From a1b396c4b14f8d35b9e526b924e458806c3f17ea Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 5 Oct 2021 18:05:30 -0700 Subject: [PATCH 01/31] adding state lattice beginning point --- nav2_smac_planner/CMakeLists.txt | 24 +- nav2_smac_planner/README.md | 24 +- .../include/nav2_smac_planner/a_star.hpp | 1 + .../include/nav2_smac_planner/node_basic.hpp | 5 +- .../nav2_smac_planner/node_lattice.hpp | 379 ++++++++++++++++++ .../smac_planner_lattice.hpp | 109 +++++ nav2_smac_planner/smac_plugin_lattice.xml | 5 + nav2_smac_planner/src/a_star.cpp | 1 + nav2_smac_planner/src/node_lattice.cpp | 264 ++++++++++++ .../src/smac_planner_lattice.cpp | 318 +++++++++++++++ nav2_smac_planner/test/test_nodebasic.cpp | 6 + 11 files changed, 1123 insertions(+), 13 deletions(-) create mode 100644 nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp create mode 100644 nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp create mode 100644 nav2_smac_planner/smac_plugin_lattice.xml create mode 100644 nav2_smac_planner/src/node_lattice.cpp create mode 100644 nav2_smac_planner/src/smac_planner_lattice.cpp diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index 1d7b71bf6a..acd2ccc69b 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -70,6 +70,7 @@ add_library(${library_name} SHARED src/smac_planner_hybrid.cpp src/a_star.cpp src/node_hybrid.cpp + src/node_lattice.cpp src/costmap_downsampler.cpp src/node_2d.cpp ) @@ -86,6 +87,7 @@ add_library(${library_name}_2d SHARED src/smac_planner_2d.cpp src/a_star.cpp src/node_hybrid.cpp + src/node_lattice.cpp src/costmap_downsampler.cpp src/node_2d.cpp ) @@ -97,10 +99,28 @@ ament_target_dependencies(${library_name}_2d ${dependencies} ) +# Lattice plugin +add_library(${library_name}_lattice SHARED + src/smac_planner_lattice.cpp + src/a_star.cpp + src/node_hybrid.cpp + src/node_lattice.cpp + src/costmap_downsampler.cpp + src/node_2d.cpp +) + +target_link_libraries(${library_name}_lattice ${OMPL_LIBRARIES}) +target_include_directories(${library_name}_lattice PUBLIC ${Eigen3_INCLUDE_DIRS}) + +ament_target_dependencies(${library_name}_lattice + ${dependencies} +) + pluginlib_export_plugin_description_file(nav2_core smac_plugin.xml) pluginlib_export_plugin_description_file(nav2_core smac_plugin_2d.xml) +pluginlib_export_plugin_description_file(nav2_core smac_plugin_lattice.xml) -install(TARGETS ${library_name} ${library_name}_2d +install(TARGETS ${library_name} ${library_name}_2d ${library_name}_lattice ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION lib/${PROJECT_NAME} @@ -118,6 +138,6 @@ if(BUILD_TESTING) endif() ament_export_include_directories(include) -ament_export_libraries(${library_name} ${library_name}_2d) +ament_export_libraries(${library_name} ${library_name}_2d ${library_name}_lattice) ament_export_dependencies(${dependencies}) ament_package() diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index 281f6c027f..2fbc5b7420 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -2,13 +2,14 @@ The SmacPlanner is a plugin for the Nav2 Planner server. It includes currently 2 distinct plugins: - `SmacPlannerHybrid`: a highly optimized fully reconfigurable Hybrid-A* implementation supporting Dubin and Reeds-Shepp models (ackermann and car models). + - `SmacPlannerLattice`: a highly optimized fully reconfigurable State Lattice implementation supporting Differential and Omnidirectionl models. - `SmacPlanner2D`: a highly optimized fully reconfigurable grid-based A* implementation supporting Moore and Von Neumann models. It also introduces the following basic building blocks: - `CostmapDownsampler`: A library to take in a costmap object and downsample it to another resolution. -- `AStar`: A generic and highly optimized A* template library used by the planning plugins to search. Template implementations are provided for grid-A*, SE2 Hybrid-A* planning. Additional template for 3D planning also could be made available. +- `AStar`: A generic and highly optimized A* template library used by the planning plugins to search. Template implementations are provided for grid-A*, SE2 Hybrid-A*, and SE2 State Lattice planning. Additional template for 3D planning also could be made available. - `CollisionChecker`: Collision check based on a robot's radius or footprint. -- `Smoother`: A path smoother to smooth out 2D, Hybrid-A\* paths. +- `Smoother`: A path smoother to smooth out 2D, Hybrid-A\*, and State Lattice paths. We have users reporting using this on: - Delivery robots @@ -16,10 +17,12 @@ We have users reporting using this on: ## Introduction -The `nav2_smac_planner` package contains an optimized templated A* search algorithm used to create multiple A\*-based planners for multiple types of robot platforms. It was built by [Steve Macenski](https://www.linkedin.com/in/steve-macenski-41a985101/) while at [Samsung Research](https://www.sra.samsung.com/). We support **circular** differential-drive and omni-directional drive robots using the `SmacPlanner2D` planner which implements a cost-aware A\* planner. We support **cars, car-like, and ackermann vehicles** using the `SmacPlannerHybrid` plugin which implements a Hybrid-A\* planner. These plugins are also useful for curvature constrained planning, like when planning robot at high speeds to make sure they don't flip over or otherwise skid out of control. It is also applicable to non-round robots (such as large rectangular or arbitrary shaped robots of differential/omnidirectional drivetrains) that need pose-based collision checking. +The `nav2_smac_planner` package contains an optimized templated A* search algorithm used to create multiple A\*-based planners for multiple types of robot platforms. It was built by [Steve Macenski](https://www.linkedin.com/in/steve-macenski-41a985101/) while at [Samsung Research](https://www.sra.samsung.com/). We support **circular** differential-drive and omni-directional drive robots using the `SmacPlanner2D` planner which implements a cost-aware A\* planner. We support **cars, car-like, and ackermann vehicles** using the `SmacPlannerHybrid` plugin which implements a Hybrid-A\* planner. We support **non-circular, arbitrary shaped** differntial drive and omnidirectional vehicles using the `SmacPlannerLattice` plugin which implements a State Lattice planner. These plugins are also useful for curvature constrained planning, like when planning robot at high speeds to make sure they don't flip over or otherwise skid out of control. It is also applicable to non-round robots (such as large rectangular or arbitrary shaped robots of differential/omnidirectional drivetrains) that need pose-based collision checking. The `SmacPlannerHybrid` implements the Hybrid-A* planner as proposed in [Practical Search Techniques in Path Planning for Autonomous Driving](https://ai.stanford.edu/~ddolgov/papers/dolgov_gpp_stair08.pdf), including hybrid searching, gradient descent smoothing, analytic expansions and hueristic functions. +The `SmacPlannerLattice` fully-implements the State Lattice planner with smoothing. While we do not implement it precisely the same way as [Optimal, Smooth, Nonholonomic MobileRobot Motion Planning in State Lattices](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2007_1/pivtoraiko_mihail_2007_1.pdf) (with control sets found using [Generating Near Minimal Spanning Control Sets for Constrained Motion Planning in Discrete State Spaces](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2005_1/pivtoraiko_mihail_2005_1.pdf)), it is sufficiently similar it may be used as a good reference. Additional optimizations for on-approach analytic expansions and simplier heuristic functions were used, largely matching those of Hybrid-A\*. + In summary... The `SmacPlannerHybrid` is designed to work with: @@ -27,6 +30,9 @@ The `SmacPlannerHybrid` is designed to work with: - High speed or curvature constrained robots (as to not flip over, skid, or dump load at high speeds) - Arbitrary shaped, non-circular differential or omnidirectional robots requiring SE2 collision checking with constrained curvatures +The `SmacPlannerLattice` is designed to work with: +- Arbitrary shaped, non-circular differential or omnidirectional robots requiring SE2 collision checking using the full capabilities of the drivetrain + The `SmacPlanner2D` is designed to work with: - Circular, differential or omnidirectional robots - Relatively small robots with respect to environment size (e.g. RC car in a hallway or large robot in a convention center) that can be approximated by circular footprint. @@ -49,7 +55,7 @@ We further improve in the following ways: - Templated Nodes and A\* implementation to support additional robot extensions. - Selective re-evaluation of the obstacle heuristic per goal/map or each iteration, which can speed up subsiquent replanning 20x or more. -All of these features (multi-resolution, models, smoother, etc) are also available in the `SmacPlanner2D` plugin. +All of these features (multi-resolution, models, smoother, etc) are also available in the `SmacPlanner2D` and `SmacPlannerLattice` plugins. The 2D A\* implementation also does not have any of the weird artifacts introduced by the gradient wavefront-based 2D A\* implementation in the NavFn Planner. While this 2D A\* planner is slightly slower, I believe it's well worth the increased quality in paths. Though the `SmacPlanner2D` is grid-based, any reasonable local trajectory planner - including those supported by Nav2 - will not have any issue with grid-based plans. @@ -70,9 +76,9 @@ For example, the following path (roughly 85 meters) path took 33ms to compute. The basic design centralizes a templated A\* implementation that handles the search of a graph of nodes. The implementation is templated by the nodes, `NodeT`, which contain the methods needed to compute the hueristics, travel costs, and search neighborhoods. The outcome of this design is then a standard A\* implementation that can be used to traverse any type of graph as long as a node template can be created for it. -We provide by default a 2D node template (`Node2D`) which does 2D grid-search with either 4 or 8-connected neighborhoods, but the smoother smooths it out on turns. We also provide a Hybrid A\* node template (`NodeHybrid`) which does SE2 (X, Y, theta) search and collision checking on Dubin or Reeds-Shepp motion models. Additional templates could be easily made and included for 3D grid search and non-grid base searching like routing. +We provide by default a 2D node template (`Node2D`) which does 2D grid-search with either 4 or 8-connected neighborhoods, but the smoother smooths it out on turns. We also provide a Hybrid A\* node template (`NodeHybrid`) which does SE2 (X, Y, theta) search and collision checking on Dubin or Reeds-Shepp motion models. We also provide the Lattice (`NodeLattice`) node for state lattice planning making use of the wider range of velocity options available to differential and omnidirectional robots. Additional templates could be easily made and included for 3D grid search and non-grid base searching like routing. -In the ROS2 facing plugin, we take in the global goals and pre-process the data to feed into the templated A\* used. This includes processing any requests to downsample the costmap to another resolution to speed up search and smoothing the resulting A\* path. For the `SmacPlannerHybrid` plugin, the path is promised to be kinematically feasible due to the kinematically valid models used in branching search. The 2D A\* is also promised to be feasible for differential and omni-directional robots. +In the ROS2 facing plugin, we take in the global goals and pre-process the data to feed into the templated A\* used. This includes processing any requests to downsample the costmap to another resolution to speed up search and smoothing the resulting A\* path. For the `SmacPlannerHybrid` and `SmacPlannerLattice` plugins, the path is promised to be kinematically feasible due to the kinematically valid models used in branching search. The 2D A\* is also promised to be feasible for differential and omni-directional robots. We isolated the A\*, costmap downsampler, smoother, and Node template objects from ROS2 to allow them to be easily testable independently of ROS or the planner. The only place ROS is used is in the planner plugins themselves. @@ -97,7 +103,7 @@ planner_server: max_planning_time: 3.5 # max time in s for planner to plan, smooth, and upsample. Will scale maximum smoothing and upsampling times based on remaining time after planning. motion_model_for_search: "DUBIN" # 2D Moore, Von Neumann; Hybrid Dubin, Redds-Shepp; State Lattice set internally cost_travel_multiplier: 2.0 # For 2D: Cost multiplier to apply to search to steer away from high cost areas. Larger values will place in the center of aisles more exactly (if non-`FREE` cost potential field exists) but take slightly longer to compute. To optimize for speed, a value of 1.0 is reasonable. A reasonable tradeoff value is 2.0. A value of 0.0 effective disables steering away from obstacles and acts like a naive binary search A*. - angle_quantization_bins: 64 # For Hybrid/Lattice nodes: Number of angle bins for search, must be 1 for 2D node (no angle search) + angle_quantization_bins: 64 # For Hybrid nodes: Number of angle bins for search, must be 1 for 2D node (no angle search) analytic_expansion_ratio: 3.5 # For Hybrid/Lattice nodes: The ratio to attempt analytic expansions during search for final approach. minimum_turning_radius: 0.40 # For Hybrid/Lattice nodes: minimum turning radius in m of path / vehicle reverse_penalty: 2.1 # For Reeds-Shepp model: penalty to apply if motion is reversing, must be => 1 @@ -138,7 +144,7 @@ This habit actually results in paths produced by NavFn, Global Planner, and now So it is my recommendation in using this package, as well as all other cost-aware search planners available in ROS, to increase your inflation layer cost scale in order to adequately produce a smooth potential across the entire map. For very large open spaces, its fine to have 0-cost areas in the middle, but for halls, aisles, and similar; **please create a smooth potential to provide the best performance**. -### Hybrid-A* Turning Radius' +### Hybrid-A* and State Lattice Turning Radius' A very reasonable and logical assumption would be to set the `minimum_turning_radius` to the kinematic limits of your vehicle. For an ackermann car, that's a physical quantity; while for differential or omni robots, its a bit of a dance around what kind of turns you'd like your robot to be able to make. Obviously setting this to something insanely small (like 20 cm) means you have alot of options, but also probably means the raw output plans won't be very straight and smooth when you have 2+ meter wide aisles to work in. @@ -148,7 +154,7 @@ By default, `0.4m` is the setting which I think is "reasonable" for the smaller ### Costmap Resolutions -We provide for the Hybrid-A\* and 2D A\* implementations a costmap downsampler option. This can be **incredible** beneficial when planning very long paths in larger spaces. The motion models for SE2 planning and neighborhood search in 2D planning is proportional to the costmap resolution. By downsampling it, you can N^2 reduce the number of expansions required to achieve a particular goal. However, the lower the resolution, the larger small obstacles appear and you won't be able to get super close to obstacles. This is a trade-off to make and test. Some numbers I've seen are 2-4x drops in planning CPU time for a 2-3x downsample rate. For long and complex paths, I was able to get it << 100ms at only a 2x downsample rate from a plan that otherwise took upward of 400ms. +We provide for the Hybrid-A\*, State Lattice, and 2D A\* implementations a costmap downsampler option. This can be **incredible** beneficial when planning very long paths in larger spaces. The motion models for SE2 planning and neighborhood search in 2D planning is proportional to the costmap resolution. By downsampling it, you can N^2 reduce the number of expansions required to achieve a particular goal. However, the lower the resolution, the larger small obstacles appear and you won't be able to get super close to obstacles. This is a trade-off to make and test. Some numbers I've seen are 2-4x drops in planning CPU time for a 2-3x downsample rate. For long and complex paths, I was able to get it << 100ms at only a 2x downsample rate from a plan that otherwise took upward of 400ms. I recommend users using a 5cm resolution costmap and playing with the different values of downsampling rate until they achieve what they think is optimal performance (lowest number of expansions vs. necessity to achieve fine goal poses). Then, I would recommend to change the global costmap resolution to this new value. That way you don't own the compute of downsampling and maintaining a higher-resolution costmap that isn't used. diff --git a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp index 39d5788b97..84481650a6 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp @@ -28,6 +28,7 @@ #include "nav2_smac_planner/node_2d.hpp" #include "nav2_smac_planner/node_hybrid.hpp" +#include "nav2_smac_planner/node_lattice.hpp" #include "nav2_smac_planner/node_basic.hpp" #include "nav2_smac_planner/types.hpp" #include "nav2_smac_planner/constants.hpp" diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp index 0b69771ef4..bc3b587668 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp @@ -29,6 +29,7 @@ #include "nav2_smac_planner/constants.hpp" #include "nav2_smac_planner/node_hybrid.hpp" +#include "nav2_smac_planner/node_lattice.hpp" #include "nav2_smac_planner/node_2d.hpp" #include "nav2_smac_planner/types.hpp" #include "nav2_smac_planner/collision_checker.hpp" @@ -55,14 +56,14 @@ class NodeBasic { } - typename NodeT::Coordinates pose; // Used by NodeHybrid + typename NodeT::Coordinates pose; // Used by NodeHybrid and NodeLattice NodeT * graph_node_ptr; unsigned int index; }; template class NodeBasic; template class NodeBasic; - +template class NodeBasic; } // namespace nav2_smac_planner #endif // NAV2_SMAC_PLANNER__NODE_BASIC_HPP_ diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp new file mode 100644 index 0000000000..e45658c21b --- /dev/null +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -0,0 +1,379 @@ +// Copyright (c) 2020, Samsung Research America +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#ifndef NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_ +#define NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ompl/base/StateSpace.h" + +#include "nav2_smac_planner/constants.hpp" +#include "nav2_smac_planner/types.hpp" +#include "nav2_smac_planner/collision_checker.hpp" +#include "nav2_smac_planner/node_hybrid.hpp" + +namespace nav2_smac_planner +{ + +// forward declare +class NodeLattice; +class NodeHybrid; + +typedef std::pair LatticeMetadata; + +/** + * @struct nav2_smac_planner::LatticeMotionTable + * @brief A table of motion primitives and related functions + */ +struct LatticeMotionTable +{ + /** + * @brief A constructor for nav2_smac_planner::LatticeMotionTable + */ + LatticeMotionTable() {} + + /** + * @brief Initializing state lattice planner's motion model + * @param size_x_in Size of costmap in X + * @param size_y_in Size of costmap in Y + * @param angle_quantization_in Size of costmap in bin sizes + * @param search_info Parameters for searching + */ + void initMotionModel( + unsigned int & size_x_in, + SearchInfo & search_info); + + /** + * @brief Get projections of motion models + * @param node Ptr to NodeLattice + * @return A set of motion poses + */ + MotionPoses getProjections(const NodeLattice * node); + + /** + * @brief Get file metadata needed + * @param lattice_filepath Filepath to the lattice file + * @return A set of metadata containing the number of angular bins + * and the global coordinates minimum turning radius of the primitives + * for use in analytic expansion and heuristic calculation. + */ + static LatticeMetadata getLatticeMetadata(const std::string & lattice_filepath); + + MotionPoses projections; + unsigned int size_x; + unsigned int num_angle_quantization; + float num_angle_quantization_float; + float min_turning_radius; + float bin_size; + float change_penalty; + float non_straight_penalty; + float cost_penalty; + float reverse_penalty; + ompl::base::StateSpacePtr state_space; + std::vector trig_values; + std::string current_lattice_filepath; +}; + +/** + * @class nav2_smac_planner::NodeLattice + * @brief NodeLattice implementation for graph, Hybrid-A* + */ +class NodeLattice +{ +public: + typedef NodeLattice * NodePtr; + typedef std::unique_ptr> Graph; + typedef std::vector NodeVector; + typedef NodeHybrid::Coordinates Coordinates; + typedef NodeHybrid::CoordinateVector CoordinateVector; + + /** + * @brief A constructor for nav2_smac_planner::NodeLattice + * @param index The index of this node for self-reference + */ + explicit NodeLattice(const unsigned int index); + + /** + * @brief A destructor for nav2_smac_planner::NodeLattice + */ + ~NodeLattice(); + + /** + * @brief operator== for comparisons + * @param NodeLattice right hand side node reference + * @return If cell indicies are equal + */ + bool operator==(const NodeLattice & rhs) + { + return this->_index == rhs._index; + } + + /** + * @brief setting continuous coordinate search poses (in partial-cells) + * @param Pose pose + */ + inline void setPose(const Coordinates & pose_in) + { + pose = pose_in; + } + + /** + * @brief Reset method for new search + */ + void reset(); + + /** + * @brief Sets the motion primitive index used to achieve node in search + * @param reference to motion primitive idx + */ + inline void setMotionPrimitiveIndex(const unsigned int & idx) + { + _motion_primitive_index = idx; + } + + /** + * @brief Gets the motion primitive index used to achieve node in search + * @return reference to motion primitive idx + */ + inline unsigned int & getMotionPrimitiveIndex() + { + return _motion_primitive_index; + } + + /** + * @brief Gets the accumulated cost at this node + * @return accumulated cost + */ + inline float & getAccumulatedCost() + { + return _accumulated_cost; + } + + /** + * @brief Sets the accumulated cost at this node + * @param reference to accumulated cost + */ + inline void setAccumulatedCost(const float & cost_in) + { + _accumulated_cost = cost_in; + } + + /** + * @brief Gets the costmap cost at this node + * @return costmap cost + */ + inline float & getCost() + { + return _cell_cost; + } + + /** + * @brief Gets if cell has been visited in search + * @param If cell was visited + */ + inline bool & wasVisited() + { + return _was_visited; + } + + /** + * @brief Sets if cell has been visited in search + */ + inline void visited() + { + _was_visited = true; + } + + /** + * @brief Gets cell index + * @return Reference to cell index + */ + inline unsigned int & getIndex() + { + return _index; + } + + /** + * @brief Check if this node is valid + * @param traverse_unknown If we can explore unknown nodes on the graph + * @return whether this node is valid and collision free + */ + bool isNodeValid(const bool & traverse_unknown, GridCollisionChecker * collision_checker); + + /** + * @brief Get traversal cost of parent node to child node + * @param child Node pointer to child + * @return traversal cost + */ + float getTraversalCost(const NodePtr & child); + + /** + * @brief Get index at coordinates + * @param x X coordinate of point + * @param y Y coordinate of point + * @param angle Theta coordinate of point + * @return Index + */ + static inline unsigned int getIndex( + const unsigned int & x, const unsigned int & y, const unsigned int & angle) + { + // Hybrid-A* and State Lattice share a coordinate system + return NodeHybrid::getIndex( + x, y, angle, motion_table.size_x, + motion_table.num_angle_quantization); + } + + /** + * @brief Get coordinates at index + * @param index Index of point + * @param width Width of costmap + * @param angle_quantization Theta size of costmap + * @return Coordinates + */ + static inline Coordinates getCoords( + const unsigned int & index, + const unsigned int & width, const unsigned int & angle_quantization) + { + // Hybrid-A* and State Lattice share a coordinate system + return NodeHybrid::Coordinates( + (index / angle_quantization) % width, // x + index / (angle_quantization * width), // y + index % angle_quantization); // theta + } + + /** + * @brief Get cost of heuristic of node + * @param node Node index current + * @param node Node index of new + * @param costmap Costmap ptr to use + * @return Heuristic cost between the nodes + */ + static float getHeuristicCost( + const Coordinates & node_coords, + const Coordinates & goal_coordinates, + const nav2_costmap_2d::Costmap2D * costmap); + + /** + * @brief Initialize motion models + * @param motion_model Motion model enum to use + * @param size_x Size of X of graph + * @param size_y Size of y of graph + * @param angle_quantization Size of theta bins of graph + * @param search_info Search info to use + */ + static void initMotionModel( + const MotionModel & motion_model, + unsigned int & size_x, + unsigned int & size_y, + unsigned int & angle_quantization, + SearchInfo & search_info); + + /** + * @brief Compute the SE2 distance heuristic + * @param lookup_table_dim Size, in costmap pixels, of the + * each lookup table dimension to populate + * @param motion_model Motion model to use for state space + * @param dim_3_size Number of quantization bins for caching + * @param search_info Info containing minimum radius to use + */ + static void precomputeDistanceHeuristic( + const float & lookup_table_dim, + const MotionModel & motion_model, + const unsigned int & dim_3_size, + const SearchInfo & search_info) + { + // State Lattice and Hybrid-A* share this heuristics + NodeHybrid::precomputeDistanceHeuristic( + lookup_table_dim, motion_model, dim_3_size, + search_info); + } + + /** + * @brief Compute the wavefront heuristic + * @param costmap Costmap to use + * @param goal_coords Coordinates to start heuristic expansion at + */ + static void resetObstacleHeuristic( + nav2_costmap_2d::Costmap2D * costmap, + const unsigned int & goal_x, const unsigned int & goal_y) + { + // State Lattice and Hybrid-A* share this heuristics + NodeHybrid::resetObstacleHeuristic(costmap, goal_x, goal_y); + } + + /** + * @brief Compute the Obstacle heuristic + * @param node_coords Coordinates to get heuristic at + * @param goal_coords Coordinates to compute heuristic to + * @return heuristic Heuristic value + */ + static float getObstacleHeuristic( + const Coordinates & node_coords, + const Coordinates & goal_coords) + { + return NodeHybrid::getObstacleHeuristic(node_coords, goal_coords); + } + + /** + * @brief Compute the Distance heuristic + * @param node_coords Coordinates to get heuristic at + * @param goal_coords Coordinates to compute heuristic to + * @param obstacle_heuristic Value of the obstacle heuristic to compute + * additional motion heuristics if required + * @return heuristic Heuristic value + */ + static float getDistanceHeuristic( + const Coordinates & node_coords, + const Coordinates & goal_coords, + const float & obstacle_heuristic); + + /** + * @brief Retrieve all valid neighbors of a node. + * @param validity_checker Functor for state validity checking + * @param collision_checker Collision checker to use + * @param traverse_unknown If unknown costs are valid to traverse + * @param neighbors Vector of neighbors to be filled + */ + void getNeighbors( + std::function & validity_checker, + GridCollisionChecker * collision_checker, + const bool & traverse_unknown, + NodeVector & neighbors); + + NodeLattice * parent; + Coordinates pose; + static LatticeMotionTable motion_table; + +private: + float _cell_cost; + float _accumulated_cost; + unsigned int _index; + bool _was_visited; + unsigned int _motion_primitive_index; +}; + +} // namespace nav2_smac_planner + +#endif // NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_ diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp new file mode 100644 index 0000000000..ae46a36116 --- /dev/null +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp @@ -0,0 +1,109 @@ +// Copyright (c) 2021, Samsung Research America +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#ifndef NAV2_SMAC_PLANNER__SMAC_PLANNER_LATTICE_HPP_ +#define NAV2_SMAC_PLANNER__SMAC_PLANNER_LATTICE_HPP_ + +#include +#include +#include + +#include "nav2_smac_planner/a_star.hpp" +#include "nav2_smac_planner/smoother.hpp" +#include "nav2_smac_planner/utils.hpp" +#include "nav2_smac_planner/costmap_downsampler.hpp" +#include "nav_msgs/msg/occupancy_grid.hpp" +#include "nav2_core/global_planner.hpp" +#include "nav_msgs/msg/path.hpp" +#include "nav2_costmap_2d/costmap_2d_ros.hpp" +#include "nav2_costmap_2d/costmap_2d.hpp" +#include "geometry_msgs/msg/pose_stamped.hpp" +#include "nav2_util/lifecycle_node.hpp" +#include "nav2_util/node_utils.hpp" +#include "tf2/utils.h" + +namespace nav2_smac_planner +{ + +class SmacPlannerLattice : public nav2_core::GlobalPlanner +{ +public: + /** + * @brief constructor + */ + SmacPlannerLattice(); + + /** + * @brief destructor + */ + ~SmacPlannerLattice(); + + /** + * @brief Configuring plugin + * @param parent Lifecycle node pointer + * @param name Name of plugin map + * @param tf Shared ptr of TF2 buffer + * @param costmap_ros Costmap2DROS object + */ + void configure( + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + std::string name, std::shared_ptr tf, + std::shared_ptr costmap_ros) override; + + /** + * @brief Cleanup lifecycle node + */ + void cleanup() override; + + /** + * @brief Activate lifecycle node + */ + void activate() override; + + /** + * @brief Deactivate lifecycle node + */ + void deactivate() override; + + /** + * @brief Creating a plan from start and goal poses + * @param start Start pose + * @param goal Goal pose + * @return nav2_msgs::Path of the generated path + */ + nav_msgs::msg::Path createPlan( + const geometry_msgs::msg::PoseStamped & start, + const geometry_msgs::msg::PoseStamped & goal) override; + +protected: + std::unique_ptr> _a_star; + GridCollisionChecker _collision_checker; + std::unique_ptr _smoother; + rclcpp::Clock::SharedPtr _clock; + rclcpp::Logger _logger{rclcpp::get_logger("SmacPlannerLattice")}; + nav2_costmap_2d::Costmap2D * _costmap; + std::unique_ptr _costmap_downsampler; + std::string _global_frame, _name; + float _tolerance; + int _downsampling_factor; + unsigned int _angle_quantizations; + double _angle_bin_size; + bool _downsample_costmap; + rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; + double _max_planning_time; +}; + +} // namespace nav2_smac_planner + +#endif // NAV2_SMAC_PLANNER__SMAC_PLANNER_LATTICE_HPP_ diff --git a/nav2_smac_planner/smac_plugin_lattice.xml b/nav2_smac_planner/smac_plugin_lattice.xml new file mode 100644 index 0000000000..34149230f4 --- /dev/null +++ b/nav2_smac_planner/smac_plugin_lattice.xml @@ -0,0 +1,5 @@ + + + State Lattice SMAC planner + + diff --git a/nav2_smac_planner/src/a_star.cpp b/nav2_smac_planner/src/a_star.cpp index 11d1976dae..c2452a6577 100644 --- a/nav2_smac_planner/src/a_star.cpp +++ b/nav2_smac_planner/src/a_star.cpp @@ -667,5 +667,6 @@ typename AStarAlgorithm::NodePtr AStarAlgorithm::setAnalyticPath // Instantiate algorithm for the supported template types template class AStarAlgorithm; template class AStarAlgorithm; +template class AStarAlgorithm; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp new file mode 100644 index 0000000000..d8909388dc --- /dev/null +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -0,0 +1,264 @@ +// Copyright (c) 2020, Samsung Research America +// Copyright (c) 2020, Applied Electric Vehicles Pty Ltd +// +// 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. Reserved. + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "ompl/base/ScopedState.h" +#include "ompl/base/spaces/DubinsStateSpace.h" +#include "ompl/base/spaces/ReedsSheppStateSpace.h" + +#include "nav2_smac_planner/node_lattice.hpp" + +using namespace std::chrono; // NOLINT + +namespace nav2_smac_planner +{ + +// defining static member for all instance to share +LatticeMotionTable NodeLattice::motion_table; + +// Each of these tables are the projected motion models through +// time and space applied to the search on the current node in +// continuous map-coordinates (e.g. not meters but partial map cells) +// Currently, these are set to project *at minimum* into a neighboring +// cell. Though this could be later modified to project a certain +// amount of time or particular distance forward. +void LatticeMotionTable::initMotionModel( + unsigned int & size_x_in, + SearchInfo & search_info) +{ + size_x = size_x_in; + + if (current_lattice_filepath == search_info.lattice_filepath) { + return; + } + + size_x = size_x_in; + change_penalty = search_info.change_penalty; + non_straight_penalty = search_info.non_straight_penalty; + cost_penalty = search_info.cost_penalty; + reverse_penalty = search_info.reverse_penalty; + current_lattice_filepath = search_info.lattice_filepath; + + // TODO(Matt) read in file, precompute based on orientation bins for lookup at runtime + // file is `search_info.lattice_filepath`, to be read in from plugin and provided here. + + // TODO(Matt) create a state_space with the max turning rad primitive within the file + // (or another -- mid?) + // to use for analytic expansions and heuristic generation. Potentially make both an + // extreme and a passive one? + + // TODO(Matt) populate num_angle_quantization, size_x, min_turning_radius, trig_values, + // all of the member variables of LatticeMotionTable +} + +MotionPoses LatticeMotionTable::getProjections(const NodeLattice * node) +{ + return MotionPoses(); // TODO(Matt) lookup at run time the primitives to use at node +} + +LatticeMetadata LatticeMotionTable::getLatticeMetadata(const std::string & lattice_filepath) +{ + // TODO(Matt) from this file extract and return the number of angle bins and + // turning radius in global coordinates, respectively. + // world coordinates meaning meters, not cells + return {0 /*num bins*/, 0 /*turning rad*/}; +} + +NodeLattice::NodeLattice(const unsigned int index) +: parent(nullptr), + pose(0.0f, 0.0f, 0.0f), + _cell_cost(std::numeric_limits::quiet_NaN()), + _accumulated_cost(std::numeric_limits::max()), + _index(index), + _was_visited(false) +{ +} + +NodeLattice::~NodeLattice() +{ + parent = nullptr; +} + +void NodeLattice::reset() +{ + parent = nullptr; + _cell_cost = std::numeric_limits::quiet_NaN(); + _accumulated_cost = std::numeric_limits::max(); + _was_visited = false; + pose.x = 0.0f; + pose.y = 0.0f; + pose.theta = 0.0f; +} + +bool NodeLattice::isNodeValid( + const bool & traverse_unknown, + GridCollisionChecker * collision_checker) +{ + // TODO(steve) if primitive longer than 1.5 cells, then we need to split into 1 cell + // increments and collision check across them + if (collision_checker->inCollision( + this->pose.x, this->pose.y, this->pose.theta * motion_table.bin_size, traverse_unknown)) + { + return false; + } + + _cell_cost = collision_checker->getCost(); + return true; +} + +float NodeLattice::getTraversalCost(const NodePtr & child) +{ + return 0.0; // TODO(josh): cost of different angles, changing, nonstraight, backwards, distance +} + +float NodeLattice::getHeuristicCost( + const Coordinates & node_coords, + const Coordinates & goal_coords, + const nav2_costmap_2d::Costmap2D * costmap) +{ + // get obstacle heuristic value + const float obstacle_heuristic = getObstacleHeuristic(node_coords, goal_coords); + const float distance_heuristic = + getDistanceHeuristic(node_coords, goal_coords, obstacle_heuristic); + return std::max(obstacle_heuristic, distance_heuristic); +} + +float NodeLattice::getDistanceHeuristic( + const Coordinates & node_coords, + const Coordinates & goal_coords, + const float & obstacle_heuristic) +{ + // rotate and translate node_coords such that goal_coords relative is (0,0,0) + // Due to the rounding involved in exact cell increments for caching, + // this is not an exact replica of a live heuristic, but has bounded error. + // (Usually less than 1 cell length) + + // This angle is negative since we are de-rotating the current node + // by the goal angle; cos(-th) = cos(th) & sin(-th) = -sin(th) + const TrigValues & trig_vals = motion_table.trig_values[goal_coords.theta]; + const float cos_th = trig_vals.first; + const float sin_th = -trig_vals.second; + const float dx = node_coords.x - goal_coords.x; + const float dy = node_coords.y - goal_coords.y; + + double dtheta_bin = node_coords.theta - goal_coords.theta; + if (dtheta_bin > motion_table.num_angle_quantization) { + dtheta_bin -= motion_table.num_angle_quantization; + } else if (dtheta_bin < 0) { + dtheta_bin += motion_table.num_angle_quantization; + } + + Coordinates node_coords_relative( + round(dx * cos_th - dy * sin_th), + round(dx * sin_th + dy * cos_th), + round(dtheta_bin)); + + // Check if the relative node coordinate is within the localized window around the goal + // to apply the distance heuristic. Since the lookup table is contains only the positive + // X axis, we mirror the Y and theta values across the X axis to find the heuristic values. + float motion_heuristic = 0.0; + const int floored_size = floor(NodeHybrid::size_lookup / 2.0); + const int ceiling_size = ceil(NodeHybrid::size_lookup / 2.0); + const float mirrored_relative_y = abs(node_coords_relative.y); + if (abs(node_coords_relative.x) < floored_size && mirrored_relative_y < floored_size) { + // Need to mirror angle if Y coordinate was mirrored + int theta_pos; + if (node_coords_relative.y < 0.0) { + theta_pos = motion_table.num_angle_quantization - node_coords_relative.theta; + } else { + theta_pos = node_coords_relative.theta; + } + const int x_pos = node_coords_relative.x + floored_size; + const int y_pos = static_cast(mirrored_relative_y); + const int index = + x_pos * ceiling_size * motion_table.num_angle_quantization + + y_pos * motion_table.num_angle_quantization + + theta_pos; + motion_heuristic = NodeHybrid::dist_heuristic_lookup_table[index]; + } else if (obstacle_heuristic == 0.0) { + static ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space); + to[0] = goal_coords.x; + to[1] = goal_coords.y; + to[2] = goal_coords.theta * motion_table.num_angle_quantization; + from[0] = node_coords.x; + from[1] = node_coords.y; + from[2] = node_coords.theta * motion_table.num_angle_quantization; + motion_heuristic = motion_table.state_space->distance(from(), to()); + } + + return motion_heuristic; +} + +void NodeLattice::initMotionModel( + const MotionModel & motion_model, + unsigned int & size_x, + unsigned int & /*size_y*/, + unsigned int & /*num_angle_quantization*/, + SearchInfo & search_info) +{ + if (motion_model != MotionModel::STATE_LATTICE) { + throw std::runtime_error( + "Invalid motion model for Lattice node. Please select" + " STATE_LATTICE and provide a valid lattice file."); + } + + motion_table.initMotionModel(size_x, search_info); +} + +void NodeLattice::getNeighbors( + std::function & NeighborGetter, + GridCollisionChecker * collision_checker, + const bool & traverse_unknown, + NodeVector & neighbors) +{ + unsigned int index = 0; + NodePtr neighbor = nullptr; + Coordinates initial_node_coords; + const MotionPoses motion_projections = motion_table.getProjections(this); + + for (unsigned int i = 0; i != motion_projections.size(); i++) { + index = NodeLattice::getIndex( + static_cast(motion_projections[i]._x), + static_cast(motion_projections[i]._y), + static_cast(motion_projections[i]._theta)); + + if (NeighborGetter(index, neighbor) && !neighbor->wasVisited()) { + // For State Lattice, the poses are exact bin increments and the pose + // can be derived from the index alone. + // However, we store them as if they were continuous so that it may be + // leveraged by the analytic expansion tool to accelerate goal approaches, + // collision checking, and backtracing (even if not strictly necessary). + neighbor->setPose( + Coordinates( + motion_projections[i]._x, + motion_projections[i]._y, + motion_projections[i]._theta)); + if (neighbor->isNodeValid(traverse_unknown, collision_checker)) { + neighbor->setMotionPrimitiveIndex(i); + neighbors.push_back(neighbor); + } + } + } +} + +} // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp new file mode 100644 index 0000000000..eb12db3fc5 --- /dev/null +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -0,0 +1,318 @@ +// Copyright (c) 2021, Samsung Research America +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#include +#include +#include +#include +#include + +#include "Eigen/Core" +#include "nav2_smac_planner/smac_planner_lattice.hpp" + +// #define BENCHMARK_TESTING + +namespace nav2_smac_planner +{ + +using namespace std::chrono; // NOLINT + +SmacPlannerLattice::SmacPlannerLattice() +: _a_star(nullptr), + _collision_checker(nullptr, 1), + _smoother(nullptr), + _costmap(nullptr), + _costmap_downsampler(nullptr) +{ +} + +SmacPlannerLattice::~SmacPlannerLattice() +{ + RCLCPP_INFO( + _logger, "Destroying plugin %s of type SmacPlannerLattice", + _name.c_str()); +} + +void SmacPlannerLattice::configure( + const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + std::string name, std::shared_ptr/*tf*/, + std::shared_ptr costmap_ros) +{ + auto node = parent.lock(); + _logger = node->get_logger(); + _clock = node->get_clock(); + _costmap = costmap_ros->getCostmap(); + _name = name; + _global_frame = costmap_ros->getGlobalFrameID(); + + bool allow_unknown; + int max_iterations; + int angle_quantizations; + int lookup_table_size; + SearchInfo search_info; + std::string motion_model_for_search; + + // General planner params + nav2_util::declare_parameter_if_not_declared( + node, name + ".downsample_costmap", rclcpp::ParameterValue(false)); + node->get_parameter(name + ".downsample_costmap", _downsample_costmap); + nav2_util::declare_parameter_if_not_declared( + node, name + ".downsampling_factor", rclcpp::ParameterValue(1)); + node->get_parameter(name + ".downsampling_factor", _downsampling_factor); + + nav2_util::declare_parameter_if_not_declared( + node, name + ".allow_unknown", rclcpp::ParameterValue(true)); + node->get_parameter(name + ".allow_unknown", allow_unknown); + nav2_util::declare_parameter_if_not_declared( + node, name + ".max_iterations", rclcpp::ParameterValue(1000000)); + node->get_parameter(name + ".max_iterations", max_iterations); + + nav2_util::declare_parameter_if_not_declared( + node, name + ".lattice_filepath", rclcpp::ParameterValue(std::string(""))); + node->get_parameter(name + ".lattice_filepath", search_info.lattice_filepath); + nav2_util::declare_parameter_if_not_declared( + node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(true)); + node->get_parameter(name + ".cache_obstacle_heuristic", search_info.cache_obstacle_heuristic); + nav2_util::declare_parameter_if_not_declared( + node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0)); + node->get_parameter(name + ".reverse_penalty", search_info.reverse_penalty); + nav2_util::declare_parameter_if_not_declared( + node, name + ".change_penalty", rclcpp::ParameterValue(0.15)); + node->get_parameter(name + ".change_penalty", search_info.change_penalty); + nav2_util::declare_parameter_if_not_declared( + node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.50)); + node->get_parameter(name + ".non_straight_penalty", search_info.non_straight_penalty); + nav2_util::declare_parameter_if_not_declared( + node, name + ".cost_penalty", rclcpp::ParameterValue(1.7)); + node->get_parameter(name + ".cost_penalty", search_info.cost_penalty); + nav2_util::declare_parameter_if_not_declared( + node, name + ".analytic_expansion_ratio", rclcpp::ParameterValue(3.5)); + node->get_parameter(name + ".analytic_expansion_ratio", search_info.analytic_expansion_ratio); + + nav2_util::declare_parameter_if_not_declared( + node, name + ".max_planning_time", rclcpp::ParameterValue(5.0)); + node->get_parameter(name + ".max_planning_time", _max_planning_time); + nav2_util::declare_parameter_if_not_declared( + node, name + ".lookup_table_size", rclcpp::ParameterValue(20.0)); + node->get_parameter(name + ".lookup_table_size", lookup_table_size); + + LatticeMetadata metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); + _angle_quantizations = metadata.first; + _angle_bin_size = 2.0 * M_PI / static_cast(_angle_quantizations); + float min_turning_radius = metadata.second; + + MotionModel motion_model = MotionModel::STATE_LATTICE; + + if (max_iterations <= 0) { + RCLCPP_INFO( + _logger, "maximum iteration selected as <= 0, " + "disabling maximum iterations."); + max_iterations = std::numeric_limits::max(); + } + + float lookup_table_dim = + static_cast(lookup_table_size) / + static_cast(_costmap->getResolution() * _downsampling_factor); + + // Initialize collision checker + _collision_checker = GridCollisionChecker(_costmap, _angle_quantizations); + _collision_checker.setFootprint( + costmap_ros->getRobotFootprint(), + costmap_ros->getUseRadius(), + findCircumscribedCost(costmap_ros)); + + // Initialize A* template + _a_star = std::make_unique>(motion_model, search_info); + _a_star->initialize( + allow_unknown, + max_iterations, + std::numeric_limits::max(), + lookup_table_dim, + _angle_quantizations); + + // Initialize path smoother + SmootherParams params; + params.get(node, name); + _smoother = std::make_unique(params); + _smoother->initialize(min_turning_radius); + + // Initialize costmap downsampler + if (_downsample_costmap && _downsampling_factor > 1) { + std::string topic_name = "downsampled_costmap"; + _costmap_downsampler = std::make_unique(); + _costmap_downsampler->on_configure( + node, _global_frame, topic_name, _costmap, _downsampling_factor); + } + + _raw_plan_publisher = node->create_publisher("unsmoothed_plan", 1); + + RCLCPP_INFO( + _logger, "Configured plugin %s of type SmacPlannerLattice with " + "maximum iterations %i, " + "and %s. Using motion model: %s. State lattice file: %s.", + _name.c_str(), max_iterations, + allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal", + toString(motion_model).c_str(), search_info.lattice_filepath.c_str()); +} + +void SmacPlannerLattice::activate() +{ + RCLCPP_INFO( + _logger, "Activating plugin %s of type SmacPlannerLattice", + _name.c_str()); + _raw_plan_publisher->on_activate(); + if (_costmap_downsampler) { + _costmap_downsampler->on_activate(); + } +} + +void SmacPlannerLattice::deactivate() +{ + RCLCPP_INFO( + _logger, "Deactivating plugin %s of type SmacPlannerLattice", + _name.c_str()); + _raw_plan_publisher->on_deactivate(); + if (_costmap_downsampler) { + _costmap_downsampler->on_deactivate(); + } +} + +void SmacPlannerLattice::cleanup() +{ + RCLCPP_INFO( + _logger, "Cleaning up plugin %s of type SmacPlannerLattice", + _name.c_str()); + _a_star.reset(); + _smoother.reset(); + _costmap_downsampler->on_cleanup(); + _costmap_downsampler.reset(); + _raw_plan_publisher.reset(); +} + +nav_msgs::msg::Path SmacPlannerLattice::createPlan( + const geometry_msgs::msg::PoseStamped & start, + const geometry_msgs::msg::PoseStamped & goal) +{ + steady_clock::time_point a = steady_clock::now(); + + std::unique_lock lock(*(_costmap->getMutex())); + + // Downsample costmap, if required + nav2_costmap_2d::Costmap2D * costmap = _costmap; + if (_costmap_downsampler) { + costmap = _costmap_downsampler->downsample(_downsampling_factor); + _collision_checker.setCostmap(costmap); + } + + // Set collision checker and costmap information + _a_star->setCollisionChecker(&_collision_checker); + + // Set starting point, in A* bin search coordinates + unsigned int mx, my; + costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx, my); + double orientation_bin = tf2::getYaw(start.pose.orientation) / _angle_bin_size; + while (orientation_bin < 0.0) { + orientation_bin += static_cast(_angle_quantizations); + } + unsigned int orientation_bin_id = static_cast(floor(orientation_bin)); + _a_star->setStart(mx, my, orientation_bin_id); + + // Set goal point, in A* bin search coordinates + costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my); + orientation_bin = tf2::getYaw(goal.pose.orientation) / _angle_bin_size; + while (orientation_bin < 0.0) { + orientation_bin += static_cast(_angle_quantizations); + } + orientation_bin_id = static_cast(floor(orientation_bin)); + _a_star->setGoal(mx, my, orientation_bin_id); + + // Setup message + nav_msgs::msg::Path plan; + plan.header.stamp = _clock->now(); + plan.header.frame_id = _global_frame; + geometry_msgs::msg::PoseStamped pose; + pose.header = plan.header; + pose.pose.position.z = 0.0; + pose.pose.orientation.x = 0.0; + pose.pose.orientation.y = 0.0; + pose.pose.orientation.z = 0.0; + pose.pose.orientation.w = 1.0; + + // Compute plan + NodeLattice::CoordinateVector path; + int num_iterations = 0; + std::string error; + try { + if (!_a_star->createPath(path, num_iterations, 0 /*no tolerance*/)) { + if (num_iterations < _a_star->getMaxIterations()) { + error = std::string("no valid path found"); + } else { + error = std::string("exceeded maximum iterations"); + } + } + } catch (const std::runtime_error & e) { + error = "invalid use: "; + error += e.what(); + } + + if (!error.empty()) { + RCLCPP_WARN( + _logger, + "%s: failed to create plan, %s.", + _name.c_str(), error.c_str()); + return plan; + } + + // Convert to world coordinates + plan.poses.reserve(path.size()); + for (int i = path.size() - 1; i >= 0; --i) { + pose.pose = getWorldCoords(path[i].x, path[i].y, costmap); + pose.pose.orientation = getWorldOrientation(path[i].theta, _angle_bin_size); + plan.poses.push_back(pose); + } + + // Publish raw path for debug + if (_raw_plan_publisher->get_subscription_count() > 0) { + _raw_plan_publisher->publish(plan); + } + + // Find how much time we have left to do smoothing + steady_clock::time_point b = steady_clock::now(); + duration time_span = duration_cast>(b - a); + double time_remaining = _max_planning_time - static_cast(time_span.count()); + +#ifdef BENCHMARK_TESTING + std::cout << "It took " << time_span.count() * 1000 << + " milliseconds with " << num_iterations << " iterations." << std::endl; +#endif + + // Smooth plan + if (num_iterations > 1 && plan.poses.size() > 6) { + _smoother->smooth(plan, costmap, time_remaining); + } + +#ifdef BENCHMARK_TESTING + steady_clock::time_point c = steady_clock::now(); + duration time_span2 = duration_cast>(c - b); + std::cout << "It took " << time_span2.count() * 1000 << + " milliseconds to smooth path." << std::endl; +#endif + + return plan; +} + +} // namespace nav2_smac_planner + +#include "pluginlib/class_list_macros.hpp" +PLUGINLIB_EXPORT_CLASS(nav2_smac_planner::SmacPlannerLattice, nav2_core::GlobalPlanner) diff --git a/nav2_smac_planner/test/test_nodebasic.cpp b/nav2_smac_planner/test/test_nodebasic.cpp index 965246d67c..00aea82465 100644 --- a/nav2_smac_planner/test/test_nodebasic.cpp +++ b/nav2_smac_planner/test/test_nodebasic.cpp @@ -25,6 +25,7 @@ #include "nav2_smac_planner/node_basic.hpp" #include "nav2_smac_planner/node_2d.hpp" #include "nav2_smac_planner/node_hybrid.hpp" +#include "nav2_smac_planner/node_lattice.hpp" #include "nav2_smac_planner/collision_checker.hpp" class RclCppFixture @@ -46,4 +47,9 @@ TEST(NodeBasicTest, test_node_basic) EXPECT_EQ(node2.index, 100u); EXPECT_EQ(node2.graph_node_ptr, nullptr); + + nav2_smac_planner::NodeBasic node3(200); + + EXPECT_EQ(node3.index, 200u); + EXPECT_EQ(node3.graph_node_ptr, nullptr); } From 42bb3c874a95f127cf0ff85013a6cd69c282d253 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 6 Oct 2021 15:23:43 -0700 Subject: [PATCH 02/31] refactoring to remove analytic expansion into its own object --- nav2_smac_planner/CMakeLists.txt | 3 + .../include/nav2_smac_planner/a_star.hpp | 48 +--- .../nav2_smac_planner/analytic_expansion.hpp | 119 ++++++++ .../nav2_smac_planner/node_lattice.hpp | 1 + .../include/nav2_smac_planner/types.hpp | 1 + nav2_smac_planner/src/a_star.cpp | 210 +------------- nav2_smac_planner/src/analytic_expansion.cpp | 260 ++++++++++++++++++ nav2_smac_planner/src/node_lattice.cpp | 4 + .../src/smac_planner_lattice.cpp | 4 +- 9 files changed, 400 insertions(+), 250 deletions(-) create mode 100644 nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp create mode 100644 nav2_smac_planner/src/analytic_expansion.cpp diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index acd2ccc69b..b5ef8b8d29 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -69,6 +69,7 @@ set(dependencies add_library(${library_name} SHARED src/smac_planner_hybrid.cpp src/a_star.cpp + src/analytic_expansion.cpp src/node_hybrid.cpp src/node_lattice.cpp src/costmap_downsampler.cpp @@ -86,6 +87,7 @@ ament_target_dependencies(${library_name} add_library(${library_name}_2d SHARED src/smac_planner_2d.cpp src/a_star.cpp + src/analytic_expansion.cpp src/node_hybrid.cpp src/node_lattice.cpp src/costmap_downsampler.cpp @@ -103,6 +105,7 @@ ament_target_dependencies(${library_name}_2d add_library(${library_name}_lattice SHARED src/smac_planner_lattice.cpp src/a_star.cpp + src/analytic_expansion.cpp src/node_hybrid.cpp src/node_lattice.cpp src/costmap_downsampler.cpp diff --git a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp index 84481650a6..44fd4ce72d 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp @@ -26,6 +26,7 @@ #include "nav2_costmap_2d/costmap_2d.hpp" +#include "nav2_smac_planner/analytic_expansion.hpp" #include "nav2_smac_planner/node_2d.hpp" #include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/node_lattice.hpp" @@ -53,27 +54,6 @@ class AStarAlgorithm typedef typename NodeVector::iterator NeighborIterator; typedef std::function NodeGetter; - /** - * @struct nav2_smac_planner::AnalyticExpansionNodes - * @brief Analytic expansion nodes and associated metadata - */ - - struct AnalyticExpansionNode - { - AnalyticExpansionNode( - NodePtr & node_in, - Coordinates & initial_coords_in, - Coordinates & proposed_coords_in) - : node(node_in), initial_coords(initial_coords_in), proposed_coords(proposed_coords_in) - {} - - NodePtr node; - Coordinates initial_coords; - Coordinates proposed_coords; - }; - - typedef std::vector AnalyticExpansionNodes; - /** * @struct nav2_smac_planner::NodeComparator * @brief Node comparison for priority queue sorting @@ -259,31 +239,6 @@ class AStarAlgorithm */ inline void clearGraph(); - /** - * @brief Attempt an analytic path completion - * @return Node pointer reference to goal node if successful, else - * return nullptr - */ - NodePtr tryAnalyticExpansion( - const NodePtr & current_node, - const NodeGetter & getter, int & iterations, int & best_cost); - - /** - * @brief Perform an analytic path expansion to the goal - * @param node The node to start the analytic path from - * @param getter The function object that gets valid nodes from the graph - * @return A set of analytically expanded nodes to the goal from current node, if possible - */ - AnalyticExpansionNodes getAnalyticPath(const NodePtr & node, const NodeGetter & getter); - - /** - * @brief Takes final analytic expansion and appends to current expanded node - * @param node The node to start the analytic path from - * @param expanded_nodes Expanded nodes to append to end of current search path - * @return Node pointer to goal node if successful, else return nullptr - */ - NodePtr setAnalyticPath(const NodePtr & node, const AnalyticExpansionNodes & expanded_nodes); - bool _traverse_unknown; int _max_iterations; int _max_on_approach_iterations; @@ -305,6 +260,7 @@ class AStarAlgorithm GridCollisionChecker * _collision_checker; nav2_costmap_2d::Costmap2D * _costmap; + std::unique_ptr> _expander; }; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp b/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp new file mode 100644 index 0000000000..b45127de1e --- /dev/null +++ b/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp @@ -0,0 +1,119 @@ +// Copyright (c) 2021, Samsung Research America +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#ifndef NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_ +#define NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_ + +#include + +#include "nav2_smac_planner/node_2d.hpp" +#include "nav2_smac_planner/node_hybrid.hpp" +#include "nav2_smac_planner/node_lattice.hpp" +#include "nav2_smac_planner/types.hpp" +#include "nav2_smac_planner/constants.hpp" + +namespace nav2_smac_planner +{ + +template +class AnalyticExpansion +{ +public: + + typedef NodeT * NodePtr; + typedef typename NodeT::Coordinates Coordinates; + typedef std::function NodeGetter; + + /** + * @struct nav2_smac_planner::AnalyticExpansion::AnalyticExpansionNodes + * @brief Analytic expansion nodes and associated metadata + */ + struct AnalyticExpansionNode + { + AnalyticExpansionNode( + NodePtr & node_in, + Coordinates & initial_coords_in, + Coordinates & proposed_coords_in) + : node(node_in), + initial_coords(initial_coords_in), + proposed_coords(proposed_coords_in) + { + } + + NodePtr node; + Coordinates initial_coords; + Coordinates proposed_coords; + }; + + typedef std::vector AnalyticExpansionNodes; + + /** + * @brief Constructor for analytic expansion object + */ + AnalyticExpansion( + const MotionModel & motion_model, + const SearchInfo & search_info, + const bool & traverse_unknown, + const unsigned int & dim_3_size); + + /** + * @brief Sets the collision checker and costmap to use in expansion validation + * @param collision_checker Collision checker to use + */ + void setCollisionChecker(GridCollisionChecker * collision_checker); + + /** + * @brief Attempt an analytic path completion + * @param node The node to start the analytic path from + * @param goal The goal node to plan to + * @param getter Gets a node at a set of coordinates + * @param iterations Iterations to run over + * @param best_cost Best heuristic cost to propertionally expand more closer to the goal + * @return Node pointer reference to goal node if successful, else + * return nullptr + */ + NodePtr tryAnalyticExpansion( + const NodePtr & current_node, + const NodePtr & goal_node, + const NodeGetter & getter, int & iterations, int & best_cost); + + /** + * @brief Perform an analytic path expansion to the goal + * @param node The node to start the analytic path from + * @param goal The goal node to plan to + * @param getter The function object that gets valid nodes from the graph + * @return A set of analytically expanded nodes to the goal from current node, if possible + */ + AnalyticExpansionNodes getAnalyticPath(const NodePtr & node, const NodePtr & goal, const NodeGetter & getter); + + /** + * @brief Takes final analytic expansion and appends to current expanded node + * @param node The node to start the analytic path from + * @param goal The goal node to plan to + * @param expanded_nodes Expanded nodes to append to end of current search path + * @return Node pointer to goal node if successful, else return nullptr + */ + NodePtr setAnalyticPath(const NodePtr & node, const NodePtr & goal, const AnalyticExpansionNodes & expanded_nodes); + +protected: + MotionModel _motion_model; + SearchInfo _search_info; + bool _traverse_unknown; + unsigned int _dim_3_size; + GridCollisionChecker * _collision_checker; +}; + +} // namespace nav2_smac_planner + +#endif // NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_ diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index e45658c21b..fb21f5fe3a 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -90,6 +90,7 @@ struct LatticeMotionTable float non_straight_penalty; float cost_penalty; float reverse_penalty; + bool allow_reverse_expansion; ompl::base::StateSpacePtr state_space; std::vector trig_values; std::string current_lattice_filepath; diff --git a/nav2_smac_planner/include/nav2_smac_planner/types.hpp b/nav2_smac_planner/include/nav2_smac_planner/types.hpp index dffc88062b..c5b2e1d823 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/types.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/types.hpp @@ -42,6 +42,7 @@ struct SearchInfo float analytic_expansion_ratio; std::string lattice_filepath; bool cache_obstacle_heuristic; + bool allow_reverse_expansion; }; /** diff --git a/nav2_smac_planner/src/a_star.cpp b/nav2_smac_planner/src/a_star.cpp index c2452a6577..09f450e36e 100644 --- a/nav2_smac_planner/src/a_star.cpp +++ b/nav2_smac_planner/src/a_star.cpp @@ -14,11 +14,6 @@ // limitations under the License. Reserved. #include - -#include -#include -#include - #include #include #include @@ -71,6 +66,8 @@ void AStarAlgorithm::initialize( _max_on_approach_iterations = max_on_approach_iterations; NodeT::precomputeDistanceHeuristic(lookup_table_size, _motion_model, dim_3_size, _search_info); _dim3_size = dim_3_size; + _expander = std::make_unique>( + _motion_model, _search_info, _traverse_unknown, _dim3_size); } template<> @@ -89,6 +86,8 @@ void AStarAlgorithm::initialize( throw std::runtime_error("Node type Node2D cannot be given non-1 dim 3 quantization."); } _dim3_size = dim_3_size; + _expander = std::make_unique>( + _motion_model, _search_info, _traverse_unknown, _dim3_size); } template @@ -106,6 +105,7 @@ void AStarAlgorithm::setCollisionChecker(GridCollisionChecker * collision _y_size = y_size; NodeT::initMotionModel(_motion_model, _x_size, _y_size, _dim3_size, _search_info); } + _expander->setCollisionChecker(collision_checker); } template @@ -264,8 +264,8 @@ bool AStarAlgorithm::createPath( // 2.1) Use an analytic expansion (if available) to generate a path expansion_result = nullptr; - expansion_result = tryAnalyticExpansion( - current_node, neighborGetter, analytic_iterations, closest_distance); + expansion_result = _expander->tryAnalyticExpansion( + current_node, getGoal(), neighborGetter, analytic_iterations, closest_distance); if (expansion_result != nullptr) { current_node = expansion_result; } @@ -468,202 +468,6 @@ unsigned int & AStarAlgorithm::getSizeDim3() return _dim3_size; } -template -typename AStarAlgorithm::NodePtr AStarAlgorithm::tryAnalyticExpansion( - const NodePtr & current_node, const NodeGetter & getter, int & analytic_iterations, - int & closest_distance) -{ - // This must be a NodeHybrid or NodeLattice if we are using these motion models - if (_motion_model == MotionModel::DUBIN || _motion_model == MotionModel::REEDS_SHEPP || - _motion_model == MotionModel::STATE_LATTICE) - { - // See if we are closer and should be expanding more often - const Coordinates node_coords = - NodeT::getCoords(current_node->getIndex(), getSizeX(), getSizeDim3()); - closest_distance = std::min( - closest_distance, - static_cast(NodeT::getHeuristicCost(node_coords, _goal_coordinates, _costmap))); - - // We want to expand at a rate of d/expansion_ratio, - // but check to see if we are so close that we would be expanding every iteration - // If so, limit it to the expansion ratio (rounded up) - int desired_iterations = std::max( - static_cast(closest_distance / _search_info.analytic_expansion_ratio), - static_cast(std::ceil(_search_info.analytic_expansion_ratio))); - - // If we are closer now, we should update the target number of iterations to go - analytic_iterations = - std::min(analytic_iterations, desired_iterations); - - // Always run the expansion on the first run in case there is a - // trivial path to be found - if (analytic_iterations <= 0) { - // Reset the counter and try the analytic path expansion - analytic_iterations = desired_iterations; - AnalyticExpansionNodes analytic_nodes = getAnalyticPath(current_node, getter); - if (!analytic_nodes.empty()) { - // If we have a valid path, attempt to refine it - NodePtr node = current_node; - NodePtr test_node = current_node; - AnalyticExpansionNodes refined_analytic_nodes; - for (int i = 0; i < 8; i++) { - // Attempt to create better paths in 5 node increments, need to make sure - // they exist for each in order to do so (maximum of 40 points back). - if (test_node->parent && test_node->parent->parent && test_node->parent->parent->parent && - test_node->parent->parent->parent->parent && - test_node->parent->parent->parent->parent->parent) - { - test_node = test_node->parent->parent->parent->parent->parent; - refined_analytic_nodes = getAnalyticPath(test_node, getter); - if (refined_analytic_nodes.empty()) { - break; - } - analytic_nodes = refined_analytic_nodes; - node = test_node; - } else { - break; - } - } - - return setAnalyticPath(node, analytic_nodes); - } - } - - analytic_iterations--; - } - - // No valid motion model - return nullptr - return NodePtr(nullptr); -} - -template -typename AStarAlgorithm::AnalyticExpansionNodes AStarAlgorithm::getAnalyticPath( - const NodePtr & node, - const NodeGetter & node_getter) -{ - static ompl::base::ScopedState<> from(node->motion_table.state_space), to( - node->motion_table.state_space), s(node->motion_table.state_space); - from[0] = node->pose.x; - from[1] = node->pose.y; - from[2] = node->pose.theta * node->motion_table.bin_size; - to[0] = _goal_coordinates.x; - to[1] = _goal_coordinates.y; - to[2] = _goal_coordinates.theta * node->motion_table.bin_size; - - float d = node->motion_table.state_space->distance(from(), to()); - - // A move of sqrt(2) is guaranteed to be in a new cell - static const float sqrt_2 = std::sqrt(2.); - unsigned int num_intervals = std::floor(d / sqrt_2); - - AnalyticExpansionNodes possible_nodes; - // When "from" and "to" are zero or one cell away, - // num_intervals == 0 - possible_nodes.reserve(num_intervals); // We won't store this node or the goal - std::vector reals; - - // Pre-allocate - NodePtr prev(node); - unsigned int index = 0; - NodePtr next(nullptr); - float angle = 0.0; - Coordinates proposed_coordinates; - bool failure = false; - - // Check intermediary poses (non-goal, non-start) - for (float i = 1; i < num_intervals; i++) { - node->motion_table.state_space->interpolate(from(), to(), i / num_intervals, s()); - reals = s.reals(); - angle = reals[2] / node->motion_table.bin_size; - while (angle < 0.0) { - angle += node->motion_table.num_angle_quantization_float; - } - while (angle >= node->motion_table.num_angle_quantization_float) { - angle -= node->motion_table.num_angle_quantization_float; - } - // Turn the pose into a node, and check if it is valid - index = NodeT::getIndex( - static_cast(reals[0]), - static_cast(reals[1]), - static_cast(angle)); - // Get the node from the graph - if (node_getter(index, next)) { - Coordinates initial_node_coords = next->pose; - proposed_coordinates = {static_cast(reals[0]), static_cast(reals[1]), angle}; - next->setPose(proposed_coordinates); - if (next->isNodeValid(_traverse_unknown, _collision_checker) && next != prev) { - // Save the node, and its previous coordinates in case we need to abort - possible_nodes.emplace_back(next, initial_node_coords, proposed_coordinates); - prev = next; - } else { - // Abort - next->setPose(initial_node_coords); - failure = true; - break; - } - } else { - // Abort - failure = true; - break; - } - } - - // Reset to initial poses to not impact future searches - for (const auto & node_pose : possible_nodes) { - const auto & n = node_pose.node; - n->setPose(node_pose.initial_coords); - } - - if (failure) { - return AnalyticExpansionNodes(); - } - - return possible_nodes; -} - -template -typename AStarAlgorithm::NodePtr AStarAlgorithm::setAnalyticPath( - const NodePtr & node, - const AnalyticExpansionNodes & expanded_nodes) -{ - // Legitimate final path - set the parent relationships & poses - NodePtr prev = node; - for (const auto & node_pose : expanded_nodes) { - const auto & n = node_pose.node; - if (!n->wasVisited() && n->getIndex() != _goal->getIndex()) { - // Make sure this node has not been visited by the regular algorithm. - // If it has been, there is the (slight) chance that it is in the path we are expanding - // from, so we should skip it. - // Skipping to the next node will still create a kinematically feasible path. - n->parent = prev; - n->pose = node_pose.proposed_coords; - n->visited(); - prev = n; - } - } - if (_goal != prev) { - _goal->parent = prev; - _goal->visited(); - } - return _goal; -} - -template<> -typename AStarAlgorithm::AnalyticExpansionNodes AStarAlgorithm::getAnalyticPath( - const NodePtr & node, - const NodeGetter & node_getter) -{ - return AnalyticExpansionNodes(); -} - -template<> -typename AStarAlgorithm::NodePtr AStarAlgorithm::setAnalyticPath( - const NodePtr & node, - const AnalyticExpansionNodes & expanded_nodes) -{ - return NodePtr(nullptr); -} - // Instantiate algorithm for the supported template types template class AStarAlgorithm; template class AStarAlgorithm; diff --git a/nav2_smac_planner/src/analytic_expansion.cpp b/nav2_smac_planner/src/analytic_expansion.cpp new file mode 100644 index 0000000000..618b8f3d6c --- /dev/null +++ b/nav2_smac_planner/src/analytic_expansion.cpp @@ -0,0 +1,260 @@ +// Copyright (c) 2021, Samsung Research America +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#include +#include +#include + +#include "nav2_smac_planner/analytic_expansion.hpp" + +namespace nav2_smac_planner +{ + +template +AnalyticExpansion::AnalyticExpansion( + const MotionModel & motion_model, + const SearchInfo & search_info, + const bool & traverse_unknown, + const unsigned int & dim_3_size) +: _motion_model(motion_model), + _search_info(search_info), + _traverse_unknown(traverse_unknown), + _dim_3_size(dim_3_size), + _collision_checker(nullptr) +{ +} + +template +void AnalyticExpansion::setCollisionChecker( + GridCollisionChecker * collision_checker) +{ + _collision_checker = collision_checker; +} + +template +typename AnalyticExpansion::NodePtr AnalyticExpansion::tryAnalyticExpansion( + const NodePtr & current_node, const NodePtr & goal_node, + const NodeGetter & getter, int & analytic_iterations, + int & closest_distance) +{ + // This must be a NodeHybrid or NodeLattice if we are using these motion models + if (_motion_model == MotionModel::DUBIN || _motion_model == MotionModel::REEDS_SHEPP || + _motion_model == MotionModel::STATE_LATTICE) + { + // See if we are closer and should be expanding more often + auto costmap = _collision_checker->getCostmap(); + const Coordinates node_coords = + NodeT::getCoords(current_node->getIndex(), costmap->getSizeInCellsX(), _dim_3_size); + closest_distance = std::min( + closest_distance, + static_cast(NodeT::getHeuristicCost(node_coords, goal_node->pose, costmap))); + + // We want to expand at a rate of d/expansion_ratio, + // but check to see if we are so close that we would be expanding every iteration + // If so, limit it to the expansion ratio (rounded up) + int desired_iterations = std::max( + static_cast(closest_distance / _search_info.analytic_expansion_ratio), + static_cast(std::ceil(_search_info.analytic_expansion_ratio))); + + // If we are closer now, we should update the target number of iterations to go + analytic_iterations = + std::min(analytic_iterations, desired_iterations); + + // Always run the expansion on the first run in case there is a + // trivial path to be found + if (analytic_iterations <= 0) { + // Reset the counter and try the analytic path expansion + analytic_iterations = desired_iterations; + AnalyticExpansionNodes analytic_nodes = getAnalyticPath(current_node, goal_node, getter); + if (!analytic_nodes.empty()) { + // If we have a valid path, attempt to refine it + NodePtr node = current_node; + NodePtr test_node = current_node; + AnalyticExpansionNodes refined_analytic_nodes; + for (int i = 0; i < 8; i++) { + // Attempt to create better paths in 5 node increments, need to make sure + // they exist for each in order to do so (maximum of 40 points back). + if (test_node->parent && test_node->parent->parent && test_node->parent->parent->parent && + test_node->parent->parent->parent->parent && + test_node->parent->parent->parent->parent->parent) + { + test_node = test_node->parent->parent->parent->parent->parent; + refined_analytic_nodes = getAnalyticPath(test_node, goal_node, getter); + if (refined_analytic_nodes.empty()) { + break; + } + analytic_nodes = refined_analytic_nodes; + node = test_node; + } else { + break; + } + } + + return setAnalyticPath(node, goal_node, analytic_nodes); + } + } + + analytic_iterations--; + } + + // No valid motion model - return nullptr + return NodePtr(nullptr); +} + +template +typename AnalyticExpansion::AnalyticExpansionNodes AnalyticExpansion::getAnalyticPath( + const NodePtr & node, + const NodePtr & goal, + const NodeGetter & node_getter) +{ + static ompl::base::ScopedState<> from(node->motion_table.state_space), to( + node->motion_table.state_space), s(node->motion_table.state_space); + from[0] = node->pose.x; + from[1] = node->pose.y; + from[2] = node->pose.theta * node->motion_table.bin_size; + to[0] = goal->pose.x; + to[1] = goal->pose.y; + to[2] = goal->pose.theta * node->motion_table.bin_size; + + float d = node->motion_table.state_space->distance(from(), to()); + + // A move of sqrt(2) is guaranteed to be in a new cell + static const float sqrt_2 = std::sqrt(2.); + unsigned int num_intervals = std::floor(d / sqrt_2); + + AnalyticExpansionNodes possible_nodes; + // When "from" and "to" are zero or one cell away, + // num_intervals == 0 + possible_nodes.reserve(num_intervals); // We won't store this node or the goal + std::vector reals; + + // Pre-allocate + NodePtr prev(node); + unsigned int index = 0; + NodePtr next(nullptr); + float angle = 0.0; + Coordinates proposed_coordinates; + bool failure = false; + + // Check intermediary poses (non-goal, non-start) + for (float i = 1; i < num_intervals; i++) { + node->motion_table.state_space->interpolate(from(), to(), i / num_intervals, s()); + reals = s.reals(); + angle = reals[2] / node->motion_table.bin_size; + while (angle < 0.0) { + angle += node->motion_table.num_angle_quantization_float; + } + while (angle >= node->motion_table.num_angle_quantization_float) { + angle -= node->motion_table.num_angle_quantization_float; + } + // Turn the pose into a node, and check if it is valid + index = NodeT::getIndex( + static_cast(reals[0]), + static_cast(reals[1]), + static_cast(angle)); + // Get the node from the graph + if (node_getter(index, next)) { + Coordinates initial_node_coords = next->pose; + proposed_coordinates = {static_cast(reals[0]), static_cast(reals[1]), angle}; + next->setPose(proposed_coordinates); + if (next->isNodeValid(_traverse_unknown, _collision_checker) && next != prev) { + // Save the node, and its previous coordinates in case we need to abort + possible_nodes.emplace_back(next, initial_node_coords, proposed_coordinates); + prev = next; + } else { + // Abort + next->setPose(initial_node_coords); + failure = true; + break; + } + } else { + // Abort + failure = true; + break; + } + } + + // Reset to initial poses to not impact future searches + for (const auto & node_pose : possible_nodes) { + const auto & n = node_pose.node; + n->setPose(node_pose.initial_coords); + } + + if (failure) { + return AnalyticExpansionNodes(); + } + + return possible_nodes; +} + +template +typename AnalyticExpansion::NodePtr AnalyticExpansion::setAnalyticPath( + const NodePtr & node, + const NodePtr & goal_node, + const AnalyticExpansionNodes & expanded_nodes) +{ + // Legitimate final path - set the parent relationships & poses + NodePtr prev = node; + for (const auto & node_pose : expanded_nodes) { + const auto & n = node_pose.node; + if (!n->wasVisited() && n->getIndex() != goal_node->getIndex()) { + // Make sure this node has not been visited by the regular algorithm. + // If it has been, there is the (slight) chance that it is in the path we are expanding + // from, so we should skip it. + // Skipping to the next node will still create a kinematically feasible path. + n->parent = prev; + n->pose = node_pose.proposed_coords; + n->visited(); + prev = n; + } + } + if (goal_node != prev) { + goal_node->parent = prev; + goal_node->visited(); + } + return goal_node; +} + +template<> +typename AnalyticExpansion::AnalyticExpansionNodes AnalyticExpansion::getAnalyticPath( + const NodePtr & node, + const NodePtr & goal, + const NodeGetter & node_getter) +{ + return AnalyticExpansionNodes(); +} + +template<> +typename AnalyticExpansion::NodePtr AnalyticExpansion::setAnalyticPath( + const NodePtr & node, + const NodePtr & goal_node, + const AnalyticExpansionNodes & expanded_nodes) +{ + return NodePtr(nullptr); +} + +template<> +typename AnalyticExpansion::NodePtr AnalyticExpansion::tryAnalyticExpansion( + const NodePtr & current_node, const NodePtr & goal_node, + const NodeGetter & getter, int & analytic_iterations, + int & closest_distance) +{ + return NodePtr(nullptr); +} + +template class AnalyticExpansion; +template class AnalyticExpansion; +template class AnalyticExpansion; + +} // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index d8909388dc..b3478c50c9 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -58,6 +58,7 @@ void LatticeMotionTable::initMotionModel( cost_penalty = search_info.cost_penalty; reverse_penalty = search_info.reverse_penalty; current_lattice_filepath = search_info.lattice_filepath; + allow_reverse_expansion = search_info.allow_reverse_expansion; // TODO(Matt) read in file, precompute based on orientation bins for lookup at runtime // file is `search_info.lattice_filepath`, to be read in from plugin and provided here. @@ -69,10 +70,13 @@ void LatticeMotionTable::initMotionModel( // TODO(Matt) populate num_angle_quantization, size_x, min_turning_radius, trig_values, // all of the member variables of LatticeMotionTable + + // TODO use allow_reverse_expansion to set state_space to dubins/reeds-shepp } MotionPoses LatticeMotionTable::getProjections(const NodeLattice * node) { + // TODO use allow_reverse_expansion to get forward or inverse pair as well return MotionPoses(); // TODO(Matt) lookup at run time the primitives to use at node } diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index eb12db3fc5..d9ee491cb5 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -61,7 +61,6 @@ void SmacPlannerLattice::configure( int angle_quantizations; int lookup_table_size; SearchInfo search_info; - std::string motion_model_for_search; // General planner params nav2_util::declare_parameter_if_not_declared( @@ -106,6 +105,9 @@ void SmacPlannerLattice::configure( nav2_util::declare_parameter_if_not_declared( node, name + ".lookup_table_size", rclcpp::ParameterValue(20.0)); node->get_parameter(name + ".lookup_table_size", lookup_table_size); + nav2_util::declare_parameter_if_not_declared( + node, name + ".allow_reverse_expansion", rclcpp::ParameterValue(false)); + node->get_parameter(name + ".allow_reverse_expansion", search_info.allow_reverse_expansion); LatticeMetadata metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); _angle_quantizations = metadata.first; From e7e28c6ef2926474831645f5b1d443d70c9273d1 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 6 Oct 2021 15:44:55 -0700 Subject: [PATCH 03/31] moving smoother and collision checker into cpp files --- nav2_smac_planner/CMakeLists.txt | 6 + .../nav2_smac_planner/collision_checker.hpp | 119 +--------- .../include/nav2_smac_planner/smoother.hpp | 207 +++-------------- nav2_smac_planner/src/collision_checker.cpp | 148 ++++++++++++ nav2_smac_planner/src/smoother.cpp | 211 ++++++++++++++++++ 5 files changed, 400 insertions(+), 291 deletions(-) create mode 100644 nav2_smac_planner/src/collision_checker.cpp create mode 100644 nav2_smac_planner/src/smoother.cpp diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index b5ef8b8d29..773329fdb8 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -69,6 +69,8 @@ set(dependencies add_library(${library_name} SHARED src/smac_planner_hybrid.cpp src/a_star.cpp + src/collision_checker.cpp + src/smoother.cpp src/analytic_expansion.cpp src/node_hybrid.cpp src/node_lattice.cpp @@ -87,6 +89,8 @@ ament_target_dependencies(${library_name} add_library(${library_name}_2d SHARED src/smac_planner_2d.cpp src/a_star.cpp + src/smoother.cpp + src/collision_checker.cpp src/analytic_expansion.cpp src/node_hybrid.cpp src/node_lattice.cpp @@ -105,6 +109,8 @@ ament_target_dependencies(${library_name}_2d add_library(${library_name}_lattice SHARED src/smac_planner_lattice.cpp src/a_star.cpp + src/smoother.cpp + src/collision_checker.cpp src/analytic_expansion.cpp src/node_hybrid.cpp src/node_lattice.cpp diff --git a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp index c38aeff101..3fcc4e39ac 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp @@ -51,45 +51,7 @@ class GridCollisionChecker void setFootprint( const nav2_costmap_2d::Footprint & footprint, const bool & radius, - const double & possible_inscribed_cost) - { - possible_inscribed_cost_ = possible_inscribed_cost; - footprint_is_radius_ = radius; - - // Use radius, no caching required - if (radius) { - return; - } - - // No change, no updates required - if (footprint == unoriented_footprint_) { - return; - } - - bin_size_ = 2.0 * M_PI / static_cast(num_quantizations_); - oriented_footprints_.reserve(num_quantizations_); - double sin_th, cos_th; - geometry_msgs::msg::Point new_pt; - const unsigned int footprint_size = footprint.size(); - - // Precompute the orientation bins for checking to use - for (unsigned int i = 0; i != num_quantizations_; i++) { - sin_th = sin(i * bin_size_); - cos_th = cos(i * bin_size_); - nav2_costmap_2d::Footprint oriented_footprint; - oriented_footprint.reserve(footprint_size); - - for (unsigned int j = 0; j < footprint_size; j++) { - new_pt.x = footprint[j].x * cos_th - footprint[j].y * sin_th; - new_pt.y = footprint[j].x * sin_th + footprint[j].y * cos_th; - oriented_footprint.push_back(new_pt); - } - - oriented_footprints_.push_back(oriented_footprint); - } - - unoriented_footprint_ = footprint; - } + const double & possible_inscribed_cost); /** * @brief Check if in collision with costmap and footprint at pose @@ -103,67 +65,7 @@ class GridCollisionChecker const float & x, const float & y, const float & theta, - const bool & traverse_unknown) - { - // Assumes setFootprint already set - double wx, wy; - costmap_->mapToWorld(static_cast(x), static_cast(y), wx, wy); - - if (!footprint_is_radius_) { - // if footprint, then we check for the footprint's points, but first see - // if the robot is even potentially in an inscribed collision - footprint_cost_ = costmap_->getCost( - static_cast(x), static_cast(y)); - - if (footprint_cost_ < possible_inscribed_cost_) { - return false; - } - - // If its inscribed, in collision, or unknown in the middle, - // no need to even check the footprint, its invalid - if (footprint_cost_ == UNKNOWN && !traverse_unknown) { - return true; - } - - if (footprint_cost_ == INSCRIBED || footprint_cost_ == OCCUPIED) { - return true; - } - - // if possible inscribed, need to check actual footprint pose. - // Use precomputed oriented footprints are done on initialization, - // offset by translation value to collision check - int angle_bin = theta / bin_size_; - geometry_msgs::msg::Point new_pt; - const nav2_costmap_2d::Footprint & oriented_footprint = oriented_footprints_[angle_bin]; - nav2_costmap_2d::Footprint current_footprint; - current_footprint.reserve(oriented_footprint.size()); - for (unsigned int i = 0; i < oriented_footprint.size(); ++i) { - new_pt.x = wx + oriented_footprint[i].x; - new_pt.y = wy + oriented_footprint[i].y; - current_footprint.push_back(new_pt); - } - - footprint_cost_ = footprintCost(current_footprint); - - if (footprint_cost_ == UNKNOWN && traverse_unknown) { - return false; - } - - // if occupied or unknown and not to traverse unknown space - return footprint_cost_ >= OCCUPIED; - } else { - // if radius, then we can check the center of the cost assuming inflation is used - footprint_cost_ = costmap_->getCost( - static_cast(x), static_cast(y)); - - if (footprint_cost_ == UNKNOWN && traverse_unknown) { - return false; - } - - // if occupied or unknown and not to traverse unknown space - return footprint_cost_ >= INSCRIBED; - } - } + const bool & traverse_unknown); /** * @brief Check if in collision with costmap and footprint at pose @@ -173,26 +75,13 @@ class GridCollisionChecker */ bool inCollision( const unsigned int & i, - const bool & traverse_unknown) - { - footprint_cost_ = costmap_->getCost(i); - if (footprint_cost_ == UNKNOWN && traverse_unknown) { - return false; - } - - // if occupied or unknown and not to traverse unknown space - return footprint_cost_ >= INSCRIBED; - } + const bool & traverse_unknown); /** * @brief Get cost at footprint pose in costmap * @return the cost at the pose in costmap */ - float getCost() - { - // Assumes inCollision called prior - return static_cast(footprint_cost_); - } + float getCost(); protected: std::vector oriented_footprints_; diff --git a/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp b/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp index a9c45d4cda..cbadf92f67 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp @@ -22,7 +22,9 @@ #include #include +#include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_smac_planner/types.hpp" +#include "nav2_smac_planner/constants.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav_msgs/msg/path.hpp" @@ -39,13 +41,7 @@ class Smoother /** * @brief A constructor for nav2_smac_planner::Smoother */ - explicit Smoother(const SmootherParams & params) - { - tolerance_ = params.tolerance_; - max_its_ = params.max_its_; - data_w_ = params.w_data_; - smooth_w_ = params.w_smooth_; - } + explicit Smoother(const SmootherParams & params); /** * @brief A destructor for nav2_smac_planner::Smoother @@ -56,10 +52,7 @@ class Smoother * @brief Initialization of the smoother * @param min_turning_radius Minimum turning radius (m) */ - void initialize(const double & min_turning_radius) - { - min_turning_rad_ = min_turning_radius; - } + void initialize(const double & min_turning_radius); /** * @brief Smoother method @@ -72,178 +65,40 @@ class Smoother nav_msgs::msg::Path & path, const nav2_costmap_2d::Costmap2D * costmap, const double & max_time, - const bool do_refinement = true) - { - using namespace std::chrono; // NOLINT - steady_clock::time_point a = steady_clock::now(); - rclcpp::Duration max_dur = rclcpp::Duration::from_seconds(max_time); - - int its = 0; - double change = tolerance_; - const unsigned int & path_size = path.poses.size(); - double x_i, y_i, y_m1, y_ip1, y_im2, y_ip2, y_i_org, curvature; - unsigned int mx, my; - - // Adding 5% margin due to floating point error - const double max_curvature = (1.0 / min_turning_rad_) * 1.05; - nav_msgs::msg::Path new_path = path; - nav_msgs::msg::Path last_path = path; - - while (change >= tolerance_) { - its += 1; - change = 0.0; - - // Make sure the smoothing function will converge - if (its >= max_its_) { - RCLCPP_DEBUG( - rclcpp::get_logger("SmacPlannerSmoother"), - "Number of iterations has exceeded limit of %i.", max_its_); - path = last_path; - updateApproximatePathOrientations(path); - return false; - } - - // Make sure still have time left to process - steady_clock::time_point b = steady_clock::now(); - rclcpp::Duration timespan(duration_cast>(b - a)); - if (timespan > max_dur) { - RCLCPP_DEBUG( - rclcpp::get_logger("SmacPlannerSmoother"), - "Smoothing time exceeded allowed duration of %0.2f.", max_time); - path = last_path; - updateApproximatePathOrientations(path); - return false; - } - - for (unsigned int i = 2; i != path_size - 2; i++) { - for (unsigned int j = 0; j != 2; j++) { - x_i = getFieldByDim(path.poses[i], j); - y_i = getFieldByDim(new_path.poses[i], j); - y_m1 = getFieldByDim(new_path.poses[i - 1], j); - y_ip1 = getFieldByDim(new_path.poses[i + 1], j); - y_i_org = y_i; - - if (i > 2 && i < path_size - 2) { - // Smooth based on local 5 point neighborhood and original data locations - y_im2 = getFieldByDim(new_path.poses[i - 2], j); - y_ip2 = getFieldByDim(new_path.poses[i + 2], j); - y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_im2 + y_ip2 + y_ip1 + y_m1 - (4.0 * y_i)); - } else { - // Smooth based on local 3 point neighborhood and original data locations - // At boundary conditions, need to use a more local neighborhood because the first - // and last 2 points cannot move to ensure the boundry conditions are upheld - y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_ip1 + y_m1 - (2.0 * y_i)); - } - - setFieldByDim(new_path.poses[i], j, y_i); - change += abs(y_i - y_i_org); - } - - // validate update is admissible, only checks cost if a valid costmap pointer is provided - float cost = 0.0; - if (costmap) { - costmap->worldToMap( - getFieldByDim(new_path.poses[i], 0), - getFieldByDim(new_path.poses[i], 1), - mx, my); - cost = static_cast(costmap->getCost(mx, my)); - } - if (cost > MAX_NON_OBSTACLE) { - RCLCPP_DEBUG( - rclcpp::get_logger("SmacPlannerSmoother"), - "Smoothing process resulted in an infeasible collision. " - "Returning the last path before the infeasibility was introduced."); - path = last_path; - updateApproximatePathOrientations(path); - return false; - } - } - - last_path = new_path; - } - - // Lets do additional refinement, it shouldn't take more than a couple milliseconds - // but really puts the path quality over the top. - if (do_refinement) { - smooth(new_path, costmap, max_time, false); - } - - for (unsigned int i = 3; i != path_size - 3; i++) { - if (getCurvature(new_path, i) > max_curvature) { - RCLCPP_DEBUG( - rclcpp::get_logger("SmacPlannerSmoother"), - "Smoothing process resulted in an infeasible curvature somewhere on the path. " - "This is most likely at the end point boundary conditions which will be further " - "refined as a perfect curve as you approach the goal. If this becomes a practical " - "issue for you, please file a ticket mentioning this message."); - updateApproximatePathOrientations(new_path); - path = new_path; - return false; - } - } - - updateApproximatePathOrientations(new_path); - path = new_path; - return true; - } + const bool do_refinement = true); protected: - inline double getFieldByDim(const geometry_msgs::msg::PoseStamped & msg, const unsigned int & dim) - { - if (dim == 0) { - return msg.pose.position.x; - } else if (dim == 1) { - return msg.pose.position.y; - } else { - return msg.pose.position.z; - } - } + /** + * @brief Get the field value for a given dimension + * @param msg Current pose to sample + * @param dim Dimension ID of interest + * @return dim value + */ + inline double getFieldByDim(const geometry_msgs::msg::PoseStamped & msg, const unsigned int & dim); + /** + * @brief Set the field value for a given dimension + * @param msg Current pose to sample + * @param dim Dimension ID of interest + * @param value to set the dimention to for the pose + */ inline void setFieldByDim( geometry_msgs::msg::PoseStamped & msg, const unsigned int dim, - const double & value) - { - if (dim == 0) { - msg.pose.position.x = value; - } else if (dim == 1) { - msg.pose.position.y = value; - } else { - msg.pose.position.z = value; - } - } - - inline double getCurvature(const nav_msgs::msg::Path & path, const unsigned int i) - { - // k = 1 / r = acos(delta_phi) / |xi|, where delta_phi = (xi dot xi+1) / (|xi| * |xi+1|) - const double dxi_x = getFieldByDim(path.poses[i], 0) - getFieldByDim(path.poses[i - 1], 0); - const double dxi_y = getFieldByDim(path.poses[i], 1) - getFieldByDim(path.poses[i - 1], 1); - const double dxip1_x = getFieldByDim(path.poses[i + 1], 0) - getFieldByDim(path.poses[i], 0); - const double dxip1_y = getFieldByDim(path.poses[i + 1], 1) - getFieldByDim(path.poses[i], 1); - const double norm_dx_i = hypot(dxi_x, dxi_y); - const double norm_dx_ip1 = hypot(dxip1_x, dxip1_y); - double arg = (dxi_x * dxip1_x + dxi_y * dxip1_y) / (norm_dx_i * norm_dx_ip1); + const double & value); - // In case of small out of bounds issues from floating point error - if (arg > 1.0) { - arg = 1.0; - } else if (arg < -1.0) { - arg = -1.0; - } - - return acos(arg) / norm_dx_i; - } + /** + * @brief Get the instantaneous curvature valud + * @param path Path to find curvature in + * @param i idx in path to find it for + * @return curvature + */ + inline double getCurvature(const nav_msgs::msg::Path & path, const unsigned int i); - inline void updateApproximatePathOrientations(nav_msgs::msg::Path & path) - { - using namespace nav2_util::geometry_utils; // NOLINT - double dx, dy, theta; - for (unsigned int i = 0; i != path.poses.size() - 1; i++) { - dx = path.poses[i + 1].pose.position.x - path.poses[i].pose.position.x; - dy = path.poses[i + 1].pose.position.y - path.poses[i].pose.position.y; - theta = atan2(dy, dx); - path.poses[i].pose.orientation = orientationAroundZAxis(theta); - } - } + /** + * @brief For a given path, update the path point orientations based on smoothing + * @param path Path to approximate the path orientation in + */ + inline void updateApproximatePathOrientations(nav_msgs::msg::Path & path); double min_turning_rad_, tolerance_, data_w_, smooth_w_; int max_its_; diff --git a/nav2_smac_planner/src/collision_checker.cpp b/nav2_smac_planner/src/collision_checker.cpp new file mode 100644 index 0000000000..e17d10e98a --- /dev/null +++ b/nav2_smac_planner/src/collision_checker.cpp @@ -0,0 +1,148 @@ +// Copyright (c) 2021, Samsung Research America +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#include "nav2_smac_planner/collision_checker.hpp" + +namespace nav2_smac_planner +{ + +void GridCollisionChecker::setFootprint( + const nav2_costmap_2d::Footprint & footprint, + const bool & radius, + const double & possible_inscribed_cost) +{ + possible_inscribed_cost_ = possible_inscribed_cost; + footprint_is_radius_ = radius; + + // Use radius, no caching required + if (radius) { + return; + } + + // No change, no updates required + if (footprint == unoriented_footprint_) { + return; + } + + bin_size_ = 2.0 * M_PI / static_cast(num_quantizations_); + oriented_footprints_.reserve(num_quantizations_); + double sin_th, cos_th; + geometry_msgs::msg::Point new_pt; + const unsigned int footprint_size = footprint.size(); + + // Precompute the orientation bins for checking to use + for (unsigned int i = 0; i != num_quantizations_; i++) { + sin_th = sin(i * bin_size_); + cos_th = cos(i * bin_size_); + nav2_costmap_2d::Footprint oriented_footprint; + oriented_footprint.reserve(footprint_size); + + for (unsigned int j = 0; j < footprint_size; j++) { + new_pt.x = footprint[j].x * cos_th - footprint[j].y * sin_th; + new_pt.y = footprint[j].x * sin_th + footprint[j].y * cos_th; + oriented_footprint.push_back(new_pt); + } + + oriented_footprints_.push_back(oriented_footprint); + } + + unoriented_footprint_ = footprint; +} + +bool GridCollisionChecker::inCollision( + const float & x, + const float & y, + const float & theta, + const bool & traverse_unknown) +{ + // Assumes setFootprint already set + double wx, wy; + costmap_->mapToWorld(static_cast(x), static_cast(y), wx, wy); + + if (!footprint_is_radius_) { + // if footprint, then we check for the footprint's points, but first see + // if the robot is even potentially in an inscribed collision + footprint_cost_ = costmap_->getCost( + static_cast(x), static_cast(y)); + + if (footprint_cost_ < possible_inscribed_cost_) { + return false; + } + + // If its inscribed, in collision, or unknown in the middle, + // no need to even check the footprint, its invalid + if (footprint_cost_ == UNKNOWN && !traverse_unknown) { + return true; + } + + if (footprint_cost_ == INSCRIBED || footprint_cost_ == OCCUPIED) { + return true; + } + + // if possible inscribed, need to check actual footprint pose. + // Use precomputed oriented footprints are done on initialization, + // offset by translation value to collision check + int angle_bin = theta / bin_size_; + geometry_msgs::msg::Point new_pt; + const nav2_costmap_2d::Footprint & oriented_footprint = oriented_footprints_[angle_bin]; + nav2_costmap_2d::Footprint current_footprint; + current_footprint.reserve(oriented_footprint.size()); + for (unsigned int i = 0; i < oriented_footprint.size(); ++i) { + new_pt.x = wx + oriented_footprint[i].x; + new_pt.y = wy + oriented_footprint[i].y; + current_footprint.push_back(new_pt); + } + + footprint_cost_ = footprintCost(current_footprint); + + if (footprint_cost_ == UNKNOWN && traverse_unknown) { + return false; + } + + // if occupied or unknown and not to traverse unknown space + return footprint_cost_ >= OCCUPIED; + } else { + // if radius, then we can check the center of the cost assuming inflation is used + footprint_cost_ = costmap_->getCost( + static_cast(x), static_cast(y)); + + if (footprint_cost_ == UNKNOWN && traverse_unknown) { + return false; + } + + // if occupied or unknown and not to traverse unknown space + return footprint_cost_ >= INSCRIBED; + } +} + +bool GridCollisionChecker::inCollision( + const unsigned int & i, + const bool & traverse_unknown) +{ + footprint_cost_ = costmap_->getCost(i); + if (footprint_cost_ == UNKNOWN && traverse_unknown) { + return false; + } + + // if occupied or unknown and not to traverse unknown space + return footprint_cost_ >= INSCRIBED; +} + +float GridCollisionChecker::getCost() +{ + // Assumes inCollision called prior + return static_cast(footprint_cost_); +} + +} // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/smoother.cpp b/nav2_smac_planner/src/smoother.cpp new file mode 100644 index 0000000000..b9e8c54a25 --- /dev/null +++ b/nav2_smac_planner/src/smoother.cpp @@ -0,0 +1,211 @@ +// Copyright (c) 2021, Samsung Research America +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#include "nav2_smac_planner/smoother.hpp" + +namespace nav2_smac_planner +{ + +Smoother::Smoother(const SmootherParams & params) +{ + tolerance_ = params.tolerance_; + max_its_ = params.max_its_; + data_w_ = params.w_data_; + smooth_w_ = params.w_smooth_; +} + +void Smoother::initialize(const double & min_turning_radius) +{ + min_turning_rad_ = min_turning_radius; +} + + +bool Smoother::smooth( + nav_msgs::msg::Path & path, + const nav2_costmap_2d::Costmap2D * costmap, + const double & max_time, + const bool do_refinement) +{ + using namespace std::chrono; // NOLINT + steady_clock::time_point a = steady_clock::now(); + rclcpp::Duration max_dur = rclcpp::Duration::from_seconds(max_time); + + int its = 0; + double change = tolerance_; + const unsigned int & path_size = path.poses.size(); + double x_i, y_i, y_m1, y_ip1, y_im2, y_ip2, y_i_org, curvature; + unsigned int mx, my; + + // Adding 5% margin due to floating point error + const double max_curvature = (1.0 / min_turning_rad_) * 1.05; + nav_msgs::msg::Path new_path = path; + nav_msgs::msg::Path last_path = path; + + while (change >= tolerance_) { + its += 1; + change = 0.0; + + // Make sure the smoothing function will converge + if (its >= max_its_) { + RCLCPP_DEBUG( + rclcpp::get_logger("SmacPlannerSmoother"), + "Number of iterations has exceeded limit of %i.", max_its_); + path = last_path; + updateApproximatePathOrientations(path); + return false; + } + + // Make sure still have time left to process + steady_clock::time_point b = steady_clock::now(); + rclcpp::Duration timespan(duration_cast>(b - a)); + if (timespan > max_dur) { + RCLCPP_DEBUG( + rclcpp::get_logger("SmacPlannerSmoother"), + "Smoothing time exceeded allowed duration of %0.2f.", max_time); + path = last_path; + updateApproximatePathOrientations(path); + return false; + } + + for (unsigned int i = 2; i != path_size - 2; i++) { + for (unsigned int j = 0; j != 2; j++) { + x_i = getFieldByDim(path.poses[i], j); + y_i = getFieldByDim(new_path.poses[i], j); + y_m1 = getFieldByDim(new_path.poses[i - 1], j); + y_ip1 = getFieldByDim(new_path.poses[i + 1], j); + y_i_org = y_i; + + if (i > 2 && i < path_size - 2) { + // Smooth based on local 5 point neighborhood and original data locations + y_im2 = getFieldByDim(new_path.poses[i - 2], j); + y_ip2 = getFieldByDim(new_path.poses[i + 2], j); + y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_im2 + y_ip2 + y_ip1 + y_m1 - (4.0 * y_i)); + } else { + // Smooth based on local 3 point neighborhood and original data locations + // At boundary conditions, need to use a more local neighborhood because the first + // and last 2 points cannot move to ensure the boundry conditions are upheld + y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_ip1 + y_m1 - (2.0 * y_i)); + } + + setFieldByDim(new_path.poses[i], j, y_i); + change += abs(y_i - y_i_org); + } + + // validate update is admissible, only checks cost if a valid costmap pointer is provided + float cost = 0.0; + if (costmap) { + costmap->worldToMap( + getFieldByDim(new_path.poses[i], 0), + getFieldByDim(new_path.poses[i], 1), + mx, my); + cost = static_cast(costmap->getCost(mx, my)); + } + if (cost > MAX_NON_OBSTACLE) { + RCLCPP_DEBUG( + rclcpp::get_logger("SmacPlannerSmoother"), + "Smoothing process resulted in an infeasible collision. " + "Returning the last path before the infeasibility was introduced."); + path = last_path; + updateApproximatePathOrientations(path); + return false; + } + } + + last_path = new_path; + } + + // Lets do additional refinement, it shouldn't take more than a couple milliseconds + // but really puts the path quality over the top. + if (do_refinement) { + smooth(new_path, costmap, max_time, false); + } + + for (unsigned int i = 3; i != path_size - 3; i++) { + if (getCurvature(new_path, i) > max_curvature) { + RCLCPP_DEBUG( + rclcpp::get_logger("SmacPlannerSmoother"), + "Smoothing process resulted in an infeasible curvature somewhere on the path. " + "This is most likely at the end point boundary conditions which will be further " + "refined as a perfect curve as you approach the goal. If this becomes a practical " + "issue for you, please file a ticket mentioning this message."); + updateApproximatePathOrientations(new_path); + path = new_path; + return false; + } + } + + updateApproximatePathOrientations(new_path); + path = new_path; + return true; +} + +double Smoother::getFieldByDim( + const geometry_msgs::msg::PoseStamped & msg, const unsigned int & dim) +{ + if (dim == 0) { + return msg.pose.position.x; + } else if (dim == 1) { + return msg.pose.position.y; + } else { + return msg.pose.position.z; + } +} + +void Smoother::setFieldByDim( + geometry_msgs::msg::PoseStamped & msg, const unsigned int dim, + const double & value) +{ + if (dim == 0) { + msg.pose.position.x = value; + } else if (dim == 1) { + msg.pose.position.y = value; + } else { + msg.pose.position.z = value; + } +} + +double Smoother::getCurvature(const nav_msgs::msg::Path & path, const unsigned int i) +{ + // k = 1 / r = acos(delta_phi) / |xi|, where delta_phi = (xi dot xi+1) / (|xi| * |xi+1|) + const double dxi_x = getFieldByDim(path.poses[i], 0) - getFieldByDim(path.poses[i - 1], 0); + const double dxi_y = getFieldByDim(path.poses[i], 1) - getFieldByDim(path.poses[i - 1], 1); + const double dxip1_x = getFieldByDim(path.poses[i + 1], 0) - getFieldByDim(path.poses[i], 0); + const double dxip1_y = getFieldByDim(path.poses[i + 1], 1) - getFieldByDim(path.poses[i], 1); + const double norm_dx_i = hypot(dxi_x, dxi_y); + const double norm_dx_ip1 = hypot(dxip1_x, dxip1_y); + double arg = (dxi_x * dxip1_x + dxi_y * dxip1_y) / (norm_dx_i * norm_dx_ip1); + + // In case of small out of bounds issues from floating point error + if (arg > 1.0) { + arg = 1.0; + } else if (arg < -1.0) { + arg = -1.0; + } + + return acos(arg) / norm_dx_i; +} + +void Smoother::updateApproximatePathOrientations(nav_msgs::msg::Path & path) +{ + using namespace nav2_util::geometry_utils; // NOLINT + double dx, dy, theta; + for (unsigned int i = 0; i != path.poses.size() - 1; i++) { + dx = path.poses[i + 1].pose.position.x - path.poses[i].pose.position.x; + dy = path.poses[i + 1].pose.position.y - path.poses[i].pose.position.y; + theta = atan2(dy, dx); + path.poses[i].pose.orientation = orientationAroundZAxis(theta); + } +} + +} // namespace nav2_smac_planner From 399f0e4fcc0a6915272b93deadd0d6e9c6e89a09 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 7 Oct 2021 15:47:45 -0700 Subject: [PATCH 04/31] allowing smac planner to work with irregular bin distributions --- .../nav2_smac_planner/collision_checker.hpp | 23 ++-- .../include/nav2_smac_planner/node_hybrid.hpp | 14 +++ .../nav2_smac_planner/node_lattice.hpp | 27 +++-- .../smac_planner_lattice.hpp | 17 ++- .../include/nav2_smac_planner/utils.hpp | 14 +++ nav2_smac_planner/src/analytic_expansion.cpp | 17 ++- nav2_smac_planner/src/collision_checker.cpp | 33 ++++-- nav2_smac_planner/src/node_hybrid.cpp | 12 ++- nav2_smac_planner/src/node_lattice.cpp | 100 +++++++++++++++--- .../src/smac_planner_lattice.cpp | 50 +++++---- 10 files changed, 235 insertions(+), 72 deletions(-) diff --git a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp index 3fcc4e39ac..aa27404fcf 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp @@ -31,17 +31,25 @@ class GridCollisionChecker public: /** * @brief A constructor for nav2_smac_planner::GridCollisionChecker + * for use when regular bin intervals are appropriate * @param costmap The costmap to collision check against * @param num_quantizations The number of quantizations to precompute footprint * orientations for to speed up collision checking */ GridCollisionChecker( nav2_costmap_2d::Costmap2D * costmap, - unsigned int num_quantizations) - : FootprintCollisionChecker(costmap), - num_quantizations_(num_quantizations) - { - } + unsigned int num_quantizations); + + /** + * @brief A constructor for nav2_smac_planner::GridCollisionChecker + * for use when irregular bin intervals are appropriate + * @param costmap The costmap to collision check against + * @param angles The vector of possible angle bins to precompute for + * orientations for to speed up collision checking, in radians + */ + GridCollisionChecker( + nav2_costmap_2d::Costmap2D * costmap, + std::vector & angles); /** * @brief Set the footprint to use with collision checker @@ -57,7 +65,7 @@ class GridCollisionChecker * @brief Check if in collision with costmap and footprint at pose * @param x X coordinate of pose to check against * @param y Y coordinate of pose to check against - * @param theta Angle of pose to check against + * @param theta Angle bin number of pose to check against (NOT radians) * @param traverse_unknown Whether or not to traverse in unknown space * @return boolean if in collision or not. */ @@ -88,8 +96,7 @@ class GridCollisionChecker nav2_costmap_2d::Footprint unoriented_footprint_; double footprint_cost_; bool footprint_is_radius_; - unsigned int num_quantizations_; - double bin_size_; + std::vector angles_; double possible_inscribed_cost_{-1}; }; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp index e2b85f18a2..dab6d13339 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp @@ -115,6 +115,20 @@ struct HybridMotionTable */ MotionPoses getProjections(const NodeHybrid * node); + /** + * @brief Get the angular bin to use from a raw orientation + * @param theta Angle in radians + * @return bin index of closest angle to request + */ + unsigned int getClosestAngularBin(const double & theta); + + /** + * @brief Get the raw orientation from an angular bin + * @param bin_idx Index of the bin + * @return Raw orientation in radians + */ + float getAngleFromBin(const unsigned int & bin_idx); + MotionPoses projections; unsigned int size_x; unsigned int num_angle_quantization; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index fb21f5fe3a..274744cd0e 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -80,12 +80,24 @@ struct LatticeMotionTable */ static LatticeMetadata getLatticeMetadata(const std::string & lattice_filepath); + /** + * @brief Get the angular bin to use from a raw orientation + * @param theta Angle in radians + * @return bin index of closest angle to request + */ + unsigned int getClosestAngularBin(const double & theta); + + /** + * @brief Get the raw orientation from an angular bin + * @param bin_idx Index of the bin + * @return Raw orientation in radians + */ + float getAngleFromBin(const unsigned int & bin_idx); + MotionPoses projections; unsigned int size_x; unsigned int num_angle_quantization; - float num_angle_quantization_float; float min_turning_radius; - float bin_size; float change_penalty; float non_straight_penalty; float cost_penalty; @@ -302,13 +314,7 @@ class NodeLattice const float & lookup_table_dim, const MotionModel & motion_model, const unsigned int & dim_3_size, - const SearchInfo & search_info) - { - // State Lattice and Hybrid-A* share this heuristics - NodeHybrid::precomputeDistanceHeuristic( - lookup_table_dim, motion_model, dim_3_size, - search_info); - } + const SearchInfo & search_info); /** * @brief Compute the wavefront heuristic @@ -366,6 +372,9 @@ class NodeLattice NodeLattice * parent; Coordinates pose; static LatticeMotionTable motion_table; + // Dubin / Reeds-Shepp lookup and size for dereferencing + static LookupTable dist_heuristic_lookup_table; + static float size_lookup; private: float _cell_cost; diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp index ae46a36116..4855ed72b0 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp @@ -87,6 +87,20 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner const geometry_msgs::msg::PoseStamped & goal) override; protected: + /** + * @brief Get the angular bin to use from a raw orientation + * @param theta Angle in radians + * @return bin index of closest angle to request + */ + unsigned int getClosestAngularBin(const double & theta); + + /** + * @brief Get the raw orientation from an angular bin + * @param bin_idx Index of the bin + * @return Raw orientation in radians + */ + float getAngleFromBin(const unsigned int & bin_idx); + std::unique_ptr> _a_star; GridCollisionChecker _collision_checker; std::unique_ptr _smoother; @@ -94,11 +108,10 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner rclcpp::Logger _logger{rclcpp::get_logger("SmacPlannerLattice")}; nav2_costmap_2d::Costmap2D * _costmap; std::unique_ptr _costmap_downsampler; + LatticeMetadata _metadata; std::string _global_frame, _name; float _tolerance; int _downsampling_factor; - unsigned int _angle_quantizations; - double _angle_bin_size; bool _downsample_costmap; rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; double _max_planning_time; diff --git a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp index 0c58fbfc01..ebf2ea10c3 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp @@ -61,6 +61,20 @@ inline geometry_msgs::msg::Quaternion getWorldOrientation( return tf2::toMsg(q); } +/** +* @brief Create quaternion from radians +* @param theta continuous bin coordinates angle +* @return quaternion orientation in map frame +*/ +inline geometry_msgs::msg::Quaternion getWorldOrientation( + const float & theta) +{ + // theta is in radians already + tf2::Quaternion q; + q.setEuler(0.0, 0.0, theta); + return tf2::toMsg(q); +} + /** * @brief Find the min cost of the inflation decay function for which the robot MAY be * in collision in any orientation diff --git a/nav2_smac_planner/src/analytic_expansion.cpp b/nav2_smac_planner/src/analytic_expansion.cpp index 618b8f3d6c..0919d0d921 100644 --- a/nav2_smac_planner/src/analytic_expansion.cpp +++ b/nav2_smac_planner/src/analytic_expansion.cpp @@ -122,10 +122,10 @@ typename AnalyticExpansion::AnalyticExpansionNodes AnalyticExpansionmotion_table.state_space), s(node->motion_table.state_space); from[0] = node->pose.x; from[1] = node->pose.y; - from[2] = node->pose.theta * node->motion_table.bin_size; + from[2] = node->motion_table.getAngleFromBin(node->pose.theta); to[0] = goal->pose.x; to[1] = goal->pose.y; - to[2] = goal->pose.theta * node->motion_table.bin_size; + to[2] = node->motion_table.getAngleFromBin(goal->pose.theta); float d = node->motion_table.state_space->distance(from(), to()); @@ -138,6 +138,7 @@ typename AnalyticExpansion::AnalyticExpansionNodes AnalyticExpansion reals; + double theta; // Pre-allocate NodePtr prev(node); @@ -151,13 +152,11 @@ typename AnalyticExpansion::AnalyticExpansionNodes AnalyticExpansionmotion_table.state_space->interpolate(from(), to(), i / num_intervals, s()); reals = s.reals(); - angle = reals[2] / node->motion_table.bin_size; - while (angle < 0.0) { - angle += node->motion_table.num_angle_quantization_float; - } - while (angle >= node->motion_table.num_angle_quantization_float) { - angle -= node->motion_table.num_angle_quantization_float; - } + // Make sure in range [0, 2PI) + theta = (reals[2] < 0.0) ? (reals[2] + 2.0 * M_PI) : reals[2]; + theta = (theta > 2.0 * M_PI) ? (theta - 2.0 * M_PI) : theta; + angle = node->motion_table.getClosestAngularBin(theta); + // Turn the pose into a node, and check if it is valid index = NodeT::getIndex( static_cast(reals[0]), diff --git a/nav2_smac_planner/src/collision_checker.cpp b/nav2_smac_planner/src/collision_checker.cpp index e17d10e98a..172eb8abb7 100644 --- a/nav2_smac_planner/src/collision_checker.cpp +++ b/nav2_smac_planner/src/collision_checker.cpp @@ -17,6 +17,27 @@ namespace nav2_smac_planner { +GridCollisionChecker::GridCollisionChecker( + nav2_costmap_2d::Costmap2D * costmap, + unsigned int num_quantizations) +: FootprintCollisionChecker(costmap) +{ + // Convert number of regular bins into angles + float bin_size = 2 * M_PI / static_cast(num_quantizations); + angles_.reserve(num_quantizations); + for (unsigned int i = 0; i != num_quantizations; i++) { + angles_.push_back(bin_size * i); + } +} + +GridCollisionChecker::GridCollisionChecker( + nav2_costmap_2d::Costmap2D * costmap, + std::vector & angles) +: FootprintCollisionChecker(costmap), + angles_(angles) +{ +} + void GridCollisionChecker::setFootprint( const nav2_costmap_2d::Footprint & footprint, const bool & radius, @@ -35,16 +56,15 @@ void GridCollisionChecker::setFootprint( return; } - bin_size_ = 2.0 * M_PI / static_cast(num_quantizations_); - oriented_footprints_.reserve(num_quantizations_); + oriented_footprints_.reserve(angles_.size()); double sin_th, cos_th; geometry_msgs::msg::Point new_pt; const unsigned int footprint_size = footprint.size(); // Precompute the orientation bins for checking to use - for (unsigned int i = 0; i != num_quantizations_; i++) { - sin_th = sin(i * bin_size_); - cos_th = cos(i * bin_size_); + for (unsigned int i = 0; i != angles_.size(); i++) { + sin_th = sin(angles_[i]); + cos_th = cos(angles_[i]); nav2_costmap_2d::Footprint oriented_footprint; oriented_footprint.reserve(footprint_size); @@ -63,7 +83,7 @@ void GridCollisionChecker::setFootprint( bool GridCollisionChecker::inCollision( const float & x, const float & y, - const float & theta, + const float & angle_bin, const bool & traverse_unknown) { // Assumes setFootprint already set @@ -93,7 +113,6 @@ bool GridCollisionChecker::inCollision( // if possible inscribed, need to check actual footprint pose. // Use precomputed oriented footprints are done on initialization, // offset by translation value to collision check - int angle_bin = theta / bin_size_; geometry_msgs::msg::Point new_pt; const nav2_costmap_2d::Footprint & oriented_footprint = oriented_footprints_[angle_bin]; nav2_costmap_2d::Footprint current_footprint; diff --git a/nav2_smac_planner/src/node_hybrid.cpp b/nav2_smac_planner/src/node_hybrid.cpp index b02d99f326..16cb0925c4 100644 --- a/nav2_smac_planner/src/node_hybrid.cpp +++ b/nav2_smac_planner/src/node_hybrid.cpp @@ -247,6 +247,16 @@ MotionPoses HybridMotionTable::getProjections(const NodeHybrid * node) return projection_list; } +unsigned int HybridMotionTable::getClosestAngularBin(const double & theta) +{ + return static_cast(floor(theta / bin_size)); +} + +float HybridMotionTable::getAngleFromBin(const unsigned int & bin_idx) +{ + return bin_idx * bin_size; +} + NodeHybrid::NodeHybrid(const unsigned int index) : parent(nullptr), pose(0.0f, 0.0f, 0.0f), @@ -280,7 +290,7 @@ bool NodeHybrid::isNodeValid( GridCollisionChecker * collision_checker) { if (collision_checker->inCollision( - this->pose.x, this->pose.y, this->pose.theta * motion_table.bin_size, traverse_unknown)) + this->pose.x, this->pose.y, this->pose.theta /*bin number*/, traverse_unknown)) { return false; } diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index b3478c50c9..a985ed5197 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -35,6 +35,8 @@ namespace nav2_smac_planner // defining static member for all instance to share LatticeMotionTable NodeLattice::motion_table; +float NodeLattice::size_lookup = 25; +LookupTable NodeLattice::dist_heuristic_lookup_table; // Each of these tables are the projected motion models through // time and space applied to the search on the current node in @@ -88,6 +90,28 @@ LatticeMetadata LatticeMotionTable::getLatticeMetadata(const std::string & latti return {0 /*num bins*/, 0 /*turning rad*/}; } +unsigned int LatticeMotionTable::getClosestAngularBin(const double & theta) +{ + // TODO + // float min_dist = std::numeric_limits::max; + // unsigned int closest_idx = 0; + // float dist = 0.0; + // for (unsigned int i = 0; i != primitive_headings.size(); i++) { + // dist = fabs(theta - primitive_headings[i]); + // if (dist < min_dist) { + // min_dist = dist; + // closest_idx = i; + // } + // } + // return closest_idx; +} + +float LatticeMotionTable::getAngleFromBin(const unsigned int & bin_idx) +{ + //TODO + // return primitive_headings[bin_idx]; +} + NodeLattice::NodeLattice(const unsigned int index) : parent(nullptr), pose(0.0f, 0.0f, 0.0f), @@ -121,7 +145,7 @@ bool NodeLattice::isNodeValid( // TODO(steve) if primitive longer than 1.5 cells, then we need to split into 1 cell // increments and collision check across them if (collision_checker->inCollision( - this->pose.x, this->pose.y, this->pose.theta * motion_table.bin_size, traverse_unknown)) + this->pose.x, this->pose.y, this->pose.theta /*bin number*/, traverse_unknown)) { return false; } @@ -147,6 +171,22 @@ float NodeLattice::getHeuristicCost( return std::max(obstacle_heuristic, distance_heuristic); } +void NodeLattice::initMotionModel( + const MotionModel & motion_model, + unsigned int & size_x, + unsigned int & /*size_y*/, + unsigned int & /*num_angle_quantization*/, + SearchInfo & search_info) +{ + if (motion_model != MotionModel::STATE_LATTICE) { + throw std::runtime_error( + "Invalid motion model for Lattice node. Please select" + " STATE_LATTICE and provide a valid lattice file."); + } + + motion_table.initMotionModel(size_x, search_info); +} + float NodeLattice::getDistanceHeuristic( const Coordinates & node_coords, const Coordinates & goal_coords, @@ -181,8 +221,8 @@ float NodeLattice::getDistanceHeuristic( // to apply the distance heuristic. Since the lookup table is contains only the positive // X axis, we mirror the Y and theta values across the X axis to find the heuristic values. float motion_heuristic = 0.0; - const int floored_size = floor(NodeHybrid::size_lookup / 2.0); - const int ceiling_size = ceil(NodeHybrid::size_lookup / 2.0); + const int floored_size = floor(size_lookup / 2.0); + const int ceiling_size = ceil(size_lookup / 2.0); const float mirrored_relative_y = abs(node_coords_relative.y); if (abs(node_coords_relative.x) < floored_size && mirrored_relative_y < floored_size) { // Need to mirror angle if Y coordinate was mirrored @@ -198,35 +238,63 @@ float NodeLattice::getDistanceHeuristic( x_pos * ceiling_size * motion_table.num_angle_quantization + y_pos * motion_table.num_angle_quantization + theta_pos; - motion_heuristic = NodeHybrid::dist_heuristic_lookup_table[index]; + motion_heuristic = dist_heuristic_lookup_table[index]; } else if (obstacle_heuristic == 0.0) { static ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space); to[0] = goal_coords.x; to[1] = goal_coords.y; - to[2] = goal_coords.theta * motion_table.num_angle_quantization; + to[2] = motion_table.getAngleFromBin(goal_coords.theta); from[0] = node_coords.x; from[1] = node_coords.y; - from[2] = node_coords.theta * motion_table.num_angle_quantization; + from[2] = motion_table.getAngleFromBin(node_coords.theta); motion_heuristic = motion_table.state_space->distance(from(), to()); } return motion_heuristic; } -void NodeLattice::initMotionModel( +void NodeLattice::precomputeDistanceHeuristic( + const float & lookup_table_dim, const MotionModel & motion_model, - unsigned int & size_x, - unsigned int & /*size_y*/, - unsigned int & /*num_angle_quantization*/, - SearchInfo & search_info) + const unsigned int & dim_3_size, + const SearchInfo & search_info) { - if (motion_model != MotionModel::STATE_LATTICE) { - throw std::runtime_error( - "Invalid motion model for Lattice node. Please select" - " STATE_LATTICE and provide a valid lattice file."); + // Dubin or Reeds-Shepp shortest distances + if (!search_info.allow_reverse_expansion) { + motion_table.state_space = std::make_unique( + search_info.minimum_turning_radius); + } else { + motion_table.state_space = std::make_unique( + search_info.minimum_turning_radius); } - motion_table.initMotionModel(size_x, search_info); + ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space); + to[0] = 0.0; + to[1] = 0.0; + to[2] = 0.0; + size_lookup = lookup_table_dim; + float motion_heuristic = 0.0; + unsigned int index = 0; + int dim_3_size_int = static_cast(dim_3_size); + + // Create a lookup table of Dubin/Reeds-Shepp distances in a window around the goal + // to help drive the search towards admissible approaches. Deu to symmetries in the + // Heuristic space, we need to only store 2 of the 4 quadrants and simply mirror + // around the X axis any relative node lookup. This reduces memory overhead and increases + // the size of a window a platform can store in memory. + dist_heuristic_lookup_table.resize(size_lookup * ceil(size_lookup / 2.0) * dim_3_size_int); + for (float x = ceil(-size_lookup / 2.0); x <= floor(size_lookup / 2.0); x += 1.0) { + for (float y = 0.0; y <= floor(size_lookup / 2.0); y += 1.0) { + for (int heading = 0; heading != dim_3_size_int; heading++) { + from[0] = x; + from[1] = y; + from[2] = motion_table.getAngleFromBin(heading); + motion_heuristic = motion_table.state_space->distance(from(), to()); + dist_heuristic_lookup_table[index] = motion_heuristic; + index++; + } + } + } } void NodeLattice::getNeighbors( diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index d9ee491cb5..9a19746aae 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -58,7 +58,6 @@ void SmacPlannerLattice::configure( bool allow_unknown; int max_iterations; - int angle_quantizations; int lookup_table_size; SearchInfo search_info; @@ -109,10 +108,9 @@ void SmacPlannerLattice::configure( node, name + ".allow_reverse_expansion", rclcpp::ParameterValue(false)); node->get_parameter(name + ".allow_reverse_expansion", search_info.allow_reverse_expansion); - LatticeMetadata metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); - _angle_quantizations = metadata.first; - _angle_bin_size = 2.0 * M_PI / static_cast(_angle_quantizations); - float min_turning_radius = metadata.second; + _metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); + unsigned int angle_quantizations = _metadata.first; // TODO delete + float min_turning_radius = _metadata.second; MotionModel motion_model = MotionModel::STATE_LATTICE; @@ -128,7 +126,7 @@ void SmacPlannerLattice::configure( static_cast(_costmap->getResolution() * _downsampling_factor); // Initialize collision checker - _collision_checker = GridCollisionChecker(_costmap, _angle_quantizations); + _collision_checker = GridCollisionChecker(_costmap, angle_quantizations); //TODO give it a vector of angles from getLatticeMetadata() _collision_checker.setFootprint( costmap_ros->getRobotFootprint(), costmap_ros->getUseRadius(), @@ -141,7 +139,7 @@ void SmacPlannerLattice::configure( max_iterations, std::numeric_limits::max(), lookup_table_dim, - _angle_quantizations); + angle_quantizations); // TODO give this vector of angles size from getLatticeMetadata() // Initialize path smoother SmootherParams params; @@ -202,6 +200,28 @@ void SmacPlannerLattice::cleanup() _raw_plan_publisher.reset(); } +unsigned int getClosestAngularBin(const double & theta) +{ + // TODO + // float min_dist = std::numeric_limits::max; + // unsigned int closest_idx = 0; + // float dist = 0.0; + // for (unsigned int i = 0; i != _metadata.heading_angles.size(); i++) { + // dist = fabs(theta - _metadata.heading_angles[i]); + // if (dist < min_dist) { + // min_dist = dist; + // closest_idx = i; + // } + // } + // return closest_idx; +} + +float getAngleFromBin(const unsigned int & bin_idx) +{ + //TODO + // return _metadata.heading_angles[bin_idx]; +} + nav_msgs::msg::Path SmacPlannerLattice::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal) @@ -223,21 +243,11 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( // Set starting point, in A* bin search coordinates unsigned int mx, my; costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx, my); - double orientation_bin = tf2::getYaw(start.pose.orientation) / _angle_bin_size; - while (orientation_bin < 0.0) { - orientation_bin += static_cast(_angle_quantizations); - } - unsigned int orientation_bin_id = static_cast(floor(orientation_bin)); - _a_star->setStart(mx, my, orientation_bin_id); + _a_star->setStart(mx, my, getClosestAngularBin(tf2::getYaw(start.pose.orientation))); // Set goal point, in A* bin search coordinates costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my); - orientation_bin = tf2::getYaw(goal.pose.orientation) / _angle_bin_size; - while (orientation_bin < 0.0) { - orientation_bin += static_cast(_angle_quantizations); - } - orientation_bin_id = static_cast(floor(orientation_bin)); - _a_star->setGoal(mx, my, orientation_bin_id); + _a_star->setGoal(mx, my, getClosestAngularBin(tf2::getYaw(goal.pose.orientation))); // Setup message nav_msgs::msg::Path plan; @@ -280,7 +290,7 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( plan.poses.reserve(path.size()); for (int i = path.size() - 1; i >= 0; --i) { pose.pose = getWorldCoords(path[i].x, path[i].y, costmap); - pose.pose.orientation = getWorldOrientation(path[i].theta, _angle_bin_size); + pose.pose.orientation = getWorldOrientation(getAngleFromBin(path[i].theta)); plan.poses.push_back(pose); } From 092c1d9c2dff70be4cd51d0a2fc0a04938ad5067 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Mon, 11 Oct 2021 16:32:27 -0700 Subject: [PATCH 05/31] integrating @jwallice42 s work and enabling reverse expansions --- .../include/nav2_smac_planner/node_hybrid.hpp | 30 - .../nav2_smac_planner/node_lattice.hpp | 10 +- .../smac_planner_lattice.hpp | 13 - .../include/nav2_smac_planner/types.hpp | 60 + .../include/nav2_smac_planner/utils.hpp | 52 + nav2_smac_planner/package.xml | 1 + nav2_smac_planner/src/node_hybrid.cpp | 5 +- nav2_smac_planner/src/node_lattice.cpp | 158 +- .../src/smac_planner_lattice.cpp | 42 +- nav2_smac_planner/test/CMakeLists.txt | 12 + nav2_smac_planner/test/output.json | 4538 +++++++++++++++++ nav2_smac_planner/test/test_nodelattice.cpp | 118 + 12 files changed, 4916 insertions(+), 123 deletions(-) create mode 100644 nav2_smac_planner/test/output.json create mode 100644 nav2_smac_planner/test/test_nodelattice.cpp diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp index dab6d13339..b9efc48bbc 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp @@ -38,36 +38,6 @@ namespace nav2_smac_planner typedef std::vector LookupTable; typedef std::pair TrigValues; -// Need seperate pose struct for motion table operations - -/** - * @struct nav2_smac_planner::MotionPose - * @brief A struct for poses in motion primitives - */ -struct MotionPose -{ - /** - * @brief A constructor for nav2_smac_planner::MotionPose - */ - MotionPose() {} - - /** - * @brief A constructor for nav2_smac_planner::MotionPose - * @param x X pose - * @param y Y pose - * @param theta Angle of pose - */ - MotionPose(const float & x, const float & y, const float & theta) - : _x(x), _y(y), _theta(theta) - {} - - float _x; - float _y; - float _theta; -}; - -typedef std::vector MotionPoses; - // Must forward declare class NodeHybrid; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index 274744cd0e..b889e44143 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -25,6 +25,7 @@ #include #include #include +#include #include "ompl/base/StateSpace.h" @@ -32,6 +33,7 @@ #include "nav2_smac_planner/types.hpp" #include "nav2_smac_planner/collision_checker.hpp" #include "nav2_smac_planner/node_hybrid.hpp" +#include "nav2_smac_planner/utils.hpp" namespace nav2_smac_planner { @@ -40,8 +42,6 @@ namespace nav2_smac_planner class NodeLattice; class NodeHybrid; -typedef std::pair LatticeMetadata; - /** * @struct nav2_smac_planner::LatticeMotionTable * @brief A table of motion primitives and related functions @@ -69,7 +69,7 @@ struct LatticeMotionTable * @param node Ptr to NodeLattice * @return A set of motion poses */ - MotionPoses getProjections(const NodeLattice * node); + MotionPoses getMotionPrimitives(const NodeLattice * node); /** * @brief Get file metadata needed @@ -94,18 +94,18 @@ struct LatticeMotionTable */ float getAngleFromBin(const unsigned int & bin_idx); - MotionPoses projections; unsigned int size_x; unsigned int num_angle_quantization; - float min_turning_radius; float change_penalty; float non_straight_penalty; float cost_penalty; float reverse_penalty; bool allow_reverse_expansion; + std::vector> motion_primitives; ompl::base::StateSpacePtr state_space; std::vector trig_values; std::string current_lattice_filepath; + LatticeMetadata lattice_metadata; }; /** diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp index 4855ed72b0..908120eab2 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp @@ -87,19 +87,6 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner const geometry_msgs::msg::PoseStamped & goal) override; protected: - /** - * @brief Get the angular bin to use from a raw orientation - * @param theta Angle in radians - * @return bin index of closest angle to request - */ - unsigned int getClosestAngularBin(const double & theta); - - /** - * @brief Get the raw orientation from an angular bin - * @param bin_idx Index of the bin - * @return Raw orientation in radians - */ - float getAngleFromBin(const unsigned int & bin_idx); std::unique_ptr> _a_star; GridCollisionChecker _collision_checker; diff --git a/nav2_smac_planner/include/nav2_smac_planner/types.hpp b/nav2_smac_planner/include/nav2_smac_planner/types.hpp index c5b2e1d823..09c4436f2b 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/types.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/types.hpp @@ -88,6 +88,66 @@ struct SmootherParams double w_smooth_; }; +/** + * @struct nav2_smac_planner::MotionPose + * @brief A struct for poses in motion primitives + */ +struct MotionPose +{ + /** + * @brief A constructor for nav2_smac_planner::MotionPose + */ + MotionPose() {} + + /** + * @brief A constructor for nav2_smac_planner::MotionPose + * @param x X pose + * @param y Y pose + * @param theta Angle of pose + */ + MotionPose(const float & x, const float & y, const float & theta) + : _x(x), _y(y), _theta(theta) + {} + + float _x; + float _y; + float _theta; +}; + +typedef std::vector MotionPoses; + +/** + * @struct nav2_smac_planner::LatticeMetadata + * @brief A struct of all lattice metadata + */ +struct LatticeMetadata +{ + float min_turning_radius; + float primitive_resolution; + float grid_resolution; + float max_length; + unsigned int number_of_headings; + std::string output_file; + std::vector heading_angles; + unsigned int number_of_trajectories; +}; + +/** + * @struct nav2_smac_planner::MotionPrimitive + * @brief A struct of all motion primitive data + */ +struct MotionPrimitive +{ + unsigned int trajectory_id; + float start_angle; + float end_angle; + float turning_radius; + float trajectory_length; + float arc_length; + float straight_length; + MotionPoses poses; +}; + } // namespace nav2_smac_planner #endif // NAV2_SMAC_PLANNER__TYPES_HPP_ diff --git a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp index ebf2ea10c3..ab55befafd 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp @@ -118,6 +118,58 @@ inline double findCircumscribedCost(std::shared_ptreigen3_cmake_module eigen ompl + nlohmann_json ament_lint_common ament_lint_auto diff --git a/nav2_smac_planner/src/node_hybrid.cpp b/nav2_smac_planner/src/node_hybrid.cpp index 16cb0925c4..967398d6e8 100644 --- a/nav2_smac_planner/src/node_hybrid.cpp +++ b/nav2_smac_planner/src/node_hybrid.cpp @@ -520,10 +520,11 @@ float NodeHybrid::getDistanceHeuristic( const float dy = node_coords.y - goal_coords.y; double dtheta_bin = node_coords.theta - goal_coords.theta; + if (dtheta_bin < 0) { + dtheta_bin += motion_table.num_angle_quantization; + } if (dtheta_bin > motion_table.num_angle_quantization) { dtheta_bin -= motion_table.num_angle_quantization; - } else if (dtheta_bin < 0) { - dtheta_bin += motion_table.num_angle_quantization; } Coordinates node_coords_relative( diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index a985ed5197..6a09c3c413 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include "ompl/base/ScopedState.h" #include "ompl/base/spaces/DubinsStateSpace.h" @@ -62,54 +63,126 @@ void LatticeMotionTable::initMotionModel( current_lattice_filepath = search_info.lattice_filepath; allow_reverse_expansion = search_info.allow_reverse_expansion; - // TODO(Matt) read in file, precompute based on orientation bins for lookup at runtime - // file is `search_info.lattice_filepath`, to be read in from plugin and provided here. - - // TODO(Matt) create a state_space with the max turning rad primitive within the file - // (or another -- mid?) - // to use for analytic expansions and heuristic generation. Potentially make both an - // extreme and a passive one? - - // TODO(Matt) populate num_angle_quantization, size_x, min_turning_radius, trig_values, - // all of the member variables of LatticeMotionTable + // Get the metadata about this minimum control set + lattice_metadata = getLatticeMetadata(current_lattice_filepath); + std::ifstream latticeFile(current_lattice_filepath); + if(!latticeFile.is_open()) { + throw std::runtime_error("Could not open lattice file"); + } + nlohmann::json json; + latticeFile >> json; + num_angle_quantization = lattice_metadata.number_of_headings; + + if (!state_space) { + if (!allow_reverse_expansion) { + state_space = std::make_unique( + lattice_metadata.min_turning_radius); + } else { + state_space = std::make_unique( + lattice_metadata.min_turning_radius); + } + } - // TODO use allow_reverse_expansion to set state_space to dubins/reeds-shepp + // Populate the motion primitives at each heading angle + float prev_start_angle = 0.0; + std::vector primitives; + nlohmann::json json_primitives = json["primitives"]; + for(unsigned int i = 0; i < json_primitives.size(); ++i) { + MotionPrimitive new_primitive; + fromJsonToMotionPrimitive(json_primitives[i], new_primitive); + + if(prev_start_angle != new_primitive.start_angle) { + motion_primitives.push_back(primitives); + primitives.clear(); + prev_start_angle = new_primitive.start_angle; + } + primitives.push_back(new_primitive); + } + motion_primitives.push_back(primitives); + + // Populate useful precomputed values to be leveraged + trig_values.reserve(lattice_metadata.number_of_headings); + for(unsigned int i = 0; i < lattice_metadata.heading_angles.size(); ++i) { + trig_values.emplace_back( + cos(lattice_metadata.heading_angles[i]), + sin(lattice_metadata.heading_angles[i])); + } } -MotionPoses LatticeMotionTable::getProjections(const NodeLattice * node) +MotionPoses LatticeMotionTable::getMotionPrimitives(const NodeLattice * node) { - // TODO use allow_reverse_expansion to get forward or inverse pair as well - return MotionPoses(); // TODO(Matt) lookup at run time the primitives to use at node + // TODO get full, include primitive ID, somehow communicate more than just an end pose? + // we will likely want to know the motion primitive index (0-104) + //That the lattice node will store for the backtrace + + std::vector & prims_at_heading = motion_primitives[node->pose.theta]; + MotionPoses primitive_projection_list; + primitive_projection_list.reserve(prims_at_heading.size()); + + std::vector::const_iterator it; + for(it = prims_at_heading.begin(); it != prims_at_heading.end(); ++it) { + const MotionPose & end_pose = it->poses.back(); + primitive_projection_list.emplace_back( + node->pose.x + (end_pose._x / lattice_metadata.grid_resolution), + node->pose.y + (end_pose._y / lattice_metadata.grid_resolution), + it->end_angle /*this is the ending angular bin*/); + } + + if (allow_reverse_expansion) { + // Find heading bin of the reverse expansion + double reserve_heading = node->pose.theta - (num_angle_quantization / 2); + if (reserve_heading < 0) { + reserve_heading += num_angle_quantization; + } + if (reserve_heading > num_angle_quantization) { + reserve_heading -= num_angle_quantization; + } + prims_at_heading = motion_primitives[reserve_heading]; + std::vector::const_iterator it; + for(it = prims_at_heading.begin(); it != prims_at_heading.end(); ++it) { + const MotionPose & end_pose = it->poses.back(); + primitive_projection_list.emplace_back( + node->pose.x + (end_pose._x / lattice_metadata.grid_resolution), + node->pose.y + (end_pose._y / lattice_metadata.grid_resolution), + it->end_angle /*this is the ending angular bin*/); + } + } + + return primitive_projection_list; } LatticeMetadata LatticeMotionTable::getLatticeMetadata(const std::string & lattice_filepath) { - // TODO(Matt) from this file extract and return the number of angle bins and - // turning radius in global coordinates, respectively. - // world coordinates meaning meters, not cells - return {0 /*num bins*/, 0 /*turning rad*/}; + std::ifstream lattice_file(lattice_filepath); + if(!lattice_file.is_open()) { + throw std::runtime_error("Could not open lattice file!"); + } + + nlohmann::json j; + lattice_file >> j; + LatticeMetadata metadata; + fromJsonToMetaData(j["latticeMetadata"], metadata); + return metadata; } unsigned int LatticeMotionTable::getClosestAngularBin(const double & theta) { - // TODO - // float min_dist = std::numeric_limits::max; - // unsigned int closest_idx = 0; - // float dist = 0.0; - // for (unsigned int i = 0; i != primitive_headings.size(); i++) { - // dist = fabs(theta - primitive_headings[i]); - // if (dist < min_dist) { - // min_dist = dist; - // closest_idx = i; - // } - // } - // return closest_idx; + float min_dist = std::numeric_limits::max(); + unsigned int closest_idx = 0; + float dist = 0.0; + for (unsigned int i = 0; i != lattice_metadata.heading_angles.size(); i++) { + dist = fabs(theta - lattice_metadata.heading_angles[i]); + if (dist < min_dist) { + min_dist = dist; + closest_idx = i; + } + } + return closest_idx; } float LatticeMotionTable::getAngleFromBin(const unsigned int & bin_idx) { - //TODO - // return primitive_headings[bin_idx]; + return lattice_metadata.heading_angles[bin_idx]; } NodeLattice::NodeLattice(const unsigned int index) @@ -206,10 +279,11 @@ float NodeLattice::getDistanceHeuristic( const float dy = node_coords.y - goal_coords.y; double dtheta_bin = node_coords.theta - goal_coords.theta; + if (dtheta_bin < 0) { + dtheta_bin += motion_table.num_angle_quantization; + } if (dtheta_bin > motion_table.num_angle_quantization) { dtheta_bin -= motion_table.num_angle_quantization; - } else if (dtheta_bin < 0) { - dtheta_bin += motion_table.num_angle_quantization; } Coordinates node_coords_relative( @@ -306,13 +380,13 @@ void NodeLattice::getNeighbors( unsigned int index = 0; NodePtr neighbor = nullptr; Coordinates initial_node_coords; - const MotionPoses motion_projections = motion_table.getProjections(this); + const MotionPoses motion_primitives = motion_table.getMotionPrimitives(this); - for (unsigned int i = 0; i != motion_projections.size(); i++) { + for (unsigned int i = 0; i != motion_primitives.size(); i++) { index = NodeLattice::getIndex( - static_cast(motion_projections[i]._x), - static_cast(motion_projections[i]._y), - static_cast(motion_projections[i]._theta)); + static_cast(motion_primitives[i]._x), + static_cast(motion_primitives[i]._y), + static_cast(motion_primitives[i]._theta)); if (NeighborGetter(index, neighbor) && !neighbor->wasVisited()) { // For State Lattice, the poses are exact bin increments and the pose @@ -322,9 +396,9 @@ void NodeLattice::getNeighbors( // collision checking, and backtracing (even if not strictly necessary). neighbor->setPose( Coordinates( - motion_projections[i]._x, - motion_projections[i]._y, - motion_projections[i]._theta)); + motion_primitives[i]._x, + motion_primitives[i]._y, + motion_primitives[i]._theta)); if (neighbor->isNodeValid(traverse_unknown, collision_checker)) { neighbor->setMotionPrimitiveIndex(i); neighbors.push_back(neighbor); diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 9a19746aae..8bb8bbb40e 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -109,9 +109,6 @@ void SmacPlannerLattice::configure( node->get_parameter(name + ".allow_reverse_expansion", search_info.allow_reverse_expansion); _metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); - unsigned int angle_quantizations = _metadata.first; // TODO delete - float min_turning_radius = _metadata.second; - MotionModel motion_model = MotionModel::STATE_LATTICE; if (max_iterations <= 0) { @@ -126,7 +123,7 @@ void SmacPlannerLattice::configure( static_cast(_costmap->getResolution() * _downsampling_factor); // Initialize collision checker - _collision_checker = GridCollisionChecker(_costmap, angle_quantizations); //TODO give it a vector of angles from getLatticeMetadata() + _collision_checker = GridCollisionChecker(_costmap, _metadata.heading_angles); _collision_checker.setFootprint( costmap_ros->getRobotFootprint(), costmap_ros->getUseRadius(), @@ -139,13 +136,13 @@ void SmacPlannerLattice::configure( max_iterations, std::numeric_limits::max(), lookup_table_dim, - angle_quantizations); // TODO give this vector of angles size from getLatticeMetadata() + _metadata.number_of_headings); // Initialize path smoother SmootherParams params; params.get(node, name); _smoother = std::make_unique(params); - _smoother->initialize(min_turning_radius); + _smoother->initialize(_metadata.min_turning_radius); // Initialize costmap downsampler if (_downsample_costmap && _downsampling_factor > 1) { @@ -200,28 +197,6 @@ void SmacPlannerLattice::cleanup() _raw_plan_publisher.reset(); } -unsigned int getClosestAngularBin(const double & theta) -{ - // TODO - // float min_dist = std::numeric_limits::max; - // unsigned int closest_idx = 0; - // float dist = 0.0; - // for (unsigned int i = 0; i != _metadata.heading_angles.size(); i++) { - // dist = fabs(theta - _metadata.heading_angles[i]); - // if (dist < min_dist) { - // min_dist = dist; - // closest_idx = i; - // } - // } - // return closest_idx; -} - -float getAngleFromBin(const unsigned int & bin_idx) -{ - //TODO - // return _metadata.heading_angles[bin_idx]; -} - nav_msgs::msg::Path SmacPlannerLattice::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal) @@ -243,11 +218,15 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( // Set starting point, in A* bin search coordinates unsigned int mx, my; costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx, my); - _a_star->setStart(mx, my, getClosestAngularBin(tf2::getYaw(start.pose.orientation))); + _a_star->setStart( + mx, my, + NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(start.pose.orientation))); // Set goal point, in A* bin search coordinates costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my); - _a_star->setGoal(mx, my, getClosestAngularBin(tf2::getYaw(goal.pose.orientation))); + _a_star->setGoal( + mx, my, + NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(goal.pose.orientation))); // Setup message nav_msgs::msg::Path plan; @@ -290,7 +269,8 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( plan.poses.reserve(path.size()); for (int i = path.size() - 1; i >= 0; --i) { pose.pose = getWorldCoords(path[i].x, path[i].y, costmap); - pose.pose.orientation = getWorldOrientation(getAngleFromBin(path[i].theta)); + pose.pose.orientation = getWorldOrientation( + NodeLattice::motion_table.getAngleFromBin(path[i].theta)); plan.poses.push_back(pose); } diff --git a/nav2_smac_planner/test/CMakeLists.txt b/nav2_smac_planner/test/CMakeLists.txt index 1409c86deb..7b65220b93 100644 --- a/nav2_smac_planner/test/CMakeLists.txt +++ b/nav2_smac_planner/test/CMakeLists.txt @@ -86,3 +86,15 @@ target_link_libraries(test_smac_2d ${library_name}_2d ) +#Test Lattice node +ament_add_gtest(test_lattice_node + test_nodelattice.cpp) + +ament_target_dependencies(test_lattice_node + ${dependencies} +) + +target_link_libraries(test_lattice_node + ${library_name} ) + +install(FILES output.json DESTINATION share/${PROJECT_NAME}) diff --git a/nav2_smac_planner/test/output.json b/nav2_smac_planner/test/output.json new file mode 100644 index 0000000000..bcc46f6c40 --- /dev/null +++ b/nav2_smac_planner/test/output.json @@ -0,0 +1,4538 @@ +{ + "version": 1.0, + "dateGenerated": "2021-06-08", + "latticeMetadata": { + "turningRadius": 0.4, + "stepDistance": 0.005, + "gridSeparation": 0.05, + "maxLength": 1, + "numberOfHeadings": 16, + "outputFile": "output.json", + "headingAngles": [ + -180.0, + -153.43494882292202, + -135.0, + -116.56505117707799, + -90.0, + -63.43494882292201, + -45.0, + -26.56505117707799, + 0.0, + 26.56505117707799, + 45.0, + 63.43494882292201, + 90.0, + 116.56505117707799, + 135.0, + 153.43494882292202, + 180.0 + ], + "numberOfTrajectories": 104 + }, + "primitives": [ + { + "trajectoryId": 0, + "startAngle": 0.0, + "endAngle": 0.0, + "radius": 0, + "trajectoryLength": 0.2, + "arcLength": 0.0, + "straightLength": 0.2, + "poses": [ + [ + 0.0, + 0.0, + 0.0 + ], + [ + 0.06667, + 0.0, + 0.0 + ], + [ + 0.13333, + 0.0, + 0.0 + ] + ] + }, + { + "trajectoryId": 1, + "startAngle": 0.0, + "endAngle": 26.56505117707799, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + 0.0, + 0.0, + 0.07728785079152484 + ], + [ + 0.06521, + 0.00505, + 0.23188739606064668 + ], + [ + 0.12886, + 0.02008, + 0.38629880480400086 + ] + ] + }, + { + "trajectoryId": 2, + "startAngle": -0.0, + "endAngle": -26.56505117707799, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + 0.0, + -0.0, + -0.07728785079152484 + ], + [ + 0.06521, + -0.00505, + -0.23188739606064668 + ], + [ + 0.12886, + -0.02008, + -0.38629880480400086 + ] + ] + }, + { + "trajectoryId": 3, + "startAngle": 0.0, + "endAngle": 26.56505117707799, + "radius": 0.8472, + "trajectoryLength": 0.41640225434548295, + "arcLength": 0.39280225434548294, + "straightLength": 0.023599999999999982, + "poses": [ + [ + 0.0, + 0.0, + 0.03316065952958909 + ], + [ + 0.05607, + 0.00186, + 0.0992607498429092 + ], + [ + 0.1119, + 0.00742, + 0.1656174868971147 + ], + [ + 0.16724, + 0.01667, + 0.2318357474858811 + ], + [ + 0.22184, + 0.02956, + 0.2981320120235546 + ], + [ + 0.27547, + 0.04604, + 0.36432002602701186 + ], + [ + 0.32789, + 0.06603, + 0.43040362056026316 + ] + ] + }, + { + "trajectoryId": 4, + "startAngle": -0.0, + "endAngle": -26.56505117707799, + "radius": 0.8472, + "trajectoryLength": 0.41640225434548295, + "arcLength": 0.39280225434548294, + "straightLength": 0.023599999999999982, + "poses": [ + [ + 0.0, + -0.0, + -0.03316065952958909 + ], + [ + 0.05607, + -0.00186, + -0.0992607498429092 + ], + [ + 0.1119, + -0.00742, + -0.1656174868971147 + ], + [ + 0.16724, + -0.01667, + -0.2318357474858811 + ], + [ + 0.22184, + -0.02956, + -0.2981320120235546 + ], + [ + 0.27547, + -0.04604, + -0.36432002602701186 + ], + [ + 0.32789, + -0.06603, + -0.43040362056026316 + ] + ] + }, + { + "trajectoryId": 5, + "startAngle": 0.0, + "endAngle": 90.0, + "radius": 0.5, + "trajectoryLength": 0.8353981633974483, + "arcLength": 0.7853981633974483, + "straightLength": 0.050000000000000044, + "poses": [ + [ + 0.0, + 0.0, + 0.0 + ], + [ + 0.05, + 0.0, + 0.052382193864968965 + ], + [ + 0.10226, + 0.00274, + 0.1571083971448808 + ], + [ + 0.15396, + 0.01093, + 0.26171020631366104 + ], + [ + 0.20451, + 0.02447, + 0.36659768638821083 + ], + [ + 0.25337, + 0.04323, + 0.4712529998754368 + ], + [ + 0.3, + 0.06699, + 0.5759185996183533 + ], + [ + 0.34389, + 0.09549, + 0.6806484997078908 + ], + [ + 0.38457, + 0.12843, + 0.7853981633974487 + ], + [ + 0.42157, + 0.16543, + 0.8901478270870046 + ], + [ + 0.45451, + 0.20611, + 0.9948777271765442 + ], + [ + 0.48301, + 0.25, + 1.0995433269194588 + ], + [ + 0.50677, + 0.29663, + 1.204198640406686 + ], + [ + 0.52553, + 0.34549, + 1.3090861204812356 + ], + [ + 0.53907, + 0.39604, + 1.4136879296500173 + ], + [ + 0.54726, + 0.44774, + 1.518414132929926 + ] + ] + }, + { + "trajectoryId": 6, + "startAngle": -0.0, + "endAngle": -90.0, + "radius": 0.5, + "trajectoryLength": 0.8353981633974483, + "arcLength": 0.7853981633974483, + "straightLength": 0.050000000000000044, + "poses": [ + [ + 0.0, + -0.0, + 0.0 + ], + [ + 0.05, + -0.0, + -0.052382193864968965 + ], + [ + 0.10226, + -0.00274, + -0.1571083971448808 + ], + [ + 0.15396, + -0.01093, + -0.26171020631366104 + ], + [ + 0.20451, + -0.02447, + -0.36659768638821083 + ], + [ + 0.25337, + -0.04323, + -0.4712529998754368 + ], + [ + 0.3, + -0.06699, + -0.5759185996183533 + ], + [ + 0.34389, + -0.09549, + -0.6806484997078908 + ], + [ + 0.38457, + -0.12843, + -0.7853981633974487 + ], + [ + 0.42157, + -0.16543, + -0.8901478270870046 + ], + [ + 0.45451, + -0.20611, + -0.9948777271765442 + ], + [ + 0.48301, + -0.25, + -1.0995433269194588 + ], + [ + 0.50677, + -0.29663, + -1.204198640406686 + ], + [ + 0.52553, + -0.34549, + -1.3090861204812356 + ], + [ + 0.53907, + -0.39604, + -1.4136879296500173 + ], + [ + 0.54726, + -0.44774, + -1.518414132929926 + ] + ] + }, + { + "trajectoryId": 7, + "startAngle": 180.0, + "endAngle": 180.0, + "radius": 0, + "trajectoryLength": 0.2, + "arcLength": 0.0, + "straightLength": 0.2, + "poses": [ + [ + -0.0, + 0.0, + 3.141592653589793 + ], + [ + -0.06667, + 0.0, + 3.141592653589793 + ], + [ + -0.13333, + 0.0, + 3.141592653589793 + ] + ] + }, + { + "trajectoryId": 8, + "startAngle": 180.0, + "endAngle": 153.43494882292202, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + -0.0, + 0.0, + 3.0643048027982682 + ], + [ + -0.06521, + 0.00505, + 2.9097052575291467 + ], + [ + -0.12886, + 0.02008, + 2.7552938487857923 + ] + ] + }, + { + "trajectoryId": 9, + "startAngle": 180.0, + "endAngle": 153.43494882292202, + "radius": 0.8472, + "trajectoryLength": 0.41640225434548295, + "arcLength": 0.39280225434548294, + "straightLength": 0.023599999999999982, + "poses": [ + [ + -0.0, + 0.0, + 3.1084319940602043 + ], + [ + -0.05607, + 0.00186, + 3.042331903746884 + ], + [ + -0.1119, + 0.00742, + 2.9759751666926784 + ], + [ + -0.16724, + 0.01667, + 2.909756906103912 + ], + [ + -0.22184, + 0.02956, + 2.8434606415662387 + ], + [ + -0.27547, + 0.04604, + 2.7772726275627813 + ], + [ + -0.32789, + 0.06603, + 2.71118903302953 + ] + ] + }, + { + "trajectoryId": 10, + "startAngle": 180.0, + "endAngle": 90.0, + "radius": 0.5, + "trajectoryLength": 0.8353981633974483, + "arcLength": 0.7853981633974483, + "straightLength": 0.050000000000000044, + "poses": [ + [ + -0.0, + 0.0, + 3.141592653589793 + ], + [ + -0.05, + 0.0, + 3.0892104597248244 + ], + [ + -0.10226, + 0.00274, + 2.9844842564449126 + ], + [ + -0.15396, + 0.01093, + 2.8798824472761324 + ], + [ + -0.20451, + 0.02447, + 2.7749949672015823 + ], + [ + -0.25337, + 0.04323, + 2.6703396537143567 + ], + [ + -0.3, + 0.06699, + 2.5656740539714398 + ], + [ + -0.34389, + 0.09549, + 2.4609441538819024 + ], + [ + -0.38457, + 0.12843, + 2.3561944901923444 + ], + [ + -0.42157, + 0.16543, + 2.2514448265027887 + ], + [ + -0.45451, + 0.20611, + 2.146714926413249 + ], + [ + -0.48301, + 0.25, + 2.0420493266703343 + ], + [ + -0.50677, + 0.29663, + 1.9373940131831073 + ], + [ + -0.52553, + 0.34549, + 1.8325065331085577 + ], + [ + -0.53907, + 0.39604, + 1.7279047239397758 + ], + [ + -0.54726, + 0.44774, + 1.623178520659867 + ] + ] + }, + { + "trajectoryId": 11, + "startAngle": -180.0, + "endAngle": -153.43494882292202, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + -0.0, + -0.0, + -3.0643048027982682 + ], + [ + -0.06521, + -0.00505, + -2.9097052575291467 + ], + [ + -0.12886, + -0.02008, + -2.7552938487857923 + ] + ] + }, + { + "trajectoryId": 12, + "startAngle": -180.0, + "endAngle": -153.43494882292202, + "radius": 0.8472, + "trajectoryLength": 0.41640225434548295, + "arcLength": 0.39280225434548294, + "straightLength": 0.023599999999999982, + "poses": [ + [ + -0.0, + -0.0, + -3.1084319940602043 + ], + [ + -0.05607, + -0.00186, + -3.042331903746884 + ], + [ + -0.1119, + -0.00742, + -2.9759751666926784 + ], + [ + -0.16724, + -0.01667, + -2.909756906103912 + ], + [ + -0.22184, + -0.02956, + -2.8434606415662387 + ], + [ + -0.27547, + -0.04604, + -2.7772726275627813 + ], + [ + -0.32789, + -0.06603, + -2.71118903302953 + ] + ] + }, + { + "trajectoryId": 13, + "startAngle": -180.0, + "endAngle": -90.0, + "radius": 0.5, + "trajectoryLength": 0.8353981633974483, + "arcLength": 0.7853981633974483, + "straightLength": 0.050000000000000044, + "poses": [ + [ + -0.0, + -0.0, + 3.141592653589793 + ], + [ + -0.05, + -0.0, + -3.0892104597248244 + ], + [ + -0.10226, + -0.00274, + -2.9844842564449126 + ], + [ + -0.15396, + -0.01093, + -2.8798824472761324 + ], + [ + -0.20451, + -0.02447, + -2.7749949672015823 + ], + [ + -0.25337, + -0.04323, + -2.6703396537143567 + ], + [ + -0.3, + -0.06699, + -2.5656740539714398 + ], + [ + -0.34389, + -0.09549, + -2.4609441538819024 + ], + [ + -0.38457, + -0.12843, + -2.3561944901923444 + ], + [ + -0.42157, + -0.16543, + -2.2514448265027887 + ], + [ + -0.45451, + -0.20611, + -2.146714926413249 + ], + [ + -0.48301, + -0.25, + -2.0420493266703343 + ], + [ + -0.50677, + -0.29663, + -1.9373940131831073 + ], + [ + -0.52553, + -0.34549, + -1.8325065331085577 + ], + [ + -0.53907, + -0.39604, + -1.7279047239397758 + ], + [ + -0.54726, + -0.44774, + -1.623178520659867 + ] + ] + }, + { + "trajectoryId": 14, + "startAngle": 26.56505117707799, + "endAngle": 0.0, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + 0.01056, + 0.00528, + 0.3862988048040008 + ], + [ + 0.07114, + 0.02992, + 0.23188739606064662 + ], + [ + 0.13479, + 0.04495, + 0.07728785079152492 + ] + ] + }, + { + "trajectoryId": 15, + "startAngle": 26.56505117707799, + "endAngle": 26.56505117707799, + "radius": 0, + "trajectoryLength": 0.223606797749979, + "arcLength": 0.0, + "straightLength": 0.223606797749979, + "poses": [ + [ + 0.0, + 0.0, + 0.46358761020085415 + ], + [ + 0.06667, + 0.03333, + 0.4637676138004219 + ], + [ + 0.13333, + 0.06667, + 0.4635876102008542 + ] + ] + }, + { + "trajectoryId": 16, + "startAngle": 26.56505117707799, + "endAngle": 45.0, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + 3e-05, + -6e-05, + 0.5171981083811619 + ], + [ + 0.06423, + 0.03646, + 0.6245460333019313 + ], + [ + 0.12415, + 0.07965, + 0.7317583920706332 + ], + [ + 0.1791, + 0.129, + 0.0 + ] + ] + }, + { + "trajectoryId": 17, + "startAngle": 26.56505117707799, + "endAngle": 63.43494882292201, + "radius": 0.4472, + "trajectoryLength": 0.28777369585235674, + "arcLength": 0.28777369585235674, + "straightLength": 0, + "poses": [ + [ + -1e-05, + 1e-05, + 0.5279868542628576 + ], + [ + 0.04968, + 0.02899, + 0.6566815787447414 + ], + [ + 0.09523, + 0.0641, + 0.7853981633974483 + ], + [ + 0.1359, + 0.10477, + 0.9141147480501554 + ], + [ + 0.17101, + 0.15032, + 1.0428094725320387 + ] + ] + }, + { + "trajectoryId": 18, + "startAngle": 26.56505117707799, + "endAngle": 0.0, + "radius": 0.6354, + "trajectoryLength": 0.3682016907591122, + "arcLength": 0.2946016907591122, + "straightLength": 0.0736, + "poses": [ + [ + 0.0, + 0.0, + 0.4636476090008061 + ], + [ + 0.06584, + 0.03292, + 0.41724179149883744 + ], + [ + 0.11969, + 0.05679, + 0.324542643361065 + ], + [ + 0.17551, + 0.07557, + 0.23180039718484172 + ], + [ + 0.23283, + 0.0891, + 0.13915983516289937 + ], + [ + 0.29116, + 0.09727, + 0.046363759097421874 + ] + ] + }, + { + "trajectoryId": 19, + "startAngle": 153.43494882292202, + "endAngle": 180.0, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + -0.01056, + 0.00528, + 2.7552938487857923 + ], + [ + -0.07114, + 0.02992, + 2.9097052575291467 + ], + [ + -0.13479, + 0.04495, + 3.0643048027982682 + ] + ] + }, + { + "trajectoryId": 20, + "startAngle": 153.43494882292202, + "endAngle": 153.43494882292202, + "radius": 0, + "trajectoryLength": 0.223606797749979, + "arcLength": 0.0, + "straightLength": 0.223606797749979, + "poses": [ + [ + -0.0, + 0.0, + 2.6780050433889393 + ], + [ + -0.06667, + 0.03333, + 2.6778250397893713 + ], + [ + -0.13333, + 0.06667, + 2.678005043388939 + ] + ] + }, + { + "trajectoryId": 21, + "startAngle": 153.43494882292202, + "endAngle": 135.0, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + -3e-05, + -6e-05, + 2.6243945452086312 + ], + [ + -0.06423, + 0.03646, + 2.517046620287862 + ], + [ + -0.12415, + 0.07965, + 2.40983426151916 + ], + [ + -0.1791, + 0.129, + 0.0 + ] + ] + }, + { + "trajectoryId": 22, + "startAngle": 153.43494882292202, + "endAngle": 116.56505117707799, + "radius": 0.4472, + "trajectoryLength": 0.28777369585235674, + "arcLength": 0.28777369585235674, + "straightLength": 0, + "poses": [ + [ + 1e-05, + 1e-05, + 2.6136057993269355 + ], + [ + -0.04968, + 0.02899, + 2.484911074845052 + ], + [ + -0.09523, + 0.0641, + 2.356194490192345 + ], + [ + -0.1359, + 0.10477, + 2.227477905539638 + ], + [ + -0.17101, + 0.15032, + 2.0987831810577546 + ] + ] + }, + { + "trajectoryId": 23, + "startAngle": 153.43494882292202, + "endAngle": 180.0, + "radius": 0.6354, + "trajectoryLength": 0.3682016907591122, + "arcLength": 0.2946016907591122, + "straightLength": 0.0736, + "poses": [ + [ + -0.0, + 0.0, + 2.677945044588987 + ], + [ + -0.06584, + 0.03292, + 2.724350862090956 + ], + [ + -0.11969, + 0.05679, + 2.817050010228728 + ], + [ + -0.17551, + 0.07557, + 2.9097922564049514 + ], + [ + -0.23283, + 0.0891, + 3.002432818426894 + ], + [ + -0.29116, + 0.09727, + 3.0952288944923714 + ] + ] + }, + { + "trajectoryId": 24, + "startAngle": -153.43494882292202, + "endAngle": -180.0, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + -0.01056, + -0.00528, + -2.7552938487857923 + ], + [ + -0.07114, + -0.02992, + -2.9097052575291467 + ], + [ + -0.13479, + -0.04495, + -3.0643048027982682 + ] + ] + }, + { + "trajectoryId": 25, + "startAngle": -153.43494882292202, + "endAngle": -153.43494882292202, + "radius": 0, + "trajectoryLength": 0.223606797749979, + "arcLength": 0.0, + "straightLength": 0.223606797749979, + "poses": [ + [ + -0.0, + -0.0, + -2.6780050433889393 + ], + [ + -0.06667, + -0.03333, + -2.6778250397893713 + ], + [ + -0.13333, + -0.06667, + -2.678005043388939 + ] + ] + }, + { + "trajectoryId": 26, + "startAngle": -153.43494882292202, + "endAngle": -135.0, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + -3e-05, + 6e-05, + -2.6243945452086312 + ], + [ + -0.06423, + -0.03646, + -2.517046620287862 + ], + [ + -0.12415, + -0.07965, + -2.40983426151916 + ], + [ + -0.1791, + -0.129, + 0.0 + ] + ] + }, + { + "trajectoryId": 27, + "startAngle": -153.43494882292202, + "endAngle": -116.56505117707799, + "radius": 0.4472, + "trajectoryLength": 0.28777369585235674, + "arcLength": 0.28777369585235674, + "straightLength": 0, + "poses": [ + [ + 1e-05, + -1e-05, + -2.6136057993269355 + ], + [ + -0.04968, + -0.02899, + -2.484911074845052 + ], + [ + -0.09523, + -0.0641, + -2.356194490192345 + ], + [ + -0.1359, + -0.10477, + -2.227477905539638 + ], + [ + -0.17101, + -0.15032, + -2.0987831810577546 + ] + ] + }, + { + "trajectoryId": 28, + "startAngle": -153.43494882292202, + "endAngle": -180.0, + "radius": 0.6354, + "trajectoryLength": 0.3682016907591122, + "arcLength": 0.2946016907591122, + "straightLength": 0.0736, + "poses": [ + [ + -0.0, + -0.0, + -2.677945044588987 + ], + [ + -0.06584, + -0.03292, + -2.724350862090956 + ], + [ + -0.11969, + -0.05679, + -2.817050010228728 + ], + [ + -0.17551, + -0.07557, + -2.9097922564049514 + ], + [ + -0.23283, + -0.0891, + -3.002432818426894 + ], + [ + -0.29116, + -0.09727, + -3.0952288944923714 + ] + ] + }, + { + "trajectoryId": 29, + "startAngle": -26.56505117707799, + "endAngle": -0.0, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + 0.01056, + -0.00528, + -0.3862988048040008 + ], + [ + 0.07114, + -0.02992, + -0.23188739606064662 + ], + [ + 0.13479, + -0.04495, + -0.07728785079152492 + ] + ] + }, + { + "trajectoryId": 30, + "startAngle": -26.56505117707799, + "endAngle": -26.56505117707799, + "radius": 0, + "trajectoryLength": 0.223606797749979, + "arcLength": 0.0, + "straightLength": 0.223606797749979, + "poses": [ + [ + 0.0, + -0.0, + -0.46358761020085415 + ], + [ + 0.06667, + -0.03333, + -0.4637676138004219 + ], + [ + 0.13333, + -0.06667, + -0.4635876102008542 + ] + ] + }, + { + "trajectoryId": 31, + "startAngle": -26.56505117707799, + "endAngle": -45.0, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + 3e-05, + 6e-05, + -0.5171981083811619 + ], + [ + 0.06423, + -0.03646, + -0.6245460333019313 + ], + [ + 0.12415, + -0.07965, + -0.7317583920706332 + ], + [ + 0.1791, + -0.129, + 0.0 + ] + ] + }, + { + "trajectoryId": 32, + "startAngle": -26.56505117707799, + "endAngle": -63.43494882292201, + "radius": 0.4472, + "trajectoryLength": 0.28777369585235674, + "arcLength": 0.28777369585235674, + "straightLength": 0, + "poses": [ + [ + -1e-05, + -1e-05, + -0.5279868542628576 + ], + [ + 0.04968, + -0.02899, + -0.6566815787447414 + ], + [ + 0.09523, + -0.0641, + -0.7853981633974483 + ], + [ + 0.1359, + -0.10477, + -0.9141147480501554 + ], + [ + 0.17101, + -0.15032, + -1.0428094725320387 + ] + ] + }, + { + "trajectoryId": 33, + "startAngle": -26.56505117707799, + "endAngle": -0.0, + "radius": 0.6354, + "trajectoryLength": 0.3682016907591122, + "arcLength": 0.2946016907591122, + "straightLength": 0.0736, + "poses": [ + [ + 0.0, + -0.0, + -0.4636476090008061 + ], + [ + 0.06584, + -0.03292, + -0.41724179149883744 + ], + [ + 0.11969, + -0.05679, + -0.324542643361065 + ], + [ + 0.17551, + -0.07557, + -0.23180039718484172 + ], + [ + 0.23283, + -0.0891, + -0.13915983516289937 + ], + [ + 0.29116, + -0.09727, + -0.046363759097421874 + ] + ] + }, + { + "trajectoryId": 34, + "startAngle": 45.0, + "endAngle": 26.56505117707799, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + 0.0, + 0.0, + 0.7877847937108879 + ], + [ + 0.0209, + 0.021, + 0.7317583920706331 + ], + [ + 0.07585, + 0.07035, + 0.6245460333019313 + ], + [ + 0.13577, + 0.11354, + 0.5171981083811618 + ] + ] + }, + { + "trajectoryId": 35, + "startAngle": 45.0, + "endAngle": 63.43494882292201, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + 0.0, + 0.0, + 0.7830115330840086 + ], + [ + 0.021, + 0.0209, + 0.8390379347242635 + ], + [ + 0.07035, + 0.07585, + 0.9462502934929653 + ], + [ + 0.11354, + 0.13577, + 1.053598218413735 + ] + ] + }, + { + "trajectoryId": 36, + "startAngle": 45.0, + "endAngle": 45.0, + "radius": 0, + "trajectoryLength": 0.28284271247461906, + "arcLength": 0.0, + "straightLength": 0.28284271247461906, + "poses": [ + [ + 0.0, + 0.0, + 0.7853981633974483 + ], + [ + 0.04, + 0.04, + 0.7853981633974483 + ], + [ + 0.08, + 0.08, + 0.7853981633974483 + ], + [ + 0.12, + 0.12, + 0.7853981633974483 + ], + [ + 0.16, + 0.16, + 0.7853981633974483 + ] + ] + }, + { + "trajectoryId": 37, + "startAngle": 45.0, + "endAngle": 0.0, + "radius": 0.5121, + "trajectoryLength": 0.4401023994758333, + "arcLength": 0.4022023994758333, + "straightLength": 0.03789999999999999, + "poses": [ + [ + -1e-05, + 1e-05, + 0.7293464437590259 + ], + [ + 0.04281, + 0.03828, + 0.6170310690645247 + ], + [ + 0.08965, + 0.07151, + 0.5049335662957414 + ], + [ + 0.13991, + 0.09929, + 0.3926342471652681 + ], + [ + 0.19296, + 0.12126, + 0.28049992809694807 + ], + [ + 0.24815, + 0.13716, + 0.16832663281779695 + ], + [ + 0.30476, + 0.14678, + 0.05609734227112698 + ], + [ + 0.3621, + 0.15, + 0.0 + ] + ] + }, + { + "trajectoryId": 38, + "startAngle": 45.0, + "endAngle": 90.0, + "radius": 0.5121, + "trajectoryLength": 0.4401023994758333, + "arcLength": 0.4022023994758333, + "straightLength": 0.03789999999999999, + "poses": [ + [ + 1e-05, + -1e-05, + 0.8414498830358706 + ], + [ + 0.03828, + 0.04281, + 0.953765257730372 + ], + [ + 0.07151, + 0.08965, + 1.0658627604991553 + ], + [ + 0.09929, + 0.13991, + 1.1781620796296284 + ], + [ + 0.12126, + 0.19296, + 1.2902963986979485 + ], + [ + 0.13716, + 0.24815, + 1.4024696939770998 + ], + [ + 0.14678, + 0.30476, + 1.5146989845237697 + ], + [ + 0.15, + 0.3621, + 0.0 + ] + ] + }, + { + "trajectoryId": 39, + "startAngle": 45.0, + "endAngle": 0.0, + "radius": 0.4828, + "trajectoryLength": 0.5327902332882881, + "arcLength": 0.37919023328828805, + "straightLength": 0.15360000000000001, + "poses": [ + [ + 0.0, + 0.0, + 0.7853981633974483 + ], + [ + 0.0543, + 0.0543, + 0.7852140013369153 + ], + [ + 0.10861, + 0.10859, + 0.0 + ], + [ + 0.10861, + 0.10859, + 0.7293418448380035 + ], + [ + 0.14898, + 0.14467, + 0.6171573764473927 + ], + [ + 0.19313, + 0.176, + 0.5048741332179076 + ], + [ + 0.24052, + 0.20219, + 0.3927167875987952 + ], + [ + 0.29054, + 0.22291, + 0.28050671293185836 + ], + [ + 0.34257, + 0.2379, + 0.16815522812227288 + ], + [ + 0.39594, + 0.24696, + 0.05617465151812344 + ] + ] + }, + { + "trajectoryId": 40, + "startAngle": 45.0, + "endAngle": 90.0, + "radius": 0.4828, + "trajectoryLength": 0.5327902332882881, + "arcLength": 0.37919023328828805, + "straightLength": 0.15360000000000001, + "poses": [ + [ + 0.0, + 0.0, + 0.7853981633974483 + ], + [ + 0.0543, + 0.0543, + 0.7855823254579813 + ], + [ + 0.10859, + 0.10861, + 0.0 + ], + [ + 0.10859, + 0.10861, + 0.8414544819568931 + ], + [ + 0.14467, + 0.14898, + 0.953638950347504 + ], + [ + 0.176, + 0.19313, + 1.065922193576989 + ], + [ + 0.20219, + 0.24052, + 1.1780795391961014 + ], + [ + 0.22291, + 0.29054, + 1.2902896138630382 + ], + [ + 0.2379, + 0.34257, + 1.4026410986726237 + ], + [ + 0.24696, + 0.39594, + 1.5146216752767732 + ] + ] + }, + { + "trajectoryId": 41, + "startAngle": 45.0, + "endAngle": -26.56505117707799, + "radius": 0.4251, + "trajectoryLength": 0.5972693578464978, + "arcLength": 0.5309693578464979, + "straightLength": 0.06629999999999997, + "poses": [ + [ + 1e-05, + -1e-05, + 0.7229959773998935 + ], + [ + 0.0398, + 0.0351, + 0.5979871115198812 + ], + [ + 0.08365, + 0.06497, + 0.47317193327021895 + ], + [ + 0.13088, + 0.08915, + 0.3482719052224635 + ], + [ + 0.18076, + 0.10726, + 0.22326778928315447 + ], + [ + 0.23251, + 0.11901, + 0.09854341385276191 + ], + [ + 0.28531, + 0.12423, + -0.026572443352433615 + ], + [ + 0.33836, + 0.12282, + -0.15135965367860432 + ], + [ + 0.39081, + 0.11482, + -0.2763841013056198 + ], + [ + 0.44186, + 0.10034, + -0.4011551973058339 + ], + [ + 0.49071, + 0.07962, + 0.0 + ] + ] + }, + { + "trajectoryId": 42, + "startAngle": 45.0, + "endAngle": 116.56505117707799, + "radius": 0.4251, + "trajectoryLength": 0.5972693578464978, + "arcLength": 0.5309693578464979, + "straightLength": 0.06629999999999997, + "poses": [ + [ + -1e-05, + 1e-05, + 0.847800349395003 + ], + [ + 0.0351, + 0.0398, + 0.9728092152750155 + ], + [ + 0.06497, + 0.08365, + 1.0976243935246777 + ], + [ + 0.08915, + 0.13088, + 1.2225244215724331 + ], + [ + 0.10726, + 0.18076, + 1.347528537511742 + ], + [ + 0.11901, + 0.23251, + 1.4722529129421347 + ], + [ + 0.12423, + 0.28531, + 1.5973687701473303 + ], + [ + 0.12282, + 0.33836, + 1.722155980473501 + ], + [ + 0.11482, + 0.39081, + 1.8471804281005164 + ], + [ + 0.10034, + 0.44186, + 1.9719515241007306 + ], + [ + 0.07962, + 0.49071, + 0.0 + ] + ] + }, + { + "trajectoryId": 43, + "startAngle": 135.0, + "endAngle": 153.43494882292202, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + -0.0, + 0.0, + 2.353807859878905 + ], + [ + -0.0209, + 0.021, + 2.40983426151916 + ], + [ + -0.07585, + 0.07035, + 2.517046620287862 + ], + [ + -0.13577, + 0.11354, + 2.6243945452086317 + ] + ] + }, + { + "trajectoryId": 44, + "startAngle": 135.0, + "endAngle": 116.56505117707799, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + -0.0, + 0.0, + 2.3585811205057845 + ], + [ + -0.021, + 0.0209, + 2.30255471886553 + ], + [ + -0.07035, + 0.07585, + 2.195342360096828 + ], + [ + -0.11354, + 0.13577, + 2.0879944351760584 + ] + ] + }, + { + "trajectoryId": 45, + "startAngle": 135.0, + "endAngle": 135.0, + "radius": 0, + "trajectoryLength": 0.28284271247461906, + "arcLength": 0.0, + "straightLength": 0.28284271247461906, + "poses": [ + [ + -0.0, + 0.0, + 2.356194490192345 + ], + [ + -0.04, + 0.04, + 2.356194490192345 + ], + [ + -0.08, + 0.08, + 2.356194490192345 + ], + [ + -0.12, + 0.12, + 2.356194490192345 + ], + [ + -0.16, + 0.16, + 2.356194490192345 + ] + ] + }, + { + "trajectoryId": 46, + "startAngle": 135.0, + "endAngle": 180.0, + "radius": 0.5121, + "trajectoryLength": 0.4401023994758333, + "arcLength": 0.4022023994758333, + "straightLength": 0.03789999999999999, + "poses": [ + [ + 1e-05, + 1e-05, + 2.412246209830767 + ], + [ + -0.04281, + 0.03828, + 2.5245615845252685 + ], + [ + -0.08965, + 0.07151, + 2.636659087294052 + ], + [ + -0.13991, + 0.09929, + 2.748958406424525 + ], + [ + -0.19296, + 0.12126, + 2.861092725492845 + ], + [ + -0.24815, + 0.13716, + 2.9732660207719963 + ], + [ + -0.30476, + 0.14678, + 3.0854953113186663 + ], + [ + -0.3621, + 0.15, + 0.0 + ] + ] + }, + { + "trajectoryId": 47, + "startAngle": 135.0, + "endAngle": 90.0, + "radius": 0.5121, + "trajectoryLength": 0.4401023994758333, + "arcLength": 0.4022023994758333, + "straightLength": 0.03789999999999999, + "poses": [ + [ + -1e-05, + -1e-05, + 2.3001427705539226 + ], + [ + -0.03828, + 0.04281, + 2.187827395859421 + ], + [ + -0.07151, + 0.08965, + 2.075729893090638 + ], + [ + -0.09929, + 0.13991, + 1.9634305739601647 + ], + [ + -0.12126, + 0.19296, + 1.8512962548918448 + ], + [ + -0.13716, + 0.24815, + 1.7391229596126936 + ], + [ + -0.14678, + 0.30476, + 1.6268936690660236 + ], + [ + -0.15, + 0.3621, + 0.0 + ] + ] + }, + { + "trajectoryId": 48, + "startAngle": 135.0, + "endAngle": 180.0, + "radius": 0.4828, + "trajectoryLength": 0.5327902332882881, + "arcLength": 0.37919023328828805, + "straightLength": 0.15360000000000001, + "poses": [ + [ + -0.0, + 0.0, + 2.356194490192345 + ], + [ + -0.0543, + 0.0543, + 2.356378652252878 + ], + [ + -0.10861, + 0.10859, + 0.0 + ], + [ + -0.10861, + 0.10859, + 2.4122508087517898 + ], + [ + -0.14898, + 0.14467, + 2.5244352771424006 + ], + [ + -0.19313, + 0.176, + 2.6367185203718857 + ], + [ + -0.24052, + 0.20219, + 2.748875865990998 + ], + [ + -0.29054, + 0.22291, + 2.8610859406579348 + ], + [ + -0.34257, + 0.2379, + 2.9734374254675204 + ], + [ + -0.39594, + 0.24696, + 3.0854180020716697 + ] + ] + }, + { + "trajectoryId": 49, + "startAngle": 135.0, + "endAngle": 90.0, + "radius": 0.4828, + "trajectoryLength": 0.5327902332882881, + "arcLength": 0.37919023328828805, + "straightLength": 0.15360000000000001, + "poses": [ + [ + -0.0, + 0.0, + 2.356194490192345 + ], + [ + -0.0543, + 0.0543, + 2.356010328131812 + ], + [ + -0.10859, + 0.10861, + 0.0 + ], + [ + -0.10859, + 0.10861, + 2.3001381716329 + ], + [ + -0.14467, + 0.14898, + 2.187953703242289 + ], + [ + -0.176, + 0.19313, + 2.0756704600128044 + ], + [ + -0.20219, + 0.24052, + 1.963513114393692 + ], + [ + -0.22291, + 0.29054, + 1.851303039726755 + ], + [ + -0.2379, + 0.34257, + 1.7389515549171695 + ], + [ + -0.24696, + 0.39594, + 1.62697097831302 + ] + ] + }, + { + "trajectoryId": 50, + "startAngle": 135.0, + "endAngle": 206.56505117707798, + "radius": 0.4251, + "trajectoryLength": 0.5972693578464978, + "arcLength": 0.5309693578464979, + "straightLength": 0.06629999999999997, + "poses": [ + [ + -1e-05, + -1e-05, + 2.4185966761898996 + ], + [ + -0.0398, + 0.0351, + 2.543605542069912 + ], + [ + -0.08365, + 0.06497, + 2.6684207203195744 + ], + [ + -0.13088, + 0.08915, + 2.79332074836733 + ], + [ + -0.18076, + 0.10726, + 2.918324864306639 + ], + [ + -0.23251, + 0.11901, + 3.0430492397370315 + ], + [ + -0.28531, + 0.12423, + -3.1150202102373594 + ], + [ + -0.33836, + 0.12282, + -2.9902329999111887 + ], + [ + -0.39081, + 0.11482, + -2.8652085522841735 + ], + [ + -0.44186, + 0.10034, + -2.7404374562839595 + ], + [ + -0.49071, + 0.07962, + 0.0 + ] + ] + }, + { + "trajectoryId": 51, + "startAngle": 135.0, + "endAngle": 63.43494882292201, + "radius": 0.4251, + "trajectoryLength": 0.5972693578464978, + "arcLength": 0.5309693578464979, + "straightLength": 0.06629999999999997, + "poses": [ + [ + 1e-05, + 1e-05, + 2.29379230419479 + ], + [ + -0.0351, + 0.0398, + 2.1687834383147777 + ], + [ + -0.06497, + 0.08365, + 2.0439682600651157 + ], + [ + -0.08915, + 0.13088, + 1.9190682320173602 + ], + [ + -0.10726, + 0.18076, + 1.794064116078051 + ], + [ + -0.11901, + 0.23251, + 1.6693397406476584 + ], + [ + -0.12423, + 0.28531, + 1.544223883442463 + ], + [ + -0.12282, + 0.33836, + 1.4194366731162924 + ], + [ + -0.11482, + 0.39081, + 1.294412225489277 + ], + [ + -0.10034, + 0.44186, + 1.1696411294890627 + ], + [ + -0.07962, + 0.49071, + 0.0 + ] + ] + }, + { + "trajectoryId": 52, + "startAngle": -135.0, + "endAngle": -153.43494882292202, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + -0.0, + -0.0, + -2.353807859878905 + ], + [ + -0.0209, + -0.021, + -2.40983426151916 + ], + [ + -0.07585, + -0.07035, + -2.517046620287862 + ], + [ + -0.13577, + -0.11354, + -2.6243945452086317 + ] + ] + }, + { + "trajectoryId": 53, + "startAngle": -135.0, + "endAngle": -116.56505117707799, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + -0.0, + -0.0, + -2.3585811205057845 + ], + [ + -0.021, + -0.0209, + -2.30255471886553 + ], + [ + -0.07035, + -0.07585, + -2.195342360096828 + ], + [ + -0.11354, + -0.13577, + -2.0879944351760584 + ] + ] + }, + { + "trajectoryId": 54, + "startAngle": -135.0, + "endAngle": -135.0, + "radius": 0, + "trajectoryLength": 0.28284271247461906, + "arcLength": 0.0, + "straightLength": 0.28284271247461906, + "poses": [ + [ + -0.0, + -0.0, + -2.356194490192345 + ], + [ + -0.04, + -0.04, + -2.356194490192345 + ], + [ + -0.08, + -0.08, + -2.356194490192345 + ], + [ + -0.12, + -0.12, + -2.356194490192345 + ], + [ + -0.16, + -0.16, + -2.356194490192345 + ] + ] + }, + { + "trajectoryId": 55, + "startAngle": -135.0, + "endAngle": -180.0, + "radius": 0.5121, + "trajectoryLength": 0.4401023994758333, + "arcLength": 0.4022023994758333, + "straightLength": 0.03789999999999999, + "poses": [ + [ + 1e-05, + -1e-05, + -2.412246209830767 + ], + [ + -0.04281, + -0.03828, + -2.5245615845252685 + ], + [ + -0.08965, + -0.07151, + -2.636659087294052 + ], + [ + -0.13991, + -0.09929, + -2.748958406424525 + ], + [ + -0.19296, + -0.12126, + -2.861092725492845 + ], + [ + -0.24815, + -0.13716, + -2.9732660207719963 + ], + [ + -0.30476, + -0.14678, + -3.0854953113186663 + ], + [ + -0.3621, + -0.15, + 0.0 + ] + ] + }, + { + "trajectoryId": 56, + "startAngle": -135.0, + "endAngle": -90.0, + "radius": 0.5121, + "trajectoryLength": 0.4401023994758333, + "arcLength": 0.4022023994758333, + "straightLength": 0.03789999999999999, + "poses": [ + [ + -1e-05, + 1e-05, + -2.3001427705539226 + ], + [ + -0.03828, + -0.04281, + -2.187827395859421 + ], + [ + -0.07151, + -0.08965, + -2.075729893090638 + ], + [ + -0.09929, + -0.13991, + -1.9634305739601647 + ], + [ + -0.12126, + -0.19296, + -1.8512962548918448 + ], + [ + -0.13716, + -0.24815, + -1.7391229596126936 + ], + [ + -0.14678, + -0.30476, + -1.6268936690660236 + ], + [ + -0.15, + -0.3621, + 0.0 + ] + ] + }, + { + "trajectoryId": 57, + "startAngle": -135.0, + "endAngle": -180.0, + "radius": 0.4828, + "trajectoryLength": 0.5327902332882881, + "arcLength": 0.37919023328828805, + "straightLength": 0.15360000000000001, + "poses": [ + [ + -0.0, + -0.0, + -2.356194490192345 + ], + [ + -0.0543, + -0.0543, + -2.356378652252878 + ], + [ + -0.10861, + -0.10859, + 0.0 + ], + [ + -0.10861, + -0.10859, + -2.4122508087517898 + ], + [ + -0.14898, + -0.14467, + -2.5244352771424006 + ], + [ + -0.19313, + -0.176, + -2.6367185203718857 + ], + [ + -0.24052, + -0.20219, + -2.748875865990998 + ], + [ + -0.29054, + -0.22291, + -2.8610859406579348 + ], + [ + -0.34257, + -0.2379, + -2.9734374254675204 + ], + [ + -0.39594, + -0.24696, + -3.0854180020716697 + ] + ] + }, + { + "trajectoryId": 58, + "startAngle": -135.0, + "endAngle": -90.0, + "radius": 0.4828, + "trajectoryLength": 0.5327902332882881, + "arcLength": 0.37919023328828805, + "straightLength": 0.15360000000000001, + "poses": [ + [ + -0.0, + -0.0, + -2.356194490192345 + ], + [ + -0.0543, + -0.0543, + -2.356010328131812 + ], + [ + -0.10859, + -0.10861, + 0.0 + ], + [ + -0.10859, + -0.10861, + -2.3001381716329 + ], + [ + -0.14467, + -0.14898, + -2.187953703242289 + ], + [ + -0.176, + -0.19313, + -2.0756704600128044 + ], + [ + -0.20219, + -0.24052, + -1.963513114393692 + ], + [ + -0.22291, + -0.29054, + -1.851303039726755 + ], + [ + -0.2379, + -0.34257, + -1.7389515549171695 + ], + [ + -0.24696, + -0.39594, + -1.62697097831302 + ] + ] + }, + { + "trajectoryId": 59, + "startAngle": -135.0, + "endAngle": -206.56505117707798, + "radius": 0.4251, + "trajectoryLength": 0.5972693578464978, + "arcLength": 0.5309693578464979, + "straightLength": 0.06629999999999997, + "poses": [ + [ + -1e-05, + 1e-05, + -2.4185966761898996 + ], + [ + -0.0398, + -0.0351, + -2.543605542069912 + ], + [ + -0.08365, + -0.06497, + -2.6684207203195744 + ], + [ + -0.13088, + -0.08915, + -2.79332074836733 + ], + [ + -0.18076, + -0.10726, + -2.918324864306639 + ], + [ + -0.23251, + -0.11901, + -3.0430492397370315 + ], + [ + -0.28531, + -0.12423, + 3.1150202102373594 + ], + [ + -0.33836, + -0.12282, + 2.9902329999111887 + ], + [ + -0.39081, + -0.11482, + 2.8652085522841735 + ], + [ + -0.44186, + -0.10034, + 2.7404374562839595 + ], + [ + -0.49071, + -0.07962, + 0.0 + ] + ] + }, + { + "trajectoryId": 60, + "startAngle": -135.0, + "endAngle": -63.43494882292201, + "radius": 0.4251, + "trajectoryLength": 0.5972693578464978, + "arcLength": 0.5309693578464979, + "straightLength": 0.06629999999999997, + "poses": [ + [ + 1e-05, + -1e-05, + -2.29379230419479 + ], + [ + -0.0351, + -0.0398, + -2.1687834383147777 + ], + [ + -0.06497, + -0.08365, + -2.0439682600651157 + ], + [ + -0.08915, + -0.13088, + -1.9190682320173602 + ], + [ + -0.10726, + -0.18076, + -1.794064116078051 + ], + [ + -0.11901, + -0.23251, + -1.6693397406476584 + ], + [ + -0.12423, + -0.28531, + -1.544223883442463 + ], + [ + -0.12282, + -0.33836, + -1.4194366731162924 + ], + [ + -0.11482, + -0.39081, + -1.294412225489277 + ], + [ + -0.10034, + -0.44186, + -1.1696411294890627 + ], + [ + -0.07962, + -0.49071, + 0.0 + ] + ] + }, + { + "trajectoryId": 61, + "startAngle": -45.0, + "endAngle": -26.56505117707799, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + 0.0, + -0.0, + -0.7877847937108879 + ], + [ + 0.0209, + -0.021, + -0.7317583920706331 + ], + [ + 0.07585, + -0.07035, + -0.6245460333019313 + ], + [ + 0.13577, + -0.11354, + -0.5171981083811618 + ] + ] + }, + { + "trajectoryId": 62, + "startAngle": -45.0, + "endAngle": -63.43494882292201, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + 0.0, + -0.0, + -0.7830115330840086 + ], + [ + 0.021, + -0.0209, + -0.8390379347242635 + ], + [ + 0.07035, + -0.07585, + -0.9462502934929653 + ], + [ + 0.11354, + -0.13577, + -1.053598218413735 + ] + ] + }, + { + "trajectoryId": 63, + "startAngle": -45.0, + "endAngle": -45.0, + "radius": 0, + "trajectoryLength": 0.28284271247461906, + "arcLength": 0.0, + "straightLength": 0.28284271247461906, + "poses": [ + [ + 0.0, + -0.0, + -0.7853981633974483 + ], + [ + 0.04, + -0.04, + -0.7853981633974483 + ], + [ + 0.08, + -0.08, + -0.7853981633974483 + ], + [ + 0.12, + -0.12, + -0.7853981633974483 + ], + [ + 0.16, + -0.16, + -0.7853981633974483 + ] + ] + }, + { + "trajectoryId": 64, + "startAngle": -45.0, + "endAngle": -0.0, + "radius": 0.5121, + "trajectoryLength": 0.4401023994758333, + "arcLength": 0.4022023994758333, + "straightLength": 0.03789999999999999, + "poses": [ + [ + -1e-05, + -1e-05, + -0.7293464437590259 + ], + [ + 0.04281, + -0.03828, + -0.6170310690645247 + ], + [ + 0.08965, + -0.07151, + -0.5049335662957414 + ], + [ + 0.13991, + -0.09929, + -0.3926342471652681 + ], + [ + 0.19296, + -0.12126, + -0.28049992809694807 + ], + [ + 0.24815, + -0.13716, + -0.16832663281779695 + ], + [ + 0.30476, + -0.14678, + -0.05609734227112698 + ], + [ + 0.3621, + -0.15, + 0.0 + ] + ] + }, + { + "trajectoryId": 65, + "startAngle": -45.0, + "endAngle": -90.0, + "radius": 0.5121, + "trajectoryLength": 0.4401023994758333, + "arcLength": 0.4022023994758333, + "straightLength": 0.03789999999999999, + "poses": [ + [ + 1e-05, + 1e-05, + -0.8414498830358706 + ], + [ + 0.03828, + -0.04281, + -0.953765257730372 + ], + [ + 0.07151, + -0.08965, + -1.0658627604991553 + ], + [ + 0.09929, + -0.13991, + -1.1781620796296284 + ], + [ + 0.12126, + -0.19296, + -1.2902963986979485 + ], + [ + 0.13716, + -0.24815, + -1.4024696939770998 + ], + [ + 0.14678, + -0.30476, + -1.5146989845237697 + ], + [ + 0.15, + -0.3621, + 0.0 + ] + ] + }, + { + "trajectoryId": 66, + "startAngle": -45.0, + "endAngle": -0.0, + "radius": 0.4828, + "trajectoryLength": 0.5327902332882881, + "arcLength": 0.37919023328828805, + "straightLength": 0.15360000000000001, + "poses": [ + [ + 0.0, + -0.0, + -0.7853981633974483 + ], + [ + 0.0543, + -0.0543, + -0.7852140013369153 + ], + [ + 0.10861, + -0.10859, + 0.0 + ], + [ + 0.10861, + -0.10859, + -0.7293418448380035 + ], + [ + 0.14898, + -0.14467, + -0.6171573764473927 + ], + [ + 0.19313, + -0.176, + -0.5048741332179076 + ], + [ + 0.24052, + -0.20219, + -0.3927167875987952 + ], + [ + 0.29054, + -0.22291, + -0.28050671293185836 + ], + [ + 0.34257, + -0.2379, + -0.16815522812227288 + ], + [ + 0.39594, + -0.24696, + -0.05617465151812344 + ] + ] + }, + { + "trajectoryId": 67, + "startAngle": -45.0, + "endAngle": -90.0, + "radius": 0.4828, + "trajectoryLength": 0.5327902332882881, + "arcLength": 0.37919023328828805, + "straightLength": 0.15360000000000001, + "poses": [ + [ + 0.0, + -0.0, + -0.7853981633974483 + ], + [ + 0.0543, + -0.0543, + -0.7855823254579813 + ], + [ + 0.10859, + -0.10861, + 0.0 + ], + [ + 0.10859, + -0.10861, + -0.8414544819568931 + ], + [ + 0.14467, + -0.14898, + -0.953638950347504 + ], + [ + 0.176, + -0.19313, + -1.065922193576989 + ], + [ + 0.20219, + -0.24052, + -1.1780795391961014 + ], + [ + 0.22291, + -0.29054, + -1.2902896138630382 + ], + [ + 0.2379, + -0.34257, + -1.4026410986726237 + ], + [ + 0.24696, + -0.39594, + -1.5146216752767732 + ] + ] + }, + { + "trajectoryId": 68, + "startAngle": -45.0, + "endAngle": 26.56505117707799, + "radius": 0.4251, + "trajectoryLength": 0.5972693578464978, + "arcLength": 0.5309693578464979, + "straightLength": 0.06629999999999997, + "poses": [ + [ + 1e-05, + 1e-05, + -0.7229959773998935 + ], + [ + 0.0398, + -0.0351, + -0.5979871115198812 + ], + [ + 0.08365, + -0.06497, + -0.47317193327021895 + ], + [ + 0.13088, + -0.08915, + -0.3482719052224635 + ], + [ + 0.18076, + -0.10726, + -0.22326778928315447 + ], + [ + 0.23251, + -0.11901, + -0.09854341385276191 + ], + [ + 0.28531, + -0.12423, + 0.026572443352433615 + ], + [ + 0.33836, + -0.12282, + 0.15135965367860432 + ], + [ + 0.39081, + -0.11482, + 0.2763841013056198 + ], + [ + 0.44186, + -0.10034, + 0.4011551973058339 + ], + [ + 0.49071, + -0.07962, + 0.0 + ] + ] + }, + { + "trajectoryId": 69, + "startAngle": -45.0, + "endAngle": -116.56505117707799, + "radius": 0.4251, + "trajectoryLength": 0.5972693578464978, + "arcLength": 0.5309693578464979, + "straightLength": 0.06629999999999997, + "poses": [ + [ + -1e-05, + -1e-05, + -0.847800349395003 + ], + [ + 0.0351, + -0.0398, + -0.9728092152750155 + ], + [ + 0.06497, + -0.08365, + -1.0976243935246777 + ], + [ + 0.08915, + -0.13088, + -1.2225244215724331 + ], + [ + 0.10726, + -0.18076, + -1.347528537511742 + ], + [ + 0.11901, + -0.23251, + -1.4722529129421347 + ], + [ + 0.12423, + -0.28531, + -1.5973687701473303 + ], + [ + 0.12282, + -0.33836, + -1.722155980473501 + ], + [ + 0.11482, + -0.39081, + -1.8471804281005164 + ], + [ + 0.10034, + -0.44186, + -1.9719515241007306 + ], + [ + 0.07962, + -0.49071, + 0.0 + ] + ] + }, + { + "trajectoryId": 70, + "startAngle": 63.43494882292201, + "endAngle": 90.0, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + 0.00528, + 0.01056, + 1.1844975219908958 + ], + [ + 0.02992, + 0.07114, + 1.33890893073425 + ], + [ + 0.04495, + 0.13479, + 1.4935084760033717 + ] + ] + }, + { + "trajectoryId": 71, + "startAngle": 63.43494882292201, + "endAngle": 63.43494882292201, + "radius": 0, + "trajectoryLength": 0.223606797749979, + "arcLength": 0.0, + "straightLength": 0.223606797749979, + "poses": [ + [ + 0.0, + 0.0, + 1.1072087165940425 + ], + [ + 0.03333, + 0.06667, + 1.1070287129944747 + ], + [ + 0.06667, + 0.13333, + 1.1072087165940423 + ] + ] + }, + { + "trajectoryId": 72, + "startAngle": 63.43494882292201, + "endAngle": 45.0, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + -6e-05, + 3e-05, + 1.0535982184137347 + ], + [ + 0.03646, + 0.06423, + 0.9462502934929654 + ], + [ + 0.07965, + 0.12415, + 0.8390379347242635 + ], + [ + 0.129, + 0.1791, + 0.0 + ] + ] + }, + { + "trajectoryId": 73, + "startAngle": 63.43494882292201, + "endAngle": 26.56505117707799, + "radius": 0.4472, + "trajectoryLength": 0.28777369585235674, + "arcLength": 0.28777369585235674, + "straightLength": 0, + "poses": [ + [ + 1e-05, + -1e-05, + 1.042809472532039 + ], + [ + 0.02899, + 0.04968, + 0.9141147480501551 + ], + [ + 0.0641, + 0.09523, + 0.7853981633974483 + ], + [ + 0.10477, + 0.1359, + 0.6566815787447413 + ], + [ + 0.15032, + 0.17101, + 0.527986854262858 + ] + ] + }, + { + "trajectoryId": 74, + "startAngle": 63.43494882292201, + "endAngle": 90.0, + "radius": 0.6354, + "trajectoryLength": 0.3682016907591122, + "arcLength": 0.2946016907591122, + "straightLength": 0.0736, + "poses": [ + [ + 0.0, + 0.0, + 1.1071487177940904 + ], + [ + 0.03292, + 0.06584, + 1.1535545352960592 + ], + [ + 0.05679, + 0.11969, + 1.2462536834338316 + ], + [ + 0.07557, + 0.17551, + 1.3389959296100549 + ], + [ + 0.0891, + 0.23283, + 1.4316364916319972 + ], + [ + 0.09727, + 0.29116, + 1.5244325676974748 + ] + ] + }, + { + "trajectoryId": 75, + "startAngle": 116.56505117707799, + "endAngle": 90.0, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + -0.00528, + 0.01056, + 1.9570951315988974 + ], + [ + -0.02992, + 0.07114, + 1.8026837228555432 + ], + [ + -0.04495, + 0.13479, + 1.6480841775864215 + ] + ] + }, + { + "trajectoryId": 76, + "startAngle": 116.56505117707799, + "endAngle": 116.56505117707799, + "radius": 0, + "trajectoryLength": 0.223606797749979, + "arcLength": 0.0, + "straightLength": 0.223606797749979, + "poses": [ + [ + -0.0, + 0.0, + 2.034383936995751 + ], + [ + -0.03333, + 0.06667, + 2.0345639405953184 + ], + [ + -0.06667, + 0.13333, + 2.034383936995751 + ] + ] + }, + { + "trajectoryId": 77, + "startAngle": 116.56505117707799, + "endAngle": 135.0, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + 6e-05, + 3e-05, + 2.0879944351760584 + ], + [ + -0.03646, + 0.06423, + 2.195342360096828 + ], + [ + -0.07965, + 0.12415, + 2.30255471886553 + ], + [ + -0.129, + 0.1791, + 0.0 + ] + ] + }, + { + "trajectoryId": 78, + "startAngle": 116.56505117707799, + "endAngle": 153.43494882292202, + "radius": 0.4472, + "trajectoryLength": 0.28777369585235674, + "arcLength": 0.28777369585235674, + "straightLength": 0, + "poses": [ + [ + -1e-05, + -1e-05, + 2.098783181057754 + ], + [ + -0.02899, + 0.04968, + 2.227477905539638 + ], + [ + -0.0641, + 0.09523, + 2.356194490192345 + ], + [ + -0.10477, + 0.1359, + 2.484911074845052 + ], + [ + -0.15032, + 0.17101, + 2.6136057993269355 + ] + ] + }, + { + "trajectoryId": 79, + "startAngle": 116.56505117707799, + "endAngle": 90.0, + "radius": 0.6354, + "trajectoryLength": 0.3682016907591122, + "arcLength": 0.2946016907591122, + "straightLength": 0.0736, + "poses": [ + [ + -0.0, + 0.0, + 2.0344439357957027 + ], + [ + -0.03292, + 0.06584, + 1.9880381182937341 + ], + [ + -0.05679, + 0.11969, + 1.8953389701559615 + ], + [ + -0.07557, + 0.17551, + 1.8025967239797382 + ], + [ + -0.0891, + 0.23283, + 1.7099561619577959 + ], + [ + -0.09727, + 0.29116, + 1.6171600858923185 + ] + ] + }, + { + "trajectoryId": 80, + "startAngle": -116.56505117707799, + "endAngle": -90.0, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + -0.00528, + -0.01056, + -1.9570951315988974 + ], + [ + -0.02992, + -0.07114, + -1.8026837228555432 + ], + [ + -0.04495, + -0.13479, + -1.6480841775864215 + ] + ] + }, + { + "trajectoryId": 81, + "startAngle": -116.56505117707799, + "endAngle": -116.56505117707799, + "radius": 0, + "trajectoryLength": 0.223606797749979, + "arcLength": 0.0, + "straightLength": 0.223606797749979, + "poses": [ + [ + -0.0, + -0.0, + -2.034383936995751 + ], + [ + -0.03333, + -0.06667, + -2.0345639405953184 + ], + [ + -0.06667, + -0.13333, + -2.034383936995751 + ] + ] + }, + { + "trajectoryId": 82, + "startAngle": -116.56505117707799, + "endAngle": -135.0, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + 6e-05, + -3e-05, + -2.0879944351760584 + ], + [ + -0.03646, + -0.06423, + -2.195342360096828 + ], + [ + -0.07965, + -0.12415, + -2.30255471886553 + ], + [ + -0.129, + -0.1791, + 0.0 + ] + ] + }, + { + "trajectoryId": 83, + "startAngle": -116.56505117707799, + "endAngle": -153.43494882292202, + "radius": 0.4472, + "trajectoryLength": 0.28777369585235674, + "arcLength": 0.28777369585235674, + "straightLength": 0, + "poses": [ + [ + -1e-05, + 1e-05, + -2.098783181057754 + ], + [ + -0.02899, + -0.04968, + -2.227477905539638 + ], + [ + -0.0641, + -0.09523, + -2.356194490192345 + ], + [ + -0.10477, + -0.1359, + -2.484911074845052 + ], + [ + -0.15032, + -0.17101, + -2.6136057993269355 + ] + ] + }, + { + "trajectoryId": 84, + "startAngle": -116.56505117707799, + "endAngle": -90.0, + "radius": 0.6354, + "trajectoryLength": 0.3682016907591122, + "arcLength": 0.2946016907591122, + "straightLength": 0.0736, + "poses": [ + [ + -0.0, + -0.0, + -2.0344439357957027 + ], + [ + -0.03292, + -0.06584, + -1.9880381182937341 + ], + [ + -0.05679, + -0.11969, + -1.8953389701559615 + ], + [ + -0.07557, + -0.17551, + -1.8025967239797382 + ], + [ + -0.0891, + -0.23283, + -1.7099561619577959 + ], + [ + -0.09727, + -0.29116, + -1.6171600858923185 + ] + ] + }, + { + "trajectoryId": 85, + "startAngle": -63.43494882292201, + "endAngle": -90.0, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + 0.00528, + -0.01056, + -1.1844975219908958 + ], + [ + 0.02992, + -0.07114, + -1.33890893073425 + ], + [ + 0.04495, + -0.13479, + -1.4935084760033717 + ] + ] + }, + { + "trajectoryId": 86, + "startAngle": -63.43494882292201, + "endAngle": -63.43494882292201, + "radius": 0, + "trajectoryLength": 0.223606797749979, + "arcLength": 0.0, + "straightLength": 0.223606797749979, + "poses": [ + [ + 0.0, + -0.0, + -1.1072087165940425 + ], + [ + 0.03333, + -0.06667, + -1.1070287129944747 + ], + [ + 0.06667, + -0.13333, + -1.1072087165940423 + ] + ] + }, + { + "trajectoryId": 87, + "startAngle": -63.43494882292201, + "endAngle": -45.0, + "radius": 0.689, + "trajectoryLength": 0.25128613197928645, + "arcLength": 0.22168613197928647, + "straightLength": 0.0296, + "poses": [ + [ + -6e-05, + -3e-05, + -1.0535982184137347 + ], + [ + 0.03646, + -0.06423, + -0.9462502934929654 + ], + [ + 0.07965, + -0.12415, + -0.8390379347242635 + ], + [ + 0.129, + -0.1791, + 0.0 + ] + ] + }, + { + "trajectoryId": 88, + "startAngle": -63.43494882292201, + "endAngle": -26.56505117707799, + "radius": 0.4472, + "trajectoryLength": 0.28777369585235674, + "arcLength": 0.28777369585235674, + "straightLength": 0, + "poses": [ + [ + 1e-05, + 1e-05, + -1.042809472532039 + ], + [ + 0.02899, + -0.04968, + -0.9141147480501551 + ], + [ + 0.0641, + -0.09523, + -0.7853981633974483 + ], + [ + 0.10477, + -0.1359, + -0.6566815787447413 + ], + [ + 0.15032, + -0.17101, + -0.527986854262858 + ] + ] + }, + { + "trajectoryId": 89, + "startAngle": -63.43494882292201, + "endAngle": -90.0, + "radius": 0.6354, + "trajectoryLength": 0.3682016907591122, + "arcLength": 0.2946016907591122, + "straightLength": 0.0736, + "poses": [ + [ + 0.0, + -0.0, + -1.1071487177940904 + ], + [ + 0.03292, + -0.06584, + -1.1535545352960592 + ], + [ + 0.05679, + -0.11969, + -1.2462536834338316 + ], + [ + 0.07557, + -0.17551, + -1.3389959296100549 + ], + [ + 0.0891, + -0.23283, + -1.4316364916319972 + ], + [ + 0.09727, + -0.29116, + -1.5244325676974748 + ] + ] + }, + { + "trajectoryId": 90, + "startAngle": 90.0, + "endAngle": 90.0, + "radius": 0, + "trajectoryLength": 0.2, + "arcLength": 0.0, + "straightLength": 0.2, + "poses": [ + [ + 0.0, + 0.0, + 1.5707963267948966 + ], + [ + 0.0, + 0.06667, + 1.5707963267948966 + ], + [ + 0.0, + 0.13333, + 1.5707963267948966 + ] + ] + }, + { + "trajectoryId": 91, + "startAngle": 90.0, + "endAngle": 63.43494882292201, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + 0.0, + 0.0, + 1.4935084760033717 + ], + [ + 0.00505, + 0.06521, + 1.3389089307342499 + ], + [ + 0.02008, + 0.12886, + 1.1844975219908958 + ] + ] + }, + { + "trajectoryId": 92, + "startAngle": 90.0, + "endAngle": 116.56505117707799, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + -0.0, + 0.0, + 1.6480841775864215 + ], + [ + -0.00505, + 0.06521, + 1.8026837228555432 + ], + [ + -0.02008, + 0.12886, + 1.9570951315988976 + ] + ] + }, + { + "trajectoryId": 93, + "startAngle": 90.0, + "endAngle": 63.43494882292201, + "radius": 0.8472, + "trajectoryLength": 0.41640225434548295, + "arcLength": 0.39280225434548294, + "straightLength": 0.023599999999999982, + "poses": [ + [ + 0.0, + 0.0, + 1.5376356672653075 + ], + [ + 0.00186, + 0.05607, + 1.4715355769519873 + ], + [ + 0.00742, + 0.1119, + 1.405178839897782 + ], + [ + 0.01667, + 0.16724, + 1.3389605793090156 + ], + [ + 0.02956, + 0.22184, + 1.272664314771342 + ], + [ + 0.04604, + 0.27547, + 1.2064763007678847 + ], + [ + 0.06603, + 0.32789, + 1.1403927062346335 + ] + ] + }, + { + "trajectoryId": 94, + "startAngle": 90.0, + "endAngle": 116.56505117707799, + "radius": 0.8472, + "trajectoryLength": 0.41640225434548295, + "arcLength": 0.39280225434548294, + "straightLength": 0.023599999999999982, + "poses": [ + [ + -0.0, + 0.0, + 1.6039569863244858 + ], + [ + -0.00186, + 0.05607, + 1.6700570766378058 + ], + [ + -0.00742, + 0.1119, + 1.7364138136920113 + ], + [ + -0.01667, + 0.16724, + 1.8026320742807778 + ], + [ + -0.02956, + 0.22184, + 1.8689283388184512 + ], + [ + -0.04604, + 0.27547, + 1.9351163528219084 + ], + [ + -0.06603, + 0.32789, + 2.00119994735516 + ] + ] + }, + { + "trajectoryId": 95, + "startAngle": 90.0, + "endAngle": 0.0, + "radius": 0.5, + "trajectoryLength": 0.8353981633974483, + "arcLength": 0.7853981633974483, + "straightLength": 0.050000000000000044, + "poses": [ + [ + 0.0, + 0.0, + 1.5707963267948966 + ], + [ + 0.0, + 0.05, + 1.5184141329299277 + ], + [ + 0.00274, + 0.10226, + 1.4136879296500158 + ], + [ + 0.01093, + 0.15396, + 1.3090861204812356 + ], + [ + 0.02447, + 0.20451, + 1.2041986404066858 + ], + [ + 0.04323, + 0.25337, + 1.0995433269194599 + ], + [ + 0.06699, + 0.3, + 0.9948777271765432 + ], + [ + 0.09549, + 0.34389, + 0.8901478270870059 + ], + [ + 0.12843, + 0.38457, + 0.785398163397448 + ], + [ + 0.16543, + 0.42157, + 0.680648499707892 + ], + [ + 0.20611, + 0.45451, + 0.5759185996183525 + ], + [ + 0.25, + 0.48301, + 0.47125299987543784 + ], + [ + 0.29663, + 0.50677, + 0.3665976863882106 + ], + [ + 0.34549, + 0.52553, + 0.261710206313661 + ], + [ + 0.39604, + 0.53907, + 0.15710839714487923 + ], + [ + 0.44774, + 0.54726, + 0.05238219386497044 + ] + ] + }, + { + "trajectoryId": 96, + "startAngle": 90.0, + "endAngle": 180.0, + "radius": 0.5, + "trajectoryLength": 0.8353981633974483, + "arcLength": 0.7853981633974483, + "straightLength": 0.050000000000000044, + "poses": [ + [ + -0.0, + 0.0, + 1.5707963267948966 + ], + [ + -0.0, + 0.05, + 1.6231785206598657 + ], + [ + -0.00274, + 0.10226, + 1.7279047239397773 + ], + [ + -0.01093, + 0.15396, + 1.8325065331085577 + ], + [ + -0.02447, + 0.20451, + 1.9373940131831073 + ], + [ + -0.04323, + 0.25337, + 2.0420493266703335 + ], + [ + -0.06699, + 0.3, + 2.14671492641325 + ], + [ + -0.09549, + 0.34389, + 2.2514448265027873 + ], + [ + -0.12843, + 0.38457, + 2.3561944901923453 + ], + [ + -0.16543, + 0.42157, + 2.460944153881901 + ], + [ + -0.20611, + 0.45451, + 2.5656740539714407 + ], + [ + -0.25, + 0.48301, + 2.6703396537143553 + ], + [ + -0.29663, + 0.50677, + 2.774994967201583 + ], + [ + -0.34549, + 0.52553, + 2.8798824472761324 + ], + [ + -0.39604, + 0.53907, + 2.984484256444914 + ], + [ + -0.44774, + 0.54726, + 3.0892104597248227 + ] + ] + }, + { + "trajectoryId": 97, + "startAngle": -90.0, + "endAngle": -90.0, + "radius": 0, + "trajectoryLength": 0.2, + "arcLength": 0.0, + "straightLength": 0.2, + "poses": [ + [ + 0.0, + -0.0, + -1.5707963267948966 + ], + [ + 0.0, + -0.06667, + -1.5707963267948966 + ], + [ + 0.0, + -0.13333, + -1.5707963267948966 + ] + ] + }, + { + "trajectoryId": 98, + "startAngle": -90.0, + "endAngle": -116.56505117707799, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + -0.0, + -0.0, + -1.6480841775864215 + ], + [ + -0.00505, + -0.06521, + -1.8026837228555432 + ], + [ + -0.02008, + -0.12886, + -1.9570951315988976 + ] + ] + }, + { + "trajectoryId": 99, + "startAngle": -90.0, + "endAngle": -63.43494882292201, + "radius": 0.4236, + "trajectoryLength": 0.20820112717274147, + "arcLength": 0.19640112717274147, + "straightLength": 0.011799999999999991, + "poses": [ + [ + 0.0, + -0.0, + -1.4935084760033717 + ], + [ + 0.00505, + -0.06521, + -1.3389089307342499 + ], + [ + 0.02008, + -0.12886, + -1.1844975219908958 + ] + ] + }, + { + "trajectoryId": 100, + "startAngle": -90.0, + "endAngle": -116.56505117707799, + "radius": 0.8472, + "trajectoryLength": 0.41640225434548295, + "arcLength": 0.39280225434548294, + "straightLength": 0.023599999999999982, + "poses": [ + [ + -0.0, + -0.0, + -1.6039569863244858 + ], + [ + -0.00186, + -0.05607, + -1.6700570766378058 + ], + [ + -0.00742, + -0.1119, + -1.7364138136920113 + ], + [ + -0.01667, + -0.16724, + -1.8026320742807778 + ], + [ + -0.02956, + -0.22184, + -1.8689283388184512 + ], + [ + -0.04604, + -0.27547, + -1.9351163528219084 + ], + [ + -0.06603, + -0.32789, + -2.00119994735516 + ] + ] + }, + { + "trajectoryId": 101, + "startAngle": -90.0, + "endAngle": -63.43494882292201, + "radius": 0.8472, + "trajectoryLength": 0.41640225434548295, + "arcLength": 0.39280225434548294, + "straightLength": 0.023599999999999982, + "poses": [ + [ + 0.0, + -0.0, + -1.5376356672653075 + ], + [ + 0.00186, + -0.05607, + -1.4715355769519873 + ], + [ + 0.00742, + -0.1119, + -1.405178839897782 + ], + [ + 0.01667, + -0.16724, + -1.3389605793090156 + ], + [ + 0.02956, + -0.22184, + -1.272664314771342 + ], + [ + 0.04604, + -0.27547, + -1.2064763007678847 + ], + [ + 0.06603, + -0.32789, + -1.1403927062346335 + ] + ] + }, + { + "trajectoryId": 102, + "startAngle": -90.0, + "endAngle": -180.0, + "radius": 0.5, + "trajectoryLength": 0.8353981633974483, + "arcLength": 0.7853981633974483, + "straightLength": 0.050000000000000044, + "poses": [ + [ + -0.0, + -0.0, + -1.5707963267948966 + ], + [ + -0.0, + -0.05, + -1.6231785206598657 + ], + [ + -0.00274, + -0.10226, + -1.7279047239397773 + ], + [ + -0.01093, + -0.15396, + -1.8325065331085577 + ], + [ + -0.02447, + -0.20451, + -1.9373940131831073 + ], + [ + -0.04323, + -0.25337, + -2.0420493266703335 + ], + [ + -0.06699, + -0.3, + -2.14671492641325 + ], + [ + -0.09549, + -0.34389, + -2.2514448265027873 + ], + [ + -0.12843, + -0.38457, + -2.3561944901923453 + ], + [ + -0.16543, + -0.42157, + -2.460944153881901 + ], + [ + -0.20611, + -0.45451, + -2.5656740539714407 + ], + [ + -0.25, + -0.48301, + -2.6703396537143553 + ], + [ + -0.29663, + -0.50677, + -2.774994967201583 + ], + [ + -0.34549, + -0.52553, + -2.8798824472761324 + ], + [ + -0.39604, + -0.53907, + -2.984484256444914 + ], + [ + -0.44774, + -0.54726, + -3.0892104597248227 + ] + ] + }, + { + "trajectoryId": 103, + "startAngle": -90.0, + "endAngle": -0.0, + "radius": 0.5, + "trajectoryLength": 0.8353981633974483, + "arcLength": 0.7853981633974483, + "straightLength": 0.050000000000000044, + "poses": [ + [ + 0.0, + -0.0, + -1.5707963267948966 + ], + [ + 0.0, + -0.05, + -1.5184141329299277 + ], + [ + 0.00274, + -0.10226, + -1.4136879296500158 + ], + [ + 0.01093, + -0.15396, + -1.3090861204812356 + ], + [ + 0.02447, + -0.20451, + -1.2041986404066858 + ], + [ + 0.04323, + -0.25337, + -1.0995433269194599 + ], + [ + 0.06699, + -0.3, + -0.9948777271765432 + ], + [ + 0.09549, + -0.34389, + -0.8901478270870059 + ], + [ + 0.12843, + -0.38457, + -0.785398163397448 + ], + [ + 0.16543, + -0.42157, + -0.680648499707892 + ], + [ + 0.20611, + -0.45451, + -0.5759185996183525 + ], + [ + 0.25, + -0.48301, + -0.47125299987543784 + ], + [ + 0.29663, + -0.50677, + -0.3665976863882106 + ], + [ + 0.34549, + -0.52553, + -0.261710206313661 + ], + [ + 0.39604, + -0.53907, + -0.15710839714487923 + ], + [ + 0.44774, + -0.54726, + -0.05238219386497044 + ] + ] + } + ] +} diff --git a/nav2_smac_planner/test/test_nodelattice.cpp b/nav2_smac_planner/test/test_nodelattice.cpp new file mode 100644 index 0000000000..964fb8c937 --- /dev/null +++ b/nav2_smac_planner/test/test_nodelattice.cpp @@ -0,0 +1,118 @@ +// Copyright (c) 2021 Joshua Wallace +// +// 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. Reserved. + +#include "nav2_smac_planner/node_lattice.hpp" +#include "gtest/gtest.h" +#include "ament_index_cpp/get_package_share_directory.hpp" +#include + +using json = nlohmann::json; + +TEST(NodeLatticeTest, parser_test) +{ + std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); + std::string filePath = pkg_share_dir + "/output.json"; + std::ifstream myJsonFile(filePath); + + ASSERT_TRUE(myJsonFile.is_open()); + + json j; + myJsonFile >> j; + + nav2_smac_planner::LatticeMetadata metaData; + nav2_smac_planner::MotionPrimitive myPrimitive; + nav2_smac_planner::MotionPose pose; + + json jsonMetaData = j["latticeMetadata"]; + json jsonPrimatives = j["primitives"]; + json jsonPose = jsonPrimatives[0]["poses"][0]; + + nav2_smac_planner::fromJsonToMetaData(jsonMetaData, metaData); + + //Checks for parsing meta data + EXPECT_NEAR(metaData.min_turning_radius, 0.4, 0.001); + EXPECT_NEAR(metaData.primitive_resolution, 0.005, 0.0001); + EXPECT_NEAR(metaData.grid_resolution, 0.05, 0.001); + EXPECT_NEAR(metaData.max_length, 1, 0.01); + EXPECT_NEAR(metaData.number_of_headings, 16, 0.01); + EXPECT_EQ(metaData.output_file, "output.json"); + EXPECT_NEAR(metaData.heading_angles[0], -180.0, 0.01); + + std::vector myPrimitives; + for(unsigned int i = 0; i < jsonPrimatives.size() ; ++i) + { + nav2_smac_planner::MotionPrimitive newPrimative; + nav2_smac_planner::fromJsonToMotionPrimitive(jsonPrimatives[i], newPrimative ); + myPrimitives.push_back(newPrimative); + } + + //Checks for parsing primitives + EXPECT_NEAR(myPrimitives[0].trajectory_id, 0, 0.01); + EXPECT_NEAR(myPrimitives[0].start_angle, 0.0,0.01); + EXPECT_NEAR(myPrimitives[0].end_angle, 0.0, 0.01); + EXPECT_NEAR(myPrimitives[0].turning_radius, 0.0, 0.01); + EXPECT_NEAR(myPrimitives[0].trajectory_length, 0.2, 0.01); + EXPECT_NEAR(myPrimitives[0].arc_length, 0.0, 0.01); + EXPECT_NEAR(myPrimitives[0].straight_length, 0.2, 0.01); + + EXPECT_NEAR(myPrimitives[0].poses[0]._x, 0.0, 0.01); + EXPECT_NEAR(myPrimitives[0].poses[0]._y, 0.0, 0.01); + EXPECT_NEAR(myPrimitives[0].poses[0]._theta, 0.0, 0.01); + + EXPECT_NEAR(myPrimitives[0].poses[1]._x, 0.06667, 0.01); + EXPECT_NEAR(myPrimitives[0].poses[1]._y, 0.0, 0.01); + EXPECT_NEAR(myPrimitives[0].poses[1]._theta, 0.0, 0.01); +} + +TEST(NodeLatticeTest, test_node_lattice_neighbors) +{ + std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); + std::string filePath = pkg_share_dir + "/output.json"; + + nav2_smac_planner::SearchInfo info; + info.minimum_turning_radius = 1.1; + info.non_straight_penalty = 1; + info.change_penalty = 1; + info.reverse_penalty = 1; + info.cost_penalty = 1; + info.analytic_expansion_ratio = 1; + info.lattice_filepath = filePath; + info.cache_obstacle_heuristic = true; + + unsigned int x = 100; + unsigned int y = 100; + unsigned int angle_quantization = 16; + + nav2_smac_planner::NodeLattice::initMotionModel(nav2_smac_planner::MotionModel::STATE_LATTICE, + x, + y, + angle_quantization, + info); + + nav2_smac_planner::NodeLattice aNode(0); + aNode.setPose( nav2_smac_planner::NodeHybrid::Coordinates(0, 0, 0) ); + nav2_smac_planner::MotionPoses projections = nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives( &aNode); + + EXPECT_NEAR(projections[0]._x, 0.13333, 0.01); + EXPECT_NEAR(projections[0]._y, 0.0, 0.01); + EXPECT_NEAR(projections[0]._theta, 0.0, 0.01); + + aNode.setPose(nav2_smac_planner::NodeHybrid::Coordinates(0, 0, 1)); + + projections = nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives( &aNode); + + EXPECT_NEAR(projections[0]._x, -0.13333, 0.01); + EXPECT_NEAR(projections[0]._y, 0.0, 0.01); + EXPECT_NEAR(projections[0]._theta, 3.14, 0.01); +} \ No newline at end of file From 4119ef32d1aa1bafe120a67e94c93ea817b367c3 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 13 Oct 2021 15:03:41 -0700 Subject: [PATCH 06/31] adding in intermediate collision checking and backtracing --- .../nav2_smac_planner/collision_checker.hpp | 15 +- .../nav2_smac_planner/node_lattice.hpp | 30 ++-- .../include/nav2_smac_planner/types.hpp | 7 + .../include/nav2_smac_planner/utils.hpp | 15 -- nav2_smac_planner/src/a_star.cpp | 51 ++++++- nav2_smac_planner/src/collision_checker.cpp | 14 +- nav2_smac_planner/src/node_lattice.cpp | 135 +++++++++++------- nav2_smac_planner/src/smac_planner_hybrid.cpp | 2 +- .../src/smac_planner_lattice.cpp | 13 +- nav2_smac_planner/test/test_nodelattice.cpp | 18 +-- 10 files changed, 200 insertions(+), 100 deletions(-) diff --git a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp index aa27404fcf..27170c5689 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp @@ -47,9 +47,9 @@ class GridCollisionChecker * @param angles The vector of possible angle bins to precompute for * orientations for to speed up collision checking, in radians */ - GridCollisionChecker( - nav2_costmap_2d::Costmap2D * costmap, - std::vector & angles); + // GridCollisionChecker( + // nav2_costmap_2d::Costmap2D * costmap, + // std::vector & angles); /** * @brief Set the footprint to use with collision checker @@ -91,6 +91,15 @@ class GridCollisionChecker */ float getCost(); + /** + * @brief Get the angles of the precomputed footprint orientations + * @return the ordered vector of angles corresponding to footprints + */ + std::vector & getPrecomputedAngles() + { + return angles_; + } + protected: std::vector oriented_footprints_; nav2_costmap_2d::Footprint unoriented_footprint_; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index b889e44143..cceadbdeeb 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -69,7 +69,7 @@ struct LatticeMotionTable * @param node Ptr to NodeLattice * @return A set of motion poses */ - MotionPoses getMotionPrimitives(const NodeLattice * node); + MotionPrimitives getMotionPrimitives(const NodeLattice * node); /** * @brief Get file metadata needed @@ -92,7 +92,7 @@ struct LatticeMotionTable * @param bin_idx Index of the bin * @return Raw orientation in radians */ - float getAngleFromBin(const unsigned int & bin_idx); + float & getAngleFromBin(const unsigned int & bin_idx); unsigned int size_x; unsigned int num_angle_quantization; @@ -157,21 +157,21 @@ class NodeLattice void reset(); /** - * @brief Sets the motion primitive index used to achieve node in search - * @param reference to motion primitive idx + * @brief Sets the motion primitive used to achieve node in search + * @param pointer to motion primitive */ - inline void setMotionPrimitiveIndex(const unsigned int & idx) + inline void setMotionPrimitive(MotionPrimitive * prim) { - _motion_primitive_index = idx; + _motion_primitive = prim; } /** - * @brief Gets the motion primitive index used to achieve node in search - * @return reference to motion primitive idx + * @brief Gets the motion primitive used to achieve node in search + * @return pointer to motion primitive */ - inline unsigned int & getMotionPrimitiveIndex() + inline MotionPrimitive * getMotionPrimitive() { - return _motion_primitive_index; + return _motion_primitive; } /** @@ -230,9 +230,15 @@ class NodeLattice /** * @brief Check if this node is valid * @param traverse_unknown If we can explore unknown nodes on the graph + * @param collision_checker Collision checker object to aid in validity checking + * @param primitive Optional argument if needing to check over a primitive + * not only a terminal pose * @return whether this node is valid and collision free */ - bool isNodeValid(const bool & traverse_unknown, GridCollisionChecker * collision_checker); + bool isNodeValid( + const bool & traverse_unknown, + GridCollisionChecker * collision_checker, + MotionPrimitive * primitive = nullptr); /** * @brief Get traversal cost of parent node to child node @@ -381,7 +387,7 @@ class NodeLattice float _accumulated_cost; unsigned int _index; bool _was_visited; - unsigned int _motion_primitive_index; + MotionPrimitive * _motion_primitive; }; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/include/nav2_smac_planner/types.hpp b/nav2_smac_planner/include/nav2_smac_planner/types.hpp index 09c4436f2b..741c32f103 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/types.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/types.hpp @@ -109,6 +109,11 @@ struct MotionPose : _x(x), _y(y), _theta(theta) {} + MotionPose operator-(const MotionPose & p2) + { + return MotionPose(this->_x - p2._x, this->_y - p2._y, this->_theta - p2._theta); + } + float _x; float _y; float _theta; @@ -148,6 +153,8 @@ struct MotionPrimitive MotionPoses poses; }; +typedef std::vector MotionPrimitives; + } // namespace nav2_smac_planner #endif // NAV2_SMAC_PLANNER__TYPES_HPP_ diff --git a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp index ab55befafd..e486dae71f 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp @@ -46,21 +46,6 @@ inline geometry_msgs::msg::Pose getWorldCoords( return msg; } -/** -* @brief Create quaternion from A* coord bins -* @param theta continuous bin coordinates angle -* @return quaternion orientation in map frame -*/ -inline geometry_msgs::msg::Quaternion getWorldOrientation( - const float & theta, - const float & bin_size) -{ - // theta is in continuous bin coordinates, must convert to world orientation - tf2::Quaternion q; - q.setEuler(0.0, 0.0, theta * static_cast(bin_size)); - return tf2::toMsg(q); -} - /** * @brief Create quaternion from radians * @param theta continuous bin coordinates angle diff --git a/nav2_smac_planner/src/a_star.cpp b/nav2_smac_planner/src/a_star.cpp index 09f450e36e..5e139c9823 100644 --- a/nav2_smac_planner/src/a_star.cpp +++ b/nav2_smac_planner/src/a_star.cpp @@ -332,8 +332,53 @@ bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path return path.size() > 0; } -template -bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path) +template<> +bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path) +{ + if (!node->parent) { + return false; + } + + NodePtr current_node = node; + MotionPrimitive * prim = nullptr; + const float & grid_resolution = NodeLattice::motion_table.lattice_metadata.grid_resolution; + + while (current_node->parent) { + prim = current_node->getMotionPrimitive(); + // if motion primitive is valid, then was searched (rather than analytically expanded), + // include dense path of subpoints making up the primitive at grid resolution + if (prim) { + Coordinates initial_pose, prim_pose; + initial_pose.x = current_node->pose.x - (prim->poses.back()._x / grid_resolution); + initial_pose.y = current_node->pose.y - (prim->poses.back()._y / grid_resolution); + initial_pose.theta = NodeLattice::motion_table.getAngleFromBin(prim->start_angle); /*rad*/ + + for (auto it = prim->poses.rbegin(); it != prim->poses.rend(); ++it) { + // Convert primitive pose into grid space if it should be checked + prim_pose.x = initial_pose.x + (it->_x / grid_resolution); + prim_pose.y = initial_pose.y + (it->_y / grid_resolution); + prim_pose.theta = initial_pose.theta + it->_theta; /*rad*/ + if (prim_pose.theta < 0.0) { + prim_pose.theta += 2.0 * M_PI; + } + if (prim_pose.theta > 2.0 * M_PI) { + prim_pose.theta -= 2.0 * M_PI; + } + path.push_back(prim_pose); + } + } else { + path.push_back(current_node->pose); + // Convert angle to radians + path.back().theta = NodeLattice::motion_table.getAngleFromBin(path.back().theta); + } + current_node = current_node->parent; + } + + return path.size() > 0; +} + +template<> +bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path) { if (!node->parent) { return false; @@ -343,6 +388,8 @@ bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path) while (current_node->parent) { path.push_back(current_node->pose); + // Convert angle to radians + path.back().theta = NodeHybrid::motion_table.getAngleFromBin(path.back().theta); current_node = current_node->parent; } diff --git a/nav2_smac_planner/src/collision_checker.cpp b/nav2_smac_planner/src/collision_checker.cpp index 172eb8abb7..d9af6d0bf8 100644 --- a/nav2_smac_planner/src/collision_checker.cpp +++ b/nav2_smac_planner/src/collision_checker.cpp @@ -30,13 +30,13 @@ GridCollisionChecker::GridCollisionChecker( } } -GridCollisionChecker::GridCollisionChecker( - nav2_costmap_2d::Costmap2D * costmap, - std::vector & angles) -: FootprintCollisionChecker(costmap), - angles_(angles) -{ -} +// GridCollisionChecker::GridCollisionChecker( +// nav2_costmap_2d::Costmap2D * costmap, +// std::vector & angles) +// : FootprintCollisionChecker(costmap), +// angles_(angles) +// { +// } void GridCollisionChecker::setFootprint( const nav2_costmap_2d::Footprint & footprint, diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index 6a09c3c413..efdf156f44 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -109,27 +109,13 @@ void LatticeMotionTable::initMotionModel( } } -MotionPoses LatticeMotionTable::getMotionPrimitives(const NodeLattice * node) +MotionPrimitives LatticeMotionTable::getMotionPrimitives(const NodeLattice * node) { - // TODO get full, include primitive ID, somehow communicate more than just an end pose? - // we will likely want to know the motion primitive index (0-104) - //That the lattice node will store for the backtrace - - std::vector & prims_at_heading = motion_primitives[node->pose.theta]; - MotionPoses primitive_projection_list; - primitive_projection_list.reserve(prims_at_heading.size()); - - std::vector::const_iterator it; - for(it = prims_at_heading.begin(); it != prims_at_heading.end(); ++it) { - const MotionPose & end_pose = it->poses.back(); - primitive_projection_list.emplace_back( - node->pose.x + (end_pose._x / lattice_metadata.grid_resolution), - node->pose.y + (end_pose._y / lattice_metadata.grid_resolution), - it->end_angle /*this is the ending angular bin*/); - } + MotionPrimitives & prims_at_heading = motion_primitives[node->pose.theta]; + MotionPrimitives primitive_projection_list = prims_at_heading; if (allow_reverse_expansion) { - // Find heading bin of the reverse expansion + // Find normalized heading bin of the reverse expansion double reserve_heading = node->pose.theta - (num_angle_quantization / 2); if (reserve_heading < 0) { reserve_heading += num_angle_quantization; @@ -137,15 +123,12 @@ MotionPoses LatticeMotionTable::getMotionPrimitives(const NodeLattice * node) if (reserve_heading > num_angle_quantization) { reserve_heading -= num_angle_quantization; } + prims_at_heading = motion_primitives[reserve_heading]; - std::vector::const_iterator it; - for(it = prims_at_heading.begin(); it != prims_at_heading.end(); ++it) { - const MotionPose & end_pose = it->poses.back(); - primitive_projection_list.emplace_back( - node->pose.x + (end_pose._x / lattice_metadata.grid_resolution), - node->pose.y + (end_pose._y / lattice_metadata.grid_resolution), - it->end_angle /*this is the ending angular bin*/); - } + primitive_projection_list.insert( + primitive_projection_list.end(), + prims_at_heading.begin(), + prims_at_heading.end()); } return primitive_projection_list; @@ -180,7 +163,7 @@ unsigned int LatticeMotionTable::getClosestAngularBin(const double & theta) return closest_idx; } -float LatticeMotionTable::getAngleFromBin(const unsigned int & bin_idx) +float & LatticeMotionTable::getAngleFromBin(const unsigned int & bin_idx) { return lattice_metadata.heading_angles[bin_idx]; } @@ -191,7 +174,8 @@ NodeLattice::NodeLattice(const unsigned int index) _cell_cost(std::numeric_limits::quiet_NaN()), _accumulated_cost(std::numeric_limits::max()), _index(index), - _was_visited(false) + _was_visited(false), + _motion_primitive(nullptr) { } @@ -209,21 +193,69 @@ void NodeLattice::reset() pose.x = 0.0f; pose.y = 0.0f; pose.theta = 0.0f; + _motion_primitive = nullptr; } bool NodeLattice::isNodeValid( const bool & traverse_unknown, - GridCollisionChecker * collision_checker) + GridCollisionChecker * collision_checker, + MotionPrimitive * motion_primitive) { - // TODO(steve) if primitive longer than 1.5 cells, then we need to split into 1 cell - // increments and collision check across them + // Check primitive end pose + // Convert grid quantization of primitives to radians, then collision checker quantization + static const double bin_size = 2.0 * M_PI / collision_checker->getPrecomputedAngles().size(); + const double & angle = motion_table.getAngleFromBin(this->pose.theta) / bin_size; if (collision_checker->inCollision( - this->pose.x, this->pose.y, this->pose.theta /*bin number*/, traverse_unknown)) + this->pose.x, this->pose.y, angle /*bin in collision checker*/, traverse_unknown)) { return false; } - _cell_cost = collision_checker->getCost(); + // Set the cost of a node to the highest cost across the primitive + float max_cell_cost = collision_checker->getCost(); + + // If valid motion primitives are set, check intermediary poses > 1 cell apart + if (motion_primitive) { + const float & grid_resolution = motion_table.lattice_metadata.grid_resolution; + const float & resolution_diag_sq = 2.0 * grid_resolution * grid_resolution; + MotionPose last_pose(1e9, 1e9, 1e9), pose_dist(0.0, 0.0, 0.0); + + // Back out the initial node starting point to move motion primitive relative to + MotionPose initial_pose, prim_pose; + initial_pose._x = this->pose.x - (motion_primitive->poses.back()._x / grid_resolution); + initial_pose._y = this->pose.y - (motion_primitive->poses.back()._y / grid_resolution); + initial_pose._theta = motion_table.getAngleFromBin(motion_primitive->start_angle); /*rad*/ + + for (auto it = motion_primitive->poses.begin(); it != motion_primitive->poses.end(); ++it) { + // poses are in metric coordinates from (0, 0), not grid space yet + pose_dist = *it - last_pose; + // Avoid square roots by (hypot(x, y) > res) == (x*x+y*y > diag*diag) + if (pose_dist._x * pose_dist._x + pose_dist._y * pose_dist._y > resolution_diag_sq) { + last_pose = *it; + // Convert primitive pose into grid space if it should be checked + prim_pose._x = initial_pose._x + (it->_x / grid_resolution); + prim_pose._y = initial_pose._y + (it->_y / grid_resolution); + prim_pose._theta = initial_pose._theta + it->_theta; /*rad*/ + if (prim_pose._theta < 0.0) { + prim_pose._theta += 2.0 * M_PI; + } + if (prim_pose._theta > 2.0 * M_PI) { + prim_pose._theta -= 2.0 * M_PI; + } + if (collision_checker->inCollision( + prim_pose._x, + prim_pose._y, + prim_pose._theta / bin_size /*bin in collision checker*/, + traverse_unknown)) + { + return false; + } + max_cell_cost = std::max(max_cell_cost, collision_checker->getCost()); + } + } + } + + _cell_cost = max_cell_cost; return true; } @@ -379,29 +411,36 @@ void NodeLattice::getNeighbors( { unsigned int index = 0; NodePtr neighbor = nullptr; - Coordinates initial_node_coords; - const MotionPoses motion_primitives = motion_table.getMotionPrimitives(this); + Coordinates initial_node_coords, motion_projection; + MotionPrimitives motion_primitives = motion_table.getMotionPrimitives(this); + const float & grid_resolution = motion_table.lattice_metadata.grid_resolution; for (unsigned int i = 0; i != motion_primitives.size(); i++) { + const MotionPose & end_pose = motion_primitives[i].poses.back(); + motion_projection.x = this->pose.x + (end_pose._x / grid_resolution); + motion_projection.y = this->pose.y + (end_pose._y / grid_resolution); + motion_projection.theta = motion_primitives[i].end_angle /*this is the ending angular bin*/; index = NodeLattice::getIndex( - static_cast(motion_primitives[i]._x), - static_cast(motion_primitives[i]._y), - static_cast(motion_primitives[i]._theta)); + static_cast(motion_projection.x), + static_cast(motion_projection.y), + static_cast(motion_projection.theta)); if (NeighborGetter(index, neighbor) && !neighbor->wasVisited()) { - // For State Lattice, the poses are exact bin increments and the pose - // can be derived from the index alone. - // However, we store them as if they were continuous so that it may be - // leveraged by the analytic expansion tool to accelerate goal approaches, - // collision checking, and backtracing (even if not strictly necessary). + // Cache the initial pose in case it was visited but valid + // don't want to disrupt continuous coordinate expansion + initial_node_coords = neighbor->pose; neighbor->setPose( Coordinates( - motion_primitives[i]._x, - motion_primitives[i]._y, - motion_primitives[i]._theta)); - if (neighbor->isNodeValid(traverse_unknown, collision_checker)) { - neighbor->setMotionPrimitiveIndex(i); + motion_projection.x, + motion_projection.y, + motion_projection.theta)); + // Using a special isNodeValid API here, giving the motion primitive to use to + // validity check the transition of the current node to the new node over + if (neighbor->isNodeValid(traverse_unknown, collision_checker, &motion_primitives[i])) { + neighbor->setMotionPrimitive(&motion_primitives[i]); neighbors.push_back(neighbor); + } else { + neighbor->setPose(initial_node_coords); } } } diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index d86f6d2afd..660248bb20 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -324,7 +324,7 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan( plan.poses.reserve(path.size()); for (int i = path.size() - 1; i >= 0; --i) { pose.pose = getWorldCoords(path[i].x, path[i].y, costmap); - pose.pose.orientation = getWorldOrientation(path[i].theta, _angle_bin_size); + pose.pose.orientation = getWorldOrientation(path[i].theta); plan.poses.push_back(pose); } diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 8bb8bbb40e..600d2569a1 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -122,8 +122,14 @@ void SmacPlannerLattice::configure( static_cast(lookup_table_size) / static_cast(_costmap->getResolution() * _downsampling_factor); - // Initialize collision checker - _collision_checker = GridCollisionChecker(_costmap, _metadata.heading_angles); + // Initialize collision checker using 72 evenly sized bins instead of the lattice + // heading angles. This is done so that we have precomputed angles every 5 degrees. + // If we used the sparse lattice headings (usually 16), then when we attempt to collision + // check for intermediary points of the primitives, we're forced to round to one of the 16 + // increments causing "wobbly" checks that could cause larger robots to virtually show collisions + // in valid configurations. This approximation helps to bound orientation error for all checks + // in exchange for slight inaccuracies in the collision headings in terminal search states. + _collision_checker = GridCollisionChecker(_costmap, 72u); _collision_checker.setFootprint( costmap_ros->getRobotFootprint(), costmap_ros->getUseRadius(), @@ -269,8 +275,7 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( plan.poses.reserve(path.size()); for (int i = path.size() - 1; i >= 0; --i) { pose.pose = getWorldCoords(path[i].x, path[i].y, costmap); - pose.pose.orientation = getWorldOrientation( - NodeLattice::motion_table.getAngleFromBin(path[i].theta)); + pose.pose.orientation = getWorldOrientation(path[i].theta); plan.poses.push_back(pose); } diff --git a/nav2_smac_planner/test/test_nodelattice.cpp b/nav2_smac_planner/test/test_nodelattice.cpp index 964fb8c937..2ec9083fec 100644 --- a/nav2_smac_planner/test/test_nodelattice.cpp +++ b/nav2_smac_planner/test/test_nodelattice.cpp @@ -102,17 +102,19 @@ TEST(NodeLatticeTest, test_node_lattice_neighbors) nav2_smac_planner::NodeLattice aNode(0); aNode.setPose( nav2_smac_planner::NodeHybrid::Coordinates(0, 0, 0) ); - nav2_smac_planner::MotionPoses projections = nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives( &aNode); + nav2_smac_planner::MotionPrimitives projections = nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives(&aNode); - EXPECT_NEAR(projections[0]._x, 0.13333, 0.01); - EXPECT_NEAR(projections[0]._y, 0.0, 0.01); - EXPECT_NEAR(projections[0]._theta, 0.0, 0.01); + // TODO meaning of returns have changed + // EXPECT_NEAR(projections[0]._x, 0.13333, 0.01); + // EXPECT_NEAR(projections[0]._y, 0.0, 0.01); + // EXPECT_NEAR(projections[0]._theta, 0.0, 0.01); aNode.setPose(nav2_smac_planner::NodeHybrid::Coordinates(0, 0, 1)); - projections = nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives( &aNode); + projections = nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives(&aNode); - EXPECT_NEAR(projections[0]._x, -0.13333, 0.01); - EXPECT_NEAR(projections[0]._y, 0.0, 0.01); - EXPECT_NEAR(projections[0]._theta, 3.14, 0.01); + // TODO meaning of returns have changed + // EXPECT_NEAR(projections[0]._x, -0.13333, 0.01); + // EXPECT_NEAR(projections[0]._y, 0.0, 0.01); + // EXPECT_NEAR(projections[0]._theta, 3.14, 0.01); } \ No newline at end of file From 461d2faab09da6fb63e5860552c3bf00de830fba Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 14 Oct 2021 15:54:52 -0700 Subject: [PATCH 07/31] adding traversal function --- .../nav2_smac_planner/node_lattice.hpp | 18 +++++ nav2_smac_planner/src/node_lattice.cpp | 69 ++++++++++++++++++- 2 files changed, 85 insertions(+), 2 deletions(-) diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index cceadbdeeb..208fbf9680 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -227,6 +227,23 @@ class NodeLattice return _index; } + /** + * @brief Sets that this primitive is moving in reverse + */ + inline void backwards() + { + _backwards = true; + } + + /** + * @brief Gets if this primitive is moving in reverse + * @return backwards If moving in reverse + */ + inline bool & isBackward() + { + return _backwards; + } + /** * @brief Check if this node is valid * @param traverse_unknown If we can explore unknown nodes on the graph @@ -388,6 +405,7 @@ class NodeLattice unsigned int _index; bool _was_visited; MotionPrimitive * _motion_primitive; + bool _backwards; }; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index efdf156f44..4982f89f67 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -175,7 +175,8 @@ NodeLattice::NodeLattice(const unsigned int index) _accumulated_cost(std::numeric_limits::max()), _index(index), _was_visited(false), - _motion_primitive(nullptr) + _motion_primitive(nullptr), + _backwards(false) { } @@ -194,6 +195,7 @@ void NodeLattice::reset() pose.y = 0.0f; pose.theta = 0.0f; _motion_primitive = nullptr; + _backwards = false; } bool NodeLattice::isNodeValid( @@ -261,7 +263,56 @@ bool NodeLattice::isNodeValid( float NodeLattice::getTraversalCost(const NodePtr & child) { - return 0.0; // TODO(josh): cost of different angles, changing, nonstraight, backwards, distance + const float normalized_cost = child->getCost() / 252.0; + if (std::isnan(normalized_cost)) { + throw std::runtime_error( + "Node attempted to get traversal " + "cost without a known collision cost!"); + } + + // this is the first node + MotionPrimitive * prim = this->getMotionPrimitive(); + MotionPrimitive * transition_prim = child->getMotionPrimitive(); + if (prim == nullptr) { + return transition_prim->trajectory_length; + } + + // Note(stevemacenski): `travel_cost_raw` at one point contained a term: + // `+ motion_table.cost_penalty * normalized_cost;` + // It has been removed, but we may want to readdress this point and determine + // the technically and theoretically correctness of that choice. I feel technically speaking + // that term has merit, but it doesn't seem to impact performance or path quality. + // W/o it lowers the travel cost, which would drive the heuristics up proportionally where I + // would expect it to plan much faster in all cases, but I only see it in some cases. Since + // this term would weight against moving to high cost zones, I would expect to see more smooth + // central motion, but I only see it in some cases, possibly because the obstacle heuristic is + // already driving the robot away from high cost areas; implicitly handling this. However, + // then I would expect that not adding it here would make it unbalanced enough that path quality + // would suffer, which I did not see in my limited experimentation, possibly due to the smoother. + float travel_cost = 0.0; + float travel_cost_raw = transition_prim->trajectory_length; + + if (transition_prim->arc_length < 0.001) { + // New motion is a straight motion, no additional costs to be applied + travel_cost = travel_cost_raw; + } else { + if (prim->left == transition_prim->left) { + // Turning motion but keeps in same general direction: encourages to commit to actions + travel_cost = travel_cost_raw * motion_table.non_straight_penalty; + } else { + // Turning motion and velocity directions: penalizes wiggling. + travel_cost = travel_cost_raw * + (motion_table.non_straight_penalty + motion_table.change_penalty); + } + } + + // If backwards flag is set, this primitive is moving in reverse + if (this->isBackward()) { + // reverse direction + travel_cost *= motion_table.reverse_penalty; + } + + return travel_cost; } float NodeLattice::getHeuristicCost( @@ -415,6 +466,14 @@ void NodeLattice::getNeighbors( MotionPrimitives motion_primitives = motion_table.getMotionPrimitives(this); const float & grid_resolution = motion_table.lattice_metadata.grid_resolution; + unsigned int direction_change_idx = 1e9; + for (unsigned int i = 0; i != motion_primitives.size(); i++) { + if (motion_primitives[0].start_angle != motion_primitives[i].start_angle) { + direction_change_idx = i; + break; + } + } + for (unsigned int i = 0; i != motion_primitives.size(); i++) { const MotionPose & end_pose = motion_primitives[i].poses.back(); motion_projection.x = this->pose.x + (end_pose._x / grid_resolution); @@ -438,6 +497,12 @@ void NodeLattice::getNeighbors( // validity check the transition of the current node to the new node over if (neighbor->isNodeValid(traverse_unknown, collision_checker, &motion_primitives[i])) { neighbor->setMotionPrimitive(&motion_primitives[i]); + // Marking if this search was obtained in the reverse direction + if ((!this->isBackward() && i >= direction_change_idx) || + (this->isBackward() && i <= direction_change_idx)) + { + neighbor->backwards(); + } neighbors.push_back(neighbor); } else { neighbor->setPose(initial_node_coords); From 1d7199282656fec0c11d698c73b2b21b8591e4a5 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Mon, 18 Oct 2021 15:01:40 -0700 Subject: [PATCH 08/31] adding test coverage and passing for node lattice --- .../nav2_smac_planner/analytic_expansion.hpp | 10 +- .../nav2_smac_planner/collision_checker.hpp | 2 +- .../nav2_smac_planner/node_lattice.hpp | 3 +- .../smac_planner_lattice.hpp | 1 - .../include/nav2_smac_planner/smoother.hpp | 6 +- .../include/nav2_smac_planner/types.hpp | 12 +- .../include/nav2_smac_planner/utils.hpp | 48 +- nav2_smac_planner/src/analytic_expansion.cpp | 6 +- nav2_smac_planner/src/node_lattice.cpp | 32 +- .../src/smac_planner_lattice.cpp | 2 +- nav2_smac_planner/test/CMakeLists.txt | 14 +- nav2_smac_planner/test/output.json | 5689 ++++++++--------- nav2_smac_planner/test/test_nodehybrid.cpp | 1 - nav2_smac_planner/test/test_nodelattice.cpp | 292 +- 14 files changed, 2892 insertions(+), 3226 deletions(-) diff --git a/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp b/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp index b45127de1e..679a7cd2cd 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp @@ -16,6 +16,7 @@ #define NAV2_SMAC_PLANNER__ANALYTIC_EXPANSION_HPP_ #include +#include #include "nav2_smac_planner/node_2d.hpp" #include "nav2_smac_planner/node_hybrid.hpp" @@ -30,7 +31,6 @@ template class AnalyticExpansion { public: - typedef NodeT * NodePtr; typedef typename NodeT::Coordinates Coordinates; typedef std::function NodeGetter; @@ -95,7 +95,9 @@ class AnalyticExpansion * @param getter The function object that gets valid nodes from the graph * @return A set of analytically expanded nodes to the goal from current node, if possible */ - AnalyticExpansionNodes getAnalyticPath(const NodePtr & node, const NodePtr & goal, const NodeGetter & getter); + AnalyticExpansionNodes getAnalyticPath( + const NodePtr & node, const NodePtr & goal, + const NodeGetter & getter); /** * @brief Takes final analytic expansion and appends to current expanded node @@ -104,7 +106,9 @@ class AnalyticExpansion * @param expanded_nodes Expanded nodes to append to end of current search path * @return Node pointer to goal node if successful, else return nullptr */ - NodePtr setAnalyticPath(const NodePtr & node, const NodePtr & goal, const AnalyticExpansionNodes & expanded_nodes); + NodePtr setAnalyticPath( + const NodePtr & node, const NodePtr & goal, + const AnalyticExpansionNodes & expanded_nodes); protected: MotionModel _motion_model; diff --git a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp index 27170c5689..7057cac501 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp @@ -93,7 +93,7 @@ class GridCollisionChecker /** * @brief Get the angles of the precomputed footprint orientations - * @return the ordered vector of angles corresponding to footprints + * @return the ordered vector of angles corresponding to footprints */ std::vector & getPrecomputedAngles() { diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index 208fbf9680..33fd64348c 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -15,6 +15,8 @@ #ifndef NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_ #define NAV2_SMAC_PLANNER__NODE_LATTICE_HPP_ +#include + #include #include #include @@ -25,7 +27,6 @@ #include #include #include -#include #include "ompl/base/StateSpace.h" diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp index 908120eab2..2b935ee090 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp @@ -87,7 +87,6 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner const geometry_msgs::msg::PoseStamped & goal) override; protected: - std::unique_ptr> _a_star; GridCollisionChecker _collision_checker; std::unique_ptr _smoother; diff --git a/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp b/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp index cbadf92f67..02d473e0a8 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp @@ -74,13 +74,15 @@ class Smoother * @param dim Dimension ID of interest * @return dim value */ - inline double getFieldByDim(const geometry_msgs::msg::PoseStamped & msg, const unsigned int & dim); + inline double getFieldByDim( + const geometry_msgs::msg::PoseStamped & msg, + const unsigned int & dim); /** * @brief Set the field value for a given dimension * @param msg Current pose to sample * @param dim Dimension ID of interest - * @param value to set the dimention to for the pose + * @param value to set the dimention to for the pose */ inline void setFieldByDim( geometry_msgs::msg::PoseStamped & msg, const unsigned int dim, diff --git a/nav2_smac_planner/include/nav2_smac_planner/types.hpp b/nav2_smac_planner/include/nav2_smac_planner/types.hpp index 741c32f103..89fcffcc74 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/types.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/types.hpp @@ -128,13 +128,12 @@ typedef std::vector MotionPoses; struct LatticeMetadata { float min_turning_radius; - float primitive_resolution; float grid_resolution; - float max_length; - unsigned int number_of_headings; - std::string output_file; - std::vector heading_angles; - unsigned int number_of_trajectories; + unsigned int number_of_headings; + std::string output_file; + std::vector heading_angles; + unsigned int number_of_trajectories; + std::string motion_model; }; /** @@ -150,6 +149,7 @@ struct MotionPrimitive float trajectory_length; float arc_length; float straight_length; + bool left_turn; MotionPoses poses; }; diff --git a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp index e486dae71f..e9d1f685a7 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp @@ -104,26 +104,25 @@ inline double findCircumscribedCost(std::shared_ptr #include +#include +#include + #include "nav2_smac_planner/analytic_expansion.hpp" namespace nav2_smac_planner @@ -226,7 +229,8 @@ typename AnalyticExpansion::NodePtr AnalyticExpansion::setAnalytic } template<> -typename AnalyticExpansion::AnalyticExpansionNodes AnalyticExpansion::getAnalyticPath( +typename AnalyticExpansion::AnalyticExpansionNodes AnalyticExpansion:: +getAnalyticPath( const NodePtr & node, const NodePtr & goal, const NodeGetter & node_getter) diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index 4982f89f67..5b1918057f 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -66,7 +66,7 @@ void LatticeMotionTable::initMotionModel( // Get the metadata about this minimum control set lattice_metadata = getLatticeMetadata(current_lattice_filepath); std::ifstream latticeFile(current_lattice_filepath); - if(!latticeFile.is_open()) { + if (!latticeFile.is_open()) { throw std::runtime_error("Could not open lattice file"); } nlohmann::json json; @@ -85,24 +85,24 @@ void LatticeMotionTable::initMotionModel( // Populate the motion primitives at each heading angle float prev_start_angle = 0.0; - std::vector primitives; + std::vector primitives; nlohmann::json json_primitives = json["primitives"]; - for(unsigned int i = 0; i < json_primitives.size(); ++i) { - MotionPrimitive new_primitive; - fromJsonToMotionPrimitive(json_primitives[i], new_primitive); + for (unsigned int i = 0; i < json_primitives.size(); ++i) { + MotionPrimitive new_primitive; + fromJsonToMotionPrimitive(json_primitives[i], new_primitive); - if(prev_start_angle != new_primitive.start_angle) { + if (prev_start_angle != new_primitive.start_angle) { motion_primitives.push_back(primitives); - primitives.clear(); + primitives.clear(); prev_start_angle = new_primitive.start_angle; } - primitives.push_back(new_primitive); + primitives.push_back(new_primitive); } motion_primitives.push_back(primitives); // Populate useful precomputed values to be leveraged trig_values.reserve(lattice_metadata.number_of_headings); - for(unsigned int i = 0; i < lattice_metadata.heading_angles.size(); ++i) { + for (unsigned int i = 0; i < lattice_metadata.heading_angles.size(); ++i) { trig_values.emplace_back( cos(lattice_metadata.heading_angles[i]), sin(lattice_metadata.heading_angles[i])); @@ -112,7 +112,7 @@ void LatticeMotionTable::initMotionModel( MotionPrimitives LatticeMotionTable::getMotionPrimitives(const NodeLattice * node) { MotionPrimitives & prims_at_heading = motion_primitives[node->pose.theta]; - MotionPrimitives primitive_projection_list = prims_at_heading; + MotionPrimitives primitive_projection_list = prims_at_heading; if (allow_reverse_expansion) { // Find normalized heading bin of the reverse expansion @@ -137,14 +137,14 @@ MotionPrimitives LatticeMotionTable::getMotionPrimitives(const NodeLattice * nod LatticeMetadata LatticeMotionTable::getLatticeMetadata(const std::string & lattice_filepath) { std::ifstream lattice_file(lattice_filepath); - if(!lattice_file.is_open()) { + if (!lattice_file.is_open()) { throw std::runtime_error("Could not open lattice file!"); } nlohmann::json j; lattice_file >> j; LatticeMetadata metadata; - fromJsonToMetaData(j["latticeMetadata"], metadata); + fromJsonToMetaData(j["lattice_metadata"], metadata); return metadata; } @@ -296,11 +296,11 @@ float NodeLattice::getTraversalCost(const NodePtr & child) // New motion is a straight motion, no additional costs to be applied travel_cost = travel_cost_raw; } else { - if (prim->left == transition_prim->left) { + if (prim->left_turn == transition_prim->left_turn) { // Turning motion but keeps in same general direction: encourages to commit to actions travel_cost = travel_cost_raw * motion_table.non_straight_penalty; } else { - // Turning motion and velocity directions: penalizes wiggling. + // Turning motion and velocity directions: penalizes wiggling. travel_cost = travel_cost_raw * (motion_table.non_straight_penalty + motion_table.change_penalty); } @@ -498,8 +498,8 @@ void NodeLattice::getNeighbors( if (neighbor->isNodeValid(traverse_unknown, collision_checker, &motion_primitives[i])) { neighbor->setMotionPrimitive(&motion_primitives[i]); // Marking if this search was obtained in the reverse direction - if ((!this->isBackward() && i >= direction_change_idx) || - (this->isBackward() && i <= direction_change_idx)) + if ((!this->isBackward() && i >= direction_change_idx) || + (this->isBackward() && i <= direction_change_idx)) { neighbor->backwards(); } diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 600d2569a1..e6f3502b98 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -128,7 +128,7 @@ void SmacPlannerLattice::configure( // check for intermediary points of the primitives, we're forced to round to one of the 16 // increments causing "wobbly" checks that could cause larger robots to virtually show collisions // in valid configurations. This approximation helps to bound orientation error for all checks - // in exchange for slight inaccuracies in the collision headings in terminal search states. + // in exchange for slight inaccuracies in the collision headings in terminal search states. _collision_checker = GridCollisionChecker(_costmap, 72u); _collision_checker.setFootprint( costmap_ros->getRobotFootprint(), diff --git a/nav2_smac_planner/test/CMakeLists.txt b/nav2_smac_planner/test/CMakeLists.txt index 7b65220b93..609b0b4174 100644 --- a/nav2_smac_planner/test/CMakeLists.txt +++ b/nav2_smac_planner/test/CMakeLists.txt @@ -86,15 +86,11 @@ target_link_libraries(test_smac_2d ${library_name}_2d ) -#Test Lattice node -ament_add_gtest(test_lattice_node - test_nodelattice.cpp) +#Test Lattice node +ament_add_gtest(test_lattice_node test_nodelattice.cpp) -ament_target_dependencies(test_lattice_node - ${dependencies} -) +ament_target_dependencies(test_lattice_node ${dependencies}) -target_link_libraries(test_lattice_node - ${library_name} ) +target_link_libraries(test_lattice_node ${library_name}) -install(FILES output.json DESTINATION share/${PROJECT_NAME}) +install(FILES output.json DESTINATION share/${PROJECT_NAME}) diff --git a/nav2_smac_planner/test/output.json b/nav2_smac_planner/test/output.json index bcc46f6c40..07e1bfb1a4 100644 --- a/nav2_smac_planner/test/output.json +++ b/nav2_smac_planner/test/output.json @@ -1,43 +1,42 @@ { "version": 1.0, - "dateGenerated": "2021-06-08", - "latticeMetadata": { - "turningRadius": 0.4, - "stepDistance": 0.005, - "gridSeparation": 0.05, - "maxLength": 1, - "numberOfHeadings": 16, - "outputFile": "output.json", - "headingAngles": [ - -180.0, - -153.43494882292202, - -135.0, - -116.56505117707799, - -90.0, - -63.43494882292201, - -45.0, - -26.56505117707799, + "date_generated": "2021-10-14", + "lattice_metadata": { + "motion_model": "ackermann", + "turning_radius": 0.5, + "grid_resolution": 0.05, + "stopping_threshold": 5, + "num_of_headings": 16, + "output_file": "output.json", + "heading_angles": [ 0.0, - 26.56505117707799, - 45.0, - 63.43494882292201, - 90.0, - 116.56505117707799, - 135.0, - 153.43494882292202, - 180.0 + 0.4636476090008061, + 0.7853981633974483, + 1.1071487177940904, + 1.5707963267948966, + 2.0344439357957027, + 2.356194490192345, + 2.677945044588987, + 3.141592653589793, + -2.677945044588987, + -2.356194490192345, + -2.0344439357957027, + -1.5707963267948966, + -1.1071487177940904, + -0.7853981633974483, + -0.4636476090008061 ], - "numberOfTrajectories": 104 + "number_of_trajectories": 80 }, "primitives": [ { - "trajectoryId": 0, - "startAngle": 0.0, - "endAngle": 0.0, - "radius": 0, - "trajectoryLength": 0.2, - "arcLength": 0.0, - "straightLength": 0.2, + "trajectory_id": 0, + "start_angle_index": 0, + "end_angle_index": 13, + "trajectory_radius": 0.5259, + "trajectory_length": 0.64856, + "arc_length": 0.58225, + "straight_length": 0.06631, "poses": [ [ 0.0, @@ -45,169 +44,131 @@ 0.0 ], [ - 0.06667, - 0.0, - 0.0 + 0.05284, + -0.00266, + -0.10064988343582648 ], [ - 0.13333, - 0.0, - 0.0 - ] - ] - }, - { - "trajectoryId": 1, - "startAngle": 0.0, - "endAngle": 26.56505117707799, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ - [ - 0.0, - 0.0, - 0.07728785079152484 + 0.10515, + -0.01062, + -0.20129976687165296 ], [ - 0.06521, - 0.00505, - 0.23188739606064668 + 0.15639, + -0.02379, + -0.30194965030747944 ], [ - 0.12886, - 0.02008, - 0.38629880480400086 - ] - ] - }, - { - "trajectoryId": 2, - "startAngle": -0.0, - "endAngle": -26.56505117707799, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ - [ - 0.0, - -0.0, - -0.07728785079152484 + 0.20605, + -0.04205, + -0.4025995337433055 ], [ - 0.06521, - -0.00505, - -0.23188739606064668 + 0.25363, + -0.0652, + -0.503249417179132 ], [ - 0.12886, - -0.02008, - -0.38629880480400086 - ] - ] - }, - { - "trajectoryId": 3, - "startAngle": 0.0, - "endAngle": 26.56505117707799, - "radius": 0.8472, - "trajectoryLength": 0.41640225434548295, - "arcLength": 0.39280225434548294, - "straightLength": 0.023599999999999982, - "poses": [ + 0.29864, + -0.09302, + -0.6038993006149584 + ], [ - 0.0, - 0.0, - 0.03316065952958909 + 0.34062, + -0.12521, + -0.7045491840507849 ], [ - 0.05607, - 0.00186, - 0.0992607498429092 + 0.37916, + -0.16147, + -0.805199067486611 ], [ - 0.1119, - 0.00742, - 0.1656174868971147 + 0.41386, + -0.20141, + -0.9058489509224374 ], [ - 0.16724, - 0.01667, - 0.2318357474858811 + 0.44437, + -0.24464, + -1.006498834358264 ], [ - 0.22184, - 0.02956, - 0.2981320120235546 + 0.47038, + -0.29071, + -1.1071487177940904 ], [ - 0.27547, - 0.04604, - 0.36432002602701186 + 0.47038, + -0.29071, + -1.1071487177940904 ], [ - 0.32789, - 0.06603, - 0.43040362056026316 + 0.5, + -0.35, + -1.1071487177940904 ] ] }, { - "trajectoryId": 4, - "startAngle": -0.0, - "endAngle": -26.56505117707799, - "radius": 0.8472, - "trajectoryLength": 0.41640225434548295, - "arcLength": 0.39280225434548294, - "straightLength": 0.023599999999999982, + "trajectory_id": 1, + "start_angle_index": 0, + "end_angle_index": 15, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ 0.0, - -0.0, - -0.03316065952958909 + 0.0, + 0.0 + ], + [ + 0.05884, + -0.00273, + -0.09272952180016114 ], [ - 0.05607, - -0.00186, - -0.0992607498429092 + 0.11717, + -0.0109, + -0.18545904360032228 ], [ - 0.1119, - -0.00742, - -0.1656174868971147 + 0.17449, + -0.02443, + -0.27818856540048387 ], [ - 0.16724, - -0.01667, - -0.2318357474858811 + 0.23031, + -0.04321, + -0.370918087200645 ], [ - 0.22184, - -0.02956, - -0.2981320120235546 + 0.28416, + -0.06708, + -0.46364760900080615 ], [ - 0.27547, - -0.04604, - -0.36432002602701186 + 0.28416, + -0.06708, + -0.4636476090008061 ], [ - 0.32789, - -0.06603, - -0.43040362056026316 + 0.35, + -0.1, + -0.4636476090008061 ] ] }, { - "trajectoryId": 5, - "startAngle": 0.0, - "endAngle": 90.0, - "radius": 0.5, - "trajectoryLength": 0.8353981633974483, - "arcLength": 0.7853981633974483, - "straightLength": 0.050000000000000044, + "trajectory_id": 2, + "start_angle_index": 0, + "end_angle_index": 0, + "trajectory_radius": 0.0, + "trajectory_length": 0.15, + "arc_length": 0.0, + "straight_length": 0.15, "poses": [ [ 0.0, @@ -215,4324 +176,3918 @@ 0.0 ], [ - 0.05, + 0.075, 0.0, - 0.052382193864968965 - ], - [ - 0.10226, - 0.00274, - 0.1571083971448808 - ], - [ - 0.15396, - 0.01093, - 0.26171020631366104 - ], - [ - 0.20451, - 0.02447, - 0.36659768638821083 - ], - [ - 0.25337, - 0.04323, - 0.4712529998754368 - ], - [ - 0.3, - 0.06699, - 0.5759185996183533 + 0.0 ], [ - 0.34389, - 0.09549, - 0.6806484997078908 - ], + 0.15, + 0.0, + 0.0 + ] + ] + }, + { + "trajectory_id": 3, + "start_angle_index": 0, + "end_angle_index": 1, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, + "poses": [ [ - 0.38457, - 0.12843, - 0.7853981633974487 + 0.0, + 0.0, + 0.0 ], [ - 0.42157, - 0.16543, - 0.8901478270870046 + 0.05884, + 0.00273, + 0.09272952180016114 ], [ - 0.45451, - 0.20611, - 0.9948777271765442 + 0.11717, + 0.0109, + 0.18545904360032228 ], [ - 0.48301, - 0.25, - 1.0995433269194588 + 0.17449, + 0.02443, + 0.27818856540048387 ], [ - 0.50677, - 0.29663, - 1.204198640406686 + 0.23031, + 0.04321, + 0.370918087200645 ], [ - 0.52553, - 0.34549, - 1.3090861204812356 + 0.28416, + 0.06708, + 0.46364760900080615 ], [ - 0.53907, - 0.39604, - 1.4136879296500173 + 0.28416, + 0.06708, + 0.4636476090008061 ], [ - 0.54726, - 0.44774, - 1.518414132929926 + 0.35, + 0.1, + 0.4636476090008061 ] ] }, { - "trajectoryId": 6, - "startAngle": -0.0, - "endAngle": -90.0, - "radius": 0.5, - "trajectoryLength": 0.8353981633974483, - "arcLength": 0.7853981633974483, - "straightLength": 0.050000000000000044, + "trajectory_id": 4, + "start_angle_index": 0, + "end_angle_index": 3, + "trajectory_radius": 0.5259, + "trajectory_length": 0.64856, + "arc_length": 0.58225, + "straight_length": 0.06631, "poses": [ [ 0.0, - -0.0, + 0.0, 0.0 ], [ - 0.05, - -0.0, - -0.052382193864968965 - ], - [ - 0.10226, - -0.00274, - -0.1571083971448808 - ], - [ - 0.15396, - -0.01093, - -0.26171020631366104 - ], - [ - 0.20451, - -0.02447, - -0.36659768638821083 + 0.05284, + 0.00266, + 0.10064988343582648 ], [ - 0.25337, - -0.04323, - -0.4712529998754368 + 0.10515, + 0.01062, + 0.20129976687165296 ], [ - 0.3, - -0.06699, - -0.5759185996183533 + 0.15639, + 0.02379, + 0.30194965030747944 ], [ - 0.34389, - -0.09549, - -0.6806484997078908 + 0.20605, + 0.04205, + 0.4025995337433055 ], [ - 0.38457, - -0.12843, - -0.7853981633974487 + 0.25363, + 0.0652, + 0.503249417179132 ], [ - 0.42157, - -0.16543, - -0.8901478270870046 + 0.29864, + 0.09302, + 0.6038993006149584 ], [ - 0.45451, - -0.20611, - -0.9948777271765442 + 0.34062, + 0.12521, + 0.7045491840507849 ], [ - 0.48301, - -0.25, - -1.0995433269194588 + 0.37916, + 0.16147, + 0.805199067486611 ], [ - 0.50677, - -0.29663, - -1.204198640406686 + 0.41386, + 0.20141, + 0.9058489509224374 ], [ - 0.52553, - -0.34549, - -1.3090861204812356 + 0.44437, + 0.24464, + 1.006498834358264 ], [ - 0.53907, - -0.39604, - -1.4136879296500173 - ], - [ - 0.54726, - -0.44774, - -1.518414132929926 - ] - ] - }, - { - "trajectoryId": 7, - "startAngle": 180.0, - "endAngle": 180.0, - "radius": 0, - "trajectoryLength": 0.2, - "arcLength": 0.0, - "straightLength": 0.2, - "poses": [ - [ - -0.0, - 0.0, - 3.141592653589793 + 0.47038, + 0.29071, + 1.1071487177940904 ], [ - -0.06667, - 0.0, - 3.141592653589793 + 0.47038, + 0.29071, + 1.1071487177940904 ], [ - -0.13333, - 0.0, - 3.141592653589793 + 0.5, + 0.35, + 1.1071487177940904 ] ] }, { - "trajectoryId": 8, - "startAngle": 180.0, - "endAngle": 153.43494882292202, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, + "trajectory_id": 5, + "start_angle_index": 1, + "end_angle_index": 15, + "trajectory_radius": 0.5031, + "trajectory_length": 0.46652, + "arc_length": 0.46652, + "straight_length": 0, "poses": [ [ - -0.0, - 0.0, - 3.0643048027982682 + 1e-05, + -1e-05, + 0.46364760900080615 ], [ - -0.06521, - 0.00505, - 2.9097052575291467 + 0.05356, + 0.02299, + 0.3477357067506044 ], [ - -0.12886, - 0.02008, - 2.7552938487857923 - ] - ] - }, - { - "trajectoryId": 9, - "startAngle": 180.0, - "endAngle": 153.43494882292202, - "radius": 0.8472, - "trajectoryLength": 0.41640225434548295, - "arcLength": 0.39280225434548294, - "straightLength": 0.023599999999999982, - "poses": [ - [ - -0.0, - 0.0, - 3.1084319940602043 + 0.10941, + 0.03964, + 0.23182380450040307 ], [ - -0.05607, - 0.00186, - 3.042331903746884 + 0.16682, + 0.04972, + 0.11591190225020132 ], [ - -0.1119, - 0.00742, - 2.9759751666926784 + 0.225, + 0.0531, + 0.0 ], [ - -0.16724, - 0.01667, - 2.909756906103912 + 0.28318, + 0.04972, + -0.11591190225020132 ], [ - -0.22184, - 0.02956, - 2.8434606415662387 + 0.34059, + 0.03964, + -0.23182380450040307 ], [ - -0.27547, - 0.04604, - 2.7772726275627813 + 0.39644, + 0.02299, + -0.3477357067506044 ], [ - -0.32789, - 0.06603, - 2.71118903302953 + 0.44999, + -1e-05, + -0.46364760900080615 ] ] }, { - "trajectoryId": 10, - "startAngle": 180.0, - "endAngle": 90.0, - "radius": 0.5, - "trajectoryLength": 0.8353981633974483, - "arcLength": 0.7853981633974483, - "straightLength": 0.050000000000000044, + "trajectory_id": 6, + "start_angle_index": 1, + "end_angle_index": 15, + "trajectory_radius": 0.6149, + "trajectory_length": 0.57019, + "arc_length": 0.57019, + "straight_length": 0, "poses": [ [ - -0.0, - 0.0, - 3.141592653589793 + 1e-05, + -2e-05, + 0.46364760900080615 ], [ - -0.05, - 0.0, - 3.0892104597248244 + 0.05212, + 0.02308, + 0.370918087200645 + ], + [ + 0.10614, + 0.04126, + 0.27818856540048387 + ], + [ + 0.16161, + 0.05436, + 0.18545904360032228 ], [ - -0.10226, - 0.00274, - 2.9844842564449126 + 0.21806, + 0.06226, + 0.09272952180016114 ], [ - -0.15396, - 0.01093, - 2.8798824472761324 + 0.275, + 0.0649, + 0.0 ], [ - -0.20451, - 0.02447, - 2.7749949672015823 + 0.33194, + 0.06226, + -0.09272952180016114 ], [ - -0.25337, - 0.04323, - 2.6703396537143567 + 0.38839, + 0.05436, + -0.18545904360032228 ], [ - -0.3, - 0.06699, - 2.5656740539714398 + 0.44386, + 0.04126, + -0.27818856540048387 ], [ - -0.34389, - 0.09549, - 2.4609441538819024 + 0.49788, + 0.02308, + -0.370918087200645 ], [ - -0.38457, - 0.12843, - 2.3561944901923444 + 0.54999, + -2e-05, + -0.46364760900080615 + ] + ] + }, + { + "trajectory_id": 7, + "start_angle_index": 1, + "end_angle_index": 0, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, + "poses": [ + [ + 0.0, + 0.0, + 0.4636476090008061 ], [ - -0.42157, - 0.16543, - 2.2514448265027887 + 0.06584, + 0.03292, + 0.4636476090008061 ], [ - -0.45451, - 0.20611, - 2.146714926413249 + 0.06584, + 0.03292, + 0.46364760900080615 ], [ - -0.48301, - 0.25, - 2.0420493266703343 + 0.11969, + 0.05679, + 0.370918087200645 ], [ - -0.50677, - 0.29663, - 1.9373940131831073 + 0.17551, + 0.07557, + 0.27818856540048387 ], [ - -0.52553, - 0.34549, - 1.8325065331085577 + 0.23283, + 0.0891, + 0.18545904360032228 ], [ - -0.53907, - 0.39604, - 1.7279047239397758 + 0.29116, + 0.09727, + 0.09272952180016114 ], [ - -0.54726, - 0.44774, - 1.623178520659867 + 0.35, + 0.1, + 0.0 ] ] }, { - "trajectoryId": 11, - "startAngle": -180.0, - "endAngle": -153.43494882292202, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, + "trajectory_id": 8, + "start_angle_index": 1, + "end_angle_index": 1, + "trajectory_radius": 0.0, + "trajectory_length": 0.22361, + "arc_length": 0.0, + "straight_length": 0.22361, "poses": [ [ - -0.0, - -0.0, - -3.0643048027982682 + 0.0, + 0.0, + 0.4636476090008061 + ], + [ + 0.06667, + 0.03333, + 0.4636476090008061 ], [ - -0.06521, - -0.00505, - -2.9097052575291467 + 0.13333, + 0.06667, + 0.4636476090008061 ], [ - -0.12886, - -0.02008, - -2.7552938487857923 + 0.2, + 0.1, + 0.4636476090008061 ] ] }, { - "trajectoryId": 12, - "startAngle": -180.0, - "endAngle": -153.43494882292202, - "radius": 0.8472, - "trajectoryLength": 0.41640225434548295, - "arcLength": 0.39280225434548294, - "straightLength": 0.023599999999999982, + "trajectory_id": 9, + "start_angle_index": 1, + "end_angle_index": 2, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ - -0.0, - -0.0, - -3.1084319940602043 - ], - [ - -0.05607, - -0.00186, - -3.042331903746884 + 3e-05, + -6e-05, + 0.46364760900080615 ], [ - -0.1119, - -0.00742, - -2.9759751666926784 + 0.06423, + 0.03646, + 0.5708977937996869 ], [ - -0.16724, - -0.01667, - -2.909756906103912 + 0.12415, + 0.07965, + 0.6781479785985676 ], [ - -0.22184, - -0.02956, - -2.8434606415662387 + 0.1791, + 0.129, + 0.7853981633974483 ], [ - -0.27547, - -0.04604, - -2.7772726275627813 + 0.1791, + 0.129, + 0.7853981633974483 ], [ - -0.32789, - -0.06603, - -2.71118903302953 + 0.2, + 0.15, + 0.7853981633974483 ] ] }, { - "trajectoryId": 13, - "startAngle": -180.0, - "endAngle": -90.0, - "radius": 0.5, - "trajectoryLength": 0.8353981633974483, - "arcLength": 0.7853981633974483, - "straightLength": 0.050000000000000044, + "trajectory_id": 10, + "start_angle_index": 2, + "end_angle_index": 0, + "trajectory_radius": 0.5121, + "trajectory_length": 0.44007, + "arc_length": 0.4022, + "straight_length": 0.03787, "poses": [ [ - -0.0, - -0.0, - 3.141592653589793 + -1e-05, + 1e-05, + 0.7853981633974483 ], [ - -0.05, - -0.0, - -3.0892104597248244 + 0.04281, + 0.03828, + 0.6731984257692414 ], [ - -0.10226, - -0.00274, - -2.9844842564449126 + 0.08965, + 0.07151, + 0.5609986881410345 ], [ - -0.15396, - -0.01093, - -2.8798824472761324 + 0.13991, + 0.09929, + 0.4487989505128276 ], [ - -0.20451, - -0.02447, - -2.7749949672015823 + 0.19296, + 0.12126, + 0.3365992128846207 ], [ - -0.25337, - -0.04323, - -2.6703396537143567 + 0.24815, + 0.13716, + 0.2243994752564138 ], [ - -0.3, - -0.06699, - -2.5656740539714398 + 0.30476, + 0.14678, + 0.1121997376282069 ], [ - -0.34389, - -0.09549, - -2.4609441538819024 + 0.3621, + 0.15, + 0.0 ], [ - -0.38457, - -0.12843, - -2.3561944901923444 + 0.3621, + 0.15, + 0.0 ], [ - -0.42157, - -0.16543, - -2.2514448265027887 - ], + 0.4, + 0.15, + 0.0 + ] + ] + }, + { + "trajectory_id": 11, + "start_angle_index": 2, + "end_angle_index": 1, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, + "poses": [ [ - -0.45451, - -0.20611, - -2.146714926413249 + 0.0, + 0.0, + 0.7853981633974483 ], [ - -0.48301, - -0.25, - -2.0420493266703343 + 0.0209, + 0.021, + 0.7853981633974483 ], [ - -0.50677, - -0.29663, - -1.9373940131831073 + 0.0209, + 0.021, + 0.7853981633974483 ], [ - -0.52553, - -0.34549, - -1.8325065331085577 + 0.07585, + 0.07035, + 0.6781479785985676 ], [ - -0.53907, - -0.39604, - -1.7279047239397758 + 0.13577, + 0.11354, + 0.5708977937996869 ], [ - -0.54726, - -0.44774, - -1.623178520659867 + 0.19997, + 0.15006, + 0.46364760900080615 ] ] }, { - "trajectoryId": 14, - "startAngle": 26.56505117707799, - "endAngle": 0.0, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, + "trajectory_id": 12, + "start_angle_index": 2, + "end_angle_index": 2, + "trajectory_radius": 0.0, + "trajectory_length": 0.21213, + "arc_length": 0.0, + "straight_length": 0.21213, "poses": [ [ - 0.01056, - 0.00528, - 0.3862988048040008 + 0.0, + 0.0, + 0.7853981633974483 + ], + [ + 0.05, + 0.05, + 0.7853981633974483 ], [ - 0.07114, - 0.02992, - 0.23188739606064662 + 0.1, + 0.1, + 0.7853981633974483 ], [ - 0.13479, - 0.04495, - 0.07728785079152492 + 0.15, + 0.15, + 0.7853981633974483 ] ] }, { - "trajectoryId": 15, - "startAngle": 26.56505117707799, - "endAngle": 26.56505117707799, - "radius": 0, - "trajectoryLength": 0.223606797749979, - "arcLength": 0.0, - "straightLength": 0.223606797749979, + "trajectory_id": 13, + "start_angle_index": 2, + "end_angle_index": 3, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ 0.0, 0.0, - 0.46358761020085415 + 0.7853981633974483 ], [ - 0.06667, - 0.03333, - 0.4637676138004219 + 0.021, + 0.0209, + 0.7853981633974483 ], [ - 0.13333, - 0.06667, - 0.4635876102008542 - ] - ] - }, - { - "trajectoryId": 16, - "startAngle": 26.56505117707799, - "endAngle": 45.0, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, - "poses": [ - [ - 3e-05, - -6e-05, - 0.5171981083811619 + 0.021, + 0.0209, + 0.7853981633974483 ], [ - 0.06423, - 0.03646, - 0.6245460333019313 + 0.07035, + 0.07585, + 0.892648348196329 ], [ - 0.12415, - 0.07965, - 0.7317583920706332 + 0.11354, + 0.13577, + 0.9998985329952097 ], [ - 0.1791, - 0.129, - 0.0 + 0.15006, + 0.19997, + 1.1071487177940904 ] ] }, { - "trajectoryId": 17, - "startAngle": 26.56505117707799, - "endAngle": 63.43494882292201, - "radius": 0.4472, - "trajectoryLength": 0.28777369585235674, - "arcLength": 0.28777369585235674, - "straightLength": 0, + "trajectory_id": 14, + "start_angle_index": 2, + "end_angle_index": 4, + "trajectory_radius": 0.5121, + "trajectory_length": 0.44007, + "arc_length": 0.4022, + "straight_length": 0.03787, "poses": [ [ - -1e-05, 1e-05, - 0.5279868542628576 + -1e-05, + 0.7853981633974483 ], [ - 0.04968, - 0.02899, - 0.6566815787447414 + 0.03828, + 0.04281, + 0.8975979010256552 ], [ - 0.09523, - 0.0641, - 0.7853981633974483 - ], - [ - 0.1359, - 0.10477, - 0.9141147480501554 - ], - [ - 0.17101, - 0.15032, - 1.0428094725320387 - ] - ] - }, - { - "trajectoryId": 18, - "startAngle": 26.56505117707799, - "endAngle": 0.0, - "radius": 0.6354, - "trajectoryLength": 0.3682016907591122, - "arcLength": 0.2946016907591122, - "straightLength": 0.0736, - "poses": [ - [ - 0.0, - 0.0, - 0.4636476090008061 - ], - [ - 0.06584, - 0.03292, - 0.41724179149883744 - ], - [ - 0.11969, - 0.05679, - 0.324542643361065 + 0.07151, + 0.08965, + 1.009797638653862 ], [ - 0.17551, - 0.07557, - 0.23180039718484172 + 0.09929, + 0.13991, + 1.121997376282069 ], [ - 0.23283, - 0.0891, - 0.13915983516289937 + 0.12126, + 0.19296, + 1.2341971139102759 ], [ - 0.29116, - 0.09727, - 0.046363759097421874 - ] - ] - }, - { - "trajectoryId": 19, - "startAngle": 153.43494882292202, - "endAngle": 180.0, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ - [ - -0.01056, - 0.00528, - 2.7552938487857923 + 0.13716, + 0.24815, + 1.3463968515384828 ], [ - -0.07114, - 0.02992, - 2.9097052575291467 + 0.14678, + 0.30476, + 1.4585965891666897 ], [ - -0.13479, - 0.04495, - 3.0643048027982682 - ] - ] - }, - { - "trajectoryId": 20, - "startAngle": 153.43494882292202, - "endAngle": 153.43494882292202, - "radius": 0, - "trajectoryLength": 0.223606797749979, - "arcLength": 0.0, - "straightLength": 0.223606797749979, - "poses": [ - [ - -0.0, - 0.0, - 2.6780050433889393 + 0.15, + 0.3621, + 1.5707963267948966 ], [ - -0.06667, - 0.03333, - 2.6778250397893713 + 0.15, + 0.3621, + 1.5707963267948966 ], [ - -0.13333, - 0.06667, - 2.678005043388939 + 0.15, + 0.4, + 1.5707963267948966 ] ] }, { - "trajectoryId": 21, - "startAngle": 153.43494882292202, - "endAngle": 135.0, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, + "trajectory_id": 15, + "start_angle_index": 3, + "end_angle_index": 2, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ - -3e-05, -6e-05, - 2.6243945452086312 + 3e-05, + 1.1071487177940904 ], [ - -0.06423, 0.03646, - 2.517046620287862 + 0.06423, + 0.9998985329952097 ], [ - -0.12415, 0.07965, - 2.40983426151916 + 0.12415, + 0.892648348196329 ], [ - -0.1791, 0.129, - 0.0 - ] - ] - }, - { - "trajectoryId": 22, - "startAngle": 153.43494882292202, - "endAngle": 116.56505117707799, - "radius": 0.4472, - "trajectoryLength": 0.28777369585235674, - "arcLength": 0.28777369585235674, - "straightLength": 0, - "poses": [ - [ - 1e-05, - 1e-05, - 2.6136057993269355 - ], - [ - -0.04968, - 0.02899, - 2.484911074845052 - ], - [ - -0.09523, - 0.0641, - 2.356194490192345 + 0.1791, + 0.7853981633974483 ], [ - -0.1359, - 0.10477, - 2.227477905539638 + 0.129, + 0.1791, + 0.7853981633974483 ], [ - -0.17101, - 0.15032, - 2.0987831810577546 + 0.15, + 0.2, + 0.7853981633974483 ] ] }, { - "trajectoryId": 23, - "startAngle": 153.43494882292202, - "endAngle": 180.0, - "radius": 0.6354, - "trajectoryLength": 0.3682016907591122, - "arcLength": 0.2946016907591122, - "straightLength": 0.0736, + "trajectory_id": 16, + "start_angle_index": 3, + "end_angle_index": 3, + "trajectory_radius": 0.0, + "trajectory_length": 0.22361, + "arc_length": 0.0, + "straight_length": 0.22361, "poses": [ [ - -0.0, 0.0, - 2.677945044588987 - ], - [ - -0.06584, - 0.03292, - 2.724350862090956 - ], - [ - -0.11969, - 0.05679, - 2.817050010228728 + 0.0, + 1.1071487177940904 ], [ - -0.17551, - 0.07557, - 2.9097922564049514 + 0.03333, + 0.06667, + 1.1071487177940904 ], [ - -0.23283, - 0.0891, - 3.002432818426894 + 0.06667, + 0.13333, + 1.1071487177940904 ], [ - -0.29116, - 0.09727, - 3.0952288944923714 + 0.1, + 0.2, + 1.1071487177940904 ] ] }, { - "trajectoryId": 24, - "startAngle": -153.43494882292202, - "endAngle": -180.0, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, + "trajectory_id": 17, + "start_angle_index": 3, + "end_angle_index": 4, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - -0.01056, - -0.00528, - -2.7552938487857923 + 0.0, + 0.0, + 1.1071487177940904 ], [ - -0.07114, - -0.02992, - -2.9097052575291467 + 0.03292, + 0.06584, + 1.1071487177940904 ], [ - -0.13479, - -0.04495, - -3.0643048027982682 - ] - ] - }, - { - "trajectoryId": 25, - "startAngle": -153.43494882292202, - "endAngle": -153.43494882292202, - "radius": 0, - "trajectoryLength": 0.223606797749979, - "arcLength": 0.0, - "straightLength": 0.223606797749979, - "poses": [ - [ - -0.0, - -0.0, - -2.6780050433889393 + 0.03292, + 0.06584, + 1.1071487177940904 ], [ - -0.06667, - -0.03333, - -2.6778250397893713 + 0.05679, + 0.11969, + 1.199878239594252 ], [ - -0.13333, - -0.06667, - -2.678005043388939 - ] - ] - }, - { - "trajectoryId": 26, - "startAngle": -153.43494882292202, - "endAngle": -135.0, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, - "poses": [ - [ - -3e-05, - 6e-05, - -2.6243945452086312 + 0.07557, + 0.17551, + 1.2926077613944127 ], [ - -0.06423, - -0.03646, - -2.517046620287862 + 0.0891, + 0.23283, + 1.3853372831945743 ], [ - -0.12415, - -0.07965, - -2.40983426151916 + 0.09727, + 0.29116, + 1.4780668049947359 ], [ - -0.1791, - -0.129, - 0.0 + 0.1, + 0.35, + 1.5707963267948966 ] ] }, { - "trajectoryId": 27, - "startAngle": -153.43494882292202, - "endAngle": -116.56505117707799, - "radius": 0.4472, - "trajectoryLength": 0.28777369585235674, - "arcLength": 0.28777369585235674, - "straightLength": 0, + "trajectory_id": 18, + "start_angle_index": 3, + "end_angle_index": 5, + "trajectory_radius": 0.5031, + "trajectory_length": 0.46652, + "arc_length": 0.46652, + "straight_length": 0, "poses": [ [ - 1e-05, -1e-05, - -2.6136057993269355 - ], - [ - -0.04968, - -0.02899, - -2.484911074845052 - ], - [ - -0.09523, - -0.0641, - -2.356194490192345 - ], - [ - -0.1359, - -0.10477, - -2.227477905539638 - ], - [ - -0.17101, - -0.15032, - -2.0987831810577546 - ] - ] - }, - { - "trajectoryId": 28, - "startAngle": -153.43494882292202, - "endAngle": -180.0, - "radius": 0.6354, - "trajectoryLength": 0.3682016907591122, - "arcLength": 0.2946016907591122, - "straightLength": 0.0736, - "poses": [ - [ - -0.0, - -0.0, - -2.677945044588987 - ], - [ - -0.06584, - -0.03292, - -2.724350862090956 - ], - [ - -0.11969, - -0.05679, - -2.817050010228728 - ], - [ - -0.17551, - -0.07557, - -2.9097922564049514 - ], - [ - -0.23283, - -0.0891, - -3.002432818426894 + 1e-05, + 1.1071487177940904 ], [ - -0.29116, - -0.09727, - -3.0952288944923714 - ] - ] - }, - { - "trajectoryId": 29, - "startAngle": -26.56505117707799, - "endAngle": -0.0, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ - [ - 0.01056, - -0.00528, - -0.3862988048040008 + 0.02299, + 0.05356, + 1.2230606200442917 ], [ - 0.07114, - -0.02992, - -0.23188739606064662 + 0.03964, + 0.10941, + 1.338972522294494 ], [ - 0.13479, - -0.04495, - -0.07728785079152492 - ] - ] - }, - { - "trajectoryId": 30, - "startAngle": -26.56505117707799, - "endAngle": -26.56505117707799, - "radius": 0, - "trajectoryLength": 0.223606797749979, - "arcLength": 0.0, - "straightLength": 0.223606797749979, - "poses": [ - [ - 0.0, - -0.0, - -0.46358761020085415 + 0.04972, + 0.16682, + 1.4548844245446952 ], [ - 0.06667, - -0.03333, - -0.4637676138004219 + 0.0531, + 0.225, + 1.5707963267948966 ], [ - 0.13333, - -0.06667, - -0.4635876102008542 - ] - ] - }, - { - "trajectoryId": 31, - "startAngle": -26.56505117707799, - "endAngle": -45.0, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, - "poses": [ - [ - 3e-05, - 6e-05, - -0.5171981083811619 + 0.04972, + 0.28318, + 1.6867082290450979 ], [ - 0.06423, - -0.03646, - -0.6245460333019313 + 0.03964, + 0.34059, + 1.8026201312952992 ], [ - 0.12415, - -0.07965, - -0.7317583920706332 + 0.02299, + 0.39644, + 1.9185320335455014 ], [ - 0.1791, - -0.129, - 0.0 + -1e-05, + 0.44999, + 2.0344439357957027 ] ] }, { - "trajectoryId": 32, - "startAngle": -26.56505117707799, - "endAngle": -63.43494882292201, - "radius": 0.4472, - "trajectoryLength": 0.28777369585235674, - "arcLength": 0.28777369585235674, - "straightLength": 0, + "trajectory_id": 19, + "start_angle_index": 3, + "end_angle_index": 5, + "trajectory_radius": 0.6149, + "trajectory_length": 0.57019, + "arc_length": 0.57019, + "straight_length": 0, "poses": [ [ - -1e-05, - -1e-05, - -0.5279868542628576 - ], - [ - 0.04968, - -0.02899, - -0.6566815787447414 - ], - [ - 0.09523, - -0.0641, - -0.7853981633974483 + -2e-05, + 1e-05, + 1.1071487177940904 ], [ - 0.1359, - -0.10477, - -0.9141147480501554 + 0.02308, + 0.05212, + 1.199878239594252 ], [ - 0.17101, - -0.15032, - -1.0428094725320387 - ] - ] - }, - { - "trajectoryId": 33, - "startAngle": -26.56505117707799, - "endAngle": -0.0, - "radius": 0.6354, - "trajectoryLength": 0.3682016907591122, - "arcLength": 0.2946016907591122, - "straightLength": 0.0736, - "poses": [ - [ - 0.0, - -0.0, - -0.4636476090008061 + 0.04126, + 0.10614, + 1.2926077613944127 ], [ - 0.06584, - -0.03292, - -0.41724179149883744 + 0.05436, + 0.16161, + 1.3853372831945743 ], [ - 0.11969, - -0.05679, - -0.324542643361065 + 0.06226, + 0.21806, + 1.4780668049947359 ], [ - 0.17551, - -0.07557, - -0.23180039718484172 + 0.0649, + 0.275, + 1.5707963267948966 ], [ - 0.23283, - -0.0891, - -0.13915983516289937 + 0.06226, + 0.33194, + 1.6635258485950573 ], [ - 0.29116, - -0.09727, - -0.046363759097421874 - ] - ] - }, - { - "trajectoryId": 34, - "startAngle": 45.0, - "endAngle": 26.56505117707799, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, - "poses": [ - [ - 0.0, - 0.0, - 0.7877847937108879 + 0.05436, + 0.38839, + 1.7562553703952188 ], [ - 0.0209, - 0.021, - 0.7317583920706331 + 0.04126, + 0.44386, + 1.8489848921953804 ], [ - 0.07585, - 0.07035, - 0.6245460333019313 + 0.02308, + 0.49788, + 1.9417144139955411 ], [ - 0.13577, - 0.11354, - 0.5171981083811618 + -2e-05, + 0.54999, + 2.0344439357957027 ] ] }, { - "trajectoryId": 35, - "startAngle": 45.0, - "endAngle": 63.43494882292201, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, + "trajectory_id": 20, + "start_angle_index": 4, + "end_angle_index": 1, + "trajectory_radius": 0.5259, + "trajectory_length": 0.64856, + "arc_length": 0.58225, + "straight_length": 0.06631, "poses": [ [ 0.0, 0.0, - 0.7830115330840086 - ], - [ - 0.021, - 0.0209, - 0.8390379347242635 + 1.5707963267948966 ], [ - 0.07035, - 0.07585, - 0.9462502934929653 + 0.00266, + 0.05284, + 1.47014644335907 ], [ - 0.11354, - 0.13577, - 1.053598218413735 - ] - ] - }, - { - "trajectoryId": 36, - "startAngle": 45.0, - "endAngle": 45.0, - "radius": 0, - "trajectoryLength": 0.28284271247461906, - "arcLength": 0.0, - "straightLength": 0.28284271247461906, - "poses": [ - [ - 0.0, - 0.0, - 0.7853981633974483 + 0.01062, + 0.10515, + 1.3694965599232436 ], [ - 0.04, - 0.04, - 0.7853981633974483 + 0.02379, + 0.15639, + 1.2688466764874171 ], [ - 0.08, - 0.08, - 0.7853981633974483 + 0.04205, + 0.20605, + 1.1681967930515906 ], [ - 0.12, - 0.12, - 0.7853981633974483 + 0.0652, + 0.25363, + 1.0675469096157642 ], [ - 0.16, - 0.16, - 0.7853981633974483 - ] - ] - }, - { - "trajectoryId": 37, - "startAngle": 45.0, - "endAngle": 0.0, - "radius": 0.5121, - "trajectoryLength": 0.4401023994758333, - "arcLength": 0.4022023994758333, - "straightLength": 0.03789999999999999, - "poses": [ - [ - -1e-05, - 1e-05, - 0.7293464437590259 + 0.09302, + 0.29864, + 0.9668970261799377 ], [ - 0.04281, - 0.03828, - 0.6170310690645247 + 0.12521, + 0.34062, + 0.8662471427441121 ], [ - 0.08965, - 0.07151, - 0.5049335662957414 + 0.16147, + 0.37916, + 0.7655972593082856 ], [ - 0.13991, - 0.09929, - 0.3926342471652681 + 0.20141, + 0.41386, + 0.6649473758724591 ], [ - 0.19296, - 0.12126, - 0.28049992809694807 + 0.24464, + 0.44437, + 0.5642974924366326 ], [ - 0.24815, - 0.13716, - 0.16832663281779695 + 0.29071, + 0.47038, + 0.46364760900080615 ], [ - 0.30476, - 0.14678, - 0.05609734227112698 + 0.29071, + 0.47038, + 0.4636476090008061 ], [ - 0.3621, - 0.15, - 0.0 + 0.35, + 0.5, + 0.4636476090008061 ] ] }, { - "trajectoryId": 38, - "startAngle": 45.0, - "endAngle": 90.0, - "radius": 0.5121, - "trajectoryLength": 0.4401023994758333, - "arcLength": 0.4022023994758333, - "straightLength": 0.03789999999999999, + "trajectory_id": 21, + "start_angle_index": 4, + "end_angle_index": 3, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - 1e-05, - -1e-05, - 0.8414498830358706 + 0.0, + 0.0, + 1.5707963267948966 ], [ - 0.03828, - 0.04281, - 0.953765257730372 + 0.00273, + 0.05884, + 1.4780668049947359 ], [ - 0.07151, - 0.08965, - 1.0658627604991553 + 0.0109, + 0.11717, + 1.3853372831945743 ], [ - 0.09929, - 0.13991, - 1.1781620796296284 + 0.02443, + 0.17449, + 1.2926077613944127 ], [ - 0.12126, - 0.19296, - 1.2902963986979485 + 0.04321, + 0.23031, + 1.199878239594252 ], [ - 0.13716, - 0.24815, - 1.4024696939770998 + 0.06708, + 0.28416, + 1.1071487177940904 ], [ - 0.14678, - 0.30476, - 1.5146989845237697 + 0.06708, + 0.28416, + 1.1071487177940904 ], [ - 0.15, - 0.3621, - 0.0 + 0.1, + 0.35, + 1.1071487177940904 ] ] }, { - "trajectoryId": 39, - "startAngle": 45.0, - "endAngle": 0.0, - "radius": 0.4828, - "trajectoryLength": 0.5327902332882881, - "arcLength": 0.37919023328828805, - "straightLength": 0.15360000000000001, + "trajectory_id": 22, + "start_angle_index": 4, + "end_angle_index": 4, + "trajectory_radius": 0.0, + "trajectory_length": 0.15, + "arc_length": 0.0, + "straight_length": 0.15, "poses": [ [ 0.0, 0.0, - 0.7853981633974483 + 1.5707963267948966 ], [ - 0.0543, - 0.0543, - 0.7852140013369153 + 0.0, + 0.075, + 1.5707963267948966 ], [ - 0.10861, - 0.10859, - 0.0 + 0.0, + 0.15, + 1.5707963267948966 + ] + ] + }, + { + "trajectory_id": 23, + "start_angle_index": 4, + "end_angle_index": 5, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, + "poses": [ + [ + 0.0, + 0.0, + 1.5707963267948966 ], [ - 0.10861, - 0.10859, - 0.7293418448380035 + -0.00273, + 0.05884, + 1.6635258485950573 ], [ - 0.14898, - 0.14467, - 0.6171573764473927 + -0.0109, + 0.11717, + 1.7562553703952188 ], [ - 0.19313, - 0.176, - 0.5048741332179076 + -0.02443, + 0.17449, + 1.8489848921953804 ], [ - 0.24052, - 0.20219, - 0.3927167875987952 + -0.04321, + 0.23031, + 1.9417144139955411 ], [ - 0.29054, - 0.22291, - 0.28050671293185836 + -0.06708, + 0.28416, + 2.0344439357957027 ], [ - 0.34257, - 0.2379, - 0.16815522812227288 + -0.06708, + 0.28416, + 2.0344439357957027 ], [ - 0.39594, - 0.24696, - 0.05617465151812344 + -0.1, + 0.35, + 2.0344439357957027 ] ] }, { - "trajectoryId": 40, - "startAngle": 45.0, - "endAngle": 90.0, - "radius": 0.4828, - "trajectoryLength": 0.5327902332882881, - "arcLength": 0.37919023328828805, - "straightLength": 0.15360000000000001, + "trajectory_id": 24, + "start_angle_index": 4, + "end_angle_index": 7, + "trajectory_radius": 0.5259, + "trajectory_length": 0.64856, + "arc_length": 0.58225, + "straight_length": 0.06631, "poses": [ [ 0.0, 0.0, - 0.7853981633974483 + 1.5707963267948966 ], [ - 0.0543, - 0.0543, - 0.7855823254579813 + -0.00266, + 0.05284, + 1.671446210230723 ], [ - 0.10859, - 0.10861, - 0.0 + -0.01062, + 0.10515, + 1.7720960936665495 + ], + [ + -0.02379, + 0.15639, + 1.872745977102376 + ], + [ + -0.04205, + 0.20605, + 1.9733958605382025 + ], + [ + -0.0652, + 0.25363, + 2.074045743974029 + ], + [ + -0.09302, + 0.29864, + 2.1746956274098554 ], [ - 0.10859, - 0.10861, - 0.8414544819568931 + -0.12521, + 0.34062, + 2.275345510845682 ], [ - 0.14467, - 0.14898, - 0.953638950347504 + -0.16147, + 0.37916, + 2.3759953942815075 ], [ - 0.176, - 0.19313, - 1.065922193576989 + -0.20141, + 0.41386, + 2.476645277717334 ], [ - 0.20219, - 0.24052, - 1.1780795391961014 + -0.24464, + 0.44437, + 2.5772951611531605 ], [ - 0.22291, - 0.29054, - 1.2902896138630382 + -0.29071, + 0.47038, + 2.677945044588987 ], [ - 0.2379, - 0.34257, - 1.4026410986726237 + -0.29071, + 0.47038, + 2.677945044588987 ], [ - 0.24696, - 0.39594, - 1.5146216752767732 + -0.35, + 0.5, + 2.677945044588987 ] ] }, { - "trajectoryId": 41, - "startAngle": 45.0, - "endAngle": -26.56505117707799, - "radius": 0.4251, - "trajectoryLength": 0.5972693578464978, - "arcLength": 0.5309693578464979, - "straightLength": 0.06629999999999997, + "trajectory_id": 25, + "start_angle_index": 5, + "end_angle_index": 3, + "trajectory_radius": 0.5031, + "trajectory_length": 0.46652, + "arc_length": 0.46652, + "straight_length": 0, "poses": [ [ 1e-05, - -1e-05, - 0.7229959773998935 - ], - [ - 0.0398, - 0.0351, - 0.5979871115198812 - ], - [ - 0.08365, - 0.06497, - 0.47317193327021895 + 1e-05, + 2.0344439357957027 ], [ - 0.13088, - 0.08915, - 0.3482719052224635 + -0.02299, + 0.05356, + 1.9185320335455014 ], [ - 0.18076, - 0.10726, - 0.22326778928315447 + -0.03964, + 0.10941, + 1.8026201312952992 ], [ - 0.23251, - 0.11901, - 0.09854341385276191 + -0.04972, + 0.16682, + 1.6867082290450979 ], [ - 0.28531, - 0.12423, - -0.026572443352433615 + -0.0531, + 0.225, + 1.5707963267948966 ], [ - 0.33836, - 0.12282, - -0.15135965367860432 + -0.04972, + 0.28318, + 1.4548844245446952 ], [ - 0.39081, - 0.11482, - -0.2763841013056198 + -0.03964, + 0.34059, + 1.338972522294494 ], [ - 0.44186, - 0.10034, - -0.4011551973058339 + -0.02299, + 0.39644, + 1.2230606200442917 ], [ - 0.49071, - 0.07962, - 0.0 + 1e-05, + 0.44999, + 1.1071487177940904 ] ] }, { - "trajectoryId": 42, - "startAngle": 45.0, - "endAngle": 116.56505117707799, - "radius": 0.4251, - "trajectoryLength": 0.5972693578464978, - "arcLength": 0.5309693578464979, - "straightLength": 0.06629999999999997, + "trajectory_id": 26, + "start_angle_index": 5, + "end_angle_index": 3, + "trajectory_radius": 0.6149, + "trajectory_length": 0.57019, + "arc_length": 0.57019, + "straight_length": 0, "poses": [ [ - -1e-05, + 2e-05, 1e-05, - 0.847800349395003 + 2.0344439357957027 ], [ - 0.0351, - 0.0398, - 0.9728092152750155 + -0.02308, + 0.05212, + 1.9417144139955411 ], [ - 0.06497, - 0.08365, - 1.0976243935246777 + -0.04126, + 0.10614, + 1.8489848921953804 ], [ - 0.08915, - 0.13088, - 1.2225244215724331 + -0.05436, + 0.16161, + 1.7562553703952188 ], [ - 0.10726, - 0.18076, - 1.347528537511742 + -0.06226, + 0.21806, + 1.6635258485950573 ], [ - 0.11901, - 0.23251, - 1.4722529129421347 + -0.0649, + 0.275, + 1.5707963267948966 ], [ - 0.12423, - 0.28531, - 1.5973687701473303 + -0.06226, + 0.33194, + 1.4780668049947359 ], [ - 0.12282, - 0.33836, - 1.722155980473501 + -0.05436, + 0.38839, + 1.3853372831945743 ], [ - 0.11482, - 0.39081, - 1.8471804281005164 + -0.04126, + 0.44386, + 1.2926077613944127 ], [ - 0.10034, - 0.44186, - 1.9719515241007306 + -0.02308, + 0.49788, + 1.199878239594252 ], [ - 0.07962, - 0.49071, - 0.0 + 2e-05, + 0.54999, + 1.1071487177940904 ] ] }, { - "trajectoryId": 43, - "startAngle": 135.0, - "endAngle": 153.43494882292202, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, + "trajectory_id": 27, + "start_angle_index": 5, + "end_angle_index": 4, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - -0.0, 0.0, - 2.353807859878905 + 0.0, + 2.0344439357957027 ], [ - -0.0209, - 0.021, - 2.40983426151916 + -0.03292, + 0.06584, + 2.0344439357957027 ], [ - -0.07585, - 0.07035, - 2.517046620287862 + -0.03292, + 0.06584, + 2.0344439357957027 ], [ - -0.13577, - 0.11354, - 2.6243945452086317 - ] - ] - }, - { - "trajectoryId": 44, - "startAngle": 135.0, - "endAngle": 116.56505117707799, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, - "poses": [ + -0.05679, + 0.11969, + 1.9417144139955411 + ], [ - -0.0, - 0.0, - 2.3585811205057845 + -0.07557, + 0.17551, + 1.8489848921953804 ], [ - -0.021, - 0.0209, - 2.30255471886553 + -0.0891, + 0.23283, + 1.7562553703952188 ], [ - -0.07035, - 0.07585, - 2.195342360096828 + -0.09727, + 0.29116, + 1.6635258485950573 ], [ - -0.11354, - 0.13577, - 2.0879944351760584 + -0.1, + 0.35, + 1.5707963267948966 ] ] }, { - "trajectoryId": 45, - "startAngle": 135.0, - "endAngle": 135.0, - "radius": 0, - "trajectoryLength": 0.28284271247461906, - "arcLength": 0.0, - "straightLength": 0.28284271247461906, + "trajectory_id": 28, + "start_angle_index": 5, + "end_angle_index": 5, + "trajectory_radius": 0.0, + "trajectory_length": 0.22361, + "arc_length": 0.0, + "straight_length": 0.22361, "poses": [ [ - -0.0, 0.0, - 2.356194490192345 - ], - [ - -0.04, - 0.04, - 2.356194490192345 + 0.0, + 2.0344439357957027 ], [ - -0.08, - 0.08, - 2.356194490192345 + -0.03333, + 0.06667, + 2.0344439357957027 ], [ - -0.12, - 0.12, - 2.356194490192345 + -0.06667, + 0.13333, + 2.0344439357957027 ], [ - -0.16, - 0.16, - 2.356194490192345 + -0.1, + 0.2, + 2.0344439357957027 ] ] }, { - "trajectoryId": 46, - "startAngle": 135.0, - "endAngle": 180.0, - "radius": 0.5121, - "trajectoryLength": 0.4401023994758333, - "arcLength": 0.4022023994758333, - "straightLength": 0.03789999999999999, + "trajectory_id": 29, + "start_angle_index": 5, + "end_angle_index": 6, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ - 1e-05, - 1e-05, - 2.412246209830767 - ], - [ - -0.04281, - 0.03828, - 2.5245615845252685 - ], - [ - -0.08965, - 0.07151, - 2.636659087294052 + 6e-05, + 3e-05, + 2.0344439357957027 ], [ - -0.13991, - 0.09929, - 2.748958406424525 + -0.03646, + 0.06423, + 2.1416941205945834 ], [ - -0.19296, - 0.12126, - 2.861092725492845 + -0.07965, + 0.12415, + 2.248944305393464 ], [ - -0.24815, - 0.13716, - 2.9732660207719963 + -0.129, + 0.1791, + 2.356194490192345 ], [ - -0.30476, - 0.14678, - 3.0854953113186663 + -0.129, + 0.1791, + 2.356194490192345 ], [ - -0.3621, - 0.15, - 0.0 + -0.15, + 0.2, + 2.356194490192345 ] ] }, { - "trajectoryId": 47, - "startAngle": 135.0, - "endAngle": 90.0, - "radius": 0.5121, - "trajectoryLength": 0.4401023994758333, - "arcLength": 0.4022023994758333, - "straightLength": 0.03789999999999999, + "trajectory_id": 30, + "start_angle_index": 6, + "end_angle_index": 4, + "trajectory_radius": 0.5121, + "trajectory_length": 0.44007, + "arc_length": 0.4022, + "straight_length": 0.03787, "poses": [ [ -1e-05, -1e-05, - 2.3001427705539226 + 2.356194490192345 ], [ -0.03828, 0.04281, - 2.187827395859421 + 2.243994752564138 ], [ -0.07151, 0.08965, - 2.075729893090638 + 2.131795014935931 ], [ -0.09929, 0.13991, - 1.9634305739601647 + 2.019595277307724 ], [ -0.12126, 0.19296, - 1.8512962548918448 + 1.9073955396795172 ], [ -0.13716, 0.24815, - 1.7391229596126936 + 1.7951958020513104 ], [ -0.14678, 0.30476, - 1.6268936690660236 + 1.6829960644231035 + ], + [ + -0.15, + 0.3621, + 1.5707963267948966 + ], + [ + -0.15, + 0.3621, + 1.5707963267948966 + ], + [ + -0.15, + 0.4, + 1.5707963267948966 + ] + ] + }, + { + "trajectory_id": 31, + "start_angle_index": 6, + "end_angle_index": 5, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, + "poses": [ + [ + 0.0, + 0.0, + 2.356194490192345 + ], + [ + -0.021, + 0.0209, + 2.356194490192345 + ], + [ + -0.021, + 0.0209, + 2.356194490192345 + ], + [ + -0.07035, + 0.07585, + 2.248944305393464 + ], + [ + -0.11354, + 0.13577, + 2.1416941205945834 + ], + [ + -0.15006, + 0.19997, + 2.0344439357957027 + ] + ] + }, + { + "trajectory_id": 32, + "start_angle_index": 6, + "end_angle_index": 6, + "trajectory_radius": 0.0, + "trajectory_length": 0.21213, + "arc_length": 0.0, + "straight_length": 0.21213, + "poses": [ + [ + 0.0, + 0.0, + 2.356194490192345 + ], + [ + -0.05, + 0.05, + 2.356194490192345 + ], + [ + -0.1, + 0.1, + 2.356194490192345 + ], + [ + -0.15, + 0.15, + 2.356194490192345 + ] + ] + }, + { + "trajectory_id": 33, + "start_angle_index": 6, + "end_angle_index": 7, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, + "poses": [ + [ + 0.0, + 0.0, + 2.356194490192345 + ], + [ + -0.0209, + 0.021, + 2.356194490192345 + ], + [ + -0.0209, + 0.021, + 2.356194490192345 + ], + [ + -0.07585, + 0.07035, + 2.4634446749912255 + ], + [ + -0.13577, + 0.11354, + 2.5706948597901063 ], [ - -0.15, - 0.3621, - 0.0 + -0.19997, + 0.15006, + 2.677945044588987 ] ] }, { - "trajectoryId": 48, - "startAngle": 135.0, - "endAngle": 180.0, - "radius": 0.4828, - "trajectoryLength": 0.5327902332882881, - "arcLength": 0.37919023328828805, - "straightLength": 0.15360000000000001, + "trajectory_id": 34, + "start_angle_index": 6, + "end_angle_index": 8, + "trajectory_radius": 0.5121, + "trajectory_length": 0.44007, + "arc_length": 0.4022, + "straight_length": 0.03787, "poses": [ [ - -0.0, - 0.0, + 1e-05, + 1e-05, 2.356194490192345 ], [ - -0.0543, - 0.0543, - 2.356378652252878 + -0.04281, + 0.03828, + 2.4683942278205517 ], [ - -0.10861, - 0.10859, - 0.0 + -0.08965, + 0.07151, + 2.5805939654487586 ], [ - -0.10861, - 0.10859, - 2.4122508087517898 + -0.13991, + 0.09929, + 2.6927937030769655 ], [ - -0.14898, - 0.14467, - 2.5244352771424006 + -0.19296, + 0.12126, + 2.8049934407051724 ], [ - -0.19313, - 0.176, - 2.6367185203718857 + -0.24815, + 0.13716, + 2.9171931783333793 ], [ - -0.24052, - 0.20219, - 2.748875865990998 + -0.30476, + 0.14678, + 3.029392915961586 ], [ - -0.29054, - 0.22291, - 2.8610859406579348 + -0.3621, + 0.15, + -3.141592653589793 ], [ - -0.34257, - 0.2379, - 2.9734374254675204 + -0.3621, + 0.15, + 3.141592653589793 ], [ - -0.39594, - 0.24696, - 3.0854180020716697 + -0.4, + 0.15, + 3.141592653589793 ] ] }, { - "trajectoryId": 49, - "startAngle": 135.0, - "endAngle": 90.0, - "radius": 0.4828, - "trajectoryLength": 0.5327902332882881, - "arcLength": 0.37919023328828805, - "straightLength": 0.15360000000000001, + "trajectory_id": 35, + "start_angle_index": 7, + "end_angle_index": 9, + "trajectory_radius": 0.5031, + "trajectory_length": 0.46652, + "arc_length": 0.46652, + "straight_length": 0, "poses": [ [ - -0.0, - 0.0, - 2.356194490192345 - ], - [ - -0.0543, - 0.0543, - 2.356010328131812 + -1e-05, + -1e-05, + 2.677945044588987 ], [ - -0.10859, - 0.10861, - 0.0 + -0.05356, + 0.02299, + 2.7938569468391883 ], [ - -0.10859, - 0.10861, - 2.3001381716329 + -0.10941, + 0.03964, + 2.9097688490893905 ], [ - -0.14467, - 0.14898, - 2.187953703242289 + -0.16682, + 0.04972, + 3.025680751339592 ], [ - -0.176, - 0.19313, - 2.0756704600128044 + -0.225, + 0.0531, + -3.141592653589793 ], [ - -0.20219, - 0.24052, - 1.963513114393692 + -0.28318, + 0.04972, + -3.025680751339592 ], [ - -0.22291, - 0.29054, - 1.851303039726755 + -0.34059, + 0.03964, + -2.9097688490893905 ], [ - -0.2379, - 0.34257, - 1.7389515549171695 + -0.39644, + 0.02299, + -2.7938569468391883 ], [ - -0.24696, - 0.39594, - 1.62697097831302 + -0.44999, + -1e-05, + -2.677945044588987 ] ] }, { - "trajectoryId": 50, - "startAngle": 135.0, - "endAngle": 206.56505117707798, - "radius": 0.4251, - "trajectoryLength": 0.5972693578464978, - "arcLength": 0.5309693578464979, - "straightLength": 0.06629999999999997, + "trajectory_id": 36, + "start_angle_index": 7, + "end_angle_index": 9, + "trajectory_radius": 0.6149, + "trajectory_length": 0.57019, + "arc_length": 0.57019, + "straight_length": 0, "poses": [ [ -1e-05, - -1e-05, - 2.4185966761898996 + -2e-05, + 2.677945044588987 ], [ - -0.0398, - 0.0351, - 2.543605542069912 + -0.05212, + 0.02308, + 2.7706745663891486 ], [ - -0.08365, - 0.06497, - 2.6684207203195744 + -0.10614, + 0.04126, + 2.8634040881893092 ], [ - -0.13088, - 0.08915, - 2.79332074836733 + -0.16161, + 0.05436, + 2.956133609989471 ], [ - -0.18076, - 0.10726, - 2.918324864306639 + -0.21806, + 0.06226, + 3.0488631317896324 ], [ - -0.23251, - 0.11901, - 3.0430492397370315 + -0.275, + 0.0649, + -3.141592653589793 ], [ - -0.28531, - 0.12423, - -3.1150202102373594 + -0.33194, + 0.06226, + -3.0488631317896324 ], [ - -0.33836, - 0.12282, - -2.9902329999111887 + -0.38839, + 0.05436, + -2.956133609989471 ], [ - -0.39081, - 0.11482, - -2.8652085522841735 + -0.44386, + 0.04126, + -2.8634040881893092 ], [ - -0.44186, - 0.10034, - -2.7404374562839595 + -0.49788, + 0.02308, + -2.7706745663891486 ], [ - -0.49071, - 0.07962, - 0.0 + -0.54999, + -2e-05, + -2.677945044588987 ] ] }, { - "trajectoryId": 51, - "startAngle": 135.0, - "endAngle": 63.43494882292201, - "radius": 0.4251, - "trajectoryLength": 0.5972693578464978, - "arcLength": 0.5309693578464979, - "straightLength": 0.06629999999999997, + "trajectory_id": 37, + "start_angle_index": 7, + "end_angle_index": 6, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ - 1e-05, - 1e-05, - 2.29379230419479 - ], - [ - -0.0351, - 0.0398, - 2.1687834383147777 - ], - [ - -0.06497, - 0.08365, - 2.0439682600651157 - ], - [ - -0.08915, - 0.13088, - 1.9190682320173602 - ], - [ - -0.10726, - 0.18076, - 1.794064116078051 - ], - [ - -0.11901, - 0.23251, - 1.6693397406476584 + -3e-05, + -6e-05, + 2.677945044588987 ], [ - -0.12423, - 0.28531, - 1.544223883442463 + -0.06423, + 0.03646, + 2.5706948597901063 ], [ - -0.12282, - 0.33836, - 1.4194366731162924 + -0.12415, + 0.07965, + 2.4634446749912255 ], [ - -0.11482, - 0.39081, - 1.294412225489277 + -0.1791, + 0.129, + 2.356194490192345 ], [ - -0.10034, - 0.44186, - 1.1696411294890627 + -0.1791, + 0.129, + 2.356194490192345 ], [ - -0.07962, - 0.49071, - 0.0 + -0.2, + 0.15, + 2.356194490192345 ] ] }, { - "trajectoryId": 52, - "startAngle": -135.0, - "endAngle": -153.43494882292202, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, + "trajectory_id": 38, + "start_angle_index": 7, + "end_angle_index": 7, + "trajectory_radius": 0.0, + "trajectory_length": 0.22361, + "arc_length": 0.0, + "straight_length": 0.22361, "poses": [ [ - -0.0, - -0.0, - -2.353807859878905 + 0.0, + 0.0, + 2.677945044588987 ], [ - -0.0209, - -0.021, - -2.40983426151916 + -0.06667, + 0.03333, + 2.677945044588987 ], [ - -0.07585, - -0.07035, - -2.517046620287862 + -0.13333, + 0.06667, + 2.677945044588987 ], [ - -0.13577, - -0.11354, - -2.6243945452086317 + -0.2, + 0.1, + 2.677945044588987 ] ] }, { - "trajectoryId": 53, - "startAngle": -135.0, - "endAngle": -116.56505117707799, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, + "trajectory_id": 39, + "start_angle_index": 7, + "end_angle_index": 8, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - -0.0, - -0.0, - -2.3585811205057845 + 0.0, + 0.0, + 2.677945044588987 ], [ - -0.021, - -0.0209, - -2.30255471886553 + -0.06584, + 0.03292, + 2.677945044588987 ], [ - -0.07035, - -0.07585, - -2.195342360096828 + -0.06584, + 0.03292, + 2.677945044588987 ], [ - -0.11354, - -0.13577, - -2.0879944351760584 - ] - ] - }, - { - "trajectoryId": 54, - "startAngle": -135.0, - "endAngle": -135.0, - "radius": 0, - "trajectoryLength": 0.28284271247461906, - "arcLength": 0.0, - "straightLength": 0.28284271247461906, - "poses": [ - [ - -0.0, - -0.0, - -2.356194490192345 + -0.11969, + 0.05679, + 2.7706745663891486 ], [ - -0.04, - -0.04, - -2.356194490192345 + -0.17551, + 0.07557, + 2.8634040881893092 ], [ - -0.08, - -0.08, - -2.356194490192345 + -0.23283, + 0.0891, + 2.956133609989471 ], [ - -0.12, - -0.12, - -2.356194490192345 + -0.29116, + 0.09727, + 3.0488631317896324 ], [ - -0.16, - -0.16, - -2.356194490192345 + -0.35, + 0.1, + -3.141592653589793 ] ] }, { - "trajectoryId": 55, - "startAngle": -135.0, - "endAngle": -180.0, - "radius": 0.5121, - "trajectoryLength": 0.4401023994758333, - "arcLength": 0.4022023994758333, - "straightLength": 0.03789999999999999, + "trajectory_id": 40, + "start_angle_index": 8, + "end_angle_index": 9, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - 1e-05, - -1e-05, - -2.412246209830767 + 0.0, + 0.0, + -3.141592653589793 ], [ - -0.04281, - -0.03828, - -2.5245615845252685 + -0.05884, + -0.00273, + -3.048863131789632 ], [ - -0.08965, - -0.07151, - -2.636659087294052 + -0.11717, + -0.0109, + -2.956133609989471 ], [ - -0.13991, - -0.09929, - -2.748958406424525 + -0.17449, + -0.02443, + -2.8634040881893092 ], [ - -0.19296, - -0.12126, - -2.861092725492845 + -0.23031, + -0.04321, + -2.770674566389148 ], [ - -0.24815, - -0.13716, - -2.9732660207719963 + -0.28416, + -0.06708, + -2.677945044588987 ], [ - -0.30476, - -0.14678, - -3.0854953113186663 + -0.28416, + -0.06708, + -2.677945044588987 ], [ - -0.3621, - -0.15, - 0.0 + -0.35, + -0.1, + -2.677945044588987 ] ] }, { - "trajectoryId": 56, - "startAngle": -135.0, - "endAngle": -90.0, - "radius": 0.5121, - "trajectoryLength": 0.4401023994758333, - "arcLength": 0.4022023994758333, - "straightLength": 0.03789999999999999, + "trajectory_id": 41, + "start_angle_index": 8, + "end_angle_index": 11, + "trajectory_radius": 0.5259, + "trajectory_length": 0.64856, + "arc_length": 0.58225, + "straight_length": 0.06631, "poses": [ [ - -1e-05, - 1e-05, - -2.3001427705539226 + 0.0, + 0.0, + -3.141592653589793 ], [ - -0.03828, - -0.04281, - -2.187827395859421 + -0.05284, + -0.00266, + -3.0409427701539666 ], [ - -0.07151, - -0.08965, - -2.075729893090638 + -0.10515, + -0.01062, + -2.94029288671814 ], [ - -0.09929, - -0.13991, - -1.9634305739601647 + -0.15639, + -0.02379, + -2.8396430032823137 ], [ - -0.12126, - -0.19296, - -1.8512962548918448 + -0.20605, + -0.04205, + -2.7389931198464876 ], [ - -0.13716, - -0.24815, - -1.7391229596126936 + -0.25363, + -0.0652, + -2.638343236410661 ], [ - -0.14678, - -0.30476, - -1.6268936690660236 + -0.29864, + -0.09302, + -2.5376933529748347 ], [ - -0.15, - -0.3621, - 0.0 + -0.34062, + -0.12521, + -2.437043469539008 + ], + [ + -0.37916, + -0.16147, + -2.336393586103182 + ], + [ + -0.41386, + -0.20141, + -2.2357437026673557 + ], + [ + -0.44437, + -0.24464, + -2.135093819231529 + ], + [ + -0.47038, + -0.29071, + -2.0344439357957027 + ], + [ + -0.47038, + -0.29071, + -2.0344439357957027 + ], + [ + -0.5, + -0.35, + -2.0344439357957027 ] ] }, { - "trajectoryId": 57, - "startAngle": -135.0, - "endAngle": -180.0, - "radius": 0.4828, - "trajectoryLength": 0.5327902332882881, - "arcLength": 0.37919023328828805, - "straightLength": 0.15360000000000001, + "trajectory_id": 42, + "start_angle_index": 8, + "end_angle_index": 5, + "trajectory_radius": 0.5259, + "trajectory_length": 0.64856, + "arc_length": 0.58225, + "straight_length": 0.06631, "poses": [ [ - -0.0, - -0.0, - -2.356194490192345 + 0.0, + 0.0, + -3.141592653589793 ], [ - -0.0543, - -0.0543, - -2.356378652252878 + -0.05284, + 0.00266, + 3.0409427701539666 ], [ - -0.10861, - -0.10859, - 0.0 + -0.10515, + 0.01062, + 2.94029288671814 + ], + [ + -0.15639, + 0.02379, + 2.8396430032823137 + ], + [ + -0.20605, + 0.04205, + 2.738993119846487 + ], + [ + -0.25363, + 0.0652, + 2.6383432364106607 + ], + [ + -0.29864, + 0.09302, + 2.5376933529748342 ], [ - -0.10861, - -0.10859, - -2.4122508087517898 + -0.34062, + 0.12521, + 2.4370434695390077 ], [ - -0.14898, - -0.14467, - -2.5244352771424006 + -0.37916, + 0.16147, + 2.336393586103182 ], [ - -0.19313, - -0.176, - -2.6367185203718857 + -0.41386, + 0.20141, + 2.2357437026673557 ], [ - -0.24052, - -0.20219, - -2.748875865990998 + -0.44437, + 0.24464, + 2.135093819231529 ], [ - -0.29054, - -0.22291, - -2.8610859406579348 + -0.47038, + 0.29071, + 2.0344439357957027 ], [ - -0.34257, - -0.2379, - -2.9734374254675204 + -0.47038, + 0.29071, + 2.0344439357957027 ], [ - -0.39594, - -0.24696, - -3.0854180020716697 + -0.5, + 0.35, + 2.0344439357957027 ] ] }, { - "trajectoryId": 58, - "startAngle": -135.0, - "endAngle": -90.0, - "radius": 0.4828, - "trajectoryLength": 0.5327902332882881, - "arcLength": 0.37919023328828805, - "straightLength": 0.15360000000000001, + "trajectory_id": 43, + "start_angle_index": 8, + "end_angle_index": 7, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - -0.0, - -0.0, - -2.356194490192345 + 0.0, + 0.0, + -3.141592653589793 ], [ - -0.0543, - -0.0543, - -2.356010328131812 + -0.05884, + 0.00273, + 3.0488631317896324 ], [ - -0.10859, - -0.10861, - 0.0 + -0.11717, + 0.0109, + 2.956133609989471 ], [ - -0.10859, - -0.10861, - -2.3001381716329 + -0.17449, + 0.02443, + 2.8634040881893092 ], [ - -0.14467, - -0.14898, - -2.187953703242289 + -0.23031, + 0.04321, + 2.7706745663891486 ], [ - -0.176, - -0.19313, - -2.0756704600128044 + -0.28416, + 0.06708, + 2.677945044588987 ], [ - -0.20219, - -0.24052, - -1.963513114393692 + -0.28416, + 0.06708, + 2.677945044588987 ], [ - -0.22291, - -0.29054, - -1.851303039726755 + -0.35, + 0.1, + 2.677945044588987 + ] + ] + }, + { + "trajectory_id": 44, + "start_angle_index": 8, + "end_angle_index": 8, + "trajectory_radius": 0.0, + "trajectory_length": 0.15, + "arc_length": 0.0, + "straight_length": 0.15, + "poses": [ + [ + 0.0, + 0.0, + 3.141592653589793 ], [ - -0.2379, - -0.34257, - -1.7389515549171695 + -0.075, + 0.0, + 3.141592653589793 ], [ - -0.24696, - -0.39594, - -1.62697097831302 + -0.15, + 0.0, + 3.141592653589793 ] ] }, { - "trajectoryId": 59, - "startAngle": -135.0, - "endAngle": -206.56505117707798, - "radius": 0.4251, - "trajectoryLength": 0.5972693578464978, - "arcLength": 0.5309693578464979, - "straightLength": 0.06629999999999997, + "trajectory_id": 45, + "start_angle_index": 9, + "end_angle_index": 9, + "trajectory_radius": 0.0, + "trajectory_length": 0.22361, + "arc_length": 0.0, + "straight_length": 0.22361, "poses": [ [ - -1e-05, - 1e-05, - -2.4185966761898996 - ], - [ - -0.0398, - -0.0351, - -2.543605542069912 + 0.0, + 0.0, + -2.677945044588987 ], [ - -0.08365, - -0.06497, - -2.6684207203195744 + -0.06667, + -0.03333, + -2.677945044588987 ], [ - -0.13088, - -0.08915, - -2.79332074836733 + -0.13333, + -0.06667, + -2.677945044588987 ], [ - -0.18076, - -0.10726, - -2.918324864306639 - ], + -0.2, + -0.1, + -2.677945044588987 + ] + ] + }, + { + "trajectory_id": 46, + "start_angle_index": 9, + "end_angle_index": 10, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, + "poses": [ [ - -0.23251, - -0.11901, - -3.0430492397370315 + -3e-05, + 6e-05, + -2.677945044588987 ], [ - -0.28531, - -0.12423, - 3.1150202102373594 + -0.06423, + -0.03646, + -2.5706948597901063 ], [ - -0.33836, - -0.12282, - 2.9902329999111887 + -0.12415, + -0.07965, + -2.4634446749912255 ], [ - -0.39081, - -0.11482, - 2.8652085522841735 + -0.1791, + -0.129, + -2.356194490192345 ], [ - -0.44186, - -0.10034, - 2.7404374562839595 + -0.1791, + -0.129, + -2.356194490192345 ], [ - -0.49071, - -0.07962, - 0.0 + -0.2, + -0.15, + -2.356194490192345 ] ] - }, - { - "trajectoryId": 60, - "startAngle": -135.0, - "endAngle": -63.43494882292201, - "radius": 0.4251, - "trajectoryLength": 0.5972693578464978, - "arcLength": 0.5309693578464979, - "straightLength": 0.06629999999999997, - "poses": [ - [ - 1e-05, - -1e-05, - -2.29379230419479 - ], - [ - -0.0351, - -0.0398, - -2.1687834383147777 - ], + }, + { + "trajectory_id": 47, + "start_angle_index": 9, + "end_angle_index": 7, + "trajectory_radius": 0.5031, + "trajectory_length": 0.46652, + "arc_length": 0.46652, + "straight_length": 0, + "poses": [ [ - -0.06497, - -0.08365, - -2.0439682600651157 + -1e-05, + 1e-05, + -2.677945044588987 ], [ - -0.08915, - -0.13088, - -1.9190682320173602 + -0.05356, + -0.02299, + -2.7938569468391883 ], [ - -0.10726, - -0.18076, - -1.794064116078051 + -0.10941, + -0.03964, + -2.90976884908939 ], [ - -0.11901, - -0.23251, - -1.6693397406476584 + -0.16682, + -0.04972, + -3.025680751339592 ], [ - -0.12423, - -0.28531, - -1.544223883442463 + -0.225, + -0.0531, + -3.141592653589793 ], [ - -0.12282, - -0.33836, - -1.4194366731162924 + -0.28318, + -0.04972, + 3.025680751339592 ], [ - -0.11482, - -0.39081, - -1.294412225489277 + -0.34059, + -0.03964, + 2.9097688490893905 ], [ - -0.10034, - -0.44186, - -1.1696411294890627 + -0.39644, + -0.02299, + 2.7938569468391883 ], [ - -0.07962, - -0.49071, - 0.0 + -0.44999, + 1e-05, + 2.677945044588987 ] ] }, { - "trajectoryId": 61, - "startAngle": -45.0, - "endAngle": -26.56505117707799, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, + "trajectory_id": 48, + "start_angle_index": 9, + "end_angle_index": 7, + "trajectory_radius": 0.6149, + "trajectory_length": 0.57019, + "arc_length": 0.57019, + "straight_length": 0, "poses": [ [ - 0.0, - -0.0, - -0.7877847937108879 + -1e-05, + 2e-05, + -2.677945044588987 ], [ - 0.0209, - -0.021, - -0.7317583920706331 + -0.05212, + -0.02308, + -2.770674566389148 ], [ - 0.07585, - -0.07035, - -0.6245460333019313 + -0.10614, + -0.04126, + -2.8634040881893092 ], [ - 0.13577, - -0.11354, - -0.5171981083811618 - ] - ] - }, - { - "trajectoryId": 62, - "startAngle": -45.0, - "endAngle": -63.43494882292201, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, - "poses": [ - [ - 0.0, - -0.0, - -0.7830115330840086 + -0.16161, + -0.05436, + -2.956133609989471 ], [ - 0.021, - -0.0209, - -0.8390379347242635 + -0.21806, + -0.06226, + -3.048863131789632 ], [ - 0.07035, - -0.07585, - -0.9462502934929653 + -0.275, + -0.0649, + -3.141592653589793 ], [ - 0.11354, - -0.13577, - -1.053598218413735 - ] - ] - }, - { - "trajectoryId": 63, - "startAngle": -45.0, - "endAngle": -45.0, - "radius": 0, - "trajectoryLength": 0.28284271247461906, - "arcLength": 0.0, - "straightLength": 0.28284271247461906, - "poses": [ - [ - 0.0, - -0.0, - -0.7853981633974483 + -0.33194, + -0.06226, + 3.0488631317896324 ], [ - 0.04, - -0.04, - -0.7853981633974483 + -0.38839, + -0.05436, + 2.956133609989471 ], [ - 0.08, - -0.08, - -0.7853981633974483 + -0.44386, + -0.04126, + 2.8634040881893092 ], [ - 0.12, - -0.12, - -0.7853981633974483 + -0.49788, + -0.02308, + 2.7706745663891486 ], [ - 0.16, - -0.16, - -0.7853981633974483 + -0.54999, + 2e-05, + 2.677945044588987 ] ] }, { - "trajectoryId": 64, - "startAngle": -45.0, - "endAngle": -0.0, - "radius": 0.5121, - "trajectoryLength": 0.4401023994758333, - "arcLength": 0.4022023994758333, - "straightLength": 0.03789999999999999, + "trajectory_id": 49, + "start_angle_index": 9, + "end_angle_index": 8, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - -1e-05, - -1e-05, - -0.7293464437590259 + 0.0, + 0.0, + -2.677945044588987 ], [ - 0.04281, - -0.03828, - -0.6170310690645247 + -0.06584, + -0.03292, + -2.677945044588987 ], [ - 0.08965, - -0.07151, - -0.5049335662957414 + -0.06584, + -0.03292, + -2.677945044588987 ], [ - 0.13991, - -0.09929, - -0.3926342471652681 + -0.11969, + -0.05679, + -2.770674566389148 ], [ - 0.19296, - -0.12126, - -0.28049992809694807 + -0.17551, + -0.07557, + -2.8634040881893092 ], [ - 0.24815, - -0.13716, - -0.16832663281779695 + -0.23283, + -0.0891, + -2.956133609989471 ], [ - 0.30476, - -0.14678, - -0.05609734227112698 + -0.29116, + -0.09727, + -3.048863131789632 ], [ - 0.3621, - -0.15, - 0.0 + -0.35, + -0.1, + -3.141592653589793 ] ] }, { - "trajectoryId": 65, - "startAngle": -45.0, - "endAngle": -90.0, - "radius": 0.5121, - "trajectoryLength": 0.4401023994758333, - "arcLength": 0.4022023994758333, - "straightLength": 0.03789999999999999, + "trajectory_id": 50, + "start_angle_index": 10, + "end_angle_index": 9, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ - 1e-05, - 1e-05, - -0.8414498830358706 - ], - [ - 0.03828, - -0.04281, - -0.953765257730372 - ], - [ - 0.07151, - -0.08965, - -1.0658627604991553 + 0.0, + 0.0, + -2.356194490192345 ], [ - 0.09929, - -0.13991, - -1.1781620796296284 + -0.0209, + -0.021, + -2.356194490192345 ], [ - 0.12126, - -0.19296, - -1.2902963986979485 + -0.0209, + -0.021, + -2.356194490192345 ], [ - 0.13716, - -0.24815, - -1.4024696939770998 + -0.07585, + -0.07035, + -2.4634446749912255 ], [ - 0.14678, - -0.30476, - -1.5146989845237697 + -0.13577, + -0.11354, + -2.5706948597901063 ], [ - 0.15, - -0.3621, - 0.0 + -0.19997, + -0.15006, + -2.677945044588987 ] ] }, { - "trajectoryId": 66, - "startAngle": -45.0, - "endAngle": -0.0, - "radius": 0.4828, - "trajectoryLength": 0.5327902332882881, - "arcLength": 0.37919023328828805, - "straightLength": 0.15360000000000001, + "trajectory_id": 51, + "start_angle_index": 10, + "end_angle_index": 10, + "trajectory_radius": 0.0, + "trajectory_length": 0.21213, + "arc_length": 0.0, + "straight_length": 0.21213, "poses": [ [ 0.0, - -0.0, - -0.7853981633974483 + 0.0, + -2.356194490192345 ], [ - 0.0543, - -0.0543, - -0.7852140013369153 + -0.05, + -0.05, + -2.356194490192345 ], [ - 0.10861, - -0.10859, - 0.0 + -0.1, + -0.1, + -2.356194490192345 ], [ - 0.10861, - -0.10859, - -0.7293418448380035 - ], + -0.15, + -0.15, + -2.356194490192345 + ] + ] + }, + { + "trajectory_id": 52, + "start_angle_index": 10, + "end_angle_index": 11, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, + "poses": [ [ - 0.14898, - -0.14467, - -0.6171573764473927 + 0.0, + 0.0, + -2.356194490192345 ], [ - 0.19313, - -0.176, - -0.5048741332179076 + -0.021, + -0.0209, + -2.356194490192345 ], [ - 0.24052, - -0.20219, - -0.3927167875987952 + -0.021, + -0.0209, + -2.356194490192345 ], [ - 0.29054, - -0.22291, - -0.28050671293185836 + -0.07035, + -0.07585, + -2.248944305393464 ], [ - 0.34257, - -0.2379, - -0.16815522812227288 + -0.11354, + -0.13577, + -2.1416941205945834 ], [ - 0.39594, - -0.24696, - -0.05617465151812344 + -0.15006, + -0.19997, + -2.0344439357957027 ] ] }, { - "trajectoryId": 67, - "startAngle": -45.0, - "endAngle": -90.0, - "radius": 0.4828, - "trajectoryLength": 0.5327902332882881, - "arcLength": 0.37919023328828805, - "straightLength": 0.15360000000000001, + "trajectory_id": 53, + "start_angle_index": 10, + "end_angle_index": 12, + "trajectory_radius": 0.5121, + "trajectory_length": 0.44007, + "arc_length": 0.4022, + "straight_length": 0.03787, "poses": [ [ - 0.0, - -0.0, - -0.7853981633974483 + -1e-05, + 1e-05, + -2.356194490192345 ], [ - 0.0543, - -0.0543, - -0.7855823254579813 + -0.03828, + -0.04281, + -2.243994752564138 ], [ - 0.10859, - -0.10861, - 0.0 + -0.07151, + -0.08965, + -2.131795014935931 ], [ - 0.10859, - -0.10861, - -0.8414544819568931 + -0.09929, + -0.13991, + -2.019595277307724 ], [ - 0.14467, - -0.14898, - -0.953638950347504 + -0.12126, + -0.19296, + -1.9073955396795172 ], [ - 0.176, - -0.19313, - -1.065922193576989 + -0.13716, + -0.24815, + -1.7951958020513104 ], [ - 0.20219, - -0.24052, - -1.1780795391961014 + -0.14678, + -0.30476, + -1.6829960644231035 ], [ - 0.22291, - -0.29054, - -1.2902896138630382 + -0.15, + -0.3621, + -1.5707963267948966 ], [ - 0.2379, - -0.34257, - -1.4026410986726237 + -0.15, + -0.3621, + -1.5707963267948966 ], [ - 0.24696, - -0.39594, - -1.5146216752767732 + -0.15, + -0.4, + -1.5707963267948966 ] ] }, { - "trajectoryId": 68, - "startAngle": -45.0, - "endAngle": 26.56505117707799, - "radius": 0.4251, - "trajectoryLength": 0.5972693578464978, - "arcLength": 0.5309693578464979, - "straightLength": 0.06629999999999997, + "trajectory_id": 54, + "start_angle_index": 10, + "end_angle_index": 8, + "trajectory_radius": 0.5121, + "trajectory_length": 0.44007, + "arc_length": 0.4022, + "straight_length": 0.03787, "poses": [ [ 1e-05, - 1e-05, - -0.7229959773998935 - ], - [ - 0.0398, - -0.0351, - -0.5979871115198812 + -1e-05, + -2.356194490192345 ], [ - 0.08365, - -0.06497, - -0.47317193327021895 + -0.04281, + -0.03828, + -2.4683942278205517 ], [ - 0.13088, - -0.08915, - -0.3482719052224635 + -0.08965, + -0.07151, + -2.5805939654487586 ], [ - 0.18076, - -0.10726, - -0.22326778928315447 + -0.13991, + -0.09929, + -2.6927937030769655 ], [ - 0.23251, - -0.11901, - -0.09854341385276191 + -0.19296, + -0.12126, + -2.8049934407051724 ], [ - 0.28531, - -0.12423, - 0.026572443352433615 + -0.24815, + -0.13716, + -2.9171931783333793 ], [ - 0.33836, - -0.12282, - 0.15135965367860432 + -0.30476, + -0.14678, + -3.029392915961586 ], [ - 0.39081, - -0.11482, - 0.2763841013056198 + -0.3621, + -0.15, + -3.141592653589793 ], [ - 0.44186, - -0.10034, - 0.4011551973058339 + -0.3621, + -0.15, + 3.141592653589793 ], [ - 0.49071, - -0.07962, - 0.0 + -0.4, + -0.15, + 3.141592653589793 ] ] }, { - "trajectoryId": 69, - "startAngle": -45.0, - "endAngle": -116.56505117707799, - "radius": 0.4251, - "trajectoryLength": 0.5972693578464978, - "arcLength": 0.5309693578464979, - "straightLength": 0.06629999999999997, + "trajectory_id": 55, + "start_angle_index": 11, + "end_angle_index": 10, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ - -1e-05, - -1e-05, - -0.847800349395003 - ], - [ - 0.0351, - -0.0398, - -0.9728092152750155 - ], - [ - 0.06497, - -0.08365, - -1.0976243935246777 - ], - [ - 0.08915, - -0.13088, - -1.2225244215724331 - ], - [ - 0.10726, - -0.18076, - -1.347528537511742 - ], - [ - 0.11901, - -0.23251, - -1.4722529129421347 + 6e-05, + -3e-05, + -2.0344439357957027 ], [ - 0.12423, - -0.28531, - -1.5973687701473303 + -0.03646, + -0.06423, + -2.1416941205945834 ], [ - 0.12282, - -0.33836, - -1.722155980473501 + -0.07965, + -0.12415, + -2.248944305393464 ], [ - 0.11482, - -0.39081, - -1.8471804281005164 + -0.129, + -0.1791, + -2.356194490192345 ], [ - 0.10034, - -0.44186, - -1.9719515241007306 + -0.129, + -0.1791, + -2.356194490192345 ], [ - 0.07962, - -0.49071, - 0.0 + -0.15, + -0.2, + -2.356194490192345 ] ] }, { - "trajectoryId": 70, - "startAngle": 63.43494882292201, - "endAngle": 90.0, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, + "trajectory_id": 56, + "start_angle_index": 11, + "end_angle_index": 11, + "trajectory_radius": 0.0, + "trajectory_length": 0.22361, + "arc_length": 0.0, + "straight_length": 0.22361, "poses": [ [ - 0.00528, - 0.01056, - 1.1844975219908958 + 0.0, + 0.0, + -2.0344439357957027 + ], + [ + -0.03333, + -0.06667, + -2.0344439357957027 ], [ - 0.02992, - 0.07114, - 1.33890893073425 + -0.06667, + -0.13333, + -2.0344439357957027 ], [ - 0.04495, - 0.13479, - 1.4935084760033717 + -0.1, + -0.2, + -2.0344439357957027 ] ] }, { - "trajectoryId": 71, - "startAngle": 63.43494882292201, - "endAngle": 63.43494882292201, - "radius": 0, - "trajectoryLength": 0.223606797749979, - "arcLength": 0.0, - "straightLength": 0.223606797749979, + "trajectory_id": 57, + "start_angle_index": 11, + "end_angle_index": 12, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ 0.0, 0.0, - 1.1072087165940425 + -2.0344439357957027 ], [ - 0.03333, - 0.06667, - 1.1070287129944747 + -0.03292, + -0.06584, + -2.0344439357957027 ], [ - 0.06667, - 0.13333, - 1.1072087165940423 - ] - ] - }, - { - "trajectoryId": 72, - "startAngle": 63.43494882292201, - "endAngle": 45.0, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, - "poses": [ + -0.03292, + -0.06584, + -2.0344439357957027 + ], + [ + -0.05679, + -0.11969, + -1.9417144139955416 + ], [ - -6e-05, - 3e-05, - 1.0535982184137347 + -0.07557, + -0.17551, + -1.8489848921953802 ], [ - 0.03646, - 0.06423, - 0.9462502934929654 + -0.0891, + -0.23283, + -1.756255370395219 ], [ - 0.07965, - 0.12415, - 0.8390379347242635 + -0.09727, + -0.29116, + -1.6635258485950577 ], [ - 0.129, - 0.1791, - 0.0 + -0.1, + -0.35, + -1.5707963267948966 ] ] }, { - "trajectoryId": 73, - "startAngle": 63.43494882292201, - "endAngle": 26.56505117707799, - "radius": 0.4472, - "trajectoryLength": 0.28777369585235674, - "arcLength": 0.28777369585235674, - "straightLength": 0, + "trajectory_id": 58, + "start_angle_index": 11, + "end_angle_index": 13, + "trajectory_radius": 0.5031, + "trajectory_length": 0.46652, + "arc_length": 0.46652, + "straight_length": 0, "poses": [ [ 1e-05, -1e-05, - 1.042809472532039 + -2.0344439357957027 ], [ - 0.02899, - 0.04968, - 0.9141147480501551 + -0.02299, + -0.05356, + -1.9185320335455012 ], [ - 0.0641, - 0.09523, - 0.7853981633974483 + -0.03964, + -0.10941, + -1.8026201312952996 + ], + [ + -0.04972, + -0.16682, + -1.686708229045098 + ], + [ + -0.0531, + -0.225, + -1.5707963267948966 + ], + [ + -0.04972, + -0.28318, + -1.454884424544695 + ], + [ + -0.03964, + -0.34059, + -1.3389725222944935 ], [ - 0.10477, - 0.1359, - 0.6566815787447413 + -0.02299, + -0.39644, + -1.223060620044292 ], [ - 0.15032, - 0.17101, - 0.527986854262858 + 1e-05, + -0.44999, + -1.1071487177940904 ] ] }, { - "trajectoryId": 74, - "startAngle": 63.43494882292201, - "endAngle": 90.0, - "radius": 0.6354, - "trajectoryLength": 0.3682016907591122, - "arcLength": 0.2946016907591122, - "straightLength": 0.0736, + "trajectory_id": 59, + "start_angle_index": 11, + "end_angle_index": 13, + "trajectory_radius": 0.6149, + "trajectory_length": 0.57019, + "arc_length": 0.57019, + "straight_length": 0, "poses": [ [ - 0.0, - 0.0, - 1.1071487177940904 + 2e-05, + -1e-05, + -2.0344439357957027 ], [ - 0.03292, - 0.06584, - 1.1535545352960592 + -0.02308, + -0.05212, + -1.9417144139955416 ], [ - 0.05679, - 0.11969, - 1.2462536834338316 + -0.04126, + -0.10614, + -1.8489848921953802 ], [ - 0.07557, - 0.17551, - 1.3389959296100549 + -0.05436, + -0.16161, + -1.756255370395219 ], [ - 0.0891, - 0.23283, - 1.4316364916319972 + -0.06226, + -0.21806, + -1.6635258485950577 ], [ - 0.09727, - 0.29116, - 1.5244325676974748 - ] - ] - }, - { - "trajectoryId": 75, - "startAngle": 116.56505117707799, - "endAngle": 90.0, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ + -0.0649, + -0.275, + -1.5707963267948966 + ], + [ + -0.06226, + -0.33194, + -1.4780668049947354 + ], + [ + -0.05436, + -0.38839, + -1.3853372831945743 + ], [ - -0.00528, - 0.01056, - 1.9570951315988974 + -0.04126, + -0.44386, + -1.292607761394413 ], [ - -0.02992, - 0.07114, - 1.8026837228555432 + -0.02308, + -0.49788, + -1.1998782395942515 ], [ - -0.04495, - 0.13479, - 1.6480841775864215 + 2e-05, + -0.54999, + -1.1071487177940904 ] ] }, { - "trajectoryId": 76, - "startAngle": 116.56505117707799, - "endAngle": 116.56505117707799, - "radius": 0, - "trajectoryLength": 0.223606797749979, - "arcLength": 0.0, - "straightLength": 0.223606797749979, + "trajectory_id": 60, + "start_angle_index": 12, + "end_angle_index": 9, + "trajectory_radius": 0.5259, + "trajectory_length": 0.64856, + "arc_length": 0.58225, + "straight_length": 0.06631, "poses": [ [ - -0.0, 0.0, - 2.034383936995751 + 0.0, + -1.5707963267948966 ], [ - -0.03333, - 0.06667, - 2.0345639405953184 + -0.00266, + -0.05284, + -1.671446210230723 ], [ - -0.06667, - 0.13333, - 2.034383936995751 - ] - ] - }, - { - "trajectoryId": 77, - "startAngle": 116.56505117707799, - "endAngle": 135.0, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, - "poses": [ + -0.01062, + -0.10515, + -1.7720960936665493 + ], [ - 6e-05, - 3e-05, - 2.0879944351760584 + -0.02379, + -0.15639, + -1.8727459771023758 ], [ - -0.03646, - 0.06423, - 2.195342360096828 + -0.04205, + -0.20605, + -1.973395860538202 ], [ - -0.07965, - 0.12415, - 2.30255471886553 + -0.0652, + -0.25363, + -2.0740457439740285 ], [ - -0.129, - 0.1791, - 0.0 - ] - ] - }, - { - "trajectoryId": 78, - "startAngle": 116.56505117707799, - "endAngle": 153.43494882292202, - "radius": 0.4472, - "trajectoryLength": 0.28777369585235674, - "arcLength": 0.28777369585235674, - "straightLength": 0, - "poses": [ + -0.09302, + -0.29864, + -2.174695627409855 + ], [ - -1e-05, - -1e-05, - 2.098783181057754 + -0.12521, + -0.34062, + -2.2753455108456815 ], [ - -0.02899, - 0.04968, - 2.227477905539638 + -0.16147, + -0.37916, + -2.3759953942815075 ], [ - -0.0641, - 0.09523, - 2.356194490192345 + -0.20141, + -0.41386, + -2.476645277717334 + ], + [ + -0.24464, + -0.44437, + -2.5772951611531605 ], [ - -0.10477, - 0.1359, - 2.484911074845052 + -0.29071, + -0.47038, + -2.677945044588987 + ], + [ + -0.29071, + -0.47038, + -2.677945044588987 ], [ - -0.15032, - 0.17101, - 2.6136057993269355 + -0.35, + -0.5, + -2.677945044588987 ] ] }, { - "trajectoryId": 79, - "startAngle": 116.56505117707799, - "endAngle": 90.0, - "radius": 0.6354, - "trajectoryLength": 0.3682016907591122, - "arcLength": 0.2946016907591122, - "straightLength": 0.0736, + "trajectory_id": 61, + "start_angle_index": 12, + "end_angle_index": 11, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - -0.0, 0.0, - 2.0344439357957027 + 0.0, + -1.5707963267948966 ], [ - -0.03292, - 0.06584, - 1.9880381182937341 + -0.00273, + -0.05884, + -1.6635258485950577 ], [ - -0.05679, - 0.11969, - 1.8953389701559615 + -0.0109, + -0.11717, + -1.756255370395219 ], [ - -0.07557, - 0.17551, - 1.8025967239797382 + -0.02443, + -0.17449, + -1.8489848921953802 ], [ - -0.0891, - 0.23283, - 1.7099561619577959 + -0.04321, + -0.23031, + -1.9417144139955416 ], [ - -0.09727, - 0.29116, - 1.6171600858923185 - ] - ] - }, - { - "trajectoryId": 80, - "startAngle": -116.56505117707799, - "endAngle": -90.0, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ - [ - -0.00528, - -0.01056, - -1.9570951315988974 + -0.06708, + -0.28416, + -2.0344439357957027 ], [ - -0.02992, - -0.07114, - -1.8026837228555432 + -0.06708, + -0.28416, + -2.0344439357957027 ], [ - -0.04495, - -0.13479, - -1.6480841775864215 + -0.1, + -0.35, + -2.0344439357957027 ] ] }, { - "trajectoryId": 81, - "startAngle": -116.56505117707799, - "endAngle": -116.56505117707799, - "radius": 0, - "trajectoryLength": 0.223606797749979, - "arcLength": 0.0, - "straightLength": 0.223606797749979, + "trajectory_id": 62, + "start_angle_index": 12, + "end_angle_index": 12, + "trajectory_radius": 0.0, + "trajectory_length": 0.15, + "arc_length": 0.0, + "straight_length": 0.15, "poses": [ [ - -0.0, - -0.0, - -2.034383936995751 + 0.0, + 0.0, + -1.5707963267948966 ], [ - -0.03333, - -0.06667, - -2.0345639405953184 + 0.0, + -0.075, + -1.5707963267948966 ], [ - -0.06667, - -0.13333, - -2.034383936995751 + 0.0, + -0.15, + -1.5707963267948966 ] ] }, { - "trajectoryId": 82, - "startAngle": -116.56505117707799, - "endAngle": -135.0, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, + "trajectory_id": 63, + "start_angle_index": 12, + "end_angle_index": 13, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - 6e-05, - -3e-05, - -2.0879944351760584 + 0.0, + 0.0, + -1.5707963267948966 ], [ - -0.03646, - -0.06423, - -2.195342360096828 + 0.00273, + -0.05884, + -1.4780668049947354 ], [ - -0.07965, - -0.12415, - -2.30255471886553 + 0.0109, + -0.11717, + -1.385337283194574 ], [ - -0.129, - -0.1791, - 0.0 - ] - ] - }, - { - "trajectoryId": 83, - "startAngle": -116.56505117707799, - "endAngle": -153.43494882292202, - "radius": 0.4472, - "trajectoryLength": 0.28777369585235674, - "arcLength": 0.28777369585235674, - "straightLength": 0, - "poses": [ - [ - -1e-05, - 1e-05, - -2.098783181057754 + 0.02443, + -0.17449, + -1.292607761394413 ], [ - -0.02899, - -0.04968, - -2.227477905539638 + 0.04321, + -0.23031, + -1.1998782395942515 ], [ - -0.0641, - -0.09523, - -2.356194490192345 + 0.06708, + -0.28416, + -1.1071487177940904 ], [ - -0.10477, - -0.1359, - -2.484911074845052 + 0.06708, + -0.28416, + -1.1071487177940904 ], [ - -0.15032, - -0.17101, - -2.6136057993269355 + 0.1, + -0.35, + -1.1071487177940904 ] ] }, { - "trajectoryId": 84, - "startAngle": -116.56505117707799, - "endAngle": -90.0, - "radius": 0.6354, - "trajectoryLength": 0.3682016907591122, - "arcLength": 0.2946016907591122, - "straightLength": 0.0736, + "trajectory_id": 64, + "start_angle_index": 12, + "end_angle_index": 15, + "trajectory_radius": 0.5259, + "trajectory_length": 0.64856, + "arc_length": 0.58225, + "straight_length": 0.06631, "poses": [ [ - -0.0, - -0.0, - -2.0344439357957027 + 0.0, + 0.0, + -1.5707963267948966 ], [ - -0.03292, - -0.06584, - -1.9880381182937341 + 0.00266, + -0.05284, + -1.47014644335907 ], [ - -0.05679, - -0.11969, - -1.8953389701559615 + 0.01062, + -0.10515, + -1.3694965599232438 ], [ - -0.07557, - -0.17551, - -1.8025967239797382 + 0.02379, + -0.15639, + -1.2688466764874173 ], [ - -0.0891, - -0.23283, - -1.7099561619577959 + 0.04205, + -0.20605, + -1.168196793051591 ], [ - -0.09727, - -0.29116, - -1.6171600858923185 - ] - ] - }, - { - "trajectoryId": 85, - "startAngle": -63.43494882292201, - "endAngle": -90.0, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ + 0.0652, + -0.25363, + -1.0675469096157646 + ], [ - 0.00528, - -0.01056, - -1.1844975219908958 + 0.09302, + -0.29864, + -0.9668970261799381 ], [ - 0.02992, - -0.07114, - -1.33890893073425 + 0.12521, + -0.34062, + -0.8662471427441116 ], [ - 0.04495, - -0.13479, - -1.4935084760033717 - ] - ] - }, - { - "trajectoryId": 86, - "startAngle": -63.43494882292201, - "endAngle": -63.43494882292201, - "radius": 0, - "trajectoryLength": 0.223606797749979, - "arcLength": 0.0, - "straightLength": 0.223606797749979, - "poses": [ + 0.16147, + -0.37916, + -0.7655972593082856 + ], [ - 0.0, - -0.0, - -1.1072087165940425 + 0.20141, + -0.41386, + -0.6649473758724591 ], [ - 0.03333, - -0.06667, - -1.1070287129944747 + 0.24464, + -0.44437, + -0.5642974924366326 ], [ - 0.06667, - -0.13333, - -1.1072087165940423 + 0.29071, + -0.47038, + -0.46364760900080615 + ], + [ + 0.29071, + -0.47038, + -0.4636476090008061 + ], + [ + 0.35, + -0.5, + -0.4636476090008061 ] ] }, { - "trajectoryId": 87, - "startAngle": -63.43494882292201, - "endAngle": -45.0, - "radius": 0.689, - "trajectoryLength": 0.25128613197928645, - "arcLength": 0.22168613197928647, - "straightLength": 0.0296, + "trajectory_id": 65, + "start_angle_index": 13, + "end_angle_index": 11, + "trajectory_radius": 0.5031, + "trajectory_length": 0.46652, + "arc_length": 0.46652, + "straight_length": 0, "poses": [ [ - -6e-05, - -3e-05, - -1.0535982184137347 + -1e-05, + -1e-05, + -1.1071487177940904 ], [ - 0.03646, - -0.06423, - -0.9462502934929654 + 0.02299, + -0.05356, + -1.223060620044292 ], [ - 0.07965, - -0.12415, - -0.8390379347242635 + 0.03964, + -0.10941, + -1.3389725222944935 ], [ - 0.129, - -0.1791, - 0.0 - ] - ] - }, - { - "trajectoryId": 88, - "startAngle": -63.43494882292201, - "endAngle": -26.56505117707799, - "radius": 0.4472, - "trajectoryLength": 0.28777369585235674, - "arcLength": 0.28777369585235674, - "straightLength": 0, - "poses": [ + 0.04972, + -0.16682, + -1.454884424544695 + ], [ - 1e-05, - 1e-05, - -1.042809472532039 + 0.0531, + -0.225, + -1.5707963267948966 ], [ - 0.02899, - -0.04968, - -0.9141147480501551 + 0.04972, + -0.28318, + -1.686708229045098 ], [ - 0.0641, - -0.09523, - -0.7853981633974483 + 0.03964, + -0.34059, + -1.8026201312952996 ], [ - 0.10477, - -0.1359, - -0.6566815787447413 + 0.02299, + -0.39644, + -1.9185320335455012 ], [ - 0.15032, - -0.17101, - -0.527986854262858 + -1e-05, + -0.44999, + -2.0344439357957027 ] ] }, { - "trajectoryId": 89, - "startAngle": -63.43494882292201, - "endAngle": -90.0, - "radius": 0.6354, - "trajectoryLength": 0.3682016907591122, - "arcLength": 0.2946016907591122, - "straightLength": 0.0736, + "trajectory_id": 66, + "start_angle_index": 13, + "end_angle_index": 11, + "trajectory_radius": 0.6149, + "trajectory_length": 0.57019, + "arc_length": 0.57019, + "straight_length": 0, "poses": [ [ - 0.0, - -0.0, + -2e-05, + -1e-05, -1.1071487177940904 ], [ - 0.03292, - -0.06584, - -1.1535545352960592 - ], - [ - 0.05679, - -0.11969, - -1.2462536834338316 + 0.02308, + -0.05212, + -1.1998782395942515 ], [ - 0.07557, - -0.17551, - -1.3389959296100549 + 0.04126, + -0.10614, + -1.292607761394413 ], [ - 0.0891, - -0.23283, - -1.4316364916319972 + 0.05436, + -0.16161, + -1.385337283194574 ], [ - 0.09727, - -0.29116, - -1.5244325676974748 - ] - ] - }, - { - "trajectoryId": 90, - "startAngle": 90.0, - "endAngle": 90.0, - "radius": 0, - "trajectoryLength": 0.2, - "arcLength": 0.0, - "straightLength": 0.2, - "poses": [ - [ - 0.0, - 0.0, - 1.5707963267948966 + 0.06226, + -0.21806, + -1.4780668049947354 ], [ - 0.0, - 0.06667, - 1.5707963267948966 + 0.0649, + -0.275, + -1.5707963267948966 ], [ - 0.0, - 0.13333, - 1.5707963267948966 - ] - ] - }, - { - "trajectoryId": 91, - "startAngle": 90.0, - "endAngle": 63.43494882292201, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ - [ - 0.0, - 0.0, - 1.4935084760033717 + 0.06226, + -0.33194, + -1.6635258485950577 ], [ - 0.00505, - 0.06521, - 1.3389089307342499 + 0.05436, + -0.38839, + -1.7562553703952188 ], [ - 0.02008, - 0.12886, - 1.1844975219908958 - ] - ] - }, - { - "trajectoryId": 92, - "startAngle": 90.0, - "endAngle": 116.56505117707799, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ - [ - -0.0, - 0.0, - 1.6480841775864215 + 0.04126, + -0.44386, + -1.8489848921953802 ], [ - -0.00505, - 0.06521, - 1.8026837228555432 + 0.02308, + -0.49788, + -1.9417144139955416 ], [ - -0.02008, - 0.12886, - 1.9570951315988976 + -2e-05, + -0.54999, + -2.0344439357957027 ] ] }, { - "trajectoryId": 93, - "startAngle": 90.0, - "endAngle": 63.43494882292201, - "radius": 0.8472, - "trajectoryLength": 0.41640225434548295, - "arcLength": 0.39280225434548294, - "straightLength": 0.023599999999999982, + "trajectory_id": 67, + "start_angle_index": 13, + "end_angle_index": 12, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ 0.0, 0.0, - 1.5376356672653075 + -1.1071487177940904 + ], + [ + 0.03292, + -0.06584, + -1.1071487177940904 ], [ - 0.00186, - 0.05607, - 1.4715355769519873 + 0.03292, + -0.06584, + -1.1071487177940904 ], [ - 0.00742, - 0.1119, - 1.405178839897782 + 0.05679, + -0.11969, + -1.1998782395942515 ], [ - 0.01667, - 0.16724, - 1.3389605793090156 + 0.07557, + -0.17551, + -1.292607761394413 ], [ - 0.02956, - 0.22184, - 1.272664314771342 + 0.0891, + -0.23283, + -1.385337283194574 ], [ - 0.04604, - 0.27547, - 1.2064763007678847 + 0.09727, + -0.29116, + -1.4780668049947354 ], [ - 0.06603, - 0.32789, - 1.1403927062346335 + 0.1, + -0.35, + -1.5707963267948966 ] ] }, { - "trajectoryId": 94, - "startAngle": 90.0, - "endAngle": 116.56505117707799, - "radius": 0.8472, - "trajectoryLength": 0.41640225434548295, - "arcLength": 0.39280225434548294, - "straightLength": 0.023599999999999982, + "trajectory_id": 68, + "start_angle_index": 13, + "end_angle_index": 13, + "trajectory_radius": 0.0, + "trajectory_length": 0.22361, + "arc_length": 0.0, + "straight_length": 0.22361, "poses": [ [ - -0.0, 0.0, - 1.6039569863244858 - ], - [ - -0.00186, - 0.05607, - 1.6700570766378058 - ], - [ - -0.00742, - 0.1119, - 1.7364138136920113 - ], - [ - -0.01667, - 0.16724, - 1.8026320742807778 + 0.0, + -1.1071487177940904 ], [ - -0.02956, - 0.22184, - 1.8689283388184512 + 0.03333, + -0.06667, + -1.1071487177940904 ], [ - -0.04604, - 0.27547, - 1.9351163528219084 + 0.06667, + -0.13333, + -1.1071487177940904 ], [ - -0.06603, - 0.32789, - 2.00119994735516 + 0.1, + -0.2, + -1.1071487177940904 ] ] }, { - "trajectoryId": 95, - "startAngle": 90.0, - "endAngle": 0.0, - "radius": 0.5, - "trajectoryLength": 0.8353981633974483, - "arcLength": 0.7853981633974483, - "straightLength": 0.050000000000000044, + "trajectory_id": 69, + "start_angle_index": 13, + "end_angle_index": 14, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ - 0.0, - 0.0, - 1.5707963267948966 + -6e-05, + -3e-05, + -1.1071487177940904 ], [ - 0.0, - 0.05, - 1.5184141329299277 + 0.03646, + -0.06423, + -0.9998985329952097 ], [ - 0.00274, - 0.10226, - 1.4136879296500158 + 0.07965, + -0.12415, + -0.892648348196329 ], [ - 0.01093, - 0.15396, - 1.3090861204812356 + 0.129, + -0.1791, + -0.7853981633974483 ], [ - 0.02447, - 0.20451, - 1.2041986404066858 + 0.129, + -0.1791, + -0.7853981633974483 ], [ - 0.04323, - 0.25337, - 1.0995433269194599 - ], + 0.15, + -0.2, + -0.7853981633974483 + ] + ] + }, + { + "trajectory_id": 70, + "start_angle_index": 14, + "end_angle_index": 12, + "trajectory_radius": 0.5121, + "trajectory_length": 0.44007, + "arc_length": 0.4022, + "straight_length": 0.03787, + "poses": [ [ - 0.06699, - 0.3, - 0.9948777271765432 + 1e-05, + 1e-05, + -0.7853981633974483 ], [ - 0.09549, - 0.34389, - 0.8901478270870059 + 0.03828, + -0.04281, + -0.8975979010256552 ], [ - 0.12843, - 0.38457, - 0.785398163397448 + 0.07151, + -0.08965, + -1.009797638653862 ], [ - 0.16543, - 0.42157, - 0.680648499707892 + 0.09929, + -0.13991, + -1.121997376282069 ], [ - 0.20611, - 0.45451, - 0.5759185996183525 + 0.12126, + -0.19296, + -1.2341971139102759 ], [ - 0.25, - 0.48301, - 0.47125299987543784 + 0.13716, + -0.24815, + -1.3463968515384828 ], [ - 0.29663, - 0.50677, - 0.3665976863882106 + 0.14678, + -0.30476, + -1.4585965891666897 ], [ - 0.34549, - 0.52553, - 0.261710206313661 + 0.15, + -0.3621, + -1.5707963267948966 ], [ - 0.39604, - 0.53907, - 0.15710839714487923 + 0.15, + -0.3621, + -1.5707963267948966 ], [ - 0.44774, - 0.54726, - 0.05238219386497044 + 0.15, + -0.4, + -1.5707963267948966 ] ] }, { - "trajectoryId": 96, - "startAngle": 90.0, - "endAngle": 180.0, - "radius": 0.5, - "trajectoryLength": 0.8353981633974483, - "arcLength": 0.7853981633974483, - "straightLength": 0.050000000000000044, + "trajectory_id": 71, + "start_angle_index": 14, + "end_angle_index": 13, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ - -0.0, 0.0, - 1.5707963267948966 + 0.0, + -0.7853981633974483 ], [ - -0.0, - 0.05, - 1.6231785206598657 + 0.021, + -0.0209, + -0.7853981633974483 ], [ - -0.00274, - 0.10226, - 1.7279047239397773 + 0.021, + -0.0209, + -0.7853981633974483 ], [ - -0.01093, - 0.15396, - 1.8325065331085577 + 0.07035, + -0.07585, + -0.892648348196329 ], [ - -0.02447, - 0.20451, - 1.9373940131831073 + 0.11354, + -0.13577, + -0.9998985329952097 ], [ - -0.04323, - 0.25337, - 2.0420493266703335 - ], + 0.15006, + -0.19997, + -1.1071487177940904 + ] + ] + }, + { + "trajectory_id": 72, + "start_angle_index": 14, + "end_angle_index": 14, + "trajectory_radius": 0.0, + "trajectory_length": 0.21213, + "arc_length": 0.0, + "straight_length": 0.21213, + "poses": [ [ - -0.06699, - 0.3, - 2.14671492641325 + 0.0, + 0.0, + -0.7853981633974483 ], [ - -0.09549, - 0.34389, - 2.2514448265027873 + 0.05, + -0.05, + -0.7853981633974483 ], [ - -0.12843, - 0.38457, - 2.3561944901923453 + 0.1, + -0.1, + -0.7853981633974483 ], [ - -0.16543, - 0.42157, - 2.460944153881901 - ], + 0.15, + -0.15, + -0.7853981633974483 + ] + ] + }, + { + "trajectory_id": 73, + "start_angle_index": 14, + "end_angle_index": 15, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, + "poses": [ [ - -0.20611, - 0.45451, - 2.5656740539714407 + 0.0, + 0.0, + -0.7853981633974483 ], [ - -0.25, - 0.48301, - 2.6703396537143553 + 0.0209, + -0.021, + -0.7853981633974483 ], [ - -0.29663, - 0.50677, - 2.774994967201583 + 0.0209, + -0.021, + -0.7853981633974483 ], [ - -0.34549, - 0.52553, - 2.8798824472761324 + 0.07585, + -0.07035, + -0.6781479785985676 ], [ - -0.39604, - 0.53907, - 2.984484256444914 + 0.13577, + -0.11354, + -0.5708977937996869 ], [ - -0.44774, - 0.54726, - 3.0892104597248227 + 0.19997, + -0.15006, + -0.46364760900080615 ] ] }, { - "trajectoryId": 97, - "startAngle": -90.0, - "endAngle": -90.0, - "radius": 0, - "trajectoryLength": 0.2, - "arcLength": 0.0, - "straightLength": 0.2, + "trajectory_id": 74, + "start_angle_index": 14, + "end_angle_index": 0, + "trajectory_radius": 0.5121, + "trajectory_length": 0.44007, + "arc_length": 0.4022, + "straight_length": 0.03787, "poses": [ [ - 0.0, - -0.0, - -1.5707963267948966 + -1e-05, + -1e-05, + -0.7853981633974483 ], [ - 0.0, - -0.06667, - -1.5707963267948966 + 0.04281, + -0.03828, + -0.6731984257692414 ], [ - 0.0, - -0.13333, - -1.5707963267948966 - ] - ] - }, - { - "trajectoryId": 98, - "startAngle": -90.0, - "endAngle": -116.56505117707799, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ + 0.08965, + -0.07151, + -0.5609986881410345 + ], [ - -0.0, - -0.0, - -1.6480841775864215 + 0.13991, + -0.09929, + -0.4487989505128276 ], [ - -0.00505, - -0.06521, - -1.8026837228555432 + 0.19296, + -0.12126, + -0.3365992128846207 ], [ - -0.02008, - -0.12886, - -1.9570951315988976 - ] - ] - }, - { - "trajectoryId": 99, - "startAngle": -90.0, - "endAngle": -63.43494882292201, - "radius": 0.4236, - "trajectoryLength": 0.20820112717274147, - "arcLength": 0.19640112717274147, - "straightLength": 0.011799999999999991, - "poses": [ + 0.24815, + -0.13716, + -0.2243994752564138 + ], [ - 0.0, - -0.0, - -1.4935084760033717 + 0.30476, + -0.14678, + -0.1121997376282069 + ], + [ + 0.3621, + -0.15, + 0.0 ], [ - 0.00505, - -0.06521, - -1.3389089307342499 + 0.3621, + -0.15, + 0.0 ], [ - 0.02008, - -0.12886, - -1.1844975219908958 + 0.4, + -0.15, + 0.0 ] ] }, { - "trajectoryId": 100, - "startAngle": -90.0, - "endAngle": -116.56505117707799, - "radius": 0.8472, - "trajectoryLength": 0.41640225434548295, - "arcLength": 0.39280225434548294, - "straightLength": 0.023599999999999982, + "trajectory_id": 75, + "start_angle_index": 15, + "end_angle_index": 14, + "trajectory_radius": 0.689, + "trajectory_length": 0.25131, + "arc_length": 0.22169, + "straight_length": 0.02962, "poses": [ [ - -0.0, - -0.0, - -1.6039569863244858 - ], - [ - -0.00186, - -0.05607, - -1.6700570766378058 + 3e-05, + 6e-05, + -0.46364760900080615 ], [ - -0.00742, - -0.1119, - -1.7364138136920113 + 0.06423, + -0.03646, + -0.5708977937996869 ], [ - -0.01667, - -0.16724, - -1.8026320742807778 + 0.12415, + -0.07965, + -0.6781479785985676 ], [ - -0.02956, - -0.22184, - -1.8689283388184512 + 0.1791, + -0.129, + -0.7853981633974483 ], [ - -0.04604, - -0.27547, - -1.9351163528219084 + 0.1791, + -0.129, + -0.7853981633974483 ], [ - -0.06603, - -0.32789, - -2.00119994735516 + 0.2, + -0.15, + -0.7853981633974483 ] ] }, { - "trajectoryId": 101, - "startAngle": -90.0, - "endAngle": -63.43494882292201, - "radius": 0.8472, - "trajectoryLength": 0.41640225434548295, - "arcLength": 0.39280225434548294, - "straightLength": 0.023599999999999982, + "trajectory_id": 76, + "start_angle_index": 15, + "end_angle_index": 15, + "trajectory_radius": 0.0, + "trajectory_length": 0.22361, + "arc_length": 0.0, + "straight_length": 0.22361, "poses": [ [ 0.0, - -0.0, - -1.5376356672653075 - ], - [ - 0.00186, - -0.05607, - -1.4715355769519873 - ], - [ - 0.00742, - -0.1119, - -1.405178839897782 - ], - [ - 0.01667, - -0.16724, - -1.3389605793090156 + 0.0, + -0.4636476090008061 ], [ - 0.02956, - -0.22184, - -1.272664314771342 + 0.06667, + -0.03333, + -0.4636476090008061 ], [ - 0.04604, - -0.27547, - -1.2064763007678847 + 0.13333, + -0.06667, + -0.4636476090008061 ], [ - 0.06603, - -0.32789, - -1.1403927062346335 + 0.2, + -0.1, + -0.4636476090008061 ] ] }, { - "trajectoryId": 102, - "startAngle": -90.0, - "endAngle": -180.0, - "radius": 0.5, - "trajectoryLength": 0.8353981633974483, - "arcLength": 0.7853981633974483, - "straightLength": 0.050000000000000044, + "trajectory_id": 77, + "start_angle_index": 15, + "end_angle_index": 0, + "trajectory_radius": 0.6354, + "trajectory_length": 0.36821, + "arc_length": 0.2946, + "straight_length": 0.07361, "poses": [ [ - -0.0, - -0.0, - -1.5707963267948966 + 0.0, + 0.0, + -0.4636476090008061 ], [ - -0.0, - -0.05, - -1.6231785206598657 + 0.06584, + -0.03292, + -0.4636476090008061 ], [ - -0.00274, - -0.10226, - -1.7279047239397773 + 0.06584, + -0.03292, + -0.46364760900080615 ], [ - -0.01093, - -0.15396, - -1.8325065331085577 + 0.11969, + -0.05679, + -0.370918087200645 ], [ - -0.02447, - -0.20451, - -1.9373940131831073 + 0.17551, + -0.07557, + -0.27818856540048387 ], [ - -0.04323, - -0.25337, - -2.0420493266703335 + 0.23283, + -0.0891, + -0.18545904360032228 ], [ - -0.06699, - -0.3, - -2.14671492641325 + 0.29116, + -0.09727, + -0.09272952180016114 ], [ - -0.09549, - -0.34389, - -2.2514448265027873 + 0.35, + -0.1, + 0.0 + ] + ] + }, + { + "trajectory_id": 78, + "start_angle_index": 15, + "end_angle_index": 1, + "trajectory_radius": 0.5031, + "trajectory_length": 0.46652, + "arc_length": 0.46652, + "straight_length": 0, + "poses": [ + [ + 1e-05, + 1e-05, + -0.46364760900080615 ], [ - -0.12843, - -0.38457, - -2.3561944901923453 + 0.05356, + -0.02299, + -0.3477357067506044 ], [ - -0.16543, - -0.42157, - -2.460944153881901 + 0.10941, + -0.03964, + -0.23182380450040307 ], [ - -0.20611, - -0.45451, - -2.5656740539714407 + 0.16682, + -0.04972, + -0.11591190225020132 ], [ - -0.25, - -0.48301, - -2.6703396537143553 + 0.225, + -0.0531, + 0.0 ], [ - -0.29663, - -0.50677, - -2.774994967201583 + 0.28318, + -0.04972, + 0.11591190225020132 ], [ - -0.34549, - -0.52553, - -2.8798824472761324 + 0.34059, + -0.03964, + 0.23182380450040307 ], [ - -0.39604, - -0.53907, - -2.984484256444914 + 0.39644, + -0.02299, + 0.3477357067506044 ], [ - -0.44774, - -0.54726, - -3.0892104597248227 + 0.44999, + 1e-05, + 0.46364760900080615 ] ] }, { - "trajectoryId": 103, - "startAngle": -90.0, - "endAngle": -0.0, - "radius": 0.5, - "trajectoryLength": 0.8353981633974483, - "arcLength": 0.7853981633974483, - "straightLength": 0.050000000000000044, + "trajectory_id": 79, + "start_angle_index": 15, + "end_angle_index": 1, + "trajectory_radius": 0.6149, + "trajectory_length": 0.57019, + "arc_length": 0.57019, + "straight_length": 0, "poses": [ [ - 0.0, - -0.0, - -1.5707963267948966 - ], - [ - 0.0, - -0.05, - -1.5184141329299277 - ], - [ - 0.00274, - -0.10226, - -1.4136879296500158 - ], - [ - 0.01093, - -0.15396, - -1.3090861204812356 - ], - [ - 0.02447, - -0.20451, - -1.2041986404066858 - ], - [ - 0.04323, - -0.25337, - -1.0995433269194599 + 1e-05, + 2e-05, + -0.46364760900080615 ], [ - 0.06699, - -0.3, - -0.9948777271765432 + 0.05212, + -0.02308, + -0.370918087200645 ], [ - 0.09549, - -0.34389, - -0.8901478270870059 + 0.10614, + -0.04126, + -0.27818856540048387 ], [ - 0.12843, - -0.38457, - -0.785398163397448 + 0.16161, + -0.05436, + -0.18545904360032228 ], [ - 0.16543, - -0.42157, - -0.680648499707892 + 0.21806, + -0.06226, + -0.09272952180016114 ], [ - 0.20611, - -0.45451, - -0.5759185996183525 + 0.275, + -0.0649, + 0.0 ], [ - 0.25, - -0.48301, - -0.47125299987543784 + 0.33194, + -0.06226, + 0.09272952180016114 ], [ - 0.29663, - -0.50677, - -0.3665976863882106 + 0.38839, + -0.05436, + 0.18545904360032228 ], [ - 0.34549, - -0.52553, - -0.261710206313661 + 0.44386, + -0.04126, + 0.27818856540048387 ], [ - 0.39604, - -0.53907, - -0.15710839714487923 + 0.49788, + -0.02308, + 0.370918087200645 ], [ - 0.44774, - -0.54726, - -0.05238219386497044 + 0.54999, + 2e-05, + 0.46364760900080615 ] ] } ] -} +} \ No newline at end of file diff --git a/nav2_smac_planner/test/test_nodehybrid.cpp b/nav2_smac_planner/test/test_nodehybrid.cpp index 9954a011ef..910d590e07 100644 --- a/nav2_smac_planner/test/test_nodehybrid.cpp +++ b/nav2_smac_planner/test/test_nodehybrid.cpp @@ -144,7 +144,6 @@ TEST(NodeHybridTest, test_node_debin_neighbors) nav2_smac_planner::NodeHybrid::initMotionModel( nav2_smac_planner::MotionModel::DUBIN, size_x, size_y, size_theta, info); - // test neighborhood computation EXPECT_EQ(nav2_smac_planner::NodeHybrid::motion_table.projections.size(), 3u); EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[0]._x, 1.731517, 0.01); diff --git a/nav2_smac_planner/test/test_nodelattice.cpp b/nav2_smac_planner/test/test_nodelattice.cpp index 2ec9083fec..81019e034d 100644 --- a/nav2_smac_planner/test/test_nodelattice.cpp +++ b/nav2_smac_planner/test/test_nodelattice.cpp @@ -1,4 +1,5 @@ // Copyright (c) 2021 Joshua Wallace +// Copyright (c) 2021 Samsung Research America // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -12,109 +13,210 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. +#include +#include +#include +#include +#include #include "nav2_smac_planner/node_lattice.hpp" #include "gtest/gtest.h" #include "ament_index_cpp/get_package_share_directory.hpp" -#include using json = nlohmann::json; TEST(NodeLatticeTest, parser_test) { - std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); - std::string filePath = pkg_share_dir + "/output.json"; - std::ifstream myJsonFile(filePath); - - ASSERT_TRUE(myJsonFile.is_open()); - - json j; - myJsonFile >> j; - - nav2_smac_planner::LatticeMetadata metaData; - nav2_smac_planner::MotionPrimitive myPrimitive; - nav2_smac_planner::MotionPose pose; - - json jsonMetaData = j["latticeMetadata"]; - json jsonPrimatives = j["primitives"]; - json jsonPose = jsonPrimatives[0]["poses"][0]; - - nav2_smac_planner::fromJsonToMetaData(jsonMetaData, metaData); - - //Checks for parsing meta data - EXPECT_NEAR(metaData.min_turning_radius, 0.4, 0.001); - EXPECT_NEAR(metaData.primitive_resolution, 0.005, 0.0001); - EXPECT_NEAR(metaData.grid_resolution, 0.05, 0.001); - EXPECT_NEAR(metaData.max_length, 1, 0.01); - EXPECT_NEAR(metaData.number_of_headings, 16, 0.01); - EXPECT_EQ(metaData.output_file, "output.json"); - EXPECT_NEAR(metaData.heading_angles[0], -180.0, 0.01); - - std::vector myPrimitives; - for(unsigned int i = 0; i < jsonPrimatives.size() ; ++i) - { - nav2_smac_planner::MotionPrimitive newPrimative; - nav2_smac_planner::fromJsonToMotionPrimitive(jsonPrimatives[i], newPrimative ); - myPrimitives.push_back(newPrimative); - } - - //Checks for parsing primitives - EXPECT_NEAR(myPrimitives[0].trajectory_id, 0, 0.01); - EXPECT_NEAR(myPrimitives[0].start_angle, 0.0,0.01); - EXPECT_NEAR(myPrimitives[0].end_angle, 0.0, 0.01); - EXPECT_NEAR(myPrimitives[0].turning_radius, 0.0, 0.01); - EXPECT_NEAR(myPrimitives[0].trajectory_length, 0.2, 0.01); - EXPECT_NEAR(myPrimitives[0].arc_length, 0.0, 0.01); - EXPECT_NEAR(myPrimitives[0].straight_length, 0.2, 0.01); - - EXPECT_NEAR(myPrimitives[0].poses[0]._x, 0.0, 0.01); - EXPECT_NEAR(myPrimitives[0].poses[0]._y, 0.0, 0.01); - EXPECT_NEAR(myPrimitives[0].poses[0]._theta, 0.0, 0.01); - - EXPECT_NEAR(myPrimitives[0].poses[1]._x, 0.06667, 0.01); - EXPECT_NEAR(myPrimitives[0].poses[1]._y, 0.0, 0.01); - EXPECT_NEAR(myPrimitives[0].poses[1]._theta, 0.0, 0.01); + std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); + std::string filePath = pkg_share_dir + "/output.json"; + std::ifstream myJsonFile(filePath); + + ASSERT_TRUE(myJsonFile.is_open()); + + json j; + myJsonFile >> j; + + nav2_smac_planner::LatticeMetadata metaData; + nav2_smac_planner::MotionPrimitive myPrimitive; + nav2_smac_planner::MotionPose pose; + + json jsonMetaData = j["lattice_metadata"]; + json jsonPrimatives = j["primitives"]; + json jsonPose = jsonPrimatives[0]["poses"][0]; + + nav2_smac_planner::fromJsonToMetaData(jsonMetaData, metaData); + + // Checks for parsing meta data + EXPECT_NEAR(metaData.min_turning_radius, 0.5, 0.001); + EXPECT_NEAR(metaData.grid_resolution, 0.05, 0.001); + EXPECT_NEAR(metaData.number_of_headings, 16, 0.01); + EXPECT_EQ(metaData.output_file, "output.json"); + EXPECT_NEAR(metaData.heading_angles[0], 0.0, 0.01); + EXPECT_EQ(metaData.number_of_trajectories, 80u); + EXPECT_EQ(metaData.motion_model, std::string("ackermann")); + + std::vector myPrimitives; + for (unsigned int i = 0; i < jsonPrimatives.size(); ++i) { + nav2_smac_planner::MotionPrimitive newPrimative; + nav2_smac_planner::fromJsonToMotionPrimitive(jsonPrimatives[i], newPrimative); + myPrimitives.push_back(newPrimative); + } + + // Checks for parsing primitives + EXPECT_EQ(myPrimitives.size(), 80u); + EXPECT_NEAR(myPrimitives[0].trajectory_id, 0, 0.01); + EXPECT_NEAR(myPrimitives[0].start_angle, 0.0, 0.01); + EXPECT_NEAR(myPrimitives[0].end_angle, 13, 0.01); + EXPECT_NEAR(myPrimitives[0].turning_radius, 0.5259, 0.01); + EXPECT_NEAR(myPrimitives[0].trajectory_length, 0.64856, 0.01); + EXPECT_NEAR(myPrimitives[0].arc_length, 0.58225, 0.01); + EXPECT_NEAR(myPrimitives[0].straight_length, 0.06631, 0.01); + + EXPECT_NEAR(myPrimitives[0].poses[0]._x, 0.0, 0.01); + EXPECT_NEAR(myPrimitives[0].poses[0]._y, 0.0, 0.01); + EXPECT_NEAR(myPrimitives[0].poses[0]._theta, 0.0, 0.01); + + EXPECT_NEAR(myPrimitives[0].poses[1]._x, 0.05284, 0.01); + EXPECT_NEAR(myPrimitives[0].poses[1]._y, -0.00266, 0.01); + EXPECT_NEAR(myPrimitives[0].poses[1]._theta, -0.10064988343582648, 0.01); +} + +TEST(NodeLatticeTest, test_node_lattice_neighbors_and_parsing) +{ + std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); + std::string filePath = pkg_share_dir + "/output.json"; + + nav2_smac_planner::SearchInfo info; + info.minimum_turning_radius = 1.1; + info.non_straight_penalty = 1; + info.change_penalty = 1; + info.reverse_penalty = 1; + info.cost_penalty = 1; + info.analytic_expansion_ratio = 1; + info.lattice_filepath = filePath; + info.cache_obstacle_heuristic = true; + + unsigned int x = 100; + unsigned int y = 100; + unsigned int angle_quantization = 16; + + nav2_smac_planner::NodeLattice::initMotionModel( + nav2_smac_planner::MotionModel::STATE_LATTICE, x, y, angle_quantization, info); + + nav2_smac_planner::NodeLattice aNode(0); + aNode.setPose(nav2_smac_planner::NodeHybrid::Coordinates(0, 0, 0)); + nav2_smac_planner::MotionPrimitives projections = + nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives(&aNode); + + EXPECT_NEAR(projections[0].poses.back()._x, 0.5, 0.01); + EXPECT_NEAR(projections[0].poses.back()._y, -0.35, 0.01); + EXPECT_NEAR(projections[0].poses.back()._theta, -1.107, 0.01); + + EXPECT_NEAR( + nav2_smac_planner::NodeLattice::motion_table.getLatticeMetadata( + filePath).grid_resolution, 0.05, 0.005); } -TEST(NodeLatticeTest, test_node_lattice_neighbors) +TEST(NodeLatticeTest, test_node_lattice_conversions) { - std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); - std::string filePath = pkg_share_dir + "/output.json"; - - nav2_smac_planner::SearchInfo info; - info.minimum_turning_radius = 1.1; - info.non_straight_penalty = 1; - info.change_penalty = 1; - info.reverse_penalty = 1; - info.cost_penalty = 1; - info.analytic_expansion_ratio = 1; - info.lattice_filepath = filePath; - info.cache_obstacle_heuristic = true; - - unsigned int x = 100; - unsigned int y = 100; - unsigned int angle_quantization = 16; - - nav2_smac_planner::NodeLattice::initMotionModel(nav2_smac_planner::MotionModel::STATE_LATTICE, - x, - y, - angle_quantization, - info); - - nav2_smac_planner::NodeLattice aNode(0); - aNode.setPose( nav2_smac_planner::NodeHybrid::Coordinates(0, 0, 0) ); - nav2_smac_planner::MotionPrimitives projections = nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives(&aNode); - - // TODO meaning of returns have changed - // EXPECT_NEAR(projections[0]._x, 0.13333, 0.01); - // EXPECT_NEAR(projections[0]._y, 0.0, 0.01); - // EXPECT_NEAR(projections[0]._theta, 0.0, 0.01); - - aNode.setPose(nav2_smac_planner::NodeHybrid::Coordinates(0, 0, 1)); - - projections = nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives(&aNode); - - // TODO meaning of returns have changed - // EXPECT_NEAR(projections[0]._x, -0.13333, 0.01); - // EXPECT_NEAR(projections[0]._y, 0.0, 0.01); - // EXPECT_NEAR(projections[0]._theta, 3.14, 0.01); -} \ No newline at end of file + std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); + std::string filePath = pkg_share_dir + "/output.json"; + + nav2_smac_planner::SearchInfo info; + info.minimum_turning_radius = 1.1; + info.non_straight_penalty = 1; + info.change_penalty = 1; + info.reverse_penalty = 1; + info.cost_penalty = 1; + info.analytic_expansion_ratio = 1; + info.lattice_filepath = filePath; + info.cache_obstacle_heuristic = true; + + unsigned int x = 100; + unsigned int y = 100; + unsigned int angle_quantization = 16; + + nav2_smac_planner::NodeLattice::initMotionModel( + nav2_smac_planner::MotionModel::STATE_LATTICE, x, y, angle_quantization, info); + + nav2_smac_planner::NodeLattice aNode(0); + aNode.setPose(nav2_smac_planner::NodeHybrid::Coordinates(0, 0, 0)); + + EXPECT_NEAR(aNode.motion_table.getAngleFromBin(0u), 0.0, 0.005); + EXPECT_NEAR(aNode.motion_table.getAngleFromBin(1u), 0.46364, 0.005); + EXPECT_NEAR(aNode.motion_table.getAngleFromBin(2u), 0.78539, 0.005); + + EXPECT_EQ(aNode.motion_table.getClosestAngularBin(0.0), 0u); + EXPECT_EQ(aNode.motion_table.getClosestAngularBin(0.5), 1u); + EXPECT_EQ(aNode.motion_table.getClosestAngularBin(1.5), 4u); +} + +TEST(NodeLatticeTest, test_node_lattice) +{ + std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); + std::string filePath = pkg_share_dir + "/output.json"; + + nav2_smac_planner::SearchInfo info; + info.minimum_turning_radius = 1.1; + info.non_straight_penalty = 1; + info.change_penalty = 1; + info.reverse_penalty = 1; + info.cost_penalty = 1; + info.analytic_expansion_ratio = 1; + info.lattice_filepath = filePath; + info.cache_obstacle_heuristic = true; + + unsigned int x = 100; + unsigned int y = 100; + unsigned int angle_quantization = 16; + + nav2_smac_planner::NodeLattice::initMotionModel( + nav2_smac_planner::MotionModel::STATE_LATTICE, x, y, angle_quantization, info); + + // Check defaults + nav2_smac_planner::NodeLattice aNode(0); + nav2_smac_planner::NodeLattice testA(49); + EXPECT_EQ(testA.getIndex(), 49u); + EXPECT_EQ(testA.getAccumulatedCost(), std::numeric_limits::max()); + EXPECT_TRUE(std::isnan(testA.getCost())); + EXPECT_EQ(testA.getMotionPrimitive(), nullptr); + + // Test visited state / reset + EXPECT_EQ(testA.wasVisited(), false); + testA.visited(); + EXPECT_EQ(testA.wasVisited(), true); + testA.reset(); + EXPECT_EQ(testA.wasVisited(), false); + + nav2_costmap_2d::Costmap2D * costmapA = new nav2_costmap_2d::Costmap2D( + 10, 10, 0.05, 0.0, 0.0, 0); + std::unique_ptr checker = + std::make_unique(costmapA, 72); + checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0); + + // test node valid and cost + testA.pose.x = 5; + testA.pose.y = 5; + testA.pose.theta = 0; + EXPECT_EQ(testA.isNodeValid(true, checker.get()), true); + EXPECT_EQ(testA.isNodeValid(false, checker.get()), true); + EXPECT_EQ(testA.getCost(), 0.0f); + + // check collision checking + EXPECT_EQ(testA.isNodeValid(false, checker.get()), true); + + // check operator== works on index + nav2_smac_planner::NodeLattice testC(49); + EXPECT_TRUE(testA == testC); + + // check accumulated costs are set + testC.setAccumulatedCost(100); + EXPECT_EQ(testC.getAccumulatedCost(), 100.0f); + + // check set pose and pose + testC.setPose(nav2_smac_planner::NodeLattice::Coordinates(10.0, 5.0, 4)); + EXPECT_EQ(testC.pose.x, 10.0); + EXPECT_EQ(testC.pose.y, 5.0); + EXPECT_EQ(testC.pose.theta, 4); + + delete costmapA; +} From 79f8f00181010b1e9f33a35c87fb921b3d092aaa Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Mon, 18 Oct 2021 15:07:04 -0700 Subject: [PATCH 09/31] adding updated rosdep key --- nav2_smac_planner/README.md | 20 ++++++++++++-------- nav2_smac_planner/package.xml | 2 +- 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index 2fbc5b7420..fb51ea275c 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -14,24 +14,27 @@ It also introduces the following basic building blocks: We have users reporting using this on: - Delivery robots - Industrial robots +- Vertical farming ## Introduction -The `nav2_smac_planner` package contains an optimized templated A* search algorithm used to create multiple A\*-based planners for multiple types of robot platforms. It was built by [Steve Macenski](https://www.linkedin.com/in/steve-macenski-41a985101/) while at [Samsung Research](https://www.sra.samsung.com/). We support **circular** differential-drive and omni-directional drive robots using the `SmacPlanner2D` planner which implements a cost-aware A\* planner. We support **cars, car-like, and ackermann vehicles** using the `SmacPlannerHybrid` plugin which implements a Hybrid-A\* planner. We support **non-circular, arbitrary shaped** differntial drive and omnidirectional vehicles using the `SmacPlannerLattice` plugin which implements a State Lattice planner. These plugins are also useful for curvature constrained planning, like when planning robot at high speeds to make sure they don't flip over or otherwise skid out of control. It is also applicable to non-round robots (such as large rectangular or arbitrary shaped robots of differential/omnidirectional drivetrains) that need pose-based collision checking. +The `nav2_smac_planner` package contains an optimized templated A* search algorithm used to create multiple A\*-based planners for multiple types of robot platforms. It was built by [Steve Macenski](https://www.linkedin.com/in/steve-macenski-41a985101/) while at [Samsung Research](https://www.sra.samsung.com/). We support **circular** differential-drive and omni-directional drive robots using the `SmacPlanner2D` planner which implements a cost-aware A\* planner. We support **legged, cars, car-like, and ackermann vehicles** using the `SmacPlannerHybrid` plugin which implements a Hybrid-A\* planner. We support **non-circular, arbitrary shaped, any model vehicles** using the `SmacPlannerLattice` plugin which implements a State Lattice planner. It contains control sets and generators for ackermann, legged, differential drive and omnidirectional vehicles, but you may provide your own for another robot type or to have different planning behaviors. The last two plugins are also useful for curvature constrained planning, like when planning robot at high speeds to make sure they don't flip over or otherwise skid out of control. It is also applicable to non-round robots (such as large rectangular or arbitrary shaped robots of differential/omnidirectional drivetrains) that need pose-based collision checking. The `SmacPlannerHybrid` implements the Hybrid-A* planner as proposed in [Practical Search Techniques in Path Planning for Autonomous Driving](https://ai.stanford.edu/~ddolgov/papers/dolgov_gpp_stair08.pdf), including hybrid searching, gradient descent smoothing, analytic expansions and hueristic functions. -The `SmacPlannerLattice` fully-implements the State Lattice planner with smoothing. While we do not implement it precisely the same way as [Optimal, Smooth, Nonholonomic MobileRobot Motion Planning in State Lattices](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2007_1/pivtoraiko_mihail_2007_1.pdf) (with control sets found using [Generating Near Minimal Spanning Control Sets for Constrained Motion Planning in Discrete State Spaces](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2005_1/pivtoraiko_mihail_2005_1.pdf)), it is sufficiently similar it may be used as a good reference. Additional optimizations for on-approach analytic expansions and simplier heuristic functions were used, largely matching those of Hybrid-A\*. +The `SmacPlannerLattice` implements the State Lattice planner with smoothing. While we do not implement it precisely the same way as [Optimal, Smooth, Nonholonomic MobileRobot Motion Planning in State Lattices](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2007_1/pivtoraiko_mihail_2007_1.pdf) (with control sets found using [Generating Near Minimal Spanning Control Sets for Constrained Motion Planning in Discrete State Spaces](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2005_1/pivtoraiko_mihail_2005_1.pdf)), it is sufficiently similar it may be used as a good reference. Additional optimizations for on-approach analytic expansions and simplier heuristic functions were used, largely matching those of Hybrid-A\*. In summary... The `SmacPlannerHybrid` is designed to work with: - Ackermann, car, and car-like robots - High speed or curvature constrained robots (as to not flip over, skid, or dump load at high speeds) -- Arbitrary shaped, non-circular differential or omnidirectional robots requiring SE2 collision checking with constrained curvatures +- Arbitrary shaped, non-circular differential or omnidirectional robots requiring kinematically feasible planning with SE2 collision checking +- Legged robots The `SmacPlannerLattice` is designed to work with: -- Arbitrary shaped, non-circular differential or omnidirectional robots requiring SE2 collision checking using the full capabilities of the drivetrain +- Arbitrary shaped, non-circular robots requiring kinematically feasible planning with SE2 collision checking using the full capabilities of the drivetrain +- Flexibility to use other robot model types or with provided non-circular differental, ackermann, and omni support The `SmacPlanner2D` is designed to work with: - Circular, differential or omnidirectional robots @@ -39,13 +42,13 @@ The `SmacPlanner2D` is designed to work with: ## Features -We further improve in the following ways: +We further improve on Hybrid-A\* in the following ways: - Remove need for upsampling by searching with 10x smaller motion primitives (same as their upsampling ratio). - Multi-resolution search allowing planning to occur at a coarser resolution for wider spaces (O(N^2) faster). - Cost-aware penalty functions in search resulting in far smoother plans (further reducing requirement to smooth). -- Gradient descent smoother +- Gradient-descent, basic but fast smoother - Faster planning than original paper by highly optimizing the template A\* algorithm. -- Faster planning via precomputed heuristic, motion primitive, and other values. +- Faster planning via custom precomputed heuristic, motion primitive, and other values. - Automatically adjusted search motion model sizes by motion model, costmap resolution, and bin sizing. - Closest path on approach within tolerance if exact path cannot be found or in invalid space. - Multi-model hybrid searching including Dubin and Reeds-Shepp models. More models may be trivially added. @@ -111,7 +114,8 @@ planner_server: non_straight_penalty: 1.50 # For Hybrid nodes: penalty to apply if motion is non-straight, must be => 1 cost_penalty: 1.7 # For Hybrid nodes: penalty to apply to higher cost areas when adding into the obstacle map dynamic programming distance expansion heuristic. This drives the robot more towards the center of passages. A value between 1.3 - 3.5 is reasonable. lookup_table_size: 20 # For Hybrid nodes: Size of the dubin/reeds-sheep distance window to cache, in meters. - cache_obstacle_heuristic: True # For Hybrid nodes: Cache the obstacle map dynamic programming distance expansion heuristic between subsiquent replannings of the same goal location. Dramatically speeds up replanning performance (40x) if costmap is largely static. + cache_obstacle_heuristic: True # For Hybrid nodes: Cache the obstacle map dynamic programming distance expansion heuristic between subsiquent replannings of the same goal location. Dramatically speeds up replanning performance (40x) if costmap is largely static. + allow_reverse_expansion: False # For Lattice nodes: Whether to expand state lattice graph in forward primitives or reverse as well, will double the branching factor at each step. smoother: max_iterations: 1000 w_smooth: 0.3 diff --git a/nav2_smac_planner/package.xml b/nav2_smac_planner/package.xml index c7bf1261ec..2f1091f4dc 100644 --- a/nav2_smac_planner/package.xml +++ b/nav2_smac_planner/package.xml @@ -26,7 +26,7 @@ eigen3_cmake_module eigen ompl - nlohmann_json + nlohmann-json-dev ament_lint_common ament_lint_auto From 6425699b40f9121c4f17648f71bb527f7edbb76f Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Mon, 25 Oct 2021 16:56:30 -0700 Subject: [PATCH 10/31] compiling, generating paths (though bogus) --- .../include/nav2_smac_planner/types.hpp | 1 - .../include/nav2_smac_planner/utils.hpp | 1 - nav2_smac_planner/src/node_lattice.cpp | 3 +- nav2_smac_planner/src/smac_planner_2d.cpp | 2 + nav2_smac_planner/src/smac_planner_hybrid.cpp | 2 + .../src/smac_planner_lattice.cpp | 16 ++- nav2_smac_planner/test/output.json | 97 +++++++++++++++++-- nav2_smac_planner/test/test_nodelattice.cpp | 1 - 8 files changed, 109 insertions(+), 14 deletions(-) diff --git a/nav2_smac_planner/include/nav2_smac_planner/types.hpp b/nav2_smac_planner/include/nav2_smac_planner/types.hpp index 89fcffcc74..927f3934a1 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/types.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/types.hpp @@ -130,7 +130,6 @@ struct LatticeMetadata float min_turning_radius; float grid_resolution; unsigned int number_of_headings; - std::string output_file; std::vector heading_angles; unsigned int number_of_trajectories; std::string motion_model; diff --git a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp index e9d1f685a7..68a618ee79 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp @@ -113,7 +113,6 @@ inline void fromJsonToMetaData(const nlohmann::json & json, LatticeMetadata & la json.at("turning_radius").get_to(lattice_metadata.min_turning_radius); json.at("grid_resolution").get_to(lattice_metadata.grid_resolution); json.at("num_of_headings").get_to(lattice_metadata.number_of_headings); - json.at("output_file").get_to(lattice_metadata.output_file); json.at("heading_angles").get_to(lattice_metadata.heading_angles); json.at("number_of_trajectories").get_to(lattice_metadata.number_of_trajectories); json.at("motion_model").get_to(lattice_metadata.motion_model); diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index 5b1918057f..a6714ae67a 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -237,7 +237,7 @@ bool NodeLattice::isNodeValid( // Convert primitive pose into grid space if it should be checked prim_pose._x = initial_pose._x + (it->_x / grid_resolution); prim_pose._y = initial_pose._y + (it->_y / grid_resolution); - prim_pose._theta = initial_pose._theta + it->_theta; /*rad*/ + prim_pose._theta = it->_theta; /*rad*/ // TODO initial_pose._theta + if (prim_pose._theta < 0.0) { prim_pose._theta += 2.0 * M_PI; } @@ -424,6 +424,7 @@ void NodeLattice::precomputeDistanceHeuristic( motion_table.state_space = std::make_unique( search_info.minimum_turning_radius); } + motion_table.lattice_metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space); to[0] = 0.0; diff --git a/nav2_smac_planner/src/smac_planner_2d.cpp b/nav2_smac_planner/src/smac_planner_2d.cpp index 5e089e5969..db4d85fed0 100644 --- a/nav2_smac_planner/src/smac_planner_2d.cpp +++ b/nav2_smac_planner/src/smac_planner_2d.cpp @@ -58,6 +58,8 @@ void SmacPlanner2D::configure( _name = name; _global_frame = costmap_ros->getGlobalFrameID(); + RCLCPP_INFO(_logger, "Configuring %s of type SmacPlanner2D", name.c_str()); + // General planner params nav2_util::declare_parameter_if_not_declared( node, name + ".tolerance", rclcpp::ParameterValue(0.125)); diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 660248bb20..9565049cd5 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -60,6 +60,8 @@ void SmacPlannerHybrid::configure( _name = name; _global_frame = costmap_ros->getGlobalFrameID(); + RCLCPP_INFO(_logger, "Configuring %s of type SmacPlannerHybrid", name.c_str()); + int angle_quantizations; // General planner params diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index e6f3502b98..f2716ac603 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -56,9 +56,11 @@ void SmacPlannerLattice::configure( _name = name; _global_frame = costmap_ros->getGlobalFrameID(); + RCLCPP_INFO(_logger, "Configuring %s of type SmacPlannerLattice", name.c_str()); + bool allow_unknown; int max_iterations; - int lookup_table_size; + double lookup_table_size; SearchInfo search_info; // General planner params @@ -122,6 +124,18 @@ void SmacPlannerLattice::configure( static_cast(lookup_table_size) / static_cast(_costmap->getResolution() * _downsampling_factor); + // Make sure its a whole number + lookup_table_dim = static_cast(static_cast(lookup_table_dim)); + + // Make sure its an odd number + if (static_cast(lookup_table_dim) % 2 == 0) { + RCLCPP_INFO( + _logger, + "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd", + lookup_table_dim); + lookup_table_dim += 1.0; + } + // Initialize collision checker using 72 evenly sized bins instead of the lattice // heading angles. This is done so that we have precomputed angles every 5 degrees. // If we used the sparse lattice headings (usually 16), then when we attempt to collision diff --git a/nav2_smac_planner/test/output.json b/nav2_smac_planner/test/output.json index 07e1bfb1a4..25f46ac3d1 100644 --- a/nav2_smac_planner/test/output.json +++ b/nav2_smac_planner/test/output.json @@ -1,13 +1,12 @@ { "version": 1.0, - "date_generated": "2021-10-14", + "date_generated": "2021-10-24", "lattice_metadata": { "motion_model": "ackermann", "turning_radius": 0.5, "grid_resolution": 0.05, "stopping_threshold": 5, "num_of_headings": 16, - "output_file": "output.json", "heading_angles": [ 0.0, 0.4636476090008061, @@ -18,13 +17,13 @@ 2.356194490192345, 2.677945044588987, 3.141592653589793, - -2.677945044588987, - -2.356194490192345, - -2.0344439357957027, - -1.5707963267948966, - -1.1071487177940904, - -0.7853981633974483, - -0.4636476090008061 + 3.6052402625905993, + 3.9269908169872414, + 4.2487413713838835, + 4.71238898038469, + 5.176036589385496, + 5.497787143782138, + 5.81953769817878 ], "number_of_trajectories": 80 }, @@ -33,6 +32,7 @@ "trajectory_id": 0, "start_angle_index": 0, "end_angle_index": 13, + "left_turn": false, "trajectory_radius": 0.5259, "trajectory_length": 0.64856, "arc_length": 0.58225, @@ -114,6 +114,7 @@ "trajectory_id": 1, "start_angle_index": 0, "end_angle_index": 15, + "left_turn": false, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -165,6 +166,7 @@ "trajectory_id": 2, "start_angle_index": 0, "end_angle_index": 0, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.15, "arc_length": 0.0, @@ -191,6 +193,7 @@ "trajectory_id": 3, "start_angle_index": 0, "end_angle_index": 1, + "left_turn": true, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -242,6 +245,7 @@ "trajectory_id": 4, "start_angle_index": 0, "end_angle_index": 3, + "left_turn": true, "trajectory_radius": 0.5259, "trajectory_length": 0.64856, "arc_length": 0.58225, @@ -323,6 +327,7 @@ "trajectory_id": 5, "start_angle_index": 1, "end_angle_index": 15, + "left_turn": false, "trajectory_radius": 0.5031, "trajectory_length": 0.46652, "arc_length": 0.46652, @@ -379,6 +384,7 @@ "trajectory_id": 6, "start_angle_index": 1, "end_angle_index": 15, + "left_turn": false, "trajectory_radius": 0.6149, "trajectory_length": 0.57019, "arc_length": 0.57019, @@ -445,6 +451,7 @@ "trajectory_id": 7, "start_angle_index": 1, "end_angle_index": 0, + "left_turn": false, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -496,6 +503,7 @@ "trajectory_id": 8, "start_angle_index": 1, "end_angle_index": 1, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.22361, "arc_length": 0.0, @@ -527,6 +535,7 @@ "trajectory_id": 9, "start_angle_index": 1, "end_angle_index": 2, + "left_turn": true, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -568,6 +577,7 @@ "trajectory_id": 10, "start_angle_index": 2, "end_angle_index": 0, + "left_turn": false, "trajectory_radius": 0.5121, "trajectory_length": 0.44007, "arc_length": 0.4022, @@ -629,6 +639,7 @@ "trajectory_id": 11, "start_angle_index": 2, "end_angle_index": 1, + "left_turn": false, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -670,6 +681,7 @@ "trajectory_id": 12, "start_angle_index": 2, "end_angle_index": 2, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.21213, "arc_length": 0.0, @@ -701,6 +713,7 @@ "trajectory_id": 13, "start_angle_index": 2, "end_angle_index": 3, + "left_turn": true, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -742,6 +755,7 @@ "trajectory_id": 14, "start_angle_index": 2, "end_angle_index": 4, + "left_turn": true, "trajectory_radius": 0.5121, "trajectory_length": 0.44007, "arc_length": 0.4022, @@ -803,6 +817,7 @@ "trajectory_id": 15, "start_angle_index": 3, "end_angle_index": 2, + "left_turn": false, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -844,6 +859,7 @@ "trajectory_id": 16, "start_angle_index": 3, "end_angle_index": 3, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.22361, "arc_length": 0.0, @@ -875,6 +891,7 @@ "trajectory_id": 17, "start_angle_index": 3, "end_angle_index": 4, + "left_turn": true, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -926,6 +943,7 @@ "trajectory_id": 18, "start_angle_index": 3, "end_angle_index": 5, + "left_turn": true, "trajectory_radius": 0.5031, "trajectory_length": 0.46652, "arc_length": 0.46652, @@ -982,6 +1000,7 @@ "trajectory_id": 19, "start_angle_index": 3, "end_angle_index": 5, + "left_turn": true, "trajectory_radius": 0.6149, "trajectory_length": 0.57019, "arc_length": 0.57019, @@ -1048,6 +1067,7 @@ "trajectory_id": 20, "start_angle_index": 4, "end_angle_index": 1, + "left_turn": false, "trajectory_radius": 0.5259, "trajectory_length": 0.64856, "arc_length": 0.58225, @@ -1129,6 +1149,7 @@ "trajectory_id": 21, "start_angle_index": 4, "end_angle_index": 3, + "left_turn": false, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -1180,6 +1201,7 @@ "trajectory_id": 22, "start_angle_index": 4, "end_angle_index": 4, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.15, "arc_length": 0.0, @@ -1206,6 +1228,7 @@ "trajectory_id": 23, "start_angle_index": 4, "end_angle_index": 5, + "left_turn": true, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -1257,6 +1280,7 @@ "trajectory_id": 24, "start_angle_index": 4, "end_angle_index": 7, + "left_turn": true, "trajectory_radius": 0.5259, "trajectory_length": 0.64856, "arc_length": 0.58225, @@ -1338,6 +1362,7 @@ "trajectory_id": 25, "start_angle_index": 5, "end_angle_index": 3, + "left_turn": false, "trajectory_radius": 0.5031, "trajectory_length": 0.46652, "arc_length": 0.46652, @@ -1394,6 +1419,7 @@ "trajectory_id": 26, "start_angle_index": 5, "end_angle_index": 3, + "left_turn": false, "trajectory_radius": 0.6149, "trajectory_length": 0.57019, "arc_length": 0.57019, @@ -1460,6 +1486,7 @@ "trajectory_id": 27, "start_angle_index": 5, "end_angle_index": 4, + "left_turn": false, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -1511,6 +1538,7 @@ "trajectory_id": 28, "start_angle_index": 5, "end_angle_index": 5, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.22361, "arc_length": 0.0, @@ -1542,6 +1570,7 @@ "trajectory_id": 29, "start_angle_index": 5, "end_angle_index": 6, + "left_turn": true, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -1583,6 +1612,7 @@ "trajectory_id": 30, "start_angle_index": 6, "end_angle_index": 4, + "left_turn": false, "trajectory_radius": 0.5121, "trajectory_length": 0.44007, "arc_length": 0.4022, @@ -1644,6 +1674,7 @@ "trajectory_id": 31, "start_angle_index": 6, "end_angle_index": 5, + "left_turn": false, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -1685,6 +1716,7 @@ "trajectory_id": 32, "start_angle_index": 6, "end_angle_index": 6, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.21213, "arc_length": 0.0, @@ -1716,6 +1748,7 @@ "trajectory_id": 33, "start_angle_index": 6, "end_angle_index": 7, + "left_turn": true, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -1757,6 +1790,7 @@ "trajectory_id": 34, "start_angle_index": 6, "end_angle_index": 8, + "left_turn": true, "trajectory_radius": 0.5121, "trajectory_length": 0.44007, "arc_length": 0.4022, @@ -1818,6 +1852,7 @@ "trajectory_id": 35, "start_angle_index": 7, "end_angle_index": 9, + "left_turn": true, "trajectory_radius": 0.5031, "trajectory_length": 0.46652, "arc_length": 0.46652, @@ -1874,6 +1909,7 @@ "trajectory_id": 36, "start_angle_index": 7, "end_angle_index": 9, + "left_turn": true, "trajectory_radius": 0.6149, "trajectory_length": 0.57019, "arc_length": 0.57019, @@ -1940,6 +1976,7 @@ "trajectory_id": 37, "start_angle_index": 7, "end_angle_index": 6, + "left_turn": false, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -1981,6 +2018,7 @@ "trajectory_id": 38, "start_angle_index": 7, "end_angle_index": 7, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.22361, "arc_length": 0.0, @@ -2012,6 +2050,7 @@ "trajectory_id": 39, "start_angle_index": 7, "end_angle_index": 8, + "left_turn": true, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -2063,6 +2102,7 @@ "trajectory_id": 40, "start_angle_index": 8, "end_angle_index": 9, + "left_turn": true, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -2114,6 +2154,7 @@ "trajectory_id": 41, "start_angle_index": 8, "end_angle_index": 11, + "left_turn": true, "trajectory_radius": 0.5259, "trajectory_length": 0.64856, "arc_length": 0.58225, @@ -2195,6 +2236,7 @@ "trajectory_id": 42, "start_angle_index": 8, "end_angle_index": 5, + "left_turn": false, "trajectory_radius": 0.5259, "trajectory_length": 0.64856, "arc_length": 0.58225, @@ -2276,6 +2318,7 @@ "trajectory_id": 43, "start_angle_index": 8, "end_angle_index": 7, + "left_turn": false, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -2327,6 +2370,7 @@ "trajectory_id": 44, "start_angle_index": 8, "end_angle_index": 8, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.15, "arc_length": 0.0, @@ -2353,6 +2397,7 @@ "trajectory_id": 45, "start_angle_index": 9, "end_angle_index": 9, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.22361, "arc_length": 0.0, @@ -2384,6 +2429,7 @@ "trajectory_id": 46, "start_angle_index": 9, "end_angle_index": 10, + "left_turn": true, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -2425,6 +2471,7 @@ "trajectory_id": 47, "start_angle_index": 9, "end_angle_index": 7, + "left_turn": false, "trajectory_radius": 0.5031, "trajectory_length": 0.46652, "arc_length": 0.46652, @@ -2481,6 +2528,7 @@ "trajectory_id": 48, "start_angle_index": 9, "end_angle_index": 7, + "left_turn": false, "trajectory_radius": 0.6149, "trajectory_length": 0.57019, "arc_length": 0.57019, @@ -2547,6 +2595,7 @@ "trajectory_id": 49, "start_angle_index": 9, "end_angle_index": 8, + "left_turn": false, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -2598,6 +2647,7 @@ "trajectory_id": 50, "start_angle_index": 10, "end_angle_index": 9, + "left_turn": false, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -2639,6 +2689,7 @@ "trajectory_id": 51, "start_angle_index": 10, "end_angle_index": 10, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.21213, "arc_length": 0.0, @@ -2670,6 +2721,7 @@ "trajectory_id": 52, "start_angle_index": 10, "end_angle_index": 11, + "left_turn": true, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -2711,6 +2763,7 @@ "trajectory_id": 53, "start_angle_index": 10, "end_angle_index": 12, + "left_turn": true, "trajectory_radius": 0.5121, "trajectory_length": 0.44007, "arc_length": 0.4022, @@ -2772,6 +2825,7 @@ "trajectory_id": 54, "start_angle_index": 10, "end_angle_index": 8, + "left_turn": false, "trajectory_radius": 0.5121, "trajectory_length": 0.44007, "arc_length": 0.4022, @@ -2833,6 +2887,7 @@ "trajectory_id": 55, "start_angle_index": 11, "end_angle_index": 10, + "left_turn": false, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -2874,6 +2929,7 @@ "trajectory_id": 56, "start_angle_index": 11, "end_angle_index": 11, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.22361, "arc_length": 0.0, @@ -2905,6 +2961,7 @@ "trajectory_id": 57, "start_angle_index": 11, "end_angle_index": 12, + "left_turn": true, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -2956,6 +3013,7 @@ "trajectory_id": 58, "start_angle_index": 11, "end_angle_index": 13, + "left_turn": true, "trajectory_radius": 0.5031, "trajectory_length": 0.46652, "arc_length": 0.46652, @@ -3012,6 +3070,7 @@ "trajectory_id": 59, "start_angle_index": 11, "end_angle_index": 13, + "left_turn": true, "trajectory_radius": 0.6149, "trajectory_length": 0.57019, "arc_length": 0.57019, @@ -3078,6 +3137,7 @@ "trajectory_id": 60, "start_angle_index": 12, "end_angle_index": 9, + "left_turn": false, "trajectory_radius": 0.5259, "trajectory_length": 0.64856, "arc_length": 0.58225, @@ -3159,6 +3219,7 @@ "trajectory_id": 61, "start_angle_index": 12, "end_angle_index": 11, + "left_turn": false, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -3210,6 +3271,7 @@ "trajectory_id": 62, "start_angle_index": 12, "end_angle_index": 12, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.15, "arc_length": 0.0, @@ -3236,6 +3298,7 @@ "trajectory_id": 63, "start_angle_index": 12, "end_angle_index": 13, + "left_turn": true, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -3287,6 +3350,7 @@ "trajectory_id": 64, "start_angle_index": 12, "end_angle_index": 15, + "left_turn": true, "trajectory_radius": 0.5259, "trajectory_length": 0.64856, "arc_length": 0.58225, @@ -3368,6 +3432,7 @@ "trajectory_id": 65, "start_angle_index": 13, "end_angle_index": 11, + "left_turn": false, "trajectory_radius": 0.5031, "trajectory_length": 0.46652, "arc_length": 0.46652, @@ -3424,6 +3489,7 @@ "trajectory_id": 66, "start_angle_index": 13, "end_angle_index": 11, + "left_turn": false, "trajectory_radius": 0.6149, "trajectory_length": 0.57019, "arc_length": 0.57019, @@ -3490,6 +3556,7 @@ "trajectory_id": 67, "start_angle_index": 13, "end_angle_index": 12, + "left_turn": false, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -3541,6 +3608,7 @@ "trajectory_id": 68, "start_angle_index": 13, "end_angle_index": 13, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.22361, "arc_length": 0.0, @@ -3572,6 +3640,7 @@ "trajectory_id": 69, "start_angle_index": 13, "end_angle_index": 14, + "left_turn": true, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -3613,6 +3682,7 @@ "trajectory_id": 70, "start_angle_index": 14, "end_angle_index": 12, + "left_turn": false, "trajectory_radius": 0.5121, "trajectory_length": 0.44007, "arc_length": 0.4022, @@ -3674,6 +3744,7 @@ "trajectory_id": 71, "start_angle_index": 14, "end_angle_index": 13, + "left_turn": false, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -3715,6 +3786,7 @@ "trajectory_id": 72, "start_angle_index": 14, "end_angle_index": 14, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.21213, "arc_length": 0.0, @@ -3746,6 +3818,7 @@ "trajectory_id": 73, "start_angle_index": 14, "end_angle_index": 15, + "left_turn": true, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -3787,6 +3860,7 @@ "trajectory_id": 74, "start_angle_index": 14, "end_angle_index": 0, + "left_turn": true, "trajectory_radius": 0.5121, "trajectory_length": 0.44007, "arc_length": 0.4022, @@ -3848,6 +3922,7 @@ "trajectory_id": 75, "start_angle_index": 15, "end_angle_index": 14, + "left_turn": false, "trajectory_radius": 0.689, "trajectory_length": 0.25131, "arc_length": 0.22169, @@ -3889,6 +3964,7 @@ "trajectory_id": 76, "start_angle_index": 15, "end_angle_index": 15, + "left_turn": true, "trajectory_radius": 0.0, "trajectory_length": 0.22361, "arc_length": 0.0, @@ -3920,6 +3996,7 @@ "trajectory_id": 77, "start_angle_index": 15, "end_angle_index": 0, + "left_turn": true, "trajectory_radius": 0.6354, "trajectory_length": 0.36821, "arc_length": 0.2946, @@ -3971,6 +4048,7 @@ "trajectory_id": 78, "start_angle_index": 15, "end_angle_index": 1, + "left_turn": true, "trajectory_radius": 0.5031, "trajectory_length": 0.46652, "arc_length": 0.46652, @@ -4027,6 +4105,7 @@ "trajectory_id": 79, "start_angle_index": 15, "end_angle_index": 1, + "left_turn": true, "trajectory_radius": 0.6149, "trajectory_length": 0.57019, "arc_length": 0.57019, diff --git a/nav2_smac_planner/test/test_nodelattice.cpp b/nav2_smac_planner/test/test_nodelattice.cpp index 81019e034d..5b93dfa64d 100644 --- a/nav2_smac_planner/test/test_nodelattice.cpp +++ b/nav2_smac_planner/test/test_nodelattice.cpp @@ -49,7 +49,6 @@ TEST(NodeLatticeTest, parser_test) EXPECT_NEAR(metaData.min_turning_radius, 0.5, 0.001); EXPECT_NEAR(metaData.grid_resolution, 0.05, 0.001); EXPECT_NEAR(metaData.number_of_headings, 16, 0.01); - EXPECT_EQ(metaData.output_file, "output.json"); EXPECT_NEAR(metaData.heading_angles[0], 0.0, 0.01); EXPECT_EQ(metaData.number_of_trajectories, 80u); EXPECT_EQ(metaData.motion_model, std::string("ackermann")); From a51790c8e871bc6913f1c257cfadfc5d64912158 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 27 Oct 2021 17:21:48 -0700 Subject: [PATCH 11/31] adding working base code --- nav2_smac_planner/CMakeLists.txt | 2 + .../include/nav2_smac_planner/node_basic.hpp | 3 +- .../nav2_smac_planner/node_lattice.hpp | 7 ++- .../include/nav2_smac_planner/types.hpp | 1 + .../include/nav2_smac_planner/utils.hpp | 6 +- nav2_smac_planner/package.xml | 1 + nav2_smac_planner/src/a_star.cpp | 58 +++++++++++++------ nav2_smac_planner/src/node_lattice.cpp | 43 +++++++------- nav2_smac_planner/test/test_nodelattice.cpp | 8 +-- 9 files changed, 76 insertions(+), 53 deletions(-) diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index 773329fdb8..ac1787cddf 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -21,6 +21,7 @@ find_package(nav2_costmap_2d REQUIRED) find_package(pluginlib REQUIRED) find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) +find_package(angles REQUIRED) find_package(ompl REQUIRED) find_package(OpenMP REQUIRED) @@ -62,6 +63,7 @@ set(dependencies nav2_costmap_2d nav2_core pluginlib + angles eigen3_cmake_module ) diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp index bc3b587668..039f5810c3 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp @@ -58,7 +58,8 @@ class NodeBasic typename NodeT::Coordinates pose; // Used by NodeHybrid and NodeLattice NodeT * graph_node_ptr; - unsigned int index; + MotionPrimitive * prim_ptr; // Used by NodeLattice + unsigned int index, motion_index; }; template class NodeBasic; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index 33fd64348c..75d924907d 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -29,6 +29,7 @@ #include #include "ompl/base/StateSpace.h" +#include "angles/angles.h" #include "nav2_smac_planner/constants.hpp" #include "nav2_smac_planner/types.hpp" @@ -70,7 +71,7 @@ struct LatticeMotionTable * @param node Ptr to NodeLattice * @return A set of motion poses */ - MotionPrimitives getMotionPrimitives(const NodeLattice * node); + MotionPrimitivePtrs getMotionPrimitives(const NodeLattice * node); /** * @brief Get file metadata needed @@ -161,7 +162,7 @@ class NodeLattice * @brief Sets the motion primitive used to achieve node in search * @param pointer to motion primitive */ - inline void setMotionPrimitive(MotionPrimitive * prim) + inline void setMotionPrimitive(MotionPrimitive * & prim) { _motion_primitive = prim; } @@ -170,7 +171,7 @@ class NodeLattice * @brief Gets the motion primitive used to achieve node in search * @return pointer to motion primitive */ - inline MotionPrimitive * getMotionPrimitive() + inline MotionPrimitive * & getMotionPrimitive() { return _motion_primitive; } diff --git a/nav2_smac_planner/include/nav2_smac_planner/types.hpp b/nav2_smac_planner/include/nav2_smac_planner/types.hpp index 927f3934a1..8895e8cba0 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/types.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/types.hpp @@ -153,6 +153,7 @@ struct MotionPrimitive }; typedef std::vector MotionPrimitives; +typedef std::vector MotionPrimitivePtrs; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp index 68a618ee79..fcb267e980 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp @@ -145,11 +145,7 @@ inline void fromJsonToMotionPrimitive( json.at("trajectory_length").get_to(motion_primitive.trajectory_length); json.at("arc_length").get_to(motion_primitive.arc_length); json.at("straight_length").get_to(motion_primitive.straight_length); - try { - json.at("left_turn").get_to(motion_primitive.left_turn); - } catch (...) { - /*TODO for actual*/ - } + json.at("left_turn").get_to(motion_primitive.left_turn); for (unsigned int i = 0; i < json["poses"].size(); i++) { MotionPose pose; diff --git a/nav2_smac_planner/package.xml b/nav2_smac_planner/package.xml index 2f1091f4dc..f2c5654915 100644 --- a/nav2_smac_planner/package.xml +++ b/nav2_smac_planner/package.xml @@ -27,6 +27,7 @@ eigen ompl nlohmann-json-dev + angles ament_lint_common ament_lint_auto diff --git a/nav2_smac_planner/src/a_star.cpp b/nav2_smac_planner/src/a_star.cpp index 5e139c9823..f940bccb71 100644 --- a/nav2_smac_planner/src/a_star.cpp +++ b/nav2_smac_planner/src/a_star.cpp @@ -339,6 +339,7 @@ bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & return false; } + Coordinates initial_pose, prim_pose; NodePtr current_node = node; MotionPrimitive * prim = nullptr; const float & grid_resolution = NodeLattice::motion_table.lattice_metadata.grid_resolution; @@ -348,29 +349,23 @@ bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & // if motion primitive is valid, then was searched (rather than analytically expanded), // include dense path of subpoints making up the primitive at grid resolution if (prim) { - Coordinates initial_pose, prim_pose; initial_pose.x = current_node->pose.x - (prim->poses.back()._x / grid_resolution); initial_pose.y = current_node->pose.y - (prim->poses.back()._y / grid_resolution); - initial_pose.theta = NodeLattice::motion_table.getAngleFromBin(prim->start_angle); /*rad*/ + initial_pose.theta = NodeLattice::motion_table.getAngleFromBin(prim->start_angle); - for (auto it = prim->poses.rbegin(); it != prim->poses.rend(); ++it) { + for (auto it = prim->poses.crbegin(); it != prim->poses.crend(); ++it) { // Convert primitive pose into grid space if it should be checked prim_pose.x = initial_pose.x + (it->_x / grid_resolution); prim_pose.y = initial_pose.y + (it->_y / grid_resolution); - prim_pose.theta = initial_pose.theta + it->_theta; /*rad*/ - if (prim_pose.theta < 0.0) { - prim_pose.theta += 2.0 * M_PI; - } - if (prim_pose.theta > 2.0 * M_PI) { - prim_pose.theta -= 2.0 * M_PI; - } + prim_pose.theta = it->_theta; path.push_back(prim_pose); } } else { + // For analytic expansion nodes where there is no valid motion primitive path.push_back(current_node->pose); - // Convert angle to radians path.back().theta = NodeLattice::motion_table.getAngleFromBin(path.back().theta); } + current_node = current_node->parent; } @@ -416,10 +411,10 @@ typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() return node.graph_node_ptr; } -template -typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() +template<> +typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() { - NodeBasic node = _queue.top().second; + NodeBasic node = _queue.top().second; _queue.pop(); // We only want to override the node's pose if it has not yet been visited @@ -427,6 +422,24 @@ typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() // a new branch is overriding one of lower cost already visited. if (!node.graph_node_ptr->wasVisited()) { node.graph_node_ptr->pose = node.pose; + node.graph_node_ptr->setMotionPrimitiveIndex(node.motion_index); + } + + return node.graph_node_ptr; +} + +template<> +typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() +{ + NodeBasic node = _queue.top().second; + _queue.pop(); + + // We only want to override the node's pose/primitive if it has not yet been visited + // to prevent the case that a node has been queued multiple times and + // a new branch is overriding one of lower cost already visited. + if (!node.graph_node_ptr->wasVisited()) { + node.graph_node_ptr->pose = node.pose; + node.graph_node_ptr->setMotionPrimitive(node.prim_ptr); } return node.graph_node_ptr; @@ -440,12 +453,23 @@ void AStarAlgorithm::addNode(const float & cost, NodePtr & node) _queue.emplace(cost, queued_node); } -template -void AStarAlgorithm::addNode(const float & cost, NodePtr & node) +template<> +void AStarAlgorithm::addNode(const float & cost, NodePtr & node) +{ + NodeBasic queued_node(node->getIndex()); + queued_node.pose = node->pose; + queued_node.graph_node_ptr = node; + queued_node.prim_ptr = node->getMotionPrimitive(); + _queue.emplace(cost, queued_node); +} + +template<> +void AStarAlgorithm::addNode(const float & cost, NodePtr & node) { - NodeBasic queued_node(node->getIndex()); + NodeBasic queued_node(node->getIndex()); queued_node.pose = node->pose; queued_node.graph_node_ptr = node; + queued_node.motion_index = node->getMotionPrimitiveIndex(); _queue.emplace(cost, queued_node); } diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index a6714ae67a..8f4b12cde9 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -1,5 +1,4 @@ -// Copyright (c) 2020, Samsung Research America -// Copyright (c) 2020, Applied Electric Vehicles Pty Ltd +// Copyright (c) 2021, Samsung Research America // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -109,10 +108,13 @@ void LatticeMotionTable::initMotionModel( } } -MotionPrimitives LatticeMotionTable::getMotionPrimitives(const NodeLattice * node) +MotionPrimitivePtrs LatticeMotionTable::getMotionPrimitives(const NodeLattice * node) { MotionPrimitives & prims_at_heading = motion_primitives[node->pose.theta]; - MotionPrimitives primitive_projection_list = prims_at_heading; + MotionPrimitivePtrs primitive_projection_list; + for (unsigned int i = 0; i != prims_at_heading.size(); i++) { + primitive_projection_list.push_back(&prims_at_heading[i]); + } if (allow_reverse_expansion) { // Find normalized heading bin of the reverse expansion @@ -125,10 +127,9 @@ MotionPrimitives LatticeMotionTable::getMotionPrimitives(const NodeLattice * nod } prims_at_heading = motion_primitives[reserve_heading]; - primitive_projection_list.insert( - primitive_projection_list.end(), - prims_at_heading.begin(), - prims_at_heading.end()); + for (unsigned int i = 0; i != prims_at_heading.size(); i++) { + primitive_projection_list.push_back(&prims_at_heading[i]); + } } return primitive_projection_list; @@ -154,7 +155,7 @@ unsigned int LatticeMotionTable::getClosestAngularBin(const double & theta) unsigned int closest_idx = 0; float dist = 0.0; for (unsigned int i = 0; i != lattice_metadata.heading_angles.size(); i++) { - dist = fabs(theta - lattice_metadata.heading_angles[i]); + dist = fabs(angles::shortest_angular_distance(theta, lattice_metadata.heading_angles[i])); if (dist < min_dist) { min_dist = dist; closest_idx = i; @@ -226,7 +227,7 @@ bool NodeLattice::isNodeValid( MotionPose initial_pose, prim_pose; initial_pose._x = this->pose.x - (motion_primitive->poses.back()._x / grid_resolution); initial_pose._y = this->pose.y - (motion_primitive->poses.back()._y / grid_resolution); - initial_pose._theta = motion_table.getAngleFromBin(motion_primitive->start_angle); /*rad*/ + initial_pose._theta = motion_table.getAngleFromBin(motion_primitive->start_angle); for (auto it = motion_primitive->poses.begin(); it != motion_primitive->poses.end(); ++it) { // poses are in metric coordinates from (0, 0), not grid space yet @@ -237,13 +238,7 @@ bool NodeLattice::isNodeValid( // Convert primitive pose into grid space if it should be checked prim_pose._x = initial_pose._x + (it->_x / grid_resolution); prim_pose._y = initial_pose._y + (it->_y / grid_resolution); - prim_pose._theta = it->_theta; /*rad*/ // TODO initial_pose._theta + - if (prim_pose._theta < 0.0) { - prim_pose._theta += 2.0 * M_PI; - } - if (prim_pose._theta > 2.0 * M_PI) { - prim_pose._theta -= 2.0 * M_PI; - } + prim_pose._theta = it->_theta; if (collision_checker->inCollision( prim_pose._x, prim_pose._y, @@ -464,22 +459,23 @@ void NodeLattice::getNeighbors( unsigned int index = 0; NodePtr neighbor = nullptr; Coordinates initial_node_coords, motion_projection; - MotionPrimitives motion_primitives = motion_table.getMotionPrimitives(this); + MotionPrimitivePtrs motion_primitives = motion_table.getMotionPrimitives(this); const float & grid_resolution = motion_table.lattice_metadata.grid_resolution; unsigned int direction_change_idx = 1e9; for (unsigned int i = 0; i != motion_primitives.size(); i++) { - if (motion_primitives[0].start_angle != motion_primitives[i].start_angle) { + if (motion_primitives[0]->start_angle != motion_primitives[i]->start_angle) { direction_change_idx = i; break; } } for (unsigned int i = 0; i != motion_primitives.size(); i++) { - const MotionPose & end_pose = motion_primitives[i].poses.back(); + const MotionPose & end_pose = motion_primitives[i]->poses.back(); motion_projection.x = this->pose.x + (end_pose._x / grid_resolution); motion_projection.y = this->pose.y + (end_pose._y / grid_resolution); - motion_projection.theta = motion_primitives[i].end_angle /*this is the ending angular bin*/; + motion_projection.theta = motion_primitives[i]->end_angle /*this is the ending angular bin*/; + index = NodeLattice::getIndex( static_cast(motion_projection.x), static_cast(motion_projection.y), @@ -496,8 +492,9 @@ void NodeLattice::getNeighbors( motion_projection.theta)); // Using a special isNodeValid API here, giving the motion primitive to use to // validity check the transition of the current node to the new node over - if (neighbor->isNodeValid(traverse_unknown, collision_checker, &motion_primitives[i])) { - neighbor->setMotionPrimitive(&motion_primitives[i]); + if (neighbor->isNodeValid(traverse_unknown, collision_checker, motion_primitives[i])) { + neighbor->setMotionPrimitive(motion_primitives[i]); + // Marking if this search was obtained in the reverse direction if ((!this->isBackward() && i >= direction_change_idx) || (this->isBackward() && i <= direction_change_idx)) diff --git a/nav2_smac_planner/test/test_nodelattice.cpp b/nav2_smac_planner/test/test_nodelattice.cpp index 5b93dfa64d..2b2f546117 100644 --- a/nav2_smac_planner/test/test_nodelattice.cpp +++ b/nav2_smac_planner/test/test_nodelattice.cpp @@ -103,12 +103,12 @@ TEST(NodeLatticeTest, test_node_lattice_neighbors_and_parsing) nav2_smac_planner::NodeLattice aNode(0); aNode.setPose(nav2_smac_planner::NodeHybrid::Coordinates(0, 0, 0)); - nav2_smac_planner::MotionPrimitives projections = + nav2_smac_planner::MotionPrimitivePtrs projections = nav2_smac_planner::NodeLattice::motion_table.getMotionPrimitives(&aNode); - EXPECT_NEAR(projections[0].poses.back()._x, 0.5, 0.01); - EXPECT_NEAR(projections[0].poses.back()._y, -0.35, 0.01); - EXPECT_NEAR(projections[0].poses.back()._theta, -1.107, 0.01); + EXPECT_NEAR(projections[0]->poses.back()._x, 0.5, 0.01); + EXPECT_NEAR(projections[0]->poses.back()._y, -0.35, 0.01); + EXPECT_NEAR(projections[0]->poses.back()._theta, -1.107, 0.01); EXPECT_NEAR( nav2_smac_planner::NodeLattice::motion_table.getLatticeMetadata( From e6dca9b6b02679a529f01d3e37c0c44f380a47d1 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 27 Oct 2021 17:22:16 -0700 Subject: [PATCH 12/31] adding search info --- nav2_smac_planner/src/smac_planner_lattice.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index f2716ac603..0a79186a48 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -111,6 +111,7 @@ void SmacPlannerLattice::configure( node->get_parameter(name + ".allow_reverse_expansion", search_info.allow_reverse_expansion); _metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); + search_info.minimum_turning_radius = _metadata.min_turning_radius; MotionModel motion_model = MotionModel::STATE_LATTICE; if (max_iterations <= 0) { From 3a89142f5bde6e1b006dc23b56d36d9c2fc2c917 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 28 Oct 2021 16:36:57 -0700 Subject: [PATCH 13/31] fully working for non-lateral lattices --- .../nav2_smac_planner/analytic_expansion.hpp | 7 +++++++ .../include/nav2_smac_planner/node_basic.hpp | 1 + .../include/nav2_smac_planner/node_lattice.hpp | 6 +++--- nav2_smac_planner/src/a_star.cpp | 2 ++ nav2_smac_planner/src/analytic_expansion.cpp | 17 +++++++++++++++-- nav2_smac_planner/src/collision_checker.cpp | 2 +- nav2_smac_planner/src/smac_planner_lattice.cpp | 3 ++- 7 files changed, 31 insertions(+), 7 deletions(-) diff --git a/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp b/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp index 679a7cd2cd..c576a23c95 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/analytic_expansion.hpp @@ -110,6 +110,13 @@ class AnalyticExpansion const NodePtr & node, const NodePtr & goal, const AnalyticExpansionNodes & expanded_nodes); + /** + * @brief Takes an expanded nodes to clean up, if necessary, of any state + * information that may be poluting it from a prior search iteration + * @param expanded_nodes Expanded node to clean up from search + */ + void cleanNode(const NodePtr & nodes); + protected: MotionModel _motion_model; SearchInfo _search_info; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp index 039f5810c3..f49f10d53a 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp @@ -60,6 +60,7 @@ class NodeBasic NodeT * graph_node_ptr; MotionPrimitive * prim_ptr; // Used by NodeLattice unsigned int index, motion_index; + bool backward; }; template class NodeBasic; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index 75d924907d..d849a04cc2 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -162,7 +162,7 @@ class NodeLattice * @brief Sets the motion primitive used to achieve node in search * @param pointer to motion primitive */ - inline void setMotionPrimitive(MotionPrimitive * & prim) + inline void setMotionPrimitive(MotionPrimitive * prim) { _motion_primitive = prim; } @@ -232,9 +232,9 @@ class NodeLattice /** * @brief Sets that this primitive is moving in reverse */ - inline void backwards() + inline void backwards(bool back = true) { - _backwards = true; + _backwards = back; } /** diff --git a/nav2_smac_planner/src/a_star.cpp b/nav2_smac_planner/src/a_star.cpp index f940bccb71..577ab30a75 100644 --- a/nav2_smac_planner/src/a_star.cpp +++ b/nav2_smac_planner/src/a_star.cpp @@ -440,6 +440,7 @@ typename AStarAlgorithm::NodePtr AStarAlgorithm::getNe if (!node.graph_node_ptr->wasVisited()) { node.graph_node_ptr->pose = node.pose; node.graph_node_ptr->setMotionPrimitive(node.prim_ptr); + node.graph_node_ptr->backwards(node.backward); } return node.graph_node_ptr; @@ -460,6 +461,7 @@ void AStarAlgorithm::addNode(const float & cost, NodePtr & node) queued_node.pose = node->pose; queued_node.graph_node_ptr = node; queued_node.prim_ptr = node->getMotionPrimitive(); + queued_node.backward = node->isBackward(); _queue.emplace(cost, queued_node); } diff --git a/nav2_smac_planner/src/analytic_expansion.cpp b/nav2_smac_planner/src/analytic_expansion.cpp index 1ebbadebda..c390b07a39 100644 --- a/nav2_smac_planner/src/analytic_expansion.cpp +++ b/nav2_smac_planner/src/analytic_expansion.cpp @@ -51,7 +51,7 @@ typename AnalyticExpansion::NodePtr AnalyticExpansion::tryAnalytic const NodeGetter & getter, int & analytic_iterations, int & closest_distance) { - // This must be a NodeHybrid or NodeLattice if we are using these motion models + // This must be a valid motion model for analytic expansion to be attempted if (_motion_model == MotionModel::DUBIN || _motion_model == MotionModel::REEDS_SHEPP || _motion_model == MotionModel::STATE_LATTICE) { @@ -206,10 +206,11 @@ typename AnalyticExpansion::NodePtr AnalyticExpansion::setAnalytic const NodePtr & goal_node, const AnalyticExpansionNodes & expanded_nodes) { - // Legitimate final path - set the parent relationships & poses + // Legitimate final path - set the parent relationships, states, and poses NodePtr prev = node; for (const auto & node_pose : expanded_nodes) { const auto & n = node_pose.node; + cleanNode(n); if (!n->wasVisited() && n->getIndex() != goal_node->getIndex()) { // Make sure this node has not been visited by the regular algorithm. // If it has been, there is the (slight) chance that it is in the path we are expanding @@ -228,6 +229,18 @@ typename AnalyticExpansion::NodePtr AnalyticExpansion::setAnalytic return goal_node; } +template<> +void AnalyticExpansion::cleanNode(const NodePtr & node) +{ + node->setMotionPrimitive(nullptr); +} + +template +void AnalyticExpansion::cleanNode(const NodePtr & /*expanded_nodes*/) +{ + return; +} + template<> typename AnalyticExpansion::AnalyticExpansionNodes AnalyticExpansion:: getAnalyticPath( diff --git a/nav2_smac_planner/src/collision_checker.cpp b/nav2_smac_planner/src/collision_checker.cpp index d9af6d0bf8..b267259c9c 100644 --- a/nav2_smac_planner/src/collision_checker.cpp +++ b/nav2_smac_planner/src/collision_checker.cpp @@ -141,7 +141,7 @@ bool GridCollisionChecker::inCollision( } // if occupied or unknown and not to traverse unknown space - return footprint_cost_ >= INSCRIBED; + return static_cast(footprint_cost_) >= INSCRIBED; } } diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 0a79186a48..75f468f60b 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -111,7 +111,8 @@ void SmacPlannerLattice::configure( node->get_parameter(name + ".allow_reverse_expansion", search_info.allow_reverse_expansion); _metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); - search_info.minimum_turning_radius = _metadata.min_turning_radius; + search_info.minimum_turning_radius = + _metadata.min_turning_radius / (_costmap->getResolution() * _downsampling_factor); MotionModel motion_model = MotionModel::STATE_LATTICE; if (max_iterations <= 0) { From 0a81707ad43cf33ea4bc734f3c26b4ada3780003 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 28 Oct 2021 17:28:22 -0700 Subject: [PATCH 14/31] removing downsampler for lattice, pushing in cost penalty --- .../include/nav2_smac_planner/node_hybrid.hpp | 3 +- .../nav2_smac_planner/node_lattice.hpp | 5 ++- .../smac_planner_lattice.hpp | 4 -- nav2_smac_planner/src/node_hybrid.cpp | 8 ++-- nav2_smac_planner/src/node_lattice.cpp | 3 +- .../src/smac_planner_lattice.cpp | 43 +++---------------- 6 files changed, 18 insertions(+), 48 deletions(-) diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp index b9efc48bbc..faffbd362c 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp @@ -379,7 +379,8 @@ class NodeHybrid */ static float getObstacleHeuristic( const Coordinates & node_coords, - const Coordinates & goal_coords); + const Coordinates & goal_coords, + const double & cost_penalty); /** * @brief Compute the Distance heuristic diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index d849a04cc2..4c45378caf 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -362,9 +362,10 @@ class NodeLattice */ static float getObstacleHeuristic( const Coordinates & node_coords, - const Coordinates & goal_coords) + const Coordinates & goal_coords, + const double & cost_penalty) { - return NodeHybrid::getObstacleHeuristic(node_coords, goal_coords); + return NodeHybrid::getObstacleHeuristic(node_coords, goal_coords, cost_penalty); } /** diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp index 2b935ee090..ec5accf0c3 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp @@ -22,7 +22,6 @@ #include "nav2_smac_planner/a_star.hpp" #include "nav2_smac_planner/smoother.hpp" #include "nav2_smac_planner/utils.hpp" -#include "nav2_smac_planner/costmap_downsampler.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" #include "nav2_core/global_planner.hpp" #include "nav_msgs/msg/path.hpp" @@ -93,12 +92,9 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner rclcpp::Clock::SharedPtr _clock; rclcpp::Logger _logger{rclcpp::get_logger("SmacPlannerLattice")}; nav2_costmap_2d::Costmap2D * _costmap; - std::unique_ptr _costmap_downsampler; LatticeMetadata _metadata; std::string _global_frame, _name; float _tolerance; - int _downsampling_factor; - bool _downsample_costmap; rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; double _max_planning_time; }; diff --git a/nav2_smac_planner/src/node_hybrid.cpp b/nav2_smac_planner/src/node_hybrid.cpp index 967398d6e8..b011608a79 100644 --- a/nav2_smac_planner/src/node_hybrid.cpp +++ b/nav2_smac_planner/src/node_hybrid.cpp @@ -355,7 +355,8 @@ float NodeHybrid::getHeuristicCost( const Coordinates & goal_coords, const nav2_costmap_2d::Costmap2D * /*costmap*/) { - const float obstacle_heuristic = getObstacleHeuristic(node_coords, goal_coords); + const float obstacle_heuristic = getObstacleHeuristic( + node_coords, goal_coords, motion_table.cost_penalty); const float dist_heuristic = getDistanceHeuristic(node_coords, goal_coords, obstacle_heuristic); return std::max(obstacle_heuristic, dist_heuristic); } @@ -422,7 +423,8 @@ void NodeHybrid::resetObstacleHeuristic( float NodeHybrid::getObstacleHeuristic( const Coordinates & node_coords, - const Coordinates & goal_coords) + const Coordinates & goal_coords, + const double & cost_penalty) { // If already expanded, return the cost unsigned int size_x = sampled_costmap->getSizeInCellsX(); @@ -473,7 +475,7 @@ float NodeHybrid::getObstacleHeuristic( new_idx = static_cast(static_cast(idx) + neighborhood[i]); cost = static_cast(sampled_costmap->getCost(idx)); travel_cost = - ((i <= 3) ? 1.0 : sqrt_2) + (motion_table.cost_penalty * cost / 252.0); + ((i <= 3) ? 1.0 : sqrt_2) + (cost_penalty * cost / 252.0); current_accumulated_cost = last_accumulated_cost + travel_cost; // if neighbor path is better and non-lethal, set new cost and add to queue diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index 8f4b12cde9..ae05ce83d1 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -316,7 +316,8 @@ float NodeLattice::getHeuristicCost( const nav2_costmap_2d::Costmap2D * costmap) { // get obstacle heuristic value - const float obstacle_heuristic = getObstacleHeuristic(node_coords, goal_coords); + const float obstacle_heuristic = getObstacleHeuristic( + node_coords, goal_coords, motion_table.cost_penalty); const float distance_heuristic = getDistanceHeuristic(node_coords, goal_coords, obstacle_heuristic); return std::max(obstacle_heuristic, distance_heuristic); diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 75f468f60b..50655589c0 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -32,8 +32,7 @@ SmacPlannerLattice::SmacPlannerLattice() : _a_star(nullptr), _collision_checker(nullptr, 1), _smoother(nullptr), - _costmap(nullptr), - _costmap_downsampler(nullptr) + _costmap(nullptr) { } @@ -64,13 +63,6 @@ void SmacPlannerLattice::configure( SearchInfo search_info; // General planner params - nav2_util::declare_parameter_if_not_declared( - node, name + ".downsample_costmap", rclcpp::ParameterValue(false)); - node->get_parameter(name + ".downsample_costmap", _downsample_costmap); - nav2_util::declare_parameter_if_not_declared( - node, name + ".downsampling_factor", rclcpp::ParameterValue(1)); - node->get_parameter(name + ".downsampling_factor", _downsampling_factor); - nav2_util::declare_parameter_if_not_declared( node, name + ".allow_unknown", rclcpp::ParameterValue(true)); node->get_parameter(name + ".allow_unknown", allow_unknown); @@ -112,7 +104,7 @@ void SmacPlannerLattice::configure( _metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); search_info.minimum_turning_radius = - _metadata.min_turning_radius / (_costmap->getResolution() * _downsampling_factor); + _metadata.min_turning_radius / (_costmap->getResolution()); MotionModel motion_model = MotionModel::STATE_LATTICE; if (max_iterations <= 0) { @@ -124,7 +116,7 @@ void SmacPlannerLattice::configure( float lookup_table_dim = static_cast(lookup_table_size) / - static_cast(_costmap->getResolution() * _downsampling_factor); + static_cast(_costmap->getResolution()); // Make sure its a whole number lookup_table_dim = static_cast(static_cast(lookup_table_dim)); @@ -166,14 +158,6 @@ void SmacPlannerLattice::configure( _smoother = std::make_unique(params); _smoother->initialize(_metadata.min_turning_radius); - // Initialize costmap downsampler - if (_downsample_costmap && _downsampling_factor > 1) { - std::string topic_name = "downsampled_costmap"; - _costmap_downsampler = std::make_unique(); - _costmap_downsampler->on_configure( - node, _global_frame, topic_name, _costmap, _downsampling_factor); - } - _raw_plan_publisher = node->create_publisher("unsmoothed_plan", 1); RCLCPP_INFO( @@ -191,9 +175,6 @@ void SmacPlannerLattice::activate() _logger, "Activating plugin %s of type SmacPlannerLattice", _name.c_str()); _raw_plan_publisher->on_activate(); - if (_costmap_downsampler) { - _costmap_downsampler->on_activate(); - } } void SmacPlannerLattice::deactivate() @@ -202,9 +183,6 @@ void SmacPlannerLattice::deactivate() _logger, "Deactivating plugin %s of type SmacPlannerLattice", _name.c_str()); _raw_plan_publisher->on_deactivate(); - if (_costmap_downsampler) { - _costmap_downsampler->on_deactivate(); - } } void SmacPlannerLattice::cleanup() @@ -214,8 +192,6 @@ void SmacPlannerLattice::cleanup() _name.c_str()); _a_star.reset(); _smoother.reset(); - _costmap_downsampler->on_cleanup(); - _costmap_downsampler.reset(); _raw_plan_publisher.reset(); } @@ -227,25 +203,18 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( std::unique_lock lock(*(_costmap->getMutex())); - // Downsample costmap, if required - nav2_costmap_2d::Costmap2D * costmap = _costmap; - if (_costmap_downsampler) { - costmap = _costmap_downsampler->downsample(_downsampling_factor); - _collision_checker.setCostmap(costmap); - } - // Set collision checker and costmap information _a_star->setCollisionChecker(&_collision_checker); // Set starting point, in A* bin search coordinates unsigned int mx, my; - costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx, my); + _costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx, my); _a_star->setStart( mx, my, NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(start.pose.orientation))); // Set goal point, in A* bin search coordinates - costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my); + _costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my); _a_star->setGoal( mx, my, NodeLattice::motion_table.getClosestAngularBin(tf2::getYaw(goal.pose.orientation))); @@ -290,7 +259,7 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( // Convert to world coordinates plan.poses.reserve(path.size()); for (int i = path.size() - 1; i >= 0; --i) { - pose.pose = getWorldCoords(path[i].x, path[i].y, costmap); + pose.pose = getWorldCoords(path[i].x, path[i].y, _costmap); pose.pose.orientation = getWorldOrientation(path[i].theta); plan.poses.push_back(pose); } From f2f48f63764dedaa67e69bd60e8ac88f96a5b75c Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Thu, 11 Nov 2021 17:00:46 -0800 Subject: [PATCH 15/31] adding in updated heuristics, tuned gains, and generally working for ackermann cases --- nav2_smac_planner/README.md | 6 +++--- nav2_smac_planner/src/node_hybrid.cpp | 17 +++-------------- nav2_smac_planner/src/node_lattice.cpp | 18 ++++-------------- nav2_smac_planner/src/smac_planner_hybrid.cpp | 6 +++--- nav2_smac_planner/src/smac_planner_lattice.cpp | 8 ++++---- 5 files changed, 17 insertions(+), 38 deletions(-) diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index fb51ea275c..9f2045e52c 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -110,9 +110,9 @@ planner_server: analytic_expansion_ratio: 3.5 # For Hybrid/Lattice nodes: The ratio to attempt analytic expansions during search for final approach. minimum_turning_radius: 0.40 # For Hybrid/Lattice nodes: minimum turning radius in m of path / vehicle reverse_penalty: 2.1 # For Reeds-Shepp model: penalty to apply if motion is reversing, must be => 1 - change_penalty: 0.15 # For Hybrid nodes: penalty to apply if motion is changing directions, must be >= 0 - non_straight_penalty: 1.50 # For Hybrid nodes: penalty to apply if motion is non-straight, must be => 1 - cost_penalty: 1.7 # For Hybrid nodes: penalty to apply to higher cost areas when adding into the obstacle map dynamic programming distance expansion heuristic. This drives the robot more towards the center of passages. A value between 1.3 - 3.5 is reasonable. + change_penalty: 0.20 # For Hybrid nodes: penalty to apply if motion is changing directions, must be >= 0 + non_straight_penalty: 1.25 # For Hybrid nodes: penalty to apply if motion is non-straight, must be => 1 + cost_penalty: 2.0 # For Hybrid nodes: penalty to apply to higher cost areas when adding into the obstacle map dynamic programming distance expansion heuristic. This drives the robot more towards the center of passages. A value between 1.3 - 3.5 is reasonable. lookup_table_size: 20 # For Hybrid nodes: Size of the dubin/reeds-sheep distance window to cache, in meters. cache_obstacle_heuristic: True # For Hybrid nodes: Cache the obstacle map dynamic programming distance expansion heuristic between subsiquent replannings of the same goal location. Dramatically speeds up replanning performance (40x) if costmap is largely static. allow_reverse_expansion: False # For Lattice nodes: Whether to expand state lattice graph in forward primitives or reverse as well, will double the branching factor at each step. diff --git a/nav2_smac_planner/src/node_hybrid.cpp b/nav2_smac_planner/src/node_hybrid.cpp index b011608a79..0f008874f9 100644 --- a/nav2_smac_planner/src/node_hybrid.cpp +++ b/nav2_smac_planner/src/node_hybrid.cpp @@ -313,20 +313,9 @@ float NodeHybrid::getTraversalCost(const NodePtr & child) return NodeHybrid::travel_distance_cost; } - // Note(stevemacenski): `travel_cost_raw` at one point contained a term: - // `+ motion_table.cost_penalty * normalized_cost;` - // It has been removed, but we may want to readdress this point and determine - // the technically and theoretically correctness of that choice. I feel technically speaking - // that term has merit, but it doesn't seem to impact performance or path quality. - // W/o it lowers the travel cost, which would drive the heuristics up proportionally where I - // would expect it to plan much faster in all cases, but I only see it in some cases. Since - // this term would weight against moving to high cost zones, I would expect to see more smooth - // central motion, but I only see it in some cases, possibly because the obstacle heuristic is - // already driving the robot away from high cost areas; implicitly handling this. However, - // then I would expect that not adding it here would make it unbalanced enough that path quality - // would suffer, which I did not see in my limited experimentation, possibly due to the smoother. float travel_cost = 0.0; - float travel_cost_raw = NodeHybrid::travel_distance_cost; + float travel_cost_raw = + NodeHybrid::travel_distance_cost + (motion_table.cost_penalty * normalized_cost); if (child->getMotionPrimitiveIndex() == 0 || child->getMotionPrimitiveIndex() == 3) { // New motion is a straight motion, no additional costs to be applied @@ -475,7 +464,7 @@ float NodeHybrid::getObstacleHeuristic( new_idx = static_cast(static_cast(idx) + neighborhood[i]); cost = static_cast(sampled_costmap->getCost(idx)); travel_cost = - ((i <= 3) ? 1.0 : sqrt_2) + (cost_penalty * cost / 252.0); + ((i <= 3) ? 1.0 : sqrt_2) + (((i <= 3) ? 1.0 : sqrt_2) * cost_penalty * cost / 252.0); current_accumulated_cost = last_accumulated_cost + travel_cost; // if neighbor path is better and non-lethal, set new cost and add to queue diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index ae05ce83d1..623d232c56 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -268,24 +268,14 @@ float NodeLattice::getTraversalCost(const NodePtr & child) // this is the first node MotionPrimitive * prim = this->getMotionPrimitive(); MotionPrimitive * transition_prim = child->getMotionPrimitive(); + const float prim_length = + transition_prim->trajectory_length / motion_table.lattice_metadata.grid_resolution; if (prim == nullptr) { - return transition_prim->trajectory_length; + return prim_length; } - // Note(stevemacenski): `travel_cost_raw` at one point contained a term: - // `+ motion_table.cost_penalty * normalized_cost;` - // It has been removed, but we may want to readdress this point and determine - // the technically and theoretically correctness of that choice. I feel technically speaking - // that term has merit, but it doesn't seem to impact performance or path quality. - // W/o it lowers the travel cost, which would drive the heuristics up proportionally where I - // would expect it to plan much faster in all cases, but I only see it in some cases. Since - // this term would weight against moving to high cost zones, I would expect to see more smooth - // central motion, but I only see it in some cases, possibly because the obstacle heuristic is - // already driving the robot away from high cost areas; implicitly handling this. However, - // then I would expect that not adding it here would make it unbalanced enough that path quality - // would suffer, which I did not see in my limited experimentation, possibly due to the smoother. float travel_cost = 0.0; - float travel_cost_raw = transition_prim->trajectory_length; + float travel_cost_raw = prim_length + (prim_length * motion_table.cost_penalty * normalized_cost); if (transition_prim->arc_length < 0.001) { // New motion is a straight motion, no additional costs to be applied diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 9565049cd5..b4ecee5e53 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -95,13 +95,13 @@ void SmacPlannerHybrid::configure( node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".reverse_penalty", _search_info.reverse_penalty); nav2_util::declare_parameter_if_not_declared( - node, name + ".change_penalty", rclcpp::ParameterValue(0.15)); + node, name + ".change_penalty", rclcpp::ParameterValue(0.20)); node->get_parameter(name + ".change_penalty", _search_info.change_penalty); nav2_util::declare_parameter_if_not_declared( - node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.50)); + node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.25)); node->get_parameter(name + ".non_straight_penalty", _search_info.non_straight_penalty); nav2_util::declare_parameter_if_not_declared( - node, name + ".cost_penalty", rclcpp::ParameterValue(1.7)); + node, name + ".cost_penalty", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".cost_penalty", _search_info.cost_penalty); nav2_util::declare_parameter_if_not_declared( node, name + ".analytic_expansion_ratio", rclcpp::ParameterValue(3.5)); diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 50655589c0..6a31575bcd 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -80,13 +80,13 @@ void SmacPlannerLattice::configure( node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".reverse_penalty", search_info.reverse_penalty); nav2_util::declare_parameter_if_not_declared( - node, name + ".change_penalty", rclcpp::ParameterValue(0.15)); + node, name + ".change_penalty", rclcpp::ParameterValue(0.05)); node->get_parameter(name + ".change_penalty", search_info.change_penalty); nav2_util::declare_parameter_if_not_declared( - node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.50)); + node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.05)); node->get_parameter(name + ".non_straight_penalty", search_info.non_straight_penalty); nav2_util::declare_parameter_if_not_declared( - node, name + ".cost_penalty", rclcpp::ParameterValue(1.7)); + node, name + ".cost_penalty", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".cost_penalty", search_info.cost_penalty); nav2_util::declare_parameter_if_not_declared( node, name + ".analytic_expansion_ratio", rclcpp::ParameterValue(3.5)); @@ -281,7 +281,7 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( // Smooth plan if (num_iterations > 1 && plan.poses.size() > 6) { - _smoother->smooth(plan, costmap, time_remaining); + _smoother->smooth(plan, _costmap, time_remaining); } #ifdef BENCHMARK_TESTING From 460271dc426c71f8982dacbdee8956e08d382362 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Mon, 15 Nov 2021 18:10:25 -0800 Subject: [PATCH 16/31] reverse expansion working --- nav2_smac_planner/README.md | 38 +++++++++----- .../nav2_smac_planner/node_lattice.hpp | 7 ++- nav2_smac_planner/src/a_star.cpp | 9 +++- nav2_smac_planner/src/analytic_expansion.cpp | 1 + nav2_smac_planner/src/node_hybrid.cpp | 2 +- nav2_smac_planner/src/node_lattice.cpp | 52 ++++++++++++++----- 6 files changed, 81 insertions(+), 28 deletions(-) diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index 9f2045e52c..18df3a817f 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -18,11 +18,11 @@ We have users reporting using this on: ## Introduction -The `nav2_smac_planner` package contains an optimized templated A* search algorithm used to create multiple A\*-based planners for multiple types of robot platforms. It was built by [Steve Macenski](https://www.linkedin.com/in/steve-macenski-41a985101/) while at [Samsung Research](https://www.sra.samsung.com/). We support **circular** differential-drive and omni-directional drive robots using the `SmacPlanner2D` planner which implements a cost-aware A\* planner. We support **legged, cars, car-like, and ackermann vehicles** using the `SmacPlannerHybrid` plugin which implements a Hybrid-A\* planner. We support **non-circular, arbitrary shaped, any model vehicles** using the `SmacPlannerLattice` plugin which implements a State Lattice planner. It contains control sets and generators for ackermann, legged, differential drive and omnidirectional vehicles, but you may provide your own for another robot type or to have different planning behaviors. The last two plugins are also useful for curvature constrained planning, like when planning robot at high speeds to make sure they don't flip over or otherwise skid out of control. It is also applicable to non-round robots (such as large rectangular or arbitrary shaped robots of differential/omnidirectional drivetrains) that need pose-based collision checking. +The `nav2_smac_planner` package contains an optimized templated A* search algorithm used to create multiple A\*-based planners for multiple types of robot platforms. It was built by [Steve Macenski](https://www.linkedin.com/in/steve-macenski-41a985101/) while at [Samsung Research](https://www.sra.samsung.com/). We support **circular** differential-drive and omni-directional drive robots using the `SmacPlanner2D` planner which implements a cost-aware A\* planner. We support **legged, cars, car-like, and ackermann vehicles** using the `SmacPlannerHybrid` plugin which implements a Hybrid-A\* planner. We support **non-circular, arbitrary shaped, any model vehicles** using the `SmacPlannerLattice` plugin which implements a State Lattice planner. It contains control sets and generators for ackermann, legged, differential drive and omnidirectional vehicles, but you may provide your own for another robot type or to have different planning behaviors. The last two plugins are also useful for curvature constrained or kinematically feasible planning, like when planning robot at high speeds to make sure they don't flip over or otherwise skid out of control. It is also applicable to non-round robots (such as large rectangular or arbitrary shaped robots of differential/omnidirectional drivetrains) that need pose-based collision checking. -The `SmacPlannerHybrid` implements the Hybrid-A* planner as proposed in [Practical Search Techniques in Path Planning for Autonomous Driving](https://ai.stanford.edu/~ddolgov/papers/dolgov_gpp_stair08.pdf), including hybrid searching, gradient descent smoothing, analytic expansions and hueristic functions. +The `SmacPlannerHybrid` implements the Hybrid-A* planner as proposed in [Practical Search Techniques in Path Planning for Autonomous Driving](https://ai.stanford.edu/~ddolgov/papers/dolgov_gpp_stair08.pdf), with modifications to the heuristic, traversal functions to increase path quality without needing expensive optimization-based smoothing. -The `SmacPlannerLattice` implements the State Lattice planner with smoothing. While we do not implement it precisely the same way as [Optimal, Smooth, Nonholonomic MobileRobot Motion Planning in State Lattices](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2007_1/pivtoraiko_mihail_2007_1.pdf) (with control sets found using [Generating Near Minimal Spanning Control Sets for Constrained Motion Planning in Discrete State Spaces](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2005_1/pivtoraiko_mihail_2005_1.pdf)), it is sufficiently similar it may be used as a good reference. Additional optimizations for on-approach analytic expansions and simplier heuristic functions were used, largely matching those of Hybrid-A\*. +The `SmacPlannerLattice` implements the State Lattice planner. While we do not implement it precisely the same way as [Optimal, Smooth, Nonholonomic MobileRobot Motion Planning in State Lattices](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2007_1/pivtoraiko_mihail_2007_1.pdf) (with control sets found using [Generating Near Minimal Spanning Control Sets for Constrained Motion Planning in Discrete State Spaces](https://www.ri.cmu.edu/pub_files/pub4/pivtoraiko_mihail_2005_1/pivtoraiko_mihail_2005_1.pdf)), it is sufficiently similar it may be used as a good reference. Additional optimizations for on-approach analytic expansions and improved heuristic functions were used, largely matching those of Hybrid-A\* to allow them to share these optimized implementations to drive search towards the goal, faster. In summary... @@ -48,21 +48,21 @@ We further improve on Hybrid-A\* in the following ways: - Cost-aware penalty functions in search resulting in far smoother plans (further reducing requirement to smooth). - Gradient-descent, basic but fast smoother - Faster planning than original paper by highly optimizing the template A\* algorithm. -- Faster planning via custom precomputed heuristic, motion primitive, and other values. +- Faster planning via custom precomputed heuristic, motion primitive, and other functions. - Automatically adjusted search motion model sizes by motion model, costmap resolution, and bin sizing. - Closest path on approach within tolerance if exact path cannot be found or in invalid space. - Multi-model hybrid searching including Dubin and Reeds-Shepp models. More models may be trivially added. - High unit and integration test coverage, doxygen documentation. - Uses modern C++14 language features and individual components are easily reusable. -- Speed optimizations: no data structure graph lookups in main loop, near-zero copy main loop, dynamically generated graph and dynamic programming-based obstacle heuristic, optional recomputation of heuristics for subsiquent planning requests of the same goal, etc. +- Speed optimizations: no data structure graph lookups in main loop, near-zero copy main loop, dynamically generated graph and dynamic programming-based obstacle heuristic, optional recomputation of heuristics for subsequent planning requests of the same goal, etc. - Templated Nodes and A\* implementation to support additional robot extensions. -- Selective re-evaluation of the obstacle heuristic per goal/map or each iteration, which can speed up subsiquent replanning 20x or more. +- Selective re-evaluation of the obstacle heuristic per goal/map or each iteration, which can speed up subsequent replanning 20x or more. -All of these features (multi-resolution, models, smoother, etc) are also available in the `SmacPlanner2D` and `SmacPlannerLattice` plugins. +Most of these features (multi-resolution, models, smoother, etc) are also available in the `SmacPlanner2D` and `SmacPlannerLattice` plugins. -The 2D A\* implementation also does not have any of the weird artifacts introduced by the gradient wavefront-based 2D A\* implementation in the NavFn Planner. While this 2D A\* planner is slightly slower, I believe it's well worth the increased quality in paths. Though the `SmacPlanner2D` is grid-based, any reasonable local trajectory planner - including those supported by Nav2 - will not have any issue with grid-based plans. +The 2D A\* implementation also does not have any of the weird artifacts introduced by the gradient wavefront-based 2D A\* implementation in the NavFn Planner. While this 2D A\* planner is slightly slower, I believe it's well worth the increased quality in paths. -Note: In prior releases, a CG smoother largely implementing the original Hybrid-A\* paper's. However, this smoother failed to consistently provide useful results, took too much compute time, and was deprecated. While smoothing a path 95% of the time seems like a "good" solution, we need something far more reliable for practical use. Since we are working with mobile robots and not autonomous cars at 60 mph, we can take some different liberties in smoothing knowing that our local trajectory planners are pretty smart. If you are looking for it, it now lives in the `test/` directory in a depreciated folder. This smoother has been replaced by a simpler optimization inspired solution which is faster, far more consistent, and simpler to understand. While this smoother is **not** cost-aware, we have added cost-aware penalty functions in the planners themselves to push the plans away from high-cost spaces and we do check for validity of smoothed sections to ensure feasibility. It will through terminate when paths become in collision with the environment. +Note: In prior releases, a CG smoother largely implementing the original Hybrid-A\* paper's. However, this smoother failed to consistently provide useful results, took too much compute time, and was deprecated. While smoothing a path 95% of the time seems like a "good" solution, we need something far more reliable for practical use. Since we are working with mobile robots and not autonomous cars at 60 mph, we can take some different liberties in smoothing knowing that our local trajectory planners are pretty smart. If you are looking for it, it now lives in the new Smoothing Server as the Cost-aware smoother. This smoother has been replaced by a simpler optimization inspired solution which is faster, far more consistent, and simpler to understand. While this smoother is **not** cost-aware, we have added cost-aware penalty functions in the planners themselves to push the plans away from high-cost spaces and we do check for validity of smoothed sections to ensure feasibility. It will through terminate when paths become in collision with the environment. If you would like to use this smoother, however, it is available in the smoother server, though it will take some additional compute time. ## Metrics @@ -79,9 +79,9 @@ For example, the following path (roughly 85 meters) path took 33ms to compute. The basic design centralizes a templated A\* implementation that handles the search of a graph of nodes. The implementation is templated by the nodes, `NodeT`, which contain the methods needed to compute the hueristics, travel costs, and search neighborhoods. The outcome of this design is then a standard A\* implementation that can be used to traverse any type of graph as long as a node template can be created for it. -We provide by default a 2D node template (`Node2D`) which does 2D grid-search with either 4 or 8-connected neighborhoods, but the smoother smooths it out on turns. We also provide a Hybrid A\* node template (`NodeHybrid`) which does SE2 (X, Y, theta) search and collision checking on Dubin or Reeds-Shepp motion models. We also provide the Lattice (`NodeLattice`) node for state lattice planning making use of the wider range of velocity options available to differential and omnidirectional robots. Additional templates could be easily made and included for 3D grid search and non-grid base searching like routing. +We provide 3 nodes by default currently. The 2D node template (`Node2D`) which does 2D grid-search with either 4 or 8-connected neighborhoods. We also provide a Hybrid A\* node template (`NodeHybrid`) which does SE2 (X, Y, theta) search and collision checking on Dubin or Reeds-Shepp motion models. We also provide the Lattice (`NodeLattice`) node for state lattice planning making use of the wider range of velocity options available to differential and omnidirectional robots. Additional templates could be easily made and included for 3D grid search and non-grid base searching like routing. -In the ROS2 facing plugin, we take in the global goals and pre-process the data to feed into the templated A\* used. This includes processing any requests to downsample the costmap to another resolution to speed up search and smoothing the resulting A\* path. For the `SmacPlannerHybrid` and `SmacPlannerLattice` plugins, the path is promised to be kinematically feasible due to the kinematically valid models used in branching search. The 2D A\* is also promised to be feasible for differential and omni-directional robots. +In the ROS2 facing plugin, we take in the global goals and pre-process the data to feed into the templated A\* used. This includes processing any requests to downsample the costmap to another resolution to speed up search and smoothing the resulting A\* path (not available for State Lattice due to the lattices generated are dependent on costmap resolution). For the `SmacPlannerHybrid` and `SmacPlannerLattice` plugins, the path is promised to be kinematically feasible due to the kinematically valid models used in branching search. The 2D A\* is also promised to be feasible for differential and omni-directional robots. We isolated the A\*, costmap downsampler, smoother, and Node template objects from ROS2 to allow them to be easily testable independently of ROS or the planner. The only place ROS is used is in the planner plugins themselves. @@ -133,7 +133,7 @@ planner_server: ## Install ``` -sudo apt-get install ros--smac-planner +sudo apt-get install ros--nav2-smac-planner ``` ## Etc (Important Side Notes) @@ -164,6 +164,20 @@ I recommend users using a 5cm resolution costmap and playing with the different Remember, the global costmap is **only** there to provide an environment for the planner to work in. It is not there for human-viewing even if a more fine resolution costmap is more human "pleasing". If you use multiple planners in the planner server, then you will want to use the highest resolution for the most needed planner and then use the downsampler to downsample to the Hybrid-A* resolution. +### Penalty Function Tuning + +The penalty function defaults are tuned for all of the planners based on a 5cm costmap. While some change in this should not largely impact default behavior, it may be good to tune for your specific application and needs. The default values were tuned to have decent out of the box behavior for a large number of platforms and resolutions. In most situations, you should not need to play with them. + +**However**, due to the nature of the State Lattice planner being able to use any number of custom generated minimum control sets, this planner may require more tuning to get good behavior. The defaults for State Lattice were generated using the 5cm Ackermann files you can find in this package as initial examples. + +When tuning, the "reasonable" range for each penalty is listed below. While you may obviously tune outside of these ranges, I've found that they offer a good trade-off and outside of these ranges behaviors get suboptimal quickly. +- Cost: 1.7 - 6.0 +- Non-Straight: 1.0 - 1.3 +- Change: 0.0 - 0.3 +- Reverse: 1.3 - 5.0 + +Note that change penalty must be greater than 0.0. The Non-staight, reverse, and cost penalties must be greater than 1.0, strictly. + ### No path found for clearly valid goals or long compute times Before addressing the section below, make sure you have an appropriately set max iterations parameter. If you have a 1 km2 sized warehouse, clearly 5000 expansions will be insufficient. Try increasing this value if you're unable to achieve goals or disable it with the `-1` value to see if you are now able to plan within a reasonable time period. If you still have issues, there is a secondary effect which could be happening that is good to be aware of. diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index 4c45378caf..363a322299 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -241,7 +241,7 @@ class NodeLattice * @brief Gets if this primitive is moving in reverse * @return backwards If moving in reverse */ - inline bool & isBackward() + inline bool isBackward() { return _backwards; } @@ -252,12 +252,15 @@ class NodeLattice * @param collision_checker Collision checker object to aid in validity checking * @param primitive Optional argument if needing to check over a primitive * not only a terminal pose + * @param is_backwards Optional argument if needed to check if prim expansion is + * in reverse * @return whether this node is valid and collision free */ bool isNodeValid( const bool & traverse_unknown, GridCollisionChecker * collision_checker, - MotionPrimitive * primitive = nullptr); + MotionPrimitive * primitive = nullptr, + bool is_backwards = false); /** * @brief Get traversal cost of parent node to child node diff --git a/nav2_smac_planner/src/a_star.cpp b/nav2_smac_planner/src/a_star.cpp index 577ab30a75..066062901b 100644 --- a/nav2_smac_planner/src/a_star.cpp +++ b/nav2_smac_planner/src/a_star.cpp @@ -343,6 +343,7 @@ bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & NodePtr current_node = node; MotionPrimitive * prim = nullptr; const float & grid_resolution = NodeLattice::motion_table.lattice_metadata.grid_resolution; + const float pi_2 = 2.0 * M_PI; while (current_node->parent) { prim = current_node->getMotionPrimitive(); @@ -357,7 +358,13 @@ bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & // Convert primitive pose into grid space if it should be checked prim_pose.x = initial_pose.x + (it->_x / grid_resolution); prim_pose.y = initial_pose.y + (it->_y / grid_resolution); - prim_pose.theta = it->_theta; + // If reversing, invert the angle because the robot is backing into the primitive + // not driving forward with it + if (current_node->isBackward()) { + prim_pose.theta = std::fmod(it->_theta + M_PI, pi_2); + } else { + prim_pose.theta = it->_theta; + } path.push_back(prim_pose); } } else { diff --git a/nav2_smac_planner/src/analytic_expansion.cpp b/nav2_smac_planner/src/analytic_expansion.cpp index c390b07a39..f22acc12a7 100644 --- a/nav2_smac_planner/src/analytic_expansion.cpp +++ b/nav2_smac_planner/src/analytic_expansion.cpp @@ -224,6 +224,7 @@ typename AnalyticExpansion::NodePtr AnalyticExpansion::setAnalytic } if (goal_node != prev) { goal_node->parent = prev; + cleanNode(goal_node); goal_node->visited(); } return goal_node; diff --git a/nav2_smac_planner/src/node_hybrid.cpp b/nav2_smac_planner/src/node_hybrid.cpp index 0f008874f9..6d71779b67 100644 --- a/nav2_smac_planner/src/node_hybrid.cpp +++ b/nav2_smac_planner/src/node_hybrid.cpp @@ -331,7 +331,7 @@ float NodeHybrid::getTraversalCost(const NodePtr & child) } } - if (getMotionPrimitiveIndex() > 2) { + if (child->getMotionPrimitiveIndex() > 2) { // reverse direction travel_cost *= motion_table.reverse_penalty; } diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index 623d232c56..3dd3c52aeb 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -21,6 +21,7 @@ #include #include #include +#include #include "ompl/base/ScopedState.h" #include "ompl/base/spaces/DubinsStateSpace.h" @@ -126,9 +127,9 @@ MotionPrimitivePtrs LatticeMotionTable::getMotionPrimitives(const NodeLattice * reserve_heading -= num_angle_quantization; } - prims_at_heading = motion_primitives[reserve_heading]; - for (unsigned int i = 0; i != prims_at_heading.size(); i++) { - primitive_projection_list.push_back(&prims_at_heading[i]); + MotionPrimitives & prims_at_reverse_heading = motion_primitives[reserve_heading]; + for (unsigned int i = 0; i != prims_at_reverse_heading.size(); i++) { + primitive_projection_list.push_back(&prims_at_reverse_heading[i]); } } @@ -202,7 +203,8 @@ void NodeLattice::reset() bool NodeLattice::isNodeValid( const bool & traverse_unknown, GridCollisionChecker * collision_checker, - MotionPrimitive * motion_primitive) + MotionPrimitive * motion_primitive, + bool is_backwards) { // Check primitive end pose // Convert grid quantization of primitives to radians, then collision checker quantization @@ -219,6 +221,7 @@ bool NodeLattice::isNodeValid( // If valid motion primitives are set, check intermediary poses > 1 cell apart if (motion_primitive) { + const float pi_2 = 2.0 * M_PI; const float & grid_resolution = motion_table.lattice_metadata.grid_resolution; const float & resolution_diag_sq = 2.0 * grid_resolution * grid_resolution; MotionPose last_pose(1e9, 1e9, 1e9), pose_dist(0.0, 0.0, 0.0); @@ -238,7 +241,13 @@ bool NodeLattice::isNodeValid( // Convert primitive pose into grid space if it should be checked prim_pose._x = initial_pose._x + (it->_x / grid_resolution); prim_pose._y = initial_pose._y + (it->_y / grid_resolution); - prim_pose._theta = it->_theta; + // If reversing, invert the angle because the robot is backing into the primitive + // not driving forward with it + if (is_backwards) { + prim_pose._theta = std::fmod(it->_theta + M_PI, pi_2); + } else { + prim_pose._theta = it->_theta; + } if (collision_checker->inCollision( prim_pose._x, prim_pose._y, @@ -292,7 +301,7 @@ float NodeLattice::getTraversalCost(const NodePtr & child) } // If backwards flag is set, this primitive is moving in reverse - if (this->isBackward()) { + if (child->isBackward()) { // reverse direction travel_cost *= motion_table.reverse_penalty; } @@ -448,6 +457,8 @@ void NodeLattice::getNeighbors( NodeVector & neighbors) { unsigned int index = 0; + float angle; + bool backwards = false; NodePtr neighbor = nullptr; Coordinates initial_node_coords, motion_projection; MotionPrimitivePtrs motion_primitives = motion_table.getMotionPrimitives(this); @@ -476,20 +487,37 @@ void NodeLattice::getNeighbors( // Cache the initial pose in case it was visited but valid // don't want to disrupt continuous coordinate expansion initial_node_coords = neighbor->pose; + // if i >= idx, then we're in a reversing primitive. In that situation, + // the orientation of the robot is mirrored from what it would otherwise + // appear to be from the motion primitives file. We want to take this into + // account in case the robot base footprint is asymmetric. + backwards = false; + angle = motion_projection.theta; + if (i >= direction_change_idx) { + backwards = true; + angle = motion_projection.theta - (motion_table.num_angle_quantization / 2); + if (angle < 0) { + angle += motion_table.num_angle_quantization; + } + if (angle > motion_table.num_angle_quantization) { + angle -= motion_table.num_angle_quantization; + } + } + neighbor->setPose( Coordinates( motion_projection.x, motion_projection.y, - motion_projection.theta)); + angle)); + // Using a special isNodeValid API here, giving the motion primitive to use to // validity check the transition of the current node to the new node over - if (neighbor->isNodeValid(traverse_unknown, collision_checker, motion_primitives[i])) { + if (neighbor->isNodeValid( + traverse_unknown, collision_checker, motion_primitives[i], backwards)) + { neighbor->setMotionPrimitive(motion_primitives[i]); - // Marking if this search was obtained in the reverse direction - if ((!this->isBackward() && i >= direction_change_idx) || - (this->isBackward() && i <= direction_change_idx)) - { + if (backwards) { neighbor->backwards(); } neighbors.push_back(neighbor); From 391be46c4bfb7720b25a8fed64315d80767e9079 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 14:24:42 -0800 Subject: [PATCH 17/31] adding complete support, refactoring, etc --- nav2_navfn_planner/src/navfn_planner.cpp | 4 +- nav2_smac_planner/CMakeLists.txt | 3 + nav2_smac_planner/README.md | 10 +- .../include/nav2_smac_planner/a_star.hpp | 8 - .../include/nav2_smac_planner/node_2d.hpp | 7 + .../include/nav2_smac_planner/node_basic.hpp | 18 +- .../include/nav2_smac_planner/node_hybrid.hpp | 7 + .../nav2_smac_planner/node_lattice.hpp | 7 + nav2_smac_planner/src/a_star.cpp | 160 ++---------------- nav2_smac_planner/src/node_2d.cpp | 17 ++ nav2_smac_planner/src/node_hybrid.cpp | 18 ++ nav2_smac_planner/src/node_lattice.cpp | 46 +++++ nav2_smac_planner/src/smac_planner_2d.cpp | 4 +- .../src/smac_planner_lattice.cpp | 2 +- 14 files changed, 142 insertions(+), 169 deletions(-) diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp index d589a8b9c9..34a85dfe52 100644 --- a/nav2_navfn_planner/src/navfn_planner.cpp +++ b/nav2_navfn_planner/src/navfn_planner.cpp @@ -39,6 +39,7 @@ #include "nav2_costmap_2d/cost_values.hpp" using namespace std::chrono_literals; +using namespace std::chrono; using nav2_util::declare_parameter_if_not_declared; using rcl_interfaces::msg::ParameterType; using std::placeholders::_1; @@ -184,8 +185,7 @@ nav_msgs::msg::Path NavfnPlanner::createPlan( #ifdef BENCHMARK_TESTING steady_clock::time_point b = steady_clock::now(); duration time_span = duration_cast>(b - a); - std::cout << "It took " << time_span.count() * 1000 << - " milliseconds with " << num_iterations << " iterations." << std::endl; + std::cout << "It took " << time_span.count() * 1000 << std::endl; #endif return path; diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index ac1787cddf..0aba534138 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -78,6 +78,7 @@ add_library(${library_name} SHARED src/node_lattice.cpp src/costmap_downsampler.cpp src/node_2d.cpp + src/node_basic.cpp ) target_link_libraries(${library_name} ${OMPL_LIBRARIES} ${OpenMP_LIBRARIES} OpenMP::OpenMP_CXX) @@ -98,6 +99,7 @@ add_library(${library_name}_2d SHARED src/node_lattice.cpp src/costmap_downsampler.cpp src/node_2d.cpp + src/node_basic.cpp ) target_link_libraries(${library_name}_2d ${OMPL_LIBRARIES}) @@ -118,6 +120,7 @@ add_library(${library_name}_lattice SHARED src/node_lattice.cpp src/costmap_downsampler.cpp src/node_2d.cpp + src/node_basic.cpp ) target_link_libraries(${library_name}_lattice ${OMPL_LIBRARIES}) diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index 18df3a817f..fa5f3b224d 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -69,11 +69,15 @@ Note: In prior releases, a CG smoother largely implementing the original Hybrid- The original Hybrid-A\* implementation boasted planning times of 50-300ms for planning across 102,400 cell maps with 72 angular bins. We see much faster results in our evaluations: - **2-20ms** for planning across 147,456 (1.4x larger) cell maps with 72 angular bins. -- **30-120ms** for planning across 344,128 (3.3x larger) cell map with 72 angular bins. +- **30-200ms** for planning across 344,128 (3.3x larger) cell map with 72 angular bins. -For example, the following path (roughly 85 meters) path took 33ms to compute. +An example of the 3 planners can be seen below, planning a roughly 75 m path. +- 2D A* computed the path in 243ms (Panel 1) +- Hybrid-A* computed the path in 144ms (Panel 2) +- State Lattice computed the path in 113ms (Panel 3) +- For reference: NavFn compute the path in 146ms, including some nasty path discontinuity artifacts -![alt text](test/path.png) +![alt text](test/3planners.png) ## Design diff --git a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp index 44fd4ce72d..6383fd8236 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp @@ -207,14 +207,6 @@ class AStarAlgorithm */ inline bool isGoal(NodePtr & node); - /** - * @brief Set the starting pose for planning, as a node index - * @param node Node pointer to the goal node to backtrace - * @param path Reference to a vector of indicies of generated path - * @return whether the path was able to be backtraced - */ - bool backtracePath(NodePtr node, CoordinateVector & path); - /** * @brief Get cost of heuristic of node * @param node Node index current diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp index f5a43d0fef..4150deaee7 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp @@ -260,6 +260,13 @@ class Node2D const bool & traverse_unknown, NodeVector & neighbors); + /** + * @brief Set the starting pose for planning, as a node index + * @param path Reference to a vector of indicies of generated path + * @return whether the path was able to be backtraced + */ + bool backtracePath(CoordinateVector & path); + Node2D * parent; static float cost_travel_multiplier; static std::vector _neighbors_grid_offsets; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp index f49f10d53a..407cde5c79 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp @@ -56,6 +56,21 @@ class NodeBasic { } + /** + * @brief Take a NodeBasic and populate it with any necessary state + * cached in the queue for NodeT. + * @param node NodeT ptr to populate metadata into NodeBasic + */ + void populateSearchNode(NodeT * & node); + + /** + * @brief Take a NodeBasic and populate it with any necessary state + * cached in the queue for NodeTs. + * @param node Search node (basic) object to initialize internal node + * with state + */ + void processSearchNode(); + typename NodeT::Coordinates pose; // Used by NodeHybrid and NodeLattice NodeT * graph_node_ptr; MotionPrimitive * prim_ptr; // Used by NodeLattice @@ -63,9 +78,6 @@ class NodeBasic bool backward; }; -template class NodeBasic; -template class NodeBasic; -template class NodeBasic; } // namespace nav2_smac_planner #endif // NAV2_SMAC_PLANNER__NODE_BASIC_HPP_ diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp index faffbd362c..d913f9a5dc 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp @@ -417,6 +417,13 @@ class NodeHybrid const bool & traverse_unknown, NodeVector & neighbors); + /** + * @brief Set the starting pose for planning, as a node index + * @param path Reference to a vector of indicies of generated path + * @return whether the path was able to be backtraced + */ + bool backtracePath(CoordinateVector & path); + NodeHybrid * parent; Coordinates pose; diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp index 363a322299..7be319c88a 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_lattice.hpp @@ -398,6 +398,13 @@ class NodeLattice const bool & traverse_unknown, NodeVector & neighbors); + /** + * @brief Set the starting pose for planning, as a node index + * @param path Reference to a vector of indicies of generated path + * @return whether the path was able to be backtraced + */ + bool backtracePath(CoordinateVector & path); + NodeLattice * parent; Coordinates pose; static LatticeMotionTable motion_table; diff --git a/nav2_smac_planner/src/a_star.cpp b/nav2_smac_planner/src/a_star.cpp index 066062901b..cf52ac3d57 100644 --- a/nav2_smac_planner/src/a_star.cpp +++ b/nav2_smac_planner/src/a_star.cpp @@ -272,12 +272,12 @@ bool AStarAlgorithm::createPath( // 3) Check if we're at the goal, backtrace if required if (isGoal(current_node)) { - return backtracePath(current_node, path); + return current_node->backtracePath(path); } else if (_best_heuristic_node.first < getToleranceHeuristic()) { // Optimization: Let us find when in tolerance and refine within reason approach_iterations++; if (approach_iterations >= getOnApproachMaxIterations()) { - return backtracePath(&_graph.at(_best_heuristic_node.second), path); + return _graph.at(_best_heuristic_node.second).backtracePath(path); } } @@ -313,91 +313,6 @@ bool AStarAlgorithm::isGoal(NodePtr & node) return node == getGoal(); } -template<> -bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path) -{ - if (!node->parent) { - return false; - } - - NodePtr current_node = node; - - while (current_node->parent) { - path.push_back( - Node2D::getCoords( - current_node->getIndex(), getSizeX(), getSizeDim3())); - current_node = current_node->parent; - } - - return path.size() > 0; -} - -template<> -bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path) -{ - if (!node->parent) { - return false; - } - - Coordinates initial_pose, prim_pose; - NodePtr current_node = node; - MotionPrimitive * prim = nullptr; - const float & grid_resolution = NodeLattice::motion_table.lattice_metadata.grid_resolution; - const float pi_2 = 2.0 * M_PI; - - while (current_node->parent) { - prim = current_node->getMotionPrimitive(); - // if motion primitive is valid, then was searched (rather than analytically expanded), - // include dense path of subpoints making up the primitive at grid resolution - if (prim) { - initial_pose.x = current_node->pose.x - (prim->poses.back()._x / grid_resolution); - initial_pose.y = current_node->pose.y - (prim->poses.back()._y / grid_resolution); - initial_pose.theta = NodeLattice::motion_table.getAngleFromBin(prim->start_angle); - - for (auto it = prim->poses.crbegin(); it != prim->poses.crend(); ++it) { - // Convert primitive pose into grid space if it should be checked - prim_pose.x = initial_pose.x + (it->_x / grid_resolution); - prim_pose.y = initial_pose.y + (it->_y / grid_resolution); - // If reversing, invert the angle because the robot is backing into the primitive - // not driving forward with it - if (current_node->isBackward()) { - prim_pose.theta = std::fmod(it->_theta + M_PI, pi_2); - } else { - prim_pose.theta = it->_theta; - } - path.push_back(prim_pose); - } - } else { - // For analytic expansion nodes where there is no valid motion primitive - path.push_back(current_node->pose); - path.back().theta = NodeLattice::motion_table.getAngleFromBin(path.back().theta); - } - - current_node = current_node->parent; - } - - return path.size() > 0; -} - -template<> -bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path) -{ - if (!node->parent) { - return false; - } - - NodePtr current_node = node; - - while (current_node->parent) { - path.push_back(current_node->pose); - // Convert angle to radians - path.back().theta = NodeHybrid::motion_table.getAngleFromBin(path.back().theta); - current_node = current_node->parent; - } - - return path.size() > 0; -} - template typename AStarAlgorithm::NodePtr & AStarAlgorithm::getStart() { @@ -410,75 +325,20 @@ typename AStarAlgorithm::NodePtr & AStarAlgorithm::getGoal() return _goal; } -template<> -typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() -{ - NodeBasic node = _queue.top().second; - _queue.pop(); - return node.graph_node_ptr; -} - -template<> -typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() -{ - NodeBasic node = _queue.top().second; - _queue.pop(); - - // We only want to override the node's pose if it has not yet been visited - // to prevent the case that a node has been queued multiple times and - // a new branch is overriding one of lower cost already visited. - if (!node.graph_node_ptr->wasVisited()) { - node.graph_node_ptr->pose = node.pose; - node.graph_node_ptr->setMotionPrimitiveIndex(node.motion_index); - } - - return node.graph_node_ptr; -} - -template<> -typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() +template +typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() { - NodeBasic node = _queue.top().second; + NodeBasic node = _queue.top().second; _queue.pop(); - - // We only want to override the node's pose/primitive if it has not yet been visited - // to prevent the case that a node has been queued multiple times and - // a new branch is overriding one of lower cost already visited. - if (!node.graph_node_ptr->wasVisited()) { - node.graph_node_ptr->pose = node.pose; - node.graph_node_ptr->setMotionPrimitive(node.prim_ptr); - node.graph_node_ptr->backwards(node.backward); - } - + node.processSearchNode(); return node.graph_node_ptr; } -template<> -void AStarAlgorithm::addNode(const float & cost, NodePtr & node) -{ - NodeBasic queued_node(node->getIndex()); - queued_node.graph_node_ptr = node; - _queue.emplace(cost, queued_node); -} - -template<> -void AStarAlgorithm::addNode(const float & cost, NodePtr & node) -{ - NodeBasic queued_node(node->getIndex()); - queued_node.pose = node->pose; - queued_node.graph_node_ptr = node; - queued_node.prim_ptr = node->getMotionPrimitive(); - queued_node.backward = node->isBackward(); - _queue.emplace(cost, queued_node); -} - -template<> -void AStarAlgorithm::addNode(const float & cost, NodePtr & node) +template +void AStarAlgorithm::addNode(const float & cost, NodePtr & node) { - NodeBasic queued_node(node->getIndex()); - queued_node.pose = node->pose; - queued_node.graph_node_ptr = node; - queued_node.motion_index = node->getMotionPrimitiveIndex(); + NodeBasic queued_node(node->getIndex()); + queued_node.populateSearchNode(node); _queue.emplace(cost, queued_node); } diff --git a/nav2_smac_planner/src/node_2d.cpp b/nav2_smac_planner/src/node_2d.cpp index a9ed0abf58..073c50076a 100644 --- a/nav2_smac_planner/src/node_2d.cpp +++ b/nav2_smac_planner/src/node_2d.cpp @@ -146,4 +146,21 @@ void Node2D::getNeighbors( } } +bool Node2D::backtracePath(CoordinateVector & path) +{ + if (!this->parent) { + return false; + } + + NodePtr current_node = this; + + while (current_node->parent) { + path.push_back( + Node2D::getCoords(current_node->getIndex())); + current_node = current_node->parent; + } + + return path.size() > 0; +} + } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/node_hybrid.cpp b/nav2_smac_planner/src/node_hybrid.cpp index 6d71779b67..300aa3703a 100644 --- a/nav2_smac_planner/src/node_hybrid.cpp +++ b/nav2_smac_planner/src/node_hybrid.cpp @@ -647,4 +647,22 @@ void NodeHybrid::getNeighbors( } } +bool NodeHybrid::backtracePath(CoordinateVector & path) +{ + if (!this->parent) { + return false; + } + + NodePtr current_node = this; + + while (current_node->parent) { + path.push_back(current_node->pose); + // Convert angle to radians + path.back().theta = NodeHybrid::motion_table.getAngleFromBin(path.back().theta); + current_node = current_node->parent; + } + + return path.size() > 0; +} + } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index 3dd3c52aeb..9570104b83 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -528,4 +528,50 @@ void NodeLattice::getNeighbors( } } +bool NodeLattice::backtracePath(CoordinateVector & path) +{ + if (!this->parent) { + return false; + } + + Coordinates initial_pose, prim_pose; + NodePtr current_node = this; + MotionPrimitive * prim = nullptr; + const float & grid_resolution = NodeLattice::motion_table.lattice_metadata.grid_resolution; + const float pi_2 = 2.0 * M_PI; + + while (current_node->parent) { + prim = current_node->getMotionPrimitive(); + // if motion primitive is valid, then was searched (rather than analytically expanded), + // include dense path of subpoints making up the primitive at grid resolution + if (prim) { + initial_pose.x = current_node->pose.x - (prim->poses.back()._x / grid_resolution); + initial_pose.y = current_node->pose.y - (prim->poses.back()._y / grid_resolution); + initial_pose.theta = NodeLattice::motion_table.getAngleFromBin(prim->start_angle); + + for (auto it = prim->poses.crbegin(); it != prim->poses.crend(); ++it) { + // Convert primitive pose into grid space if it should be checked + prim_pose.x = initial_pose.x + (it->_x / grid_resolution); + prim_pose.y = initial_pose.y + (it->_y / grid_resolution); + // If reversing, invert the angle because the robot is backing into the primitive + // not driving forward with it + if (current_node->isBackward()) { + prim_pose.theta = std::fmod(it->_theta + M_PI, pi_2); + } else { + prim_pose.theta = it->_theta; + } + path.push_back(prim_pose); + } + } else { + // For analytic expansion nodes where there is no valid motion primitive + path.push_back(current_node->pose); + path.back().theta = NodeLattice::motion_table.getAngleFromBin(path.back().theta); + } + + current_node = current_node->parent; + } + + return path.size() > 0; +} + } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/smac_planner_2d.cpp b/nav2_smac_planner/src/smac_planner_2d.cpp index db4d85fed0..feec6f527d 100644 --- a/nav2_smac_planner/src/smac_planner_2d.cpp +++ b/nav2_smac_planner/src/smac_planner_2d.cpp @@ -65,7 +65,7 @@ void SmacPlanner2D::configure( node, name + ".tolerance", rclcpp::ParameterValue(0.125)); _tolerance = static_cast(node->get_parameter(name + ".tolerance").as_double()); nav2_util::declare_parameter_if_not_declared( - node, name + ".downsample_costmap", rclcpp::ParameterValue(true)); + node, name + ".downsample_costmap", rclcpp::ParameterValue(false)); node->get_parameter(name + ".downsample_costmap", _downsample_costmap); nav2_util::declare_parameter_if_not_declared( node, name + ".downsampling_factor", rclcpp::ParameterValue(1)); @@ -88,7 +88,7 @@ void SmacPlanner2D::configure( node->get_parameter(name + ".use_final_approach_orientation", _use_final_approach_orientation); nav2_util::declare_parameter_if_not_declared( - node, name + ".max_planning_time", rclcpp::ParameterValue(1.0)); + node, name + ".max_planning_time", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".max_planning_time", _max_planning_time); nav2_util::declare_parameter_if_not_declared( diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 6a31575bcd..fdd8f18e6d 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -74,7 +74,7 @@ void SmacPlannerLattice::configure( node, name + ".lattice_filepath", rclcpp::ParameterValue(std::string(""))); node->get_parameter(name + ".lattice_filepath", search_info.lattice_filepath); nav2_util::declare_parameter_if_not_declared( - node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(true)); + node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(false)); node->get_parameter(name + ".cache_obstacle_heuristic", search_info.cache_obstacle_heuristic); nav2_util::declare_parameter_if_not_declared( node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0)); From 1659f1c779488647d79445577af49184d4ae3f2f Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 14:25:27 -0800 Subject: [PATCH 18/31] adding forgotten files --- nav2_smac_planner/src/node_basic.cpp | 77 + nav2_smac_planner/test/3planners.png | Bin 0 -> 1359591 bytes nav2_smac_planner/test/config.json | 2028 ++++++++++++++++++++++++++ 3 files changed, 2105 insertions(+) create mode 100644 nav2_smac_planner/src/node_basic.cpp create mode 100644 nav2_smac_planner/test/3planners.png create mode 100644 nav2_smac_planner/test/config.json diff --git a/nav2_smac_planner/src/node_basic.cpp b/nav2_smac_planner/src/node_basic.cpp new file mode 100644 index 0000000000..7c116d64d6 --- /dev/null +++ b/nav2_smac_planner/src/node_basic.cpp @@ -0,0 +1,77 @@ +// Copyright (c) 2021, Samsung Research America +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#include "nav2_smac_planner/node_basic.hpp" + +namespace nav2_smac_planner +{ + +template +void NodeBasic::processSearchNode() +{ +} + +template<> +void NodeBasic::processSearchNode() +{ + // We only want to override the node's pose if it has not yet been visited + // to prevent the case that a node has been queued multiple times and + // a new branch is overriding one of lower cost already visited. + if (!this->graph_node_ptr->wasVisited()) { + this->graph_node_ptr->pose = this->pose; + this->graph_node_ptr->setMotionPrimitiveIndex(this->motion_index); + } +} + +template<> +void NodeBasic::processSearchNode() +{ + // We only want to override the node's pose/primitive if it has not yet been visited + // to prevent the case that a node has been queued multiple times and + // a new branch is overriding one of lower cost already visited. + if (!this->graph_node_ptr->wasVisited()) { + this->graph_node_ptr->pose = this->pose; + this->graph_node_ptr->setMotionPrimitive(this->prim_ptr); + this->graph_node_ptr->backwards(this->backward); + } +} + +template<> +void NodeBasic::populateSearchNode(Node2D * & node) +{ + this->graph_node_ptr = node; +} + +template<> +void NodeBasic::populateSearchNode(NodeHybrid * & node) +{ + this->pose = node->pose; + this->graph_node_ptr = node; + this->motion_index = node->getMotionPrimitiveIndex(); +} + +template<> +void NodeBasic::populateSearchNode(NodeLattice * & node) +{ + this->pose = node->pose; + this->graph_node_ptr = node; + this->prim_ptr = node->getMotionPrimitive(); + this->backward = node->isBackward(); +} + +template class NodeBasic; +template class NodeBasic; +template class NodeBasic; + +} // namespace nav2_smac_planner diff --git a/nav2_smac_planner/test/3planners.png b/nav2_smac_planner/test/3planners.png new file mode 100644 index 0000000000000000000000000000000000000000..3a6ef221c4dabf32d9b8c643f97c1633156f56a8 GIT binary patch literal 1359591 zcmZsCWlUVp+cxe}T8g{3xVslC)X5UCt3Z#o*wm;1s?{{_w~; z={QOvR{${Hjf`p%VrXuG&+FiCIMdE@a@qvx!m_r$(b;RtE`zLL2g76L70Z6zDpdU0~or&E-CM z{nSB>s*V#ujI!Q07B*S=I1@yBy8g^hITgg+N1C|eNnjUD)bXtT(aCq9v(@jbq`6sr zhA&t8PeV{YRNolc1y>3YUlhpss&pjMClV|4R*Uc{*@Am}I64y*9gLF05o`IUc&h%Q zjy7lC$HqU|Q+h0na4^T}jb(cqWvi{XHL~ef+OAt8JV- zIpg-)88ghRN?S&`k>i0Gbj9t`K*8|?lCdL!lFF>qU+|ZlV^c_#LDxwpe#@N1`VH@M zefQ=-hmRsgyIZDYu#+esG7{wTB6&EfbK6Li<$hQ^uZhq7X;t^`(+vcN)M29^%x#D= zPro0oB+soAJnb{Um3s7XNxx{TVjB+swY8J=-|etLLG!#$xPRq_|96RFT@b~`>3kmE zdoarg&;X+T<%lVjsfI~z`b%8er+Jo7>>j(P=U^Z3By1s!fbDc8CUd26oU!cU@`!zM zw&@#f;4m{)n-7@zYq{L2{s ztLc~5ld$`4TtC9{6!t2X*IPqy95~$ql+5@0S)w(&eC~bmvXt^{B&x(seC0+(o=>u$ z)OmBk4rt>F+de@NXR6Xk5iquYyK2~E&JKTvA#tO!jQF0hjQ^b<+dKZ2Z;c@9QTiD4 zg62bdUCC)0lMU<#tVOU&cO#8>fu9nKVW{f*{ogR=?tv9|r_E7qxzrePTNY-gIiZiQ z(DPo9^Vzxaf-;K9gGJhl)u+8>(-~x zT>cjOZ1er9Y?n1Phd?zIMKAKW;PIq?=6b24_<`LLEAmk!)NB4hG^I{bmqD%b&NgXw z%8yIXF~X$rHG(#7uPuYJ0h?;@7v~&MB{uKGp5f4t9@R(ta5~~J(?b-w(1KM^_c~no z{g(wdVd=JPc)WLmoPU_4@cSk3yT2^!V%>ra*y$%~p4_^VH^mN8mz>RYqS0^OONc=h zA*bVp``$x!XP@yBch7(elqb3=UJX~5xX*WwYn}_H)Vyb2-fVlV#Us~=afd>?*5TyG zE!Vj@{W!PM)3W2Z29ir8Mc(bgUFFJZhi2B!Rk)Sgu%1BQ<_>dp*3Yg%aVpt;A+Haw zy=Pmz9+2GE-q^i`wYIq6l5u=yoXX@1nMB#ozNdga+{&gJ#+3$&Z3ykt=-w;Zns*za zF&@GHnn+n<_D-*2h9#dkxUZis9$W(_Lw`bDXG2;VcqyB0E+9#4!;=i~;y`BrKU}ll z5nGbVzsVFhM|Epdi;5icf4@g2;N*?3#+ZV!BuI&u!>?-5)!>xjK4oY}3aMLGEcI>V z+~Zd@=`1$+qB6|jt7eW3yR$p21zBVmAEc%lPogF{3XsxqaD*TxHDa(f&MFo(PFh14 zg7Mf4Xd4f#X=y(G;E7jJBtfPi?g%7sqZ?8Fye^Tb)v`l9`0uU|yG_z;@ZWaYzPnvj zJZh+{{FJzGa8>&wg%}LB5YLxLQZOT2zx=5-T_YAR?5+tg>bb(ryt*aNU+J4+N$1HRm>q+SisY9$OHXi zkgF8Iu>g{lP3>JxJhd-Y)WdSfRt4EMA|)~19TCn?l;SV8Plv)A{fXVw(XZLPX{$9g zwq7GGBH6?u;A^6(S)SrLEb*5c0k-G5&aM&1j?i@fALRAff5D6oJ_nvJ1r1@GR-j%zt{SV2K$5=`LCgCEr-|v6FM4B8VQ|$-=ZYTI22_|Ct#V%+@#bJ#a8yb8O%KQkyC9k4($ot6i6Ts0|)s8b{e?Q6B0dJp0 zYUx@NFX%yXV5oVG?pUCP38b1t2k9U!F>&b?d99F}TH!B0hKh}2d zdcC)%*HG!RIv|tCnjUBb62>>KG}qc5_#|NLR1&}fb!r*xn~W_ifa#fV4`itC;qYka z0-EqDdOxtfT84nW)M}%CH+u-JTX&mipPCG$6e1eI4y}2GJ_rE5ehJ`|FObo#(oFNu zw8jhgYhKFT(aQyD)jP2CTdIW~c!!`(oPA?v6Z5;*WRm}v`fQhUzZ0G1xt=*gs_PI`2)Z>H{I4DZ_$4S&3}Ff}R)IyX*Np-w{+fmmO0=XcQ=dSUlrgaIMR~JbY!vJ^3(! z)0neaF8&&F;c*D2uf#vHEBDCMk;h9ul=Z48r8rGBexAS5FAnPN-7yWiMPQQs;;p%B zM~9*HqS6iHflwxdnQI)nXRvdb{b6LXBECXah(||M5_3Nh8Tpah>nC;w{D^JEc8&FK z^Re5c9%xhh1M#2OR7y2g{Mc-1Gc0pgw{uisofiY6xw75u_AK&&VcU!r>9qexMkt zl_wkrlI4~j7JwFzVE;Bz{8El^mKhy_PA6Y!e^QPpJVrPFLpvEV&G;xvp9`vIq&ohs zMa;4AtNnz;M_9O`DXr_g+K=|r2S0!6JYba0`j>{>OCZ#b?j`SqcO1Br3_ReQz~29* zwQ4yO(xYo1ITz4TZq|fI3Nsu0-H79CFB33^j|hQ!SZx4TOL!)|eO*63c7vQmXI>qit&*ih`*|0kA} zQoT4TLE+}^>O&%^tL!kUj_+PJCmqMcc3rNF%cQJU!vPj0U?DQIlLER@Ol~^Kdi!dC zY0s*tfv-k#mF^kO&sKL(bj!;1JR`l1`LCD7tOTB_4jQxP-x<+RiDb6HctyJdA$V!u z;C>{wX;~M9HL-XUj9NTL#HXQ2C(U3EL&LxVF-5A390I(wWPR<)efGBeVvd_FD-T(` zN{)$Pj~CqsxyCC4F^laEzN+`^hCmfS0yg3_VKx-RXl|XEb zk4Kri|3ssG_@D9iJ%^Ejhm`6LxfON3G>|&^&uTjlqK#J={{{bfXB^AO!)4X@)^6yC zdYK!T4QCFmvT)T2EG_b z!#SVK9GB28&7xfIF4w4{26R+dUpL`sNd6?9P_qOs>`wZmUghghOg;iklX$UmxOp65 z8LT(Fy4TAEz24C6?OVwG)6;{_Qlo+t?-euoCO$O^GJL;Ot8>@aEL3?8KG_?YhQgve&}R}oksjNb z)p)zDoOd=equwY zUxW@q_3?ZKekBH@-+HSVj07|p1R@?<73C)f%PN^L-_r4W;N?XxkR^^#E7Xc0Yp>L5 ze^0?3%Jku_*XpCs$f{uXnP`YA!d8Y*9zb!zLf(s}E!f@vtzeg`Sk5y#TO?%+X5uBv zNW%fJ&80@JUgF~q5Y@)+Pz-K!(ok&EI(#Cj24fG?{6*B%$N1@KV>V!8AEiJ}J`N0D zcD<*HLEe%z&Qq&n%qdLZ{=+9>kz~GUcc&JW=$3+0G*j>qMg1n*DdnNUT%LA@3V1Ia zhxh2>v!eH^5L2}Z?7dF2to1t{cMyf18Yd6|vI=u-B3tZh{_HRh0~}EbHxKw8f&}#nco4^7FgnR)#pO?ovB{A-|v&y!X$h zqc`xM2nWB3`stHd4cC4CP&ZYQD_p`m(NmVWJl}q@;r?lQ$O0#3po+%Ix9r0YZ7Z0z zc8AEwE(~-k=hZVUt$W2n+N^SwY8#cSnNGy=X!7MS)86EbdWP3wrMjR0U3%qsLmaqm zFH!#Cr2GyhE?$34AKVH8Q6cl&yXEXV|13+c#J)&1PJMNZ^Gx6FYWN+d=Cw@wy>LUm zGS=!~I6D40hU|k8=gi&zVX=-Mb*BGz@bO)C?mnTD!qBLgo_4oK?Rx5MLdR?|;H zMkBT}I5+FC!Axv(*QHaY^tvQIf>rOefR+~|0dGnVGxFc03l;s-^ollH>`lM^baA_t zt4ox#O{mCso>`uXETmP_X7KZ#_;$2>I9TC(ifx;s;b#a$b57a1uq=7k-xcEP%~?|q zg&Tgy;wu#UF>WwVoOP6xaaQ~YEzD~h`UMISY2WHi%H5fcfoKWW{(XRxyBOxA+fc*B@=BhyK4WBX(zFHqa@RhEiwBfYi zj<;5EbEd-&4KeqPL!bMeHN8{TT{!@^B@n>xwP#o`H&9zsqThrcbnAX@Y-B;O;BJ?h z3Ts?#eiHzyOsoJH)@*Vy%T_467*g7+yEFJ*S5qY(M>oVio<@|i*G4Z6MsquZi@+BI z4KWHtli&q0(LnZCGTFM$&I53z*A0>Pgkjfojk8&J&GseHdoz!tC~g6NBk>%N)_P5> zsG&jMMIT*COiY1eYr17=A-kwkp4+|p7+_~(W7MrEn;rGg;U@=D_tP*2Hl{Z8Ny2 zwb#B%STE^j@|(K!e~lLL3_8^Weax5Tqx*#uErYy&Cq_Sk+vX3jS>4y&jZZDXdlPIg?zR?=xF=Mt1 z#?7JR%0ywFG#Gk6kyS5UwNw+#eZGG9IlSvJcmHcZD$KIw6kxA&z&PoL{n=5IQ|MP8 zJVa<$&8By4h($-39xN1|#q5N+(&p!{)#_V=%T zj!bOT`wv~W@?JH$L9Voa<>nz4q{X8%H5tx&B{+@0d0Y^iT;GXMhR^SLyr`wP2%^AY zD2E|z)Y9m!s|DWB-ANv0om{|}ob#NG$bZC&0O1<`$YpNK_|EYxh>`vlNs`=k_|}HI z2h<5wyArXe6m$uX^QF`wL{*Y>KckN!B1$I8$VuvB9c>t7?5DmzIthMVPK zIGW&@V@U7e-(*3JE2<>DwQo0Y7{HVOaQzM~s}i=gXB}B+X@5gquJ`1f_c?LCBpPEF7}%YJ0yYHpylns(|b91My6!!en_Kgryd;pc~rj!-9FP|6(|0r@EcY zD&F&#{(7Pw*N{zm)src?7V@adB<>*X4f8 z3Om(9^*)x`Jq2a1nPGms@GB+P=Q08fvzxTb#fRdeAJ4Z$5ZsSPHHlioKD;pXq%#2q z&m2<09NdMf?lMgmluC!KThm;lB_>Dt5nTDHh)uT_L5zn8hlg~=R49oR^Hb7OJAhIr zJmC-TY?z@RBoo-Mj~2loqg{hjVm6tN7fUm-k{HCEVSl!B!i36`$LNoPkZ! zP7hq)8CL33)7uqSs-X$0X%cFB37UO@p@3^t=+6E;>z=^Vl`odk7*h`FAA}?{6nUEV z$85)~+c>d-i(NDG++o=S4Z$NC#DAhgX9yrUlF_?hNiOd|McQ=MZbR$6!QEBd^`WGf zt&iETmjT~0O?>xqw)4< zsv(;7dfB*;=%L-g#M(hYcD8IiF<_{T?K_|t2D($ZSZb;Bcsn%T*G=!m`#ZeVR)5MF z?wQ3pdvE)8Q!^PV>aK@Ex==BBs8h0ci)QKiuu+MtV7!tgv~(PZ7h%}0-+NkDkPdK` zgX8LgvppB9_NiM+a(YDxN&OEwRn!gfD18Qd#B zv~37LYX@rGk{k9V zi?(qHnIMj)iu*>g@;eZihm+2)wS>K-Yp8q>Z{tG^xNrQM>$}#K=t`)RiZB`k?&!(K8EHC(>*8)rfmIstc=)`2RD>5+DJRdiBW{w~! zqM+0OJa1dY!9MBFx;0n{oQr^4*(t(hq}V814E603^E=&lv&=_^W&&!_4rPl_@{x!h0e88IeSnh`T z>2Jkj6`O8oy$8^3mfsSd79MW{(GW0z{D=&x@qXxi}R3Vc0K9_@cdl= z-*eogpZpS9MmsJaM_SL^pC>}!O7#AQIT5=>PVeW3Qi3^Ifv;XxU#oqoDyeHx7Wpu5 zby4xuJ6Bnj2n>&tMMz3`Elz1m3|jpYbMj9HU=&AUzZLXszBsGkMFPU3^u@=8a|E>> zT;e@y=gp3Wd<&z8uUMNlw!D=rkzmJX3eA_aFkQ=p3|kO;&#ht&LCId5FzLvCm2mDo zGuyZN7+_BFL(5V|?YR>iEkFfVp^YPC4H5s2B92*oAnaoCM-1+*@&tMYJP!i+N1m&K zA;iEsOUaql)K4p8D7qi4#|kN6o>=uCGNnR1eE1uk*xIBwo-O_a7BBH>!D!w&hK>(z z_{u`*9jG~q>_^2%tHx%m&97H-a91RU5$#`(kT9vevotV?n^}S9buR7?L101|U=E!Z z&2TYMT2}wQE&r5NLjpY~+xdD3i$$&)f3<}f68q`8I$g&hQYBbSZ?Th5n9V@u_cFP) z<{iRsnM~Zui{ss4_Qtk7*k{{voGn>ShHH}gZ1XO5f9uxaT3&8MGI58^SeXnBf1QU_ z!Qd#u+m1l^P123(UjlBUMkWXXE=)ZzHt>n(C5_W_>(Sy%6xy27HevS=7h%47jIaA` z=tY|9F`4%3AO}OQL_2<^g`h)6Y{WT|(a%88$Ztx`F%+s1v}-9hZ~QZeU4WX079dB@DC5^UD!t z+H%Ry{#~*@BP-?-@td`!>K|T#UhEezZuZNEN&JL2=HuXwV&Q&}D@<(vsQBo%uBP#A zWtYqhz-Ho_D*n@W!)jN=ys4e*P5G3@Z?yfj){_Uv_jUAkWM zc;>53k&I-)4ds3)CE;Mtq>)eGuOct|A)<_TP>-x;*WrX-yw>x^Ob*aj9>VJ9WapKx zDZag$Pi$uuM0i^<{Idll_j!7-3x6z}wvGg-HSpRPd@fCgwFCGsh7mY5T{*NE+k*4M(*_;AZ084WJ6*WC6LAy^_L z^2Qu#n+=4&(@3E#i;t@6c%+6|6iUc*SVK4+Q~R@l7Jv2p7z+d{`xpfAsk(xu@q zw--x*N_9a_PdM>c+xVw6vP*U#$=FS^Rn&5c-Migt&VI)uCN2!ahv+Ij7`D$}b&6uU=nN7J$Lwu^_rf4jCKtMl5#Cbrc(Z3oTE95;#U z74UyP6|J;uHF(04ZAg$gZd+S^3T|?sRT!Eeiw-(l4y;LLZao!)%d48}X?$ZR?~GUW zAmO^7q{1?aLfBsADP5X`!ub+4kj!~RtAT`#_N!WERj~y`3b-oQFJQ6udRuqr4&b$g znRaNAqMgy1@C`I{44JL)UGP)tI6KM~hD0zA9kF zR{y>qwamCR(*o?qY$;E60$J5yWSVYS^EkGKf~=&}^z-S?5^9@TF4^f=`dVm+}Vnl;DWJ0>`V4|U4? z4h7kCY2<~{k=ZR773m3bs?~36?S^LXNio*duyxu(=b&Wf94drrJ0G%4hc%7c$#x~` zN=ou(HMeitUIGnGvumTQxjSbVT9zvAZQfKPVGHesj-^ep*TbhNsToP*F^67b+HCQf zpJamaBdq_E?X0sl=jUOD-b}%_<(j5uO8~o#<}!_kp)F&*wFboR7S)%qYy|fJ{;*2T zgbED|Tt$hN{ssnG)dB00;IvQe>{d^^=9ZztBEE8fA}2|#pd4wq8>+RpaDs=^4)SE%1{vnT9>jx<9v36z6MC&YPD_a_=5H}62j_mv{Jwi z&G%zG;}{ughr+kB%N~us#At&{{k(plkh8d!RqKekN3b0z!}%vqys)1T^~ag6195FR zVtZ+#7Jwj&u>KJZui%Ta=L)*FZtTD>`oP_HB)Gb^3^wl6(fK2g=}xM_nTFB7k~3Vp z8wsX;X;U@w0}?Qka=M23Vtvr8M|WAw>)zEg3Pxq0--uUnD?t#FrV6YXRu9az_QM`h zSu;F~dOC&WJOO@w(}30mJT$G9^KJ`y;ibARxOarM5#%{YUnR8n3O4Lj7>x?F1c}f| zaP%F&l4UPM`7BODyOQQ3r5REjk9Nhq~x&YoOcYQmDk#~+zFCl}&u-5qvr z=t%|I-B;Xhptr~)O)!{~^@Ky;DSoEIs_e89&1qXSjr2KYHb(lLl0Y_?WS?NdMXNwu!zd7kO>22_vN9v^azWZ3H?p3;k#*PX; zOGh&(1qEFJdU^#ExllBPj6eQ=k;`E7noM@ye5h`8d{!Pa!znX@y`J2P zeqY0Fkm~cViw%f^E($4z#|gx_wsWvi}@ zNdPvzb$rXfpCa$b!p-o)IoX1x4BG{GxG+_}z!hD-t;@gb;{B&Rwz)Z7ktM1?@Eqfa z>+5%^%<7qv*uKQb6uy$)E3NI`NQzI*&YX|(Q_9Bi0fW)1Xa~2M_`&Mj9?y$|_a_aS z9eKIDxD+N6sf1Bt7U4B6b_fgw4-69;mf`Bbfo0l#p7A_zWP;A`wG;6dhmBI0Mkdp0 zmpVUHbN&9r!NV|}FXf|n+b5M+qlhJ+@rh(Ch5z%kq%^T_Q9ecY?&qcsVGdqQjPWWG z<3!q18VK(g?l1vpFkX{Fv}YNuxJrbB+ziDeT~g^lcV7E?*YQ~i+G)2%nvtmwp|l6bE-^7 ztESV`tbGhz3Zhl8zP^PCf>wtPv|tL3&u&t?MzadV#_#!K0QMr-XK8c3k}bjD7sv>7 z=g-J$4)Pcs#IkN=!#~Jsc8gM91Ee)pt%--@PDWDJx5VrPvUgY)orZ^aVSgZjYBo=Invj`vv|f zQ^Z6;u8rH~EKY_xG_6BB4%n%b->)v$w#>utzwuKV>ykyUQ=ybNF;?&$ABSL+=m8r6 zcU3l>{I$ddW4UY)sx6Ia_2oSImw`Lml{r!^A-zr1;DiD~+V+6{klW4RMbXBw2o=tKcnN&^m%6*geG%&~A2xsc!Ty4b*at zW_vEeBoG2Vrt(zqa}FE$fzomf4R*o6z~FZBBp!DR qX@Da`hOR*{%@Eo=?a!}rK zv3FTljfPr8rOqFHL(xbfhw(o|9>phDCUJS1zcG>SGxmr0*KB3dguDCxP-WW%*XQxs zMEd4dTU0*75~b@#N9S0|Nam(gp#WtHXX7Ju8P44X$!|Zri+jkrgmHZKg3GO0$wuc0 zjtK~cUr=+D4Gl)Kaj>bgpFKz9?Q?&Mvv*p4&JA-fIj)~!ZswX7P<`&Gcgh4Soqr_Q zwlAYU7QQuJy5NXCTaQzGh52r}bLT~Wh~_g0mn_xAo)tdD=&uXFP)@{*a#&v~NQ z1WEn0pBCoix=-sfieqUwgib((n_Fc(;(Bk{)b+`}kx361lzL2ryPId5nd*{fb}`} zvxSc8tK4Cuo-rEP$F4_4X)M{`9;G@|)sx#&$$g8pS^D?Ono3U6FL|w@$~P{z{!wbF zc+D5Hvj6+5iz;30lOAmRUWi9-s45x$4>r!??xsTq-g{|l?#$2l9a5uK6#?ikW~VT3)ZehIb*}5K#Zia>Zj$XN1NXTC?M$PE-!| zkAYnB1V&+>&hJ_@KgY^j4*g!d7T17mnv`*^u53t?I;SRd3ua?WApFVm2QT9vv-sOB zOc&9fT*re6ABLr|;dG>G|-+!^=o((Re;!bYZNu4PvMkpH&OruV%rhhTON;GXh zw*DMymiZg6*l+T#OdX}J&PSBf_|<^!AJ^v42VY0P^b35~Xms~t+FF+15k14u(Tv;m zgQvy3-#ku)%D19Y)-P+f>ky=D2&-+I!$b~LpoU1lIfSO2=+}sKa$@c;{}1wr@ayMa zoA1%~{l#(GpGDuGuzRe35I+uOw^Pi7XKh-8|4Uu``vPmWWVXuqkW?w`pA&@w{N0@K z4YpIDF-0zlTZF@$s>CyW*etRoy@F(}WxZ#kXa4r6tlia{EW0jjJ^PP-;+3W1#ia^I z#RZ$pL7ka-`lep8fOGpRRxUeBdR9-@D2p21p>1Q$%bh+PiY4yt-KV|(U+XG`t$1{0 zHp|6++G8yLtD%|;I!vX8M}8csi2xMYo<4`AwYVT_x}Bf2oQJ9U2Hv`#886)nyvbBE zoa#Rq-<&;mf4}#(XQE$zlYFcmU&_!ck$HGZX;(xkM;fxFmKHGkr4Xz-?utXQC0Hg+ zbabJBV3^^A`>(s+#RY*qTPRpVnzN2$pOhakLU}Lmyo&>)>@L* zHxxZ(;HO|~Kgc=UJwskcv1*Za7y>zkk*nZ)?p4>cyskigPtQVyNNr1GMZ(-xzZ4mA zfnLFcA^Hy=7ZsX*^?kp>w!}_}ot%sV@%eNDk|>_Sjf(&SYD= z3Xd|M;1=t`g48`e|KaW>lr$#O(+Qh;NZ7k5sP>EU#Y}U+dQ^R(s zvky{%K#+8DZy|ezS8E~Uitc3E#Yw{2AR4&HhD1%>dB4+-`qzIY#`g=Ytk)_Z7o8w% zOpG8~($q`BqvCmk8d&Z#*S9||noz|LKNy!-Dx}pRp!KVA#1(eK{^3DYqj#o8UMM5E zV*N9MK0+qDLm&RrQbPwBrZi9m8vN|YUf>E}!+AeyGH!T0vRR;_9?)BP_a72jgraZ? zhbj5L*AVrKezu%29lAGj7MMMkOCw-O-^Z9%?SE~e#sM`d(ko<|i&$OD9k(~$(Y>;L zcncCgPGrdu45pD71YMesa3nGM6QyPMUzMmvH3p!es^-f0pG8?881B(NzJJI!M>Kjp zx(;b@HD4It3=9$&yOQrB#vNZ=H)abA@yis0!SK*>`M4z1tGs~0r2*Ircf)8AWwN zx5(WwT|DN z>CY`gQo6&+|7pyUl(AxmgfL&9dle&G~n3lNAef*eQGWUHG zd+M&1X*oRUTR_y6ttyzc^gtxl^npO^-4QhC)sP{Ic1lwr;cvr)A-Z%PuYY=iI1Awo zQ`m_ip`mtE3L!PCq#TLls`Ch!%!mj7Q|!K{sGQ5Yr@BTuDVS2TUdPXsrpcaj;;>L- z1tPx*aQ?`3TD8UDaQxL}$@fk7PfnSChIa|C4izzP`n_#pG=v92e9!TsmF3fk|C46b zd$YM!Dz#hQ8+t!{eCj-ZB4a;ai+cfkJ$_0WNilKqBKWSjy#Jl8X8H+d4C6tMVtSbB zKz(;A{E$#6yo5Jj4Yz+5-|6VRraL5M?A={C*38UZRVSsq`q@gh@C2jLql~l4Eb>D2 zHF1R>`C8K&`ro&T*o1TE>YQ_aS@Gvok4!FG^0RJs-e}r>3BJ@$W{GIm75o?P1%gWb zP9SL&d1-2b)?X;tnIYNJK)|O!2TJv&2oRiLbAkBQ6mi+l3k{m1wKh{!PmlTPzBE5T zdN7}oHbbM}K^Gp$YLfmCj{Vtv%RSlA{tMuB??6>BTmxl(xoFaX>xjxB_fbz>iZp_g zq>|47wv9DTxw-+gNPY-?bN!7Ul4}0EO8gqIi^Og^qZziteOop3mNtHExn6X+=1a8D zwa3XY;T{`fD?UJ)nZO68^2=<~{NO-|Op0s-) zb94o}b|5=I`7;;Y&lD>=-`o}5AwVVnwy15lAk@M z?YnXCFd(sAp03JZWBYS$!4IYny__NNk{OOkGf(o}v4q>wkk6Mz^qZ|LdaW0f*Ev`s zTUa^+o(|WAQyL=vI2pQQk#4(;s3T_aICfi&rF_NgzPerEKHGkstKMX#m3ug()mM6D zNUQ}XX?>HwlX=Wm>CbIQ6qkqwmQXhWw}gCmOCO)nf^&pjyNXVqq^d#z9jzlV`^WBR z>afW#HiNq9o7{Q#>znR!Q0^T#`uCBRHih>;g|ylR}HAG z`kObo+B{`WkBL@S*EL89xdeOQHG530>vmEsc8W`pA@=q*iX)Y%l8X2}vDBPmVVcV= z0Ku%kp67%|8TlMuz0178gT;TrLZ(wub_b1+-$yyLt5?J)sWOL4iX{_97DH5Lm4=4; zQXmmfCcT`f*mYl}1<5$o!R($YV+N@=~C`<$*Rtz9eD5a!ptaPp6{x>G`UlQk6r z>_|H#Sv94}S%w<{8ubz@QQ8I>!4%ph6}Twh@sx(j$--2xjDdy=Gu?w?zPmPmUD4e` ze5V3n$Q5l+xNzDm0ho>|FDohKV8VpTTa>04?Qq8MVM=@U%|QWU5#Wp^pMeE6a1=69u3t*Kz+6c;{ye9Fka1q=< z*caN{N4XZYZoleX7C}9d;NDASBn7?_9=z+_++JU6ZgNJ1GaBm+6L8umgX<`p@OwWV zq%2CK8_P0)hN8=EIM_I{a0P~;Q!iH0L*`Kj^)q8P%su1bLh$9g2@o8EYI4Vs5li3F zzZMs-f%tRxpS&CRQj2e2Jn+{yL*c)zp8G;b zlXG?X1~!LgN;vrCYJ3L0Zm=O$etf#D(dwb4Xhhmz1m_>)sNB-Q_cw>O9*=|K(q$KLxcc8-bLI*lf+I533gu;0KB|?bGe&4}3->&%q#eEL(c;YtXaOX)r z{h_P8BKF@WbxPCEOPFqZl{ecF6`v2hzTVb3iHhO6+N{{ir3@*BerWO!idY)-FoodO z_#MT@dW`6p=})(n>L$K{#@4@oQX9pF=_3`{%V?cwJ}E&~zWld<-d}Ua9+}o@P!6g+u@@D3lV zqpf%A56)<ANd;dY(^I0% zs`AJ?<>32m{uM>BN}l5UXEf`d zE%VLw)a8ZzW4ik+XPJ9;8L97uJ%44KxUiM1Btnp;6m&~L;$I)%^Jtu5(A#rXuBc~! z>*PJZeA-`Td96vUiuTshaZg#&xce>)Qu*TEOMU34|FgCodMkZ5QM%recFz~$u$24- zKp)TQ?CbOu5zKPUi`q!6tN>YCWbf$FJIOJSP#bB85?&#i?%C%hJ8t>}qqB4j$AlY0 zSEIS+&(=0^qLEq`uYMm2t~QGNIitKoe~|aQZbtgncqLP?Hc+M+Hw%lTFgm^Qe;l8< zDCvYEvS9je;Zq^v`pu`)4WSu2i!`#&s+k!eZMruC_9C2vT22 zmdiDoi3}#P`jL%tXz;p3Fucl?@13pBW&@dc@?`C% zM4o<-VrtFpF?Qdnl9_d#zeD4nZ~F!TYsLwG3O+^S2=ngBII`)z<7>Sw;Iy zU9^S$AWmdX*?va;cw*BEHB{A@!Z1Z&=sJz8;O}kJc^glHt&vuNHk0&?Hc9gY>F(+R zv=>CWp=DYod3%}cl5{lsl;ykvI(f>$E2x50AWm&zTUF}DW1GjqU9U6m8g8@w+8)({GQizkiRoWfNG( zcbwBKM3*PXQlXA?apt6ae*BY*=ltKk>sppxd1Ep<<9usThqMqixj{oqz+Na^OHn2E zXm@+@z5YPR3re0rRD*H__cq{NQ+-$qnX&55$1*;%HL2WxSTG&ddf2cyp*CS6kBr%9 zR$a;+uWmS3V+>cH1j?JH8i=O9be6#BvD0g6HQI==5j5&zXKjMG{{RtO)`%v9$prD6 zNf>2W9Ol~h^nF*oIdSB3zS-F!%F2=~n3H|A`=I?Esx%=maxwo%Nj241Sc&~bjm$^N6W_Ieg%WT|2r@nhDG%ZK zDuZHsWJp7iKzs_H$cjQtB858Vxyn>Y#in1zOBANqOht z`f{^=8Q9%GkAG-iRG$E+XY-lrMv#c#(}hq8Q|xF!g;)Q;d`0y{6&${Ef5qD6~h2D-PS(>=w6!-NC!hi%s`))>oNWCz|^2!7K~1 zJZmlPB;x25(lS9}WNByPCibt2ZC}ogYgl_-f7uHzP*nUW!ugtF*gD4-TSVwjif{Ca zaU@*N{t0m#TYiH*6Whyyi#*&R(K|mU^)c(O71gb}eNwYqa07L!T zUDAQU?oHH*rgmG!(m^Jg*In&d1+MlXfGH9r#QoMk3tu|SH_s?!eJp@s04EKPk%8}I0Ij`^#EpleS0@XU|!fWbz+n!#9mXN|Y z<}J;vWfQ9LiYaKa2k2|NGVt#C6dY zY$1ef`gdYAg_X?JN|^s|8;xMJ@grI^U}EB+rY_M`X$^j-=% z^H=}iH_O&DU#*b@XQzUw6irqa8yoI_IPh~^-J{?6c;cbpS%kq77|Z9 zYf0O=l?xw2$?bQ)JBb)cpEnwUBY9#ug?Zi;Hp0Ja;{GqpnjUej`u_lmKy|-A>tJOL z*p3RiyEN7A5;oy!q=86m+*xV^_EV#~E?hvpZ{^Lx8t{cVE78}rXyu)U)cg@Lqux;Z;j89GC*8O{!o}ITUD4zIUppN+*$Ps_*R9??m4J`M$f!9Kj%g0Ue98D+`5=+VbSK zwZWkF9n#V>aONmms~enH1wO6a1A01Bat7(U2-7R{EX&={F$`8ec!Z-LeS#0a+1c^k z33gq&jQ(a5rw<>RQ$25dbPP+!CeTD*ZqvtDb?-60^W&dmc6bo)zWwd4>XVt1QzZFU zm|VM1+8}`Rz%j6H&EtdO-ll7}vGv+@jIJ5Mv9DDJd$r*K{V4^y{S8+N29d|m^ zL7y#VA5#jG^OX(Uwq8s>w7V0;|MUmIo;7&)_$S!3b}e4oZ4bz8Ubh}U_~y6qZ+`ld z+I6)X4gBnTZ{yp4`wj-CXN&nqv&c^$pd~J^OHzB$Qq#?E${flwy}rgAew!ddHUIyr z*>k#N(v3GPx7xa+k}aE?SAvO>*f03CQ-Bj9@XkOBkAtijD$0PJyt%Gbhk95 zqhaJlVQg8~vw61p04^XYqqSJK|GG^GdIDt0`F^^n zW+BZ_&QVt*jGQ(g%9)%qv=oq6%-?QZY+3tXXsTLY^lXUW&JH)i#IGwn*0OGw@2l4C zUckrNT{op%mI2>dS9fU^qG6~d{=bx+uH6vUF_=br4Pei;y`KpSOh+nkIi3r2xIzc2 zy7q_5t?rDFD@7Riy|OhgyrNY@Z#pKuGhg;|RT~n=PZ>^P#c8a&eIJ|>k^Akh)TDdH1>Sn3_&L#!#|j9|6S{8Py=y;< zJUZG{9~Pk|{3bXl2&$%fFLbCjJ37}FYO}1)PWV+nuYPy`x^GoJudb)urPhsM)(f~o zzD`-az((q>RBlN$(^f;H*}|F!5AksAn#y)otyqCq_U*?{KKh^*UPIH<*njT4%Jy27 zb=Nq5u6iNWGi~TenCrN>ik%O>;=}K{$`Y04MN}$}^qT@CIp~W|(OCt|ZbLJrbiNaV zI&%`xv<6U&h0aw(%bp$&xtz--oC3NiOAu$mqUBVcYPJjMo-Z%r(dyM*2W>BVI*#Fq ziDDaYV7iHer_Z9@XyC!RwaDV?4f;6Cu=f4~9Q@)e;&z(zWW(7cG>D2#JgXw@ym%El z+cA$Z8OJU36~FzA#yZon=5;wgDO)S6QOH#l*Viu2Tz?vlD{iIMYrkJZEU!6 zw`hm6yz{4mS<>0wFL^qNgQw1VZE2%l8{u+(b2~b7njg5WH&or43H!G12$p;8Kl{75_uen?@W~VO_w`}< z@KUT=v7)kW|GN*G%jIfBYgAUqJ-vcy+VTiRf|m44>O!u8%=6Xf&GY9Cu3rbT?)Ur` zp#%In+RUBZV7gp)b(cYJHgZ*+b@1!158ae4_bc%1U6{k;?zTWTwlTfw%5(V)&K zlUCa+gx6)Jz5c%~&4(hT7RLHG+r)f`Fadp7)<7T2(`y&qsSDZ$q0Gqo5T6_`9uK`K z%iF}Z4>nXyI*O66{`Pv=(+Pb27w_Z!Z&f?KtKh)dbJ%+A25xQc?f^4Ef3t~izWYmL zCPJgx&JW-cAM$t(OwHiCKmHjKWO)A@U&r*4po*3xV6PvfXT<*g29%nH?ZmE zEsU-n!HKWDR$14U8#l4{+?R?2<2G%FxEZ!}He(3>G9bT@Yk%m^5X(P(U&}9=m#!ts zc1VmU&om454$oC?OX`32o($N8c!NJiuC1k5Va)T+JrE)L%ods6MB-;*a09a4x_z6N zHa#h)HfI)(5u=^UE1M;l14GCzu97ysP04VJek{~rzh z;19l!mCLFF{wxLDqu7ig(SrSanzPAH<@fCxpCA=JJ*goxxcYJge-oc%urAk)=Kdnj zh!-2Wr`xZp?d;;+x##tHu)LI<4RvT838_+sQ&qdJS2l!)e7DnzB-VdDb=+(saa#z9Qu~Gc&uiruTU;Y)Q|MTx5%bk3m zojZ%cfq|f1edN?B3{Omf_2x2r*~M7f$i5fS<)|u-n46S!{m;}MVJmUa)-+R_*9rN5 zK8ERf6AXC#UG2;iwS{cxkR?$CJ{=ivndn4nr|!yVJrjU&ED!2q2FceQxQ zW1(3Q!kFKdyXcZ`)#0DzG|>H(9w54}X&`$cu`}Yg+ZSIymK5+c=SbYwcC-!*lx+}) z$D%&>a0GJ(*QD1geb22!wioJ`3zBlWhx)fWYI0p+DaMC*c-}=`*^vEPHnJ{0A#g1p zu1U@iVnf|4>u)T6mi)}Vj$ZZ!L$ zX(i&sF)|qf`S6%`698@s+$2lUH{1F1#&H~DXmAh_fWP_RJtT30*AE}Y=5^~U-)r^v z;rxO9Xg2z=@%o*D0tWnbEUOpDBt1-dw$E8}K;9pB^v1D=z zhfjThpa0f(JEJz!Mtbo9?mvEnwIiz#MG>An9mCMz5C%&=nM#lE5NJTuP zqPd1-FJn>uj#hzvV>wg~MPD;jLaS7+Q3!A#6g&gbF0+1^AcsYVPkV(F6Pe+>iYNS5 zc(awLMusQ3vf1d9V-^*`2ytFln)iNqd?F9BHkch8#Pm?P<7?^o1RCu&c3ioNb+_;3 z!LF80Nh`%`$4}t+>qo^Wk;7_gU$cc*KRF>bP!q__RHjg0yLEH~L-23*#GO|EY6u9Wj)lJCwDL0_vHQ=rc@gUYBL7 zbNlaRPUHUT%vt`%Dc5II-Lii7x9p|cW1h1tOI?Lo_aOoVF4joOoR$n|X1f`uDH|Zy z%%7a$!y0ZOCy$x? ztP}WrU3Fas^~*ggsMd2rdQ6#aS7sQ?=k`g+9nWK<-51(bV@qlm40FGZAZFR6U7wO~ zviyk6(9{furl%{{KL9wiXD<%z*;`qL;PiVZaJoOikvCt(*Is_5#v2mL43yo}f|US? za2(MJI(?rKW;25}uNm*Mlz4W2#)rl)~sXCJ{L)P{wzVqP?;vf1X>XVANi8XAW> zxK)>#kG^%X)qAsxLpDkshibhtEQ7;1xtfdC7TtfVU~pgnNt~eBYN6F`*LVZibKxSk zT)!#4@{@QPm1`@8H7$u}IVZ4m?oI~#C0XLj7EQ2}%mQNX(GehN^RkPWv_T+-w27nQ z4#2^Iq=$xr9{tU#av)n)+P**pnIl;K`TDvB3N4Mnf$-!yW?hl>#U#tn*KF0s*M*l( zpTWjkcM!ERth;j$X_DalOI>D%HbCEO3z^}7b$O7PATkDhvn|9h_{zt}VPanS*|r7Z zG(%&y1t7`;XJz0rUCXi5LG#Sd93*UVCq2ij0~T=@jCXO zJ&$GM(VxN=e;WzsK@$WeLpNKrL1F(S6j`Ix<`DQ6?e%(vgOGxmR5aMv>xK(Q{VYYuYcvQSa)G~+w3=Iwu$$z{;YV(cjYjb);jggeJ+tQ%?s&L)?J*wx)4v2R zJpxj@E}S@b7I7S7!CJZHI1X<5Sg?c-6^YkP-E>BaV#8r>DLc5VD=a;TAaWq&%Yt{gQXIZg63 z@uRznbUUVx{@Gt6`r$#$?%P+Z{PdC`%nl5Q)@TLIiujZ$?~zU}#-29P8GLHVJCfS= znS9#ls+WsU35!mO`GM-G*FBB>MXx(!y{g^0jJZ@FIxVSTT;#G?{%$uo>g6v|0wh$Y zf!jvdaNtc+RtR~cqC2DC+#ARAzjzPt?B9Stdi#6m>+8dbb7!%4+jeZ-u(9%88J;ci zqkc&RJCxy6s;2UNe~ijiOSfD%;L;vqbZF_LXQ9)5T2Z1LK{BUPk}saTRb+defC56b z8I+-ndtK*=`z&NE^M>6c@`qxx5Wb{;4LW&4Dk@gSN45Y~O~< zyLXl-CBTuBr?BG5nBohGZ)^;{dhC-z-FMXpNjct-mdic|7qc23!Kh41iC3?rC$-9% zD&>+~D1E@XaVc zAUi`+Y+92%a(Rr;^YMMx$Y*|)He4 zw|Y}my#}<}hTE)a%M|5!o{|h;Lzkt3cA@b2lVNK&s8cb=E&pu2dL40=;=+M_XqFs& z>lVzPp8_^52i|1+ zozR=TgS3LH>SX&&OE7I8kiHM>`SKD>6yw3V@TPGY+`fMww;$ZcR}UQyJ|CK%M*nOR zZ8VggAp`MbAg9iGq4hA zZ$XbHV*}N0$g*+u$TGcI21atLF?5fqWx`O_DQ!{P+YI)LXGcFij?Z6v1?@(6?%~0y z86?d%G9+j;Q*5|(2N4X;y>y`CyDP@Vu=o50AT!8}&IrwiId#q_`t0YVvf*K@T(+!!JqkB%pD^Bh{D|HupCg@Q z>wL>zt;NdKLzV#a2>2GdaY{z&|NIX3-nC-6O!s^yZ3)KJwG%^Swcmi-W_yG*LapJj z9!_=<#677aNli!NOn5~ej;y1zC&Qg5W&W6ueJt%b)(c$gs7xB^nWcRi+J8}|-?O$6 z7k72LJdZ3jWd?4o7ly#M0kq8`Jwuwq%IA_#UwuDhS42f?te@(3G{1-Y6`qs)Bs{aY zwlMhjLsXMq0M|y8ee^k&->piT!zJAJ7zh13gtvavh|+8wOIp!el8*LIdI0on(X?>! z(%8s8$~QQY!?&6>hx#DD5~i`x(#Rd35RH)cmEPB*r|oYjTiseu#<9ZOqb!=nk~dxH zReyc+^^Z<#XB~Lls0_psXzY_NmI2xn9iy&eU&#xPiQH zGW7-rZj(of!?-oyS}x1LK0S&@(lfLU^d$|v^~$Tr{%jde{p1+VjU30|?+swnx^*4j zeYk!tmP}4#-R=93(O+@lgEILwN1wU!!u4)SjYqE!A&n7CZZIgTPq(iHKZ<8Ym1EO|)e^0+_X^SW5iI@Z ze}q5&-fyFkG|)~{y#4x{h@!cSf>g`gpmYtoA5{x|l|kc!R^g?1m+B7J%M{nACf!BU zRonIGQJx;xtg`{SvbUMonw07}FRZ+2EPLWpP^+U_CDwm3sM9qt;q+6E31vlN4DGc+ zBY$dplN4A-*nI6Kwp_b`2*y*2-5_V$T%`-| z#z8XJGZmX#DH3P1Ix6}QGP7vw&duT?Gdd$zo9I5xcF7r%?5kq^jD5W z8E9i8LJNIh^+{&g=6ev>mSfH1rZ)`zadq*Lwaapn9;D!E#f@gW3@?4L^oSw zmUB+X&QZT$uOO_{yRzQRZq8=0&Z^IfDh09|(3U-g%TTbj|2bKr zGSrhYS;J?qdB*v5l!2yzJew`~DdhZcL9Y|BM?boD4;yef4)BmTu&Lm>9CX`~KCauK zdabTr(`4Vmzf= zx6s#a7Fb7?DFaX+Hbru^x|y4}sa)-e|E178dR0`GdJxI<6b2Ub*sT)#KXBxa(EBye?nM z_UG`k;ycnOT)f>iB10r3u+}+Avhjfv`+UXN7>1^&>*4X^F9ECr_U^;v%rqW6d0bgu zYP9srYE~S`4M^KX>J<7*BR)5k>j%d9*S%lG<;E#t6y^1r>aNeatXykZJ0RVgR$snC zG0MD#5Y=K&Ypc=-s_w~5v-VnN;O0!xtT(%BnYLx5ABO6oc)cbq{eXbuuT(?w5UJ7HgStn-4cf>bDyRuW3rIc^ejJ?`Pml=24Eby;|{T z3=vGx7m25~Rg=Q+VLcQn=;%7xDVjTc2=(38nFw0QgX5Z4*cOw16>VQg{*@!^+6{7^ zhiA0wz2dp(T2ESEW}C>;89=`ALpi4{uh4U{7JUoH?Wa4|GKiYzIe-FV*NdXZLVGrt zW7(dA;5liZBFCTXT{@~wIxz}-7$buSiAQlM$9;bqS=3T1mXy(TXy{~PleE#+scXxi z1Aba|@tC+igs`trj}re$8`q&Y{hW5v>7y_=dKDS3Vv^e~nKpZ(Ljd;N0DZ4>41tP79{MUCLMTDU&~* z{P&X6c_z^_))e>%8Ueq-SFR*IY*F%p%lo>Fu37d$j#zj# zlKt!zs%EKcTj+9xH}^w^BeE67);90W$v*Kew4PP6W#i!{aSHW;_glj};Lb^|i`vlk z9zBy|SY`$2Hp6zHZpZ3ft}fn*cSHD)9ihjFYVFK9E=@J{L;kxEXuCqT=-OF6r~9L- zrE^HW%J;QAmh(+((-JSXunFW0*S4!~t(IN$yY79rSJE1D`PP*%JhoEnmwJAPh7!29 zRmV#u9i_dkt#QW0kH65fN8Zz*C7^!GzpKYXkB{!5uWhgeKz-14b;42CBNJ*;+9b(c zEV22X8*}4g9k%UUDr)M;aV%T<hNK_3ogTcNP-5vCBhc{d+7qs;EsP<(8J(f~1v{ z%RFA>^OET;_*;0C{J_@l#+OJLz=tn*hQvtPZS1^w8P|7iN1A9KtAr#;aB$adVApP3 z`jsv3?3fdl9xdKmCk6^>?J6_MC!cvzKMQYJ<)nl%wyxdGHw((uM0$2>% z?ggHg!P^Pys_!o*_MPw#V;vfcvU_|2XF``r>5|){_@}9Pk-+R_;>HVgSTFN6&qHs>8cK?;BfdP5K=a@b6=}j zvW%}@m5oy!@YPxONyy>N%8Twv2FlDSH=2MDzsL_lN1{A!<8kP=4DKr9z4Cif{pL+o zt-fm7@-iqx)oJsYvu#trseGTuN`?q0h{SdoWhl~MfIKUepB-D~L?UX13>Rt4(MGY% zbVUK+Y$A~ALrRQ3mG6Q<>vgkW z%eOVg#K+aLgX)y#4+m(=Hpmp?{^|{S&11gm#k|11hPv<1eM=E(M(UG@QUP_1F`_UB zZkznyw0M{2GX(u&!9Ci*_Gt&8$Uv`WxpW&CkW8^p+>IdD5O4#GCCws*mAxN}a+JM} z113@@P(kt-tocewGbOSG{ep(Jyrahav5&nPn-Yiy=>qry(GXJ~RzHcm&#a-MfZfa^_ zt9Q55)6)Zw4YUU^3>bbf{NRRR4~&7~7sC&R?HNCf0Rscr5AMeFxNUd4cePr(NRgsM zag{`hq*$yXSw*snwcq<^`XT?w_##f6%>4g*Z&h^P#r0dDsa2`kdO0#7XgkK!F1%-o>ZK-^VkLKC&*2{L*8Oqxv@w z=i)OR+NeH!Cm`)`TEZ@+`fi;FnBWBZ^!_4fJC zUIA`<5IAt4v)t>q-h$EU8V(;nft7RTC$WPy!r6?sazV0wwLmi;zbeC5w1kg#fMgV@ zzvlX><$OZZQ@@9qU9Z;@{vJ;u7vUb_*W9`yRah_S+au4zPIl z^l8kEM&SnTpWSi{`%k`y`HNS;$MA4QtkT!igE|=_UeoNCxeFQ3PL``jYqQg#Dev zJ$YM;@*leblOGZ91NbSc@bT-3s*AF{Z~eLEfVKsmnO-)w28)7xuIWdTzcYrmF7GI? zdeKtNzuHHMGCB_aS+DBM>yfpU^G=E%HNF*e-OmW$_q-0Ibszg<+ZPE7b4RhV9fvMk ztW7`dJT9PUTx+o&tzW5InVNMI-uBHl*hsBkIFpuS%W4(y)TZqp*)=$G? z>ufxy%`fAg@zhh!EQt&VZqtFPhs(HlB9Z71~NyTH#s0&X8xynueoPkJd)->*Vxf4ByWzT_Am z_1Ata#Cq>fHf>Kq*An<{qBq_KCmRt)9RpT;-e>-OvE&qmr65!BE6LPP8%?Mh^8g z46Ri2O!{$TwSyF1+J~RH{__U*R9_ap=H_+ZY_$-S!L@y7F`b)i)1r$JN!gsd#hV+g zj+ncZM*F6HNcE@yi)XncschMG`zXzhiEk@<_@B=2np*G@$+gkMF4Y?Qd{AYy#6VsX zW$ml#DyDSqdHb-ZDx^T!lUjYsGp7lEA4#3`v^?v%^W<$L(t(z{`sCZ)to+#V;a%zz47GSS6~fAU18U$5Ao@zzmM-f_UV4* zWN0)RVYEC#xiE*9Uw;jCUE>!Xc(AihRhFnHr+ccGlq^v}zT}Hd6bHmt*bJf3p7peT zJEdrYJppUEdlCB+8b;R=H~)R3S#feS1`)5mu^KWThPJgHio7jHwKOJqFFrj*(L2Sw zMb?Y3_u(9KBj?9WhY#c2XYattZDZ^|eHx1k3z(Z5w#?Tb$5YH0Ve1@T(|gl-R9>Os z$my{%V_weV^qQ^bW2KTsi_*4WUx~@}1S{&+X+4?8ava)Q#>A}K{AtKio*xr?6vbQ6 z$FQ5WRnj%U=uBhq-jk=W|K$6vohp763^&3W=4f-ZL}iY|O-YUGXz%&Wm-;eu`jsTV zVjx(Uqdcz*h^*TjtBVV`@n>&g`QwX_bHED}q`vl&C-%0yU- ziM`7#b0&@>Rzmgsg^^V$%C)RU#aj-c9b32J;k)m_+wZ=MZ$9@dzWjw>#NxsN-uvJ* zmKGN~PTl65(@Uad^aazt-VY=8)P3dhWzr1Xj=5q>n_b$ik=!FK?Kf`2+;6yeWavwH z{IA!hB|Cf58LC->%4PdwB})5NIDP2+=B(7ld(2ivRPe-#qgnpP~4;btf~*4O%rKSY;YuQ;#siI*{M~5#B8PgP#s`j|UzW#Y-dEWD!3Q|CZ!gvcJoni5$Za_Dt>^L4 zS6{~4yLVyb*naHZv7@uj<>f`3+rAB3&YqvhT}@VP?ToR0tAZXXYB#xa4#gVuxw_1s zPd052r1huP)3kMMDd!HaK6SU+2f*{?QXoDH-zZg|l{|b)!AmL)yY#N$cTKm8pbs{=llL_BBeR-r3MW0ODIQ_v=g)WW8|(R}m(qH0gYmh|6$E;oA5v4%a} zJWZgbt@yO9!t_H<;IhC*_10KH`Uzr&c6`EIjgi?d9g&4W{M#-gD0GZ`YYJzW55oR? z9s5(id5J9t+pM1X--6`fS!-oitK&J$*BIdF!_2dK`g;*5()<%VXXVaVr3fCR?^9S=zY5&eI>_@o#?@C2BnL z=p$Gim}7am`<7d=HXh^R<;#Q0pEz^~qqQ~M`s!Do&_E%hS^du?dBG?ET!V<=`GMlrW2Liv0#T?p%z&T?Ci z4W;c`Ox)k5jr+rB&(57#`Hg$<#_3bo@y>A^J#+{kd~^mk9Xgz8Zzu+jw4Kidx-=&m z$mJe6Idge*bl>`S&ar*Y&3(vY;wD1y=aGGUk=UZybJ|89*=1hFA|9V8hV=QKYC^wF zAvjG>q?V|u3*_>0FfeZUlx=JJMVnMU#gh6JD(Sf*SBa^1oEU#`*3U1~S}dzts3+sZ zsL$uFynRnk-Og`XwlDAM@5UOcR$tNs*~V>8n~`2Oy{#r3(ds{)b3Cs6wXueeoUg1| zNfp%XvL{|ssoZrvgQo^?IOb z^C4e8#?!e>OJBisNjDg96YCh6HVz+uR zMY-}Vg2?aHt%mH{C6JDa%wVnIH{fp$X1Z20B|;5+ZzKD5umEJZlp1*)U|ARjP4(k^e?z{bt z&N_@kECQ(}>#nuYwyi6<+ps8G%&6yX-^Iu{-Fz*?F@ei+e9*F*1%mjbIcn~{pBd}* zycU<#^tUI)Dcowb9g*`7-tet)lJgP%w~sigi>{ z44?FFXHGh2^IBBtBZS4j8?;phh_$3XraEOQY|r!;XPy>M0=yED+G)y9W#IY4--+i# z>%6W+cK`h*-aVl0M(8l&3KWy?V`;6ikw4uGuNp~7$C=j?SZ9hK_-k)DoAWkotyZE_ zX)M65idx%CU-U}-sa=a@B*8HyM{&MkvzU#b&B8XGhQ@@ZY(75c$@?(x#l3$^pM?4` zOyjkVsUB}3V+!b=GAWVHLq4&(pmKV!fUcR1>3Mbu0CkOro_!AA`ut}HeJ$%3{-^&K z7oPeqUjFa?2rvKeCEWJUeh0tw*k?NHytjWp>bk(EzxOOjWPPUWbCf=dAClE}_SxiQNnxI=jMmCx53Lb>1{ zr6k&l9T%VOPAf_O$PNtohfR^HuX>2XL!&Zi8n9b8=6sUHg!krjgXS(lD9auWFNsL4isi| zRc2dX#@)^qxu#o()PptA#aeuUVq9VS2OpzEh5Md+9`#5+DR=zH5xje_`*Y7iTUS=F zZDj>-96ye~{_c0MWqG;t#O=#Vi#UGt1^@+aef6hpKi4n^$$P{@H=C!VXFh9C%~-3J zH=V7=w#deN=gmhuf1l`D=xd`r$Pj*4yO(*H@{&Yj5%G!3<>Gr>W@v<)p8643BtsOx z`}xg=+@d^*JxZPUA@<}pUJH#eqQ$=`>rd(XFTI45r%z$qmMz%2WeX1N-G@Va_hrj> zMSYw7=IeGpXx5BWuXOjL>waGx*6h3arFplFss6Xe#0}|dzWRkBepyIyo_|q@w>N29 zU6?q%XVJA{7{-hq!;~ltCa5t^c-hU|`t1rizq8>mN19;tt>iaXD!vjt+#pH$o|Jws zBppG1uomG}#citN(zKsuyOI8y{(B6_*t?|mqOab_FO^F+hR7-11@x>_ZF$t{kw=?l zQ%&nw%T>FY5aBONo*&x}KLV9AV!Fy$eC%zLeHj0%R3KUl;k*mr8N|68KNjQY|7o5Gd1@vAq|e%aRm(pcytwC|tQ z1moef2l-y67(33wqj-~M5$U{3u`lZ}`ki9v$gkR-$%Flvy5iEX3^ZSE_6*kZ+{pYp z&0G4)MER4Awt7uujaFH5t1{lx>k$?{0~24OYisOR^^9r&SjGIrHuPwR`Ae(V^}&Z& zo1eqS+qQM;po^Y+$z@;tAxU#&6xr=M94a*S;(m&Y*sO!v(gPWeP zF4P+eA2~NK%0sj)uPb=Z!1wh3*SAu#(Kv1+DE4*@%`(%5dWz|I=5qM!i~3N4mYZf% z>X4}3FAGQKh<_R_{miiv^IY`xee{XYT@;~g#--O+t5pCs=88EKg}$iB^~6uu>-?`| z68ePCZdO!pt=QK31)qcGse1-V{Lb^UF@?2k@tk_eT_1dehrjnMzVYPe`^7tb0o8x; z$0+~BZv*wPxyae#bR@oe7)>`fhPIx@?=<$?*v`?I^D_J8Y<~7EJgmI|5;YicBG5=Z zg_crEM<)Gk`=wYz`>4;}#O6{2G@8^^Jj0sOxnk#a(-wbIQ{}ehVn3Dp&8S8BSx;s2 zv2On9sCYSL^a|3YJ}<75lGdlD$RxeSaz?WHwF)b5$|u*i!t}0kR~hTrK1cGUu_6A# zygj%{tw?cB^A~?zjWag!;5yD_QpWbLHh)JbO77{V#_!|tjtqZ@AOat@n?d%niU#db>#V?K1D`H&Kl-cJZ@9Tx_tfmaE7!!eY;ni zY|LfKVe=@yCY3yBO(v_GpncepI6#d!( z`;wtFHyUBIIFE51`{Rh}vcPz5gkr6p$Xbzu=R3sO#0xv=YU^YnHnCgx9CcUF}aJf6ksFC}NXZ zcBPSAMdr?W15n!6h+FQu=d}^@X=P~%hp>XxfB9|vY<>=(`~3%ij!oMamzVMCop<8a zS6`dDt&N_ev-_g_VhP{(0n`I=UhWa!a1BXjw->xr-ERQ)07L2ilH@dpzPPkhb=m@4JqqCQsb& zRI3sEwD;{|hnI=dTq`G!dvnc>A*Z30yYG7`Un{U%OunD<^)@%L z+wLM7YV#}0OPD{uhTCpDh+A(sIBPl@`dO9>qSWb{_ z)ozgG?A>ov)%;U&raz0Qzz7w_Mknc9Vnk82d@L?5%_ipNs{Im}=N;wAwQIv~3J0}m z`&YO6)0e_Uo)U77O5OhUuSHuK**AIYDSwY?t6uaPahE^!I00sC^7uE}upQ%TnAu?M zjK`V(-{!f6E2Ze!X0!IpCVA~%Hgd}Y9DWr~)+O|uAGQLX|FP~^yJ8}iX?xvBFv6*k#`|%s=b8FzJEm42pewnIB3+LVY2K z_WU`_&&^?ZaVcB=^;>SixESG_`gm_1q-8(OXv@i)>Op^Vimfep z(v-ov?HoAKT2lk-Q3-5c0_H~m3cU2%PjTa+!`K>p_Ug*Q0*>EsB)e%l4PQXqzrvNv zkN$cof(gxa3!tL~GA$SJ5dg_=Hd(;Q8qhGRL6)~Y`$eJdKE-9z&(iwSW1D+?jo(#L zJxF@WZ~Qfj-KwvOxYmCr6z1?(#IzvDNsvCAcCN& zUeJy!gGN5}%In=Pa*4OI_iI-&%|oP*h2g_K)RR11vc2ReqHppsFw&W#ve>>wdeI(o z`mJ15UfUygh zF4{JHOEp~u7z|izwct+qMmYsrR$6wb+}E1oXw;p}c161g6!Xl^)sa?Zbl7LW>Dt<+ zje%0u#sNNATOZlV`@iDd^&vL*MIP?RmKdG6+dupmH^2TfpunILw|DQ@i6i?D;GOs1 z$K};4z2$-CWxKa-z7aRP@ixRW*QlwN_PjLx6sq(N5W8lNr}K-mW7Z*iGy9NwvuLxh zW-d3}EZV$&T>lg!qRr#o*Frb09ZE4KjCu88?%8A++V`5~tmnW8L$T~e&4oPvvL2qZ zF`rfBG83C64VhnGeDraA<$wM4lj9W_1|dj>WrySV2ruUreNjXY-F?Yc?m^6yD2+8MLK;9 z3DXz;@>FwgG-(r%Z*|EWQu*phj-nhRJ!(e7Ctf#WCuQxUwfuN6PyZp`wC{Q%W4cM* z>%?b)>{abZTI8w!&+`;iLUL2hpE>8PTYFXumv4dTY(%Rsi;H#b0xdu92~wZnPh;oa ziG+pgkGH)vw)puWJUupM`)lsVNon#5rud!Q268W(mEZQAZG(Mh6i3y^cE?aV=WGm1 zDTmdWzkT$a{^qu&9{Ucym$nr}-u037R6}yX6kQIhw~^G}B1_3*Ykw7w%I`O z+`|vy}?OnjN!A=WC@Nw2y}MXT7*;vv7Kj zxAzhGx>Cmf&9QB^^+n4gf6r1by6C+K6Q>zNoU_H5faMp*VxLb}SgY2sR;{A(W4rt8rnzFXI{O46=NH(c*th`r{%D)J);N@Wo}TjM-^K9F)O%J?{xAQq`TOwp zfwK6~&XI21i4eE-#8D={I@x$MGz5ZDHr|i<9$Cx_Tlp_ zwpfeABK+#-YgAu(SBU4fmon17)uq;FgqQY#`^d8!kga1pN1MMS1M2o`)=#8QpcJcf zZP{Wh8q6Vw6cJgy`zPn!dX1i%+cDGs_;{Dtqu6X#H&okiAL)2|WXEzcU;TeZTGB(& zft6VFEND25pOU-fkcdV8Uaug%=s2XWee-LxBcntAEw(rhuwN7t4X6(6_s2a#_OZlf z!dk-4An{Mp`Q5xqB7OC%Lvj+g$USP;&y-Z#Y6T7FamzLJB@NGVvZ9vD9pFZYN3tYY zWXzh?xhmly{6)is8Qp^BYuTv4-PW%ReASDr0RIYzyp*ddlB^JzReP({2} zg%KWp=2<-d;Qjbu&+c9wjz%Lqbl<(0TUx-m3+H>w13+CAsLE06C+bONSz`{mZmY3N z`lSA}=^^V($j$*f8vx9EsVeE+VWMT&?=lqL_CIEG@w>cljRQ!eSt zUrQ6*SdLsG9Jia^Pi43=zJRwrdJ$XZw_%6dwB6U=t^mZKnx&H~g}J)1WK$hLlPGq@ zxunXbQ&$!jaN_WxVeRf-!NPy=FmAu;W|T|wxOn+8#?`pD9>W0(S@>GmVjB?Berz1o z$!Mipoqb4D>1?VZVZd%8RW3DMlM;UOR&%GM(lwNiYNIfJ+uC|9hAjGt9~-hc(dFb+ zITxfI`82M!B*9Ua>FYKPXwG1%67F@TAKjZyrMzt$PFk<2s!e}+@|3eW&o@n<(szkH zP>JB6hZ%B>XOPTJoq3#!sccd+*MiP7Jz-1#)3@@%6-htTxwD&+cb% zG@m_B`&&7%e!Xq71!{C-`_k4m6^>(c8l8%ul$F-<>59$6B1S&XNZU}b3-DHrSk49< z@Po!~m|Bn?3%X+a5|!rbR)+34xY+>N%edLZJ@$~apRCS#Y}3eQH)GpqUlTtIpY_Eh zxhmy!PHSWY#qy=c;^E}wp)^{@d7qu9>UGm)=#8Rljh(yN zpJg6hzgQWV-ScdW1W_)$*%ag7{&H!(G;7@qtUQ#wZAN@!d=}5-J}Kf%C2pUyzL+@M zzB-oh>AUa7{h#{OCblqrPc|}6N0~>Qjd0B6SN!;-rL8ZaJru$G@Q3 zEJqHvtNaq3_|Zt=?)%(XA18S^rOcQfwn)qRO(#9!L$-7)&afE-+FpD4EXJ}AZsZhD zX+O1s3i_h5#bBjtqaa<&ozn5ET`L|3r!w<*R`jZ3G;aLcBXrf7`i`!=BlUG$YJIW8`(A&~qA0IXfTN4IN1qGKDo0#? z`rL6SF6~F}{rrZs)zywgwaqKIYK5t81)W8)pIed0CbL>RXj4-kwd!{S^&GpVod#)E z7?~M~Ny%vY!w|ab*fBhQ-vfiob3~Ob6@Z?5S4{q=CxsVIUiEDL#h(-tvw!pXcI`^! zv#&1A%r=X!HfE06n*|#yxBlAweVj$Fn}g3&p2PiFzyIsw6vx&6Hiz!Q9eh`(5P%TYk%YUAK-}xAHut*Phn|c0k_|DbEXaZpU7^Da7mZcAF{9S*Ydfk!y~R=Ac(vrw&XS4ylN8w@RL zJf-2lI*>lH9qM=A>UN%&)NfDLI^`K1uaPvELQfNKp2(#+Ld08buE8^nl;vam}#OqT^*|J0ooZycs?%H}tG zTZHKI0-x7$2B6-jhQ4H7L)#PY#eLGqkiKMScQ_VgA=Vq!?f)t)Uc8LaxPMQe(DLFU zmYzLRi~eg6AH72oHY$2PkWP`Ys2G>3U<){w-g~vN4qXPE9(D;`iW9 z+nWLYt_5*FqJ@c#ZEIG#+PaR~^Qm+{dDpvfvIze?_>RV|3%Eu+eEU(klxGx9(su9I z`v~f~!t(sq@P08+-{KazB^%T<)b;gmHsVx6TCxC-lPWI5`t<4Og_RY&de@zUr5KGy zxZ%J7ltqDu@4jb{)GR$GEoqNzPtuUqHy_pyo@1UC9J9tfyp}qJxyFyL_?qfP0}Z#K z$yY)3ko?U-Naf~h{J>ZH#j;0`I8MLGCSpPs%g>6Wx1i5Dh1)udglvLuZ}Np{}1`3IJg z+;Eywm~wrT_CJMs9?ry&9c>NEU%2w9bOSd1f17&qJd`WBG@6rMYj2wV@d&0~A-3zd zr`(EM@ripr;z#pT$3yr=IkPsA-ijy;RF zpu7|swUnElqa1l={%w6_I+Fa0_2YdaOWD1g5K|Wbx8-KbR5-S81kJ|Jk6a3f6^!NE zQTz8%UH{*XJ8xLhIL{wtYJTftpZvdAg*@z*((<`Q_L${l*=qYoXK}}?KgM`8!s)$x zIyJIy*KXW*`yKf951#AQp3r!1gj4(XVbA-gQPvge_S27m_zYQK;vAG0i<%O0x{me3 z>eJNQ32(l?o^0;#5^nCo#(m}2*X~BqM(KJ8pXsFbrH4woUfo3X{kYlRX?8LMN9M43 zcUwxYfAB;6?1SgAZ|jY?|KO8h8Ll5;0gFhY9F*glM<#JUhx&itf1A-nJ|ADNrgf7-?{%EwCYztU9^n<+BR zNHHnv$KjEg3;N{_+fTa=Q@HE;pGcBon^aP`5?*Ji4h#CUrfrkQfyw4e)+Q_t ziEJ_Do5}`=jrucFZU4HxH0#x$V9t*q)4qHC+wrxy(Dp_*9H%cHT0KOXvB=0H5?w6- zmEsfT^%`3;KNhljiX)}mW4x*!Bt?5XZ*snkc}4TMqO}+qd$#7fwX}+~z~yXTxWDP# z6rD`Y+}j<1wF0u;)o%BL4bfM`d%8`Gn@PERNj1m$oA(Od_UyR&n4uP{o4s{x#8!kOe{q86U~_#8d3ng5 zHD@<%h*VAOyI*`6qpHF?M-KPuD#*1uvqoX$G0N6g%%fo{r|8rIKlj4*wjS=yPU zZkJEWM~uRilk0K)&GvgK2F_(~9K&oxlIx5I(~MT4lr58!f$Nn34zBFOd^y+ptVm*w zV73?WthL`h;aZlT#R@(aMWa&_ulT;bZvBwQVoV+{$mxuIqt{J0A3lsN%ggxa>67sp*CXWtdqawm;F5q+YF&0-kawm zXa3Q=Otbfjc8IaMlvqR&98w2azq${MxeYe~_)xK=b0k zvDbcvYEclrap#M#VD8Fz;wx0< zVj`2irlE1XF#6*jH&;u@3lyq9pzhwZy&e$vcY!vmf74IM>s`;*Y=%${Y%|A{TV4+~ zsmR}pTk7XAq@1QqaXtB+)6!l09&O8Xkxx6lOx%ihmOlNP&KmQ;QvMyvt#E())F3+B zb_iX*as?l}cN&*oIf1XNeh2^L%l`liWr+{Zp2f=25*8O0O!?7xjO}O7(#Y9V)RPSs za)mYE%Wq`(O?mrZX@jDbNy3EuzuebaQQEHQRTJ!_PSi6^aky3H6wS`KZ)soIN)U`! zZN@>iW7ptQ(mTC z4kz@fyy?vIGq3>KltKEe(7J#mBYMZS>gBWvcC1SoJ8v&3FpJ3oXs(&tv~8h&oR&(< zIttc4cqxU;Y9ebNSaX7_>6!1Z@T?6aiu$ah!}f1=?e*sY8@Fu#_Fmk|lDF}6oV~2m z#-+#uNB!!K>k1b<=u=CKyie3t6pr>^&`K{Z`&i?Dd1& zj^V=USzNgCG1O~C{;|1};~Om?a%{8NK=(Kd8PPbN*X}+`#}e7BTuO{4zE)#*jaTow z1MeOG?UFOc#(o+2LKL6|ewCA3;q*N!Yhg3Uu?I7Z-Xf}FboNc`@^7(jeADHI+PM0jH zT-KLG^DMGwu4QesGIEHQ$@7xy94C}t>fLp{ggrHLN`1A*yYYy{>oZpNKAm1I+BjL_ z9_MjxHy>UTNcr2gEGA|@;n!;z*{ToG66t)kXH~18k`oHmUjwpYD0U*VOv+S~P2vle zuHd#G{}iL~7(c)9Xs0%omzJ>fh1+oDl{H+rbZL+V-#f4$^Q)`4?UkRjI+?>5YvdcO z7cbf#`gC8vD8)sH@i-LwWx=UHRc<)-wi$`<3T4t*^>u zJn?GTFd6uMHx^E>b6oU1EOO$1%CMb789xNG_Ou|ndVs>A!EPo zdl!?&h<-fJaU$xG<{p6fs<_2z>FB{j*s{EgV@Hl)ey;zV!xFsJCe29FImX$^u=&@O zm)LT%=LJ#z>BqXc^uoGX%-#>jSe;idsD{JGXd_`MIaI#YjmuL^3~*q(D-n zej-K*wgk&m_tf+GR(x0Imd}6l{)dSp2bAco-JwD6dDcLtkEucAN&d1c4Kh5vcmS-+l}$o((G9BVSBO(TwjTZ<+VI)KF>XE z?ls%Ao0nS4NpJN_x4cV)F;gCQcm!ylxG_cdhQ_^^*U&f^=T7UT^>fVkekeY-cs!SX zd0gIHi^|yCP|I_MSdrZ+=}RVJ6%s>P#u}1eG=JHrzA}e&Zpm8F7$fXD{UMJ1^k*pQ z8mIQ|?bXe$PaVYvTY;y3^h1=R5)a(be~4^VmU!pLVT{(sIQG-mF?VsTjc4jVn&ZZ_ z7dA(i>-vpsDaDz&W>8@UI(vfjZ!gW77XRHMFK>UZb8aS=Y{opM(~|{EeeK$EoLI!k zy{*$H+q8DUz%zxOv18Wc+tx@y_Oy}=l`~(49k5So?BB!a@0+k?%c&HOyhHO>j85PLpk$BIV)HFe@&?a?_B7 zUm9out3wUG`u`ko{lW~VTH0%Evqk~?*1iI=I;q*WKob!MdJAJ1;^=P#Z36l^T}h#p zv%U?eR~1_7TaRhd?dOe$ikjp$5_r&;*M;{s7BcdtZ7p4xI{q(P%Inac++^*U-*UB( zO5scac~D_>&ohbNsn&mek_S^?uFD2MYiBl9?D94FzFEC$SsrEH=3q(sQo`%m+Mfau z@wZJa<;qD|>Su(LpFbAd*!H6`-Y4YJXs>_Yx17JSUefz->xWVqEjWze9KZi;OT=Eg zBo0G!DepD)WdvPhkP=o)o_{)CYVREL0Jg#|xdenLcZMxGe)@rS<<1`y2Y8$mT-gYs z^3_2ZE+_5!`du^~NM0Xpc3ZOn;^way6muO=S&rOtmo37V;&wR;DLwN0TNxlWp&D~b^p(CBrzYUmqBl|erZ2h~S+hHg-x;tIX z*>o`k%ldmhx^T2$0FypZNufI#a@tGr}=42cZ`GrQ0iKQR*h14kL@mJFAe70;?F5gW)A1}LHBYpXvDNaXUyCC}Uw+{}ou}MdyrJ46trX35=`#0mUCz$^ zBSDV>^h8(TA*WsWQPNpdwA@vqbS{W|FkGyq@zuDm7K8b(nla|L_K-tccCEqsQI)d` zwepNi^H{43_J@AswU$xa=9A>LzFJF)hoi{hWfxwlb+P?vY5spd`|N0WoWk?7F#oT- zY`?ts^(!4|-L4q!;+kj&G~K?KC6fh~+I`%lolnAEpRTexpUGI&)+bj$dQd z$H8ganj474Q~>5sqr%epOIW%%Y!mivkKBU`JLXVT!>r))(jv}n+uCB<#`f)rgGm0C zRa>ux8rHk0Wk>NE=AIp$)EmTp0Lj%Zx>_@1vuN6x)ZgFS9LlvaWWINoS??Ik?i>5A z+cJ@dpMDLnPhb7_)9k#VD0A>Rh>x*+&Bk+{-*U}spg@gVx8HY~G5F0P{f(^s0m zANxG86S(2P!A?25*FYi?txp?)uPvoHZJY(#JlMy1%PU0^7HKek$kUK)*OufMYB@x) z)&D29<&mZS>(K+xdy%lrNa{0G{VRuJxqsHSI0N_3mi+AIK7ljfk_!L;AOJ~3K~y-{ zHms&}f^N^ywsxsLv z#0YpdHRTzfj(9!MpJb^bnQZRX3|6mOA8&I#){gc&eNCQEmF6$7THQw*nf<2j$jf<~ zu_K}uoZBpIp8>;c^U5=+@Fj;0POnULu@^B4t%b-JP(w<=m7b#o@P)WB%eQNhH3q!noZ(6=4Ly z>2mmuP2001)1Od7(@n_D(et$9w=oVfPK-Qlq{H$7A-$hl=*a1Z(>Pl; ztrLT?uKr01HLk}%U85{Y6oucUDBNwp^I?n=fOOf+!)!12=7f!yD?2Bk%jQLoviY@_ zUU(PvzxW2QcT0QeFTVXvJn_IoI5^NT$4euaxO+*X`Z##&@BqtRpI-mb;)uNmND|M% zHMenFPvz0a9`;S@1{5fyYWQ=o;nH@4<$B0MG3}#;wtQW~x{jYLPxFb|`k#WdrkDX6iq)ygaz z$Qj5gOptm7kk~@>4!6i+;hP<2or#hd+WF)Ai$rdl7Wux*ed!JRf9B{(%4>3(LJ;LB z+EJT}lGa9V$~W@bZ0|ZR^D)lGu>QVD4Sm-=vIXA;d(EhfUzG4;T$4UoL-hm{+O`<@ zOS}B(C@V`Uxt$++MaRnirF?5dwxIG^{^A`x_vT(cmtaonnLP*9g1)1wpPCcz$LYRu z7X9+}l2lV_wR+zI>OA0zd=dZVIgrlbYeVbFic&rG=ilDHalI52$IA+~U8&=BuMkk| zNW8dw4vv3|H8rzV&Z!m)voUl8U1(+d9F4~qj|P0!^WAeO|C_%=^*??YYinz$>l#JZ z!xN!Vfug8U)VxSGZoOQA2JVg_UPUq#&3o)DlWQDn?6w$Lwi=SZenP`&_*jQ6doU}-QP9R*Kg)Ot*~VtJMA5gumS&G}-mh6&O=Y+hw$Gv7jAvgC$MM)i*e67l^jAJB6j!LW75({BRxu2I<)t(C$iYxV;tWu zmlb{`VDPZWQkZN=H^N(Q<8ff>S?##O{jG>8ve(oOBDCnSgzCnRx|P6kRlYVG<^0K_ ziP%HDeu>8a{kZvrEoR8tht!zdm`4%8#MgL@eE^& zjl4tJX0)zVg|(YDs(@c?6KTKXN{UqMXs3Bbsx9mD*uTYV#`5(%pR4%UXRW}Nu(5;x zwY3?`s$}cKw%s;=Ey>Q$H0GwBDblDA-?M%|y^GZ=z*b{@l+Q!_7Hm6%RK~{Abu)sl zp)@6BBTfN5LAAojaNYg>X&lWPFoukWMADxt{H{<_vrea#N;ETHtkhi#t>XyP37& zs2g~#PmT3p^GrK-GOm?F!ghSD7fL;N+LrQ!sllhRrxvN1v#qITK{xkA3O$wv6TQ?X z_mdIgTu(iZwO?t;XUp8%g7oe;1&jVh7(0G3*>kzAr?1)`hz(R2VGKE4+m1jwHX0-J zRo|kOST(B$4yZpXsm*lrbMv_U(A>_FKcTIP&&!?0@$?EL^;TZ6BR&w~&ro zUi=07rX^iLknh4Z8|0;rK2MSnP%p-qBA;b+QCu#LAy<>GW$XR;JdWFu*0^kp;6Z;y zs2@q|HgnU`?7ww}^DD-ww-OYr(gN~L=rKxc`S?6`oH>ItJG!4O0nOK+?>%r7fBlu` z@y7kfapS>5onM1yl36YXi)jz|#C(ob6{3SfSx0Hc1uB zMU0^f7F~5yVmbRjx4o7Ix-|LB0q}@_om|TS_eid9zWM*+%%u*6r3rhEr0)ttH;o=VjPif`$EKOzdh&~y8?a$W$b%;Zi56(_ z##2sq6$&YoS}&#JHKc|FI|d{Eai%8i3|MT)q>oy z@~ICH>rrdWrLFbE8X`{u>Yu>4G)Th{izpBPMR^yceaJerovuuaq($*j>Gu(zW2}Z`}hB+_@lKNzx6v`!k(QwJL>?zw?6k-Jp7$!vE|G; z+DKhbyo1DE9|fALqM^_6kUteT>S|4?1O1U~Yj5{5r zF{)1P@%?W5PqVJB*cVCDe>K7)noBblvbe|QV0~KidAN5H0i?968j zjEQ~T!lP;N3`b$M6~>dwL2X3Qfz-}XY!xw1jKH+Me&5_RAkdVG&^M zbjba(|7!a&H`Rc}`gvYlpUG-ex2&qhs#Xh@gJ$v30UQwqiztmd{(d?y)aGqenT7wf zv~m1$aWo%aXDiF=Vd>oH&K6St=;xB2GhMg8n>uT? zI)go@PWNuw27rCLcjLs4?Repb&tun{J9{^6UszeeiNl9+^XqR+WY!b68n0?s=f|Xb9dJYD2m9)>nTB&-KkCZ@0O7{c=Pcy2{4)XVcfL zdd}-EpV4p}kK~B255Wq)#V+daFR!QDm0BD3V{8{^oSfy_Oqc7`K^rh-Ke%)TTjp1= zIPzGJ*SI+*iq_?-{pzTCPMdAZ2Jhw<=Q`|f?06PIAG#@@7o_79&zWhWm8a$XJMk<3 z`k&%2zx^%z?8-+taQ-|_oO&P2i;LM!+p*niZZf3b!+j|8*V@DDb+s>?ExyXhpXTQB zSMAEMoG|6P^Q_dLPV1ljJjx-~biPKv?cZ9r%KVN{e43|QdA;<_6?t(?ull&2@3~qQ z?_Tis7W_P^=L z#-6+ta9_D~$vCBCY5tA)iZ(HkL^;VigPeja{<@qzljm`(jV?sb`t(P+s_x*l1G=sf z)uvB+0(I4HI@ZnFRnmXWP&o?~8?4&Vkbdx&P-R>^e{XfEv`uy|`xf*x=;oP`JQK~^ zVCDMRv^&BW^H^)|pWm{AwS~D*o*D(Vp8Xi3@!0KqVboJ&gbJg{M(|53OL+U(QT+U- zqoJ)Z9en2`ZhQ47SUG#t_6#}@_8AibA)|KaGaFIpfU!_n(PddcU-Mvt-1o# z`ZiX);9xnV>7cqR=HcC<1U%+>Edp3X76ug4$u%ml``}*u%4eQH0bqV^uJfeEkGE~Z zcc1tS9{u*y;5Sk=OG+N<+nHA&vVFCGeuGl)$hlX#gruDKTG?)Z)Ftp-4+#yCT|acx>_UO> zm(`NAF*4R&!|PHxiVl5?_L@!nJ*cgN{>dztGOPpP8GkRKG~Boypa|O1>ro$dR2iB| zpZ&?;){|A{m+-SamU&vWzDi%Aky%+nH+z>x29`});nxMCIF*8g_-)UW`eUAtu^UNg z%v&F~NYeH4PeHMchzGyT-}_$cY0FzkF82YM&ZsxL|^D6+XVT3ud z8`<96&c+%j*ZRLt0suu>Vt(r~aB&r@t81w0VftK~o5K$uc>wqP@CEEVb*9yUZf4P! ziF8?jeW{Hsy4WdmOLXe?L#lq@!vGTv?r*l!;(p5kn-FsmQU z6~&q9*mue4vvF+^EqB|Oh;yCvGtJ6lbZ5DDc_!v%(UeCPnnUOKH@TC()NavDm-mWo z-)3GaYgb=Ax7gcweQIs4%Seq|iQBRB%lj&|H~WIHMVS#cwtdq(NVJk-X2n(!RtC_b zBqo)_U$dJX{Cx6w+mE^T0GyqR4j8Yg?_eycmS|tz_Ho!^{S1^3oyOR=N@(rC}Og>S09Fnp7iBrwW@;F_`LP_@nl5Bqa$_L;#s@auUhKLC^nnc zhgW0C*Ta+Jl#huqPe#R-heqsl#>xLTqbM7<)i!nOkd)wh@~~BHUQf?zY-tQxJLZ?{ zhvhH__v}Ua>rY_3Z2{+=eiQh${yM7*^LY2rK^!>oE}C<``3qCBiCd)s3X)D=NS2i( z>w)b$foR>2Qj|NSqXW9{Y4%xgEiiY~W=;AUPD8Lo++J5JT{;<_w++{AUyp6J;E_PT zeb|gK%DG}&V{cr$vKvQf9v8)3zOQAvvQ2xwXf8(T{7v&SzW2TNzK;j@+=ati_8UF< zms#W$I`w+8S}h)>`K*p}@iZ6IjdD!g+4L~t{LtrMQ7*>ZtD?lErKR4(B>@ShWIfbm)SOatLhuMjflV9$ZyLl zuSk|zC^ttH*~N2|bLlh>md(?)te%uB?f925xF-=Z@Of%;-QrMh>$R&JlSn9XA?O|J zEb>)+pD`r+<{EZ8Z9&hjn*Zc!mVFvw^$nxT)L*9OGp86Y_dLRmw4Tc?o=7=08)F!kKo+po#^sJ)Z$*Ad}JAiD+W(3LTQTkL(>R8+IbHVpYV~ag$y4fZ< zqK(>ooj1a#^FjaRS>P>O<4uJzMiYCG4b+usqb^HaS+tufYXA#ZRxvkTYqyS9D6odP z$s8!roF6@c9@8Vw+W0w=wpF4zSzBHn5IL?a&7&xQSMRwC@9*CijAuiSf9EMIU$}@0 z1xBkCMr)}Jk1)pS;yl*M0le=|IWMUkgJJKcPmO@fWb zHPhg8)tp}g;nCyLoNLExBZc8(d+7b5l6b5XSF(4Pa;gmNDu%81_f^--icRe}KIw-lvw;kI0jC znGccXtRDvSWgFGzRoS$?nN#X&!}G*Pw`NS^mq4uZQlpe)?%gK(bUn;Rznk}+Yi+TB_5|zU)Vadr(@`#Q{ zRzKU$ak<<>Bq6`sQfQ z?XZXPkXruI%rdnmeFZ>gM%8kR{*!YD%GEI*`_9vN?vaNE0b>BD{)fK>o_G@2wQErM zOUp~BMk8w7`w2{>(XAV@xXD{SRD-f{TlCcQo9&hPUL7m``$zqHn||KTGS@ev4S#Jm ztLVoFvykW5Eq`r(_vJ%Ac17_pnj>-COtZjuK7Ji9zyBk z(Rw^#?_XWAd5vC)A|ntZWwf=2WjgtK-I-~Qy!HF6oBxh@+SvgJLTT>l<3<0#kGb=| zxkvEauNV<{e9*;*`uJ?a28cYB7 zxp&%MX-)ed*|A8aef6Uit#DYsXr<<>-VWjqB3qke1j6Ve!kSi}5eBT?buGuAGf!>M zTT2{uSPE`8_11ZwX|~QWz}mT-W@*a@kSgY+QJj#JgGTU_I-rr}~gfKE-S$x9u^K5{X$l##S*NM)Es{dn4XMV#4$h zXgKAg^mMIyY-@eB+MaEz=(y*3H-Cw3$hcWvps|z_v2}}3W1;G=8;R|yeR^)3qQs^x zJsqo_l$6cVix)3r`k7X0j zSl8|LPyNm>=PGGl+3#}{Q)L>Za?{aJzZJ*yC{p`%(;WKecyF`eoIZxm^BkpfiRYx9 z*In~7&Cq?0T+`fz`JKuiAx$l-{kD?u{6})vwxRse-pE}=Gy1fzq~~A0&mt#F&An;9 z-64O=Yah*PZu&)7$wgF7mYFev|If;np5!d|Mi?jB7VYo|$>v)Sf7|bd=CBs(ub%8D zkq9TJ9J6n=cA|JqPK^fD(Ux_N$h9U@6`6G7w!Cy$Pb4Uy(L$d}Yt$4?gIcz>WGzPf zARDpkq(3DpSB}TAf~2>iZ;oDd%?MrXNWbV%x2LSPCv6wa2z<122cCN3ad^7-`4@1* z&))`Wi9RI?tYH;%?Z$UG-CHy1MvHQyciFaCO`hNKY443J-~H?taA|odY2VXRzo0VS z@#>Fp>?f~JHjx*tu13WePd)lL&g|UL%g@vM`}g6izx+ikU%ZH4{F}c8>Kacy_Q)VS z;_1Bu`|;j^{aC(m5l?>gYbfjHYrA!8Px`6==L2#4wJ6Z$Z@ePXlj(Zbl>hCo;WvKwAK>W0gZ-5X&6-875>5QL zf_Z30&KeVKO2o8ZztY_wO}P!-w7p*7w-Ie_=CtVU-}Ei#z+Zn`8&4h}<;%^wU@>el zC(?50Xd}PXZlc~; zZ)5w(U?nYMuXL60r4^`gGTh~fZTg&Rp;AFX6fLTf)RE`Z)H9@xb(KIMQRek@BPInQpp?UUye^Rj)6J(@0bNgs3p z-1;0@7|QWdKD_!oO+P7MG1m%2gGGulY z0k62+=0n|XV7tD$s?j)xvtN*3X&D|n-?DD{U|rRYk3EfAUooj#dv9uw6F*|*7EW@` z0x+@dy2g$VK0;CTkJkLQW&FzT|Cjj2v(MnE|NalK^rd@n_pd&dyl@wj!gF0dvcAB6 z3{XF(rSn-mo{f$+v(hYfvn_Bs>a*2rE$#5RG@YayISxZ)9G1uXtaxbeW5hSRB;EC+ z_?Y74?)yFu;cHR3G+!N-zuFhDqIhGu=dxujt9hEv@UA$v(PU#VXRZ+<)sNOsFVAE5 z-H&q@F5vR&6)Z0{E&Y}RG_jwB|vL!6e<}BaKpWb7;;B%ujztT~+7Vdv@A8OO@ zNPpgba`rUL&O}CiklWo(gc4xxSb4RN`cQ@ES>3koV}aFc?d0Q;u{NuxmPH#Vd|%>t z#(j?GmChT^6xo`*wM6_`n>?o#*Xc%W&CD4`+D!_8Joq1q%K^m@6|6?J?|$QVk@PLL zH9jv-?LM7t)?zGQ)-QXc=D)G&sg!4wEq%_n-EaT^AOJ~3K~&QR{`RxrUNhd;=?u{x z*b*`2BE0rx7@tV8X(&bU!)Tfog@2TP^|u{qHsz_gT8hbF+Aa()_PBt4mrOS-7qII^ z>alqS@O)Cc77HmMpFb9>-}C-y6h)0^AA7h*dkxKRUBcXryYW}w{Wku|mwv1F6t61_ z3wZX?hw;U~`YJ}N<96jo9#P9zLz~Ce%_Hv7WKD=q_~K|?Q?D#CW)1s@TF~7nCt@0I zgVWmUMrZ1M8Ed}Y`f$TE{T`MJq}QTyd5LGqS3S2hZ;(mK(;F*wD^Hh1w^rp8+RR}cH}d3qWr~g_X zE^|PSckuo^UGMB8)>l_~i;9}9bi7HDHyPSZ-y2I$eCs>da`rs6VkNT{!dL57e^-;H zY17Aazgj9B;mX)}?lUR0<@@B|3}6U(M8((B5m1R$a*qJ4KvTaTG$+=1S()FBeR&Mx zzXoeDL$k3sozIG|?A+CPWRZi~`q=beduBa{_N+|!1Ny8=Pfun)7V*ZUwtqoII4@@c7twpT^dY&zTnO#zviQBUE_(j$827O*b~SRm9lt zmAmi4Pwu=Ohu?k&cfR~;`}B2$sy${>thAntqT)v#8$L;V)Y@NVHr!83uittL)<$!< z?UkRjd3uQo-}>BV@$t6&9;P95X=w>x{pBy>vtR$#y7&OiAxU5Rr6=(V-}p90SH_cZ z<}X*-c~}7Lfl0caVCQo_-%B%vX(^vmZafWdVb|?yIZ5C8pUQN*)gJYY%jHE9L0l?1FAL7yPK8^2v=CMrw*H16rcMoo# z`!No^bpm=csN@HA`#;XDB?9WE^u{x(CTh}ovHnflS2xw{r<^>qJAxs!F^dz|i!S4Y zCn`6MlZ-)STFN>VU)tVFK`Vn=+ip~c6DR933RAvz0=5WR5D$(R#`yx?89n*NmX25K+3d*k!)lNe{``UF<3O?i zrsGjTPeRXmf~qzXpDKp-zve{z5qU=&BfDs{Fo$FR=m~sh=>r`9gFi%Z^8$`OaSza)!nHju zj8qk!s?p5wW(LUXA85g{&PuC4d&S0KF1OjVQSIdT_?%>8^3qvpSnJa+;cett#krgP zoz}6rcR%Ga#jaLtTfTNTen}Bou00=5BP^Vji}R>dK3i_Sn8V`SGUi7Mp$wL6ZXq7a zE(qGzY@Ac_K6dE1ah}K5ynWOpWq}%UUWAp;W>r4_ssYTcu3JO|M%#2)aI-=Aw8SqbPm2tJ$MRu@V{WYpAxC&hgUJvawJz&B&|7 z{Z;=E>movZQp0A<7LP^i9NJQxtEXr;KbGocRK`eO%)f@U8ny=C6GkkltSN>=wseCM z;@&p@%0o*=C|t_(W$fd}l(oy5qs@LBixaKJAFH-`qt4$5O=%sUk^0joEk2F$Y7`?= z+{p2vfX7EM??~n}it{=5nDExmg|l7CoJ=<>Fe>Dk;blolH-B&~JvpvQuCktDz9~;G zm5!hMos#rGtx9{R+X3_iZ`o*8(FSey@LuMoti6)Pe$6cWj7#H(zaB-Qt4Gu3%zfM< z8}c(f&8celH~Uu~tHr0BQHM zz>lukN2TZ&^sDjIvPsD5J0@@Qeysawh^=1h+%wH5{rz};Y(!f*{^_;;GAZwk@e}g2 zrJJ|U(bAkqd2n5x=T@&dyw+!ZIh)I4Vq~tTxkg-vk)5B9nsfWLEzJ@nALG0Oh^@@} zWYLl0xdOa}&r2O`-1caqXydNU9N8CeF5Iolp?)I%?QMqj80vPy=c zs7an5@aEhGYmGbks8?lVW?KT9mu~cwXnD5izYNTLRX)u}G2zwdQpdBL=wu9eIj?{s zRk5`=M%ql+KkH=M*UUM0$~JFqt}ur+l&J9iM;^kZ9Q!lzN%ugZGa#&h~|(b~d1o_YKcoZGe)bvgX2iV@XC zflEtEc=|Js;lh@cb@RHsxM*~tbFrDZe8>~86maelk@~+p!s7@Luk3CNb;)VV4W*65 z-|MF?d_HYmsSk+Wn!mc&M5GMBy5Zc-BY$3d;Wb9iH|w^hdLvKc_V}9uqpHIEmDNH0 z-m<)c-}$v)1HS$k{`&X+CB8lPm-x)T`zyHV@ZrvStMl`yN9E+OLOv`^eGWhWX=1QM z29G7|D2cY#wQ2iWgXw8#_%ed6(@(>>c1@J)U6)<@8|w5Lnr>0Yx0B~NyuO|O3|lQ| z=X()I_5eCpPUy`uuVKgHF6>;|-L}V$4pg__Qq-aGVi{j$t};eLHJ>{6bU~%2vb+?_ z0E78)O06FxDZm;ZL}xCd{RBn$?R4{_Uy3;Bs)T;Y z#0S&JR{Zh|_k}sf+8VZ$kjk50_cM&I7bFGTZ%!Avl$2z>rAu>c+cnj)(&fh1Lf7bi z{5u)}mB(Hy+`kd;v^RyhR=ZzOi?)n#@xIN@WVvTQ%j*|V;I3L7q=4JDk@5tUWKKH% z=|k2?ez~9D1g?o;bEPE6T~HaznZG2E&KvGEoNWGIUJw#ldFjC~5TyV-xA0=GSuUE2 zvtLLb=<*2Y-~5Y5SNIpiLANp0(B%f(KVJ0m;4!up{o7lOElk46o{YPl@kecIi-2D-n?tir(-tv<>9q%>Q;Gt{LbYB>1>Mbi?l=ITYvtM zi!s-Va@rZbaXTvOW3ts|!Y@ilq#7Z5Nk4}q(;w45nFHXdsl zy7#u*@%)$W!^MNcKjC)r@F6T-yo{}9&!Z-v-Lx&Am6G%4Ma%klUAA4Z?Q+h*K5S!h zwwSJkg{QfR(zIhYgnvxKS{iCiS5uEU{pIt*X>6z)Yel?cnY#4mV^@5Sa|IhS(pj!? zM|t=dXEAmx<6V32$DMocGxLvm@eULK@maFOjf&mV;pKEpA}M^# zly+>ZwzS%X%41QbwH%L6;cE2vBPTOoOYeE41NfJ=n*YX-hq9KV;2X(6D#Iz2Bl2yj ztXiArF8>?VjmF;2=o-GY5@RasM=_O2HB%eCHTezN%*J9B+kuX+vX-U_p!jQq1eoCgZrY zzn<(I=U%H6mbY#$$ZO3b)rz>(Ee@9XS5B^|C*sJUZQD&Ewgr}@Y$GFMVE=mJ2sQD` z@on0TK0ofYul?q_9_cnMSEeO69wL=~MTgJ-s}0hXtrUQMJe)tZt+5&AcbaLWWTTC8 z%H@DV;@EWYZu2M~y*CQAD<93hhSl>~mFL6b#nSq$T31Vym*iUdG(uKan)&8uLxXzt zfowBpN7!}hLp=7>)A-isKHJ+Pp)0Ga`29csQ~dkC@$X>U%9hTuRaxTezxV}w_Uqro z(#MyfuPZe9m-t~h^HTAy^@GJ^v_HA^qkXtoP+i2B*nw&T53UM zIq&9ZruQ{>(M@4o&i~dnE#_AFzj5*foL#+u`*+=po3`$Avg!8khC4rdWt>`&>;?4r zgC>ixez*B6XKnWWw6i*mIsLX7w-jYWeKf8roI3jv>fgE>*ty(W{^M=iFrF)0?Rxo( zR)ZSzx}&PbmOkBiKAV|OSgaXcxAQihn>M=Sa}L|WuzS((^m>}t@;vp~I?u=S`%kuv zZZ2k=*7edwmt9M1nz3-+?{oFohiZOXwmiiSb=$3GQGzMbmtie`uL;@0*<>G{OXEwL z{A=9$q!dkZdsVoJeB`dlNzXd}t*or=rmeBj>)hmYXyz5^l(m6LkDIX`xBVQGq|#&F zxGgpmZS&TVtfA{NAc=T`y`0J_r$t-6>C@*%tAZ@6_IiqPQoP48&Hg8w+nWvV^4-pbsZn+un?{8w)(#1=-`-PX#oJKvykMFtz$8R{&yJ4H@ z%EAIp96p2#D=QeSt>K;@yo93WXpUB2>Tg*ecCFy!o!jxV+mE3tOPtxcW3U{a-rK() zOSfIZffFb3(!KZK%#PW4MfCCZ^s9=qP+b&w{-Fo(sUN+B`3q|h%u%=FUtta2A6rUe zokxAcP+(shvt_OuN$Zzj*8IDVQjO=HQTJi=^uGKp@_Urdd5o^WXc_D48hmbR7i|gs zSDxrLoXUysEg-13$y)7qLrW}QxP%9u`yrlx@P5=CFG-Ke5_@;=26pep{BPffn;*R! zdwO2n6MFl`8&Ix}aq#VTX}-wI-uiM)*&=qq zKfz7gZ^5pmo$XzpxaoD9&c;g~wX3Hby|cAWdZ;Cd6n-nDwpzOu{h}T(^=UtKvmV^y z{~+42gyM;tfYaxJs*&TZ6YpT>_8r*1rF-Es?O|>75|>cPrv=b?8kVSVFyt2U0Tu0i zzlf0nZVuDY_;zjbkLP=rkBItZDZR%1_W;s@Nv>g+X><`v+DPXy0zN90*Q1rb3xM+( z2i~(qsga$tHMMO4Y0e9?^lB+89b1!tKkdI=TCjeu=?lwX$3)6o-KRE~%E|TZ(xQ%A z*PG-b0b7dKx|ccj+g>X6Us|hZ-!JuAkP-9Jvd!`6T1}L&y7Z@SVBl~09GA3a%h*1q zGlyf2)e@g<#`5L#$alpSMMCvqYE=caN6i)gfZF%dZ`w}#={H~ive?99CBCjQZIlME zM>+)T_)G0{rt_%*-V^X_Ym)kr(`+$WZqau%<+P^;=v2`23S`5rd_1?BfEkU_KBo{l z7;f1aVEf|zz10Z&8`aQ|{POQAMUgy>wZPEqAmwM{w9N=?#Lza1;5y*vJKMBETmFy} zTX0RK{(th`GscoEOAq@Z;-&YMSy@$?S(W8|byc;QHe-5bc2~39nOPE$At;F;L{Z|3 zl=wpeC{!af;FAte@2ixVZyUJf<>SOJ@1+juJ_jVHkn&E;KA&#w3nY~Km(1tu zi`!OL8|J5pNXhie8|5r*%bJ-taE)xa7R^BB60J~&EyI{*pl96Jqx8YzC(8E&d;vXW7c6CjbN^?GYtOWjA?O_rV#r-v?%eR@Gvur`E? zH*HI3Ii@L_Q!=ik#;rHo7tyJlxz>8Nts|PWf#UvjvIa@Nwr5t)ug3q}a&1U1Q#FV6 zaUR;jrrSXEyY`3Ab}w(IwH;(Ia2_v~>FF(?ah5K!(FtDuMd^0SmCFsT8}C#{F+bp8g2V&+49`HI(;?y z<*?tjvhV#ZuToxqds+u6ABrtxTPMj_H=owmUH!eaadTU2eRdk3Me~hiu^tC4qv^N* zl-@iYMn9Lqqqv^u&M6Uz02s^@M}{q(_}+zvk-z zk6|Fn_2a$ToO8#gI>Maj-H& zzR6E#10~&DE{DhmwqRv#a`v&68>sJGqqg5%x|Eb-PrKGZ#=hWZTfV!t$#cYpddrhL z{kPBN^TI^5oGt&j$r-qp9JpK-v>j!%&NG{Dy-9VYIID*?!cpLMS}xs=L!8CET{nhY zJ4@3vRNrl&wcpMIq{Sq+vdJ+E5##ar817H)$enRCOGY0*#je|Tnq|^$6H(S$($mzb z=mBv4=wZY)e=xJOG!C7=glMCV0Fl6DYD*{0mRnm*>UycBr|lWiYLPwBc=FQ$AVd2t zz9}d@M2yXzE?ho(5chZPC=80sgXMt%EH`6#x;8fv#SI)jcL5gI_=+s9g{7$!NO{PA8zj1jroxgJla07 znP(A5Egf-d}a&1aQtCMeqn?uV|AlpdE+k#U{=B332Kl0BB}Opb;g7rmHgjVk}_^v^qM zs3oFI&6G(@6E>`g;+9LFQKNy$`w#GNa(f{|4Ym&=`0K9%VTc<~9%8n43ilsBMo)Kl zZqRoAT=cig8k4O+6@$A~(D-Lnh~L^4z>F50Uv}hV3V;neU8*d@HMjFk@N)2tk>3dO z85#1KHjW|kYMPQkpWF&vKdUGFOpb)+5!O(&3aq3LeO7^_QLa%2F}qmuOD}hV;Vz6aKeG;r{C4JrgvxR?9*bpy>?^W9YqyLokH;*ZE6BFlUZ*B{sGifF z=QJlT5Nd3?99;5eYk*h#b5GsYyYQ(t*U8HxlfGehW1`;iEV520m&UkU9Yn9Gkoz5H zsVsHo_m%!=VVe8RX*B2&*I^5+4o3!Ww0m67YZqeGFMSGopxVdfSzroE^SQ2ha%^!A zsbmV*PRpSa#nP6^MR=dKVduHk69{|szAE_2`Lcr?w`%E&T@cnV4YE|4{-lJJ64{m0 zT5GhNRC0f7X7d}qLXY)KEl)KU;+mySnsPaLB5dj=Jap~?9#3qm6toQhXO14jy*EF@ zg&+PHqu)s|{;jW+=2;vb!s-ikEz>QKa|TLoKI6@Hdy6WcP&%c|CoR!2HtH`RKU)?>9!8<=PL zI;zf-S2qA$dh!{rJUNdY1G{i`$4iPsT0Y2glDU=SiBd!7Ksauhwp6V1ur>RQ%b;I@ zdc$=}ou9Cgwv8N(Qh(?35K|!MV-*N~`8a}ycL4x5?%l=Bd-w3wGiNLI$o9=CJ^Mcm zon!r&dQgPBPU-}9UOLVvz0el}Bm(JW`IHZZ+v6W&FekGJJ%~Wv;?+vIe|}WB~3_P2F%a74@Kot*;brU32%1+rS-yDtbWe+Fyb=(ney_}(|Z ziQoHIKf)jU(t$0;5I z-}|CG{yAgusGr-Cv?eO`TvvDU$vf5yeeV+|UHaL`p4mTH??z(-al$9YQZIQAmm__ZaQS4+}Xuv8^|wKA*nJuCZ*-{*73JRL%(DQ|gRTk>dL+GN(okh;9q z@3jug!K+0<+Yo8|HgV0&X>Ey0ZJhGzvzH~k15n?ko$jvGvi?gYrTKZItM03&@Xkho18|Yr! zG;i3x0yyB9gOAf5huNDn59g*4^vOOsJFI-NHXLB*NTaKUTf1jU`&I=uySi{=b`PR@ z1K0P?VzaB-no=IbQHWc!GuU_OYV&k;n1F4zIRH7U)4nZ^4B`INj;(jB2`l~mSn2QY zSb5J9nEqVpz??~XP0A!hUOms=#;p!j<#0PK{^EP-j*!JZTZU5K^OYm@Wot=Fo6_2j z*6wHR(Oqi}n|zhx8WNE8&OS-axl#_uYbQ-_R3pKGOP6tN-`>hR<@!H=1HsG)`hV%` zr9s==8`+Aq-(l8%@*qe)8-RTgVb&|kL0Bx*M%z=azlh1`cl=d_)>4=EFJFOdJx{xk zS6)>|gjS^8JTBwj+Q^snUpqSdP6%r>+vnEc*3YyeEtN)FmQ?uj%a!l>nKrm(i<#Z! z8@W;ecby@eI#B7QV=eKNCJpb_MXhUYG6Ut(CFWfBQ`)BP^$nbP_kH~FFMJ#I0z%RayACq9ZJokVI#$|%mi0;l17N!1_o>3o@7Pdu=~B}(zhlaAl^LDaXN>3fOqWRp zd0EMH+>V-2MQ>|$_nCqXYt zQ)zsvn4}qQuWgH!2YHf2<2K0G=YJ2p5ZX9SP8Y^N-nF-@~khgJsybD_e6oLkgKcjtX< zO7o2^w?&r7fdwp^qAaLd&owXNF{!FQR)J2Jw-qREMZR_`^`&+-1fTJ${|6*J>hGG% z%h@l-P|gPqaMoc=k~?t_4*f5wOU`C}DtCeagNsX8>F-CqtJ-46$cK;7`-c~h>^%&8 zt33Vny|YMy0Q)XoMfd7DLh#j$G<*3}52C*?>w$Dbu+vV@eTlly`PTS4x)Ro7>^5iU)wN>8d(;4Kat=%X8edSr*NaxcsU&~uxI=_Bx zb-P^yJ2AgDhoy}LL8mVGXRZy$)S860nKh@ha?)z&u3c0PuI$zJbqwA(Bl)H-qxg3r z>=?q)=}{csyB80iJi)@!VudzKZ8PPIyp+h=+m{if9U-NmO9#@bV>{P3s`9zDhkbHZ zQV4jC-KV0omIifB*A}(Xo668OhOF7zM7kCEc5a~FbK5NMv35|Zzsgoh%yWPp z*I!h&?E~9wa{TF;q;_rJQJJA=1>2@>0FG>15e|y*r{|fjL-$knQB!cBupqfL^{=d4 zE-(KL)k<6BWUnMOkj*IbruGYSTW*EKo3zE`2(e`_R^>5nsD-43Qvi1eK4F_aImCd10Jz`!1}AO10{L@HQ+0wgT$@@Z?N;em zD3(NQv+$;N;>CIX34bXG$de+i=yWR+_l|?OQVpL@;^si^)LQ0k;u;6sI(SmpRu%E< zd<*f<9<*Y|`sJ+uy)UhP=3-ImO;RGr_ws*Rf;`P$_RMm4zQkC|0h)_Mr|ArooJdk# zi2mhOoPPfUd~oJ;3Fd$(im+pR9KZ1DSMh_t`ah%ocMk!l%7eC-h6WMWB7}l_Qg1>b znKVBLM31DFgeE>@*f!bD)=CLXKB+YqZ&2{fkyfmq&(qE;tFv8uuPA+M?Qrcpe_1-8 zEho=@>=Z~_%i3UY-UTL~Y?HRmIMr6#<{J-R|MPGnwH>SDSuMwM6RnHWcPk%tu%gv9 zrGA;#@&1$Rc(SqF%-aw>^3}>bLe@-&9mur{;+0ZMwxeiehMU^wXWkk}?8`RA2oW{) z0;>@fX)h9by1ViGvE#UM>n0j;jOoc880hQ6+|#G1H|p3i?w*eNaB@4k*EZ0-vLPfw z(j19=kh*9Q4{c2{cMkGu^+^W%-dZ!hajzmXTz=|HZ}VFIXlHkN zaFF7#fz7^d%uQ@l__b~AUtYn;<9X0}K+@E7LNxGnd<@qr25bYs{KyFAM@G=QwuUHa zAVz>4ckd&t(@Gr>p@H@O9^BqDjmrlQR4SL?>i&HQ;snz-Zlh;qUG*i%!VuX)diwtfn=ghmwM(&2+0EtA{L*b1D!y3glFM{s+3 zx}$Ar1>!iym0LFvCkbYD>_mTWZ(HT8Z*1WDjhjf`xQ5`RJ=nc(H~K1+W#>Y1I%#A0 zbGcr&JaE%g)gX%H=~kgN9i|=qdaErjtI@UO{G%ngiq`+qw^q+D^6gmJ#Q#g%Teh9O zL2~WZ)gLVjR413AbmaD+O)uotnnl`ukXZ?+zYKUBUgy9oR8G zUYKWTXb?}wM=?4#pS9k{Q+V4q^*oiAzO{Lp%idM>)+WlA(N&diXmz$cTYA0{*lM0m zrLU5|jH%f?MNSKCR$JFlCqX+dtkNOh>2&PCvw7vg`_|mm&-tBOMt=EywO(|GQ5Fv4 zIw80eW?>xI#R|W47f97!JD;t4k{u0_S#xXi<`%J1%ivw$y6j0|vTyp+b<>u?*zhp^ zjaR>lfBO5shwpyeqAG3;!{6oM}>4?Xa|RH{=0NQ zE#p0Xx<LtpUJ6 zrfKRhD-Eh&Za}!JPsmycpZ0tW>(tZ1?iwh6h!~Bg^rV)gA*oSTE-g%JeMC!hZY!6b z{-O)&T>j5;M9vVmEPfxTyw3uv8tAQ*_pHE5dB0vodXg{To8RS0SgFD3xhKa^hkVF- ze2x-bo7`k4c^@t3vLm^H2yA$!GxNFkKg368PT~H}9fh0k2wwer{~UFQawKIzOV2V{&rsSt>9m@2J z#Nb#yll4g%OKB|i=^5gF^HEeem9++Webv%f+b&Yqr?&d-Dr;NG@wfJ{tNY3{?o(^4 z`glTK4~hO{4_Gd1tyc4u!1Te-ZCM+TGevGxmU)?4Ly=4B5r7ZZMdQG@%cBBL$@%>! zOWS_xIqbJv`GhXnF7A&kLF3cTG!707nmE#$EbEE90WcIL$bcY;U5h8K-CZo^miSJG zwziw30Ue0U^+~)*Ea*~Pnxd2GEXUTI!%`vjo3|CFpRA{|Y?DFT_Ix|{WO27|Jicx_ zsJ~oao^JtSr1gn@dgcUTRMI}_v9mNG%d;cJC*q~pN^N7lXr1g?+VY|O>v9|<-)Eg) zb9u|zT&;omkZ%iqdr&6dK2K;(i){^jT7n$~YyWD^j?2+nsn)3Ym&@7HIpS*%S^$}T&eI`*qPZp0RGVW})3pj^bXbK}^*qgg?<+h1cb<-B zA-{|u=eh59F-Ur?lG^2wTH@>StS(~9ky?Wti@aw=P^>#z{nF~S)H118>3otFNtbc; z5f0Lp2a{-7FX>p?H{J=uZk)-~jx2L4~eUSY{^#;c0=J0siw!+(-0U${dyz#;NSX*Dm zcfR^H4D|Kk@xnaT*EhUD+m{a>z`(*XCRZL5mb(?cRaH;uv_4Tr?OKNG=hPm53Hi9l zYkv{`tln#Dv~tPXYg#MT8x6y3rs;G#keGwH={c=i*_&3ajbgFFdJnDD>U!4udayFs zht{sGKnPquasczA`J2h2 zI7ZjT1_l?F(6wGSJxFmKf!8DmsG) zsg?t_39cO64K6fPV&+*Ut7PmuVMHnj9YNL|KQ(5|GxH4G+$m_#See-r-=XKe~$3){W8A)7r$RAXgd$umoj-$!(Yd< z(e~Sc>MdzS);|mDziOFsBz*R`eC|qef11EkuC&ovuhZHkR6T)tBRx9Axl+j%8LE}u zu^{7)>G22+gcy7L1e;x5rGeWo96y2NZzeeZ5B>$Nz4;0HkL)T9+I}>-9bKDsY@2(M z;fwTU!U>-hE_o4Qhz=B^zA|4|E9%uJ&6kIKT7%XM%~qgQ2SpWP&QG&d{8u+PZq{vypyQfHFgm&uH8(!X^XQDiTn#!e9j_Fiy;;894 z$LxN!w8;U1QnB?pj@;T~#&3!mFc^(D>E{1dk&4s74}B;GI^yEt2FCr30n)(Ge9Afr~(r@elX zTaxyR_^#ZEp3R65upBm1=HmuZr%aUP)CLiqCx)inj1WW46~d@I*C1V#vjJSBfRy|2Zce~dh?rX zciMtZLRA~LRnRtZ`ozjt{~WOrFrR*Xm>?P9w{rabYzL#RO_^sKYZ~?26r2Yl9iTTJ zYueRV(Q}_L5U8}$?seyutLJIYRgnF%dXVHRx=(bJ1xrVzuQl3gSfUV<<%I_Gl1<@S&p<`z!Pa?5i8(WNll!X_@Re0Llil={302;iDvb`ZS-qm(R&<$Q6}M2VBrediHc_Wc9h5 zvaNkd&mz$`Iah3dWC%ErWRg?|qSza#G&VFBk^P_j0Ew(P0OEZ-M+B+aq==rc! z8?Vaya>&c?(m&@YxAltCxi#n6VfnxP@5(ewo36MHe;GcoZS(g%@TAr6bbV6KbJO{C zZ>DwI2A-wub2)$8wG4E5n3ja{yQ?#@Uc$a^9l&j6y?n-Hro8LV?K+Ib%{BCdA-Ygk zHF2qQz)b2_=HCDxnnEdwYm%fT%})oo5&zd5!u?<3DNRTJyE>RlF}f~aIyo9vJ5HMZ z{=U^UJpcB)_~W1dHX4yWR?L9}!0mZpbq!eE#LC(#cJJ7U-U|G@2zAF~)t>oCeaS&o< zus{1v?M!Sdk^ucnt64ppy?X@Y9#SlKp<^t)HQ1Ee!(hTHioz zqYge0sDU6z@cs*DvDsaIAl?UO(_2N3eR>Y#59bhV)X}wGM+~w$rLInR*4jMj>l(+* z8>1|&oP*!#v)!ADX=X03l+$^U@2Yb=2#1 ztgNkJcyMq_ZM}W}J}%z4fmctT!5{wMhlu~jKLXb3z_-2)v>CJ=MG;1ahVi6i(^3^6 z9j1X2S^8%lT9d+6#mOKGkXb8oJa6U0p56_zykNPXXzJ^V|6RhPEHe zBLq^O$Yry|o?65}f(B|h_5MeA>$R8hWZPINZeBcb68O&ooV#+lG%Z1+E5cfTFM3wi zgdWT{LX#G4?E^kjoco^ASt?I!?Wt>D40O)vm8UQkrOgNJc&whb+WTjL_o6cW4oo+d z&xE#ltF>Mdx2?%KP<##{TN>q)im)UMYe36-q)|=nvFS*8_B%yfr-}TY=ispKsf9Kj zGe#82MZY^(%&^iUS z!e2T8azV`sUstduYV5Uo4o?}Bw%kov+`fFU#)Wolaf_HL+!JtpPBFiu%o^stIq0@n z2X*lxLh8n%=ax6P{nNB5={(6wBJ5KQyvx{apXezbrqNrBUs&oCN7rzqI5>5M?-&bHQCq*WKx!w*%74! zs(rLYWsrM;+$~g6oP{2z7apf=Nc+bZR}n__b#OAUTAw^dq1X+Fe%T!^w=tx%f?FKJ zUU?Uyk>ODD4k$d)(qGW*2aRHsQ5Ron{mH45xVLMkGX_0tYk2(!KgxP1=LVM!g&$<@ z^e|hlruk+anp)ONYS$(bvh=c)Rv=$ie4g+{wZQhi6+Mba-5SVwB{KilX0tSRwRz0H zWGRU%LDodMXaj-V1jL4Mx}l&h+S!V&_R8rqsQv8#N!$*;3)ZnxvBsG7&8o4Qbj7p-4g zeKpUvEz-FuUEnQSmgnk+JNqXQBEiD?yjX1i zb0uV_c#f8}t{m01X^9!Y+IVnM=FwiBjNdAE(z+_smoC|7C+Ocin`FR;&n70@8UTF! zL8gD0{a@;0Qqvd?l@w%cUDa2}ub&jnw(5G9a>%^`vsw{aF8M2ilZKLmi__wqz@ zKOU{sWygX8pm;-e0DYCY9TN?*CjE@8a@qSpe3yY#K9F8+!X1Si17tUn4IVZZq~w+8 zvQ7?smO&x*bU&(%$I?pjbcXPp(*fc#U_#DE3$iAnFzO#5gIe^7d3L_VqFrpaq`xRI zHp=E5&l$=qLT8)!)I3R!1lve@tB9WKNtWKVmh;BBx*qpMSp}We@U2B!WdG*LO5Hlw z0^@xC@sVj{+Ps=*&f4@mgIW4AFXO`?V&QS&mPe@7H?i;H6-0<}ch{~;LEDFaOD!4MBtbR-1c79vP*B{+F^l$&WB0VB7EeOoJynOlX@dMMR)fX&h z)AY%ABFGvNF^}}j((SOenWlgJt~JoMsm8M(Z=8nz+@9%oTBnmYWN2NFv<;cg4eFMM zifqIU{O+C4aAJ4@XUBGCE#X5ILXgdyo=lj^&lq%XBS0ISlBVWC-gxpk6Sl4WA!Vf0 z;w3hUX8ylnMXH5ia%fRC#0^%^t%3ts8 z!B1ZQT4`ImHaGG0AO09!>zimq5ze1D>Rmr-1%CGOOWF4$pMHkfE7w6m(_s*!-qqFe zv^#hF7yw}3<*PV!?qW7Sf{f=!87|4@O9N%K-feGe$;XD`ryoIociD+EQ}1}`rg@&l$k^!5CsStDUKpEGTTvZ+5@b8 zoo)%%8|o|7n3ZKc3i8DHBpcysG#SS+8gY!S3OBG;ZfTNWvt9>QHqbTLhamDFzDV%1 zmtVqH-uNkoA1@f)$ejw7H&lT*j&b|meZ2L~yZCqh{P$bz4MQVtU~_#F@zOdr7gyE0 z&3YYi93u>i`|5*{!9o1;H@}5n5C2I!Qn6(qtfj%-Q^YJerW)cDPEr-!1M_+I<4k{hjZe z@I9B#Di_a*lU}A{qVffZvPm2``SMLIw=K4I>nhXOV&-I>X#C7N$P*jrjt(fEyGwJlK<{I_>DJyh+q1~>v;Rqk8yDKEOzfKH)i~&&03YsKXa># z-p-0>DJYAc$#+bve!SxJfVrLDQ_IXCZ9=xeotakQn48RVnhrOmXG_ZazK1 z_TBP6b|&&^PW-2Xcp*ykwUyhMVnd!*MXp9Z0nFt+ev?Wr)XDiR>D~q~+i}<2ooA37 z5gA6$4o`WKMXG+K^~q~aL7h7tw?sIV@xVD;9I^8#R$oc6A{@g7uyr)IAD+V_*P3{MPFL zfU`e+553E)NKe$(J%Q*a)3XfR2I9<718CQdElK~DhM3jSSl`gbn;#OVjL!qMUR(RR zbderzb!TbB=F4j4Orc5_czyxMMn?9-o;pT!oIr;qAxqC;&pdN{5;<-LOvtS;HnOM|wPKe>eD|9lI{wi)2x0!D|1apq_zuJrWHL2F&w zh33y+574ti>nbjNNPEjl-h8`OmrwcmR+LVGY_GPlfFfI2(_i{qZ&-EhV{2b)x#yFC z)@FplinO&{3|h@ozR}Xyav#Qp=0k3|T92i9VQog<;+pn}HmLD&2x0bC;x>e}jjcUQ z_A_$Zsi}mtDe7n5*lK>O!L?iE|N2>Zxmq4+da&9Pz@yElF#==-ON-by7krYB+sJJV z&8KSvb1<_EjAE_T$}U---n7heflA?kGhL?j5p#J2Ae8iK86wJo)ONEn zZKUSY=eV!hcj8htofI5r{^7vjk@RO7V9h~d78t8>W~tLHWU`$B60G+3VR2;0!586v z^vOKB*VeNqdizG|VbM~D$4bv-%lD;(lGJByTAe13tGn{fVq`0F&&_Xb_Ew-X5;(sF zQtp=ZJTaJcwFLLAt%K8~wb3v3AyHccQ@*w9h`wV;T1n?zBdd$oT!{P7EdpUy58c<6 zfVKlygBOmUKpe-o@P}^$_ZM;UtIuPsxeA-+u7RuCjOKGry?Zw1g^Sk}p?fJ$Ys2 z*$%$cKKYXefm5Pi&RDz7Uv}b6lh;mvdt6{`&21;suFn@HOVm8U&L>%iKaCA6$?K7| zO=S)K^!~Q`@XWe_mPu9@WF6Ue!nWOb#s`RKeJw5LOmM+KvONP#KmS!kttow%S>* z)$qe_z20^|i{O(}Cy;dDBx8b$hYw*hs^Q@IO9;RleR&S^{G{2d*PbnCnVE)m`_iCU zuBHQBcXgfN#=X1v2DzxR7c{?p&UU-*On0ozW^cBEXQ=2qeA z?OXWa|Ngre_`f~@wh*-a$)!v9*+2SiH2&cm`0d?ez<>Mg?A^b7>re6e(Fq*bz171w zS_6OVlnXonI6=q0Us#@XT3!|FcAbLi*0!r}w+B`5+iqE9da>5W-QSYKXbV!mck|hL z(zL1WNn7vjp(#=y3^VP>YN0Ik^-8e3yFve@WyOf_{M+y1gR`eAZ-PpG>l0l3>HFCH zZxa0cE3cNOe>ygbH(z@Nul?vJpfGJs3D!4B+nZ9oKV7#b37MuV2-z zf(oF4Wa-@N|;rU!Ol_aHL}%ij2$85ugFOO)npoH^#WXXMn-hP8i( zjAgD>#w8JblKrIb)IPa8QsPXq&vy9?q7dQq2wppT7Ja?FIDPmC`g{8d+U$3k!D&T4 zCFenUwTe5#0NuMzC>cIsD4k)hlOutpKX<>SZ$~_Rmu11Eaovbjz;!UXwCAHiZizMG ztYOErDNo{+4leC9)AXD-dTeY;Zei<0)~0-}Doq{jz|`)9MphoDmN@a3OXFuTlGYT9 zI%s(#$-+Jvm}dD5X+ABOl?+YG?%4V8z%x^((oRcOy?j*4_~SC!$Z}gIoh_RG_{x@C z*e#D7oM^V%4cun#OC!OT5$Z9gv9t0-IyL|uWJz;a1~AiAZ1%a^a=+Y{inkq6IyqYQ zUZ0lb=K@j=$q;|K44VHUB%+Ocx|mk8(|~GypA|toHR`wJ%?`0KjL*kK#~t5j*bQLkPxt+!NxR7hc4|$Z)9> zCkX;94-BMz4{4E`W(_IsX&JFtWDf+UwUbfPhu)Q+K9k0iUlLo*#Fakno2S)fVt)JD zt-bShN|~WrHE)VhZHKt}n&dH3W^-T&Jo7;6zFJe&Qa{x#$vK$5qtkXs1Ee|B$O0;~ z-b&XlR)yZ~9)w|tm9@3Xc^;3CI_t&@n>r<7vo@SwsSQ+<#V56JDS_zvx|KtOMOuOmU*gx&-S(Ne7^(p$uh;Y z-2#zc*5}*I#-yG4;64-fN#;H2TlXRJ`R^kS3%jedz zv()HH2bLWAnUtBXZod`q*?qP>*51<3rR^Z~fB!~YcLr)(n#z{%>*AanIg05)3RXXDy`m ztPS*Gv%3rTckL()U^#sL0=7MRjGnc1^scTo7q24F>Dk12I9N3iI8DSj(y5_zg|pPE z5-|#$SpfFgsaq?1tM>Kh3qD!gT7I|9tf9Geutf)vGaYx=tHrs97fId&QI6IQ)7eB@ z9JCamGb2epu@?piFto6U)xJK|yUNeUdg&$bsD-2D2x zq$gfmN(_#*K4?$tg-Vk^9v4bX8P zX=@`i&}jBXA8w$nD3-#c$;pFIB<}LIZsD9{PGg-`#k-`%0s4W=A}~C zc5OWQ=iV%H{@4-R+B4I3fN&#<@YX9YW23vfqrt!caQWZ?#9@g2m#$!bWCZWMaCS?9 z%s2P!MjV7V{ONhIk|!-vein-{;*pX1o5r!Uc|JVz9PaPjfuxPoh6$cUz&3zNC%3j* zUJ}X>M0rCM+dMpTnHmFV%5bHR;0ml2$Kir;Q7XZ3P2Jmlx_z#e5AHcxiKxz6szU=qpah`H* zvRG=gZ%KZBP^2HWn)g|Qtk3n~u=I0n8^4CGt#bX|`c=q2%)<}qsoHAiw{~N-w!y}d1 zHd|)?Z`ZluzPD~Y{w)=DZ3w%DF_BoP%G7zeZf&~l8`_EMi+7PEb<7S;HS^|~KO6`{ z%t$&3Veo31q3ejYBcT~+8GYzhx?>u6N|5DS^ObQ)ITLL3bmQEqW0e)@0Kks%3Dlwp z+eStU)AA^~2D~*Ut8%oqoB$QeEKieo$J?beJ90k3shuCT0&Gi@cup#P;p=96EnpDQo%FAfwL!`|SqGhH5Fil& z+iCxoZ?#ps`wopka?BYV$hY7!4mX)Wy|g@qKu*5_7v z9i1<;HJWR^eZKmAHI}v0ecztl+)jEQ&HCG-Z3tg_=Dohtgmh^#ebu&GojR|rKHWmL zSlh@}i;`B9F4OAb)+Tm!dfm?Ji#Kp*={|mLH(wbmIT_ceaZEf(@-10D@jB+D)@o)h zNnDT8wKA9dY4!YY)92Y4ZW){1UD)jEDsRVMJcGV(?!<$xE}Xk^881I~x>DOi#Hb6G zpjbegHLwqXHt&3_P$GvZqSF6xU56@X}s08%X(;DP-|Qb-9D4{uckK+ zQuWcZwKv?k==!yM`UyX!AYR)(8GsJ(soxd{nj>*3bOJS%9jHE}8;T_kUHnoGdl&-g zENO0e`xIj&EhQ1H(iW1m&3ra;nuc!p%5S6YKj+sL8Rd_1P7>6ZfoLHzJnFI`?8tmd zP8^)@>|q^>^e4?_W%#$tVVRmFEzo@T;epyLPtKM!AkVO7I!J^K$tPA?@GY@WJE=6= zCO!p|1EsCrkop9o4C5&d=td+8F%BR%5is5G+|q&C6tvy|+sX-&Fu;1#cBOWF`rL6m z8B1-^-8XJx|D`KH1L#`c5FV8f93+PVNaQjAH?mG2*OXPSHlRJUQ<;qjjr zbf#6Em*jri7O?WRi1)x5N9K~OmohKc(uGoM4kTr}%*`A8v{zK}0%`BE#3NptQt_$x zKf*_6PU6AN9p2m3EcERdMfX7UP0QE!&LW6o9RBozXa#F)#4p%7C*CD7p7O7T%IVH? z>1{{^W~?W|H-<&pVX@v^C4Xl@&WrSSp4}&LlW!yX_(c_cU#1H@?|kpI=A_FE)Tgf< zo469#+2-TddQ6J?Q4AL6dF5z*So0-%mX;@VXP<5u z7Wn6`$4xNKm$=rwE;+j<$7y)?$BXex_JX1UO12E4j;*B zT{@97ftaSONh0dwcOqU;hUFpsW2G5%Tob zc3@_52fp|7KabiLHv}BqGm9PL6X@yg!U)AT4Gndmg+LI67(TeGr94)qNowVA)2di3 zn?v?}xo-D)L0%85wyrvcIxGFl=vM0Zu3qNq_EofR`HX!p(gsMMvB%4{M7N)9bR7km zrYBuD$>w9IbVAzZl1icmA_M>qUc3whK_$Ob@Awe<7Dj=))q=JGX^R7NxB_X(d}CY# zXdWui$Xdw%B()idSACMSGNC$2YGq~RwW`Rd?sQwKIW6)C-x}q4&<;WS918g*=i`i1 z!uw~Kr$Sj014s|Q(7o8#@-7A!j zuM*Z=z!$X5ZA(WXt)G{H`J6CzNysZ%%VdBM)?2r=fzM!f;!7Usssv+wJDy$FzC^3Hw4h|*d^;QW!p zxIHt4dK(V5h2dc=3=d;za1a3!3_V@MgUQL3%K?B#+tVxX>a`m7UAl_VxhDugXLyrV zML0=~4|%c@&mjO}G+BF)pUA#%#Zm0j_1cGWhj#UHK0lDgZgnkzu}=AQUeW>eVwc3X zoJZ5N1?@MHbjCJeoY5kslix!ppDd4T=!WWXAl|tx z;`zYz$hedCN72mCEzowh)@*sRqU=Ln*}if$7fZEgx_mQk@)8P3(ZRFKCnUbDU%`LF zk>#0X?PR@#0)k~(fL!FrD<^2`{i#jGOXk+DWc#YTT$)7*cpE7I)RFoYC@eb3JPfqK zPlmHFC32~(`!dZ^kObr1)i$kdEQ6c)hNgNp59QpUawW)-lq1I4BaI8+ZWSO#5F}YF zRG!=p;|79+EI8gM9|6rpB%bpWswHtD1GgjF&maN9wB*H+A-wt8E8aE$>1lX3_w2^_ zqdC0z=G*FB)U<^Wq+@kw_cT5`aV)niFQkGDQQX{E5CR{aIhEP9RpI*HS=4Jaoc!=( zgfaPB>?w1MA9;%xowQ^*2yv)Z?N!dJH$H#Sur-O(`5s6c7LZa`>%e&ymbHDg9QH}- zMEy_PLh=WO7j8QF&V6p{Do-QJlD3&^4e7M}+qFuW;`ISk zQWt~sE`3wX-;4R4?61VDYuCABr>!PedsTuT7@5cC}N0_;JyUDj`!&$2J$Z#^LS3}6mQ1CZir7oTUjN8DZPhfei&LN-r zYoPbiR?U~f*6K!PO}7gp&49W2rKQ|7)}FVmk@jOAzw;fb;jgRp4QE>cA3YVxaGkdt z^2(C+w+D$guclq8M_L;^QJ;bLlW8|X13{GF(-S8UMx3{4mwonJ*;XbO02O{Os7#!ULK*2}zRRjrZTf=_5xm*x!%y*RGjAO$nU|w0`u0jIOyFM4SDjXO3TV*SNpOJ$k%`J>nNJbWo?l< zN3m_C>&w>@e8)J@cU=nCuMdf!CwfI!ZnCCm7d~w}J(0VCfyE{CuC5mLS;F-8N!06g z{OpsD@zRNtrRmpudhpTdQ#k(dr-&Lc&eiaxnt7xl!rB0TJeZhalTo$s~t`j zcV)1$wu(`idNmuK2MS@i`%i=*vx4PD8C3%`ebdUBsQX%eu-{L*$BmVP3!#3_Cd}Z%B9;P>n$^g zWO-DkURJl|RXq($b1wc(c#vmI(XuFCk*CMN@-^8eeO;J5%_=TzCjc=j6le|Mkd#i# zdb4g{f2CSO27z?#r8uSbMa}Yjr_JS+E9ZKOC*E3~@oLF3R#tXRcO&eX>W+ zYfBIEIySizJzY?)HF0@s&kQzuYPi31Cl*GAbH}6BXrNY4uT`A9{{VvvOU-_UnaWFx z-Z%E`!Hs=;DxE}qduAF@qk+9wuAy()uN>3dr*DaP%JfC^j<1NmGc%3l3fDVXcse?o zUeBBWlXveU?uu}2-(K9J za3$ngZ!hl5OyR)AOWA_8&giqT+kqm7Q-0ajhS9k4_uZE^U)QhdhARhGo97yRHkZ`L_1t%V7X^Sa zcW}$&I(7X=M|b1s$h32UEa`>`q%BPHiS*i7{MMF!s_$}1#Mh)Rg!v(1hH;dLbY-+3 zR7gW@vcIjK9SVH4VrzZv>tt_%ux(Ex`7ipO=-Z{Y`;-^DLyZ zJA(Y&N;;XI+sF_&eUx5+{CreH{#!Sl9%H}6wX_s^-dP>c+P&_n&C-5@r!LuBcOF`9 z;%hTNr%V^ohiw7dZMH`c{n4i-a|wCn21ta(B)5U4Tq4!{`JN=&+)N?cq=U)eS$#61 zJ#9Ny>GN@*`xZBYPo)kcH^k^Uz`akL6ahjsOn-xBFO#hIj7L}Rk!7Y-QAYyW`pnik zbJ|e+pN>9T$Ye7IARmmyGh;)`8@30jRlbwWIj|{0oCRyMU0gTmT^#ZWl5sZPXg=e+ ztmLgzDekTuJb-Hl_M!+*z4sw@+<%ajM~m(h5Sn^nQr(?{FKMh;+osm00qG4ysN>rH zeYkRHf7XvGK;tjxV-0nDc;-1goZOzaEoj{yUK$+4zk2;^_{I-@gfOY&tyf;oPWf&X z?oRDOBZ_e5o%cch6}jOY;0*}@r0<0#eGvp1mi38Y0DB_x9JstUI?kDX_=m;)HbsAUnC-htv^vC#$!)q(EMmL1D^rnSZO*bIe5Ep0`|4G zHd-J4>ThCm+go_;@Bc@Y(g)ce`%4M<%rUJ`YRRZ|C#DC&1f`IEg}gpVO|fXsmD_*M z*4N|8V7D#)^!c`*#G$Xea$8nDFRI_#mr@UspHf4!<>b|sKW>`dd@Z->@^cW)OO0IX z?~?vpTg+0cI~G;=aQnUkpWg3|5#wKuldBuLf2_01Any5XBbeJUk=2m|z@3>Xj6@OQ zN00Dm`vmSz@51uX09FPE(7m>S*{jz<+AlynfiUY{)6N@GB$t!=7o}z%DaS+x9&4`b zgI2Am2 zzWZ`WZa-Avb5@HgDofi*E>z=FWsoOhEH7kwrML2~*g)6-QB$L@_tbFx;4JRUOl^5B z>CZY?S?=;j-}qS{gvND%1P^vhRtkjwS}0I=o2?W?zMp}VUK)05?gPDx<9ty)^=*_*aDsdghIrwx{yEee4RqHk+(sz$ zi+nBTT*bjv`>m@DlYQ27J(h3PRPSn znz!1+V%x@7|5oOKKg7zw z03PfpKV)xsa1bN&G2Z{j{{qq93UT)6vBLG~daZ`r)6=Nc>)3zk3To@*lMI@8ldDqP zL-IQF-O*{kYpqOtrM@mM~V2qsC;P%a|*wc zLgvqRR`{Rg8}oUJoZCvBM>{7-Oh^*eY5fXiK8cf(q>XCV5hfQFWLvK62`j+ zp|5kLkSkWN(p+JtED#Q8NkK9-y26-os!eiwQ|xHV$E^>vaph0pmg{HLt@4cJl~sIr zFx!?c001BWNkl2%3g$Eq5IRh&abZEN3kq@7%4&*gijX${4$ z%l3GukFWW7s-`8X&(fAO>NM>Y(XPzT^z0gkfSn&OPbK$Ab7VWL4PSsrDX}0!$E6|? zHv`P5^<cfeV1PUqh|2`{Bx+h{Amt!!9iK2J>!W~K`Yund;%kaEZZ#ex z4rGvA*lcgQ*vcnZ@%7%izj}7?@-VAm>0&jXn8sH?>!5NSqC#bJPl%(Y0kRFTD_km= ztb)-uUZ~bwJ;=(GE@|t`aGj&NPT%~NS0qQMBSHiBrg!4Xq5YM1(O)^RKl{Gg--ppB zPmv%%|H=xsJ(^4BRG8q-^b{@~KG@QAZ#QQ5AV?AnEi7VaegOmX%j!MNKOZlaG({(3 z-<_U95G1&K@BmiY+>JaxI)XbhQ`q)+4!3vD;L_oPZI$DL<-virg2{a_KRSYi(Gd(i zUCj7^4Nhfl;X23skeIpHn*6D1@NP{m`s*!+FOQ4cO7=YCwn|>g4?v8Z=J49=Wu8O1 zIS>7o=g;yl;y4saBWsYHCk<{&w+~o-S1y?Jt*l`3!GlUC&u=?5iz9#e=WzY+{vTLg zUGd_Xl^5LrRWwe#^>MOF5TczD< z{mxIr@2qazDM*>g4`_ zZM#L#>gs7)YKJ|qqZR-N{sLyM-vnuq{+1Wlp6bOq zwWf)!bGlab2%on@%U(-iuFdR@eRVsys%}&TbUI6$+6K0^0!wkWlw6wWSqd-sO<0Z_nUD~hZ0yjOmiSNXxp`i0S+AI+mTZ3C)H?Z`8@$yhca-R!#`P9 zmS+t~zk;@Rby&E@s~sOn>&%@)NUPo5Ano%3$T=@t(rDVEq^Hp)7}-wpUD$HjcGcXR zY&Ej13t&n|+rN7@8P{*Mbs598*Z-KE!ce|qXTE*v|8J=d>e_UiQvSG*NG^?{^v zEXw9V`ds^5YE2tIYW6RQf|jofe=;_PAAR%d=-RB~l{el*lEnDnh0}PreLEVp_OEwN zf&eT1{rJ)A-vE&M6Ow|3ts;oS5DzD}7?Mx(oaQ{z3X*m#%a|$_ z#}@~!x9sz`ho!77!>0CJ$k6Hhc5`Z*R&y+}XaOnviTB4@z0CQn1}IyRZZV#P#hjjSiM>4g>h+$KJIy)Eafn+`NS-X=L@tei2V2e;;!P;>avJ{VRve zkqJvK{(_uetwOaiO9Tg#ln}-V_FcJ(>$9_!g0_<%Uj+`GLAPYpVzlV5-eqdCQ?H zzYGlBrlT>|J%I7kTS~iLo(EeDkI3cMt?P-T@p^StnX5izS$yX%Nq}_a;Q& z$||Pr+`*lxYV-fkIs{3AJ=bocwo%U_CnQDtH5jX5XzeKd%xWlYgHN;iJRx6CZ#Q2V zJw6NRTrPRb?3KJ+OiR}1?$>LX=tLmpPP zsR4D;c0RN_Y1@Ia3Ek?X@(rl1udK{6M}n`-KEp0AjbDMO)*kRLIQ2j41SDpBT$~0bZD7(#=RZBO3oTN-+r=v8sR^|Dx9BJCG9f*6-wdHjr;5ONY2_qYvlOaggWcvNhzV_S0rQ zxQ3cv{j>DQ;#i+2r2|^E$aVvPeRILK-5-t(aaFCQVqF$Jav0$FyD2fk8NpAQwROqNwh>|2k}T{1FZU!_OcVU6ZWr zIEpYgF{b*f-J)s!+GZVNj~|N`bE}cf176fkq7ZWv6F^qGe-?IaZeZ;3)21skX||5= zEl+TzbFwJJTRLl5{p4*oX)TO(zkHFu<;EfD+)bUj4KYS(?>{?!w5_YzZtb4It=;J^ z@@WnU~w6bc1+;o=T5e@0DFD!EC68Y_8siKbPaurtJ(aQi%Z0Vw4*JPv;eHbNM3!%|};Tv)rhP>@AiE zUk=!slr5J{?SnO!eWSoKI#JJbUjKVLF49<)X^8g*Vm$TPMOp)r=hsTk%fUZ<77xi( zc?KR!-~=O27qIurwMs$T01!+Kqx;`~5z~{CxOML?rY3iwRzUCTJw5pJh*4` z>@Po6LA`OgZ!wNrwX$S+wtk;J8mRXW^IoUdwBd7s`Slg4m;3Bz*}JQY_wZotDPG=w zRJ4t>GvZvt(GpRDEQvRn$TLI(=y}d^PmY4*rjmcQPqoqpcjbWmRy+r!Jy8bBzy4FK z#q&UgpzYh!)96`U!_HgxymS_1%lYg<2)w?TjHD!_ngi!8x5-W8@)Z9s z4O`JAtZgT0lb&1KSlYv68|YK~h!W^IUAZo$w53T+&-u4UNn4EWegSCiAhSgP4%5{q zWNY1n=ulb%@6z-k$Ilj58M zqb)9ztW}zGO8!Z99z;Dh?AdZ>qFpLK4PoJJFuci^H%sgJ#$zGvbn;j-cI1_}ayty^ zVdQsUyO_5I%9C8>I3(gz&QsqB+j8#nAI&*w8(%xH7uWaBVzq@6zV7Uv27&-b&YcHs zc&9SYA3K8EGt=1YF84*Q_x55Pz_tDRkc1)jUcLsPj!o1+%SbZBjWuwdYdR1;eRh5S zEN;!Te(GBzim*I5h#*Pu(^tNNv+ulz)xN$h1#A-}LC~>{%Z(_)qlpQ;_rh76e&++Q zTuPceMqZW6bA>LV)#1BR+LqhE&(e?Ej(%4Toh|WM*v3BH*Vg0Oz|1vRN>C~GgidY$ z+A)+mpSFMP29$JWu_OqxXL_c|6JC>yOHnNcE?q$oqEfI&UvDo?y>JTQ#W~FX+8enyd*x8K0>@F13l23u<3 zT5m5tJAM>h^-UxRFgo`X(FW^zq$dVoJTgbqf!n_RyH-}Y-OPMh+A)MDTZ6RUeSE|H zZtW*oZyW}=H@UO2j+6X9p8&t`Z5(*+P^I*(@FP7ptJ}oSMsMgW_+)zeoS}1G01aD} z33g6t`e=5XWgor*!*miDyGuX&@^%8O=r-kfiR!aS^+B?#e0*Ufc~VZy*@!!^E8k{m~Fc z28Sw@R|MO~#&G+=CgzuxDg|x35`>;pQ;U2wd9t|*tuXiXpUC}Z2evEsc(QG*rGwQhM2!X}?>|5o$HJ>+SD^VBAm@i~z9CD~ z3GmJTqBQNaBTtUxm71TvsJ8N!l*zMdYZQ59XrFlN>m8PNyCpEE@!9!oc_u2ge#?GE zZOv;hV)~AcPUM4pQYw~*ad7lffDrx5D;RzH6i-J-OM5(aVh_&zjql;+|N2jH?es0| znVKqGpC-6+a6h)q&0%cysfZOy{eJoub)qBd^+0*hwncC|N>(SGKKTNvYJPX>24bq% z9+nxgzV_&6KK%J=a?=*q(K?i~P-%Wy;&mMsltZT@B6FP;vLAV4=FYdGz8B+5kDZUj z`yKzGBbMxMGOX=;%L=#-05~?X3-?!_X75SOmn<*E9XTQ8ayO@-Js1pbpsl{<(GA>@ zZd3W*5AB(VRX=nsaTbA>AXx43e=xG z-HHQ80QY2S8&r(!nRT8K-MD8!QC*2CmHJN$o{~SvhJaJA51*-W6sz}k0bTZk-Io+dM<<^V$4mbjT{SEZ z3}U^v2k*XEyl?>kgNuuJ?!6B&w6K(^LQ-N;yBl2*mIns0(bJ80U#d{<(h^R;`vHa) z7Bk+EE(QjWA&LMmgaqK_A9*S=jR2o<B^jBt6^=QbmKp&9gqsZvEiPhlsG75Ld437M|Lea6?AwOF^h@8v zV9AO42?8vR4x#VqDuS5x0&1t^(HyqT*H}y1V%{xpwaJIF`Basfp4GgpLeJK=)9;FH zw=z4~rg484+tF2AZ>>7m@=6NSFPp}-fNedR=JNAc8`)XB@{`6I8vW>AlwG)Sj_u;^vJ*8=v2M4g$*O!e~BsjaC2eMCz=`B>6FB@3;lF#$T z&*qg+Ecm!#S&MY)Vp_I3pQSf#6Z`yC(l$$fYkR@^z!G6sK$PKcpZ0XoX(&vk6nNsZ z2N@%_1)8IfjY#%sl=YD}2#2P8E*BuZL~puItz6P!r1y?2IX+jF^=f;|0QFS|XveTO zM(NYI^~_3prbmo5EILIx4H91O>%k|-jyOIFf{BNZFn#lOX8%+9WD`sOiTq2t0(^Ap zx!l=1`s68QuU-cS&NBugF`m*Ap?j}rYi{E7U!Ni)$AJc{ypn%j;C&v))y12xof z@#tZ!_V;0abfl$#Z6MtgcxPq`0TLWJcOF23bEl4@-c`fn@og<{j9%^Q!;RTJNDyG} zI0r{Uk06G?3s0O|m0sAuizTUtTS>Ut#%0KicH07j0@;PR7uc>9x&@#2Y- zh3VIOdayV=tmr^4Pt%EB#7$D39iSmNxjw`LS>L3do@BVu!Sr%GWO%K9yLB7S<|)rx z1SM>y`3jjpaJ)WP( z#^#3iUA8#;WbL|&&Fo^jUB8&C7fPS+C>C!aM+AVss2)7~<*TA~rTR z(BIov>g$#;zqp7$`RQBOzHJ+JZQqVJ|Msup(R)`A{PkDx!r%G}7}yMP{-e+E_3wWR z+eTVj>w5FU5Ac`_iZfy-bc9BUBmVR zGnIq3ckkSl1#E|5h{=fw;J^M}TF23y*z?tsIDhRbZr#6!iLtRtW#+-L{RePt|A9(r zee~(_#WD_SJrDd$%3ZDhO0MtfzzG6$ZERv-X}M#Ybe{zTNrI85^EmavN2smWv57A5 z>N59UOFur1mn3x9NH9FVfQ6Cjr?>l{Ycs`J5(bzb87a?D5rQPa$qzrq`C~`0JTQRO z{=Sy|6SaCB6AvHZ%)9R+Mu<&xWtxbMp3z)0faQ+Xa~S|m9tnwO7IW@ua<3Cm)y^oB zZT|Pgwot23HLo9c`L;@a9;yG8x6In<$iC}$T%XkbZ40zTz&uS`SsA@%b+BbjH%K)Q zB1D7$!1ntO5j7e(cj6e9Dr}5Q7S^!wJ0Ig;o}9#A`fmC9G{MT?00!rm5N$LvO)&u- zea8L=rUI>h=LT*2gh5q!mI_)c_2o@AJLLMgzpSdn>YA(WbGNKwr$lSUbU8@8&>2?p zjdZ|h71n2@`xJgIA&=2kF%t6GzAvp#C!e!nsR=gwZeU_=Z~*f zQtbFnocMg9Xk7A)Wi4p)IH7+mBwuiIs5Ao{0eYI!9dmjh66o^~i|-l-jo^2F`*>fX(sE+nBor&Zw~0lL>V zz~O#;F*Rxd9_*UL$IlfnR!CSH8p69Ty?|HW_*29P(7m>aFp(!y$B1hI9`2mP$ERB; zcW@AIf8|BI_LDadt<@1`U6DpC1)NhKiBq$>=$gX;G*9sX%RostRz^|Y5D5?lSRU%f z8(({^av#fJeq;piKfm>WZGuLvhI)5bQ*pI&Q`0*4l}_yY;`nYH$5>fg0|H>6w+}&^ zLGkOG8`xY}1sXAGBmL;DU{qUP=z=S=i1s8cm+M{C9KByWwARX2_2#X(2Fhyk$!AwK z7X@x3d!Ing4Ga3cu1A{9(wPFtuw{8KK+4(VsgQKFs+7F61e9vIRP)gM5}teKL;U2M zUoF875dDATy=jmgS#}=wWxiMYUWF=Dp;n+!*wKx(yU~qqO!rLBXofSxWrh?jj;U}c zM1>s^<*FE_c-HjcM9fhq5wHFGt zSH1T#{UhJabI!dtm-niG?j{f7q29~9d)|A_`OZCgZpKCJvWLZg{yyA)_$ro{mQh<> z4L9c4$wD@R(=VRD$v59c)r#7@auB$f7eXE#=neFW6Pbw=uc4grk+)R3^q4VCz9&KY z^N&w!lElf;?cOL(*6){smCIePX8Uxv1FG2^N7I5}Gbu&kM7<~p_w z|HyTqw-b=qR@cM1E-sxz^$6SKxClUNlLH?!YxB4;JB%Z({h}vwrSizT%E4Qi=K%hy z9G^#|;Y#AXn4T%;wwt%1Y0jB6>CutA6-&5SHg*vAG`O+d7e}tiZ&!=uPyc`Z_E$ zG@xc>1$}q!gQO6-1*v{0$DsARi1BS*k>$=eHDaZv20j4S^D%VeCg2r{I-ZJu zLp`HcZ(Pwk`tE?9inLbJsF?Cj>S^ZOr@0+Cxo1(p@UB6O_I8(b>Xf3jsw#~1_P}?7 zaeUabZ9}I$E!WoKet#d}1HHo!L@(%7N7-+hcL@9XsI_I&9IYp|Zrzk}o+R0Lo3yMU zyk?i>Hc1dwS1G|a%9BeQr}A*bX5)`2xtEqCE)A}5{447qd`!9RGM=}^5h?jS2b}wG z=}s^8C`q7RsGzf(0A-a@(cax~1qc5!*fKGN<+@r-bf#QmoefwXXvE0mM55C+jRBWQ zdheAEtoDsOhK4D?2Oo7g_T;3gqhlH~xz>2wbc)ArHjERMHXTLHcOPkWL zIuDJ@EoZQtS1MI0^J{)_5pR5W8Y`=-_#5B&CTgpzaq-4=3}3sAUE8B=lpZFP032%>f}SFVldq>qhJ zS9?3U+S|k5bu~3`f9orF@yIdsl!ts{8FaoZ+mu*bWGGcO$7a35_{wYr8}Wd*#L{hv5;JrDJZi+JIK58?UB z>Y;}>u%F+hq_L8YwTsI*`m;0m@Z<|vt*I_KFj_X3M>d~F`_vQ;T)d36s!Dut@+GWQ zS8XWBn(KL}T3Z8r!1o;-IDZ)~Jlxo`3-|i_k*`RM(F-7mu)Sq!8i&uEW3P=VE0n8U z z8dXkm8oli3Yw>_vQnGQvyuLAoH_3QmGhCPk3$u;Xds)I}wb5n-iZ(vj)9RbZq=Jx$ zp?*<567PJY$hV4qDWd3m#&M8wTx1-Cpjk34sW=26I%t!EuqqC2P&PT$$f&YZug_A* zaWPq^UBsj_c&JgOvP}b*`c5VTasX29rLO0tQp}cCR`Bos{72&2>GS8YwXF^N26rar z4_d;H2K?eu+$ys@KW_9QN^f$H;;B)QpHyA?T9tLtdg1Lh*O9r_xPypXn|d@UsfGv9 zu=1K=Gg`&;!*)@O0<{($1cq|B!7<369yyGewzkOe0D#y2;wPwB&jE1Y_#WT`e4|c{ zNfvpyD8O-pK3&_t7o*+LM{m9QlebW@nuFteaD3u&{3VY}@r4tb`wqBbMDPq^j2&Z4 z12w(^Il&u!7dUtP2p%^_zd@SK=kdy$ZzG#4AlRlX*6Vl}>FLFl1N&mf&qk{?)p+a6 zuL1yGe*0b2EUf@O;QAgiP5}>kdhzLj{Uw*XR$Ya+Up<9a-h2nywOlxw!B_^ffevF) zL^DRgK5l^H%9u3%NTV-@$ttbxA{oje$HQVnJx;&8c@Eo8g4Blh!7~>@Dzl8bW*Wp4 zJzcY;@B8rlpw6k;S^V%X{sNgy2H*RIUyw$!66pN3tGM)!|2@3X!{LyU001BWNkl6*GsW6F1R-3imH zbSkozbf4im9M}D6qfMO^LDz^&1+p=ZEV8VWP=`&S<8`#Q;hVqmE&NfHgZyv&A-wJ-RQX@fhP$w$q8>Uy_txktE{|K+Av9oI_yOBh-H z*3I4s|AOf)2+Q;^x4wj%k4JI5wTHEse-!souWu;_8p6~RGte!%r6`OI&{Nho|ATKf zl$>t6BaY{*(k4ZAs%X2DT!RuH7s4oXDoqB3unr!7NMd8&FW<7_ zIc6bT9(DQ@wH5$8)&mu3SlPk|?WmVO<~1_Fy@7t**|8n@h+qz- z(0XMh?(EpU;c^tM)Yf3Ey9@opcTp(nqxw45?d==`KJ3}{xs8mSmez9XxHdct0NAr* z2dXO4IjcnTRK+JZqEl@&|I?!KBy1_TI9++=Q9S-7{FyA9rR9?FEa~66?nhVjSh8Hl zkx~~>GD+#6E=y|*KcHTc@zFdx7uZG}C)W8=QCm|pws&`9ab+bjEdZ?6)L^u?2i*@w z0pyWKR^z0SFOw}&%5~Dum0PzP<|n+YdTeU9REE69$&T^L!*}IiOsX-;-XdG2_^ytU zYrBSPwsbnS0183%z6-sGJo;;82_`vpj`J7jJpwwl!PDvjCICu0g9<|0t zb^ZFum+@!szn9QniT6xyCG`(|eX1D!N#w#WYP|OP^%3JZCkkWA=fOFUo}R7|&-2)) z1Z!5o7fCPQx{2l06`VY5Iwv~55BR}+H4zD&=x1MXQA8T@7egN@jh>{I#qD|VEl}Sa zZNAz0GM%Ao))#Hbk<`}Qj9>WDYxsZv!=HxNUOsXZ&cFExm;d+za=#6nI{sW@IRJp+ zSuFk5pWqMcGWgZ6|6E}I&bq+wpNBuR2hQJo0h!v9Wd#`e`pH+sZwDx=9G#QORcq8> z&0jzU85BU=DV~1ewXc-i&d)P(3k-LP*nOIc<3z>AjY2jMX|_r?_@r%zp4K*1`SrN+l7O#$ zEdAJYI(W2G63~wy8+|d#lJ$4Ub+e2tLw%EA8KA{xDhxIzP!8EuJTg$IzjlS3r!&@4SjkOFpIYOC3XdWt% zNQ@BdKK-)I`?NqxxxJ);pT776ke(C2;Wo@v$eDo+BXY-@5D)*#x z^Ylr=(D+&rQL{9$n%6n$MiE(hsjZ18-Qc3%Ba??2{VU$s#Mdb0q3Bn^wG3O+#2<8{ z6*vB?6Yi+5f-g_G~Rhnkg@@CghL?!fJ#bVo+T(dm~?06uW={3UFin84i~1Gu?ssO<7Q z*Ts9Up2Q39o<_~mO1P?MLs}lCt>6Za@kXo5E)S*QlFKBShJd(qq@QbT#<}B1%I@RS zCJvDUQvH^4B?;O+NxF3N2F_i(3IOnL&%pa{|0A5r3gD~X0Gi5k+CIAP05W^7;q2&# zo7q%GesN}&9|`XBL#4@|G}zgvv4H%lsz4*V9F((c2;s&E~Cly`(5yOljr3(py9LnBR-S#-;JLxUn)#{UnQ} zJ}h-&{iEyZHeFnC0xC=C=e!;5mDM=V)QOhL+HiA5@*0Vg)ggCg&3vR(ZQSG+g@+^_ zc91-CqIs@PHVcHV1KLMk8OodI<}laNjD^OA#MDeF@YUD z@s62MEtkJl>l~5BH%1VaG*3_RCRq&Q@UXmRw+`CUmtuoVdtbF6T31#zOU$5V561@_ z7n5VLFVb+N%U@`wH7r+`4``*(`U+RA<6)v}tM%k1K5l%D_yAg`9~DnyQe_8eIZw%; zfa&%&tXEZrIn@{~*94BvRrz&zaL_(6jchIt4?gmsIiheke;Ey+=qKEHjgJ$(%&f-N ze5qND^+Z=^@kn-BWY==VG4!!oSB?AqeYm@Qpro=r*Ts$9yWkXjbdHQ6yIz1g;?phmSUqRA z7{$@Ft0?Ztt<6#%f~8g8IZoyhK}K0DZYw*%Nm-k{k-V9dtEj+4*H*NTO$lkIUSH7T z+4BD1>+i=xL$W-0QZ(}8b7-@CF5%Nq8h!Ee zJ2R4~6gz8r+N|*?w;ZWcNo;G=D)aJl58(8L^SF8c9vnE>-qRBq&11On}_&9m9C!>h2}l@|KJC}-+dvxbZ}@FeBa)V zqo15X%hV&`*rsz+&Vi|4`rK9F+TwdAW!7g+x=rh|q~sYJoiiz4vObxX{6{PB{?7jg zyz)9wU5&TTe1hTo_u#*I1Ab=@kkVZ`EoAjkWwZFfeKuaTVFeW)yNIGpmLh!8iTO5Xqte| zccfNFl1J%+QXAmmFWll2q!)|>YmWy9&9ifO{`AlA;fusCH%b+`98SLT9x7MYarl#S zxb*D7^e5FY@(~2%A&VFP@bPepL3;vHuV?U6Su@3J1!VBzdmrGF=a1oWQ*>}TPJ2JS zitYy^%vwQn{KUH-z;%3FeD)bkbtDJdP}KY20fw&M06c_F>4182OP}tcL*r^{ow@~3r3?PrP=eG>Hk<6&B3(Lp zFB(%Mm2FZv+|HKA)Q{zF{z9cbzBZjZPB+oNsZyf$xg1fqOwU`O_@B~DNh{R`@MK7{{L@iBC__bgCF7SUh>bby6b11sz%M6`7A0 zrguPx%FyTzGK__K|Ae)crcB_@>@m&abaY5_NBag(Wn z2&yc(PHF9tLor3a%8RI6GD25S$9PvKZtUJ=^h;kCz4srWfB0U=>+)3lypSgEZ^ zy+OzwyRYoqha0plwE400(V`>Jv;9Xg0izJTq+chG%*6nSJq zPVB;AZZZ7hGd@6kQI07^Euc;Rpq+l!#d|LX4%=zQAzzWjM<v`CB`3fGjw&31C z|Avko*2e)ZaC>MF_qK1m+JP+%+T<~Lk9avfi^8SX@ z*=#10>L{JGM6Y*!wv<+fNKfepIUY=JE+x&wQpZ5osdP}wVJpd`IGvy8=OxKH98ro{ zm-?-=;DEm=mlC=8K+-tK=Y|eY?0>%iC!a1-yyG~iudT&*zx_@8={rBg^6Dx)FF9|( zqdkpBQ2}Wc#S+9{03M;aTORFExK0CXP#^Z+-gOy|^|c z;aMFEN2N)w%a$hXcv8=zbYGLdNlaxocIhr@HiIRtS6v5x5(Y{tpZ7p+64Q#7_*fby zrEHexM9G&YO?_MH`rGT8u)VGcO2?OXY;@98taoI}a2iQ>;XmgZyb1IGAsyha9WX~W|9 z%oEr6OSX=;q_eG>=R^U!3o5n8twzKjUI%%NBh4?17T; z*U#%Uc7{ku}M_qa#*gf z#l7tViIK3A=-S>raC{$KqhnaFsK8oHHKyCQY$$T{^?ke1H1`;dvyVeg>xN^ebVZ$m z+c=_0(jqEll`f0;S`hNc^RaF8AttwWY>G|cNzh7d4X*9q8#r2q^U2&6Rr5?yDO$nA z2Un5XT8Gx|4%Ajxm(|YoTn>}7vv3>-UG43dnw`Oizw>)I{P(`SA*XFTUWNa!PQy7? z+WfZhQByaR^GpBzv}tqnxpb{hiz7a3tAS0{N<2&$)Q)}iogSr&B<)k^_?K&DwBw_6 zQI3B|x6?TeN1MvUB?FpuJ{lj*W5=!GM5k>4sHv(#O;r_s`te6_T^GHboyf$Ov|s6F2`GE)Bgkd zX#8Vrt=)>g#y*(OE-2j*eYGKTLb__!sC=}>cze}M;&aaSJWL1H()fH_>L|XX>*{v< zgs!{mwes~s8j{r0H&bHeDk|V-+;Dv5bB~&HCXr5;1|yr?I7#kEJ3|r$Y1OGzdS7Hb z(DY;J&#wW6V4a-1b`{lCRoJ_Ihc#_QE(h21#EB`AiI_m*ZAsQPWON zqpyAW6l$xh(KXl$*L9K2WRTq??32x8fD+1*bKixOP|^EegzA)rLN>prJC{E{#CeHw zK$d5VlNCQX`R8FS=%8 zA$?wPdz;iuA?}%0Pq4emk|mx;nA&TyEg?Exw0>txleT50=qY9?dM#09nRvy-HMU%w zXGG&{iHPEf^nW_vit=+CfZiXvClRMSliX#ih}L&-;$oqAr4;?kbsV@E7eD&+43>ZA z&rq0M#Oc2?jr@P|ItF|DV)N#+S$J7;%2qo)K}(dcihWECPnNV3HThneWfh+$dEnAa z#OTQ<0j4dtnKtPfziu;7*cNZJQNo@tuAOPqNV5yoV>4vgOXOo`8Y_7D_B1l$RrIr_ z{@b66p4Mh`;4q1N=Kh1ut;MV@l!nYB)*x3l8irk4Z14FTf^5k zU(>t}weB(?bzDE-g|F9Z`}YVZh_&h}EY;N|_UrEU0r;+i*6CSX-@6;0>td-sIbRg5 zRaapRRRDm|if(w0gI!l{6a~76v&W8NskXH8SBsl-!#j7N;AYT$cLXZ-iw`Hp@tB^M zRL^zDO{%<$0@iD)aQ^V2)DGK#NATZ%87R|f`|_=uxb|=V0^ScU zz}ejn=lMVx_dE}O_WpZ#?bVl2U;BADo;n&dNloVSLFs^ZDRQPf{WwiI<&dqMboy>| ziKdRuxd{igk{`(5L0U)T<}Z$LO*t_606zGZ7)cE`>cuF&u%rsAGqeEgZs;zu%Y@#}|eB19hEUc%AOQ)M?^nCWZ+tK$+qRHJsBD1_v8O`NVWw%5ih_*z0(hUsKoBXhp3zC*-Ws z>L6b)p~yO=QCD>%25Z|e{pb-cT)&3zeC4aD@<~%?G^y4-DUP*Sl!S-lu&{j&=niF3 zwdrNjTqxbns><+G^C#FTl;KFcI8kQOXX^?YIS! zETPf*20$9Ax+mo%tqL{I3)u`le*XAp5^1~Od6-{ZL~}z!sw2g@^_Of3QX>z3N88h) z=f^tpb>cnx)W62g?_AZ)38;ZgbSfBq}e$bSfWz&gw7UbJn}J>mqzE^7U%h zg}JUAk61rXRMKddMM>+7(xuaVWO?!Jmr^N^uIU291>{y{vE?wGDBM_Aha)GC!*yNM zZ{YNt=3?H;6al`TG?67jhBuVlhvWrm7?fXHIRab#zDu9t+Wx(%0~o~7flHThZ(wsz zEZT8<7%j7pFwwacBfUKvDr@l8Z8SfcL)Fr%aMtEl9#e}V)W|IqTz`>VM4#)*>Y-$` z6Ixa|f~RK!_{bvb70@udfJ0}_0}gOw&#tn@wej&hc3-)M+WBP^kcEm!UAerDfm?Uc zIW~?*tt}WHw7)@9hOUEh`3y6u_`xl0X)G#!bZbgc;C8V$7N;4I}plQsF3 z3L+ciq4Vr?OL^K+&t|hYvUeZe{-s-3nP0|2YXw%;)>7p~ICAns92?-ep}G=!vZS4) z@%QZM%T+DYDPy*l+b333dYyTtX-AwPA!^c78d*-u@h*U*TEEAvoC zy7JQ0h z+a)KGP{d>Rbte)%%9#1Nx_=MGy1UA9=3T9+#{IrNOm(zlwzak7{Bg8aRfWZd24vtN zS5bkB2ZQ5syfP#6F4xv#xwaM*ou44Ga#tf&h7SJ(IA66r2O8hy`a0a$w+oM2(`_u+ z=t&*(yVy{_spUOxZbH5y1I|sP(j}F79-AggnYOP{wMO`F;KyT^@#2>4XsgJEd2RAM zj#e%_z|G(LGvL1hj_%u!ch7!;mku34)dn2fmseIWHv9mO-n|R=!g-u{Ha=Q_nt%FR zzdDs;5L?gXF}1pY?CV27w)}|J^NWjE?5si0ufKx5NB09g&G5G$1Y8Hs{+Rpdl`%#uC}8TBM+qae3jY*G$Mvzm!X?0T2oh)i-@>4W+& z#nt2cr`(fy$+~VR%cfH46(5B4l0;E?gEyH;;y8d0G|xVQn<8qqqL=>5U&e>4qp8!+ zH#H(xQ4#W7H*A@To8SY;AOjBtsCa5_m{yM*CZAnAm4=%)GXG37MqFCGCA>Xpu&*6E z$5R|mHuI;!bvC?gUst8JRVUq~sGH?%YgN9+An(}?WcEmH@_L-TCBEr*e3j|o0B;<_E|fC`%5$UV0r|9d;7uAfG(eSFv>xxYKxiNj44Jn z;Dy{xnXpyVK^?~>%|dmRqiz~QK9eN|Cl^H;ZOKFR7>IyfKP-o?|K3~hvga}MJHNb1 zB}yXnwz*_llQzaBImKx{dSBvrV>E6~-&z|l)3Fxke~!qf^k;L1>GwI}%V=xSDLNNt z)w*?j}x<^Ja-rI$1d#MAn!~g&w07*naRP9HxmP$8w z4dLdlA@tsVfIU~P!7UW9*w}y%PQF-Hd6y3!000bKyNQ8YcR`v@M%$(Xq@6;_GJXml ze>ptd#wt2&pMLQ~S?#>|>@#KMOQLK0_HJrK=DbHyDwwA>rJ=R;byQ@ta5r!glIMAtnSF%+_@g)Q-Cz0^>S}9KIc}FqD!OAD z+mQb+Ps4xdMW9TlZ9I4k@4tHkZcQcdH-8mXm6gc2F4psT~C!IAVMaxP`{bVVXM?JSF{2R21u9*2u#42|{X!k>6V}#dCyBtTo zU}+TgbweGKA8njLK{$MP$iOLH+p1XDx zkLDj^U|af^@tm0NIw$66HC@@8AK}^L3CTL5IkVGN<^YGbp{s9Oc;Z3HMX(u9)=_%e zTwhJ5EC9vq#nlrsM^QW`Abi*!-8m?#URw0MVgJvWn)J zx#H>IDp*I*s+z@R)GscgZea=4%PU&X1M=Xaac&+BkApJv$e>XCNT=;6%eEu>s>Z}E z_R|e_t|{nG%|hT1ZSKo*-lBK}g%MOEuU@G%bpY8iyG37AzInu%6bV3~kNxUuhw>fH8xo!9!A{V9dwVL?s=K;E$(7~Ip zF4E4j>v`UBIM4L~H5J&ub0?2*5sy=8l@u8ol;4fn)tP}c{fH$Fl^gO%Ev zs}roPF};6$749w(hIMm0&YawM4DPc<&9Zv zX>LKmD`0qJ1kWFQ7Nwgdi8|Zcv8#Uo*VnFNWMVuqz1{p}QaMJ~hPpbu`1~B z%F4(}Z#b*hgjDox^)g~`W$5}%+}t&U)tcnv+WWtG9Or&AkE?g?psK10TU*-_^Qblk zH5ZT#Id&kq$gNXFBk;nuE4-j%%($^mHts0e9DI{>KYrfD8>(#ilkl-={3^wmWtNo& zE8FXhq9}P|(?;z^D|Jto<*FSLOWB?@8N_^RK4}PxAMfZ|RJkgJE^BQPfn#LeCy9r3 zhwQk>zWjSZTvH}=^%}COKZ|^LU%6XL6zz&$QT#T}Yy9H+4oWBpj>qjQCI?hw8AMYt zk+T}1q`4i(mwonRpQL|>#fPAQ@@0yIVD$JHb-^)6xm`q=_&b~_l@7tIzux3;HPilx?&x7mbZ*`BvUPF>+u;7|Uxu5>05ui( z)~Q$V!`3(O-np|VywHmSJBP|Dw_#u_zIW&U0x~Y#1in)W2aPW$Id{2s+|8%*^#9;q zGHoW-O+!)^n|g$;O{8%&%O6E)IVMd`DxHHg?b6SJ5Vn)E4ilR zq097UwJNCB9EHfIpzA3JuS2^ov4$Pvsr!1~sI+=|nNR9$zIM$lgIhg2;~!)tL+`9m=cs3#=^Lcq+7}(%UT~ zG)htSDY`G6x+%TB_WAYnS;2H6&s8QmCq;BK3=AxBAUE{#o3A(zXeuglz%8|mpmf9@V?7M4TFz}FuCo<x)b+j~-!Q_%7Nf zrnEEnxD*0g9dZoSyjS5<$jMFxH4I8@pO}X4y12W2psZkFuIHim{sZ_0pnYNrp6lZ7 zjsZMsDL?R7|J{4&zjF^&D{CmgMcw=o`tIBV+<-rnN*xoEp~JR{%q+)FI?3A3KMaU# z3$}Gnx?K=en^piX+b_C4I#AK3RbH=HsvBy^K74GMm`1^MvDnxE&Uy7fUEQOjs9jtV z{o-LT3*inD)mgQ?hMs#P;csrAS9303bYS*Gnf9~hbZ#AJIZFSf57}?|ck{!EJ31>o zp{#J~sRS6Kz@(JPW%yH+j??t)X`ZMSDw{aB+e^~t6qTdaoE$&h!VlO-K;1KYVWNX5 zxm>!8Dqp_qIqew2Zih-PFFs#Vt4qXvC5%i=prx@1-O67ihSEJ# z`6NsBW{CsUNewA~DMhuVl!=s9ku3$>Nq`%bOTTXdW7Dj|>qs(s*wZFG1HJ%)-_gbg z9l-O&nBG_+``|>})6=CR-JoGlBaIy@pZ+|!NaDvk>!M#q@hyn7Dve?SqkTOXZEwKL zJqP2h?YP_9kA{T>w2w~~OUb|khXoY>kX&65G8gquh!XJ1Jm`ogz@L#cPL(pxO$JM2 zsDI}*@GD9oQR%o^BZYio3kY7ETPr$3jdab2#j#lxP>Ichl#-Mn`X?X9h7ZfL;x^fYq$ zJbF7jH(u`jduVTIL32Z6iqz(urQZQ5pcJ)294H`VmT8k>d9Q$Tvv+Z{wI8+F%Ch(Z zr@Go&?Ck5q>UwaT%jJLmLmd3|*HPP9p3$PMsTsXT_u$5GC96o?%IuQQ5cwvyLy>24ap~$<qs-N@ss2r4ye8 z@mvI9Z``88Xz;s$Oo;i@SL*4IhWkJM1m8LP z&*1w$e*E441*iVOUq}D9o-3=&_SRN>^W{_czV}1;etDKn<@!lDIXJ?YpE%|C>B@Eg z(O2O-U;V@1Mxnw*W&H+%7dU{MO>c{{kERU+ zn_3}#Q!jRC^UKFE?F2(ipgHnzU-0B}6)P@YE_+HZPUx zfw)Spw)DaYz2fUaX{>Y#mEwk~#2`)|0Mst7;N`d9#rrS66zkm8*4&Jr|MFMx{kPu4 zAHDHoeDl;PG}R}cO6WTd;3%0!uOcbTt6rQ@;}X1f4Y;7E;)^t9fFH6D@bTiZK(t8Q z=Q5Z7HPhNP(m3r@zb@~X+x-o^h8UX4RmayaIFnpi(WF|VdMh1*?3m&#TdJ7@AUD zw+?a1PaK5Cn4cvh!}1`MPEvvg&fH|B3|3hC*c3X(CRvSY%q8b4FlS?KbuNTX!+x;_ zwa*l^G^mNRR<6OQpqS?P@N*xfBeECP!e1TWrMs*x0N161k&^8IIM3kqkW~p`J-S{d zZ6{J!wOgwA36=Ce?_rb{?HJ?0$IjF4)8FW}PL4%(aiKkFH#4n&R#|=pGrxXiqot+0x!A+1B2U#u#I!8m;JFk^*YuWp+px?Zom~8Ics( zo=Y4oO-nZ3Buh&t@Y0wXr1DC2$~Dbr5LfeP!#aZkmaA)VbN8-PZTrhg4*LYZO|^#R zu5COe|8wABp|Kth`g#-Vo?Dp5^2#bjEG~nFM@De=_kN7-swN!x#tA&c0v=9I!gU>V zcWf-$)b%@eka69VPTR?pW`38FF5_l!pt%<>b?ij7OU{$!P~%`HdcS@&EO+<709N1r z1m0S{>@oqMabGv~{H?E|wmO|7rq5QgB7TK)8m=+@Rigk{@D(V5FbB1Ej%b$1HBa5Z z@Oh)CHIg(FlGaw*wP&aFc!k#!H-AleZEjOh>HNA5uVo&NX`*!k?!-+JzzOGyy337u zPN;c0Y`)R!D7y3r^iSn{(lI`XwaThgj@$co4C2A~IL4=^v8A~MZ3%|ehuz!Y_&x@P z@1lNw5pGe#cEZ0Is6(@yum@ZwDs4Gx?xn%X>E_>N8)V{$<7CtLB1^H)J#&sG*C_Lu zCODH*alJ&=WW&p5^e;PBmgSqRr1Wvl2sSJ&Ef4y}v#ddH88=mN)MVl`z3t}M##6M3 zRF@=ydD?>`Y7cO!Bl75nC2}WGPej#L$X-AhviC>ey<$>U2BrJsUg&Vvbmbx5i zm2oqus;tEF>WcNg4HJ;lWkBjx@hDOpe{(t6#>uvJ;_MYc9y>+b1JhI7tV*MS*>D@@ zfi!FMSNup4b0=f99XQw8jLXj)z*-qcfIm$tWHOufvUNV2MZO{n+6Gpem1-`_73XN* z$u?nbMR}PF)+;MFrJbeH@W=y9&ppC(2cFqbIUk%qhn}sS)~JFy*=z`Qvgt?hd?O0M z0Kigy4LM(b^;y02Qi#YUso;57T3m)ZIs@Me+P5CXIJ=q$TypPx|H-AO}CM9(%@e^PBoo5qe|fjR@(Dz_G!}pD2J+(a#7nQCRQ!x zl2&QS`Yuu+ZHsOrzK5#SWFF(XF19o`bgW4F2q($0xE{m*LZq?dMOy7P{2fKn>&3)#r^ZyiEY zWxckdA9qmV_X2qnD((Lzylr(1SfIDId505uA+Wn5!EXz*n9aZR77F5w%W%g0Ux;E-y5O7 z*so;sc^tTS8Swm~wKD^iD`s#Eu1ni=eE#v^ zgyAsN?4a{dgS>S1q8vxP95olo30#KQe~p;uNap=|ANlw?#c!%+3I(DZ$@vpiN<5CO-q6k?Sq=t*Py4<>;&Web2@I%b%uWl)exD!Wi&M z4rl=O?ih?s&Yx-2J-vm|<45_*Il`<1^D}s;fs$(Si5jggE*$q2w1Hkm$9NJr3(NJ63=BAWG$>~Z3 z5wt)%wo1JenY3@`Q7MvJ~+m_BAdm_M~(qUj+N9V8@0Ez zqWx&{W|AVCRH0Q3=n_~NUE3$8FxAoig)oS1lmJV6>+jzT;r~tvje)ST08JwZ-q? zvz^EIfM!TjBaj9UN6p)4<4v0UrI8&=sM77&Sg%{o9kaY>zG<%az2W(X8M>dRu+eC566(Ns=&SeeoK4oG&47c%eQXg zOUIu#qHF`eXm>ZV>v?qF8x_x0^-$L$(%8qHB2%Y*i5ZCFr#1|h zuCFbPoAV<2=YbT5QxVa8Nat-`Qv~>G}9#s7SaCn ze|-_p{oE^wr@&p`w+DN!Tw@V+9jJq#d0a$~jRNTugjsZ(yD!E~jgg6EWDoVH7lrdo z9LH_ROZ()8X(zG!{w;EG)g~sRUdlB_tyL{f z8o|K5^7AvtlWDUp1ZH`0GT+Rr=aMs7-%oJ>@ia-^apdSj*|YOS2Vl40;qWKtaQ65S z%(S(kP{K(vPm^j^R*=o-(fwc){lj;WLl&8}0*?Od3>^44cl0op>ua%ET^$)28VI6v zX9|U4lxe#a&|}w4D+RaKQM7F}t^xS~GRQ*(5ePmmJZzbmLdV1emKy4D{>ZbD^PyvW z0z=nt6`g^}8cAB6kJj-SY#E<|iiHeB^EN&&l#^@Vw4Dvx?H2bOl-}jR#okL-g`bfk z9$i|crLc44&A=Ux_4#SD4w*#v_z8ZFxX(E&z51v0BKazy(x8-swca|?Kls>1^`C1h zYAhvhC70qj?qYKw&a;;ZeAZH4H=s_t2)-$&^uRmID{>FzmR<;ZX7YE{SFk(LBVv5KAhnlHpXo_Dj!)HLj^v0wA8 z>CBdZccOw24(5_XoscV+D~Gi``3jYPIx)%A8qD^p#K3a=w2x5OZn zhmW$d^ah%g&$tN9&tfEfuYkj6&f(nA!>Jv&>uPGz+SG*c>1kZJehsfa_q;V-_3A1r z)^g#KBAY-Izoya8s;-y`bj336ej|$k`v3qS07*naRNV5?(``h7({o3ar3)aMh`!~j zUUEF})7hlGJ$49d=2vAz-H!wDr4#j6E=+0%UobkG=L_0rzvQB$x_ro`NB8Z3FK)8R zK9o)l`>6U%vze~u_#&-@fihB2pi<>gsLWz=TSub9Hm8-E8k|3J2*-c+F?=|Ib4j5f z+MojW%S~uC!t%PwhGDsqek9}On%)-9?BjWY&vL1j`G5mFZfr_-tWe&A|GV!1zxExV zJ-wr#tq?^ZRL%O;M(MMCG?sUsL7em%nV{pBq59sO3jM^G~57i{<+AqYRZw zj~5oOp3kAarWXF(3YH#B1GN>%_O@>72HM*CI#$=#(A1E8T&7J04=8SC>Use25u5Df z^s|c>u)Vt%yZZZ4@H{Mx&0=kA26Out(43;Z0I;;Of=_SV3Z1rFo0_oP--h*k0Zvmj z27CL^-LVzxxm>F9;;6Zy0S_l9v8A~=(P?|Bz8-b+%W!iX@Opq@@RY=Px(&S8Aw_hF zx@2mcpU1w-SMc7cld=G>zJd$@FWgoq6Biw>7ew%-R+>~QUM?3a z+wP~C879WH*Bphb%vvN)j%$T&9L(`D$0OdDC9yESCeuduz-I6?+hVptaZY{i+g*7j zy7gHZyj4j?E_pxw*xN{d#^&?!BhvCTa_l7zrWMbxb6s3_*v=HM5APhrNM8?D*aqlq zK8J;wX-saFFZMZ(kDWJep?+?$*rLE0MsXB?A682-6Qpz`GbKmD+;kZ=#>5S6Ts(@u zCPjpdB0@GC=>S08;u0F>(;R6H_~#$Ozn#NMUq7bj9^urntWmDA!@Pbgbuq zoSNd(JbAp#>qx@I=~|Oc&yco~c;aboypqc2c#PX&bPdrHcB|FeYVqR47o8rAk6~qP z4ZHdWQl)p;Uz;4F_}lUhw+qVjI-h;AG(J6zsoy(|{_kdiuWtn|kHf!k8+hTwhRdF9 zbur)Yq}HLDr+PFlo75sX%-8IT?YppESVMib+Q^fZswykdH_!_V1gC{&eNhQgCp5`tosbTzP4c3C|hTu5#qQY1ife?m!X0J0o#_gS7g0DwAvcQkzqn zXW+!4zBy1Qr8+?P+h(8f;KM2S*mvm)uJ7HATxGOV6aYAmgA>ml!bitOuytTtq~jo` zN3AWmxqApZZVsbqcCN^6RU5b-p9x1yuA*Rrn{sdq0Z08&xG^3tOMJ(592#YwCkiL( zbw<@EQ%2!oiMPngVWxq&8(in}3+#VFg?44>Kz1Y*-4~k?*W9bVW$q!3GI8zj2qqCX-env1kP6RG=5<_!6JjxcuQ}FS&S;0)6 zVWT7~XnKm`YGg0lI5~g&c{oSe+mHTKG8~McbgCCh_^E z&pqNhis!pfa$UZ5eVwd>Rrco6p1XeH1d8vdgPr zd!>6ny^4L9SK0;C#*x`<+B8^d+F=A~{uaEn2yY$Jx>7`RXqTxbU>`AS~#FztF;mESM`g$wb?s2TbfMcL zboX#aYoF|eKK5o?q|L+DPV<@?mFQKg*OiPXqOpiAf0{IAuYKdbjndkmX%en z31+JtNyZ9Y0am3)87d^Gh=Xq%BU!3lV9_&D3)TzMIfi(b8(v&3^|LO) zMY)O!d~otb0Kl=2K0)L3V>lii1VV?Vd=Bfm95QYO)m2sSeLp->yr!xeZV4dyz4K== zGdG9l4jjbVAD+X9|M35Yb7&j3{FCqEm%jWu0AP7#1=UqmC6&9nwuWprgKQ>P9}mXI zarOEQeEHx})ONO{E=Q4m47w!y^WYRWhia;-arxFw)YepEZebo5{@qWIy*-PMdt34P z3ooW>Uu#nnUOz!;UqA68-uOqr)T2kJI1ohEADNiI!>LKUa&%*nqED7!h`W670G`QR zM90HPaXpE1N=Y7kSNS-%CJlf~SSg8!lX4|BjYjay z>K2dzy{+z`a&-->)zup^hGhx`RIKOVI}X;WH}7b8x8R|2eLeW$0BcoM@GVg;X(GeT-T@8&=p&BSZXElC~is%q7taX6J|6V-rqcTk@7aq_KD~^KH?HHwLx&U713)30LB2AJ%zB`+Q!H(1rj&Y~9N&1X z4Cv3nZ(j1+?R7-#uefkYHYr_mS&81b)tQ2O7JZ1;6d`mHrJ&c z0*Idn*X|6Xb4z>hg7DNN#-^sw+|Yo*-t>+(E32!xaqk|U*}V(l7E5ClP#x$_9ox2I zb!GwA@7}@gf$gcw)oG}|A6viMhRzaB#^R)qsg#P6OkJXsHRNEZu?sE=$RZCg`wwYw zILyf)kYQa9$FWxZ`F`=D@7{gPY-z(%U3q~M z>Xw$U{q`Mnj*b_dF7%hY<@uPpw&-iu^l?S;u5|2Dn%HM+@3pU+($d?nr(bKOV{BfF zt+jDjq!j!cca1Qx6Oo6fmDoowh4gkhE}d)2GAgHhiJ40lA8zPq<09h~u&Jyxc4Fn@ySTAZK<{&Vv9+x&Hs5sn7Icn{qh4HKoQ&M;4wg5dM znv{u>dq?3v)3Rjh!Y0nsF(Q$P&68HF?1Q}HlSDO0je|@>8m`1~GLV&t>16wP+ikyX zZIZZ)&oVm}ld&D8#ZclB`ki4C{Pk^z5bQ)2!WMw#R*~yywgfp<399a3{ivtJ`K?4= zan=q#vOKMhx%o5U<5{j=5KZyA3)e@2F)E0BrWW}m+9-)mpUr63^m##=2))#y+Xzi= z96SSxcc`w~C~%I`F|dgv)i2$dmbdgt;IOAbCYDa45r0v8TOP^z5H~u}mIq(EYg*k* zNoM1eh0yWK6;7~@cIBC~7x3w`2Qb#XaZGXe%sI5q&f>=IUAVKObZl3#zK$=w^)?)@ zD7`%towd2OPB|g_2%hOXTZujS;6e8YzW#{+YQc8mFyw+s(+D5bM5!BlkP zfNLmj6FeI)ypsvJrw@8bPVpOV*Qco7rlgdypb>H)?znB!J9wGFZ_)v&&t#L7A5#|l zVc($L;pOq?1MND;jZ``xcZhTVL>|fERiAhu8-Rjfs8`s7yDA2?8hestK4_F}nvdP@ zfZE8%!h?$5t)z}yeD2Wdae7*P_Z*7Coia0SLdV-tpHhbtFt}1Iz2Mayjp#dTd$(9}!(H^LA0M5q|fr zy^AK(z9aE`5}CHsIQx`uTr+F2r_r&Ap59(>9N9+7F;eJvqVO$8xE!PCl2Gc?RI;ww z`C5&9X4}^VZ=<;ztt2$pBzZe@=}j|T))35TgnW%YD!3R)lYq1N;mH}#p1XigpV^O* zo*tw9<&b=VNv#?C4jb3X0f$~#G6ypnOs1Kv(P`6>tv=gCw6(#USp3o3a@ej&;H~#D zt|SvmP#S%~tLfuv_o*jx9Fm?BCw1%vO>*8wg3(kCx&HF;Q$SnKr!xUnkAze<;4BxJ zY}3Yw8ztiAqOP*&ZP3*qZW0cJVIgD#E_^r+aKFC~*Y}pb;iS_i&mF_zkItfXau$A3 zQQ%@(y2~iFhE!aAZmCELl8Ny#DR1Pt%HhL4H);I1BfPGfNwqUAxs_SqcfSpEriq_++`f&EKfR3J zt)2MVODD0sx{BZbvme1*&*PWA_BFINHCc}rw^G5!iG$B#XMaB~WiG(YX5jlikS8$z z$8WxYZ@hd8txf4S+ur`%bmb)7 zx0Rzy0R^)O6m34ap10wM0XuFFW5>2n!=G!&ISe!$Hz~;@*38v(mRDazK_Fa z&Y@*yHZ*|wMfU`H`<^?z16)&)Tu&kVw1rNhJ zccfd(o)5p^!Sj8%DbkPjbR(b1;Lw>1jH9Sn5d|m|rt7D1E5l}hvE7SqT~wMVqfj*I znv-mYG@O`ikht13(!`~Y-iS`pC3PK5=UBW=HXLo!@1z8_eUBpk0t3}WW=@WC`E|-G z*Dd|8-?Objj*;#7*fd3L2Dg@yLLXD9Q|r39Zja!&N^u2sxTgybg$fsAecNz*XwbUG zAI(3;gNgCTwvKmo!iR%_;k&|dTiH4ILAAt*OiVy&<*JZzAn5x>M%iYwi5fGWp4)}^ zD_S#ct(fXa=VZI(&<=FB^`O4C20MCsH_!`eo9$ct_(+)+TqzalKV6D4E(iCXR?E|1 zR^kmbQ|0LL`9#_w*EFc7|&oJ6GQ+5b@y7b({?jCZ7Yhm7bMFx{#U29Tn?TW;OMcbDV)7}1q0i?DMwQw@-=ntS~NX>K4gF zGuhOFxgA;8X&hq}sEAOXcdA-jMgN_3?qF#sn*?KZy&CF{}PtHIaKZJNOal;fZ4WIG(28F z{o@5gACM=~@E*{Ui?bY=qpj<^{5$7pQJ5_X+4(^O{Q+9Ub~0%oe2JvrI+; zrTi*|#Bn5_cpvRJU2mV=Ho)x@3Lo(CbhNSK<7UgJe-zeG_4530jbB7h?H25A>J~jA zY0qN_t3E4xPwGea5z0d<1(g z8Kgr3K(OE9c^;}$+L?!U4kGVn(SPe6d?4ge)Ux2O!qw`!W3-vKUVpK}v<;bD+fI`I zs+!fSfShyNT49e~u2zUw<`V{h;gJXMecu`+$fkFwz)1Gz7^fek)tIG?DVm-hdQGA@ zj9qS7eBPP&)jEpi_Kvv5`90wY2Od0R;G$5pY$+Qum9JjNQsjCC?7nghLpN?G}AQw4un=rjxP9qEK_kV|iY^s=E-@Pg2M&x`%tbF; z_Q=-@wFJf-qqQfsdwqTJp2%l!M;J1F>2lGmCz@=sC=PSjXKoZ`(aZNO_v6|W-8R0O z%=>aJ=p(Mr16|Ly<%6hK$5FPn#mRWC>+`TVyl(v^O#M4AiR#la8NG19xd)%G3Y)l4 zuW4|3K|MAJ?|Hwni;jeUVC)#01yz<>}+B=eM`txAfBw?{mj)X^>EJ7Kg=f?fW04PpKN4fJkcfUW6hrrU(Tc`*y4M*@Nj$R|7Y(_gDlCi z^q|k(U+fW?5t)%ovuW#-gCb1ZoUgwckk$sW_{7!ROf}=q%LJ$S5{_9X&*}X9zy|cH=L$*$x!*0 z`IAsfwqYJDsv|=K1Ne8o`EC63KmJ#>pONiXlWV`som->qebu3V(S%*2FWUNq?^pQ} zX|rWKA$u#ySe@y+BYXCuktDcr_bvcnu)iO_^^I@gpB?;<@P`kV@Qq*p7B-HLcZ>%B z+<*TA{P^&PX#VwI#o@pCZ6pJI`0;=GkC6S>-vPeyjaqSp`P?qNaX1ikRBv|CL}aq z;SVV3C-T>pWkn6qavp-3&h&(5DMPb!c=c!R;fG&&V?~RkNq8Va?!cFW5`eU?ObYXJ zd`a&yQXG5teSCcE#o7y*q-?r*3kOb~#WH%3EVl5*_kM^Uzx7M?-ttf)+b>_m?(-J` z2Q<;hOW`tn`A>g@pML2Jm>aG)Y5n?7-ofyr88p!=mcHppeg73-cEBQZod+c%@F_S| zsJ0WL*J*Yqp~04C&m}rz`0jGviHKHTmG~))m3>qf!qZH0wVk$9T9V&T?ij;MDx42h z(J(EgK$9VwMQNh#)L+Uyhj)mIwwynmB0-8>7cQZZws7u1=Z%lzxI~m@5 z^>ZD=Q%?P1DH>8sM2?wFQWzbNk2ON~tN60a)5>~Id3sg6%hr{?7K#5gKlFLD3@-;< zs`{4CZDoDf^3b!oCD~^}!+;?V?8oirQx5vr=lvLM9|-qa&5d;&_Dmm+nOTLuaJyUa z5eZ)}3(wyvUEMllUvYr&Oq8DVS{Yis4cyzj9%m08D9z{W!U7&VeuSzr-ksQhp}9GX zK782DSqwfopI@8FufOA=H@!H3^2rvIYjNfJmTl7KE@gg5TT01S{3)CIGV+BzSaaYY zMn_iR@a_RzzjGT~H&&naB=Mu<`?|;TckRFb{BU5#NGnIv^`0#YBQ1k7-^-sUs~^gb z?xWSnkL1DQCpdlS0(NZLj16noVrh99m(O3u^xKoz`*;5aqNIMkAOC0H#h3r$*D<(j zD=z(Ce}*f+_cr$Z)vx9^7g|_;?;3vmkA4q3{_cN>#;W03ao(Mt!ZN+phGg9k(A(W2 z))05=R=AeJ@yJueM@Lp+$EM9#zh+HWX$%bv;I$(!a-92po4R&%6l+IEyNdT|EFyGOW9I9|umK zLEr8r+}yIct4+q0ah^Jhq?uy%!^eoT470<-wR!N+>>RdTxrVJ*u0wB9wiE9Bu~x3! z6YCb{_t|If&$_WMb$w4YrVWj3mxa~$pQiLa7WUH(>mtl8%F_ug-0qxrMt%};OB8P> zi6sh_++Cv}-^0=&3J$Ul^I48Lo8EKo0;b2;)>^dv@_~c6^_%xF|I;&Yx1Rtt)_~pG zya_|Ib6EBGNwM^aQm3+7>`JAOScowpj|fD73PTe5u15#Bo-`Kr`JsLm&>n#9>*uZ5 zF&6qQ=Zkrn6PL`XJM3|s3gwsIwnJ{Kwtr~sACk~QYQ}Hc+e$A;_w>9a@rtrhL>Xr; z-?@DP7oOa~#{SiyQ)FdrF6Q07U1;aEVo{vD~OSn_ec#{LrSZX0& z%CPC$Ev%k?3~j-5i_|_O0y1D=b^&ntdoofqkSu3tEH4&$Z7j6#%1_@b;u)ElLCxEfol3)|@0UZ%%KehhNy{aK6fI}5v6ko9FIibWBB2$Vht6?_^;y>X+!^o!z_rDBxjpSta%?=X%i^VOP1=8YR>Rj0M^&JXW{GGD*ewdhXF&sc{A zlD)Ka?>q+mlvN;QPw9XQ0mv!2QACGnE)>UzOVVBef zI7xyuNrGvtOvq&9DdcBtMra~D^dNOvW-LQS_}PnWUHNOkLUzH2mgP<_BnwN6_@f{G z0L@mbW7xi>CA|LAcaXF)H5uaftnP*>LYA-l7Wlj+WYazy5+>E5aAhr8#}o!9^mKqV2c-m;V^8z8C{zBS?CC zvG*^(iR8siIDPGM5$4Sf+gtzuAOJ~3K~z`Y`fAq$Z9Qf|>9&ap{KhxGi6ri9d$KrI z3sPd0Ymo2dsnUzV2Idy=+E0FlpMCMQXI9?PM~`sy{SVQ%u!JxF;754p3$L$e zQg`3ENo>A)L)c+SO1X_?#ZZBMU9o9RBze&K=s1+negWes0hC3z)ch8*wv5 z)XE3KBInRpY~uAFzk>uRK6?2jJnrHId;r*W;S#oAx{9Qkf=+;qdG%j=uK+sJ{)&FTgoDxWI#JdaywvP@iP$*I7yN(X7O1A-r6MJfD@+A*rEo z{`F40qpnX_iN6dzuuaS@;APPXmSru-n(s`ocyo2QdOTOgTc<7S!4S*SxMj#(gix)|k(n`8W3O@!Ep=+|`xZ`H zH$SY-udnOsJcdGtm=uS#8zwv{8&qQj=GV^bGf*c z(;KI%#~G^ZY^Y8`<1|uaU$bpc+Z(c`{`e2+w~kMGJUffIYxi;G#trl|8hGn-uVHa% z38yYz#Fh;kOHM|n__=5CHbR+0U9NJ8O1_7lf1cwJPbac}eo`sck?PtAwMA{i%luqO zUf8=AbJy+z_h$hBYgVtu7dG$3ANK24`4qgkh&N}*ajS)+$3Mge zpF4)>@wLx%jP}S!Coy?&AMR~fk7iF#*U$GZEo0*5ZR|Te+1}bjo>Ox<>0QV}=+pch zwp_iA?N_hj?#2x`cVK_*MbSWxyT=|p#LLG&K;|OsJ2MG~2oKkc0RWc!dNJSSI8~CS zSTp?qFTeKzGUN+IcAme41R1Vx--?@CHlx|wQ+e|C!2AMsT)vF0S8s^PEndW6^<@{j zYs3<6ms-yNM3_*Y|D=3X*%*JFaN+Bn!#$glF)H@c3Wv?V*}IzemWPwEmvL`@OwICN zi3t6onH?23i?nSx2;Qi?y$!6lIY zTdvIE^Q+-Lr2ooLur{mz?of2&Hpx;SpXK-GuE! zV~E>hI9zhJi<#;Za;%#4O`B|`hV#WymN7&?5sv$)Zw*2=LAOGEU0Z{CqEqs1P1QI- zb-cOoOfM}Nq0L#jl^A*Q1ii~kweouQ@@4e(_F(7c&aZNpbxgI!{a)sfzH7^tqcCeh zt4bU40-=pJ{&~0M?Av*{9&77jo8%vG3;lX7Kv})`8^6W*Jizo^bs`Q zCjGpQTlVGL?j?&YtXh1md|#&p!VYLJ)J4G)$hsEKWWefa9WO1;rn1?%=z7*(JSN}2 zz+TLWl85u?FIbLMeA@d+%&y-Gi{gH+t=uo5@JMMb}Mb=EJ%0_pYvGTd98ux_aa)^+&?W>;iv$~W%I8y1``%a}!>EwQy^lfnqpP>yA zZ(i%U_G7STX3wwjov!IJ;WX@1Tu1hfQ%{q|WqevEQlG37pC6(qJNXQKM2J&mu4m`< zn21EId2GC0fkXM>tymKj2pyujVIH`~VSbJ7m!@3MqCcV%c>OBh## z!rPFxP3qsaw}f*MsoeXV#A=p%cqqpq9@D)yrrP&&ZBesCSlmWrpVnbCHVko^GUV&~ z_Hamx31xmlrIPlFQM$&AHt&4wt!&q1rMXwf?F}gXa|;-nn?v8?A|mH-Y4@%`33J&# zF@d3h0Sxr@1IQ0BICSzf;xxnHlXX&OdQA${dDgXVF5#t3?Ua*b3NO%Ilpp^StP0D5Y-uj<$23 zv^+f-uYQ&W$Dc;Fz4;o{!!`pN_>|H&C zov$6j+QZw6YpXj97S)m7o*wjeIbkS4vWD@UdY~ld^(pP2N9kKwLek36LZdyQ7(TZ| zlbAX}9+`-cL@#!LBmdBOmJxCwnq(eJTZz*Qee;XR5TkE) z5l7$q5GP+c($(bfzO$3qeElXG%c+{Ara>O7$EaN*-pL)e2cpQ6=hCy-#O`w!u=VOS z+~2Ssk48ta_uQnXb<)?++&p?0mkPbPc3Khg6AcoiIP}peq&?)PsV*(;q@lQVh<{i+Yd5L^Tc2Bm!~ddZN6gLT`5A zgex>@H!EphsDH~aok_GW<$f~syic6VV(m<@tDdR$-XY%7z4-LHEUrlW-$}1TIsG;r z%4$D&+G+oUI)(EghhLtZ@SOw&I8fLXN+tXqx#@62H7zxhL4 z*|P!P|83wa9Tsl48VxKA3?LG{lNST|!*+D?O;}S}I&tQzHW-SxJgq7XN!C^_J|pnk zl(cX3e>IPmxd>r>n@j5%{o1eQ%Ar9r%g6mX$@8CKzBva6V6ZWOC`wE@<=~K0IV&F% z(aRc~m$u(y93m6OpVW`k^*YksxQgEvJBwvb{5y};_dea_tCQT^vKbD*kq=LTCys62 zwAHJty>gNDtV=^n!ONfNPPBgg-<{;t#q+rKkG~I>rNAqPkftdbNrGSb(k}(W_cWX6 zS#GKtqXEovoL^U?;ocr@eV?Q}n~|rwgV4`Xs>*-v4VaVb%RR=uh(1*-0E@Wc?c8AO0motNXi(_m^HiR(#*LeFye! z-_h0c8W)r35m~xMeI(zs%=h@MN56QSc>mdR7{5K$-VA3sLugzfGJ2KmQd@0{02seW zuFM>XpNfj#$KHJ(??0o3+mUnVUt9zn@ZyIb*xz5gZL4=VKRHOs(Ci$J{_F!WITg1T`$gD%^#-=PM*i68@JkH1NjMqG+E5?Mgg7Kg$fAhD%AF*bhc{}-NG zhl|)8g?UCDSxKqvGu3ktVGirhQuzEMlyU@JGyGH;Tk+Emv2ymC@-A;$&hPMBUihS7 zW}CF+LoR&CV>>3bjIbFaUG{tkyIT;H}8 za1IAgoI!$CdqGfMmPGM#Tk7ihrLwxUz0cm)zb#+T*Z3LTQ~mKcpYN6B)aJ~VvmQbX zX~&P#=X+ISQohI2;WRgZ2`kTxjEsfkrAj=iXgQna8vOmy@&cC9MKnOC49hkzYn;b_ z$W!rx#!M{8qXl3zLd06~-|^P5W( z7h{k>g!OmtSFdsusKI(T2U=BS2V z2=RToT=`kZO1wz@c+1AYIexndz}jV9GxUr-;?QDBT9i#^YSWlW1U}K0v4DS;CWS6z z9Zp%{Azd597*C;A(iQkUgXdlkK4+Xb)7zH2=Wz;7tw zGNNs(^3u{=KVv)E`eR3|tcN5oDN%+jXBc}(eQHZZPs)YWvY*=)78-?d>MGZbj#u83 zi<`@MqeT+7WZIuv536l3pJN^&RypII!Lzj*&-oj3WUcDo+5_nt&=%f5-WV}@ zT3>Q}$M?a~zn~~5r|Nr|&TL6@Qz`}3i1dL{3)N^vmQ(ko5JrUhpT(w{|Fw(2xqbV+ z#QI%d$FfJ+x|MP0))KOgb+7p))Tx#Kwm1mEdoo`6e57)3ISj|qDIS}q&aeNwyq!qT zC;NXWTv;rUdQSUL--~m5v$oP=WPPWTFSlvQlCg!5zFXQ7-gHG)EaxG)zsW?)N3rIF zeapbyBE}v(1a_BZ5u+okFgmgdgY)y)cIGUQ0TVZFBg$NR&5&KoL4C@%|ki;5wA_Gf)_OBk42M9*Rq<9DVo z`ruIztGFUAxfq%T!6MM&(!nS59>(%1y&rF?`WBxUp1&+F57jrji2m6{PfsZtkOK<( zRP7kLy;1)46pj7JoTFVzz7|G8nqc|YfKEQDdoo@9G^ZK<9U`;Uyg}xy?3wE4s-zR) zwBaK0KjUQoIiF@TzSamOj6j$HN&KpFqfZo*_+L|GnW7!SU;>Pyx6+WZd@U73U&-<5 z_`NA?AH0gIJGTe&Z%VUu6w$x7AIq!yasR=Cj^U*i!W_%8!@2_}mJgS=sSsx_$GzQR z;!vOT>)G~Q$buV*K)U(uL1kY>qT54cD1YLvr2x8Gkcv1YkK`#vfk%ePk}f zH+FmjYX`6uUmpgNKbdC!vka{G9dc65~2?w~PmOlI}u>o|fhJ+bLfw>l0Kz z`Wk!gXUjLF<^kR&V%v#dHeXY+UHg{Kzedkgk0X?MPJ5rf%XaSb{QC9##g|?Nb{xm4 z%a;(xG44!H;oXxb@Na(g>%s6lFI~p2^OxG2nrR|SPHN~L$~EoZ*SVK^%;3byPrl{& zG$cHl^=V5teZ_%rCH=0?b-R&czx{8i-_fSkX#5ZV29T^gtz!od;n+VsRQw(tS%rW5 zo8MY-d@GU2IYgP}Rs7P-T-Zv7$||1`+|1>tt7LKgQ^-F_iCnu>!Bh9UlQ_%TZv~2s zEs(EtmSYVTb$0LTEROW+FZT#kFA*ZV^6qiG|LV)Qw_(FmmAij&5nuW4_t8WTQp9-S z!xM;JbopkYD5{J*&T@>hnd{|ak@@)7Z1|AZNs+i#@wPPIhUP7rmH^W>eb@F? z@{~?KZ=24s%)M9!I;cdBM1}biRmAm#o&%v+#Fwr&E}1ceyR9SI6t>KTv(@dC2Wo5RjN7qRc^ndLW}%NC~j%# z0KyO5%K2+o@#MQ_;P&pvoh?I{UtFxUAl~NK=I$3=Y~ShTxpIUdt%2>cejk=2FS!(@#^q(FQpO;(R_5^N~Y{2bB3y6lqzV>fbOi zkbanfN)+MaeEn=Vzg4`(&K3F|oZnml5x4I%sVy?Q%Mq!~bEtkoVl7Xou5CE`O!uh8Z+T_+LUC)GsWs>K zeVtotS;E)l^Ez~he@IUed7-7>)9uAR!LhOhruM0AM;T(S7S53$Kg1QCmaYez55C48 zK7WGV>VSf=&@~4X#{+7%pG)8TBDPNhdy zw^2y{DEo*#2vQvl5pING6Dv(1)c5j6R^4&Jpg?wIS&@{IZbZ6~+4Qx^s%~g}kHc2G zZ4M_pE9X?Y3teUlopd<;!oN=DDa)F;KR*Qk*fKOxP-1SdoT~1wercqh{I1Tm5Nb7% zxNhA=RPv0Ua`)1`ajuiTg<^h6VdJjl%%zJs^}qfx_Pulv+kbsi?cCV3wSoU^NV#To zsOoy}PNE3dxp@nE8a>$5VQ|8G7JLq5xPCdDb|uz*$Z(n_e0FN**@@P`^N35saIHmc zvB{=bt1D>{6PcAs6h+vvY4Zx7{_Mz_=?B<(;S$ECAG8;T>P4VF;0Bl)5qOV5FFTZb z$NLtRvE|wgpuITwX=L@|$5{2`2_iV$o|t&*a__i&1zWFP!@yj=NVe5z0QC<{R}wjg z^|$XLX=ZAIwTf()lNCP<$Dxr5U1u7Z14~9n`9kItG<3mqdHl}(ymm8(#eqKD+pq!C z8M<1Ug` ziVRV)@S9G#)|&^oJ@U{DztE5dT=Vvu7Hu$Ux5^k9`sS9=KevPo;nURYfJdH>Mmz6% z`Ez(E#>c4|z0u@*;&~N2>=weORKL{Uvf?k5Fjl)XIoJLv@8Q7;pCbAQBaFa8$hAts zh`w6N32^!Es_>oZep%SgQl5{p!3V#8$U9|E`+TID=jiA3Z;i*x(2KS`zEyJSyNrWE z+IFaWk?ezUdq6O^S_5;7SpD!3P-D^d#us;C|3He#t5-UPl_FcN?inEo_loiX8y%*q zJ=-3qIb%5AopLDi<(#yE9yb@|}<=ne-KIxveHvVv6=WAM562(X_S~d{Ymo)I} zdw&f8&=dCt%Hc|WQ4aL57PY6W&`W6G$PPoxh8~yD*SOrFvOSHkr;y_oRbly8 zhNL~2&u9gRAcv-&wGe+RA7`@q*F)+&HT3*>TFBqS)3vXo3^5wu!N6|n`ta`EcdTYYa8N-Jz{o}GmI*QY0PgrQtW+rAYp!y!+vztNEq z{KhYTBVRc7b1Yl0UB`jbX9e=NSUOhv(w5Qck)Pji=Pnw@TR8r?S3a47bSeAJP9kk2 zxUl!>H(I~)?s1GwKP)Ei<%Zl`sz%lNaqFC%p-ZLF)f4OWgGyIrU}0E z{T~BSo_dm|#c4!bFLW|sQhcWxa*zv799n^eR3VNa7iovikCmKR_hYRe>q#V64tW5H z{}8wz%6m80>0TW!THcfVT$SS@opPr%y7d;;%ZI#}^S(*^t67WIn-gI*9$?%V-nc9= zJM|+vb=8Tu8E;$kt}PRP_b0viEevUUbPAxwto#N&siFM(iywWA)9E4H*xGqf;Fn%L zhQ{BCaQfnfj$x(b7Q?ni+v3Bu9u=iUX&B4P=$al0;A58IZaxdW^&B zoWJSO4%zC;@Tz2gW$i|f_V{Bjb_7P3wMu;NDLtUpzy0VXU3w`2S<`$o0qc7A@F<2G zeVA!2VtOgT`o2MxgGktTx%r1qMU`(~W9Fq}d=y-!&F9JbwC%7~ zuG|;+V}C2i<=q*~CR3Q1n*~rkFKV$@l|)A0viIt6WjgPiPMPJgwwRG%Ra}%eYj5%z zxxaoLmiwOnAxhNe(#}CqhX?;+N?a_WY0@ z9u*`MDvu$Om^c!5LgMpLz5I-F5JO|>5VvyBeV2HE#=&tBKVRiIq%QfI4y_k+OPua| z8}=gr3dEFur-j>eHY%ej%7Kq3css8a4jGH@Y*T1fgX5!Gs~+dDNJraA_Gqz)zltY> z^=du6*0H~d6-7QQhq3phRh3v+zVm{RF0U!$I?C%K6Z)e?-e{-9src+7j3;f)>d?;1 zeYr@q$bZ9&+GB8^h(yiX6sV{3Jec*5x-1gq`gOo1mVH}VBj5g6ITfJ(BWN4_)sJD!&Qg(tInCbn)K?*l`%*FW}o8<4mU!- z^M>;u(uFifA@gU=U^t9)kbXFMJ&7E8^70mSnXn<6`13CgN~ zYIh5QGv{#P{3MR-*^9p3UR=3#6GH=oST{DN!nGO=T-v=0Td!P4l-e_qEDV;=seav- zxf{Mm-#_^_9u^-2)|GDSsdGM1D=*qYOF$^~t^p*S(la=>fGsy};Kr8jcF2F)lB6lN zU(Qb+UFmCm*G^Ak$Hglczdzju2|Ng37kcKxx{Zo(5Z{T^y8?LhEiPmGrK`x|7*}@g zSkXyV8*ksi$m1ETdh{4OE?$9)BHY>dbSG|axP2D`bBo2RKu4a;VB_sOU7zILXtl8Y z@>L*%nqV!T;Mcq7Ebx*ZH~-6U*k2A7ffgv!t0pM~Z#tpZLh}@LT1?D3th;j`5i$(T z&SUkXM<8l#ZPB(X*U-PXsPdheNo4l(dEUmR9%9WDoph^#GfkrAi?w-B!7fA&wZ~kC zG+>Yvt&ro++EZh>cGxbl#-+&oFhJ+m-$d;JB0g`x4jX7X3ee7GohmO_$jg&JqAKz~ zVWi|#obnX%NaSBH*w#qWlH^$3b1IBQ<)5x!3Z>rJ&y?TqhI4c(c{l#9%*XpQGR#@R zR5lcE2ybWt>$4jDr1s@DjGbI$)NdzlGstr;s6UX8pz|>3Z4HE}$rtgW?I>8Lu&iA@ zime+bFnRR~mX?W1f2O*NO7@i4N{`TZm$fbMEk%yg413Q^V)uoMxV?Fz_M-I-ckW`}*-5wzaIFYUG|)nWr&v;lD0SF$ z?H0!G-Z%J#`+MKwBH~sC+AK^9v|GhV(n(P+=71K-x#NM-$NYWHncWf^$7XUPp z1jk-Fg2q5E<`?}pw}r&w;%c$&f{}zBt*|lrZ8gO6w5~(pB4Pb(&yzj7JY889Ta#R> zNQBY8D!-eFSg6d5Tv-FU%{xHd19`^)RMV9Y z?a_LZ%bY@dnN!l&o<>5p!J&1+c^y$NgFh5lN#_K}1tVT4NzahKXYT@CNCm36`s@}6I=hdRy zY#mShyhb%XJ5rwyhr(;y9I`ERPqGY+WAnRl+bTxwCD}atMm;-gUy0i(W#HZq5LY4F z&Zig4yoAcBv8wN5sC=>dZIPAVJM?$iQ`oArFDgU5;kZb5I$r%2T8+J>hszYJpx;qj z%e=M6KN^5*L)NZuE!cu&MVWof(AiH!=8irKTxy6l8e+dv(;Sz~t6lI;V-3FELsn4p zo{-(JyeCf$kPEjX*moRr>a&NaR?yLZ8*6c+#(c86*p{#j{b%0hvRTEhEmB zDKye#07*Juw3l>X3|a3WTnuErJxB+Kk@gQ2X@^U$d5WApmOV*gYt~AnYPC%7)perp z%Kqy6Y0D98JY^PE`)S&KMYTp2kCt!eHZ}o}g16fcn@{plsiwo>_fH~%E7p$%O2{AC+-`b0|qmlspKm)%bvKstGW}TZ>89ygg9f~&;hlLxVJ9NEM_wLll zC=RE7Sr;Gr&DXV=a^5}ZN+S`*-VZ-R;mHYFSFH1uM8H_zYV2OMt-W|bmYYi}ml5gZ z9SnKphhwlyzw0gBW-}1lGgL0!0`_jDF6GJLOTE3aWwLMk4&3_YQD9_b#c|ZtMJK1# zZK`FUC?vWUNw5{pI|0xHAxcm#&N;k)<}`M1-G;v2UMwswq9-sp-Rf!J+=2breC-C3 zl=lAHKIX%X^3pLJs@8KI3-yaCOu4F{m2a8DLbaI{lX!fxgF}X)**R>xa_#48(RNR> ziOn}|V&B9e_uM2} zNdvbwZ$jFrpWpR&?_u|aix_%5iwrSVJ$j5?=Px0PV%*!%0#Yxfnq-{GC4xz(X={V%M zNn{%*KS=`sG5CaQxf76HKS>MeIhMTs@>28tvHK6P=Kh1i&V^nVn3_pk0-p5ATLqsQ z#HFUe59+gQP3^=mPp;bC_q?cE5@82A?Td!^HI~x)qh9a(6Md!(r;Fk_IlPjIr!__+ zA^l16&#$QBAv%4Q0JjDkBcFI?`qx8^VgB?`qRzgpOe6hsY z{`1v5#>QDiAGJJdBo!Xsv6NNjkcYMEEZpY!B(nGK>lEzr)3AT$UZ9CO?c`!ODuvW4nRmq#>RFLdDvX{%g&3%vWl=uJc z#MZUW0Yv_6{W>HiCduskp4G9 z{LfUBH@~)jvowrX)MxM-I*TqZt=;fDI9LMep7qRu~b@VJP3%(QLYb23q z&+LgTf65o)wGmC4V$IY8yz=gGy#MO4t~W9tJbeZeH*ce{)C2(ZE-tOOyhWU+&S2xs z+en)E3%q-mm(jblga{5NUVNc;JV~13<>Mb<^@B%1syE@1UgYGwKfd5^7`MFG_dvwz z06=d51bERl;np0Lrfu%e>Gv!(5ic!a^VJ&|n|e@Ub$RnF0Q4>`qi=QzbaD058Uk+K7lp2V`8#gZWKbJT72spKHtNUZOp2Q?jqhSIuT7#}Yltb_Z1=8%~O> zL7xZPut1m_+Zb1h-NIaeB+PNkSfP!tx@6t?tg7(UT*Pu;&Y8Ru1;hJwXYpzkW3I+- zy4K3ZKjel@e(f^X1Z}X8i?oXkJ}T!KdY6{b(>}GUlMM9rW8nB5O#bjaywl%@*I%gb z6Jum*qB(9`F&)Ms6@5|Wv|8*4lYB~BdKr%G3EK*}oQA^tp1BhTvAOr{A^j!$Cfg97 zEy=S-w3JC|%!Z>DT;3XO9xYe3<@3i4tR8)C%$6_o&VukLZ0hM%w&vXXuw9qFJa1ER z+e^iTKjMY&uDI&68_h{=J#o3UHOQ}N?Pw0-F9`{W)vtVBUen_h^+YrI(0v~@*iny8 zGSJr-oCEDva@!!^P!YDb)GnT8Ou`r4m&5Fng~R1NlKYMB6LwU+8;SnPE5NZW*uP^Z zE?&Qmk0;OJ%~wAc3`>2fbDed{L$$5&NAG^VMYpm}o3Z?b+0;(>e{CWB-tTX>;s41( zGJ~PfK{`B%JOI~o{yWFqbX1A1CGBbKHJv*y8@FnEs8Ly5{3ORHJ+9nXEAcVmb-B2l z^x=;ia=hBhP#XFa?VPLFUZ{H}*9R~8%{9wQv3b#U4Beme9LQNasd;%t_D$kl@+!qC z{YyEb*2p4-f0%(jJX6Q2Tc`Dg%%|i5QGVU&+#{$N`CFzfzv=O3jevOJHpLN%D^BHz zp3xr6mQiX*=SCyHaA@}VWqzCDl)q&gl)06?h<-=vI+u~Q4(L4Bv&4RXlx1NZ$#($N zweS`_Q;Z=TBY&6S4h|K1GBRb+xS*4FleU+x*!=jotsFts#UW)nD9drEWlBpYjXoQV|-#~r!>9C;&%<+ana(VZ%ovQ3kNOTvIW>6Xh z%9VtBp_HqPPnCJF08P4v5TUSOL0`{v;Gbb4OOpRxYR%)vx8Fl=oM7wF1|)Gqbvr7v z)RS!>T7Uc`bp?*Y{?-e(b@zAbFN^NBb&UP<6x(vE!`5}Bx!iyF0CQ(F}s0K?j?vs`+M4cy>{dr#_vzz{`z%YFH$|YYj@>+ z-_iQHk>_Qw6R@zMb36UC+wmtY-LyCxjF-rpQn2>JX@-L*&LE3pEcf-|$?8>D>gx;UEpiUyQ&WHg_MbV2!P$8Q zWQHHlV&9obWRafisj`U<5#lVv;S;A2rCA#sCB@{rLxjO6^EmX;sT`KY5z;t8+DN>3 z9U`oL^cZ_4&x;AexOn}uGrH8TH0BRazS`VN(nw+SX+TU~nZnVKO04Q6Zo|_A)JJ#< zo1v)mDP?-JL|-qkriE&>t6C2u$#{Jvqj%h=s_n(5jS}tmPcg{jrs=K>Od=SE&=84T zR3S^Q7iiFZ%AJFpxY0B|tTO=6Qy=-0Y2j7<^S|I-4dJrzKvx#{E%nKR9$~RWTkA-N zD?=i6d|W4-6duAUBi4SZA&wHtS(xjT@tN{?s)f*RrhbP+6J1WrM;jbdh`3fEG);n; z?LO(%f^sGqk{of6y~x*j)dJt=C7&*HnVFx%wcEEbK04Mp@Ct>QM&0lbb>xe-vGTfn zHiGlogzTlA?09#z@?>rnam_`d^Miw!8ybY(62|R5@=|x^ua?f-I6Sy6apNzpgtRBo zrxV}9&ugDb*pUBsZOi2lqkn!8gLCuGt1!=8Mjt)GzO$29_2>y+{ODtxeBnsxhTAF` zoSj4O!cxJ3eLQXX8|##;IWM}S_AGf)K8}>68AcyGMC4r8i?&A|&!Dl?1TFX*eeejo zE?mN;J@rpe1b{fpaOA{EAahuI{{ecITg3um07#lCMjp@9ifedw7JJTLfXje2_a7j2 zc1(f!N@jFtC-Eis1tdE1aj}Cww~KfaPqXj>u?Vy!F9X^e%K0fqBRz{vj4nO`vE`6R z^q|ipjYWH)6Q<~GPZ8vjO%nMIC#@&@)-KJ9Nk?fhuBGh&_2{_Jg%cW+uNv3o;@Je5 z2g++CN=TlIYKWM)T!?4UosN_A!Q5JUL_dF_F)6v!P;c_qy7D(O!;8z>NXxxhPxOD7 zW$JL&Dj#3c_qET{n49CZSN(j*^kwX2>EzeS z?rY@7tw6Q|3Sl`Tb6rMy)+ZBR;O)ac|Ewk3$FR6(6w{9$cMK}+S-34l=EKi*FFyB@ zB6)ELwMgrPB1eoxBNL9xphb?x**?x%rEu2&F zd9bff8Nan|>{%#g{f+{8zG-OWT93}k@VdSdr0BzPk#g34m!P!6dA|5PiE;aXT5v~O ztZ3;rkK*dF2hxkIJ*{WE*hKO>%f!P{ZR4c&{q+N(o{=F&Qg}vA<&%&%UU?N!7i3ZQ zyY7T=MxC;i*>3BnB);~g?3xRF5B<*5%aEYa%>is_mVeq&?cTZ-ySHwwe56dTww-qN z@BZk(rzvIJz3$V`vJ~}NUitV8i^Q!mcDl>fl^6!!Wv)klB==Vh=yy!Y`qrswA$w_NT*sSR3hpX z%x5kC(tR_;X?(=sZ`|Z~84LMwhT`&n>&=HNm8d{&6h9$kx|U-)?yqG_+ASvLoQC*V znCscP*4F^3w|bnkEKG<|mTNrJm%@E4LIya8*ku^Jb{0J|4>5fDZ4ABhBe=yDqOIeY z+xH6Y{pw!>+Us8yw(dh~b$IQP%ya+Eix@ilK4zxxV|J#6{lEXaSbh5UaOYS58sLEY zzx-QRUbh)8O5mbA-?A=v^_!mmlQ=t!)3wc$btCbgw6fH;L$~Bvqr` zy!@*hXqn+JYv_Ksx+1&1gn%JB$Ku5QApob%gx}Hq(6(c8E@b7&-<(Tp=(Wq05GSjM zPp2v4OS2Ro+&_g41EUy96GoTWH+{C)i3D{o?MXs9&pIF2zsI*RGXJWx3^H-|=}fq}9`qQZuedDJgD z372xELVdPg8|mEcL$>Kz%S!rI*)x8L>a@5#ru^h}O&~N>&>sdBn!NC^WP-uD1-$sd z$2k7lD~RAQGcvNG3E$@_eM?K|TU^5E!$&xH@(h}2z#+z=4^E*6Eu21b2#?2BW3j)# zbTKrLPp-ykhCP!Pu=ehh*x4m_dC@{yOYr=j61AuK^8s23o7gtxv^3ZFp^r`@L5j17 z_T$0YweaZ#5T_}Qz59Ot%3;tef|>Y7$j~>tgqMHzf#)a7M4v)TuO4m`aq`*V`AH$j zfEVBYC@>s?qW#bbRJ355;*)KQCUnDuxf~hMhb(v-&KDZU^TCLR7d_HcZ4NHeBJLEf zeZF?w{wHCfrtsyGiBPia)E3xclgBKNFE5|e4-N20y>U8xRt7&Cw{yj>pCira;RUuu zKJJuln(Ei5R7A%u0Y@-iAIZThC-t2evMq$#n@mZ^mBHFId*XIz(FqSkSlnmPqs4?0 zwXQ_!`l&j+K>zl+MJRP0f0%=mahj^U)DxXw+5ag{>oYAOrfWX!)TwApKw*79YkjdM z)J}zyIfclp9WJp{o>>c>%Et?9UpR{!1tyb<%PvOJw zyp6@Clbkrtv~m z+$%zqW!QN04v^(uEp2~f*%}K?>^ps~GG2!WeT$3OaO+O{xkTwta$&g;*|%jf_Hgd? z$WNrcQ|sq(#QX^dxiukf_XB>>wrjU~SNzYO-J&;(%_T;ai-t+``MDY?vqojU<%E0n z=4Hkj^fcoLSu)x%DVLMySHtZ>BCM>aC(=8QH2B;%Ds<$tS=~?kMcZVn^jUuvC-^fT zT4yNY_I1gBB^M93L2Jn+YL*%pW z8dvxuH9oJk&!94#%~y!i$~YKzGcUG$SoRN@3-SpL)HgLFkuQ#ye8R>-pYi)sm>U_w z?TLwCd8BMQx(9oPGTfP-!pD>6@Z!Ge6M<}cT%u5$<_b9`maSUc_8ZbdIAP_fomht8L>lnoWsVoN2G#vbYuJCDQ4DXt30Xbf zUM07zIdR<~L5d!2{4bOj&V`+~(i*TBKP%o+m4UXWvVWJSp0n?z?Qz;m=!JYz<5K*^+w9Bj ztcq-NW!^#Slky=~Oy$>N6{F3gjL$BB*Sgg>j>Fn{K&WzB%mft^NeJ&t9-0+xmT|J= zgt7*liHG!J+mBy+T>b^Rt^Y|hi!8EnsXRF{{hy2=XWr2={^=mx8TWi8`Kb)vo1XU#*NK3g>pks2DV+o|=Eo6MwBXYqC( zcLImezG3{Ooo^tC@H|vw*rWo^1Qf_dc zR_etXfp$iBCJ$9$t)4```4XZd)h9yBcsutRsz>Xh18E~5dI!=xP2gjTGgO zC%VE!q>c>s_v0^ol+-2Z(!#NQj>In}FYN4@0Am)3O%I7!g3z+ z)+a!5`{Sj|zUQ_dSr+RrIUI_3h)nWA=14rlImy8&#gd8gI+dms2_QLreyawx4q7Vh zL=HoBLX-Jg521zJ1ZD|4@B|8jX9|5<+LryJOp>B*Zc=npJ7s7RGx%a??Jy?5T3UtkDnUiqnvU8>lCX@({z1XYtB=$MMb=UdLj8e=uJpF~4R9zCV)Ts+oe- zO~^KL>u_F}$XvHxRG$PUuUR{5?Lq!Mj@Sb+1NLi#7elhAle*_`lHZ1Lio_a`_@C0Y z^`X;|6HuQ92hf(tmeFn95Qy~DJwduf%x+1!$%mOn(DY{dt%)>Ouc&^*RH>ZZQptoi%UzmbmKY>?%q>c zvU;{A%!jpIEb~uw_4?;S%6w`!TCicAYNy1I2;l>o6O-MN_+4)L%s<0VX0hYa6}ULU z&CQ#is?5(*Ry}@#@w-#S=H58Vu;t2iG?N}QdmFg7VFTud%QyOOzj76EnqkW zALBLVIH}<8I(}Y0CO3vtzAP$|9-nnhc1gBnw$`Kt`EqO5W?Ol`h|ogLfqBFt#DqHO zP@hq%`JQB2_KY+em!80(-`w8xk~+!%@-{}N_wk}aV#IV3Z06-IBogP?CDf9E>e>ew z7y2AlV<(OCW0RshiCkMb%}FDrCoUC@y@Ysh_|$wK1^TrV=CV=n-qT38Jh&=`Fn6fK zmo>k(+@^kB_&N6c@~Vw5^n|}b&SH#E9DcY?{I`>EJQ9aX9#7#cqvr5Y@jTC&$^Jlx z)$n*H|IKaZs)tXoH`repJ0`Z*1{5mI$?-`v_Jpr<{$p7LO}hSX zsUOQUsx3;W9F#};tIuEcEgn=DJtCg}23-3n7rkAm)z`p#uf1BNx~};uE}S}vQ-gyT z-gf{1FgQ1lm)`%V&|3z2O9R>(%f~%aIPmzfMykB5O`=x6U2#}|j|Q+TqgBM4w@g!=Xp$zW8izzC-7Z~ zNB~~AEjKmFC9Iqdir*UPz^vWPDu}GQNkJN|eCFK^vrpeFJlXOkCyD*Bjb;IRn4MkqeW#S`y zSyxuS*5j8UCEx#9v`6>tah)L^DO;TbZG!XrD%F!MGik&2>oETc=|XDMhN#cgLiw_3 za7bs$<)dZGFy$SaXN_^f_#~7@=zuhvi@Y{sb2WtSb$mYVqBbEHxY~ZtTuI|M$)Bvf zU_FNF%5uL@f3Cw5t3=mrnUvLu4rBWc_e2?oLt}9k!{^|hDK zTD=z8-~h70LAV}1fP&t`MCtP!t8QD$8^j6F%O^vp0Mda$O#jMX#-lI%3da8Ij}SGN zvFV@xk4OhbF!hz+z>}B0EK$+oEQrfQiY$1i{BT*$E0 z`f0qJy&AV#fHw0aZM;TW)LtGyd+E34sIugg6TYjr((3mc<@d|{qGZbrSu|}TA)?oY zC~TNC5!3hJg(2y5;$xYC_SHkbml5>o9q+_z~*&1^j)($pE!fgjH zV17&JBje%aTBOG{z5V#DU2h?u_oN*K(tOAvU00+Wx6K2E%J+0I(I#jbwNLT1bs)R0 zgwLT?-~(w5idSlcpH^HjWp*?)7$L)lzL!ZHM~LGXQO(z+x+uzDU*ISwu04$dG|}6x z6=~dDaZT=8w}#V}j$L1sNE1%=m+xB9hTMt2c@ImGAZjn2eIB*?`(OWU{Dpt|w}Cz& zbAWTs)3J*p{OHXu<4b?~XBe1Wcn-OckYD#XKitpv!s}`&bIaAwIPaUh=W9z^Luq}r z1Jv>4(|01D4*6?~5p~@#BbTQ*et!zDyn7rA{r&jC*WL<-bx~A=56RK@Kg61;>7p$9 zg@$x0RxWg6%Z>||vGc;E!a6(f;y0SOYN4lnU7si>C%ky~mk$!y?x#T8Bk&pdM3?g% zwb~)jwn*eni29TDkf&bde_5Nu@ryqHv2cX-CecOTdrg{=j0yiQOY(w)WG-%RZ zo8pqEYKJBX3D#xiIcMUQdA6jK@d&*Mo zKoLJwyc*ZZMIp9)wvG9(f#LScK$<3eX`+jI1=|MpgMNOr$Z}+=B+_y@lLLtO{2>U+ zzdwBh(5VG91SRVslt&HH!>82gHWjL6TX(vRNrV}xbUR@HU;NV4Go*DwS#D7sM~IW? zwr+c!f30)gWcw=5i6yQ+!s2#9EJdSF9Y=_ZFxC!JRqcmekw&?&-SLUB?I$`f++GvW zU*sSUmrE|1p|+d|yvq0c=N9qhAN&a4{pGK9^+pVr1?to}z(MsXI$bEd)K~WtK9>l==*jjQ%Wp%!DZCxV zkeO82BUi%w{(k}33WQoE-(w9&@LQ?02;8RZvLeQ+v>`ROO@lM@*nRFIT1lhh zBC$F$G&hIU4t|c%SGFX;>4j3#YY%CuLT}Ea@fuwp%?L!_2v5#uFRmoIL1Mc(Z39GZ8~BKJlSpWJxu zAnjI2kN$Q4x5mj9%>%S)I8u6}51)P$Awm9zE$#ta&MN)+x}=TU+DpqGXE!kGICKuA zPVLFs5-C#urmd0r7G~Ezx0JV)X*MWxZu26`sK-onZds(}tK!vYjy3ILLe7b=FCW#} zMcei?a<*-WVD<8J*huTg$F%mIea^CUKWEjvhVO;MVkC{8 z%G#d9y3YG9IWze%KNmh138zY^FA`5l?qbUv%C}74qIN*e56O1MHbL4D$_;PO%Y8`N zo?naLF!JyTcAvk9ERJ!1eYFoAA05MiojdW!3>RsMrSQ5V|%BWrNw%_=B$J` zGQ@AcoZ3FSpnmj>03ks}L-WIfIDO<0o~&L~#M}cQ9vQ)We}8d(erOQyf9@Cn;K;`( z(X+ISs6DPi7%OMMbofRDdRHTj^hE7ZBdIZ}0eY(PYKaN8n^x}x*inWxt&o9~sMhg5saPey#J;EcVHb)rXY$R}F_%=2&b z1o6IDUC%(9qKS1=ILZOrYVCRab`r)qE*LuY%2ieiJ~EWvL~{WjDVO0)n?HU^reXP? zp1YDZ$bp!yJyko`Ij5CB$@RkC!^gCKUO9jAx6D06d@_b`KMJ8}I^?X1NtEZ)_fS6S z$;0_`)*)Ww`@XRC=Yvqn^5;t!Mb~?}Tst!FRO4D3P@(mc<>_*5YgCp0;^SLnj-;OS zcbR4wSA^S;ZA+G``54$QC*>fl`%HwEt-`L1(Q$F9C1%#^2Fdq0!FX~Oqc_s|s5|_d zYgf*~L9|^RaoTKeaXW;30UNb>7iAKmY2|YJdOSv7qI5-e}SPN{w^+j>DMrH z?3db4W<{M;*Nx1P=J2xoRoI;wvbN`;cx_)TYge>ZgguQ+mo`$9ugPmK7TA$z`uIE9 zUcIu#w*|JhyCNR#>-Zo|>l-;Of21-(BTTtva=y`!+40?WWwl$2}EacN3De_m7aE{sB%M-UHt+w4)r=#`59jhEtJ`1rOz6!+a-Ht#M>XV_bzVq8XGk-$E$BGXVs}e->BoQnSAc!%fUC23@AOHu(iUDmaIiAJ*0oAa@c?WUiaN@-mx}K=se&s55pT7WP`9OQmQWIbK&i9l(j^Hr4e;=-H-;Ry9@8HPE zld80o_oS7-dL#eM3$|%-FrU~*vc6Z;lb8V79*L(rJVWfo5-jtq;u4l#II@d@zKBx2)d-mJs5a z&pG_`%JNgjd+4r@F~dD9)Z<+7tt^!7mD*EEbj|q+<;jn;Y|`4ILmoDjoGO$*Zr?I4 z;v8hJv4dQ!C0$>#m)bD$y1u643x^4{K`pZ7+d2xjM%z!JVxX%&cP?AFt>X@rQQx!W z(w2zAN$;)SW#KQav#3W}Ls_ccD8qr(ThJdzXoz!BIahfJv!d-1uJNZ*nJGu@{7Pn~ zwMb7$+^hSPt;5LsZgpALzIH3N&B(q=sdI?(JV-y&NrnanuzCFkjIJ8#81~_sFC9J!958E$a#r*IPvLnO~^V~dM zy&BD)p5mFlr6r8a%qX1zz`;{zFfca{%e`oUHJ@ObA0Dvv%5`kRwRT!scMka*n40a4 z%yN;oUT~~Ej`lEQ%Lu>7H|XSP5>uA`jj@gNNA}H6XfLLNN;fTVi9~x;i_AxC+Yfoh z5Xa^vzZqz8vmHYxDdWEW8>jSSMA^iI-gv5chqk(0a+);Zc1+g^JtjqXLYjPP9Qy-0 zpFY(0oJcFgUqhRHt%gG$FQf+@FX!PWsMo*NPxhbSBnWM_4Om`$=`C(n0Wv`x}#wQzgtJ~oc8^U6tnC}fMJf8(5lSfjSp z@}B%FdzsJcd_3uU2KJTKD%$VXlKQ3gb7^~+_W2UCQ)sqdnnw@{kb2RzFR@#>gzT(l zS$=sm%anTLcuImZdoVrTdGlJCA|6 z#Udy2yjI36+S+P#%j5Cgnhy zz3_|qhr|Iq8%I}p0~S4N@my51RwV`wg^pCHPVu0~iS(qDBes{?7daJ+#tJfZ*}E+x z(ViaWx3woyzt*?<*g}t1Ykh?9yybT?ZEfE)&Xi(nGgK3Lc0R;*%4$sONtRY(Fdtd@ zXoySVA1!5hp8Z~yLs>IU=t$<)e)mgkS%7{ll%i==ul#Gk{kF^zydwCp*=CNfj zv`k8-BXKpQs%uZj76q=8=-4$@m+|?yS&O!mVSeHB8p@M=w&(E_2CrVm!1>eYd2j_& zU;9nW?>LCXod5zZcDXj@-HCcscqHxzA@q>7~54FM8+-9iQ% zU#PJ8FAbCQ1ebQrG)SvWqF!{M7rtuKSq`CWc|xIN1!|M#!xIZzw4tUU9=XH-(A5e^ zJ>Ok;j6b^h0hZF`HW7!4S(iC3zU7jirb>F^MPRZEO6^e7r(yG0XqjrG4iuFG8r%&# z5eN$#!;q>9O+m!B@zK!p6HnFzqnOP3MB;nME%9nL+C9`uyn^(Ad2a7lz1DQMS- z2Gg=M{<+usepP9GZB~V-qK~eqKl(1iS#Uvs-WB@PpsJ<}^#Y9;pMUWs96NXj{e6Ai zJzpvzy>!+UNvAga^DUj-ZkeV!YcRi?FB49MRmkt@UJw`dNuFve2gzxwFDnMvbK4d- zbKAQAm*doj?ze7{B^8qFq>z2#FOUluVx`gwu=y zIrD9kZZkR$npAR$nV#rHCm~X4H6k|-tPj*HUp z)AWT)Ep=-}qr<9rI(fu!+YH6*6Kfk!h?D3X+jKjVot=G%f0;%}6}#?a*ko@Wmhg1Tivv z@XE`W8ROrtGQJ z61FHZ-?sgQIDuti`LmRBZXcnA+u@WsZ{_!>H)u;``Lf15vAHL`hvvxaO-PoqCVv0g z+xV+{-omP$K~WaTY-As0d=euPxgeZL{)^rsLi(~;H^h%+p9(GB_G>?MZ6zX0Yp?4% z;}ki!PTiCKNybAhFG*7j&COwMXs9$l+b1?*`^2W&`Iq%ebrGplZM&}%C&yi7L;bqt zc4N7UwCOtbkYCW2UHaZI+OLo=?m%=n-?)+_F@^>P@%G0b;oEP#iGct|me|a{NBMiU z@~qnOXF<5%=u*jc;`gmiamj1G<(9Te;sVK6qV_}zZ)VOp0s;#c8cR*Q`u4ks;c)!b zW0)TrgkSF=n~~>h@8o%GxP7Uya&hbCfgY z+SY!^G$d!|vdT8W+%9XM{#+)OXH&|=)u}vGwlJd3Me=FMd)Y?$Z&1<;yY*CvMNhWg zv~Q&GLb@J{T<0<5xRNkvRJ4Cikw#NxinO`EOn;hxNenATZkz~h4|K2y&|hk;k&D%# zt<4C$^jvC{w+A!AC@YU;P!e(SMq`avWXp|Ii7i^y2#&ANR(Tzx7X56forI8}Ur+Lx z(53~yZYlkclyT-Ni{1%G$P!x(gr5m{WB*y(!vG*^Eu%621j)iI8uK$4x_S9dS|9F)O=J?vRs;@>(CrogD6XpHF`0>c@N+mlH~;~Ozg(o&Le1! zZbI7I3l{@fZ$DZCBdUCs`RIFc?kcQL%UR1?zJ7xItoFB25f^J(Vs-7~x!rSnra0Lj z%XlL2oJZ~%WV_653XSqQ)mA&n%={ew_$PmcfBlWOFt%zH;`Zje{>4S~EiWVQ)pABL zw^Me!QvRkgTKsAIZ57(~tvx?c-it##k3A2ME9*H|&8>azDKRy*H^vzJc1NGV@pde- zV7YhEn4M~s$3M6=$<{5egz{>wi|xy-SBU`g@cuRyi+-eMrca6|qpNUb*UlBaZROUc zO^DMBJ1$+pz{~<@OB;{y@EZsD4n!V9I)J!WNBnV+&UQ8IeLAPqX;F!0^4#8>cP)f} zWX|foZE4TetyoxG>=-VT+d5^|I473~++*rJFQ0u{Sy>EqTU38vAO1h~-Za><>pBnn z&b{|__v?8c&;z;wG#Vf#V&ni21SwJ^Ma7aVOR;SINV!r`MXridNu`piB(79al^;%} z;-tz+*>OeX#3idNS+=RcVk8bAMUWUsf|$p~JT-cr`@MJX$&Yi_{l2yKI_KWkXh4*m zjcUAm&e?nIwbx#It#9qK_dZpxhrM696B~E#0sw4Ww+1rFZ^q zil+fT#-@$8CegN*bchi+0ug>Q3WEIgOAW0IH*6U)phqcv9ck85!v1=0HK(>gJsj^w z?9=Xrqm|XzqRsx4i=bnkNYi^^i-SCdkC?tHXmQO8dyhVqcq{Xy)?T*DCy!+qDJkV? zwmsGXX{+ATc|I?}>AE~Bc+`H1GK;#QzdR<;l9fm(>TcdjwyRC&N?mVjq31E?wC~V( zoDk!m$Y*)9im!nlOM8c{juEW&M2?0PYv%o`{Q6iyOZm6P+26M0V*=*3 zD^}r4yFP|qRbj3&HL0PBq8#f#4X}AYd=Fmbxu1|Hty+r-?^KpLuuYn(^6XiaZS3dS zk~b0=_*#y6_dQomu-VIlM#6KK7O>*d!c2TV_sU_6>KY%r=Gqy!APiGo(P!Gj#<{vm z@BX^$^1Vf8i54nd#+LUK)Y=HOZ2`l?YV>gH<4@qJTW{`Mq|>V^eCgBo;#-eC0-!mm zZO#1rOzl+AWfN@PP3Uhf2AEYJ+W^K-SL)`n1Wi{47ExcP^Q2)^v}1NXL~s1*VNQ70 z9Fm~Mpu{OcfKaA}CSOG^O!?tUMD zMeANo7M5Y`4OIU)VVuh`f&yFc?Uym>Lg_eZPana}E4>M@;U^)@zV=|JwQ-!AXYO7k zY;`V8UOH3i^m9hXW0E|vye>*tnlTjCzn-?rqv!e~F3v9R`NiV;Tm7ysmNx)uQf^)c z)Q%T=VNQA5nBmI9GhLA9``+uaP76h>MLd85q-3Tvv`6W zH8zdPN32{PdonF)Z^!#O z`=pxT@3A%B4vqC~G{RtM2}^?ky3(NE$J|_#XT#cc_-kJQQ-TWs03ZNKL_t*i*%`S1 zAgPpFOte7D(W;L+U5PPtc{IFj@O0wV4zbknUZ zUFyNd$o$>Ja{Ryb3>QMHEn;5{(R`gJo;em%+ZP1>(o!^PT|w7&;iYRJ5{bsVsbRMq4cXRWPfJ%x(0ZI>N? zdrbrQMKR{i``5=?CzMv-n{E|H(|6y>J+lOe-4{q$vGHZ`L$$boi-&#=XZP;K!pb4eU;Qzhy5&C9y&i^h z&3yfE<*Lv+znGdairRJ0ono}*AXgvtc)t>{@s;={Z5nIA)@0c1N zWSZOq>I!oUi>Odzp#u~5dOfTf_un6X_dEEjU-%-{%+F)6w1h*?J&#>)zJn!+dz+0u z`DtHyRK`}ve>tx9F)^iWlJH+rqE}XHWHjQopg8(R3D+g(YP;3H^g_u7PYpwjHvew< zZ9$Qbvtz6bcU@{(HnP0TaxB?y6}{yxdsbz}zo$2Dz-!lBjd!lvRn#?WdUNj{RCSF# zue>o{xNTZ&zRnKW$@t_LtK^DO;<)rOVjh)WHv7R8tw+qA=PU2ehV$E_qFHTJ?jvKm zZr{~-=jhRyXetLb7Kh1w~K6|QLWj`HD%#y0A!fl6cz{_vGF}Zj2 zvL+k?;o3o=(+l)ABCmu z$fF;t0Ou98G-qN|$Nd*c$up(W#hF?F z8>P|Wdrg|n^Y}Xa{dUCVu3C>^D36 zS}i>zEvEdS3T{8vSTkEYWcemi(b{6 zv?ta$f=zy#(X}Zi-9Ok&>u_O1GmPvEZ?+~%iZbwKFEge#=)Do}vYOot$K*{)dm6!} zsM-703q5I{y#i=xbJWb5o<00Bo_gse?A^I@<}$von`ED1r5VcQdgW3n!@8xH%lxzw zDqF9YW(u3U8&90X++z2q8Ee#d;kDOr@gIL5*mVd`oji$+>(*hh3SEjE>`WI$6M>0irr(b>e;@tNrz`#&oKI{W^m5O8>8;nM;+m7NGpZtuFks z7le>S0(9dDnek#WpHAwmM2S*WOB=k}DmRzMp&U4rQe!OH`AeE~Gm~ z>w+q|%lwhHi|t`QK<;`8C|#96NwY+C5f3q!+B!(Cj6Y8=>YSA+eQHGIlv?dLD*Jtw zv|Rj?F9~$`1YfZ;8(x&m6`IFUP$%Gu8CV3UivaxjNj!akI~vFC~j+`M!|1u@7QOl2) z%T#sfP^mu_lQ9|_flH~mnAP~R&CF)=c~Z4ex5bzPGz)h%0xE5FTokVLnANt0VWllD zH_a*yvn7gUmF5rwnTNAh$5U&{RL-bkLQmrkT{No_(pbghIf5NOP>;tgH>+^2f$gnD z4q1x$y_p;6$y11r^S-n_(QDd*^jKq#iE~|4S=kBSKE~CJ(%JSYm9@rBUIrx^os&Q}n*tgW}_C&m@n~W79S!=2Zf4)`a9ikQeTgJj3HJU%Q(O-kd zr|5!yjcL2urN6Tc0stoW>t)kb9ng6f{~EDfR+N+H(T|aytEWVL{@Ut@mLki~Hnfkj z<@mQYjMc4w{#h0a8;xjJE7Vx~%9Ggj_20sV=U&FB51hFDPQ3Yx{|T1XtjD*$}23EiE0@gkM80L<@iyhzm9o+Cg{fD@; zWf$K4;;#d}0p9$@zm4IFRg*d*A~r1STd(mgCEFJNYF>}cyZyKF5)lwF8&B<0bg%kE zoa~oynV;b~UxuA407I-kbsqQs>4O;bhWO?eK99w@{CllCw{FAV{OZq7uI-fV+aCW3 zw!C+2{FSM}_<#(*2`bub{q3W+D#*0NLX@Y*K^Xt`{-!GaY5%m%ux5u^W!pD$eBmh* zbNlu&-$V$VjElMG)TF+r4OsG|tFIqfaHhOomxr=I>6^Bk^ewVD$8A zp_ZLqKLM;?3w&&PR`rT)Ht_PJx3WK`$=8pen0K0-ee`J*x}$>WsebMVj;?(NTQ+RK z$~-`iVXQ%SdSzg0T3Ve?o^ z?P&6-rijdZ%JiunNk@r9A5j-AXC$h6#z@K6l;QMgwvdQ3B2VupJT74$R4y-ndz&Az zn5FoIN)$5CR(NcqG?}x+XI_svPW(oJs^HP%p8RdG*AL3GmeEVTqpXMuJt`h0ym+n8 z`Zns1dVAkLBUipcT(cDWO=Z_EseGiBqansDN{inzQQF-9vT zl8-0yzkILZ^^a{Y^JLd$f4iunt}!@w5^D}Wfh`aH0Z#9}4ae^N1&nrXcdH&e4$bte zhVSbP#duw1ZjK?La4Q;fs1ZAfL1!JDAQt!oEr4Roxk zD%B*XDsxoEEJXvDIp;X&%I+E^zu~4;Dr5_|ef|nHR#i3j%&!^0)}TVioE7-$nlFC< zTV@AWtEx>2k-Y1!iu>x$Ggr#eZ8E+RiM^=cfIY5KRP&(vlY_C+n6{_)jvvQ~Z#{$l zhPUwI#*H|*@9N8JO@z50JY_B+wzljkl^G_#A-_$J5cYAa6|pozb87NT{MNuLZ@r0y zhhGIwUBr8r&Y}W37j4ffw`R2Tudswayfn@6eN-vxOdI6N;FgWZ(&6iqO0LwF+u2uo zVrKT;Cw)uQR2AH$qJ&&Gs0Qa^PZEu(kM>?8GvYSHysJXgdxr5&ZOi9F`#k3>%s zy^G!Rr;0TTmio}wl@Jh4UzMF%S&Q}eBPmKezHEb7j_5NpyP-0OQm3rV^H~lqcvhW? za`ZB_XS$K8d}%$J$S8Vl{pXXl8&EIn7e)Dn>@|3b7=5%qg{uq-G#qG?A@2cj{1OgR zr=!1A`yUaJjs{Fxk>A&a_BO&*I?P4fro5Co=kW%|vFFfoE8W;bbwSgvIldKFYRhu| ze0fhJ%F^qQ_I^abdak$bMV?TvwLoe@e~J8u+)YU1_w@)LtlYy5=q8pXH5? zoD=4#LN01nmPb*uqA9Zy8|I0dOSl`pX~y|y{V-byXhF;|v>G;i`8r+mpTE|QlOKwAyqTT4hO)reYA(0^ z@Se3gZfa(WY{H(F+gi=uG5=sWB4YQ6eS*+tTOMXwQB87~7UXT_7H@A$cvnx3K?hxx zgSD*GjuJby#lNhbec@w4#U*v|i<~xnVCSORY!A1XW1@AHP>1^kWc9^Z2@^h9zRAH; zsUf8!`X2>avbt>50PnRxx9YPnqoxfpJgpuPAWMpm36`+?C2 z)zSi19D5h54?l@jZ@-HA-4nR;H$RE@Kl{sAT(=n~?)oCm?YSO|U>h3LJFiRS819OH zjY&V&JvL{%q7PQ=uH{u~8gY>W`iolRQvq1Q00RtRQP0v?hnn{w&5Przu7DwM--CaS zM?Q5A&aGLK_C?j>T-K-m{2|O;TEt*s3B$T4zD2jYX0}WjjI}y@-5=!$Gr7YT8<~?ZHs@YPBpOt>*Jw58m?O9olR=&xrF(dP7os>I~l=?Cs z`;f-;vDSu9bew8*>+@;rycT)938;@E3e<(g5wn-LHsjMcRUB;fat)Ws)?)_6U%pp7 zHpu;C)DYfR9%65EWBF`8mTgqc_8wp7|2;1yU0ud*^z8d`4Q=1+I_DGbsGQpIrc!Hb zBM}N~pj=B7PQ=dkDs7GxUn^U|Tz<6oCg?Py}wL#G{er(inOl{ zsrkzzW!mvnwC%p{EDuLfv>FwFOS`Xa#>=_W=>ORtV9mor^d9&noVnp{EUw!e z`k{T%n=R_*T9L5u0b?GUDB4ECg)_mb+5Vk@;h zG0x`brllztY*!Om)~GP3gq&w4GUNw*%*SC|DrR(wF<<;maYg}mb)CW>J3*}MQgsAs z9H?5QibX>ce{0B+cUxxky#pwh(Ag4#dh*vk+*!#zfBt7PSS}5h@bIzMao6TuSlJs) zo>u6ETI-3znq2GzZn|6#m{j%=rg%4*OJmj)dycZ4Rw~cuO@X$*3-U&AmZvVTm8O1$ zYS5pYgfL6$2Bf)R@=s==-<_L!)aEdJUbP{a(QXS5fEsV?+lvdU=4a&o%BNE2m)FnQ zvj0Do;f`8bAF9#uRw18i6{nJP(W-s8m=;lAM*BO3%l|X z3a86(sPv@XS(`7b#w{8-deJi5-+Upg0fM-rD=vj1;M0A1JWJ9R##k+Oej6wFShIQw zChtjOc%)W3f}?5UDuz62-Td-wTU5>fC5Ang;@NQJ3FYNWknRQB>}#XT9`tC5fk8Eq zwCQ{8O4&a>`;8Kdb~^$}Pf7D+A%~ZAyXPhShyqIx>&HSpX+L#=p1aBC7cvm6Yil`< zz0PU-w7ouLG`c(@|l3UZOmWeoBOI6moP} z$+I@wqWVb54$&Jg2xXhqmNwRHG+wx6QC(x%HXc2JtE(P{y&iVF_g=x5`Z_MyrY+{; zZGHV4|9N}G|3}G1X+%p`#);lLb?K{0PNhewSIHB@A=Zbqm(eOl4{JW9653^?oXH?Y zgr((+vZ{+`rMI++D|%Y?Y`l)%csOaDomXnlhU10W%`ygCETN0idJ~QsjAIDW7B?E# zoLtfI+Z!*A^k0Th$!og}mB2lXDI3e(CGs(=cskk=EtQXH^(UES$#_$Q(`BuiG#n0b z;l+2c_G>Q!U;eqyyeBtp#7}O&4LASzDOX>arq_EVQd0|G3#h+WyGr@yy?Uj%U07Pe zrG*6mz-UzC{DliMm+fO1Hq3l9GHgp-`u~?9sSVYZL_f>CY8Rqc)|Xp)tq8$S%r_MJ zLZvsEDsCc%CblrD{8~XooUDl_KsU*sL8KGhxlgO$<)8~ZiN^BS$(}PuB`vn7F8j)l z$H#hdvSNf-ug1mJBAezPO(fiNCG15NW0uPCm!*i^eS7r@PcpJ{ZHPIGA?%r91*5Ac zU`Co*pYVP>!JIL@KVBrp$0hRiHWHJTH?p>4Ml24t1?@Z!mG;*9$u>9Jd1O)lOosX5 zort>PsL(q7XpUB^3bfkvocHpRqg8U1NLqbOE$w5SK1Ez^{m2p;uhP<#?Shn7xs@Yb z=>qKeGU=vyZB^VrAIFT=t>aanmxlyE>WSBW9QpQX%En(cC5M-emsA-W=>3fD;QVQ9 zc>WP=d+1-IfAJhn-g-aIU2_XAZQYIGnhmHYo8d^i9iP?3{S05V#~{344+f|QbK~m@ z!!;XlY1E-7<3PW{i-!(k&DnFf z>aDknw$-Sx=JYw#BeNm4JeQl2Eh;jc;r(4{uZ?c3D~tH7wcguAPvmh0k%OOw?vJ@H zzX_@L8oGVA*dgovN@ma_9su~Zppq*~+M6D2#kwpC@cyfOFFFm^mKKNiO3$hHF?m*6 zK$G2Y(#y}^a6R7H{lQP!j=Zat?FC7M!NKPP;bHUpg4|EU5ssVw3kKM zieeg{G!#43hPQKE&Nf8JL_F$c*@d@#ANgL2abXj$_oRf@>~)qt)koia?za*E?d)e%F{(-x8Yv1%43 zF03Y|E$ioXlpu4DL{e(i+7_30)AES3KYp)a2NYt`hT7G@)irTMlq)tV3%gr~J8|J{ zSFD#saML#VP4_o3R*Cikz+}Pp#vgtI2mY_Wi&y^RzlT$IJb=;awXRGo@8g=LJz2h4 z#*qDr=RWJA;OPBy>!}_IXjIPLdN1a79>Dgm|36s&+kX#7zW6us{ull_hAZZwabLOo zp0aE2KYHW#ezKm;-dkx|z6H#KKdib;kQ(AB+fw3m3vH=1<=ywYYt8bNFR;2&b^C7Y zI(R*<-LrSL{1Ywj;bp~frM9>9gwvn|@LKCutj zIFDWH=5c9Z0Y^`sz}AiJpRUS7yYAj@dpfHG%aGzPU&;gE=2w}zTAXWObffC1^=Unx z64fQbJVDIr5&T zQ@U+h&>m!A>it<$RY=NnRN4#wEJ{Zu!22auR|&?y(PmBOiKQYx)KJo>3U0i=vz(@T zK5l8>I^elfDttN(JJzm_wu$YitNAD?BfH+%2an(v-C#WCZL^iV5VeIktV3(*p@$9c zpG1WkLkt|Rs_W+KG;(TQRrbff?c~k4W!7rqKR;sqh%+wvTbHjPRj+e_V zA7kGNIc-|RI`mpkJS;aeH)%NTsUEl#7LHOqp`r`IJpwJqT!uq2rp+f=d{-jEi0ZU< z@27^7#nJS;nOp(G8*QE<;TdzV;3(e{^n~KE}AW4 z!!r5)@vj0E87k^jo0P{--VxPnP=_xlo?NyT#1`hrjW8eM|rIa-TghKpo`WGDeHWD#2TFEBA4D~=h&UJ064nY z*QvT`meEWVN-NFCXWQ5)@2RfE`#G96`q5_Tv$o`=oVTtk_G-sgF*Yr^(b!?dsrRwr zxks?!neU-DT*R5{@5K2%2XS%N0W7WCg1X-ey;9oqHZ5=Cw`@z>-59UbK);XC+VvQ% zT@L`bguPf?zZsWqz7Jw|-_!A-=rz5vk?zJS{)| z&D!cmg5~pi-Pk4_`yR$i+s0_wG!Q`?4yOxa%xQH-+him zBGv<=B5!Fey@&CO>)OA5Xm#kJRs277!jKjF%(l_AX@f?F8j(|{$}u<{LsB2hq?U|+ z%Aa$pa{q9mA0J@>jUN7y^H~suiDX){~ELO#pR`jU!L+8 zIm<>)cY5INdzSqrCAP3x#HgEfOKoXVvoU@8*RV>gTgtM{*UXY^!5uf>N1I*NxLj@j z%6<3aPydGs)t)`e=C3_f;ddEJiIjZIV(LP68 zq}rzsaTxN%8QJr|HFXJuX4DE0ARH{XisV;o5& zX8HYsJi~rbcCi=qmq#s(?kz`LuK``In8E8R1TWFW<+1bI?GeGvp7TfjMjpjaQ%blG5T$#>-~R>?burTE|Ljy}YQG;u4bTtmY z*J$?cGjw|yb%@lL_1?5rh zB&VU*0q0XR(SE?^sm&p_gZk+-?PHa1ryiXyd7?FK^5`;R=41Gyr&F^ZEg*=1 z*aO?Pw#L(?xZx$zDzzX6JKh6e(k8R;TU+wBc@)|jee?*WX5~EkelA}~mohB9d<1FaDArBS z<-J;Fg>~Vwji4NV5Dj&W=_rLpjy-69`Cs18EBAgRkX|MupT8374a~MWbZW-}RC43F zujKz(@2a*&j$3|Ue4F1oRk)z%g2NXQ7a4QO2i#*47^D;|eN6-yQ`l+U#4TqpQT&-ahy~i8_$=n77t` z0<{ZUbBVh7nI5=LzZ}ysTC$g)T%4j?sp|0^F0EG25_Q4u@N`FwnwmNq9~i%kP@b^O zu^VkewBXUwYp-QqxGBd^6}QpI_1p4CzgmS~o?itVPSX)J*)_0gC%?8NWAetjgIqdZo`h| zi)^Y_+d`_^2VS=A)+O3wL%hpL(YJk&lwp;a^qV$TW;vUhv33Qj9o_L;J8#o-<@y>& zLFPA051vtrR(l#hM3U;?Xd`GRnkN_LSK-vg4Kq^-&7Ws=!)Aiij%zQ?rjRw7bSAK8hd8N35T<{x6OgxFHmg~mr zQll8_8AV$Z8&PU*SFq~s!`Sfb_p#=UXK`WIwK#tJ&!Dd2Hi_wT z64U$E$GIgkZ=>LSa2B!EK@N@IsbEW^Z5E5)E3Ckc%hmXwod9jQl+L(*j9Jj`ezYpB_^s^W&E#l36?T39W z=j+Xy6gT<%%E9vdTT|XIKFfYv{j<;_2VEB3#|VI7)MhrPxt_(FHR;cO@DScPaSZ#% za=&)(UhLa-`KQuX6YD>%uP#sK%j0FX!&lV5wwL+fyykIq{>)q4?EOl_%*H)um(}mv zbH(q(w*1BM8^5Y%wfY5-(e|{B1CKdS*RRSrNNb1@ zZM3XqS*2;Xhj+^LL@N9Cn1lEHQ7npP@&&-;q@I+|TN&?b57e^EuY&25kK{_+oh9~& z&C+YDjkZxR99inFwpH8fd5Wj~MxOmz2-OqjV(t0t4O84mNBl)@J*rYVIbD8}CUVLV z+F)wqR1dG?!d7ne_P8_R&#Yfnt}*$xR1+Se6!QMzy|Q(XcIZjIYO~>5oa>#Z*0hpe z=i|nB9s|L-e!nKLg15ysGPLL0quY|JJo4&ZClvFx(=YRRnK#_(Z`JL&Q%AAop+CUR zum2Og@|*uNPT%@zj8@K1q6M!zYLE1oDBssT_e`~=)Gd{d|GJO8p=x4BQXpz(KJ|)C z{5kQfRS$K4fQ9Q0;pF_UVDtC?2s^*_k8tFRzmDPj+8|B!VtygDN;vkNwxi9DQ#ZAi z(uYS)AVToEVsqiqlEyq1?fJ#qI=1rBRO)Q$2eT1w$!|Yy%8yX#R!LQmtg2`@^|w~r z_7d8&8y#fUELB&dsnAS2zZNBnN%NH9hbjcX4l7sgN3nK+B$b<2hA7i!fZ9pg1Qq3u zbNv*9-$Sn-MW|6@5dbiUMXZ=mv=dux*@L}K;K?OCLA4Ka0nN*s;n*GO3m^~Ubug7i zwgenezTIXue>zKeP#S=)8ZwFo5lN$wWd;zYrvtn9;P@-=0LRWx&zx|m$#eCs*-s;NA`#a?%K@S*{aC7lL0nzgIPhatw3|5gT|Cpi)RH6UDrGh56} z*u_?~S@3xJm-1`-UOfn_q{UIH9w;S*(Pix4q5ZkLGuLPH)LI$2Y#ZM(b*H&m7{n&{kO%b6Vkw(4e+Qrt^MT@-b z6ug&x%V0-OoF!N7DFzkg-L86BGOwdVy{1VV`51E^Pu(lAEw71%HMp`;y6@ZvMiC#E z_c5hhcYAXguti<5iRS6jDt})`uC>eam)99v6up}tSw=@kCG*#l64UNSIdddveA47B zV;S=5t#ghH+7UzaH6{MH@@m^?an;W^c2GBnav4+wF5$N5gsrqKL(zMfoNB;rPU6c} zMog?OEK97v;Hx(f)FQn%a5&2%s-zNjE%uZ>xGX zdsG##z0AsXRf#P8dFb)%^n7D8KLqYiFKDFDL{0+?F^5H0V}mJ8HyT-KjBL6{v}F1V z$G5hSRu>>jjEE5KDet%YkF30=X(d%Nx@%$%)qzYyOG$W5?@Aljufq)o4&bdLN2ccW z+|_8)$V|_TbGE;n^qocOO1s;iWat-@XC@z===FAId3;UMuJx#P?7+$uD{%eQ`|-q! zFD&~cwzlNape03zdN1>Ef4NeLEtglW-QSiLHTwRDE-)^kzMo!2Q#tNzR?kMWEf$MN zL3OzFQDw?rk5YTpH}VvtEcuwK=jeD_Qag^TaIG@%JjTV>{es`@Bu+)lJi>zLM!7f6 z8@c+E%)S0=PkSpCWf?Jo$98!t`#!cssq=0Z-6*T_Y}1HvGIT?1rR69S{`L0TT5k4{ zTc!BCp7dZXLT)QjdYek5QMo!x53i%Cl#8z;%BJ*CbxO5t4Z^dSBaeEt zN7Pe#nx$vWYs=;pvUn@U6Oq1J%5f%B+}-rKe+`*>FOw=fQQX?v#5eg@0@V*w79Q1lP0EwE zVt(NZzs?*z24}E!X*uJ(;bf6^FSJ%Yxypq+^F8QjB3t`Pb04}joY#6_mG(u2@>>SJ zR<)#=q-L`wZMl4{`qhcDbcPOR!?ce)^(0>Xhku5PgAp$Lt=&`eTVKRY1(%yB?QVNo z+CCt9xQInrE{nI8gZWDfcUep~ zi~lI=>&7p$dQtmb#v^tze%wykp3YskfTbbd_sEhJQ%E9 zF84=&;*|DJYS1njkwYXoh5rJkqFrP{qo4q{_l52D-Z ztp=|<T$XHh$A2YuA7*v)&4I2S<8Q;IdRRTI(M_z}#$Q=4D< z18*aJQY+=75PBxSTWB3QHDu9t6mO;=T|1P#*=~QXbu|OKeetVxjDi(E+>N@apLQL& zWhw7)GM8D&uS)WG`6#W7Z$GHig_eWUXvG0+Tx1Kh`O>PveFE<43`_!_zoHeO#+b7AUrS@=P zc`27i4Ryy|WvA`1pQPak_5bo6j9xzu+;cCmch^k(>7?E?UVa+VbP)2tmJMeh933!StS6dvE)5DE3wJfpR`FKt8b@%=E4UVkZT2W zMlaq|PpWqn+9?M-xzs`!4F|0iy})BhQ#mTbH$r#~wdk)JkHFKcEPy059EuO~;hg1Y zx9VBo*Yu5sz}hxlx}GP$OI&3|{Z!f(s%74xGRpT2!y?EXUXf5w*l1XQp+Q+iX=U~Oiw)qqb}xhB7lxB=A!&Kel+z0O+Q+u zrCMnEwsBL{bXwZiUcN?4(JiqrWK=f(vkX z#c|;+iyvWSOakQnT_trzy7_qYe8NdpeIh@3tdb-iwVC3Pe^%fjQy<<8PT#@3H3ib-`P$P;|XF-S-Y|cAM@nR*MYPJ#z8#ESAAMMMN?lH zd%HtT(dpGu;e%AaqP}@uBh~JSy-d%%{>GCoDEHEynr!*oBR2Jd>=jN#^xPe-gY9qb zRZ_~RtC#bsyv}5$GU&O#`w5IO?xIkNRVazEEA7ZVIkE~^EllNgBsnJXJlA0^juC;aA_RM$17|m$4&1@@9 zuxAzvTSQ|2H)@=FFeGO$Olt7;c;wNp{ep6poL>^?$6Y(UXpLj9sx(TvnP({xbB=f# z?4)vy3*r5}vIc*x9O)S2R(;Ml*OTAmkf+IMgu_u*$_s%L-cy~dtLGtCFJJ<0mgG-Bg3-^a>VU%;@p0`K4VOE`7oC&E}^+)&07HL5@p$-UCw zXQ?ipXQNDW+Y`manZy=1Zo`Q?e+K;vXR-0|2eI+-Z)3wVKfvOutvGk!28`zCWyELk zuTPebWg-Tfefb;fi&n{dY11!KwZ#k;U07t%aNZNjCPlMmnkTnTOi#OYJGaLsxg*nc%{IB?Cf>gr0? z14Hyv=@AjPBWFJjwOq7k5!04qsO*beuCvIzlx`;Td{mh>U75(GjlYQE^x5>XarVbs z_bh(Ul%tMl*UC}j`!!1*hZ2kGeE>N4;){5(cMvBwwSU>`?wfDHqfb5Q?yX(D8V7c_ zpLlLbb-OzsP`32)Y{Cag({Rf4eEGOsE)O}i50-SiM*q~Nnt^4AWM^qkl(TLFeMhzm6sHT3&a@I+5cXPnYuW+_cZ=!#zXs zyqrrmROF=>Wo5j2ysI1RR92CPtY<6vf4L0ZBMr`tsEjLERoPo_^~ce+8?QdM^}6b{X{9dOE`7b{x}LPQxgI(h+VX8%n52mw z@=RtPF|uyO`d%0P0&zdX7Inh@uiu7IsWv^;AhyS)&lkE7UCSNnpSV5O> z^X-Z8+0;NARJ*#o@0cDlm!mS?ixk>?Y97%n}AZo{Tk1BFORx1l%Uav=axrasi)8}0aW0Dj13iC{c3Hl=jO1uYafR9%wgpZ z{s24w__uKMzF)-oJqJS%uzw@R%;8rc=)F=K*c(|tY4Y_|a>tkU@dUZ>hgPZI$>P2Y zn|iD1`SQJKdE)#tYpIIb2ALtHNzumUASMGTX0##CeIV_@hHr3eEIUzQ3Y|l9uP6EJ z#jC#bH#H<>>n?v%Av;DDs|z@mF1u_`3>9+MMB^HbG+#Uqur!{e;EU+j_wB=TH{Cd? zbzyN4uU_JutXsVX0C4k@Pht1#Z=nJ(s@Y@xali2N?IjG+#}fLegeRcX0~=s% z@=_x*EBuZ+k?F~_L3_D*nG_b<3BKKnjc4ZvKvm5micoI0;7`-#wA|O(Mlo}jG3Vt; zepzYINA>rA0r<_|W4-lQSFg}%VzVT^-0rS(8VLDmO>yMX#mB?L!^}`gw3wy6DpSvzKE4P|Ak+ymMyR=5=}>3_r~CWza3s zM7S=Yq=s$^80amzktfpg)Edr4urtpyF3OaH6F`An(@# zrsuYMdftnbCB-W6LFsxJ>HTfFYd&wgX+=Hp+VQ0|5tG+u9g9(WGdWaJ7x~O+wx@0^ zU|3EQb*wxG-uEUtq@HmS7uQXr-S%lO#W|$V3yYrM^6-8ykv%!7$F%(T%l6Q6 zR953LNjv33q=?mWU!}Pr`7g(>b?HcMcgwOd?&zLuig5>NLQ=||0NQ>o7OYFBTbJ8Wj+7lWv z+UPOut;W)$wt5Tf6E(n}tf}|;!rER1>z6Y$mduueNBdA-dmf|iWzW%a9Zy3jJ(n)! zB66~^Z+$r$x17Dm$j{pvo_Ow~H}x@)`+1C9g}*U*J6+n`wzyN}XUh*PQnPc>Y(q0Y z3_irtia8wHyk$c3?7M4mY}*#BTDuN4fHh~&WA)kdFe_>sZhA6?Z9|MAO`g)x14pv< znYXiEKDq78&|)SxPpdsoZo^_NWv$VsmFPG7UGg$(ym0K~Nj&lAKg62fc^vp3r{}Lw z#^%eZ@5&@EH}4%|9*t-2Ov*yE!}^qXok%dtf-s<_NjB_(|>+6^B=NBn3W*FKKPMPU~C zahaLlY|ED|id#L>EjN2ctL?Se>h<@m7JUWBC($$Vo?+e6|CX_u=P~mp{tHQQwwif} ze+%GVO>XyAG1^8#YL*q!+P;w?bJQ%BSp?7)?dwtZmM57{@|aT;=a~`FBsZ z>sco>QNsqmCLt zi`FG8%R8K3i({Yqc^v)JzlY5a|1s9Q`T|xReGQj(T!jm}uEWCmEsj3>!&^GmYn~|Y zhtenO|H)bGY5HV7iPp+`#FjSLSACk?{K&W=Tl3945xSl%iBS1^{;3VR6u@k-Uzp8h z(Gg`bevTf@Y?Qa6_v-6d zb^hX59?fR(YAj=J((OT|R)=f<A+_{ zj$001kL{Z`FS{&2bj7bz`F}b-)q{Jq?CnWrZxx9Eiff{c)W4Q|9@30y7MXkf@5-0? zriglHiN6lN`6iAWKZYHfx8T5@JyY|?WZ%DAZqoiLeUYY!gL8brXH|MXuUS1@sR1!< zIeH9l?%UJ3XnXIDop|P@mnPRojvvSIQ>Splfdj2&Ja^Ok3^Vp^L$6Dde7(~(l=V-? zEYa)FPJcS}*;0o6%ebH{qi8xJNfh_Iy@(#JavBxingTYHt?v&!Js`IoW#r(|tIbHV zq;K1_1My-@Yj;mK495kuO?wa)^?A?ZC8J)kJWQ<1LU6Qu45c|r9O~^nWgWMlHFD}t z-Xj{WAPO>iUben(qO~IK%;k{jPD#m^=X+4!5BA%>!BAmx7A_jhrjj(QV%yJj@v)*m zF4`^;T{h;LoaI}7YSc7(OqPQ&XxnD)@}DkuER%W~J@(5s=>a@pm|xRm%4DXxVr^6m zI*lJ{T{9cUw_R~1hHqco91^XU;!`VS#|3yioy$!%ROh;^B=Hw(wRtjoXQUR&TBz@h zSd)4a??L2_G>U&10_8pQ|8;`MH+fj3dYckwG?I*30cGR(`>5L_m8lb1VH#*jHC9|^a zF+%3;y@l}J%G#WHGAldalnmYl001BWNkl+~aPJ)^^79<+tUtdxx*P z1}`7Hb_$okvp3#|7Y<#IJ#V~;L(e{sA?)+w_4rfbCKKCjV6XGl{F@r8WdMc}t+ywbVil z*|@Wh5YjBV*(B5M#ws?aXxlA{B_UPIWMW(n)bxGMp^ zZbbCqg%5ey0~(GfFWQURUuCkIa(TDwU!6SnF-V*J%k-hFvt4i4CqAOc^ebyiv{~6N zZ!>h66#GXlW$Y)-$vkj*t$ZD7_BPym=`#ET+HFO9uc~(PyiT5-O&@M@V6@@=4qqht z7e_W}qlZY!F%Hu(0gBh1AE?h6TO8YR-ZeM=0$!Fz!FBX z(T|)_C#kQrC%RnETZs}2YaezYMjgMACOWRO6!FkcOcHhK3b?#9i?o`2*_G+% zPhI-NK2*Qdi44Jr#4&;%jTkc~>eCT8xb;qp}y2 zO6fTj2`Vm7zT-JJo)^Q{{BS0~1@ZQq2tHc-$fG8o!`DgQk+-a*lpzO?o@#LR%|~A) z-ELat@AA8m5gic|vz01!)r943V7BLRL!^&SD%WO3K6OG*bMbc;Lt0y+Oxvu3$Ke`- zm3ZIFsFa(P%j(b2L&OxmZjaOX5#s7PxA4hCl-mQIf{1acnmLL2PcK*NrH&9hL@|nMeV|RZEOKUbxIAx@n z_n-FFG@tBk1|}R*qFyg5X&+G*zXeHe!L|arL71o18P_#@Oi1ZzoJfAvXZRDfeNPW3 z8=-Ycial2!2>BhoL(Ef2NtL}HwaRUb>vX|(xyVQtXOCPyyMJu!W}I2Se!|10l`HYu zHCMCR9x#9Y0yZ8yiM6NBfIi*)jLodolmECiw@E{%XVyzzZ!>)>@qo&rEp>YiZyC#y z>USf>Suytht9E1Ky7kzxWy?(YPi@$M_qT7urX&1%4`8t}xlyh-8kEaf_$x=Twk-FJ zx&6(3XPf+IO)Bj=+{>-?<)*ieyocvrIgG^v*DQO{c4_OfL~WzSDW34-Jl|C9YnX;* z^?ueDZL*_oH9TDz8E1BEc_~Il%PTwUn26S4TKg{_(|lN|4SCO!-;cGJqL=hzU-5Mp z-uBUqUu0LFlp5R7-JWR8)Vgb*Y8$5YRE5!m8>MMzO`}%B%RH#U@P;1f!MIATM`>v@ ze^YYJ)_DIJOES00S6in3B_f}=v5WWH@Ne`JYWK{m(RX<+Y*}@V%Of7oFr|O%YScLU zT*Dt6V##kBC>I4s#FuTUj=h=bte3cHL3T=X)OkIu%6mwg=iuAYvL89-lrJtF)}HgZ z4O=%@6)rb>kjPcqcK$gmU+U!1&l**L(8*dYu zwEE2#vH0?fI6c1}gPU&0g}v9e*bYCo^czP$p2=ezlb>H{lIxeXs?lj3)lDyw%4lpq zc;H)O?@fz(u--J;+EHV)%D}nnZbda*LjTckVB3SghvAK%z?nmLVPV~7uulQ)SITv| zH#eQ}JsbUv`a+cg$G_LCNTXeItp1U!g?yB;3R_2BOMG01JS9S~`=wp20Sr66__`)P1hAxIhD9Br0fc}H)H?s^lm!#&Yvkp1bmjVU8%WrwN?*wGDC8%_PQK<(Yvq(3KV@C+ktw-40U*>8lThlsXPTv`7J%758b?{;$6RZ*Pj~a zb+c>%CQsV@U@TYad!Da^qHI%zww@|SWxEIUVTaXiqn0*+FHSt(qPD3or;p~OPxF_pt5J!U8jUxZ z=2jNMfsdxlH~YwxmN%QO%sxtn2_IIMdQD88XFBP5)_?h_2PKVm9n5=(eLHeff7WYy zS_(HbGx6MX{iC?`@tkJ{^sbqJJ)NY0R$(xhFXdLsy6~@zCY;K9{fjXz@#*6Y*Es zUnP>#xDu{>cW-+?u5>-3)A*sRBlC@AOlIChdDmwVaj@-NxNRthTg}u~>(?y+!$T-| zhpXH3llgEgc_wNr(5-3`f<5T~eez)nN zSx`%fPJEAf?Ji@FS*VuF(`@V!SF0uP^2)F%`OtVrQ^XRyPwAGrna5CB(ve<9Gd4=1 z$6g*S(jm&``yJ|+zW>o$$``~y)Ooc4@c@)8rYcj0m#5>jE}g9EA$n&{VZ-nIZ#cL2 zIvjoA-^ZmbyPO;=M@#F>;tD|fG9DU0>6W~=*)4k-ajfq{_TOkyKDX99cEhk(lk@l| zzlsZc4q?x~`1{!Yo!`S~umZ>L{t|{OS37=6{O0W<`;&UX+N~`*^0Kyj&uu66LHPCB z$2V=7cjT_3#uAbov^0 zC9SZ07R?VZ#F3rbQTG~oyt!`=j&9xB%F%24uLc0z@XT}AaO#wM#<_{nc=VfG{0Y(4 z4qfU-%M!7iMjo{25noM95qnZ^y{}VW67fq!ab@r1>CpZIc>lx+9Def+tXs1N+ctG? ztUbPEGge$$z?LJ&V5j;;8|3Xv^l{NDux##WDcj7BMU5s+Z+qMPQmnBXeNB_-@?)J@ zW54C3vuoDk#HLMHcjC-c+GRxI?V?8(b&#j`Nzq5;NHu>J{Zd&@``eE*v)}gY*p@B0 zFhAc)D@)rqZ^7EtYw+fK?_$r6{L59-QrQM?)%ETyV{>|aY`fwf-t+OrmDaNlN-e`1 z)AXP{<+dP>uF5_4WppD#^rl(F6Mq{WJr6=+&@SH@fP+D2v%c`GIHuMEPzm9v|s#cy}Z1H8eRn6lLkA^%ClsvzD;%o7q zxvWQ9O>`Vlx?Ss>M?7Ru52EAyA4o|e&d5u4!ZT%~?e`mSwEYbQ)gE0WZ1u#2!g@Bd zNntcufmFecrK(XC{m6q%y^bi4DtW^oM9y~DCZ$-9F*Z?PT!+`R!++g{xU`J3JZ~dc zx4pOJ(Sqf|dXL~u-;ZzEj7uw5PTIKY!bNO8aYEinkR!#-s`uI#CpT@xh57jjt&Jy6 ziahFZ>3Ym-Q-k8+-uMnz#c9mOamsPyBeZBgK8W9ou_q={YD*dZi`I+%u6>oH{N8JW?eJsUuZ@jkLSvh3JZ9r4qWC815^t}GO}~x6wLtofK)Yv4lxv~k zqX)(<&3ti%vxn})n$ZaBzx%H+`0npxaPAb2-}OZ-uGxsvC(MR5^j?g2e6LmE|32O_ zTclWreHwk0T7|kZcOI3*l3fvj+IHUKGjBP(H30^dBV{bqfrKX&704R{@94BV_sn=U zsA92^-sKrb)kKY{UtKo+;hq`=I<+`p{of|H zexku%O22UEdc3uFHx^c`DC+7;i*s{$YxnME;r7$dO@?y~?g-Px7sg*7qw&u2wjty} zZrPhze!u_0?)lUP=~!o1>KgPVH#(sfT}Z6$$_6#lnx!+h0uThDp;L*K`^_9E^^xN}lzOd@r-Q%OmLG7*2&A$Pm{N-*j%R(o&w7PUz$@|y!-ZAq7BXHBvpD+ zv`~(*a-I)}?aNR{#HE=p@}~QpuYlyEkb%EGy<<-~H(okoq z!5(eLtvC5*X7;nakWmCeOrfYGM#Lr0Sxg&kq(0ALE-M%Hy^N5erh25Jw3>F(GDn)x zqSupllxUJtCvsElqJFyPd}8xA_j>l!FOOwgJ?Gs$!P-VaroLWotel0e%HQ+mJ$ot3 z9L=<0?`(l^#0O;0G587l;evP8y{n8$`)AGF%QGbI>vy<@E;+dTM!flODFfLJtF>Cpv z7O~IsR%h5l`@Zah*zT~($g@&6nXiJ6@B9K8`?3;x6;5wjkEd_D35#=c6Y6KrpU2q?=dp5b z1vaf;pZ4X2)$=&Dc?0?jOIUsO0swz#5l29Udh*3f^6b%>`BAm0(f_b~ncAb5ID)37 zT(7{Q(av0CPau|p9AHcRdr+*Epk=k&)`B}9E#dSLk zYt!_U`>DF9Q$1fi72fNw=ONysuW7S1rKj+5RM{%;5oeE`Ev;X>7He0po+?PlZ;Onp$FNxZK32HKLB^t%xW**M;mv(3nch7SRMH&ZuI9m#)7KCpK-GN3Ol8kf5!?EH@oUoTACFk$DarAf@7unc-74it&##>Ipi#BfZ*}`V z^GTPKW70SLR!d(j1rK-99^f2IY&#~u%R^B7>Au_`*TyGfJUu3$;if-6jhYB@IH9lf z;-+uQZ#CPR4lCaidIJn)tdXwjSkt;1wq?7t$0brA_SW|edSbO-T;0bokugzqY^&*q z(Pg{2&d+i#&CTKLy0uQ9pa0k)oZdi8yZP90^q+qL7}Z#J@@%jsT;Sfr2%~-1k3o$4 zpphKMkAK7G^Hr0YZ7x%zP`LIng6H$IH{OkfZF{io&;A**;D`8A^8bX8BCR z`ZlVR^Trb=F}Julm1j*)zw{y&mzJ=rCFQSn8K?x}Xv^)h*SIn$qwR_P zTh?5ngDiP4=(SlTllvF;K*R&S=j(z;wlA~(zMa0u;eNMI6ln;fV7+quM(xqMrqSd% z2_=wM>%l&Xa#Oq-f9E{3*==36sQuz)ReCL*O!iNe+mW6(Y8_d(#%hYX6lq%l_w-Lun@f_G0bi=lxVY zp+#*r+3SR+(pMYIQRr>1j-}Wmif^OEjQ3S9yay{a#!9MpQ@b0>0n|)?qCpLwEjE$} z#3mxuK6~FzdlbiD?wh@Zs1Q#VV{}#C&-{;$&Zs-4Gt@=3x0YA$m$t2um7a=GPE4xY zt-ZP+Aik8hX*69XF@kO+ut^*CpXroe0%-ZOWdoT_sO2A%AG46((E`R3Kv4X)-0VsJ z6^ktW%Wr-I=PsPb=kC4-dw1?~&rWYxkMG@gFYf!!pQDD~*ldfp?fg69O||dcc9G*G z!#SD!;)18rAGO)1X=xg_wgB6DJR1|L{cII&3lMw%%B3D^48~s!v$-CBeo9k&g}4BS zT$hNlOdgl%{mW~ay=+l#?Cg>&olcxSjX(YVL->`S{gT_DFfBFn4RQH>K8}}@6n*^L zlp=cSzMjR`>ZG&EOf9vy+E%_6t6ibO5CfF{sg`;fJs2{(>x5>V@E5IREqV1`8DSW2^`tKK%TWf_UP_TqeEU2f`E|)}n?Go$ zQx(rj9h{ABMl*VCkFL$ql|J8NY+n*!PiA~&E%I&mi)Kq3?t7t+QA-ZxT}QCTHIbiQ z^1`3^pY%C~tI4&YK;=+lmiPi(Z8QINf6>uuQ0YdS6=NyAU(zG)BK9OM^-_q4ozLw5 zCQrZdpoe(cpZ!yu%BVsYZgaD21wAJplBcvz-tsc?iikLiwJtAtIj=hY4t9R)pJ6nr z@y^fxM_5|DwpD%}hqk{wHmqzkVjp`tR&xZ~ zPCJ^knfO)Dls68euV8zlJyvS=JI1_vOqACgKsCgphS+wMyPs9|aV|%18;4xTz^^I| zVP70xSh*5E_|zwhetqG!SMkIP&*Q-EJ^1WhcNfor=EUvS_Fs+d?;XKSPdtsmrNuFq z1JvL~U2kQo;y1m0^ihm2vY5^1?MB3<=0+WjSdvd`_nZAV!~i|ixbB6QFzWYOH#mRL zl*J7`wZ~`q9C20$LQbRW?VqCd8eS?zhc?fOGlT3W*S zix+3gUxj~7YV!fUoX@NGy^V@EiT5;ro^Q4`c+IxE4bAezSl`y^sXlc97e~i&Y14MB z+_)B-H*CaRH{ColZw(-Op z&Q8a!rHzQ*&-&71t5I5pn;+w{RFAf&wNw!mF^BeSxuq(Xih5fv=F@p$&pA;qBMtx# zQ`>K~zh1-Y;toRVeQ$UqleNX;h`4>z$3|Qbsj*3hfVi+V;*a*E(U?iH1{Vhtvz9cw zeS?)XJY}aHSCg${Tx3bDRDHE)7|WsDB z`L%r3-lnD61A{T{GoEZ=tHvcDsJ|_MPp> zqp$qXA^l=3Hz;T%mfIw?YQ3@jY5rAEsrRI2d($u)&y?7klQ@In$E@{?zNx6Nu=Oe& z`Qoo*>$m!$-*)pq=jKQ`lqW;bnZ~HynaiK&s;!&VBe7Uf}fJI$U zYt*owT=Uc9_IYBeh3{a6DA8o7s^mdO+r9ibWvnvvW~>B%{jr1UV~C^MwqEvvZA%L) zR^Y9@yU`nsu>XZu(Hn7E&6X~3Cq}7iwLDXK%@PQ78`^U6LJeTdSJEy6XD!iX7P?X` z|F7I{mfLdd7_NHj?Pfvzhm^X3p5|j}GnScQYo~L0VV)Vvwq)b2IjL(C zrd#mBtFPdOYp%h%HEZ$yiQ_nT;UYF~SSF(re%ka(?L%9dC0L!Ek8UUT!BWm?rV*um z%|W-Pya)F8BSec(seIfZ+@Ibbi=ZvqMeHC%0%9?QSEVHh7ro~Lk-p5 zttK*TaxhFbDt?=T%1mYBu`1i>Lrkx^lsG?WUiOblBaY4tYt(XAOL+_vc`lQeQItAI zyPbN#m)MYNe+rNrS^xkb07*naR6_6w{xoimh#VE^^PIzI^RgG&ZGNl`C;NUapR+y8 zM=o=HsNJ=e%PgTz>8RA(t+sJ)ryF=L7X!08Q1!dlwSU$7&Yh z#RC2w$0@J9)wh&srS_glf*-}hL`vBhZ|BwX7`4K0Ee7DOtrniNNe-jkEbU*<)n?`5 zas+SZ%hMb({bg&kZ6?baUXOUb1Z$~aadX3|P21SS4Ye`rLyu)j3z%E8tgk!@P|mY4 zs~lPs3%InffZ?c|ima;&XV^@2%O>`n7BDrF-w~T(E6p$4PYTl#Eykyo|NtMILx=49>&l>lQ{Ru7blvhmb!H5x7E`8?N9iK3y)Fc zR(|+Yxz(ttZDE3MT~*w#-EUpQm+4{~-RL(XZF-b43a}O^9WO^eKCBm;7jqf<%G%2( zRZHIX69~(;XB&dpHsY4H1?VMRKi^<J6g)O#+`^b*Y^>oF6bWxTY>DPp=TzS5lScCG^b zT|L41NNFL|9%a>cwKjS>8ow|$YIdTRZCk8irvm0*WHoCT`_o(C*g8swe#npNc)!hG zMe1!BY3}TCYwXs55{+v0eGljgOk&TX;xOhefhqe=VCPum#jO_o5IO^J5MkDY8(YcEBM;p5+IIgj^= zUURhn5T4Z&9!H^sa$4FAuRGp8D_86l+1}N%%dx5|T(@r@?z{cYJcFboJGNu-&NmpgnNGw)K>Hd)wesjlUqH=sue_%X%n!0skzwt!1)N-iKA zn)Kn+r|1T#C!4Um1bm+C9^AG6-Gz~2nYNT!dYk>pmPVE1sDpN0qaKY=4@Vf)HF`5{ z(p7!zV}w!XBIAsvT7l>@$`+SCO6mKY<^A%W*-DSzGekeO-MwmNq1ONVLwNX)9>egz z`!(G0cYh6UA31^_KKnF&>GNMG^Hvq=s`?OAoO17t{fCWk{vT-5z)Xr=Nv%naOny32 zo9>ie$)1;(n0eGfYP=D3C|`)}bBV;sakGo| zi62phKb9sGOwRGN?udCzj-zUPEJ)1*d-@oS+uKN$3t72%y21$PMW3TFSd)772vyz8 zJT-A+g=)M+-Fl=qe%hP#qS^-@>BAGlM;KsfBFA1;uI}hBC`@i`h1{arPiEcfSugPeL9_&1RzWFxo^czH~iB{_vphd{Nf4M2Cxm(8H zc`D=8NGr?l@ZWF=+kfyQoVe@faB=5;s4r1Fq%tZoh(71o=*tENZa4wr>GF)$nly4> z&a6?5bmK^WGFt3iCUu?Lni*9w=2S^@t4{fjP-V5aWe48>!mr`{s*RZc!+(lh7~!p7 z_)XL+SGV?E*0)_Li_zP9wvybcSz52B?eP@-oS%7!Z7987TcTvW^yruMx<;hglppw_ zn#C)vR#yT9DpOR(D)}4fWWf;OrwN=>AT@Xbv_h=-@|i|gK}Icf^W}O3BQa%xw*rhT zz>8g30_!M)X0WQ^qoaD`>bguDq8{LgQ0W>f;=H?8C;4Fvah=-X(6A#laZOI?{v8!F#nxr4%kL8+V zByCN*`-fVYaYfToBsHAjlHxIg84Q3P0E4s902+PYS9SGKcU5MFenh@_hrfu7tZvLe z``WTAGs46Dx%>0?zUThjW7`C_pE{eBs;6qWj(PPCud_nebuOn=wb;>-JeW0z%cNL9@=? z=S`|eD@708gGCfY*f%+eKlx|>8e4vC026z*;quKJxN&<5TQ;<^({MQA~35k(*`9 z)USgJ@temh=Lcx{qu|IoXa~Or`LfOOoS{a*iys=I$4S~o(l(Nm%adBY-TbzOAvy-6 zi`qb5-|M{eShsocWDMoa3w^RhV$k_4R{p|}19@M{E$d=#IhN?KRr8RvPM4>hipk<* zPoA~oY~_X1M(Tbz`5KOw);y-QZK&UQI+i|u;8Fq(JCJ@0=PE6sv}MvR*k0uPG+C_f zTiFmPhEw@kQaoL(%OLLQY#GZ#MfDApkgvz`Z6RybP=i2?Ozn~KUyWR-1Wyk^J*hd6 zCE7_CIgu>oP|K}8Q36>Tk{$yn_(AGbp14UMCvQSO8QC?~)7-AqQ$-fU`oW>5@UTMY zo!GXfyrbZ+Je?rj)LcOWi#^?#?d!|sljzyQN3dbke=|=KN0{mF#~Vi<$Nsn9Lv>-L z*>1F{nc9!7q#lF1oml3>ap#eblC6c1>5JMuFI_v{N!XV#eHkLx(8jea<x#DZ_F(2QRIU6Uw(oJNVhs-W`)z`QB-q|K0z9S3mzgp8DNi#b955 z$#ToKr)T4RyTAJUezde24*XWofnBmq_3zM|lU85)G1~6yRD|qEnxjm=OZ}Q&OUsYN zQ}TYE_Odd~zqJO?zZ3B{a-S(8i-kk$FY%~MZQI}Gn*@Ku{H1P4R9e~N@|B*Kwb+%XYi2F}_0a|iA9wkXE$j{Rg)N}u^<*gD#IguEI8x)1G^ z1TSxm8D&lNC?tHOTgD>tR(Z+gUdj_db19!uH=i{pgBk3pfUJM?HUn9E)>qoEk*&6R z)FJDenBRPjuJ@mL8yjBy6I}V}e~8+^h-n?$KN^Eu?=x>a$^HlrR`PItUY+FFm-A$P zZlP`neZlmuZ1GeEq#bN@c4K~G50Er4{PuUT{=5GXH=g@CQ0;I>q$OV`hT2d1MJzMS zqqWi==QcknoBVzlp7ms@re_-}S0860OD#15<*s`=9NnR2w%;xP8tJnhX8+{_lMg$=wCi{`&^L@Z?i1pII&OjITb`P1aftRNbgNT2;o&cI(zZSziSAUK^;l^)Xp^4hgjPozVs(!;s&ZTD z^>_-}<(NFJmu0VWI(e-D=}l2P$-YfQ?y^tluu(e2TVgmV_X#4rb9g_-ZcSm+<*Ql5 zTOHM=tfucMps^?Gaert4Z$9~0AVrq?W@ho^vDdPia~norU!s8u(oJ}bbR$8@u4CU!FnT_Sm^14ld?(=Y`NqpYC{KGH2k;jtLu5$OF?`mG8U14}_<*DMrvR-UvwhDs(L zc;bg%DaMd16+Lzi8R(Mps;6ASK^{)LXfg4LI#f5iY)@N`cH$%VleXoVos*?c*?#Bb zhuF4hb8gT!QEC_~kbSJ7Aser{YK44o7?Pc?()TRT^yMMX8S_E>YF&?3PPa^_p;v2~ zUsyn2PcPOEmk-*OQ&`@04TxLiWYg(!F3C=Mw5IZIm*t~u`?+*|23X?PkWSybha0zV zWBur83ogn#%xsoFS>!uDA0M^r(zA&q@}~!Ez9e;QI60N9GaG5krFI|5;A;bIxs>_a zbe`t7BgEH>y5^G0)&@P#@N@b8=9ExZgu2R(e0Cpg-RPSIPyjpN+zPT!G#6p}__j_u zb)JUx`X(`VBrua@hk51O8Lu6vma@I5)`Ux}L`Fes>XD+2Y+mokI`||lwhd7C?5t0r zOlu3SaiTBDoLc9}zq#!=7Y;+D#n!OBcv2zFQDaT7RNX$Zmo(C0Y$_ey#N=(YO^B4K z44Sy{`nYUfEMFA3oj|_YNan=n%E&RqZkE=hwwLrc@9j^HH*O?X(j$`gg^q@b)iu6OJxq5w1)T{mJ&ACF!|N-pkwVQZ zb$FP!9v%9QY!&v`Jk4)06y?LG7PE}9wA+4-MBQv|2)JgM+(X8C+Pi&}=#RQi0BGzZ4~oKk8ZMg{sQEyJPyrR!SndzxHw zk_6>=x}9qT=MLRv>%qTe{vmFmXY;OWjBfe%$^$|^v~HJu%h*Tq#oNhuCDI{S94HU9Hu zF}=R#`Z@HSKY`h8`*HiJ=S3^ZXY;j~tRJ@|eRPm)h;2hph)ItX#==^+h7zO02ke<$ zsdiv#;kh9hY)`o}%8mdux_dCcZ6Bf}!SGuzVC@gSh1-vR8MQV2qK}LE%IYaClhWR6 z&r9Y`HZ>A?NGo9Ff#(cqlv}MD3q2ZTa?kmCBioY#)>OJzWp9TYm}MVY>0s=vHH}8q zzVz!+sP&ZWW$AZ0r{_lL;Zq(}D;1o-dIeW*-o&$qkGN?h-5VUl51)J-kG=L*rft%h zi8S~qfjs{_pENF@ezN0FrVYQ#X93-YQp#*jX$1#_zTVM8DUO>JLm$CPY>RC)HwHj*kOTgSBR#sM8rjL-G^w>at0B{+S z?OAD_;_hi1x-QEv))i3C+A>2~3h}hXWf2mrbabSrZI`LrZ#;=;>LvhSV#7vk7#%}b z&Rg8-l?v+Byi>|clm(4gIK+@iN}EI^p7jcCmdqvJhWuzLpMxSDnWu^U>mfELEA8W3 ze#T1|2Knm4I6NFB$3k9xJl;e5OzG3R;aZiSpVnX+Ka*`siQ}mlOY^2j8CXoGw(@~X z9(u|nLJOX3CgM9&h+HgE;Wp7HB+HYf?Qa{mrcZ|kpxy+pTU+{?=@Yb0$7781vjLfY z%?b0`0PqO%aMDUMq?xwo)4PTe#UZjbkad^!q+rqP)M)VO;}l@3B~SZZbcjhE6;OPh zEGI?-*EVm$*~#s$j-T)8!Sv_|&hOZUb=PlV@}o0IP)7rmEO49iOL@J$b`~4gLwVvqd5A5*HKC8P5$|So3xFnZD}=%%d2GN(%~=-b??J{dvIlZGwPMrdcR(& zWa;jV4CD2uj^gO6ui^Elp2VGzVRL%&>S(3218+Tk1pD884|hg}aberm2g>Ws#~;Ii zcaLLm`d)KXu}AKWKWT9^j-ux(E%k#&Ru7NzEWU>kC~ak72AjY6Z*c2#zlfx>6NoFI z)%HA0&w5_kh6a57g+MQ{jHS<=+PfQ5Ysa$u>y=6%`|lmxk7})k@$;83e(_4y{#0ru z+xlVOddxFt)PICI{MZ4~O!}m6L=lqCE-a1j#Q9(U9jyK4|AY14`M+`Nxu3z(=tfSL z+Y5frXo>Q%qV>MzHJwi0)4r$nq2wHaF5BkjZJx_RtCnY(KJ+$1#8NE=%+d@&e76&Y zp^?++Y+8u#p79MU!IL@U2BmjtM;N`dm`akTM)QI2=@SWP=Rg?NCtWV8y%Yr9#6IPN zt`K~3yLwJ$(yX_B#m2`){xFi$GJ2R3Pj(_oJ7k;-r{}v`Ny@g<*R_mVptJfm$%Fhp zX-+gO_kd?ed$#Yup6xpxh`%UkZy)G~&xK&x8dT2TE3*uFy-(lMJO~uY5{V1RNvrlu zk_1<8-9qh`4gs6f9n-`8{kVMn8cv=+S1M@RuU8cOvT~cB=O@7dE~a80Th}1ZC~5<# z^RZ@H8dw4fl*&F8sq1=TLTV(^-n^7T@}$8AYhzEt``m_PjVb?cby{8?Ub}g%PuDyn zu60roe-={8@1D!+0Tyi&W&J`ZqbHU%exMZW#8Mj13D2u}v7BlvYIkzlyuJK9nI!Hw zoG^vAERAwxXe*}c%lJswFI=o<_c)X%E#b1xa;qG zTlWhGp+;amz^(>eiv;@94v@TO+bxtCA0&q@Xir0lg8Jsw)XIv)j)~#XA44J9*1gCR zIr7wP#<+ZDQz}g<8uqnXsPPzGSj;B%0C7`nqgj7z+u)5e-HPG&aGcot()o?t-!O8M zfP?=-za{K@jlZo<(i~E1If>R>T+SvxX|j)|hj^cQ+H>;tcU~Xqo|3){acFH!sMjI* zXdQ%R``gp3db~?sq&LB%Tv}?@fen!#S!+ECLWw3G?YRQh7I@mwrqRD`Zjt(H@5zrn zwZjXt34^s`lSf79S&5pt@3`*iG_K~3Pv}p7(X=YROfd@T!7^(Xky!G8Q2KORaSHAq zsPU!m0J2SedDME|j`>^b*J3Fr2;0)-8`rUS#}16O*hCuzAB~nIU%p(jB>NP$s2)}F ziq(tun&wNFSvU(h17wj4ZSJ62Y(;o5ba*#Bs5{+%72*sy&wwtZ%zEuQ3u z%C_ulzpi5eQsPl9UNI&S4gjzjk%lPqAI8O7eO1n9=cVFA_5Nla1X02izt?+fnaYzhjU4qzlro(J^@-s1 ziA*2*8y?p%HL}P9@Pb<9cLdK8QD}#!^?hV*ajvx~kx3=-fV9LGrAhxypUoAS`lRKA zLE8S?i2y5Up)QsEBQ15L%COQQ^X8l*k&k>T#Z)1p3?<68bjTNZA^eJA>1lF%rap|E zKM3)qtRv?Two%gT8LhjiFYPAdqVKwHvc2qfSluSYd9ij%zspq{DyNb0PNx*h0FqSF zq>m!yMXv{GEhBXv!1hgk4|PDkWe+j5Y%!nKTs?yg-~Ur|Oc9Hot{mD6joZ+LX+?YTN^nY9X+W4#cTh(=crW+x9K zYSb}!{3SH1ow&RIIjr;zXZ1_6p0lGrf8#ROkM%!HojElWx6-0py~6V{dX10&@~S4~ zDfNvnNuj0C7RHt&HCLV$vgb`o+Z$?Od-kLy&sVYf%J*AXj_-~P;iJ8~gS;gzEidEj z$a-h>`+sov&fj9S63oiyz6Di;+_Y|OXk@+ji(>;(}nt5 zUJvt0v4{7TP0}SaFDqr-JDFHwE3Iejrb>QuPBBT%X0bGn6?xc@9A8X)qAIT;rB4$s zYY2|gqcR)KP~JF8$LFz9P#?`$g-AzZC@Gz?4lLuXZA92I61~XvNEuY0cYr9j83!1r z!MT-YaB#TQO(QfypVAZKU{;nZ3Vzms(a89<`O@J`X$cZ*@_|j2<}sRbyHO)8(s~ej>e<1~k`kesUY8M@O*Gv!?Lvm$hmY zi{0H=?(9So0Xt8gMh$$d4Dok$Vl!@TScj#qF3k7#D@G#yu`Zx~0^De4O zH2}4&t<#pJ7NpHodd*v&icI}S0ozwMZz>f$?(sD}I)WcIPuPAK0oz1#y}kHw-ySS? zc9vcb$<3>;7a#1~i=8J=Vf5B?bA71+-k48X#Ci}kLZpAhbC1$ChrYC@#Vo$cM_Se{ zh5ntdBds3lxIcxVH(tQSr+)>rpZgiq`iDhnA%2(sS=bhgap}8V>mwaeK@A0JuxU((Z!>^t=t_m%Z&C?BoUg-kq<+k+aReTAtQebDX?b@Y>Tae`;akMi^oD__h-%3Ykb1O*!>poLTh z#%%NKZgnZKk$S2a!$ja#W$syK@)qMg8Ik9qg$P(L?ngnscCkdeSaN?pwJa^{BTGRi z)7CoBKh#OqZ-L0u z2J%}jBXO7g7&$KWsaiBjS@tPCZvu%>$)4Bk&8^3y$!}@4HG1MS583Jb^+YT6hVJcr zJDr%65$p@FrIRhw#E`f&Q7NO`*6^f+_>el;8`Uf!v3j0uT!<5_7LnJAK7c;uT}Z=3 zSpWba07*naRN6;5i7HRR;AeEZNd09wpow^DQv_*AE@`U=_X$nW%ld0MlI^ZFOV~U4 z$Ux!;eLYcW=$h>diyn)S=7W)EQ+%I+u~InZblOmJGWN9P5DyUPq)mtOy&Z}akD8>u zk|@IRn}LcvmxvMZ}J8TuNN4+%VF+=+pqdm&=%|1>lZUH;~ zX8 zMz;0ygQz5~x2K=w$&bauiOEN6Rr!?eDT${d!xbGD6ZVmot}tj@V$t+F2ddKfZ2TS` zo>L$k7H(kn>*UFd#pk4pb(p2*(#j}*FAA*EZ5D%Dr8S@2Rw+07OlYaKBvOq*XFu@^ zfEywW)IEqC^0lBv4&gKQ`6Am>UXLbNGj$njuAj&9$a>6g-K%o72!T+9)mq`9Ni3`0 zAxkV*o=n+3(k(()SkFi;L)%0n==mKgA$_W$@}(XN7h*jvM5DaX(S`eajv`uFM)zAU zV*n9m_I(P=1L1)I3N?HY5+$Cr zU88jQA^K9PWOxzfFD;a;JDNQi=UQT)5>adGNkj;J-=(fj+$r(K+BIF>*tB+C%XG4= zG>kcKtjZouvVZ;>r_^!sFMTia8CvO9TUJ=+!={}RTQR@1_|Wquvi3O2ks8(qGA-*s z-L_t^q}6E}dr%ogestJhGOb4S;Wf@f;~=StWIrajG_eJ@#@4#LNZK{A74!e#Ni5GU z;L)8sTc&3&^;o9a=3De$^q<&=iq}VIz!;vJ)$PbBZ2%A~lY^7NDj@FObmU>8q$2JGo zYwW-u>H~dpas@SYt=3t^$vt~=+p~XW7F*9&CFqvj$UR z`N5V;-CejdGK}8YIcz<9Ug)tpF6`KbOA}j42Ui2YVs|&LY#B$C06RW9EBY`E*uJ!F z3uXq&#kNUm#4&EITZ<1K-HW)^!1#sB=)E@w`HoRJ4p^pB;<3*G?kD#?f-9RhW4WvS zfNjgy$3gc72OnNuLxWga(+vt}XMGo`zjEC3SkqD|iL^sLPRg?-KN{+~a|7#M{8N1N z4}TB!O`Cv946A?iX0T8{vBxBFr``ZSn;d9^2YtUYI-CV#m!%%|N3RO$5apl`oi^elaPbrX>eVXh)heP|*dIQJq(*2b4J%*Id6nNor_wr$vRq$j zdVN9rhVv9GX^=XqnNCQM;J`b_QLk2TZR5ruPvWDeyBpO?1r;IZ9o1@XyUMz1*<+4U zU1MJRka63dwB_+l#%FcUKb!^ccA(J1sCiL&p^lUNBmte|h#fSoJM;vdmrrEwNj_vc z-@%mWz3C-ghdk$8Pfc0ikh;{erV>tQZl&vLNorF5EhQSJ#q9I)%u|^oPbhKlHt8Nt zp-Yhcz;E5K=P`wSXczg4>e^DIf%Pf7sLKrg?MY)Of)Xfh(twoCUEfa;Y=3HTY=;_3~R*wrAK#^{Y!hOp0yjj@{ZF{>!$rB7ppbOvo=7sfR$oTXXlZ$ zZ(3VQ-IC{>Xzj`+v3+FJB5hlktDGi~{i*F25c1;H&C@^3r=0HA>7ahYJQbE`?VHsd z#BV5L{MWvIPX^_%&D6SEw-B{)l4%;Y0+cESy;_kbY9LbUX>~ePiEs?Rx*Y1S#W1#S z^2d5)p0T<4&oMTm@f3+`tx#>F(ZIPYm$CB7Ibd?AFs9Q)xlEvvqdK`ks>x^?*) zS4Qq%K#!8V{;`-c@H=v*9-(HI_ z;$T#&a|$)3ro2&Yt-IFxUhOUVvE?wHk+lj(we|h9m*jnynA9g($A;lGY|r!>Z4N7v zJ=s?2cg{WJ61kj)m_5W!eh`H2ZChKfPigGsVAc?hwNTwl@UQqH=qw1itN!GX|vlt+duTQ}bq=29cU1)uV#gH6(F9LOSjlx38U zDxtij&nsW%+du`hjhQ&-@K}DwqxN-poJv$Hr7RN9@U_-xRkyUPoxG>7cTHVE=dJ6Q z-LfC|A3d6zM>uY@9uE7JKj#>mQE~?kgFtoPcM(s4Y2HDeo*BI;fufMBa3+ z`%KzYW9{P#?jHIKdZzAT?TKTkBz4?*^ttS`avlXm_>b>cn=H$f{VyfJ+Q_s$V)%XU zZKfvF!oIM6MpEM5(c|1|TWNJTjqc^pR?>4CpK6U9&XY;29a7#kDU&i?YcG$fe&sHv zPrQ!%&(GoDuHA^D*5lOHJfytwo~Zk}bwZmE*3BXiPcEq+i}?52&)Pc9rMRw4%PT8b ze&;f}&x8E zvC&e&Y8%GJaOJT{%r7oteEo)&>GP;q%82rCo88c+@sTV;YmxG@$aw&HTQ&1!%$|6i zM?Kx$s0{T0ofT{t8^hSpFsAO_LA6rF_RX6McnWohZKD`;OpQF%l>^|co%5`Y)T^QW zAZk5!D5v~9K1q~k2g~Uae=KX=Xmx<~219w*=!Q-zrh_TvfgB+wYgJQ{4LTn+5_pN` zjWy3<9YgL@8BAB-_=Mts!+UMEI#7!6W zm-d15d^-he*G15F8mBhj-;3)TH=y28!R3i9e&+z_ots0gqiU=Lu;JQu^v=uzs33t@ zCyf%E-?0sswr**8YHp=oLv^Lz%xex5S}kz}t)G&%AOs#~{X=@g9ty)4Uk0ty=hlX` zIKN{X?u@kF6nB4M0QUz5&@(@eN~4Y~=Pv??aBg z*n0Ln;w0t&&e-s(0=6Yx-Lwe+Fg7)X{(Ccsn|`9y%d}})k8NtV1dVEhGdm`6aq9$X z)oO8p{~6KE_3O|xH;&;{Mn}T8sl(nGxTO3IWFmx?FN!cjMF=|=N?+xist(IFxS_IuB9bZ z8#Qb@dmc#YnKq=^5Igh3e99;n`M&6I9)#N>oM)fkvma4cg#Hg+!@!5H0ss~^?R3+& zCice}8|8Uoq0de{dUqw(NL0$!Jj@Q+My;^G`linC{HZNz^J;>^|{P>AcI5byS$N^BfvG zsc!NnCyI$pR-(SQLvbAA7ry)zBuSzs;`Z;{)mA>MA>z2zOUt6BhDsiAlouH|Js$JY zY0cIy_-S_{#e25ZWG$EBJG6G3S-WLHhc4ef1t=GI0gz`v(33jBZ zBytKc;_@!42Bc@$->n{wAsImi>X zE2>@`^cbmHgrqHaj7Zdm<&|+PZz}ZjmTknm(q4b65lxQNMc;;b@${J0RHO+av5d** zh_N1`DK$Cq5J87?ORSryGGrY9ZA(_?FnbsO_Dt!pJJ^b zC;jB)pPVQq{UFm-gj`y=m+db3m)3+{8DEDyGX;?06x0h`FX{(5ogk4(C}$ytlJ`Th zxp<}6cDFV6^g6(8BqPi zf2FMH^7C+YQ5&_Z+5PlkpXl%THD&7V>caNTlDJYT{34a6A-5Z8sS*R9NQVgt7sJF=G`>nZzy+ef~MMVDjOY4SIcdzvKyAF{(f z17lx)gN!BJqUrx>ZQ1KZ^J(6K$QYQAZlvT_T3YUzM0}GvEpndV*7NKQmsQ3d<>~sN z_m5%VuK&=i@~K_SV`9MA_F+&U#Vd^Y~JHN&!XrNL7PTX8K=1l zp0T3(>0h*(#x2Y;^fu`im4G((EH&h zBj>KnN%N$0v~Ql`yV_r{c+~c_Z&9_Up`}J&^PZJj)@n3eLz}0U+CvEbcP-CSvh%sf zr+cTb;)nm?O{|%Wv47_-R9XaW7g6i7J&j0z^><3m-+4A7%+cOS)OE{W-a#l3_oWTI zJz6dx_~Nyzxcc4q@JL_#Cqov?LlLp}ZpJ%hBZ<*D*UkkEu7$peO189xL}8>HM<6%<{R^HiYeLPaX!OU9l)Uy&oZz6N{xi zZ5>|oJrm-jOg*D0!ol5-p!S<}eE5x*aqT}I!`PP-)FuY8w7gXOEG(u?tye|FBk&p9 zgcSI1`i-y%>r)?bu@z$U;_HQ0ctqw4!O_DbY56{0(iY6OTp=#@aFxco)*j2aCysOC zlZ!1z*J0N_Z}J+ImLj33iH2yEGcoI6dLyc>uhfpQ;JAS#!^~O}5O$XsjDAN7yGZ=3 z$6PUa5+U_o*hgW`R`=*@dQ+{PZ`X713Fi8HacSEGE^eJ@!8tJ3+ly1X!+4YB?oMny zcL6;!^Ud|TIvUjqu5I3kQ@eJdUM-Hb0)PwKw*dfFx;ij%{sMYu=9?`+>!jo{>Y!t} zVheDOGS&}ull)Ar8^hVj9k@GO?m!cw`JNt}-nkQTBjxAJuE~~x=|!~M)roUEw`1G6 zbBL1F$8zP-^ymoI%*v5>N{DmCc*+!J~Tt09}hqc<#lQ zTqu$nF4~(PXL$h>_7jWz({vQxot}GFF$#bNnGg7N$*TjNvII@}qMIN>9hGK4dTZ*a zcHkGj{FCVE?k<%+f}SAK16C@gs2L6)XYJf-uofv;2{7n)N-SScF2GDVxSaG%IS#|S$2_Q9}-Wb=z2;JkykgJ3tzY6K|{PWeMPkfIqh@n>>;2 zB+tr@!R|8ax<+@|M9#dJ|go5wn>(UiH+Z>EKwh2Cx;=K4@x34o}Ppl5DD zXqpO0GqGh&C5@&hc_LooBeEXsN9zD@=^Jw`Jp@st1rkK2O^cRgA1*~vgrR`}H2%k* z#%G`W6h=zCLXcY0$8)|8(h|$^5spLoyp~znjv@XD@la@kB_8!`emU~cpzdQmYV@-b zHMTDQ?#z9B`_*H3{?nhqU|)aBlkwW6JbkCr__#1~+AtsEYg|rcTjCy)7~U(DpRU$w z=$W4{d~M>6@hzw=p2DgB^Si*W{4A0r!QGh|4EFaSj(%MJuC*!;P8Nf-m+ry&DLbaD zPPAT@Cnp|W*B*_BtnGc@hhY59cvRLW4|7?b3Hw^|kU+5x(n!E!7~LAYDbn)hR%L`haHvbRR}Y zveldv=TeHed7Vzxrel2KW*f>)ixi;3xk_(Fj%3fPup^J#E|1FEm^6ouxqIln_&(xf z7PYlQ**&W>0IyGduZEwIV=Fv3$?=aD9Jmlj8kZVocx*Qo2~sK+?;Bu#4r zw{^Scx9`+b&tvPk;~07KZ?QPG88bVNfcu@v;sf1lQC3fC0ZQTDkrKo?OP%b=3|l^K z_XJUpI)U|{Y(9WppY!aQuLUjo)mp%!U|j~=J{jVrdyHD7?5LnI-9GiMS%bA(H{tGq z8yH`=zEpX6MB^cEwa@l}#Z+Fa`WVj3(ORfb?&Ubl>oGYq#WtjYdqV@5>ur6&7XV;m zKQP?-1WrlXPPR%LYPX`NJRIet61{oFrn9zF+c+ZICwce0`fJ;vttP;uQJ2sT-MD=l zCtrLEvoCyzJqOFJfl40RrL=vl?T}cm9`ujY9#-yck9+mksG=;Nq@9aB5RV?)yAL=2 z-3$2WkH3w9r3jDwcR!0t!P}~UG=TB`KtFo!&u4RmDXyZ~HcviDQ_8lGYl?Cu-Nvl| zWK%S*3EM$mPqOFQ@BJS?Sp>wt(pHUiq}HW`YW3k8jHUPui5izjCcTtl z8H`GHUGgF|8wE->z_Q`3E8QO)#Bx`sYJ&(3M2!Tax2KUL$Yz(hCF5o)9VbQdD&wc3 z>_{hSL5%_RxXugCl<8ZcIGvyDH<_>1Bhp9G{h_fh>#7E($3{y9Y!}g`=IPv9&z?um z>^$ln72Mje4kr#g+IC(Sw@v^Nu=VT(bk8niel?9+Le;EO^z4b1Cj{5^`sw){+u9D; zCR*z5!tsL#R`sk$NfhDsx-ksjx`Ua4{s#&Iw{&sq1lG(gV0`8h_|O{bD|;9s{rouT z=Bp>M)Zc-@t?MyR7Pl49?Yno;+0lXi5_v_?Ix{3`!$S{>zLzV1{ z`w`b07`ZWxcqNS>NSYRf!|(Yxxb(Z;5N+FvYHa5MSf{gu%uXJ{%G@G`-u@m&U;As^ zdgg0b7_)CNDBF)30~Ps`*7NpK`S>SM_c<^B8J>~jEs!>_-MuK7jNOzFwmat~Sh znp{48o6ozXbUeLeYoFJ7HUMZf4vu!ICE(F8#&(>ZG%2RO-d=p|^It&Enl+_Fr(UVx z<>#KkYzbP6_3(xhqS>l00G6sM6CP66dPaTc6=ZgBggCx*(jw0yQbV^OQu zQG0S6(fa(?E489Z6HuWYonD47`rJ0tNm+_rn z{XIPQ+dq#-Kf4!EoBdIS*db|^4w?DTlccTlml`3Q>V5cidKgp;+C0j;r)5Ao%b^XD zx*`9!4iHZ7c?)Vj`1H-OpMs@WYU$#!qtnQmN)1Qu8I3B=i!7VwlfZBz`{lW6{9V^E zOe0%HZo5E`!scfCgeKecViCmOFrZcUt|LJ@N#cL+9MeDcb;O`dq=TMh?GPdvJ~4#*koZVUxttI8 zej;*X&OC%^t*>tjJztA^8Q^y`P;L@8=$_X(vaIC?VA)MOJkp!N+EIdfHJwO#=jdU~ z_4$)(eY3N8`sHJ&BSy7WN0Ox6kw?c|^2sT3(wAz)Si|!*9Bh zo0sKp-F}>dPf7EB9sHVf>i1Z+f9MB$_D;%5%4r?+0&a-*Nil)#Q>GY^;3eIp%)T%O z_DUbP0WBw1Zqh3(5fq3*2mfdv7Up+oYvea+dy4IjzGLmi*z13d(YL>YsZV_s_a1#F zHy7s0(=FDMv13ZlFUde6D@WGnjk3P;_#w|it^&pxI!3b}Q;bD&O&b;Hon*3C*b9{Y zhPLrV8N{3DP{1S)jyF*Z@p=* z1D!+9ZA;I~P&!Vn?U1%V)<#*reP5VQoz=)g+Qv`==(dtpBr&~Tgdr@3(R@5OtsNf0 zBVTwN?@jdM$liU3;_{mn+re!1xiCP`J9H$(UQAX;ScGBqlaxy72l7bp^aFi1UA>0+ zzTU!3pa9UjrUyMgu@}*XjfLrSO>}8tjWmUKEXoZ_kfnrJq2YXIoI!y&-a#=M<@jE@ zcTWa&Y5l=D%bCKwno;?rty|IK`yR#I@4tW#0YpEwr)7HPE5yNh-YTIvwjK5m0&Qm~ z=WxTE<{&oLC3Xs}Z>#!*HLzo-cXkd--Cd}+2*3t_=ob$mdjAXn;MVjVT)27#NA~W; zV4r_F{q+qS5H%7UeDmF`yj1hlGyCX`NgBUVW;57=a2+1}z%I{@eiA6Jzx=di^|Kwr zQa@_!Pqs_mlYOL74IS9)OdN?#7*wks!a0l@&bs>T5_EK+oI);yP_U=J*$0i=Y)u)~a$FB>Q~QPpm-B z8%z5GaYxED|IVwuB>SYbY4SS18Af{h+B4+7SzgnHdPfCI-47=)_|n7{G~yWB&z{5m z!2!H`=-{gJx;Qa`dR)QIlc!N#SjlS3E6vg;)AJsTA^EyqGv&i!=KFd|odW)&qFS|z zH=cMLpZ?B^_;BwY+!<+avsf#lb(RJynQddOsBKjOxuLQgr3Yo)$3R~nD)H*uwZ6E5 zyC*NFKQ<5IrGNT|nA*~f1Hbt^4nA=Ry=&GKXV8M)dHD^DtzV0SPn4HY@&oIrnCn2E z#f~87+JAJk8Z6&)_5`{vUBu1L{W=!LcRLs_5p|U_O)~aKV@><9F|-j9G^!QM_ZH*u z)zZ6%58|npUq%0&8KD_z3l4{F^USLBtf`JVAe+2k*)q2O>D$u5r?8YPV&J83VC{?F zz?Gl=4b;2x>ni6|kd>~jh`jEXs@E<<-mDMLy~_7>?Eo1o)0*<6FT`I_P+yx*HGCvL z3*Ra7L5;V&i3~%dtAe+V9Ln;%H#mruoQ1h0iZIjP1jexsaAd_O7{CHxu5zUQ%C2TW ztPLOWX-jQ~JSW1dM_MZFa^t0Su4l2JRN@%@Jw5oFmtR7o(ZDl@k6@@j|Fu_16k)c% zABZE>hcqOK6FntmYnC@L<&$>IB!H5&lzkRXgs=?e@zsh4{ao3JqoQ5^Z8<>wUBGBL z#T=T1GUZAqPb(-Z)4mf8)gK{8Dfx>5;k0E6=lNMZB`7BVcqh^akM6~^<9K*9`6vMI6|*J4ko@&;jf@{vmqr&lToJV<3Mzr8N~f#?nCKyC&f?Wn`>; zy46uT&lPC|s|VzF?OaP)wK_wBA}vQ@&?`H&c4AKxr!A@(=OT5Wd|pq^>b3}tv9_f2 z9PiVYC(Wcp;bd{PAV#gD0gMJA%pss#R`Q{F^mT^r2U%B269%e5)RHGt?I{;zdu&@) znv*2{=!g^to@N2`2^+B~Cof;(R<z1WrrL#tRN5lLQ7m$&ASWFtU1=_-+C>SehZyctizl!>FUOlbQ(T^^P5otq zxaDM-#jWAOd6d;RZC!Roywl#aBqT`U2yZ=h1odhqySw%L1+2e*!$?AUk2Vw9ejo{* z>+Q{U;U|c2;N9cso?k%H?2+_M5NS9;CCi&PCZ;V*=ah3x(=X|KNmnaG2t~G|42tD8 zFS0=){t9)y*4wgtjWDzhqS2nO4eU76i#KxY$qlBuza+m>+T>r}1VE=_#K>Nim+27N zqCg`~2gFi&+=tY9m%DSP8)*=ooXHNFsW}%4}S3{zk;|$kcGuOvEh%$TX;6U{!QN!MCNob zc@OHTd@SZ+REg?k4PaU{0sG4uJCj~%;MUqPy#2%xzfp3iyQ>TT5HnAO#^x;yGj%)9pXMvqhOGn0+7Nb4dp&9TT&5||%n(@3145B=I`(wSVa9q*pYStIl?a0q-f0(2#5kb^w`U`c~7UFiJzr2xv zys|2iEGRiWVut)j!duc$@Y{rgZEaAlmZcCs#m#b(tk;yRIMcT5(2~^@X*+ zPHQ|;bLj=Lw1o6vp19dJ9C}K1lBWeCs}b3<26$e^VkYKT+Mp2kuEr0}#}o3}?IT~r zy+^_gSs^CT`LI8s^}g3TS~m3jlMXcU=R+(}ZoDN#V}TT(#hL%hCw;}Jp#ol6u`_KX zUHo=e*+Yx~Xmy5h0ezd_ybCu!`->Pm_7@oc%YTOpKmXr~zVR`H>}$z~EMLoo#3pE# zPyT%(IF*>0wzF^>N)9Mr9$%K%VlPA1#Xcc5l$;fZ`fhEBmuGm5bfJ&)q$SfMgjXLQ z4qdu_4X?lR4p!zC@ps2w#@D~}lc;ef)A_Uy*h&6`@*^~m16NRVK5e!gW|S+c$sIlt{SPqM9?rL_$)R%m;v z{iSY``i^X49v+6sOLJ6=l|1Q}wjhv7!QCIgQqw<=Tc)g&X=@8>wrLDx>thw*_J&cscewr2h@W}s6?DxnA+FUC zHR_Z%rd^)Io?D03y_yftb9pAoZRrnT?aa znUqKxVceqhzfMJWJ$&H#baEtUe?r?ddyTJ$s6*oU7!91-vkTWYm*0$3hOUfn#+C8a zAI@m=s#hx5|IT};)a1+u*)th*Y3-KO;uhovJ7340gP(0Pr`CbnbVq*EJ(h^4<%%agkp$1l*&sn7^;I+j;fa?@#U7=YTdbEE?sx~4kVqG(WS zdE#@ zVpW6(pFM*U2D17lwwR~%xlpI1r?S-$A>GVT`gJHfMuEZf^o-HLL9FBe&pX4zxf?|C z`7Z)+?d?|f9B4geia|?WdF70089-F*=oUTg+mi6NKS|}oIcsjEy`g*TEK~mBt~Pou z@5Cy3novIfk}KBRa+)bW&#>352Gj75IBaCsY2ub9wq+Vhp`nbY<2Wda?`vx=ulXdM zLD?!{n-d=J`a*uZ({N>gE~TqD`bV~>>}jdPEf%1wI=DYSUwwKI*-FyNbaFxhxx5u; z{bcP}!)*t-bKjn(6)yJsbtfs{3BM%6UOE_DF6i0zqlGaJN~7-y(vvhR%~y#LuX-Xp zloqOG%3Inx%mJY_J`*-23Q3kHlv_CoPd6aUsc|3ooU9`S-c$LJ+fE6lM@MmaVqCS? z)VeVhNLjB|aAV_o4Bwu{_{A%tC1Sy6I(c_>^CnEK8_RfG?&wsQ_=89HqFSqA;`~Jn z-np0c55S=(ytR+ofu)-_+sU&Cc~VC@9)xxzLeuD!b<66UHjQrcsEiej)W_-*?^>R| zk$Q3Z-<6x7~m_6tj0j0WncAQmMO;z@glbVxe+#;wL~CABZH! zN#8Qg;`H)=UrROgTz+VULw zc_d@V1YSZR*A3MxstQ=Py0-S1#-VF90h>BGFeGNnx0)FHP;o`gRN z^1aL)hDrw)OT@t6bq^u9<`&ufn?J5Y|AaNazDE3bcCXk^V(SnF7G!c3A@?MCmDi`X zA{u=z`yIzI{^EsiR7{Y@% z$1+E)hbdowL`s=T1pY#hmbJ6i4|%EWT!eg12itOgh4UBThEI!cHOICjsihcyLf!Rn zuI(H7y!IfazfI@nR+=^9yYl==je|JoK?gf%|BkUbzsJ!VH?oBy!IRw-uG^aPldZs; zt0e9rDGE1s>L4(FO13Da!F^IQpkrEps8nguE_Si^qFOu+Um$n$aJ#0lu!zzmk5KlpYyn4?^n)M&=}Uw z@)0ZCrn0BgixKV|`Yh(UN6~ZYU93I!P276=XPo}<{a?=`^8H`wuhN_n%T1JVs!uDE zAvoN7R70M#4J}bImI;xj-p)>Gr1rDVd+C`pwr7o1SEEq3sqD|yp)t~Mt!Q$~1UgRK z!fU_tNBH?4{$A;T?bVPReRiaB=PGWlUx&AzID#jB@Oowm8B?(wY5Sr5T#HGO z{nlt-d(C;$RNgQDBoMbpK80APD6LJ$t!Oq3~Dtbps9W_Lvm)N#3#-Y}eT0@dVQh5|w2Hn@>-^u${t4X~t`=qkedHChoZNMQ$ zYeo0xX7Oj=`YWvb)}I28KMOoS&^9&=ApZTYq48UP4gmOxKl$hQ=-fG+xq5l^c?ydD zo2L*Bw||Pc*DDeS7nE2cO>xO(o|pElXuj3<=irG~(0ln5?mhWDrat?1k*;-lA%0K5 z8jB8WNhNh{{?LRn}6SS&^DD2DbCWX5&?x0qGx<$8f#6cRmg7XdWU{j zIqa|J6}&p>-~N3QwCxG82Z*!-D(^|7K;V=BO9km}o*Ns&1=8zNQ)o0A=;_Ws=KtpU zbpX=cV%txj!{GGYX2VkGigY`8SD2lwk`4!-_{iO7DHK$zmO??!zZ$8M7zXk5l$~y) z=NhPB{q-9-vvU&o7*5Zpz>?MmDN)L>Jz{tzL9msx&E1ocM>=?IfR{y6CRX zwVk#Y9U8*e@Gz$C+$oh_15bNTPr^#+l0aEl5w8`+|Dl+{?aA(bt2LB_vbNS5t5-`|5PTQ&m@FGQoa zZe#S;6!;Y6s9Ac7S1)ecf`y)*tlek&`!Th4EGM^=?hOs%-q0Xs2Ko^tz{X2gvwIcP zP(cHiwr;^f?;1>xj^JK_6ECsujx%R5c>7+HQ#AWDZI3iy5lwlFK}-L9rk%z-9KujE z39PT>q2nmav2|WW8b->X^*by-AujaNXdB|`9DV8z>6yA1hdSV)?6^t)m*@A%a1&&? z(}oVZD$kDOnz5d0fJ0x<^ceJ+U+h_smZGbyxpW^{i&5lyvi{PJujim^|3~rx^(@N| zR7%g9hS;6CDWb5q(xpYg}5 z#cui@r;&D%w3C#Pba7cPa9NMYyH(R@ET^H) zZC#$$cYu{IU3)5DOEdG%->s*k<(HrK^s?viFt_@n$w$E<4G#?B*~3Tht?zvoUwQVq zmM2Qs(n6WblVScHsXk+T#`mGVTe**sHx8_J^Z1vW7Ny-w4s}-%H8(R8J$K}B z4CHKTmhz>q7ZZ6edD3CiN(BU)8#iU}$b*x#zD3-5Ix;W4)Q#SCB8^EbF48i} z{!T;Xud$HEHg-P7^6ztQ{hUbkt}oj*Uu}aqS7{TNYYGPD6L&4?yczBA7EyVht)A7Q zt>w?dos?^+KWuw5CM7!~ajW)?^(mmzKG=37>5xnARzf0CTOEYs^*8y2iIP5A=;xq7 zdjAx?iHe`(b_lV!4AR!8{WAA?n~pUxex#?+YEU(?&I(){j>4&&tBM>1~a z`g(IW4c%D39><=08r9_$Jn`Ba%~oPbiP6B#jq7k>avSQ^3KrLNyZHdX`R&_qed7iU zP2a_y_df*9Mi8IW#_861YJIBZnq z&XRgjaA#x~uRr}HjvjjrN%mg5P$Q@IF7HSlt_!2lFjUr* zju3-9Jo>ouEnmL%8H@Y?X@jLKYs;ta$uyz7TKmL41`?15>n%gItk|@gLK>GmsHpI%R#3%Ck zvWLTb(&@Xu{s*|WxdR9O>n~yd&Rst?KKgrl@pI3A1%L6stl%$y<#+KDzyFW1;n}^b z%4@K%55N42KL>o_%fLtvdU|^>Hadc%wL|DEbqHlKJ@eROZ6A`7r*T;p`At?nj?vz6 z8JyFu%_)nWtZk@wZ$y1`0?9}>lDHD&B4^KvxRT>579al*24K^*Yp9}*cMtg|p1<|s z2RMG}BaE-#fSa#8md zmp@~`_N!Qa!m=&L#j=-oKMB5T|0p(*lI))a=Pr$OgZ&?$+44Rh0mip9(~a^X}^=tSH4>(E$g7FRd#I4hn1;}) zEbCrho4SRoKllK1*QRlH)27^$grI_>RApWip0Q!dM)zn3Pq zV6i)YGGCSS!f7NQUPkg?-N%)iH*w?k6ov-|N^@%Y$xp{qtKL0%N4h$Cl9$tR>1CW? z&v|;-0o@PJ4fk|qUK;ImS)BmDkq@iaVSckyq8Fs?NdVqhC<`6aJ|GLpePK@@2|_C(a2A|;s*orEyJIzfcXPL$~jOHVcr1$y2SgK1@_!%Tt&m^A}(#_goPlM|rl#w~gVmoW96T zSQ`*79%w`@(@Gs7aiknaGDw6@TnIN%gqs~=B$(^%%{HG>DdQI}qhn23%8awt%tNcH9(tph&#EdK|a&^R349#KY9Zg+YM|g{|d|1l+!MS_}2Qv zNstcNeLtPYe3d47!TM_cDsl)QHx$zQ(%JolOG+KDr#aCpyN3{?AapL=*R zPFi03#t>IMJH>qDw=CN-%EwN`K1|=ZJ@WjBd`gr|`M#+3pTe?|AdSR-X*%*j*ry;b zljncvd49&Pk1W5Tet8~>wy639;xIqP4zf063-~+0CuvKZB#GLFgLWxDi&>~_sSWdR zuI>w|1EgLKTSMy@=@YV_TTvUiyuf7+5>8vd^MEPToi^{ZNAG3 zaE*}Qy#xEP)ZLYFvGM9PY`k)9%Tatd4+p4j)84 z=TvO1VSq>9c^{SKS|(RFHm}F^O&hS>)rosUqQu!@*cVn@;8w+dJV7|8p9m^}&_s$7KS=*4e#2yl@1j*i${*uJB)Y~Li zbx2)cwRR%~jo))Rc zrPfWd?o<+QAm<=$-ki@olJ;sq2AamrUP>jK>cksAxXx_*Ll2eP&d7LoHx?&$WBJ-? ztbOGhnER!FR=V%B|I0O|>srsU4U>G3$LnDembWO#8?ZIw8b&$!`Dm4&lO@|Up~P9_ zZ>^bpj_sPPfxkjxWt4NWm|d6BQ1=R{vx>gWV|ez+9^;(k=Dd7=ZFRKt>=tZ`x8Tqtds?QguGG-Ayo4Hf(=ELZL0URXjPNSZ za}jdY9FTPj4`m23P3Y6HWl#I2F7zE?6Sm{+lEqO(+Uv2{kkUw0pMG|JbP5p?T-&s9 z72Fh2BDAiQG~!R%7O9OiW@DSeZy%9Z#Lm51%3I%=@9DuihYy*w4@ahF2Krm3>0Pr1 z)zLm+WhT2eGB}8*4je>Zi@E$p9Aj}!x01WKIV&vZ>?IZZyq_E@;`B(98a#!6=gmby#6jXW=} zU6ZI+D%f)VBErKj>3En%rh&Eps%1dyiHAD}L;XaSfv-#A{v<9fYT-CF)-_9AU8q-9 z|EAI(ElC8B{*FZtvHx#-NA{k4zP(=hyJN55=>7v3>Tj((^Jrmd5r2Q|7y#fiPdtH> z=g;BB)NSnEwhfPL+rH|20pQR-`8n+AiqN;Q+@X!04$dPVo%s~UF@^>P@chsJ6dH$~ z#K^AlYYbjq{e68vAJ5rVDiw5ht$yrFYA+v+qSzO+CwgKvJzaR};32FV8Bx#l_4H(?a(8tW^|S4%kEiDVAcXx!|Vgk4BOyl<5yBHlBYFWv9LxY$Z96;~ASvBz*8ZUN_ z@+LQIefg|M>$vEJ4B0-ME>9Tr6aLhNCoVsF3MVC3H+Tu+dDpFa_ja4xsU&ME{AnXQ zrAAjmC2J>*LLMdM_e;CZ#ii@lapBu<17~mJgQs_t3flImeBbD{(m~pCQX~DX%LtvC zB7QiXCp-SspyV0?TAdvc1Q9M2H3GvZSUEMJq@P(dP-iU<&z`K(^J~fO4RdY zmtw^kpD4u3(Q&rqOuX`WR(ffkIHbi63u##Yg-&=hSsNX(AHKeH?Dji})2&c2%5^JUh@= zDqtG`rpCrFHI{A=?3tTKM|}lrZ`{O<4kzH7NKxcTauMcN-Pp0`^zm?@%b|aFc zo9ovB5wIgUi^1u8NNq+%;a;l%zCc00AEk!jO#^^*Jaxzu-zlR5J`QZ^*%PT*wY++1 zC1#Xu66zuAGekAM%Ub-(WG~JUnx;zfnrE3`s?V{bhbZ2B3=XP$#^yrA2=h)CN8jS{8#Ixe= z&=3}Tx-*^1fngMCRZ)D{9+6UG>qLuu7Q6GalJXd}!TO=phEpoV)DEsc`se|?e&iA` zSZ;HU^)}m~P)p~N9`8~zrA}l{WdBM17mGgiM@imh2|^FPUmT8g{jA?UQOVi^GjntJ z;Sb(G;}2g0zVtlM;v^B@57GBMTqmVlx1VfR?_^0`hJQYm?z1BP((BsR0cj{-)sz__ z!Sv`bE^RG2XD~H~*Xkv51p^o8op1-&uh62?Tic%w)h9Zb6V$U8<>deTJu})SDwff`o^}sA}3|i zTmqr|ISiPQE!9PDOOkIWNub}|6XGYCm;ApqcJg$P*2mhI!EwqWLkDT*}o4p!~c8r^$#{5PY3OAOUcH}9gJ`QRq8MX5Q z6kG-9Hk18o{eQyJx{L&~gT1&i5zZB|>_-^AHHCH8Z-K()Q&gYIl?|T0GdheLo7M;8 z^V;T(sEId5EO)1`q274qny@fH6==3TwP77V(mY9;d80P5C;E|ZzSPr&^OM_w2)MCv zL+Ml0qRI(Wnr}9Vk-qI^wI|Ru;y8OYZZxptqca$onZd2~YugSyTk7h<&GqZhwYY>T z>ZpU~wJ4~)ZnTER-GqDDPomij_C{C>p!saxn72L>Ymc(?xxS6)JNF)@KJ`^BtsT!z zop-a_PVjnvre(-%rVG&!-T{L`2Nt1k8{3U;D zJ{jLc;0;_Fr-pU5`cEFv5YD$tti@i0nD6Nc%B)qZxI5B1CgkI!UiLTDh($7cY6D!HF7+d-djqEA57h#XE5BACTnID|m(N>zI$K%gXg}TCO zSnbd8AtbCrq`u%y8*{zAt6KZXqlKO|t3Fi7(tJ-Emz6{jww${NdZ#YEgEsYdy^FJ#FX74k#V4mnK=#JRNcDv! ziAp7Ew)vIAQcKIrc+3g)-$L2Y2v#YK6~dSrE%9&ge!O0d+`iP`>qT;1Q>i$^DS zVrgX=^}7p*e*0OVk>JMf{(tPfcaS7mdLQ=7%rfo$w4L@n-tE|(x%CEnxH}vS4~8H} z0+0w2Mxh7>2}mMDAs|Rphy(=$A&C@3fe{iBkm5w}0Nx#d!`<%f-rCvO+1VX$yT|pk z_g!6GRhg+jvR=LKd+%jdR&~$r9-(idrmHevzI^sGzxTcG{TWd3u=ziA15fffluRVh z9TE)LVm%pmWQXG-W-_PslPPR;4`Jbn7t#6lpJ1bN5blo3oVI0&%%@?AdlJnxl}h%3 zno8mZycXOCsFHGqT{lZE)AI?y%&@}?WD?jqoFJ9XfO0iytTsnSzrA_y96lbHi*QAEd!YP4FUz4^7^y2D~&P@qFzqwnG0bi-JvqA)zA<|n9PNb!Cii25|knj6=G&_sJUq1qCc?DKWE!tb#u$EcJ z;>t=W4>9fX4u7*W&Qxa3>%&bGJzf(^zo|Hp*JMfwzEy9cev(FfJf%kEp%k3Zg(>F+ ze5|N4h>s(_D9RT*Jtd7f54F_3( zuu1!<+lsi;pLslRc_qg$zej5xMS+3OTgL+J8+Gwn-lGdgasin}zx9>8_)Ma4LW4H) zSqVgm=%TP5$xCk;X&hUS5rd>*A(o}3i?nzWut+X8PF8ZnKw0bMk+;lr|hEVj3V z^rD5-<|Z0f)<6Li`A!e(jrGXYq%hOdg?j_xhVA&sFaTiZ{RbGnJ&xM74Z<_!A;c@K zO>h$qCPs!Zx1;)#1{igE;JdjEjd4u|@kzX{NIio^50I)f;G7UV~WL zvr6NucH{NsJ^45sG(kb6K~9sNQb2J#s zJ!uWm2j&USX9el3HR`9;up)v{M)S$I8Z zAJM)A==h`Uq1s?3NDfMxa!5m54OX=T`yM<*E|rRmq%<}#fXmPB0y?9PWvi697O37) z`KHMpkh4f_UtMPveQ2}3^o`G}C6pS1xv#=>Jz7JqG0V}R&Smq=GSkLp7PoHPhW(wJ zKtZ?FC~cZ6^L5zP|4#3BH zLjz`aMDvGIenV}ro(&>*6kHcq$M4|a*e-bGc6>lT242Mn_*j!1U)aAUE^oRLCYxlA zfNoK5w{5ISHT7QnyrX_sM&;~cAADZxwuKs@S#BET`j8E7uL3@Cj0NcY2rsQ^*2p== zqw?{2Wy;HEsi`ZU+|X>1T&dk4?Pa@kC^J?4{PXv}*n0$d~ccP%4*2Qp;1HOnJ(Dq%*X1iU)Ym6j5{T zo+R}NU7pb~DxF8^={LeT2+DJ`v}#?gVmYZ})=EngCPoG^-P?^QT5D{81)y_krZf^o zKZ*PjC}6Rp4R=QdG1pn%7G7>{#>B`FEcnHU+d(^7(2t}Q5}xXhsuMqT*tX%JkV?ki z*h6SycnCvx#*xl$Vz#Rj3)`@W4gga<-RQgj5VLhP7#|%jYfFWZn{aSz_ZWt5Pr!C* z{ARD%*OH(4rAV#ZMiz73%3ztgTe4%C;(8G$-wbl?3{Q|YU4nU@QbIliOu<9rVBnq zPYSb?G6r>*JX^Lj*EPhisDAO`rE9T1v=6IOli2z7e}zoXD6%{H;oI@>nez6p)Qx#+ zu5GKjp058}hI{7N~tHOC@k+ zDqmw!T?&ce4s^7(Rvc-&oX$hb%pFm=O)u&h=CsY%zf?_%_cE9Ey3S?NujFi#xVZ}% z1|}{I@7#&z#zr*Om$#YM8|tyx+Jb@cyQ~e=(IRUQryM#zrftr7Cg*qR+JgRDUw_~_ zwLUv^9g5Cp{te_xP*Td5`33<#NBEVvG_x>|YvbeCJ3Jiw8PhvdJ0rM8*K7DjQ1#>w z8g<)(ho!a_Om}x_?K0WdyX9ahkBxepfL$FxTQKgIR#$NE(G(8v-d$C8oVN*5-I|ZHuLt-R^P7M!{+Nz@9{&v(`&qM=s2aewMeh(RdnoI@NjRiKlUj#pBAk* z)Z^aZ0N?}t6ZesTi+r*6x(+EuDz)?E*p>W3#{hjczE$i;P&|37f2TQ`|Ee;lk~adt zwg2N=SZcPh^O=L#*%fU!RzlP7Uc*PO0K0gf9#S6w_k@s`!IlRR5S-IK0 zeCtNt_tLePJM|^({{4S|){kGu{E5#a*IZqY09g+chQr4fwbwzes-+F*JLZ7Im6nyi zJ1i}KE@5(DG@1BZ44V|r;JR>Vr4WD(AJd&3xVd{*R6PKoxP!M5$M+v7n-&l|x`TJP zq#Ob$62EmJFFRPmKxPnF6_V!fg2kJOP7IyG;X_`6cu<99S!io&#{BY9*|d5|bjA^8 zRH$jn4`Wq<;)uPFH-_?Rb z)54vv`J&=il`02y?qR zwS+pOI6$oOb+EJ?@H0h?^5CFQ0{+$;>fzgZ9D5%YY}Z5GdZtt=s~90##P$($Q{*Ye zL8h?|uq?>lq^%I-Tf4pix%kV$G~qrQfLA||%gG^m5 z+*AVRo;(@a6P+_N*nRCr&}zPg`qiKjW+R?4-<><*+73o<-3DAAHS1Xf(b;$uJg+o<=ts;e2@+@PYH(}M7#{Uh ze{AGtI*oHDPgMPU80AtaoIABW`ObB80DFPs@129#ARuBiTZD7?rC-9WLOK9T$t5*< zIrmkKGoBGA?&ttqoQU1gMD;Jq!{~Sj(&>>4O}Y(z-ezM-@@xlgDT4duBL|SFuWa}4 z?XgjKu+TF(g+#7^bT(UTeZi0X;v%*HJ0y<~<#!?7Tqr=Q>Za8A+={H1d8%^2EX%0{ zCHh%4gk`OKQa;W*1uRBK3>~R_%u%Z{o_?ZRa_T+RnlL@fBW-j2MWz~BqfOO^DcHif zlx|6K4XgLTB<4HXV;z6H9b~Z*$*5u+XW-YuiQ8PNGl2LmBaEqbvB^f(^G4|nJgw=T zsm7-KC~u}^tAuLPH5lDJit(3r0g33vgw1pscSc6gf9HOwnA~QMCRt}{8_;&v+g`py ze&;rWsSQon!{!ZdH&q9UL(}u~SonAxGxr|BdX68rc=6^9jP(zoE+X=i(35$|Dc@3O zoUgPc=Zuo)o2(#e)0Cq)^C!vz-5v@X(_D6ydydN!GcPueXVuo?c9qFS7B-p5cBVFn z9RDIfLj3s@rgaH@i$_n6B3UvS*GpD zMVusMLydGSuy=V*5`UVu9gR+>NBWiaFs-{~`Iy|<1K*b8i}paN4_zO<4;~dQB+-r@ zR$CfzZ)BjX!!`gcwza~yEacKDBy)LmKAMKmkc30I0}qQGt+5=o1+6qU;m+6y+=K(G z;GyT?qhjp@(kSM)u-~W+Bj+%6*xqQUEu9Kf4ULZs!}dJXZfsz(uXo#=wgF(SvjZzl zO;tN=13}cyo4a?xab5J@pM;Zh;XueMItttpZ{YS5B{RQOx57r-v2jSZ+f46mxN{rp z{riz`)Z3iv0&*Ui#zd4(sOlAh8&D^0dXkv~7x~&?1Hi<{P}!Ph>gsT7*BC6{FCnbm zQ`2xZ-4eeJHqkgGd?%QjB62+~YcLbMQV+|zQ%geS($TrU=i6Vy zgD?C7+?oc&)f=MiUsZ}&N@@6}AeyK79r8VulUZ8n-Mvrj!GZ#SI8?p|KK}c zA>rfGG=AwjEko(UXkmF76NM$zzOoPdM@C~kW3r@F3ey3&KBene>V5G>x$a=no+Rn< ziS;*AeU9rKQohT#a!sWi^>ub3nMfd)FT_f(+Ai{=_Os+kdRe$_&GV-kC&wIUJJS<3 zxRW;jP30-om&I6C^Oo8r*nOQJNy;aZxIfU3{=4@v-Q9&;It75*o<(`)dFa1;AC~Xq zQEv~jHR}+_L+tGpb#(FHZwP31y`y3uW z2^#*fGgv>=0rX1!u9E#9>bQwYQ$DZq^L1woA3o`jCO9xGojkmEYAl9j1Sw zGzTX8doeLGT=5#hr$Ort^_c4I#=ykgqW$M6^^+vWVEK_KG$MftnfZIzc#R(ITz?9F z<-G!~E#Ah#)*(0we5gv*O2^j3*WSgw`57!MEdyVE8qEz2n3|izuED{I@=kaaXoJ8nwmykCWEEc7A&?_Z+8Pg_tX?>GFe5F zGKIhjNcNdNUR7?g-SSG;R^s88b@#3!xiW{<-6xRk8i>Rxbqh+>%6UteY(AP-Tzr3S zaS<0^KZmue5Apeb_%pbA^A@Zh+ym?7F<71P{0XT&8l6s(DQ)!gQGC6a!gjFP(TA1Y zCy_k+EjT;(0x_MosXZ7?;r(y2D5BERbk*u5VYYX8WUSN8asczK(i4|R&QMEWkvp>e^^VionqM*_qbQk3 z;74D434iqe{4wB`cR-{R*J(g1bAWGXV@Wz-8D_Mb9E(-unL1hm+(?)2qxFfZOV~Y~ zp_u>|8YKtt@nB~^Ztg9=^Y-A_F8F`v3z%D6#52c^mrWm!D4?abIbYm~0(GcZ1%&az z1(4d)6qJlZ(j`@vuBzCk1rPo|`!4XS&*IsaUqVmE4s^A*VgKkDk`anj*!-rE#cT-2 zS05noGD!PM9wJ+ujvW2K29dg21=I{$Ri^Ni7o;*Jjf&2xGQO_oL0g9QhY8f9Evti{ z6hIQ{Bv-N3@h+pOsz>3eF^-~ZL``{-1C8XQ^D;FL4mom%?I1S*#iMa4>?js90C5j{_gEmX%^Kd*5UeTetGzKgm*_t%od+Kzg;nlRVf|KvP z4;Ky+oB2}v03v#j+^Ouqf(yEAqqdP#u836t03ZNKL_t)P$JES`i@)+HK^q?6SeWl@ z$Ax20gqBaxOlK!%Is=6_wVA^UfB7l^3vSB6l_UEx-(L9?lr!eOokKzDT_1<89;6>GLfY{V=kY}(L8qJf;IrKw7LrT@gi<>9m#`Bv~970K-7S?glb2~G-?ZS z8AqR|_r-IZFPYw?Kc}YOF7mHT1D%72gOyvM^$gn4Rnqd&6~D}?&1G*E zQ0f^Fk7ujruJbN+9{Htj@*T9qdO4zKX>|pc-ue)WcOIdC^mzb)W7`<)>4gs;sgyY) z2hH7QeJsi$+e(}zL*pJxX+r0Re)58D+;<2ltmf6)90DAYI6zV|EU<8?@b8Qv=3FhViI3{wCk0))p+awxBMP zL9&oX%j_ZoZ9XW|YI7sjV?-ZSX|=Htmku37GM7iHkVo6>0&GtPqM>ajc`CPo1-`q{ zP>cJ+13|>REzs?;c+QQL(%qrKZOiN0zP+$L4_yzZ;p7UXu|lPR)R)vzEG3Lc6K1^un6SD46wr#F?2Ohojx6$|K ze~8&9zl@EpA^4672Mo8YX%DOVk~*gNFBxZ7_MvX|h_pNfFPT~<^$yREYnAGCJuOe8 zrc>=?aW9a^>ZU&`llW$Iu4~hfC9*_uqCu)OySRXB6%3krd*2N{PHaB6dp}f<_`bHMn+-BKyvdq!8 z6Sq185wv@yG>4q@5K`uz|rX0+4>>wkZ+iJXg@*d?n^m;Cp z!p(iVkaBalJvxewI`evlQ*e9S;@_pg3P07SN1CqZt+yW-n=itLae?uP} zJEibtoli&m37N_ePO4T4^qn9i;s2_IcG^<{F7rtW7BAn{=> zthEAGGwY~Lr?I%QTy=henvV`)to21S)Wx$QIijGF2~FZsa;tQ3tb730?Ia%-+UMqx zt*s4R|F4vKA3j9u!eVhfgoag}yivTox`H{E{OD(!glYuN1U$Lj855vjIT zHy#FDeP70VF3fIE(1;rR0W*Y6fg&*hx#B|8ngoA1SpY8ni$BH1=~WE==2!6fr=E^c zwctGtT(%fpDM^D%SIqc*RY{|y8gu3WqXPKiS@X_p50$YpQkwtr8^Hg45Qwo*`biL1 z{!}Mo{TMNBeA9F$5Q6R-*WWDO8@Hsgyef31UZ;TRHP$IMu%QEgJj)g`tB3flWr z*p6N^8K7#3Y|Rv{Ug$AOIU<8yj#pIC0)UXW zQ($(8F(#noa;AlNm&{?SBo`aDOHtV>37}9=n8Brw&}hC!=RJ4K6K~}}oe$yWtb%kr zlCfA6ox`M^>kp07*lzkHARxViQ>e6`qh38O?mYbXLoga8f zyMFY857G5#y4Y9p-J3OOyzx@`d{>&9@SPuc3AX3qrEh-+PA*^M58_M_q1KAXW5I%y zTdFsAkmqC4gL<5xsJ8_lQ$5|d_{8C|Wi*j(`GD`^ozrKq(o{LXC}^g;6Bm+C;N&}J zVHfN3)-%sm9nFi9=nKAp!{@r3%fT;cDte`P{8xqM+uQNp=~H;>jkk(3DWNUyt6;DI zgjJI+nCEhV1lSg-TrqLpppwcXU-=%XC8Sn-;Ljk*YK3&qsl(VzihfhWuZq(IpKx zpi!!`Zk$@IlwroTNk+*$XqnXf&3WiEhnKw^pNS9t^Y6ONT%LM&bYdf$#mf3xMW^+I zQ@H(L)&rT?AGY~}<`&jZx`a2=o}po6fAU$Jz4&qITEcPg#NNGVZ*GBYhdaQi z^H}Pubkh*m)u@##2>8ClwB8(P3xa|13O zJ&atL;3kv~Uc7{^$!XYm7c`c>0~fF@tTZ*jhL6jK4@5d4JFbfp@0~;Q(lTsMZZntM z(T3O%=@OnGY(3d_V*E<^F4~de0>W|KcPuP+wBo|?@|&1}V589a6UT7k{c~uYTR^s^ z7Pofq!gP06>^7s6sjI_k8}$-wq}Wa{g1b9ZH@SgDjxC2{`5F+Bh6*I;i- zUMn`oh~EH}RdkcLkE!0CEjw&~Khc!~`%$}=LEG#Cpv*V=o6dh~^XeqzSCkVsw`8`3 zd>@JIDtf;CJGl6dzlvO2H*{Tt>K0*d=X}&QvbGq1OKW&XdLknh4|1frb<7;TW zavu5S9mv;*Irs9Gr#7icV(@ksnvWWT8(J>(eWHI%Hn+KUG*y%xZ%(5l#uodnYQ9l+ zw%KVrNK4Opk~#*}C3PLNe7($6o326Y7O+oI;_`2myqO1d;`2@16C1Kr=U270DK82} ziIkxHp44Ad?ThP)s*M=T!GVc;uzW9YGOUYsGThPHinYmkEL^&awu6J^8&G*)P;aMf zo0i90bUTyd5ZwNxx)%LyD{ByeOOlIRO$r-zwODVc$ECy3>xtD6-PmFxH{sx;C#tiT z8wNVDudW71_Ux(nS+QAD5FamM)KM-#by)qRh8z2LSLSg38KnD<9$|5H1>GIh`BJD> z0_APgQln{1$eH|Z%9m5Lz06DZS+Jcy36eF9)~BfEDAI9$qe@b4X9MvuNC22$T0*{1 zKvP2l>S}7Rv6)47a}%vi)o(UhSzANq!90+6ksj2>wUm#j zqp(3d0IT^7{^G$o0Km`e+JSmII4wZmOczDErWBt<>GU?XEgL;`9k{W4AN_T0sB>y@ ze|-@(wuP=5vrXHyvWoS_hO)Nw6TkKq?OJ=4jlwJP(K$5(+w*XJ-yW$%C@p#h8>BDPRapCv=6odI%;M9{<!$`YfO0AANl4K&d!7SVpU&$KbiJ zOHSKV{nPkA>z^oZL6{9A2l#Q9TO zJB{Gt;X^1S66m}C075FSHaFt^Cr?(Ck7wI>{rTr`=B;;7v%Ud9U5r*iVuz|PrmgYq>ka2+KTc- z-af(DId}2|=66&cLHzrf!pvK~oF?^0`J4)>sS?X{%|y{=O?isapQAxf^%@1M06Fhe zeUi!mIlj2QEo4ZxHjQ_mKC^Adp3Uv(!23_0#EJLL73YwMLMTSNh%hE4KIISPH~`lj zq(hQuA5KCZRI}+z>Un^ai|Qzo^2JxKnv8v(r>u`DO_;lc+)fvlxJ5vrcz)e4^@^Dn ztD{jbpRUvBZ{m7U9Q*F_?OXWx#&wMK58#C@+7NL__NsIyFfUMWdC%{mlt#DMs63<` zhUyOVj&2iDzLHC&;3mp%;26rh@AtySa(XdItX7I>ct&xWva^^s_ejn3c8xcZfIP5T^Ii zP2*JlR7;c(3KE)e97-h;Nc%Pl(<{h4T7=bBhd+7kRs8f9zJ&Uag%7p7a+4^vgXNNs zY5vPNic&TNQN*adEuRo=6=!@niD@W zeA>~aLkHo*LeIlTunU15=Q<8@sWkGbB;I}cOssrd$H9A_dlF~feg}<9D@Dg`>5v)p zmUQM8Z7Uoz1!AUSB>dprQgrQvja<^fYEvUVI9WL!aPH&@oOu5n#)pS7-?24&F`r7} zou|*>*}r@p9&B7bd|=xmNakx&Nar_Ud365DHUs3A{eZZh@K=pgUKfV71td5N-54vm zepCx?Hx5h7XS;bcUp)&inFefKXVvv+X(Q@*DQy#v@fmYaAgQ}>{LP1#uu({Ej}3f% z-yV3DjsA)IunJOxu_423(0-v_pU1Mj!)Lfk13f*kEDP_RKabVBGiV&x0hE!MmQsc&ore;4Wsy$W z4ho9AmvfAx43x{8Yv`BUhJ96MH)-6s zJAre*_b1pnp2Zjc>^CFRx(NrHHEATWg~)WGc9oDS_xKp17=>5j36^qAY%JrB#va_H zgNFlsxVih2jVQWZwCCqvj-A%jM^r{o9YbP3(8etdLL)YlZPupYS(Qh~|E$reLx-`M z&sX)VZ&}FH)grl(hwrPST*V$ar;(VCnKv8XN1m=!XNlsgTeGb{4GQW{ah~Xu(P<== zm%3(Y8cuI~`wh&^%;Tx&&R}%+C~jQ4g@^YZ;)`GYdE65e{_{JNr<0oGEK{OgR<*NKNj2z2CQ>qSt1DmE;;laj%i29BTo z0Et`y(gVgr$IKiOZUG-1IRaQH>-=u{KI+ypL0);9m$|J>p&?|rHLJ)W*c%}2B2Kz> zE5~~!C~BG3VsGyG_Wy;I-7jLjzq%lK^u4}TTYUvfkm>;%m)e?J@ZyuF;bwF2{>iJr zfBk&yXDQZ5H-XxqC-ItkCLp_LiEJlczIN~s`o8zas2jfucX$uhckZf4e-Uk`w| zO?@gX50l-hQ+4%^=FidZNT|-r>O)in1Wc^_0WPM3#2JjqL;|VL@5S)Z9XS2O(Td-r zl7Q^X5qD};MIQx=I4~wj?_PSqE4>bOg@Xf>C7BE+0r(^ff1}obI76uilbug!h zYHQh!A|(YWC=-!&=DX8X5QT#gVM@1JCf?>0e6y4kQDv98R}PxzzVcrEe1qSo(W@wU%A<_=rRZUzG?vnEx*Bbgn|$$EK1t`A-Y*_3YwJ$Og=7LZ_w0h_*ch0&i-q=fTs(ZJs(f>) z6waMGfg>M&gvO=SqK+XPT0Dpta8|KDT-H8R_Hmg15BsYJjeX0)W;$IyVN6MDRCxwCr2OiFw%STk z7pV;5G?UaxyoMA1<=*1Rzb$O8_b87=J#MN5>nWE{oLZ>qC>CQWAG&lB#t&pV8f{wyh2YU31Bat{ z!3ji(grl`^FZE0Is)t0;feDrm%hKDDjStU-aMl)@0Jk@8r(1D^Yd=IwoVzIpyA5^(9 z`kl|6!RdG2MbqL6Y~P3P^YbpH-X})~C5!YZwUgx-4#v#GzCK(zw7;q{3OaZ4#Fm~{ z$pY}fsS{Xjt}Jp@82OfkH=lVLPrdObYFDx)o*!(P;rufUTlpl(^E_B~aelhRH56xS zwzyY}+HP6G86=v_npMyy3Ao5ZY!;9)YE_OCS5J?_8>%6@kVEtJ_b~P1&tS8qv-B=e zIv7f4Duu~D(fJFY%MB_6iu}g%aA#y>Tb&kf?%f67wlH$zHZ0aBTuw=QH_U#ZdWEbz z*Db_mGyU1%en4I#iIu&l(evHkhMipl9Si09o7=Z$`YK3hUTL0Ej|LMzi_7Dvj!^y#FKS2q{}fO#g5?REsx+;vcPJ(rm#6vv z{B?LA+y;KH2Uiooxj*49JOAl-UqyCvvve)-L;Hi%1poK5zz@9w zz=Cbq7-*s>|BkkFBYt-5Wq73(ca$vK?I2+{N={_f_e)cJ>H8xbd8C<2(>02e; zqw>01zK>)+k7vL820Sm&DEC~xj{TRf;O_7suI}Ggao(a_mhXdZ)e?UJj#jASkZP;N zE$;wq!1rN$URCwAJii!*%z+ON2QFTQ?RmI2I8Zh}(N2PDHnMo;wKqx{r_eMl1ilE( z^UHYV)$gH@bnwQD&%uk(;c7D*c<#He7tbA`4%!@bkRkTWW06~>rIHgHgxe9qF7Qcz zlxacbZ{=ipF1lX*BdqLu63a&q1L!61j`rfBn!j9cp*%}|H``o9n)pGV#vVhy4|lTw zBy5!1jQVL%T+BqY(9*$!XuWh94dWA7?;ESCPIR`K?&-F-Ih{=5GX#9QaJIPUze)*J z!3fVN{t}B>aK@yj8qCgRaeZPOCk|}&NTP74flnze?sTJ1g(S@H2%dF8Ayt_|2RQW3 z=YvfG_tKdB=;#rwH^d8rZ}l|;sdxqxS3$+%f{cQomQl2zc~tQFTkHx25!D4HVGMH7 zzz?hthN5^A2PKW|Kzf3MXS_!0buOyayE^qedW1qcfjgsRjQynz!1aLk_{SMYmTw+2 z^1G^D$jCTrZFyXT64qQz2_TWMP&e-+pn4QDWor&Uza7*f% z4HvifjbXK^v6NS~CXKa_V`;7&+>c}~kDd1(pzG1JA%$HmZ(wp!Q`##!_K6Xt@;Y_t zM<1gm9cIV>{%wo&ldY-2_{eYoP^MGJ)JGoy z8Aa>$^|*ZS0QO$JhNk%y_{32F5K;USj7OTraL{f%61y0i4+eH(d~_Ju+W1GrJWg^Q zC(t`AV6~}n%SOFQqTXH!6xPWE&c~(K&%KXKb^}NE?yvfY!|8Xgle>p z=A%3Cerq1z+w^ey%g>>wV@Fl_0zl!x5*B{z8^E{XIc-PPJ&ptl`}Nr(U*j8q$~*X? z3{9c)9Ih+s^1{Q?QJ-B>I4p+zXYoww~K+4 zi|fd;+&=qFd2V?SUfkJgPfI?=C58l9==-ScBd&9eM=i6=J9yG$Y0gq6-^)zh(k`*C>p9yr^uVMX8EEarow^efjbOg6II0Buf3 ziH>MXdB0CagD8Xi?Lo>bNZ}>P-Q2;=;mxS?xvWB@pQk{wa zm3onc2R&x5iEFAY&Fya9PbS`Bvem-DFF9A8Qe?MnpgZ&M{^i?n{@1?-)RvE?BI@oM zPEh0h!oORrJ*my0LenZXFX!r8pZ<9^N-2pOpW~cA`&FtyJYL@=oAP zR46$W&GdBQ%Hgd!E(^M`XE$z*jiGmP5<6yQx0KhplP6$#K6YQdj-LCEAmjH)-fG$c zsB>zH(eUy3S)Bc1Om8=-7zw}UD<6HleNyxvUjHsmA3lt(_71%N-~1t*nk0_@B%MzOBdAagOkV01}gg8TW_O&eVvS}pfv;METL;j?d$s9y`^;x0PwegPqDa8NC+i59(OVF+uKrBu|+6{-#^^?&1FQBfNO(blJ3=_k!qbd|m>4 zymKBd+btZ$|Br(vXJ_!?)vNfS=bkT{wl=eYr@r?V{Jd4fD8vR+j?@Hvkp^3#lA9ws zR6d4bnS!`gq2g6h^x4pl!Z4_6sB%47@)J2b%2V9a&`Ra{^_OAK9ffsf1P8}Pk^H3} z!Mh)Ph_Ao#I)3>17h>gM+cv)P@+*4nUUA{L!PRssg`fVy7m-SuaW#%JnZ{D7#I*EU zn(%ho`k0D49!xzgv|hJ}ZF`WsZ7X=yCqV;u?_t-qo0^s(EN3<1HXW~&i@Olv7=lgj z0y!xli6`HA59d!D+tSHVi9!L-zWxRr*TuOLC$QL7c|fbS`2`$3{~47>0UxmQE^*kVq5IUR(L%qH=&S{C*0T+#h%)W{_!{Lu=J+iJg?~Tl&A1C;`xN!T_#O$`M=CWy~>NaeZtN^_W+GI z9-;T-sfwSC3))d(ZUR0{0D=yHan{0fSC>o#akEmtBTHujWo`IaY-@ciJ6EGjGg@Z- zxys1WK9bE-5Q8pAn*~Q{Ne0TJv%sHFT)RmQU%=)NX8`ab>k^8;t(sGg!Y7 zAMoHxuy3ffPC;rOsa)UP&)d`VThvuP!|SgzKw55d`-xo5^QUt1|Lu8Lrw3u}3Y_s; zo13wg$>8G68=;Qdt4)o_*47Z9I#37`C?Jmn#6Cukv@|_Z*MeN|6TLtIMOjbzOnJ5* zPL&9&%IWdKEAb^nILyrXg{sb}^WGetUyT1mDbhj^_3QpnKbBjXu-4Rwm8NLGlv1X? z4y#R#sM*M3*Y%qvw{069R+}4RM|xat4vyr^rILUJbWct}7zY*{GDaP!(e7k?4F_~_ zT1MFppm8dbB-fBFrY{wgCkh#v&3n~+H_2D3vI@Y^L#`%;xgFIx*M?E1t`3>H>YcSI zEw?n|=AK;`x;cTC*+p2Tf9e7mRd`jo4#I2Ye%1Sf{kS_kh;_s9WuG=ZE)JyXT>ATb z@-6<=oTL6H=yZ2P| zTwrIpP~&07eO3SjLHoYdw{(3>LUwd+MnU*IXZbcdKlG(1c~7;K3&{lh#}t8_YEB{= zzWBvAI)}BYs&SdDCcc4I)tC5b0kX{{2q#-p@HUnI>A;j(5}2-ww&u2<>abkhxbN%g z#0!7z6}(oLgw>FaC7x6Om@j5f>w~worM0Dc+KXSDF9qnBgO2Km&Cc|m3F~o6=dYM8 z!mz#&Z|j+yf^GY_av+8SXVQW7L?5gpQeJ)Ijo0x5XFi8k#n$m`8w>4i_}+8R!1g?x zdiyLAZUHjliLfWc7G_yP*(PQim(EYhgE`+<=Y~Gc%q{Y1$-sE21x1z6Jf`$CRHxBL zwu;xtJbhTjr5E|JiL;(ue({*o&*dWruw2Ckn4ZZ;7`=HLB38S=_C7dy3>$TI$kx`B z#W63OI11bKua`yC)}EZJGsPjWP9rynrZ8U{i5iO zs!7Yu(>jKxey4fLXpemPF!=4;*0y24uH(RU98C80Vy0_r&R3-}IXo&f#~Jy!v`aEc z@>+*+Zi*f1fh0Z)boR`X*rVz?SI&EMcU*Q9M_9L42;AK$nRpmN<&rR;zE=Xmui z5AgJlzk)(0i)*)U!@GP5C$|u6=Y>@Bx|##`qx z^}^qPS0nK$UcxY3gqP5ap>jDv$4zjJ2TZWxm-xeW)7_y#_z0qH)04m?pLWS&wk&V7 z`z+_+o9}fUo=* zqLzq#%L-2Zi@_4?lB0AmUiEb}uOzpqv$k-jNx(&>u?`oGK2d6!OnqJ1d3WyA3D_=g zm$vzN?74g$o9Prjc=8l0ezvBjc$(ohQqqaFp*D=eyqEAtqW_UdC(hzX!{*@Wp4IMNKL=W%R>qS8?aTeE>jLdk3CAdJMUI9^d@l8*qye z>rWj#jHT5T+_*add^8FF|NH=GtAq9HFUeZ{>$Av=Hsiq0ya)j3Y-`8i-Fxu$*T0J| zKJ#p7G~}k`WgPkNW7v5Yc_d4cR%pg@yR96-075t%N8ji*{kyzUo>PW#Q~I7t$!x(s zE$2B`Yiq zAv1O<(H*mX5~fFU)X{ujMI`MKA2+>Ue^y6O={1hpajR6fvOc?HyB_R<%g`DX{g$0_`=7ydT<|R zIxEY|@_jhDAd0oLN&=0+E4D?~qiI;4kB^@?TsFV@wRJr4!G}m}77$>>4s+I~bJc_& z^Rr-r@kQ+tyAb5qKXD&jQ&U)JX^wO#@1C5(@U3y!t_$Q*)CL1*ULSz%`avBZPNR8Y ziS)3<^LzlQYz|J&EtS=UgFKQXGImgIsaIR@i(0Fl=lF~uTJJoP#e69e#X~-*VOG_7 zMXee=9ernctTzr-laIZb#mv)RLAHAczU`2w!}$vhS`$?cD${BBPakqjiFCH-!7jwd zKI(eg@uhG42EP8Y{|tp+jPEn6mP-=le5*_ zS1tg(@i#!2)=jA7HjN0?c9*3yM__Ffk2;QxVn?Hkxy8kb%4KFS(I%G-xFz|``a0TY<{=bY5&c0rz*101 z&SE)3^w}?n9^0d)`>dF+kAtH6RX4ok9i8{7yf{qmNcDqXqYKk6izp+Ux9<=3Sp>=^1j-WR9=U*aiuaVET4Geh)YQh5pqyY)yMh#Q}t_)IgL<9nJCBH ziOGlf_{I&iHZ`Gh-NE&*zk`||IgBUv?hAcpW?=#24b6MdE5F0aY0{CR4ePM+se;R9QaLnz)}&`p`$vVHWm&h! zCQ)f)a}&3}`X=1kk8$+B`iX7Lo06)-bNkpU*+pSCv&cm!Ix_fp;gXZ~gxSWkwBCwG zubq7lORMEK*$N73W;y~;yjjlykw>$K;|#K`R6gJ-r7F+4!%A+$gPr$KyRi|O2LRl8a32@G`WpN%y|aV)sxUKzW3i$s8w+6I8;h6X%y>^SPT!5Kbmwn&80tf7jr%k7jf z#H(`Bc(|KK^R=_M{qz4l+?qN=?k2lJ&5!aGA6&kgQ?orHioBPrCeSGJ= zck$$*!)Po96}UEj2fpuP-^gg$y5~|UY^GBszTlLcv{ju~t-H8h8IB%TcUU~|H1_`c z{~7m}U&aztd!D~HuKi23V}zE&Cn=(^5_SBUHKlT-zC-_Qx*k3DO=*L5W!-68j6Mei zc*X5k(!E4=AmNr4&8s3=*xLl_mEFJ}Ujh8;X0ARi)q4_8Qf)7BKT(R$=wZGyI7!k? zI#_F}4C^%o^Vm$Mv0mQ*&#|%AWIoYzJITK=iP<|>@m763o;rH0;^*UP^Qw(uy2lYv znYS4y;Ji>+^I~o2=H6X+xU&zrZN#fT4eIOc!r~j(u=3{@fTy00^-Lu;YCv>G^Y--} z3#%a~%f_KQ5ANf}-3hcew_xAMDBk=~VgdfYJr5k|g>^`t)U!D;hxvd07l3WyJHG`y z^UN7EH8fy-V*~TwxB$F<2kZNKu=dOA@H`)LON;P}ydam)p})HaEsagU&RtmSAH;jt zF2i0~!Sg4d#JS5Cv3&C(&?+5hmsVHs(e-OsS_{XI+U6Iq=jwITtz{GkK^d~c0>ICa zQPE(O(y4k&IjqApXM8e4IDWG=o#xY^D4ZnxnJ7tH2~h+|Yz3C@h(g*-)TFHUrBkVG zT{EkMIMQuGe5jrfPVvT6rM)OoC238HZ|c|k&SdFi{006 zVDRo;Om}tR-eA07QccS%*mwCV>Q~oGp#W+!S?s!Y6SnJNswetnH2~;+IEmhelSt(9 zjAy!xZw6%NJ#;pqy@O_5^duYT-2>*G|wlBe$h~&;yNIs<_EqNBHsiOC@3=@ zNaPAg=5k19b2y$oS1OMhRI6rV6ZNa>2%=XzrRdcGZWmx&K7xqg_4##0FQ(4VC^=U9 zrLtPAy(F?FwnGT3NS;?Bu86vFEmoWmLD4BSI=O1W$u_21FqLVXw+M=7!%#kCwt~35 zW#aoK3$Bny*PH(iw|?P&M7E2`zW6WCly&OmtLp! z{=I0tejPie9wGkfoXkJkiVj~rSG5A3Cfs(fTnh=Oa+-+`3key)f~t)wm_Jrd6ovStqQZQHYh^?Qy?UMAQN;~FX9C!@ z$7T3Xm6?teKHqp9sKd526NTfdUusXMbPTCfb4~e$Ic-n&^OKjGpW2LiR z90L^Ri?-%wv=t*5htWcN8(J2Z&@nSd#3xrNDqAjA#X($yq#E<{)1$Dyjo0VW)KagS ziNhIC`bRt~K{(0F^$2>>VcUj_hy8sRA06Iu^ySTT8h1uVO3^RIM~AVQjyHByT5f5^ z_~H0d@uDWG4-r{gDqK?4lpI{j@=C{CCG$Z2t^h1I zVPW%=BreZP_oxmvYVUe@9xneCRRe(+$L^JOaK7(jf`Sq@?j}z zba%%N&8g?prb?xXZQD37whM({`VuyJ`_a5R{*lWnHPtuZ@Tn(&Q%{tx?HL-XIzLLa z=^E@C8Htrv)mr%Iqac>qs13_gP`nXnijEwY!b?0}>H4UTOnn_5 z^~D<>%eNlkqu>7bsCjrF_J0=e+dV_Wv4B>SBP8b^90J%1Ro_R^#5Elb&xRSrrgSt% zks>M|dacrWMWt8ucv;@yFNg8WxtWcAAF8|)_tg7DmV~K4<^@S|4*^Z1ZaX_X>sG?OwsU5d~)`f+# zEs;tl(bZmw{%5jP_34iI ztBdTMt*I#m=oq_k3$7JJajz!w-daNg#z#lsTQ+(gOhUM2+r^QlFUxX#45hl;5Eif; zi$M!gGU-fVdX$Qk>)*NlDSxXxooni{Y{B>0&K-dx{AZZf8|sm*tAU6>T8bKl;6w^q zXUYS(DOf%+eL9stm^MU3V2KmB>+hnmsV-iC&{dPJkG@u{OV{&CuL)|jol;5SFC zCCPcGTVQ6Y+?EROqhjfNABnXkxU~&{Z8`x*ms~w{M}LwieI+ z@JqmfC$N|-V0?KQ$M+w=Xus5@ceJ&kslEX%jg3Gz&@tSD^r;~L7KVCz;W#$VHNOFY zTujZ);lpcJv6{)?%;6_s88)DI%+6u-)@?K`EyIHYdRmpLx0xg|#g3?TC!gV@^JOdK zdi7LJcIYK4|2{599}mUVB1AfwUPb7sp2%eywXmi1-+tWvaZ>Zr5=L&{VNw}@GX8Xw zm!?s#17RFm)sxI^CAo~x+EwUGs$L++_kQ%2{e(pr8W78fS z*u^k#RO|Oj?xY|sW}$W^gZhxd_dhw27|Zn zqHT7bj3CvX3Ch~Iyn?3X)sizab=am}dL_Iz@1t#ILDL`Nq-=fO2jIZH%c<$RUp z6mJQ>%TdD7UAl_H+n%-&KQ%&aKeLr7`PC6cYF;zH3&LUThSI$B!r=7;A|C=_Cs zcJ$V5G%l|w{lRO^`FR*o4s7aIi}33BvT&n&2)V9q)XY6ZdhQ{z9c2PN8%iZhq~6oV zSXh6Dr4jQ<4F*yT#cdawE}=&d=2g}Oq)7yFqTMKl=2A;@`6$~(N+(mLUHp%WEM>TI z-~i+|onq8551s||P8Z#2>JZ9&#CvHT+oHfG9aw+!7_7}a&=l8sP-Txk>0i!{)MvO@ zkzcV_rWruA+g+v0^_HQ9-5uxSgX58962HW${K0RMtlmg_6L(xvAk<9qo~|#@(pk#A%GB=1Lkla*C=?217i~HGCa=j|xjH{K z@lbKiH|D6*#hW)U|K>H+e(5E&o;2^sj6<&LVPSb00N@ojd!>>|)YsMqAZC?R+u4lM z|Kw+5rw^+$*Ajxilw-#oDM$9~1%7RN=I5tRDyU!?W}}o!f_!cEnaR`_l!t7W?240% zYU+lkGuKqtLVcE=%8IqddfXiv41LE?ZyzjJ$mTZD01pE%9>M*qlX&-k`5FLV;Macv z=}x}Mp|h<`+xQ@yjLPe)@pn9j(c{!JcpXd{KcGt$U2mp&(H4oaq4c~eC*7Li00d1Z z^yIKN<9(%w001BWNkl^7RoGq<xn-Pm2U^P%&9rpKzj5#T;eTL|4b}ptH3N>l+!svM|uyQ&rhL&%^nvS8(mC-$TCX zIC7nJB^!80Yb!=}R_`?b#DDSQ$RFw~8%P4sWhcF}Ro>Xu-hr;?w+EXZ{Br!`cpn$} zWW>p9g5oW!={gUefsa!j*@YZxW*=gsdkDT0CFjK^$7t)vjE%~BmUho4^DX+MDUru; z-%eb-c>|vBW9j|dSh)273ERP~)>e%5$8&TEYthPDTIJWgCnaZ(M{_4WkDA#fq~~VJ zI&JH3-#-V7aBa^h_?D!h?az7VJZ*r54tY9t7-o?MboNs4+x!DjM66uC+-Qrr`TxM;m6l zDm+H|Geo(39-FHf)aPvs_4UPiCeFH%N!G{fEfrIj`mzTL4kWLmmZ*wlJnHHGR2{Y- z&COzRW~THz;W#+7dpB&$#`TE_tYyld5;-<7h~|a{Jer-wy}C_U&%_G^5|@PDEWWGq zC=8bgqkN%&>l5Sf|MUv>{jC?_6gPFYH@D!x*cck>>QIwTW6#iV=^6W{U&d-?9etgh zuq+#EnGCwx+u{B)a53-V@ZkfftF6U@>1p`q?&HwG{pkBUuV7_;4b9WjEH4w)rfXQ5 zjcgVLS7LvOgoCd3b`16QVQj!G?;2NE(K5ftxBx}M=ym}W*%9rhT5+a!Ew3Fv9{TiG z=&GS8cUV z7`iSyrOem2>Xjqj2jZQguR!_)tXwA4BSp zpk;0eE)qb&N8i1NC?p*Cj*ZE_UgN15f`;#m!zmQd^=JmQs~e?$ahdlH4`pdWjxC5S z>-2hnURp)IBr!avxV_qi47VnQS%3aNYIk6>1a7$ zX`ov$P1wJ_Lc~`-%&2B16j%SS3og<#%UByc2rpT~-p$vmD1S3qY#d2c%i=3}n93(= zzFuD!xnZQUy&c1SJF&63iP8Q6WL7h}R;v%C5+s<6U%8klg(moaWPh8 z5n3k)E(!<-c!QGB#bp^~*n!;bZ;C!_0a$Enf$!L?O{TlLA|0AOO*(bxFs6U^TfpoZ z0O0QABv#kgV>xZ>DuZdR^D#?}4>?2Q7=$7%efxh56i;w*U`^$d(U-HdFwK z%cK&2w|p$LRTuT^lcLqeMqD|t9|sE;(K5e;;E-o&W{Sg%s3emnni@|#Y}}g2v@jUI zf1|GXhHoY{us)MP!`fQe=vs?c?_)i`iTa^Vv^F&%m(OEid3j664+Fr`wFkI(>jtcz zrdW}-biM)T5kpMR@jNP_uJ(4+PW#B-pU3Kfbu`vhx5=%(wieHyl#8#OZEe^+G=v?k zy58VA4(2)GOhn zgP-PK;dkO{D3uU5c+G%?_@S7B#O&^y$-^b?dGJ9}ami(L=^L4u@tfKm`936QcWhsdzZ5J_2KT2$B)1xd6VqUmthCc~se zQzSuv06_qI0K2ot?A-Ts_w;?=M|Itq=|8ewzVE%vtjenH*`1-kh@Pp+dinBQ`5nLS zd*6FFfswxcf+rZb>0siTagMDsxZQ~bF${ub%G<81&23(G3EJ+rg0>$!T8RNu4@}(P0Mh&`+>1XIuerq&3Cyi57YtJIL+jgHh$oWhYAr1w8j$faab3IVBYt_omSj{e$^4+M@Iq8-^MY1dWT4|lw!7n=w}eGvG6w)2Da;KG2PdL z)dHtFJl;v8 zRfV0{9+uYDgfe{{omgI9M?A?-x~{CK$eWpbd2J0>zxO^W_H;D8avXCj%LoPnP*oK- z#~xrO7PI{ktM{g1&TT_E*9k>YaHO*fnx;WFbS$s0;pX4IhuP^_biI7a^LhD*V-oB; zBlmHV-<6^^&jT?3`Ywik<%>e1nEL7()Vts^1Kr)ica{|6*ojfx{>d4XRY#%bvR}`B z^Fv^K9qNfzv^F$iq_6lBTau|1+Fm<__MSR4*4Cn-#`??KA23uzgF%8|#dK+6&>O`^ zC_*jb@P(|0(#ehA$=KE3W#ZZpz{Dy zp~}5Igj1>0wC`SQZ}S~5(6q9Oa4Lo7r4`hzZQ4QBfC-oedLB+gg^55W zi&&+TAF(m*otQ!(orMm~4uXf99)|Xsc28BiEE{2-Et=t(Y?N7?L0K$; zzOjdrJWzzTnoyBJPzc$yYWm3_qbpjX?(<90X4V#lK{0)iCy{l3vz&56)I2FlsE{_Y zQcfG$y`6>~fKN9bxn*~EYQ*xpWlF!vqeS0X+Ll6giPtrE${|dd6e?!Nu<_J0&_jL` z+)^pQ-w0FqUhv5-qh*a~qCn7gb6q{up&=}-tsxu=;q>q@ZfhF4+dEKER@~+w`mV@* z_R3KMfBcPpv0hUT6dvYakIUhKI@agBC$M)VH48uS=lR>C}GjTs!fnX{FMdvJ5 zh1;t~!9+#q4Zr4gkI0IhP6;{7l{0%7&93d09olV9ykOgWfLOe&461IGNJT<|XaYoK zC6Y+OP*r5YR+cTlyDAsgR`J2@oA}%dpYT<_7!t=(4&ZhM0Vt}8STqU^25z1?`NSO& zru^JFpx**S%EDnJHg>T$y@JY~!pFA>_1NpCP{1W~To(c-4gw_myZ2y*b?Iil6JTZs z?Hr_DCzo@oe@<5mRn1M|9#dHRP)+PrR^saUGbLxR`=}^UUWOZIPT}S6zL6VS!w%Qx zd=B>i`JEajs8fTDiyLftFh_xG#smAA1Of_B5eT_HkG4^PiT3#gn3{sy$Mfp|cmCuJ z+#MT7-2WaiDC2!Au5`L=xruaY19!Z4HugL23{?p)P7f z18#4v8~Nu5h3d*@BvHQZCIOu-XIDj@D9S`9EWoddr>^9qL@I^*x9;KA&AVtH?Zc^K zBUtRKgYr*ahEnfO?{kB4#OG7HK{klR-WPgODO}tsOXOO)458oIz2fto_c&YSCcWI- zEdzai$y+~iUU#e4f;kPB60(y;l&^GN#m}^c;&i2zjSXzwm`3%(Jv5&voc(dHvJyKr z)rfA#g#J(+*K7S#`&6{q4Cy=7wJ2yw?LWC@k+;jgGfpXIai)+lho$|#!JJMHAI1F7 z*I_fALLe4HRe?=noAq@l+fO2tNRu(J;Ad_PavjadW!;Ic2@%FLr0)!Rcg_K~jdh4H zFh82x4ZC3^zti$HdYye|Pj}0t&U(#4y8TKRn^IZm?@Z!y+BzD!P|$Xm;H z<&0B5rSR?zin%F{E1scN@_Vr@*0GU=dH?ezn4w&6W zw5t(Hdo?co;ol(m<Zql9>G8mN51$8)PCk9 zl7IRJ%#}UgZ5Q8qFTUqxP5P%|aPdsE7Qx+VMAj#vB~L+*__ya7DS|E}{_bu2@{-=| zJ-BQxJQm)zu$w2axVkOct**lD6UPutXAsC_p}@r0(V>s^q*gET(&1z*O|)^Toh+7hltVCJZ z(jUzGtEibu;^|-ed(f}xm|I>308~dSQ5~(cHsC41{fAq?)*h6WRw$~1XHT8Bef)1< zy@HukEzGBm0_7oW zY;U8rp|tGwr;m;Rzcu2!d^8qA#a_$~vZR5BG)0=IqtHyLvJNAzPgzRSdMwJP*W^dj zSn@x%k zvp5ZFPH624G!lQMK*?pF1r&tiNsQjS14XeCRyh+gxO|7rp5@b|S+Qvu6DB&R zW~H{UEYdtOErTE^(ko}!mQi^(JBO`aE3lZ2iUGE{zzR|3;m|r*s!oRT@_=G)Gbp4_ z)_uH9&LCcs^oq@oj5YJ@?i88Tq`K7HEb_O}wCfacO4>%2s*?vFvr!N;MbmZ8p34#d zu=kp6<}mG%W4}6+1-S7j({2kxn0Y`neTz)6)8f3bA*bETGJuOQh+-+8fP>APvtCtr z2K6e?_gq|qeC(X-(GAlOf0xI{>$}%)PCdolYG7W6X`d5;R*Ad*R&ze2b;) zV-Ij=V#0T3kZd4;Y#;z7>o;i83C2^0Cl`y9C5u7T3IGjR$5M8CmaLG-uPSrO29R~R zQ*_v}`$FjqQjrKurEq`W`tSp6?CjuE7oI_PYg^v3SDreDr!HPX<<_3v2G(jP!&gDw z8~|lCZm^X6YC7u_1Lmz7wsV z9584*^i!u%K2?L2^$lFUa|bV<_fBQX4J|Jngqq~}Kr=2S1DPx|UH7%K`+SL;+e#tD zG;_yf0qIc4mkv^hs&{s9_QNYV!BpKJP)F&9lL%DcTOI|a$C!xWX=zz)5rva zhtfC2G!fm4;rX}UfesCqo_z{CHPs~rZfm-Z_Jsu;y?qZlG-MDUM}2V#@6K_>H6|Nj z@|e5naqisO8<;yx^25DMpXClZs}r*`xb>%Rp=lwFkso;#Z(RBS>c9M4QFWNo|6=PD z>AUl8#Ya#5bLY~D0~%h}IK(IaE<+Ugcc?pc_R=Z;{qmSmXi(gkEB4XZA9^?Yjlx!P ztGs`c>F(r1%)WgKCk6&F`YVOk-g0XTg6Rx~x9>Z~&;4n<49&43L&Y?25XS{5SSdn$ zGRc~o_zPV{RG;Hz#5%eDT(h-}R3z*x>+zMlx3RjpiRVwBDHyapIna-aSRBm@E5xoc zY>5eV$33{3JuO*Q<_MlJ0UI_KuPX?qGl;~K z*vSQn$$&ZgpWE4n|IJl9NtplZMJWGAe%zuIV&g|8q7|4e9zM!~-Bp-~RYfsAIDqxW zCotfmyB5lc9{cON*RSEVXP!IsKzNJt>A>FfsAbhhN%?tr{@)JU`d7%C$ecHBF1~Ci zh~4U{Lw@?BBk@!~(dHMq4?W6S)SE1RO)*SorfsJNLw}Q90bXDqeb6Su+F3Yf^-HSjA3kO5UEIM0YNg= zZf-%%8jz*FD5*^8yX8)9T3$gW9DHnpwySn`ab#=)sc;yRNBRzwd9ZeK3nRDhA{fsI zndjJ;ID-b5A4}vEus>5y>5gu>U315D#NYFgsi??mVN}Ftv1#gg%6sY0B1dDbvr4;jj?`&r#8E1ELw|(Vnw4~DplAlLQ9aaWZZ+p1^TTn>>={_qQUHK@CUX-R7~lB-cSr9+X{cbM+UR z7w*F<#NYkU$K%I#*NME|Z>J3+`!@NQoAy;cKc;PkTCpZpz%R>P%*q;2(K9&()if~K z-*@1Icx8zM`X(mPHopK93Px|;!Syqz3Z6{tRagJ`L$od|+Q^qPeWi148m^Mg$z`d{ z?RPCvE1l}-6vvRUVOqbu)>)=xYsU0k1d|Gu9oY)Fr9rC5<=)Qe$|i99+ASz{dERTW z-4rR;?Dw7V0N!FH#|>2byLUgtZ0B;owjo48(dZt^i>;b?zj?qmd)o~=aN8=yMw$8s z-7F`WAJM>T13Z-4Y8&sF)6XmV1LSRQB66+ddP6O@d~%1cV}sa$GzeZ??|h8;`ay0L znYqyd04+CSG-EaApl*5vjc}8ZE4sEA50c+3xnFYX96FBjnDLUleT?6UmWQ0GR&iXT znyo0WoO*-vGzmW6B3dWD@1o}Iv{T$<9vr2-`F|k3gR;d*EFJqH7@n~Mru2WlGS2Jn zwjCcukz=~s<}xjBtYc+k9gSsGxc1Iv{N&I76qH|k5f>N6P}SRvj^@%%nRB-9F z#{(ChCQLl{_C>t={Il4psV>;tFMRS-_^UTx_c=EFS%)!?mWbxNv#7wJCWmYmQq_ab z1Dy{g=a>#4Yp==4-ab4S9y)NlDJ{49V}5szjTT+^(Y`($?K_-fV;RY29LQL*aRPWS zyp|io?V1|A|LlcBZOcbV-+1dyZ13&j*b#oDq4Gj6l)l1F>FM4cWCB5q+_+2B87J{y z+<;?6DDmjYuef>Ctth zhi?G@es1uyC<|0TC+oz$-;Z`3QAu)jeGFM6gO^*5VJWeL?=IfJSB^XffFDIvEIoDX zIG+07azV?vAlo1R;Hw92_xaIdMF&GW%_=uZDoQ;!fXxIja{CT6Ba7+2-lE(7D5+w9 zA1}W30|3AquY3~8vV)(-z>Q^U@VOa+0Vu-eHWNk;Bs+fN7BoZ8d!&#b(sUg!z3~<< zzVO_k9A#IvyNhSvzG#PjU3m9>TzcjyY}6O;xappr!O*=2_Ks&}(u?7APQcd!WJGX4 z)VM@)Ui+wJ+d;_-;IK%CYU}c)(D8vm1b^iVc>CHFWbWL?7hZk^|LNP`D!Lxa?vjBk zx$V{ro6ukiGnyZYX2bz9@40h=qh96Q>v7WooY$P-IRDJSBe_l9SKI-tQpgY70$B6K zvMErzjE^sc4=MMjZyl@I+s5)M2bI?bfq_9^Wrh1(BvL+?28G_}!LA}4C&T;Pj$_Ys z%i_upNpymZ)^}AHLsc3#r~PQ@c*kzuMzTEOE2CLuMFqBYcMFztwml!DnEyU!Xdr}s zQi}qP(Gek9C1=OU8*x=TaN7z-HUbKgk#f-af$%h7p|c&6{r+vz`i%{A&CKH3nbW@S z@l630N=FT9s;Z$K;B*SWIX5CE;mlzpUrUuoaQD~To!RvH`7q;jQMlYT{hi|?8 z1E{KsvTzt>kqFY63}W#(q6M-^dbiH&U2@Zxz4*7YoF6-xmD%qchF)F;HJid#ytyZ<)uHPh(;o#{ckLnBfrc<(~yg)P0#v zz&7cMzlo#E-c{=!9c*Ls<3OfqBAH9RfxQ$^76haXU83DYz$Tu1!dtdKKsHaP=3H**78UMKlaL}4phfM zDUi)V)!7L^qTXTTLP6yKOws3I;a(#0<{W!YPR_%xyZfg7VxEWb+s8w0c(b#WvK`IJ z(yeY{WD3CNk8honqgUv=z-5JruBjPlx{e1!LoijvS5gU?f|(44@7_oA(n^k(DyZ1q z$GHzKT>=N_7tSA~qwG#LQ50q9mVR!h-2}9%uzTz}^bdX73q8V;NFS-&=rYbT;fKFl&qlA&c#!HXDsvV)cqA zaEPmiqP=X~WgbDZPwON&TueF2+o0O5wtQc7K4|bZ*IIaXXS$-jPGS>#LW8!|+&Ix- zWGDXYRu3O#5vApr7uWt}Z?Q-s5+(<2)7}}AAD_s)yF z@E~uF;r&Y>zK7_-eHhJEx$qHpJCiVAx&XK42_!&Z3YOCCz zahOzSECV#Ng*^Bw*l`VfYUJ0DIu2x}&HzOfy01>2A00(d({OuY9J*oT&2TA`JHzI` zan{X9&OXHhSy>=EV@;YJ*iMCxbMFtpCzA;U7AQ-Z6cc~$3IQKakwwF<_xz;~asBkE zf?1!w_Qva2|Mfoy{`oHe1u|`WjoU#DXjz4$BS8Uux6mybOs|0*G{g^;P@&`Q@lmX{ zG#yHo%_oTh$ihSrG-O0vWypP^$5-?9t>ymKnj3NR)QOL)8;3%l|HMo9&U+VyYyF*F z=xJ~FbwA}CvXbMaBzP+reuSTF#Q16BqY@JSM6SP@{MS?5$oZ+)ls?NdSsZQbY~yd< zc^j&t;3q!y8p5FvzW4rnIMUUHo;H8$N~Wc?HN5`k--h|`-iG?s&*LXveGQRN7_Wcu zKKeR3JdYX7H?B->(foc_e-b^*Br|1T0A6w1}rzVk3IL9<`a0j@hC#7^=oTc zHNM#Uw4+__%6tKmGa?^ChU8*MmRKg?woG<fC`cmNl%eVsH>&`?IgZ`1QYn`fq;3-@Smas=ZoMtP$VkD0NF?9CN2bu@%M)23!&hj3@z*Sn97i|C>_{IO2B4Q!=VRP zZ`9Y9v;oN%)s-Xo)gQr+e)iM$vCqYlh*j~=OvZ5c0wBWC+}&aXHC#D=7JHSIht{=^ zn|}DkmypS3U>F9}0`G^&o9T7~4usP0$gNs=tsjnsSv-ktd@?AXw!2{% z$YirnazQEdVp|++PKk^yteNSgHFijJ|K)|s^ zO+|s8I~|S6)E}%(;=$fJ00qOIc7j&~Er9P1m97-dUo7{B|(^4BOdk zK!K_ozE7U|s3@4p;QYIn5KLvPe*4fh@{wYi2xc5{hw+fQ6QUzLNd}Cs#@~c2Q!w=eCG01M0aDkzz+q@3(E-TS=>0~znzL{ zqGEp^FMR)P8^z|DrMRV#YlgB@n0;o6aNxQ&-CeVAlshPe5a9M;Jf z?0xdzQu#ggOWCZB(f%V)vIgG2ejQm|$LC)BM1j^J&*-}OjF|6{a#VkPljVP*yZ1YX zP%%G_@WvA2t^Tkiv3}7HNOgO92ff$L?iKqW-|zO_KNV*KAN+YAI~{9*`p;ek{^j?J zy3IoD3iEW)dKLd@T7}1D1h@D0@E5Ot7XV=V>R&on6u2q3JG_$^zke-u+?usMf2P;TIZIqS5sNi$>t}oTu0r;mYuwZVg6b| z$BWoVk1zHJjTc@Rvu2&|qWH$`(;Fs#A-e7tv27;=TNucN_&J zQJ1CjW97&eH6-?aDbT^UHFCe96}<&OknJqZqza0saxWuI#-f0Zh+7}|RxO_Pll8-D zFFoncot(ki3cRzSvlfe*GwZ9Gv!+=)_;;%w7LZH>%2lC_9FKP+Znvw@5y(AXh3Gec zG;Z>{$kz>^DS*y$d=(zIWc`;}} z6F%#>bMhEgTAEARvG_R9-0~8p7Z>runX`GzEw;Bo(G3jTABX51b*jMpv*>^pbCFo< ze7UU!V@C&{*zsc&35TI7;=2~mGz5G*8brm(a)Ow-w^D?Vd3pB906c@GWW&Y#`F~d^ zpTqf}BpTBB-G8zrTV56yKb@V)(hN>Hw7&uaNTNKkoAeFJ^BAvy_ zYd3J`*l59xacBYbPU~jfc~+EP+(xKxd~%K-WhX;?ms}o>KX#6 ztN`%RdO3i{c9E;ny7O`y$;Pu&t6QJHD z+PFW`G!?->5XnRm*iORlvAZJ45W~SYNfx4Fjoo6%%OGY~#OuygBDYHcI|NS#M-Qi+ z`AM|w_-RXSPq#*u0@)yMAwT7Y>mS}(D+<%Ir_Ue|&~WSbzJdGGe}cB({xN*!`4@cL znV&@ch-$mywhsy!)0{zklXKR_2SkY|5(W1FIy&MVyiPelTZCEZ)zeq6;pWK`SZvR~ zS^3)+-^TJk`wMh^>2tu~K;E*Yk^-7()FS!22>BZx<4o(Mzsq=rcuLqpdpmBQDDLEt zCzV*B1$UxZE;ZOdJJloragB<0vZ9!H`^6U?yR4;$LEn1&ZJaqeg3gxw0Rk4tFY2=1 zZ*(DYI`IyJcsm}Y^;tRKbI#G!!aTlz`9suJRohwZ z{_^$j;gzQ^prHu+;+<<((O6dpUDt8x_rDI~KU~CScP;)rsNiRQ=(G5X?|m2XWCE`} z`<&yr&+Xb8y!ZSwc=oM#?Q1Fwe71E6ueFZkkV6gA`Y0*GG<*~kPNneD>uJ8jEIf{jj(l+zkb-wWyvIafwTHF$6k?icX z9NHA~s$1K@`AZ+-y=RLL3ITxgAAE?)on1TW&O&zw?v5501O@=1R2nb8@g@vYfoUkn zAV?g8IvQ5iapv+>T)N=T&lBB?;puliKpH{N*bJE!BB zk=wO{Q(^p#KHIxoAs2Ig_p_7Uy?zy0Jqz=@V=%w=0r1;D=IcIL)Avgh!(=D*h~s@Q z9bmt67~%OfsQbld5_ThZn^>G9H|d+t-YwKSzoS`L>brZFimT%>AVmSXYM}h?4?8kS zdy#A%cvLKu74<9Gx9OkWxpoEf%PUshmu6wUHv{z_6}Io|YijW7GtWA%U%qo2+&Zvjhtz*pab^2-;XobQDB<^;_D_a;^c8u9htioq~kFb~5- z|9|m3p8mJL2(7lTA37h2@4pv6wWwI$#K`jJ6`p~o-~RyD&YUiIqLTT$ZvoGAL-|C1 z39a#_(IW#m(%oHz-_o7VA3Kgy!@~gJtFES%RgB)eLo8r7S*l7L+szh~a2wMflKFQf zU>mStVAG^Lfg^#2<4-)JPL_%w<1ddb00*~m;`aVHkBmZ#_dg!wrT-K!?O81%YQQ`Q zGWyA`nZobfcgMz_g=}*C*NRe6bDve@Fl5uZBf1mAi?4rQcynl9<(6803Jt+j78x@D zh6>W&D<-q&b&TG)4O8W7P_D~_f>0`rtQjD_Bn}trB)8&y>#n3kDd9&+{wOUZ^BS&K&_`r%1@zwrM~$YX$q9 zPxobk%3{=+j1bfBtYu=BWByEPlUu)7GppzDQUg4jw2?cN)+D3loGH2v<>y;Z;8~qz zYfOG`nH@&+kh4A*q&_3pLRt^=FuC&xw>BzL-C_z=y4I}~1F*ntc2&$uZje@pHjP)C z01$owVU5sM%B!7|EDIFjZrQ)W+C>w6=J%@6mRR2nfe(m0Pk!GE>j{9ouH9NA^AI-1 zUghPn@uEO{7v+l+So+k@0V>y%-0pOLS4Do~#uMaq;QSLcf~B@rjExpPLASfL4Xuq$ zh^JHd#`oW}l3e`G_h5c?5NJO5roV%c+qx}{l(YeDJ$djZNmK|=@q@G!_q>A>8_z%x zS$GXEWl#JdW4hRo`IYzRSfjBpJK2o;N-;U}tw!U?LR`W3TF98J^T%cnTQI zzvGS(&nR9T=Bch$XJzTqg4=;Ia>UcOei+D1L<35g$Z(UqM z@8p#I=8M6XPSDP&icyCErP2h}ZMQZw+DE?y13@%ItMJ)B_*H}}Ex_}sW5-dRCoqJX zIWmuAYcQZ_Xoyrn4D6(IxXvVQRQn&>{OT(UuTh{tL*wcij*L%~6oC6t(D1$cXqjI| zFr6iukJD&%0{gNCW%XCLgZeDTe#h)Q^gsafUGCY}{nDwc*U_-Lj`_~g>SZ=| zm8Z_k!3$bSNBisoU;-0^{?|=37Q^VxI{*}95r7I4q5TvF?v0~oavIC+Etv1fKYsla z4^g|Z2|z(OnL;?8vcWKG=Q-0}vIr*92q#idU?7-YMAi0=V zk-@(UVP+14+W99x!wrIRnx3pYzgI5vsEIM|ue4pPv>FSASIGr905|qBz>0zr5F4^D|zB*QxjK?47Yri*nEE zMBgn9y#FjvTZSOr^>_cIDhd=u1zze$XHyGaICs9_J*++Scw)9u$gBUdbmni0_{UD| zp_0uV;HIt+4y`+hW~PWB%ZQI#i<9dH=GlF%c*_=a!n@h zx8?C(vyWN=7o!WfI}|LAA)as`W_Mw$-!B;-%p&{0`~doY|2g}bZW#F6ci+KF=buJ< zQV;1r1*F4QWnd}T8^ms(055yG%)*yXT)-!-N%wl*a0h| z%|<1aS2jmW6VP+^7jrG@(4d%RX?r4F==hCWSZ{2=Qd?9y^CiqzE^ZMzh^GK zhsvEjmeL~v<}CG`3^ol^ZSLU3*S`-06kL4% zIU%F>z}Pt2=N9a~E2as>Fpx#S9t%VGUv#|F_2<6r(A~yx$~1otNPZu4EBl~~0cAan zy`gh30>ML-C#KDjD6cbZEuL)|F`yuW09X$9VtC?H$4?;sA1~wn?fbydCYZnXHc%kb zc0OWHW;}qWePUeV5eN7w3c`s6q>}#Rm`oh!a|X8vk8!y(UwK+*F|4q7j7BV<@BWV# z|2ZH9RG=XOzb7%8aN`5qbL>7p)Q&675B~PmE13M zT-%586UU*P=6;AW$yWKnmCG3H?!jPBFXEMTxHr9urk*A|`}74sH(~alvF%=^tqQ0L z11B%Q{9+6!3qt9x0iYo4VkZPEBdBcif65XaPdWFdj5m6DbrhK792luFz9vbg2j z4aE^xx23nKP@qA9346n|ZsMu;FX7sm(@2y*d4A?%Y4p||)U9vYdJf0`Mc)RbKgJ>C zCqRZ*U1yq90yblBj*Ehm!h&y#=@3$nD)EL^;yPQRd7T#kkUcDL99*|7;3FI z4PwBytS@t2nXXMSP}^&LQoUJ5;=Fh`?<>`H6#F;o_ZF>f*`L7lTPto&wP()+i<7bD zft6Lrb?%qty=7}bevTrw$*RvCrKNpiwQ#+bVKeeO>GbJ|8TnODtO9KQ)nAsgeXuok=>Is?dISxh2o7*k19ue2nBV6F-Z1w7aD6mN$xFK+R@ggd$`#WUb$gXc_nV zXdCMuj#^PYab$TadD(jGHXhwAUKK$q<#gez=^>go|rF^XjXvh-w#+3`s zRuyU4nUXqBS)h1ehWMLLMeWKw%s;*cT=1XSL3TzLQW-_HgoX>zLqSAmXaHH_;nnwfAwP`ITkd{r3A%@2>$b_yaj*Q_o8r z%4##ncQ(Gutu0vW$e)F-R9akJ#pdpgeN?M%7^89pw)A#kEz8O;4jL z8pWBTBQSDhS?1xGOr@}t+68{os>A%_tJofi0{zy`_u8sz z#Nu(>8XwCWxZSp}h@Q!5RP5~|g8&H)5wqqxK_xe3LSD`C?{4HYUPKk(2?9kAKz{iS zC8z1+ebk64&7U8tY^=r0U-<$Q0KrHI&E*Yv`U{^#B9%lLhR#c#}LgZB)ukoYm z^JOS=s!jBpB3scEP%Fx%Btbo&C?EJknNLDR}A zpaZ=Rr=V+E!7L&&l_e6WU)#uqfwAL=*<1n9ojogSv|(bkxv-D=e=w0j+uQ=m;&Eg{LEIZT>e-gMjZL)8Eh3msqiS=P^wD}w z`R+b67zn3Qs9oQ5)stBZYB#n~mPmk|10rV+=Y3+(h&6)2WCnG~O~`K!>!Se`*<6M) zR*w#PY#r5Hsg@*b-P8bgZcd^af*a*CjAb6;#m)ViT{2Kt%zgA;IUtnvS0|w`?3i&A z3WBLLsAX=iez{M$G*uRt4B)t=5AJ;dWx&i%Oi~(DCUJhyyyWLIYi~BvY z?cnwN{JKH0a-BV~*gE+Z5n7A&rpcCy#pBIfu$-(#if>sdx{uw?tMgc1pTM=|T0DE| zbiwle?K^-&YCIH%aWfvI&Fy9Ook>A<&s1M8mRr4d{yWFoM8o<91|E#%0A1^(tE*?v zI09(X;n1Nt1C_sj7RuAb%UI9)O1_h8M!YUJOT_ud=f={3$A$;7(Akbu_{j`9Ruu&m z<>lBs5ceG+I+0YmYQ7xG9Ph{r<4avF&~Q!&EI+NA`;0Io<4p8Ee#F0KQ)C1 z(^CL|+NvtNc=nuK_Ki#LV{bo>b0ec@Z?=v*4+a7#Qv$$NT&TA^Qn+v7L=uW=3c+xq z`^5=AyGgZ20l5DE#Wv1Qvcte_Op2Fv`Ka@y6Zpbl8v@-tVCS`GpMzoOs4l`TK09*E z#)l%|Fe;@@85L#zGC0aQE?t+Js-a2^+j_Y3oCbHY9K5C5#Quour=o*X#*VDb5^W2M zFf|q9kLWargVNCb2WVbeA(Dt`3fw+c$mp3uU%87|w)>bXy>WRB7k1yrezXF&P986* zjVEs0MC0-r>NYmfJ2i#nmKIF*_Z3x#Y8Z$l61Gjo>^e2Aqx<0uS{IhE*-)4F^dw5P zTU!{tc?Y3nMz9yz*wNr0YSZz+0v50>y~zepxwD50@4k=APeaE5tpETZ07*naRGq`I zTemUQ+l!r=YS(rIvRRzJ^dX`=I>|YnIY)_8&X(;ZL>LqRmx=S~l7a!IsN55Pyh zi^bJdT)%%0r-r@pRlt&O17qVhe->A{IIe||9+@wDBSwYa6EB~TpL^?1_7*JTm+Gra zPfm9j)VQ*WuIU*Ye+OX8QE@A?Ht)o!CkQ>hK?wx0!IgU?J3Xppt-0MbOHjFI$OQ%O6 zgNu2#KTK1!Gq@%pN;_7cM)&86M7HuY`%0|infLPncK}=hZoDap_2J@WpQ3;>%4iq=*Qyvt~f@b zF2w`u*_qBcdnTu6s=4p%3iB~4#5=3n{o$i8K3`sc?g%Xn1h?)8Kz@@c(Rb8soJId1 z?0I4trRneDCVjptnHFP^(P3lG{JY#T7h5H_(~XZ&joBcz(f7{jpQQD&d88Y?t$$Tg zj`9J~+Tr!mHo9dlciM=|PYAGJXSOzYLJ)<#%{0ZWs9osfL}-N!5+Ie+&jCuDL; zR;SGIu2*gaAA2V^V}FrU3YD?KiCn9rmFR8nfTn3^Zft=1>0w}Mz2JQSuvb-yw2w`F z{>O~InTJP4AcSP35?Rgv2E>Dt*z3~PP4QIB*aetTNf(o>Bv`-mqY|h}571Xy+}Xvb zsE$`ffOHn-?ImBuWwGyFPGmilrN~*eS@tmY*$Ai@9~i)5XS2T; z#Nw7y*u1%f^&i|ttUiSJ7ZU&gBa_90|M_b$(ixav*~7`_&!Mim8Vjo{xbe-4nE$Iw zDDP}Q_Ls6SOcP@>)6fk|(d=q%LwO{E+Ujbc)xcKQ2Igj_5pJwOO;r`H-n)y;e|`t* zFJIv8OQo>1wgyF2JcG7bz;<+J4@T}78uwsrI;yfEC2~9YO(_guicTzV)mWyF&rp68 z{0sBlGrCvipgqVv7_jJB{3ymfy}d=#x*k# zxar|;-1GN{8J+B;01BHNCe>_jqh)CsiL$bivSI;1@8l%P;&CZRR&=Vm^AkXP*G2P; z26QXXP`(#O*VGKk_v1)LBAD*&@zuU?Duw>>hiIK&f&t6XS-ZZ4K6MgP{k_<%FRTZ& zE-j&IdlywZyF@Dz9i^;C)muC0emISq&22#HDaaKQK*QPwDt7n5x5jCtPG{yUdd3N0 z!BB=>8=$zXl29Uz*7+sq!2ooHXZDhJbyx1jP`9=T6AH4V9SovVb1S=iH;#(kn4@28 zqaXuWt>d4?dDm^(0viqUzh(lNGF$(3W{Sz~cy11d7Pr^-MM=l6_< z(@no3_vddR+j_yDZ=!8!37JR;v)%cFh|M=AVE)A|)SMkeUuS2j-S#Bj8`&%FQ<#LJ62LOE3yL98;0a59CVdk=8^Bs_d-JXzasx#HwwBpeEG8G6;5qL(WV86e zl@Brh+h0R=D~=DoypHl?9oYKzO>BSr764$orva&7P1|+O|4-jQW@Q(ber_4jGd%zR z^UgBLudU*lfBO}?+z+l?#;M`qyxGeEE-R@HMjiR0yycvXUgLGSX=<#b?5v?}$p8It z>G6@BvQ6wJ*=3u;j}7f*7yG41Llq(oVqjiF2{@9qaXr*T zG5Cu+aUGR?XWX0Hd8~dK{$~omaa{trcP|SKfn*kKbBi#c6m^PFA*x^BK=s&4fH>lKx8kG+vKYV!P@SdWtjb9l5y1t2WC!u1pyXc6T4udpE8l7LQvSZyGCLes>dC z-UELArGjIU3Wu>z0&7K#-Oc~#9CznEg@~4ON>eskdbr$roAu)KzkHT=KG|%N8KLdW z|D;kWzl~dn^4rMnba(P08f)v&SX+zb^>ysVVi@e{Dfq0Ny*=EUniQY$?fbw$Bb0t? z!&qH)H3qwTkV>a<_1;}f%+6w@&qX$FC1BoIEci?S2&OX_7$1k0Lz)4YmGQ@FPEg z%z%k3G}Nzc;KYnK@L%_EElX$>CxG zw>4eIz}Pri=a-;nbz~86$zIIIk8T_l$CPd^1Dx*%odX%~W+bj@>lyr6BHxnR0pa?i zwX;Q{^09OTo9jjXTko_4MgJ=0C{Cn^`Jt?^SjGO|N-@O3fvruIOf%Nv=%S;#greeX>&Um^w~ z&kt)89|vX|@}Orn222B{_%rV}?Wc1t_*Kf&n2bQ4e!A5q>jj*5@>ZKt51FOpMecJ0 zh~wqVBJJc6s=ZDaw^4J~X}CBIf%f7?6xEmc4zmjQJK&}l$ulC`xp1wMBDC&f1gV7k zyvS>k@g~-1S@wzOyi=BW@e5X8KE1mXd6iLv*bTa4m!%?rlxMrkGI2ypm9x?Ea@&8P zY8syU`On}=S_j$-Z<=-^8Fwl6-bbZ7t1u8UoExY=D*7n(Aior#j$?qolH$<|Ce+++ z5m7AgQrSQNvt8Ye$!DG3sr9F~W0nL(#|D1h0XuA(z? zc+q||imB+qoE3g)sJ9n)!gpYr2Qx|iyv%OmjomAo#ZWO@qWPzWamhmg%? zaXS=jpn5lB+DXD3=>c+5YSKyuM5RA(K$1R z-iOl&q%zR$Y|1pVf@n|!qR}mWS90UU4O|N((CpDH-%Fr-ZyKpc1Td|;X1lvQ*1_j3(q9N=Y=^FxTc}OlxBmP z=CoflYXJuqs4+^xFhCC4kiiT^XrptT@O4Fl*`1%MLz|DK4E_|>2q|w7Tj>NC3!Axq zO*{YPOgQ;J8(VS12n%swb0G5|4pfGcDRj-wdIoK;ZmeT|Wf@f!QN$AoOzJB*{%b#q zdy@|fwm6W@qHAUrieU=R7J(KDkWjfNj}aVYKTdLQr(C9RU|HcZhp#*3lY#8F05VW= zr&7uGE$0CyX!ZquViO1F;}zwY?&|@QdTtc+V;{CvL20W-w7eWGEOXW&lDyrBZfs^_ zKtp4)p#UBZ^+N%$*w%(@Fi`TdlaUCLEfEAVSs0p%<<=IMK9997mQD-~kI#$Dxt}}=Xd2q;8!-2;z6qRr0VpC%m*UcY_wk?_ z1LwVN_j^$ymBf|1;`*6iS;p>n?jY9Eh^1Fg0I)U^PmfQ*{F7?{0QFas2shVYsJjPS zySteB_GMsWAL*Zd7V%^fA6~tV$$#;eIQQDKxIZ_I)$BgZKYa&S+67Lw0suno4Z=p! z_MiL|5K99mTA?&s5Z`9wVX%qWqF| z3(-dQvQgX|6Jj}d{+^G-=RHZpYy&E5oFhQ5iL06FQSL4?(FS{RFp2X0I0nYXUG!1f zU)e>)$%)^%tyh1<>hZhEn7t?3^(OdyTQ&)sF}6w7fQfJ-g^sy-KmjHO4kvIsl1QRy zc@>#Z5QeJa!SGN~_YXW6NBi7@U=Q<*%9KxdZ5n0SOqnZ`IcF_NXob#cw)0%e=%`=Y z@YlCw5=X`-U_eF7!ZK9dKo*u>Vgd-qQ|OqP2jCsJ-LkZtJMvyZB#}h*`i_0p2-AQl zB4q*yC9Tt*f@#Z#L3KuI4_3tXQMI+_2$ZJZMH_+N%T5R~>=hCKvmn{IR9OJ3X`pU( z0}6oZ&0WH&P4bD`!db}<=fNepd~CXb`jrh=9L*gk6}R;C3`&$ceEtzvU$2kC4EtqqOn)v7TyF7P@Jb$54r@n%0fTMo$gCcRvR zmfl2gXC3Kkmu$qIPw=jpYWVqnr{rGt;BvZHS)boNb}xT-@*!f`EbjgBn`k`Ii{me! z$HvY!7S~pN1#R!mtm5WZ{}Ng_h>?Hr8K}VkpsIkXK*`yH3b6@QRmDjE5kx#Ts+NVr z80|kI+~Y>UYz943)AmVu9Azq`Cp}&k*S*PyNIcbso-@O!udYG%!VpgW;~zuyU}>3z zDK%dh!pYtmR7Z=;oGhZ9PRomKyyI4};@}UmPOsQC$TPt4L27Gw^ZqAC2R;m{+uTI$ z=BBN;F+{vlhd$6 zDs>$*y*>VLvOLr=JCE+k8AReq=ui>e*|VObs90)mEqH$@okr*MEV?IWV4AWXB5oj~ zx*XO0y~diC%a7Glc}Y z6|fxJJfAkpHgDZ+z_fi#;w;giZ9l~PiOlwpu@vTuW8d=OfYdiB25q~qTd%}GtPaX! zoom=xmW`sH-g6I+jA_U-sF16sJu6~eR^MRHl_}JzkeZy*hrW?~T{-a=r@xH{ZNt8w zhWX0#WC~+MXHpU7gMW9<4Yf*HeKe=G$X!@zF%LDf(D}%_y{V#ZMAwm1(u%zl>!PD0 z`p-q%mj-R~l_!rNt&@+XJgchoSzga#9Tri$NrCRtH@=-IABj9$UQx78FS|~@&uOpn z-`vL^(jD&g)4H7Rv(wg=*C1VO&N-*`$!*9lze<-!-Zr*a#+!%cBlorFB%Yt0uI0kd z+uqy5#`ZS)b8#_-X#$3csfBq|bTy)`y7Qus4%g5PG%c?RQ^XXFSY;G@Rh9MvONT;uFfx27jZ#`Fp;Q*1MOkK>UL|Ce*_lJq zf=)BxAQn5@AKN1-3sG%V6#|{L7#bNwQ(b-G8{nU5h~!5=xd{weXix}`v2$)tW`ZHy zKYBQ8tQ1OR(wJKkGh??kHKRNd!TR;&Gfk zI)bX40X<#cfT`yO(O6rH&X!h`M^QQ&VdA0rHM9)&AX;9IvFT~dedij6Yg+Kk zzy3w+#$qU+e25DtPUdY-ZB>VKaoH<6h=>52ZnljUF&FAUq?8R zbj=q?IRhI-dB>RBk$D!0N+-Qel|eY}I~aWwM)jj0|DvCRL{y!XofS?;05hoh{HeNu zwuMD3x3>5S)crUqn8~1JY1v+n@{VX(2^Ikx+2C+f|7EG~fBkSnfIivDPC z4vOQWYEg7AhVIFk91yF3pBZ93vu<@0^{X3%(~0t)0st(a*%?%A!9!XOBw{@_1qfFp zIu1Mthyp@1Fvu;-2fd#LZfkY`xk8-(Yz%3}0SexU^~s~ba%}Ug%nbNYqXwq10J)9Y@=vuK3718XuMkk4?I=b4VNpYqPN;ug3o zuXNge%8e+mae`O$UJ)d*%4I@9th9Kas8Cy7ji$Ofltm)erpSp2Jaz0i#%87q_BEKv z*qQnadt-(Za4DpJd(Vdm;=0$8Z(a^&h&y32w=(=!uNJzMk^5T;km6R4-*N$D0qBl* zReVQHu)G!QEnI79#C~Pez9&&$hWXBplG;v58ES&^`4J#mT)?)dH95yo0c`FUk~OAWCt&nvcbTij8#5LXVS>NGYOyu=<6@J9_Ki+V>D$ARpwywx&|pv z>*idH!lj~=wB~K0v;Dvh%|}hQC&rP^I5Q~JR92y{qXVXCBAH0Sd}AEgFKz>WVGJW5 zcNDefLX_Hw;qJfrD=42I!RXK+!a?hVp4rw_ti|_$%}sQ*wxTQ?M(xN5%%^kDsjddX zVQ89)_NFFmbhaZN*u+3rH&W>|#>OXLeCGiMe*eEinSK&C$H!2Wj-cVWCMcsV0Dy|J zG7R^UU_+Pnt2NGG99B?yHk-w*iE*SeS=YWqV==TWEhCW5qHT5&S>e1n)pf-=;bx~z z;WnD4@Y&0i;Cx>mrTqH1h+9Se%NHyEtb3^b%r_(&P*Jv@KRa4Ln? zg(YMW5Z0u;Qm8I!!pRlf97LRow~1LD+$L6pxuVZ!E15a|srAG{WLeNMa=#f+5lW=c zH9ZSm(=gTNj&J#;+RZIAudKj?0xg~8_4f8c59CjZp&AByCa2LgJqsx-PiNKsOA9o)W@Iwr@o{5TuQ4Gc(8E zcv<%D`9Y|U_V(fC_!vTgAljRn5U8uiRNgx{RqyPeHHT|bY(t(8r;b1m^=AE)^=caM z=}v|Cxe->OW@8BK?-UiZ&FU^>|N52PrO0_dbskpvd~1GlX9v5P3>uOe5KAGRN}@U% zg<%*jcUiQywT0c-9x5xMKq3R&UWPikjr0HRA0tp629BR_y)PUJ;c1WG006aRD1W9O zXGcc8%alN-%X@ZEYHw;r^tE%S9z577%$qwqX#LWQI59AYhT2--m3p+llHa#hOdH#q z{GU21V~ZAf<5#ktguG)b;(E?!Tf`IiSR6#=^X#vFeFKT|vZ7B1d(xH@zf_)kX!TOGE69lv?P#wfH;X_ptXZSxJmva}Jmp1_t80LU|W zq6~KuV?#tNOb%i;gfWoyc`CaYKjCA<__5pgo8&ikzXDP3V!5JuKiM5D!I3x~A|^*k zw3}#qL_ZwW0>lw>>$BJgZlm(~7K6#1R+v-IFrkn!ce5?M?LYpWF`qJDWlrtJlzw;b zF~5V>;Ov339=_&fzAt(T0J;w89g5vX+7_q%DEA5gC|euv!lhgE}yMuO5@^I z4_vPE{^sYcK_i2z%no+)mddYR^0pP0LGG)8{U+lN`DtT&3wI|c(cjq#!!U5=?j0m2 zmhqrv49&yc1%tK~$EbUk6MM&{U}5qnnZ3veMPLL&h^!ZmkMu{P{UgP2?ep#(T4esN90f)ZHCfPc&8&Hw}r041V31pDqmta3$20f zHO+)WSnOykI`hcmMDO3Yft~;JA~xE)(9qwGin6kT_Z&7z#A>C&*)sZ^C1i7jT^Ge_ zVajB)Sl!%!0tGD%4Nz4T>)TsMrMdIBJW__TNCX?(Vi0swT|I&%crO-@Ba_XdwyFxT zcpPuO_dalM1uZX(Vk5ST)5Ay6P+N=pQ&X6npF?>hVg+$8uLF}Cz({kh-Z}&WK}5n4 zn5K!_?_I~e^Vo-p7wV1wDaBkEWrB3v*)n%OKa%tKZ0mEe`Y+9z{but>Z@xC z25dXpWty0nn?>EZexSD#WswM48yYdt)t&dg{_%&X+S($`b4#}`Z(qW6HL$+uu#IO{SEz6Rvuqm0MEjxnY zAT2Qz3d#~C+T)WLK>jKn(U8ZW4ct3iz$XhNcM4V8#akZqh16(j!5|@LmxXb0%V48h)`N6N^wJVyLMs%O-p4AUAm0ETO(EDA1!tQapLg!u@gw581wCI*_#2WNCPbkOE`Gs zGn7#R$51V)DAX>S)uQTmtyM_1mkgX_*cU=B5C8xm07*naR0L=TJxdZc@NjM%V(dS0 zGHY#X&~b>dgl0HI)x4&8V1TZpsD_M2*5S8;xauIm#z`IJliMnSG;r8)i7LMm_y}dY zh$G*@fr#9>9%n9mn9hUNqHlbg5lF{%egLJkqGFTw-m=V}ALi z*0dV>hBa%14NpE5Y5%;wv|965QGT~JZ$zcMq(+T4w51!u2Cv@&NtMz5K3v|l9pmeY zM;2;`_HMvbZ!fOgx`}NC@v>jvwzag$%wNKzEj#J#x6sjwYeQRbc}H!X`%$IS!xu6B zhezQCw*g-+_DrY_)48Uk(iFw3`G)K~%xh5yR9ju!x&_nS%X8YEoSw#wkvnKp<483w`EAfBtbl}fX9Y*;F6G`IG`^*{)_7!&`x;rtBnDCS?t=nH5iewYib(1&zwV&MO@Xot(68mFG+0T>k!t`mTzz`N~80K zb5_oibv=97Ek8$X%4b5vXrG?Nmd}CHcE{{2`fuOK+(qn0dmm3o&EMCyo%!1s)z&+m zO2Y_DVqwY;rL~SPTAxojG%YM)*VzjwmzsbGxIH+4#g@ioM z*m>q6%5f9Q%_Y@ZBWJ<@V$lW)^p89UBg%s5z_$Y*eBM}~@M7gsF_Z5yUk)F(nV1&Mc^ zsHa5n){fh9gEz$}r&^K`z~p$Ryx7g*X&w2|#pLE`s1j(@Y-P8N{-)&*V`0XBvh~S+ z;M)x>HqsF)s9+1(jyY zz+mv%vB^n%`mOKd^6i^=?77FWYuh$NzxV>8fA%R5udIx%j}4;#mm5FHws!xq_LgwU zM%(AvgO3A$FMmzGD7|v%nHBR`4RY!e9X@BH+uVHCuOc`g0>*mQ!4(`QYbGc0*qO6fcXzD1Mi5sW zK6(E3^|uhdOT8?3BUxPaxo|*s0*FIYUDrquW5bO*7`Sm8y! zcI{Yh4os9DqBq~^Px^MrAJuDGH}f$y<7qvPpmGn9wibmfQ4beu`{TU!@4Rb#&+1K) zd4gx}NTild+EShnmP@jfarINF>R_x%C!*CD@#x?^VauZQmI?J8J_(WXWA!;nya6`U z7vA->K`? z;(J@p@Ob5%+b8&&^(FB!210pPJr=Ni#EEk0a{9IE=RY)8 z@OA4aBA@p$qa<0^Oo@4i*5iCxWOW63&51mQ-evo8m>RuajEZ9KTKazN^c0k!66lMK zQG06}*7vL>2Ege%h@RO3^cB-vIWSXg@>{z$UR_Npcdo^3|8^|ID_{T7^3qc`rIYu8)WNQMY6{a`T{R=FPTU>GANV)U#@kNSG+#h1}6qLf{@ zb`@h26L{mfbR1xM0mNAI=)Oi#??%%w|s`KhNH<`u^=-hSy7;H6gzKhrrg zgQ${ZU|j?3NH`OQ7NX^DM+t;|qXtAe{+_2yg#n9wUS5B+h?M8mSe%x;08+{=Y}1gG z)b}`hmZdu{b`o%jlNg6S`V^l$_YCg#tzQ+#?Z~CF>F`G%qiJagAH4Vi?)DWs-M~`w z(h@e_x`~6wK2wX1p~$&DDAE1K8g_heN&naGSImQYtFQPtm4b{Mq^y!VZ@R3>CI)>h zB4FnhhX^s^#Nn9_KS2zKqfbAHskLjeyS4h<pme`Iw-?id!(8BSzODBFkixP@BCxARVTvD^p0{G8Q(0q#+u z`N)?Wp|nLLe@N2E_uIb6eXJO94}{>#-+2Z}zr~`KivrSZgB!7NeIF)grV)+Jfy=`ITw1knd zds*bQk57Guu@5hxZ_gHVZuS8DKm)(^-{$5f?B2EwTLuO&H+~-ISchn1YERlaIEei_ zcVS_15!bKXfIE5v(JveZdWvCBYt`}ZvkuF@_5DWWLbSFW&A<2}UVip4ngov6y>%OQ zZ!I2qzPqy%@lk64u?Lzz7ca)~~O5qERjCn4QJe%QEtw z?VGXJ|KyCPbzx}@4r?YwFtNo28Ussdqn9lyf0WjFZA5m96cbj2!-_)$l!5)nPo;Ot z70h;~i#0P{otWvY9f)Dg#3Xi{A4cEp(QI=@1tk#H*?sDqLNHWIT!&It$f(oWp2m*H z(qRRP4;|MWWx8h!jshmpFyT%{@ujTgZOkZshEi9uza{9FmsSD4tg_CfV~#9)nm!J= zLGsrIGxIl{!$_wuBuTttCBTOvqjY_9Q{n! zxt@cgz%`O%w5_@VLhyENK(-X;FEsDysP4WzsC8O|C7EYUAz88_N)~{b3%TOPYJjzf zS?Iix43fNTU$?D)bJHf=9;h8nx4*X+o$Vbs{%^jAi@*CWy52f~f%V00o>qqrquYAu zKcwf~A8NF{{a##~Z*feqdgx=NWm*o85Pf#x9Pa)85p;Jnqy4qi!8IOSgSG$T*AO+Y z%s$`W+na7KC`i^e;_DK$ou~Cd`Y(N_8O^#+ zvA)20VEZ^rx-v@DwoLV}3Su-bETMU6X<0#cBInRPHs_}Z8%g`z9HJy; zxbwnAY`$_`%ZwQK{>v|5a?P5$I(z%v93DTKu8CBH?q^T@@INW>c+jy^S%XTWaHpqV za(k7)x|>6Swf83Q+Zx~rsmBX46{dpG4(&-OuiOasuMdg5XFj^d&M(Pcb_#U!UYaV<}ZoH*!3Dmdw{Hj!*NN4V_CM^HgZ7j*+RgG8x z8GcEQ$`FNk>2YptIlKnv>)+NEBuVyRnVV2rTPq>kC#RDfN$T@F&25%S_E_BIIOycO zO`Kw|V>9I<_TFoAZhNcjCt7Y&xv2-~^2svhV=65Re0-&&a)&XB#N5&ffz0AS@?GX9 zuV?D=**pVe`G6`nV?E2m*P$rA<|k*OMx=#oAB#z~EY_PPWEcd(+t%kr_f;JbP2y=y zdW`sMo?+_-vh>{6@?H68L*_dyYhv?TwrhS{YfS9R6WfnDoqSIi&xOjPudkMVt>*&D ze^lohJ?nzkHR(J{oz%w=d9aoB!TC|`+`O14&D)9)$ZEg6eFTdSznZEquOS$*H{tI6R ze&Op4^UR|-Nzk-Z&Hx`TSLg_DmaGC~KlSLD{RdF`5v8R5v;NdA6;6PU^QrYd$;m2?yq}a{CYg&;LtTUfhd=xnpFH~vM*26bXn{I% z4qemJc=bE)W{Z|h>jD(eA zmdy5mFlqYm+lfI4wE`be6^m;$j@X?#0)eAScI;QWto`_r6B!Jr_i~H#d$qGMFC?>( zE`p2@Ey0RZ{J5^=BB}<;c?PDWErPqu ztVG61YEw;e0aq@9N&}6Sh76+f`VjN8V^sHH8##~Pm)4v^RBgRP{Lc#k63EA@B)WW| z2wm1xL~nB<$G#2|8DqC>6)qe9BKLM{F3@?Tev=1yxew{c2K+lR-)-O2^O8Su^GhrZ zcwAfD#+J`=K#9YDr7PEP^3-X(`R40z|HIq(f8YFD z_}NeXF?#lH&V9~B5f)oo5HIE*5u8WG=iIR2Z~0W8Psqp?o(r@|wLV{+Dqjy+t+HCa z`foj2YHr5I&mG2d-~SLNA3spnd1@u}*!Jz1ADO`2+oNf8t^!nRv}^Ju54mMY$vM)$ z0T*|FejT;};Dsli#CY#|oV<7e?N_g?`VrcVk(NVpAxB>4Yn;BG?IT3r`~7dBvaSs+ zYji)|P;P?r_1S4SthIy&J_55s+S3mrT7K*5QrDSYe05AZ`Tzl!xesd3Hy z-$(HH-#CChFXwNjef{vW!2cPxDNRgI;hk^33-@c^M)X@hUAR1YrXb@qpldVz&HAXG zyLgk{gQYun@8QJxbJ(zM9bP%~4Bme84dBf;R>X7r=FQmtOFz}nGkT$%^kwNHDL2;H z6F&4zZR=5LJ1N=4sgSNwYr!IPZ6z4l&P>bGU6%JYz2K9dp7W%2SJs3W7twdtj6>(g z(7%qEIXv^>CqM*z_`-7-U)Qsu4b9CES~d-O$&t<96HpJholF zf}snSy(sV$B~Z>-dcinPgY-2&Ypd~PhbFCUNi3XxqdZ8ix=oyFGk~|iayz@MtxAY8 zcMwV?rdiuWKzkkHH*>G6YJRdSmR-d zBP9N?b)MpVa(jrXr*5(K!45RMIaqGK)>v5bb%;bnNsczHv8&IAcyRPdE>i_@wiy}K zoD;T>MTzopi?knCuBt8pCHSvsE5T%|Q5Pbo{kQIzt~sL-U5sKntB*d8EV z#%8c7Vot=RdppJT1L?=rHh4cthd!J9p5#W-Wf= zO9hWVS|v(liN7%%#t=kW_O*CtNx-p@a(dojQ%Cq>PKZb}noE=CyCX15{FbdjyBEo*qPr zD-;Pkat?8#?Sn78_kFa@&S&~ZS<-+T3COa(Tb%Rc+u_dY<&+){P@ zlXQ=gS|joMKI?j{qo(>A&At@f6^Kv!$eqtzOzono8i)}ZscaGbxXFm=ssAk)}vm_$iv4nLKa3J?>Iij@gTffYdGpP?VMW|$LuV<>TJ{{r}(wl2-(zkvRzRs*m>+93CQ4*!$ zGD=)6ucR#iK&%W$)lp5-$yM*Ob28LuXNP+l>vZ4tdij5Te)YJP0k1R~Ve&bKunFff z6j;!1#MzB=k*wi7* zjr6aS7BoXRkye+=`V+|V=sd}MNGTMVXXWN>ztk>J!}5K)9O+%%Ha1_OeCip|)~BAg ztnTdh=g?U3WrfV0U&cq39Heunr%lkA5A$ zd-%V?*b1OU+Ip4D78Nej>f*lI`2pH03mBLm!G#C%M)_t-zRhg)dSPSrxxA1k_mSMc zJ%!}I`CYiLJ`23{=6!hwtG_;sqlM{zPfRI1BeQv}bZ%9<@^WeYQ#qRinLX$2e^$r)yd%;Yd1Cp)N*G?cKK;MZk~0 z@g|~&Zm^OnD699O$YQ=iA`N=1h{L2SLag@5HmjAkv3vJ(Vl4`;^)q^ES_uzUuu+vt zq%2lM-{$sWmsom+!SXX7eS#y;JdK;1ibbjnQTOB&UVis`neht%p8n`l96$6VZfxGv z5U*{QuVC-VGl3}1GK!Fl^2~iMg`Knzt7}(|_Xu*2aeBoW2!q>HK^L?UDDCWmY2Z}M~{|ipn
_Nj#$Jk(KbZQrbSH-$&f! zUlitk|BVH!g2QR*WvEFqJJFYa9 z%V=6EW5dWu^|UB-!5r^u3mitcX3sZz|=V)x7TD| zrK}7&KS1P0=7Ycc*YhbLNs z=~0yzM}d|h>-f}~kfU+>i_*{;9<=Q_&h$psI?`2*5|EvwLE0Jz%8~76H55JH$EviP z8`h+ygQZ=Y)qJ%+$M$@F1N8~YRfr$0E08V?li!eYxUUcEYt(wa9wTk17Q-NW&aOkq zzdjzUEzAA-EB4%jCTg{m7&E)TPY%RvBG>hOuLIsz|^55^h%rjQ<2 zPv^2Skk{j+q$4yT-{|x9<*8h^1mxxc)~k73OWADYxa}X2D6#FY^8J3l4Ye7McKrsM zTA~M;g2s(>)}}U;C_wXe83&1$^gCoewY;#ngWJpIT-S%?o*!t+aQVR`JL-c-X~ceM!0g`k=$q=?0fhowpFp&(wTo zr4-USYNs!{&YVNdYvFpHte>tBNeR*@g=O8tphwPWJNn^$h|U}aM(Z1n>QOobn}~ny$ABiifb!JdeRzELo*<9pZ~j|g_+G>B z)-J0>NKS(FJF=b7Yo$vNql8KWd8y`zb~Q)QiXDZAuU|vr9G=>{7g*DV_&2`}tZA$N zV6FVU{TNU#?zqEBi*?MD6QM09^>C@$(C?K9u;tOibl8rZ!)xDu2W>O+8L0Nn*w%1C zk%Xkdgp_`Y>}2acJPz^{F-wmcAYMLc@Eircb2`AvT&M0Z>`kw8L?+@vdq(BnSnZ_E zuq<8t<9NOMj-STf&(7e=j%^J`j$A)_7f*k31c}rA#v#UIC(dBc$#WnuJ+{6VN1k~) zm)D-N=dk_arHl`K%2me+z0fKRJ@z}*tL~Rlq=C*UnP81^ zGQHF$BuJ#q1lqy90`9koFwaVO%>Xf+SJ|#*G-Xe6>k%}tIkLniASv@W%14~>k~5Jm zvCNlj7vjy1INI z>TR}`bnV%?vy0Yx^M)K1a-924E3#y|46*p052$TEL;8m$U)n4mN`=O~eOF$)g^1)t zJ=(o(2;2VFFCqSw3RZspNM25gu-G}yZy)C z`z~&e+(xu{^Qz+$ZOY3tx#kOzV%7ivAOJ~3K~&NG?VZj!M1Si`aF6w+-&a!h#6fkR zIKq3!kHQUa#}j*&cVbz*p$qZ<@e_s9N6uv$6Gh(jqr3Se=R_How0WV7FMjh|_~w`2 z#6tCit`M#1>{R{f^GchqUB`hFC#y$COPwWMc$a!clHJeKHRMMwc1P-a7@znQ(v((0 z4`aU6xR>xzefw9f?Qz6YVlBqpR8A+Z#-Q_QWbCO_vj)m234?Hi=imPTAHMJ$MmO{! za>eD*&I=c@>)Zu}jgm~Sa(L?Fqd0cxN!;2rSeMsRM~-6sol)>cW$my{dDZ<)I(A4L zBNtM`I&5BFbLO6pHJxbzM#|*6LhVIzCUpg)O}m7F9ULm6On`%QVovQG(w&6Skvy}C zYlid4V^U%UwplO^*7fOAQHK>?jMDET`x&*O1ED*LPe(36)Mu%TR06X3)V3qrwzmk2 z??%;{w;L1~Wmu9NHQ?wS|lU^!N-V}rcUbC}Gpo|7Qn zq_VJg*MzpU;`vV`p~PRWzdCoWeICCeS#pD)^Z;UczQyo4xo64rQ(?TT6=Sse}8 zb!6%Jnsl_3Xj@x=W6*jLw%c7SFs`g? zhw72+{lrUdb_@rZ(HkKXF?VV`ifW(hlpM9w;CHkhR|09Otji_vH8O5%sXruQERycW zZOr;@eLO{Pmi>eKVnw~Bl$$?#pVTe1Bdc}Tw)%!XMO5ltvfb;E&7Cv%vr=h*aysv^M3Vn64sGoz$Q;!i%aK zMR;WJTk`mY<|-cxK)g$qh%q?TgS@9puCXWtFPYO&yXz9@Nb8hN@{v7*zLU*`(4HNc zd}6Ot&q?lVxABprESnt5R&U^Za}I5JLN*D1OzSoT{I=x$>21XtXUGW5w4p{LAlpBk z`5P`f&&g5`)-~tMH~ZI?jd(;EN1GG7GNAjHMVXp+2oKVAi%V@Cv44UsnM`GKOTS~- z9%U(i#l!N}(nh{f%Cx+;_20{UHImVDmL1pf`B0r&c>7)~ql5 zNG%1`PCas3<4H1&(i%!#i%y(BhqIS2r9aM%!u@}rA^MdscS)_>_BI{SL+mM2f>S)r{(kc@{4QLFy7Nd2x~ z%gYrf<5QFP(-R*d`qi%j9nH(+!nCQsAI}~o^){N!720{~jv@)vUJ(c`;zW7n3g z08l6r*{16^u;=tSvj|3@Q%Bq-B|0@mRI<7beFkpaLZuYr?EbyWF3abMnirM;XX`_P z>y+%mlUDFFs6lpJl2!ndzCP!R~~lRs^fV##%B)qUFrE>nnT z36knRMqFJAjj}vb)TVeT9YNcMFJtiL&5T=~l1}eT5FuW2h!!1|(4-dC62yp?Dkz~0 zS}Iz9XB02L^IgSTs!gr)i$EDDqdDLdY!|C_AM?k#tWA481e&cy+NG|5VeOW>zNs%ZQ0y!X;19l+iw{jio z{-X1vQ~Oca;c$E@K~^!8pv zhx-brr(PDG;k+=k%?fy~p(SPv@UO03J2Og_$z?0g7tw-L52Gp*dB7G{)jJ0xd z&f#DG$sb|-SN;wD^yY8l_22l<#WCiMr6*{qS3)AFZc9NK=cDb*wV$fZ(8 zu==djtF>dK)$#I;@wIw*t-25EAdf~{<;`)mW@_q}_P$*nu!vu4m8AKmT5)OvVyDMa z<_ydW2NB5GQ%4LYo`*jE6vv->0^O5S*mn7fS1wythX_$6$xh7C&LHW?i;-ae@l)9Q z*=eJ(+WG+EasuA0Ot>cHSAldciM>yF_VVl3>h1h~Yv&2I4WBy1^Q%t7EyfszFqAKY z0GHvM2(++6NQ)Nb(|=8u!zMGb^G7G~(~iU>5A+6h+UP4~ z2vmNko~S0{?0-6dJZj=C{m(kYa@@TpE&$gD#r9b16y+q1e`Ma^)f9Zu6Q7V=2 z$*Ge#dh)Y|o^6CuZA{L9_ftCt%AG?fx7}Va$nPpX3W~w2GXhJOaicuL;8Z0|5hg;+kS-93xM)e zTCAY|#vQaz&w;F{Hh09gd1(n9Q?p1wk*(8mQ`&gZp?z^4&GSn*^!-l|!J&I>3UQKn zyyV&ipzY>%^Oo$Lc7C?HpUcY2QJ$ra&g)E!|FoVcos$7n`#4+Vz>a{N zlc=iC<;g)FS6UloNBq#1vwEcafp)C68h~C8(rX7Yk2-)?T4&)CXu_C8)~VH*?2Mj| zWBmIXd-!!A%TrX&FK<2wQFsQ=(@*QAV=dD1=9Wx<$!N{Qg(ZiNv#m@)bxo2|>n*0# z3UUL0);{T)&SMDo`)#DZbN`Sf^7-4+oyFdLozFb<*Y6u>(6
*dwnsQe{#7e4^mw(rLt{H+Q?P$S&)AZL^A+Y(lw4GT zi~aSWVsnrlt$EK$JiuqK=y{zt%Eeg=waw1qsZY}27PU_L1XAbi!v_xH&&K{Grswld zlg=wa{d9g`3X`6NSA$#xByob$!Ytr`C|X^Ax4bf~-Wyg%q5M61PTK&`-HK?SyHHXm zJ~0vnc&s3i%9p+xiD6WXj-5S&&wlfdF!iUYvC2&^0E-pGH_QN}H@YUDgo?ZZ+_#-$jrLYQ@^kc8UO~?n_hbF0{z7GP-bbsQhI<`uwI-7=M;q^Lxzy3tju#I- z4IFwJEv>Z|eCyH9&0DZ_U=V9My8r;|d+IyC*UevhJ30c+19{ZExQMp7c@=4h7nhk> zUC=;}j7A*cCpGprFP70hJHO)cd|rs^p(22_9{~VhLxBbPT9pdjlh05ZRC&t#l4_}W z^(H7E?9`$>USR;;7!~8;gKe2J4Ulc=S#E1%RQe=4XOpX|TmY<8pQaI0MspT>nbJ2c zRM5OIldCXu#2=}Urjf9v14Ei0$|I>_F`{yUu8C>ITRZ$lRbH`L^w#~$Mt0UltuTlV z_e)#5VNh+sGVLgr1`-YLLS_(-kj#;(fYgAP{!Wk@`QmIYr(CDMi7Ro^tsm+u>3enE z$vTR%=XCst@HppV!|3ga`5TIsB^|rDMpNj|d|kDt(3SKWA0KQN+QN#f6M55ejK@tV zVivb6lfSs0{$&FtwVTY1Q+Z5aXLD;Hk}}n{kzbb*>PU{Emge4U<*)?!{un{_E)6%i zM_W0k$CHi}qq)fZ(k#p~w%?wKcuw;24QqMhUbeWdF`F-29)Q~^^xLVt+51Iw!#t=h zTT1R`w-PKwdj656(UJ%D++#r3e+P+ed_2NLu7i_c-twjneH?iD9r(h%j>d#%1!&+r?8b+MExC>1`HYGH8^$@BtV{Ga|KY^-EtyOLH^cdg&EZDiw5fbS%3*<0wK~O9Pvt9niG2geBJ;z;j{a zv5X8BRsT7VK3YOE9GnAQeD8gH{On=ObagJPET0D&x^x*k&JSmLs&;y}v!vWi%9uw+ zuhV*vZ}6AI8hBW%t3{2->eZY(q+U`#O(WP^;$LgI^cT+vYbDjlc8s;+?0?1}$TVth zAL*n`%h7~bQ-_zhoM89Kb0}3RC@q%j);Nu=3UqY9N*1}UifGGu@#r)!8Hsaxvw5_`!0Z0#~yC)V{X+eu>L{JJ0wpY(Ow6iA3d@}u?uINEfIqAJz)a8+A{ zbn~Eop|$!5dG$%j9I?kppq)2Cwcl$SS|N5<8Rvn3YxgK`iSpev~*E47u#INY-C zxL=2CB|b)E%<9A)elA2BuiCQOQKReL+M_H_nP1y-b{_Iah5fF}Y2|>QS6N@a#c8$4 zf3uWgp>%1!SRYJ-Amkx@%b#kof>Q_f_exVd?85&KS`!KnlLQ7#Y!DMUTv z6n_u(1lBgoWqUH^~YF<9y@auE%S@2 z4^6G@#^vop%i;$BTd!Qjwo6ygIhn3ecTUcrv{V5i;Piog4b^Mcqf@1e9L#sxr}%NP`FHEt27m#QR+J}%ki8De!MY3ZgS-JK;_z>GwIz4 zXvK|mrntH?fb1{*9~wn+`?PFZ&L`_b(uU5lVRd=yOHAps&bq1O?Q0J{B9Quw)-Ab> zth2rTuJvGDzx2i^z}L5&Ys{j_j-{|xQR}&)RLhdTJZrSoSnJJ|etx9hs^?sZ%Uw|D+ZevOt7*h4pHU-F%sy zsJ!Use7<=)yiLm~LV6OniJvxHR%!=&Yg%I@vn<&<<y)G@;O9)KApPe z%V0m3EDZqLC%Hyt3G(Y9glpxKK3a~vYqd(ud1M_)k2lUmNCrjfug#n7qw+aDuhDm# zW1oLsUFhfRJC}z&TvLQfdl~IF&SP@#v(U$d)_4w~xk%TwEfu_fP+F^VE=>hCWU0JaG6cGDv5F7koZ$E!XY{lFkQp?9=t2kRUE@DH%~7sv428!u$nx;s0uWnd5(0I(|n#s}&j zEgBsd#HW|fk%$%vqlvvfN-?eDUqI%D(>Bd1pacXI9PU~(JsJrvw zF4hj-yoJH*w-mUxK$`&`|K$k+*|pS|pvCT*@k#7De*qVE?|L`|tV2VWE@SQZ1nvy> z{cbZzIRU1F~I>lm0YlrJ9&Xyyk zlL1AVcA#bL5_GMFAtN%*_QUz$+M$?dPV^<+M#RsLKF$1WyM*Kek25+BhwEIsTCn?n zx(LiJ7`n{5eZpX#OU1oU^RYmRu7%3UZL1x#<(vK1$R9iWTN*ia^m69NOVZrGXykI8 zSyP78XJnqj;8I2>;}NY(;R6^A`sG;CvX1uo+tC&Vs@iDbk8P3}wl4GfeO}$`eCGk; zJkVB8;uo6}Wcng$xNU3az^Qy|R1oU<#i*sZ85_531YQ~fP8DCUF6vnM=ZS2eYP7$s z#ydYxbb9zAPX5lfuwkJIc>aaD>1F>fHx$ z<{x|m-Cz3xhJN(9x@n#FvGZ)?rE65Ou%1*A*R+H7N+^mVeCfrPQ2FOO(YJpHtvy}K z=CyWx55D}9U%|RHX+5v)T0XDkP{-^no;-RC&hbWOb{y0Wg?etID0p(4r+p6Sn4VS9 z(05|uUgbPVouBw|J5rCQNY1R+6IM>LvEY!Pd2R_294b|Fu`Hu3 zGx68sPGTSjim=BBjN=7M-c(j{&X&AwH0_W>OQ@g9Jj0|3>$}D5I5O9|H*jldjLdmr zTPfQ(Qm5ruq)9|NI(VB~+FEPvHcg4q=#F*@))>QIR+2W|D0@!g4yjLQ$8GtEJs#;3 zeBiyr;baq#u2z-IIfD9=MsBE)M~R=Ll|uFcizY%CO12;4^+;W145>$pY$0wRUl-%~ zO7>sLD?$Qkxsu4$S^{+0Akz5O6Fr{fxU^bgJsX7lo0u|l-njlXUmthM@+Uz@DXzOb zoGd?j)W~%DU4A>*xhvmZbiYW?5%Q|0@O-38ZMV41x3^)brT%8n4^AA%=Kg+c?jJzs z8+);NTN_@mr@b~v^=j;aV79h?-~lZZ=auI{;NM#BFHR2^L$}Y(VaLT`Y`%IO<)$WF z+_e)6t&N?6+cP$f?H4bh_s-o+-(bDNo}}p8_c+Qa=|Ft^d77$8Nx80xX>7ZA82}17 zZgQVBP9_0XZ=%V=6$s`6>7hQyKjTPdIuSRKt`38{hP>2mC{ zNLPKGm!)00wgA|3PEdVDyF{n6ENQBt$k3#hLcEVQ5~j0#T;;=oI_zxDWk%NL0M@xe z!KJ9CTvoDt{6YCb#y=AEp*P#f`P%9~y54CGgF?5+7LzAw(B?AAMQ!~Os#PM9_Xt)q zwxiN7x0P{u8wMbFg!M|DFTP{fl4YKy?i<1=VcU__U2MH`+49KNrA%K>Ke2Pd{hNvE z+3g!6*6Ty}EKb)t6l>0WM`AA4Np(OVa+2nh4z!WdkMJy|ht6m5THt;|To`*&oz%|Zc?fx7>QnsX_c5?;O$^6<8L%9#V)tQt&p0YT@Psw@G zZGp z3&}^nKd}^$@71%J=3&XsOR~q7&oeo7K6b=cOj)qamNf0#s+w3H;+a`hU{ z@7Z0`X`3kep?!!3JBn6CKA$>em+A7HyK6s}Qjxbra45Nz1w>mZ-9P?|%^y^5#y?ybvYdUh5kFJ7pduBW>joBR9m>FLurclk1&fBZ=_tsuD7 z`nz{Ac=ML%{JgmIz|0<7d$8uKPhxLq;e2R&Ar|hv%eeB~AojnoGJ{u$uH3qbeLHv7 zb=n@hc?&IzOWAH=JFxNus-5_X)VWrIH9z~E04qgg$eUDtP^o)j5^KgMg~1~w>g!=6 zh@KEQ@^DF{O1ZSoEnw^At8h_-i@TP0ob}M9%V?WRBX-~2upXm*#gA;SMcXc4Nq7HG z&!A&w25`Wwjl~_eyQZhH^ZZ3@x^@E<#3+L!v1vKsgLtU=vmjhXgN3SZNxlIB*>69M zf3Mi}`$rZi6}`t42IXM@MyW#)%2*N7bw~?W07VKTM_9QC&1s<0rY#tO%yAWHbBZ(V zr1LC6M9QgRmQ$_kH3U~%e%t>-3(_HHZo7kDgBz_#>NY^&{Z=`yU49MsH1MT5*RBS{ zfe!ag4PK?Hsw$7yqv#Q+rsq+|xtB}Mb|h(#p+9y((jhdHNnWhR%TzAVMzZaE&0VdVJ{36fMOrg@^O!Q@wTpbQ@{#&khR| z?SP%pQ_y3jY-lWp@?*TdMQGoWZnTMt-C^xp?d#mZHTeo*!N@u?{sIeki9bN~7nqGvV(JJ);ZTU%Q2 z(o;`+*C(c@F)@4#8_M;aWCw5EsxJC!eOBWHzrJZXj(;-_D@xNux`3t=P#gVYy#}m>YoN- zWhc~cmixYLWzDRTBJUZ9R8j*fI&L=hZ2(@~P$+FJYH4o9;40z0+4DdIoIH47*%1MW)=W%dX!vrq z@1&(Yy>BlT+WZsOYEkF(4BBSrQK{k=8Nt}!6ds#C7Sc`h7zjr^w(0X{eu+tZ9p>{) z^)yo{H>^a_vPEjB>0Mi|GQy6;Rg^jbV{3N);H?ayh;}J4w$PZ^%0`LqxknHV(-=|y z4Ph%iwrk^Iee#XJ_#EnYQjTlHDKW9%evFC3?MC%aXhm+&WyflMdjdUbV&POHYg(Rk zl(vZ;nR0xEWStyOy61%E9E%fb$xr`1(g8o^Eh7WR+0!XM-quVrWE?0j*Rix0MS`!! zVvIF-(TSc2jYd1a%DIEL97t!5l4=)UzFG8b>rm@uwtjiUa}Ky=WAJDvq%6y6%jVm9 zv=h0k0mf({Ern9@#&Ex{0J4^O%es~U@_!$j`gO*2>er*4mm-nJ(6dy!#%XourM%u4 zPFbJ)+6Zf_#cAZX-@&@Kp9kI^z?R2%A?fSD^*guGx9-XlUq%jBhe9o1%Rcg8^`VEadv#Avp=WFi9kX-THhcvMB5c2S36;2nt3z8cSKuVu zzR^*%&&;BC^d2_c91$mWXzY-{%4F6he7O^6vsXIbrNoZhDW>S2n8x-CmryEKkd$Iv z-?EwWH8P5h*;%0aMCbGjwhv!cjV=lh4yho~*6KnMT5!#K;aG8BPu% z>qp3Go3Rt=8CvhKwWrI*PTR!a*9D+zhjjSR$khGS-y|m2mt~w%GRwvPQy6S??w4I$meDIm&UGK2Nto)_h|~D za9@VWT!c0j_`Lk@7N6*wt#@%igMk>B#v*CKP*<}r`-oMY$5D3C*+w?;SI z`}I~fSqFaYMdr88V_th$xn#$@&T)ABhkIKd|K$w)YaBhOrC+iaujYyg0+7NDuIQ>s>?El7>KcDkaYz}H}7L}-gXKWpF*f|`z>JDdHu z_Ra|`PR}9w=`W(awH2p^FBEdxp1pYwNB)=JL)=ut{{QTUP-+eD(s$0mIiRUj!sEO5 z1dl2PfOTuuVrbLm;5|t_W8>IxXG9$_WW^i}7gnCa6q*c+P~WoB6~tIOHh~=%hvA|Kw+HJx zd2~%pWBc$WY`k`}y5nC*Ytm8KESQ#t5&&L3>v5qKWDRig|FqY{B3_B zesb}fk9Cug19jgdUSVUGz77=ahZdgL>%K{V_-g4+j`V3QP^>q~BbhaHbaFN!*xA81 z%jy}%%0_ONSf!LbRPrJ|8jNZu6fIA*v4Z8X55;6(<%Q@{wd85d*&g95$+jP{?BbHK zLD2RLrZ68Xzw{ha5+x<=s#g9q5Du3tEN5kYIC=qn_`PARq#pQ@@1fsX^U+$1Pr3(6 z9{xQ)5<S3`*n9P5 z|GkL`96xgwW5dJP10aqfpee%X;bH7KuxACQv-lcy5nBD0`1cf|qi4@xVPPTry{W$+ ztt~CMH!*>|+jrD`{_ey$j(+DOod3W66s5KnJoC4I7IAYEKKtV%n06D0no@`6{@z|} z-@F9?(6S0go^?-7p=W#|+mI`zCXIWoYlRJ49`25hV?%c_ zXYX2cVApPJ|0_R%fhX#pG}JdbiuT#LtRD5el@gokis|>P8_8CwXXf(xCIz1QL8H!@ z84L|y&hVX#674%``+6YH^3sVgLWELPH%+hh-M$MKpU3d-9hfK(xn0uQ@d*svyp5KH z1#G-_1Bigr`}eJ=+&yFC*l}SPeYZwHy{Ci(7k2N$LcNEpG&Fn}t@8`$9-kCPm`l77 ziyBDDH|+b^*^hK=(@I{tzlPdr`P2wDelRm=7z2m(N?#5;QU98U#lO5b!-$h2;!$hK zqd+xAPQRxbrj$qFTFRRfe5Zx<`4~wScP5ot5_|jnH0H7nCX&B@>Xg69Uh2O-?g*3L zXDx9J*?Cjy@{&J0^H96QAjDg#))SAnxcZAiFYsMP)z%sm(j6_v@o`veuI80nm)6#= zlmj8Bdu{urvLxA?`H)z)SCVCbXIH;g^YNySW94iqab8|Ouw~Ua%z6Ce=&Q#w57SBK zL2XY+XDL0Vxdil)k?sAyDf3}%6S@a!Y;Q4ss2mz|O5UXB&=qMJ%tLF|24mkqO>H=gYso+}UOM&snR3wIpbwxrWkjzJ48xZ7mq9<9r=$=mI*^wZ4VL zMcf)4LAhMPQ+rpY-vr+U>#S`p0r{4JMyYw?8eCk)QuoT%Ff^@PJ72j@v=S=*Zd=MV zlapCc9{^ZtZpK*e@*VrTrl&D<=`uE7xdw-*ipSDC?mT}HNfcqSr?#H%0PMUljGlXA z)j5hbE3zIT@r0GbseFzyxuqR`X@22PlFfCz5x-+{1_zFRhH`T=7RAX@yUt(0y0I}O z$Eb|@gk2gJ>D<{eyNLbAPgbv|_b%+&h4G#qY`l3Bo3CB3mR-unI8c5XNofEPa+TYB z>6((1*3mRwvnYWAdnAg#)CXBN2%pGdKRVA;Zq|$CUmZ!5Hkv2ZHlp<+UPmJBgV&7G z(z6wwH4~~?zc2ATCv{I9fts{)no;?Ashfo6BduHM(h~>P-F%$J@6qq`H`i(XI!})y zok#LzJuc4u@)}ilsXC=$!iVuGN<1n2}nWyz0bt z`$ox0zk_55U9sA*)g2`dnLEF2?KP5s^d07#+)`@$Ri4bT`n=VvIjx-Qq^y$p)p-h) z!Im)+x#l+0(nD`XwUN?U;>x;Ztl@JFYx7nTSZ&m=H!g?IH9V8#;|PE3>iYDxeIK)s z^vpwoa?X?^hHKK9bejD9XwLR`ZB01T8sWYYsr%t^u2b9m`m&O)`Q`B6Z1HRn()CVr zX8K)vx>Gku@)PgRP?EPtKJw|L>`){|owz`;2Q#;pTX_)^mTOL0z_B)SwmH~~l zkA7B`K}(L1baf{0I)Db3olp3r6T(wpJn5|M%yV_=ma4PT=mu1UlQ>(cwxM8Y|)2 zpL~kve(kTJWo_*c?Jqw0RL%SSy}j7CV@G2psZtmK_++m&qL2c>!20z_UVj=}2L`db z!6T`N66Y{FHin^J{tBKw_&B;dJJIvAuVL5EzP2oWmJaRPUpVdUfdLF&zlC@)@dSki z&>B2)8X{kD(G#3ca?;Si)K?TEmqrD@xoP8yqg6f1)O+_HcAdX~wRgu+K@+sWLjynU zIGEO5k{KY9oc5zAuj#J%ro}QIJ9QRIP0esogwYM_u~g$ohR8V#-n@m!PM@vr)K85{ zy(9M!Ifs^og)|>cF>VhObFL^=Dj2wR8x9fnoIZ!6YrJmMx@4SyPaVEyU5ANg0-^U3hd9iRGe=D>4EYmxiPs#jfBI*>Xx?48u<^Ow&Cr z8#w}3o}8A7cs`hxeML^cPG=D_^5 z86n(8+JPi&Fvw;WSa8qvBJ&?M;Oja^HMf4cl$$i>mOxGtoRZ_I5%+Lx6W?%P=S)EM zc!qf4m|K2%L(#%Hf(Z9;%DW5jvfphauTUS={aHTEqu!4oW}zTJv10Q|%k`r{70fr^ zbRdmDx{Ue#%}Ou}{WM?uX89z`8auXif3(IM`&-w&UmxMQ#O5#jyYV?-wTL81{@uL! zxX9dj=iXghZ=J{9|Ky8USX#sf$B)6CA4T-+mSyL-D0p586$Q@A1=#uAh#ppdSSdv~ zb@3vOojHR|{r%{yM)7jhj^tdyaycLwnTGquXNcE!;E8{_2TkoQDE-G@!Ss%9U?^S4 z?(bcXom-aQmn@C1>%rZ=_2?O;NL&8KwENljHuUyl%RuoHazd0ihn-utVr^G9fC%xA zyo~(4uNO-*BH_%b$Ly#YRgTSvA6Y<)>=M;i#^3>45ID`Pe`q8`So}9$mvB~sV#HgSN5fW^@d=*!RwiY__P*UIMD7q%6&@(oH z4Yx+bsc5OTwCU;%EVVY{PJcgUy14Dz=jN&>(xF=Z7(*8?p>=){6tz!A*p^tMh*O2G zXQ^8N+W21^H`g`@7ss?k=J4h4ZInXTsa|@(*D6E2e4UsPCm|(9R{(8R=Kr5 z*BBee4b@VpkLY;7wNPo8myJ%B2I^qv7<&qpmItB!DRHp0-Q?M0@-Q)DDo!Wy4}DM3 z3SnOuPSOR1?00mJzB5i`d8O?M{)n`7$$9qiX_CDogmom@vFk?^^d077?|qsVFIo}G zr_J>i=SwGbi(K;ZX-{s_s4XNh!Z^(0R>s1i-jZ*d;5P%3pDb;7V?MuwLl6)TE}fJl zj6Op(V{1Z}fZilAcBmYd5C672{dda#R!esK7}e@jb_8&QS1zBfAzi1D$)oM7_Webq zVm_LRDh}~tjM+`AwVp( zLx010PB-$%z)Liy12>|3Y3iJr!DFY- zV#A%0ObX3(cj4&M=^F6Vn(mrGf+FY8JvF5mZy&x?Jw25jgVS+bL4pW7&kZZ*2Y*bk z>?Y@8+OSA}0c7{=`kD>;Bf}tBCk;xUo=(W;ODY{>33&3uqe{}0#Ua@IPM%wn>UbfY zAgRs<^o{Nfox62<(rJMO($NY>EwEFXwKEPMb4jg%1#u%kouZ+=(e&w|pgG-<6#>Y%bW$Ze2TXRvdSoijDw;+`V; z=~+OP8meglrz99n%_0ZCzE?u0Ny5 z;61X=^Xk!(Y_o8Evi{3sLpp5BGKO^-KdsdRwZ>m7pZR)Bt@}l2<#TQxEq6u_J!g>@ zAQ7`&uav!9$`wXkdd)D-o}!kNr%*vWQDe3<^&M`TdT7PI$EkAE;^p^xiQzcCoCW-~ zI*ILS$ugOD`3zkRm%v{s*7yYKuB;8a1tYAD*=_2w{bUYpTS@ZkH>rZK%~HdXHjBNvFWZv=^fm4cECo4bsBY@@b$^DIo0Q~pKEKd?ne%-4SZj1z z9!qg6LhU5AlcKz=Y>@LhIcNhBXe(h{hrhTB(>Fv~J9%IzHf}=P+KJNq z42o(aKj_r-#phq(U-CN;JeC;%CZ?uv?A=dr_WT75J+~ikzw`=T{*AwkfA!=49Z*`C z0@u~qi8x+Y^skIq$#nwy&N#&gfFh{tNtse}8` zH9m#z#i^iz78a(KLKC1=o$3?qjMncU#nAz-g2#`Y$RaK;HHV|R7p10h8QqgpE86)l zsdZriT~pISSxHMU(X+O&llj{53G6#{8r|cQ8ECePQchgc$}la&#c zcEIZGpC`aHdX;%-~B zVeK;b&cH6a&N*cT$HHFC-**HK<%kWpwH&nl{^<8*DbM{rRU6Ptg-y41B(CTMdZ@oN z#?rfq;LEv3RYq~HUA46=jFw7dczjr(A>YKHKLitXj^rI{pkN55+b`4}bcOf5T7!d* zE@so}RtlF}8uDZv*z!8VN%v>jN93Eyg#aS=a>2|Rs%$$zr3#HBS!euyHXLw^>lQ(F z&)-Y$lQZSB^{DGg=3myEZ)hX^()OFM!v)OKKFD>VbespjjT2QK-Hx&itt{}tZ&)_e zpMUPp{8Znp#AVV_Dt}za=NiQV9qsLSZ2JxzK5!6I!n43boZb1Skc!%50vKl?!-7Y4-DX${Rhy~t(}E8^!C=|aCc%H&N=k;tiypr2XXP$ z9f&&HfH>v-_<#9h%gR~LzAYH&uI~&zvS9<-X6J>|c9C(qI%B!7rw4=U*JJ0Ftt;Xq zHz4<}U5gz*U;iYo)ut;$+pzZD1lp$O!J4YpUVOdY*CFUSP{c6EbCA|fS?7>Z-6|+y z+odZQTi^RgI&H^Ef`MDNmHZoD+k@H8+8g~PQKY>sSFWOrW`%=&$H1^2Op)&hC1^}c z5iq2TYQn(v+i(uJGdKXP+4%a-maEs$J8~Cv?06Q%)&YCYoI?`Fm~Ureajp3v<9X#O zdPncUI;oON?a+lwh~dyWJCAW;&sZ}#iJj*!R(Yk)D5Rq#3Ij`91KA5AQLh|<&_~}y zRtM2KDF3Ew`8_|RljYf*@I&bopY zUjNXt*~e76L^3tkxVCwaos*+Yv%|bCmDGAImX$c2^P#bDc$14n$9{Pr_)y)1oUSYe zvAB-qh69fSiQpXQpgEys*jH~#Y>B5nx4k|z)(ZaG1Z=zWWSNUG?dT!^Q=#sHf%t5M^(qX zJ_(!|0UC7LCauC=dzkpJ95n&=?MUWF2btHW;{Dl{re$#vi31)#dICN7#>FX54((HO zc=4V0fym*#*Ivd#YfJD=4nT9cjF-Oq9^wi+Iy*!tqsepltyFakdoG9Fpd6n6V&k|R z3EiF7+A2mP;@OJjPb!I}b8v#PaI&scXZKVClNz?Hc{wXZUWw9mF)CL{ltydjQXW{G zLb{d9%BnYN#we+)#6y-|&dw5(>L}W2U?`5honEtLlbqRpYUf<31<5liy0*ePrk-o%xI(qmw$^3O_9-%dQ=;~f+7j!Y0BfXS z(z=7J$M9&eeb?Tz{RoDa{vFmyw2l~M|A%mMBl=2XX&a$%?zA3b_2=3c+rMumpPvUO zQnBVvtB&CmPCY9(c2HhIc!JmQtiD^+88*Ky_?;{ZLwbB|UDoQKdCNH^ebV-*`egB^{406aC)-9EyGU8#U#GXx z6)p$Ys_d(>7u%KM`p%kKCe_Y=5z=Y36wvu9(!c8Gh3k&>6De_duF%^$B+8OK72>`h zMO)6q{%_{%&${V%cJj96h*XYPmeHA<-0lFKju8dZSxF|nZ~QqVjD@uZke{v|AFhE$ z`cN)KG0M&DxYs%;?2__5cGmC%XUIHBNhRx@*BYch-s+S4N8g6~@jbw+_ksDUlRp=Q zsM67exq&TMbMYwdJ^4jo1-`*QD736l#TTz%!^pQzpl4zpU9WebT&ZBHxq{wb{Ru>E zD|4dVy|sAM>V=k8%(u0nd49O^S zX`zf~-~Z6#V~N_gj3zih80E;=l~j3CeDHj6&-vr}B12comsBVVI($`%<%g_moldre zFK@zSrF_cYJi;WcmXcCbp$)fDNNR?`bLbf!*A_D9cS=z1NOQ%g{k1gdk6#{k1qMlX@(01Z-#%-9+daUF8G z!o8dGBd^%pNXX?!Rj}#Omgg8^+8mLRgiCTHz)S6yTLN`1D_xP_iND=>>zBDU0F(Li zDJ)TVl<791@3tOkq>>Dwku0HRB*wb!kDT)mxVLiHDXzMA_|O@qK4kgwT1v`8$zN_h z@W-I$WBaqN!*D+h)wO+3IPanPM_;c!zto#6R!&sTP)_AsQBpET%0jEl=Fzsnjo8@N zhsl{4lxCOE^Sfs-e&!nR>t8FJ+c=W}wP~fZeo_AS7xRSVLoMy?VNrfHJHz=55OZ5+0rk+TKw99%WiHIf<5qMNxi1f_HHI0_V1#G;26I-ragFVt)J0I&sRJ-9(8lH6~6adHeus%1+{xB1d_Y`Jtz@uSVpR9=ok z>K_eX5qXx;_rkc@>J1?s#mXG56GJ_(=Ve_Fx;||Egzh~E%GZ92KCd0^te!+jL2s9p zcevgqr%?UUmi-iwv2BgFtkXy!9u|$}mz~>(Pkz!-bt2&a6GFP0FV#nW)NC6$A6Ysd z6NhwR%A=17d}QhC#hh1`-K5!T%ZGl_WvL{uv{fjsC0h(AUZc!4V;~;|@Ox!VN=zm5 z?a$?sXFl2J#kK4gep=h=PVkMPTUqvA+0#P^PfJsax#TrDrsOhx2(S9M%GRNLk}-%J zd;T2ZV>%z7**vo><=HAS4hm^%a^})KQ@)RF3O+WKr(tmlDS7b))@td_Q z~5#6{wC zD+4wDt*xgrJuNm;c8)Ay?XkPSmV3bK4Q2YiQfNHaqptEKqRJx1>nB|Sg=V{lO^s_Y zc{zXOop({0Ujkf&au$3iZH>%D)K&1(JKyu9s~vC7Mb-5s9-Ar8Ch%OJZoKC;EYf1g z?jO?8c^p)#{PgBT8Cjca$VMKPZn-ijNviu$KpBd#mw?s-^jIYfl9$&sFSLForMA5E+#_*YXs+Xk(_9yv zD@j~-tAFY7mLC|1e^VWEUSzJh$I25$xut9%6u&;hI+oOV=!&bsrxwq&F6?~I`Qj_# z`n2_8^J(A7k<0BUmvyY2=H**MI;oz=nPf@m*^qwX^Rw5AP*@+zqm^Q1pI`pwXCAdegs?(AqVXb88?riw!LSvwM&)4E5 zpOteeUk|qr)sDu@+$-c9Y3)q;Bcn*ZZC(1m@+n-8_MR?N(R}Hg`1#d!YO$&l-$Qwo zebY*IYB`<(Qb}N)y6G=VdVAuBE{T@;GQYB&c@3PdS~(>3*GOHpIt{-L!HB_(7&+t->AJw;zZ8AscK)$HwseV@L55UwUiR zGFF6cZr+F}N$}W-v)O?29VkiQS)t(z7K$JgR}wUp%PU@_{Jc=};u4;H|06Wbl{4pC zKMIQkcUCd*0Su*MG3QfS=X9hORJ+kVRDY4tCKYJuj+Lfz8F7*ziHisqrma`5;<3}i z+WeOQ03ZNKL_t(%v*^$f61@7Ick%Du`cmB^izDaIyrhpH*#Frn4BWhxEiP4rq8n8W z2v2={6i1(V3itYaCv!RJyzt)l5icZIL~~XL`siXlysIMW-9b<5>>5cCdo&;=kxUbI zdXx|C+$QCp!Bs1DR3srwIZZ zm8#>ntQ#GbDRewr=%ado83$T1lIdi9*|A~kfq93n7pF!5P%)rb%-Jp)d2f~Zlt8X_X~XrQAv0hh9ud_zzf~%}6e&u-kN8Sw8setSSW>2i^X`{h ze)NcwInNub;c;zs4?Az_ww1g)KakN;Qvvps(a<^P|(H*2=!NYcZ;Jm=Pe!oDw!wb4K?=x%iP%y5Pr z&MMMGqePkJL9cp{nI81OAD{=l(P(<-tIYHuGsz?~Ek;t5j59VIN*r=H-O~+BFF<48 z_rg*@6{_mqb5aj^{P_2|dt~Oh_f`RD!C{4aGBd)%Bf`Vozlg}l#qk4I)<(AknFddH z<>0>S|COe(QP36lj;ow2N8fnps{nvk-+B{Iz4$!tzWsLmhkxs6ufuNGECse-ZbmqbZJoeL{lN)jMo}*r z0dtyc-3=vobftRf-%J=RnWwUT>EW1>H^ewk)(*Ru>!9_~7i6*hH63ZySS0o;`@$OA zVOwwQeJzXevTxc^-5AGr*`DZ2xr}dHdXTX&>!oYEjoRrGz}j{+&Ku~p>7LDf8B(>j z(Sr=?x_Fr?gZ_4H9kXSXUd1}9J%}w+;cA~Xs(nNo2Xh@`dgWQ;<*GfD#?wsMlEcst zf3!zr-Ph4yY8%(Kvct(smvHj(<;nFBqp$vFzm4^Y4p0A2e+K;Le>5x4VJNrjZr-}G zYq3?<-3cr@os+z>G#(9H{W7O%N~(kY1lD~IUvKest9~1W0E<4p_Nrx=Es2}9BVXfU z(RMGnv(55#&JG+8^W1t|m*N*Nb$!ZKxOlY<+f=^pFp#};7c393lF5^aL_6#1g zd9-7EZ5wlpueg=;rObYllVg)S=M4BpVB=Zg2IrkOY*#Uxela2X7q-*BdD5O$uRsns z4_odosn08S@Xy!Bqr*6+>yYDA#X1qc^qY24PnLbDuivuI*K*izu^+W~!&?EwFV92d zn1cJlTdE6b?cb780KA%PeX!m>&+!}g=!)tXDYvI?`mSQtDqd*u<#>)gfg=ZJ%{jGVTGH&kD{ z?fYuTk^LCQ8O8t_Ij%8Q!Z8zVH|MU<4&T+8Xi5__AWjylq zv)IQ8*t;u{BH$ay4HlogG%Qs0xc{YBaq?gvPk!(5D_w=poc0b5@cV!IXXp-k>~G$X z)+HJ7=(ZM*co37Sv4;>jYPtg22# zx3(P?-wx1i7XF8YAba0`a4!6D7<=EG0}utOQfJZ!lW*YZEyX8~WnU(>bqw{N}I zny$9e>*BcjD{oV8yZlx%_eZQ9Qw8SYDVwovwQsmRxlM+vHC=ORs|8O##1p96fTfy% zQGnCl>K^Owy5g;`Ppu7N?LAfWBRtVx>7LqE&S`Oiov7md7-fqxw1IvEmhQQ#=rPtM zQ>@QGUgylW6@g^`%VqLO2&{YK?V07SVmAe7)fmuc$LW8n$pU}o2v{BLTFsrvJ=sxsT&>O5 z$3?Ym`y$ePcioNq?%EBj90xt{(#!bjGcRBtCkUUY?d#Jo^XYbyv&J85EO5{3Z(?t~ z!jFIL2UopLSCjS*4)E)L`6FEO$*0)I-e!X^tAaYB~N=$6~$4a<#(E?|*-AADf+Md{_i3SIA3>h3q+#AAQ`GaO)Vql1d;4Ex{l`rEkk^|z=cRV(8L zZQrDAczH=V<3AMF7Jpfv@eAwzI&-&aRYx)&9jGU9Sy!7cV=;a-H0j!)r{zXII!EAh z0FF!TGv>T_J!~LRjjT6q`v&cZw>fTDY-0?sOD8h8t}moiraVskehYJ8Qy-Umce{TS zUwOQw_&44M80jh+$+2R_#f%UbTiDj2&2bda7i2ra#EOjh6nI5PF#=IcV-(|1*G|)* zctUW@84(7L5Z65(%eu*G8WUH#%KWuljd3-O*BCY9JdU~ind9XizUjrksK8v^s|@+A z-}*4tU8anTBi@Pey^ZgB6sitZcq!svKGA6>D$|Y*Lv2;`J@t zIz8m%6SW6fP0Q-dt2KV%$fJsItld0zt8KlF{kXm`^bl{>ZqFTA>HfRI2VRD*yTuc# z7u(XjW_->54)VK-2!^&_!ZvCTX&10p6NhX4awE66zSxCOLe-Y4w@9^MUzp?imOqO3 zIH$`N=NHguuNeQSuDecDr*6miX|Zi1{eo?up7WMUmT1iPX{6T)pH>Tw`QKQ2AKEfT zC^hBCF3MZsjB2d046(l>-tjspU#(YF=W49fG2axgD@VD#Ic}{e#p6sD*`62_hJUgkeF7P=r^{9VV*%tP@|w1XKtL!N6H z%(vS&rOv$+Pf-1*2?kTfN>x%4mD86#d|@evH3<{JZ%0hU-Vub^q{h<8S`Pw{id7_gpbq z9L0^N$#&^WIxaf4qoliT+HoB>^*yleWAN)ICuI}pp9j^TR|D%F^BnOPoz7gifZzJJ ze}TopnkE@K@P^=M=_u#AmB*^=jOqYEhpK>LH+Yp))zx=cPs;~`ySu==`XNc zt?=4?_fFRLv7h}Mcf9ou76-O)YM>NAzsBGC*ME*hH=HW={w=rQYtKH1`(O6Y7xw6Y zzQ?N9i9!aqJ}JSQw%41yb`P7s`hJ$V=J+;0>#p|=p8(+Zd4hv^_S;1vFTpkV9r4D?7t=;_(zgXa+-hvW4re{mDF|UNPT#BB7dSU_Fn%%vx~0J?%rMir6Bs zhD`x~JE>SlewMgBUbOv(*kut?^wLgUk+(&)E@jYLwW+pc^i7<$0@1a9Ju3Mam`cZS zdyFIE1Or+bsKy~2V~@$ku^(faS}Kog7!R2anH^ftwZ}`2i}RO_ zYz%PE4=)K+Ga1;Htg=|%RAoMj;PO;;L^-SWc!g9~?m6`$Vu;Ldr+`u>YZ zhi&WCCdQ9(=D?G6bJ<)Q>g6}%Q~<=+BNyhgq?CEiPWf@n>zKj*+KZx$U(|{GkN>a^N6y_D)(JWA%Pp2B&0u6g`>7LJ0L9a`}p|$ATH-a-VVg zY1`UA|0-|Q<}p8jaIHFF?d@?hN5lQb+6}WDj*~o!@{RO>y+)w%S&U+|1-Z8>d3lpl z3l%A;zv;?*+_rqDlBO-A|E<~|jo+$C{kE+vvSm&7=rl%sxgF|F*tz~zXRd|Pl*P(Y zaNMP1XKYN?a#pdmwxfy<*G4gt>5i3qu!6n z8g;eRTI2j;t{MqcJX(C~e66;%tG1Lpnxe%w4taNmA1T?6pb&nm)cJmlMR=TY%*4Lb zt)7j&ybj47#dX>$y8{&Fy#WT+V!&u0vP!*_U)UiaLI5o3^huJ@mqh zc;Ka15Et(pc=Ab@Y-k3vv4$;7_(@N^`Std<-@{`+`#FC8?Z-abiWcjU(Jl#PNds*jBg5H=ZWOj*T+7h1xGvhK{@a#Wz3f%UtpJJjqD#D7?{YY=`Wat1=n_Ar zXnXwk7|7PC2%#Tmu0E^Pu&YF59@g)`y8@`QLhKbqWO(}m8T0&r`xS)$usDLyu+O;pD~3a$0PQt~qrYfA=^4CjR-k{}HRzZh%}Z z1-8;o5l@R84_$qLT}l6Wf%wPSvY$0Q`t&on@8ws)8!)SQ*IHj+)LqLMF+1y`L*wVc9ksX@h6_d&F_D(y?*D;JMfFgzI8ZeD_d$`Zgo^Qs4>=vm;#8% zrA6-P-LLxjxVEHhn}4w_2OGK8n>ZqF_+9jC-1_cW{Q3`ngr9!*JNT_X|944>9>8*c z1+2PFm37nhz_|m~Yux|B%ed#&*SB6dZtOmBX&?PceU0j#zYsob;~ezNPK@?5&^&fv zY#8;IH<&Z(v^0E5HS70!E4iIb?yoTnPnIOjTIw3nb`>wN433Yvm-W=+m_JhFXJyz1 zThkZzd^!Hg7y^iT>zn_z&*F)L5vwpooD%D)@dwwj)h3vDrg3_Ge~Q}JIOF2oN%3zk zyFNLL@3;(%n(f7d4z^LqV_-kQ+4bBv#SOh*VPtmyvr{c8u!JHyxE>Q|M)_4 zjIZr}KHXWbvwmv)%dgNz{n8BqJknI>_?}}J)hNE#hq8IJ<=p-DPL7D#U*)@1dw@#j z8YopSB1eo-x38DWd>Iq54r{i6W%t`xAk#beHapaKYV>{HUOGU9B5tB!o>{z%hT_4&&^)9B1IJojbs(+b(Eo+UB z+jVQv-i33x=FJyy?rT2)(xFG(!zzn{Wzkd}c;>>|8S|4!5_?VBjlJD`x@Ijk>rn#~hUPtv=iY*ot54TdTag%l z+Hdw@-VR!O*T$-ZDt{e2>)5C;BTMW4culFSzPgIS+NH8p9#7lAQu5OrtL0id-{`ZW z&iZ)F@nI{5T~qxv?zNl?Do5L%P%u zYbDn*=I@J~ku&63Pycrgbt+C*_1#o_9b=PxKdxT2`m@rVItK1Uw(J!&ZHsr7I_s&& zsoH1Nv#MU&M|D38Pxx6Cm31Tcr>U;L+OtaH$Ul$c$fH8Sm7QRn_O^{R?2|m1Po}!O zd3neA)OqKon=W?>%dv*k7T9v;sK!Q0_1%hmoIw2@hRQo_ch;xQ;L;WG9D7TD9%)YBe<3$*Km7djxc8;k zaPs0MtTrcy*(TiD#AWb@t;t-Iv0A`Bx4YP1Y?lY_!Cd!*0Ze-&*rl{SmC;l zKfwW(IKUn)d|Erk&*mybiXc52c2GJFUfCUWbRAFI_IpFW3|n#bHd8@&pTMo8N0$243Uz`AgfH_z4tVH{P^ub+*&PRQI?A^0b7u6N59;Lp=f7 z7oXzvfkT(YBvQ%#T|o-><;aXGde8xlUibS*)W1K*_^& ziWen$I>jNfYl8>AHm>cSKnaw@)Ndv<84moAJuI4P#xT{zv3D#*-dgf7 zL}MWAt&=AfObdIehkpW_H3})O-qCtzK%yzN-<4D+GbxN42iCb9)wu{wTRrVM!Y#?I zI7ZXReQL>A`GL9~b}##^sP~>Hj`=p88BqKC71VbjVI-nggJ} z$P`=SN=G`s>JtFpc~OAkGG|)>~Y>hA!-{ z=zhixHR4lS?$0c8L#s2cR!M4|iUzJB5qe`!M6Zw!rzay6^_lbF!sK;YE zy$<>Hua~8560ve!>sG82`Hsa$(^SP!V^~J$;X5arwO6t=2;d?*+yd zoXhU&hHxvrBVK05V~;vt$kVtS%WYWI#h%r;hpFZl$1%4hpkL(kvNUGr84}h7Zw=n$ z9}!+%W5qvS2c28#)32(oWA=vIu-m4Me!NEP5qm1%7$bC{EFIH~g*}JXjsG91l80r9 z5loxYKs*Ou%?(6L(^JgSraTWZg=zaDUu?_lr<6CBKSjIvp>Dmx;$R=^6Q_#t*5Y5! z971bJcd|C-vm7TTWo%PI2OnrA;&Wy z4jvU*s(3H9r1Gp|C-W4B&Z-C@_f?t z8e^&XHEkZVhw;NvZ@VCer<*?9rG-H<7HH{xOjpO?b(&Z$i8+ z_IMvfYl@JDX->S}Blfv+t;Xtf92!fG$V|t3E5EjfW5dXME-r~w+3llHZnL&#SEbfz zqwZ(_Glv*aakQGfYeZi0XqT~FN!aprY@Nru-R*)DLtl3AonAv+Ywc)XBk`R&_H7bJ zn{j;km1|SCm4o-{#HZ@Px!raA#kAvnFr6-PA70(N{@~-Sd@O6N`)0ew$Az`nuGXDn ztk0S>0&%LM|9Ldm>wCKO$y3r`E{K9^fFf1lT(!VG_f&|ZO-06C2ND7Qq==kUS8qWcizXrsd>$G z`r<`A`pajwp!D{)-@)GH)wawIJ+A%aJbH9^@!^MN*ZI`NOZfUPe~C3Z-1g?Xz{)=v zeCqrqTyy?YT>Hs+oH>61mrtD>JsIJa_uj|dufK_tmoDJ|dpN*y!%H^`=XT4RgEQb$ zmt^E{)u$BLsQW^+^~vBguz7Cp0QrD-CuV$nX_*%;ocOa`HqqmsSM?LI4N|Kk_IkLC z{>kRS>BV-l+V)$S;+8%p(_6sxGH$GhZ~U`7Dsi`MrJ+ts4BOs^cK6Re5AC*s1_C-- zwEq6L9$$QiVM~PHec;I@SMQ%;+lK5+;aK1KPuqKqnp;`G%S=~@<~W?Fs?VCukn zD&UTqQwQsj4if<6U?T#b7S|s2Bud3QgKY=F@tHlbU$(?-V{5PhmP0>#r@CYR6aWI= za~e=ik!rT~b1x}8RmEHNgL&$!D0$K|+g-KM%sY-CEmKEp9GliQQ4bvW#Skw7VZFBe z4h9zCiS`Wx@Ub>+J&6{bZHrEGwij{ZnBy^9#Tu=$&7%3%g*CVxy%$VdvtR3qUs0>n zHY?PsbJQhNdKuxB|9@)SbR+GU{Y;e9Yy_lUI-YZ`IX0EsJxi=QH)h}R9k*-wIgjI( z9dDQ1g}#aRv`31 z$G?Mvz1`sYnNKcY@6tZ_D?KZDDL2Nvw$SYM)UXYoP;c1D#^2&#ja%M1i^qTRB!2eY zZ|{WZuRC`h*Pr`%E5p5)U&BpjKSYNfmrtKO)R(Tl`SYi6-N)y*FXeXVal`xP@c56O z9G2Gi7WnJOzl*-{ro~Mkeu%F=_X4`r8aI4!Zi|!c#o5)SEgg^PiRJ3+V~hr5JMYne zMligM(s>zPc6?$lo;#i$p83*#j}D7fkLy1A1gp)oPlcTf2RS~rvKAYTJ?y3FSgYvA z*!Q$wY93Oox2?Dkxge<+r^Suh9wYbRImg0TMz4j{$YL$ic`p@E3}4kmV{G2M&XKpB z4CwukBdZu?>HJoV?V?OMDzK-K7l72JE_=k$EU9mB_4|<4niCr+?;7J)amVL@Dm+v_ z<3*3WjLUfJg7$&ZC#(r0ug5n5K-Hgv;{c8R6o@g)jXk^MgVIW5c%H!SR8js|Os!>)p-N3%BS1xZxoqvR*miaLsJGQ~m1?Z*vcBf=U-_L}+g$dp z6z#riraf=>Wwm`JVqms;gP$Lsb?LrIvp|OhPF}i<>puBpQvNfiufdJK@h}eFc?@Si z`tY#LFiBd|R+?z_*pE%q!Kpj2I(f^Xgekn~+h^?d!kw{0prgUyCh$hEg^*!sY`U^fWUyN09e891iwF$qT z#TL;^cCx-P?jCDpE6jEkK$6W#`zL;9lsRf#8sp9Ek)wxVw7@YE%M;~{dQgwOx_*{d zOUO|h%j~r=c(nZ>@aqCOUln=fxPfhpmIUH57H@FOcG$X(>0iDx6_a+Q z{zQC}$Gev4X>vSm=~^fuml5yvjXuj3$7-ZHprbdBdA3P4MZX*+(!3RhnTHMXn5`rk z%U9zR&E>NP<0Ty))6CKAiu06ix7tx-yz$a@v6pIzHCH{WQAIHvIrhcxp)@}ZhCOa; z#y3mc2dUUIN1xuob{x1atSL5CPooi(w}RVK*AHJ-1^>oICK6}-1+8PgBj?6gXJEcf8^oGx9+>X$HUJ( zkHu<@yIy~5vte6LzVd&Itr-M3_!#b)DYRurJIT3+8L{Oy=eGQV9*;it47#qzOAkJ{ zJ$di;cizP<@4vrIcjD4M?s@eMSpc(*!DgUOUATn%UU~&5_V>Z6@bZHX;Nt1ixa-Zg zaN|cGk^I1k%g%STS%8llOix|7gu5@ifz=6LsP_7MdtCp~$GGL)_tB%n0rupC@>OV0 z55igi+taX#ufPijxRytQs&3N<9eh#8-jDW$3GX%TBM0X#qp+e07ITTdXlW2n9Y80X z86?@JZA~3dbRL#p?2PN7{w>F%?TysGd`ez)^>&~0I4D?Py_H7aj#_LdZ~d%s%w8}{L!pV}}LhDF)iqybY-dsN50 zi$kf(KB_y)&{ZK&e9nPWm;S1hc2A+Tk6A#2)9D(uEMo(F~ za3F@~(a!31PUH2|Jki$1a;sLzEmEi9sg5BnkI#DHIzj;s{$u+^I95Z0E~UvmtdkVA z6=}hSJdsiJZ`&Z2SIc)F$L*Y3$2qs`M)tit2BUt?87tB5M~|Q~joXv1Xv=6<`F;dt zJVq>v$T`^-%(HK5?Q@M|ubNB>*PLWcuj4HBo~q!+uSzRcJPdEehhr;7`{mbOtzV) zJ9_N!C4Ii=_IKXJL(jj6o6mmWI^OkId}sbS>yP~MS?patz?qLP(2LEE8yWksm5O%9 zBKg&30|&NgLBEGIi`5EuzVS8=mP?@P@Zwh=#D#0GE#=!gIKU%MJ&PW|-o^dx=IS2) z5^{(2fMt8Po-aQ95H6fKllWcp>8E(;xfftK{?0ew#`5w3R@mDvXP@|VAGdw_E|ypU ziw@sh{$kU*NKQr z5}NI||Mw;M4n6FfG@W}m)BpefJ4-pdJ2;;zl_KPPrgB&%a;?gyj+obP+uX>KJC*Mv(1ZC= z`mI83z!N=xF)EXA!(MzS65J)ouD8;_CBJC(qS$v(o<5nLj9}{$rLj*hJ^ENe!;7e0 zKo5q9J`wj61&EG2Z8S8VnckX_6%^nTEkCVu5PFG*Nb`KvHS|$JFven+0RH*u_n7ph zfTF{B*A+MM8~6@!%USaY(`r1}9y>YV)u>5T_xWm4yGB&F)$80GOwZr8MN3>dZ6Vjp z?6UR*uG|5|UN3!yvnn@n3Q~*ilP>Zp`Rt-EeXvFw&h)+kR^^CaQepRkYS=Bn z_QOl0*Ie~E4aviwsI5zlTIK>9$?d-cSuv@)GC^wY5=YFb!g-MD#r-+b9BuSV1#Gd4 zca**UN|rk7+@99IZ!H3mg{@uYh`k$sPbO!4LTNRTbGbsF=^wOPw2FoHG-7HxLuEg? zGZ^dTPddfJW|P1#;=`zhQ4ta~GEHW#yFG^9F{E2j5S@HAn+=V-`s9AISh`VJiEVVg z2R|*P`~mXf{^3XpOv>$-{4S_E%tsR<2dC7yj$Nh}OTy_ns4=Ic8zW}8+Q#GoUbzOi<+Tto>Hepi>tP|& zmbsG!QA$o+j*+dVLh;A-LG|p_W?>1EYl;6@8MyAQR!<*mH5NK-+`9eurse36iD$9g zhc9{0LU~n1Mj%$9AcmDME0Q{_gtjj)1+Zki8e@|4$ z!t^=ima<-gZfHjPHc(JD!3A3(Z0al9bMGpl1b3l@Fg(`v0ry2n=u9f?P7od*EU^HD=M?_+$d5y91?;u|L_kuY? zR#zw__+YDMD%?vIf!IBTUKkm=!^qmfWgy>iIZRRy`9Szzo>2$pSF)ed-$kN= zE{#L(->f@+&c>8C_}*owJ(&2;S*mj7^y?pPUwWU7J%||=>K73mjezsDVsUj7BBFYOxvtc zEZ2Vhf#{CT&N{J!{LhIr-H<9)f6npS9F1dQgmGdSZ);4_y_IqG=dFKdyPY}3q|Yts zf@69dmebmk!}IN4T>m;G*;WSR3wij}h2&HLz1Eg(Q9@B>E5p}DV81DHt*+}uq;>6z zCXdtpYboI4*Cf-(l-=@8m3A%I-*!Hw@x?g)#kA8ozSpuI zmW`ghmMvNEk|&;Tc!56`IJ@ru=iZ{ur7-h|pGvcOLN(d#ocz`Yy~>>UG-ztcF;Nm_@e_7x!IhyO{xq0HBCG!tiIv z>Rvm$>G)%@oazvDGZ9KO9QeAz%BjRBEtbufq_&%m{$DP z66J+YpOPaOHn5d6!?OnR7V*9khD$qH0ArFM3p_hhMO@@LAr`qg?1f7k>r}^Mca(VL z#{WGgIEfv8V|Xkt?8lWq`Fk+DpQH4UIw)5DPfa@%UU!d>XmX+;XvZoE9(oimZMl51 zbbEVsK$lxInl$d-6s3@zNsxBYX*uqyC@-qs@y@TcT$IfL$*kh7mcPVxk;3-nmV@cA zwe+3F%?rsasG3dvo~Oyjgq}IBi?J~HQmoq* z&T|YDDsA%f&cOzi@3+Yqy7e;2AnHU4s9o7}B`7%1XyO@SZ@QgRr*a}x5Epboi1wg* z8L`rZao=6MYyVne8{xzXGLls$F|4T{gu@VSDPK5lq7C$;-$g+63Gnvg*wQES#KFU( zk@$O+(~sXW&e@r1+>+gU&BgFbh_=^_;O1EP}+=@c-@<}&u#PV0Gi!IMu-ZTRg#)dT-@j&N=Kd*Ir>6A$k zA!@y|zNx=?y@I<<2gJmTg6ig7wbr|WHGNIHKYR}J|1H<&0RZRmU-5dfoqwjDn%ZqP zo5y|?+Qu7?ae4jBo_?1e%2Q(1Ae}wtN>oe0;oE?j8H~u3@D_JIr>nn-$M!oXyHX_u~V2fTYCP~i5P4C)02#+tU+gjZXR^Lj|{{3k!XPGziH3)`>Cm4QU7uo7YX7 zID#*xeQi`_3{rX|S^Bl>4LIp3@@}o2&u;K#KwW?^P_^Emtsmku<=Dt>N?mdjk?iW1 zyfh0eki$IRu`(7~iM3f%H>z?0j{Vr^td7eXlW(7xJ#^N{V(5U|>a-+Z39*a@ftN*O zE{jxpgTWqkam6@Hd9&6_q2iE)#>DD_%)t23&f1t)1{+( z&juk?YI+ZwyuNU6cOQ8tMKE6(;kG#9@*+k9bwbpR-) zTbm~}M_|I}{ry#a+I#1dSyGgp>5|ItX<}G)qv}rhLeuwmuLifb#KL0PK*8)gO?zX$ z|G@oIFKQ#VJl|DTkE;ht`jU2PHqh1mTiU8k>x=Z7t?^27Lh%S?DW^5Ouknn|$yClP zsWSJ9&9K1rB)ClP#Zuj|cM>nM4g4O!v!D7Y%${iD#YC2{vcvT4!?TQE%so>1uqQNX zSu9;uF}3)Y+QjEL`n2kOnBy4dPuZt+wJJ|6t$+6xJ8e+-g4Ms82cXj#f5cp^-SRPS z^=@9w6xXZdRBTnszVn*Vaq%)vv2kR`w6&6F-3*)@?mWxR@8@+0?;okJSI_yzAV=LS zYgXnd=F-F^Y*+vF%k1YrybYd%=*@Wcf z+W4}L?VPcd`@V4)eML|+PDPnF__y85fO?U*&AN+W3Plbxd%DMB=9ke64UJmdtx`s< z)Z3@Z(ruqROa6`Htw^ZvkM5;T?c^!z@mtacX-oltr78YL&=}cNCsT5jAo$nNy&ak) zi8Ma9Fe>TVY{fgMNHNhUb<+bS^Ft@2@8yQ#$A%l`wA}yrdz*mb3c_KTxdDQ6Aw2$gChkXZHkmZxY=Z|G z$Gy=`)4Je^w<->n*2c{Pt^WGuS^8^D?^^Glb|0NpjRqf{wVX$gO5EXJcoJrd9fh|| zb==}aHbZKq>C09Vl;q3hXm}~Ej>D%C(Q10l?h*Fz8?GPYw`N#5VImsFyz17*)jjB} z+_*5Ka^feJnvxdu!j8}FcwE#IBVD}VZoyeMr37hzqO@Gj>(WOR>n;oaLR8zB+n#Ou z=^6N^h%p@P1@k&jty6W$DWopEs=#)hns_9_YiF~o#8~pn{fGuP?}yRS#3_$`f+rvZ zU+*Gp2jfS`RnTSHT7KT+wFswpx6{`GpiEWRR%veRfn?_njn&Z_G!*NxKf#ZBo%y@Q znl+ML_d&X9%F9vEdEw3=C;k#__PmXAZ_V(nRY70_v>RR5=?n?$$Oo0)MsA9KpfAeb$%=Za& zt-@cH8aWOc=dPKIsng;GR1+{S6?b+cM}Nk`;5v7pmzMPfHgE2|Eae1u8x*D63GL!LBN?hiV*NS>QE8!2iNRcAS#V=K-$DS2z}TrXYI z{#^Cz3BkE1p7-$TZ`f?q<~AG$4%1wss`!Gr3VAqP#q{IT5609f)B&f%J6=fhV%2IX zGG%s+C1|y)rOz>zEc&MyBqlz1-DLcVjx2)D{Zeym$!z;@o$|z>>J9L@BZsi4t|H_Y zr=~?enUb=>%m%B3u~d~j?!HR8VAYzC=d)S&mz(#}4vO7wY9w16GUny_2eD+?6f5)k zKK$6^ij}H*@?UtRgNKn+d^KZPRu7pJ#y<+tHiq}um782-vJ|r7qAUA_p}SH@#Mb*p zZ@OySg2&Hg&vgnkUxyhJ7U_3HKDrXWZxwdtncEo3FaTAUCDUgi ztP*1RrIQweJ7xiomrA0+hqwN>4)2;{b|#0XM2-(nz>_Tm5{R^veEeIz$-WYA zi4x~+jV;LCm`>&H4UO(JMNo<{cV)Aqfub!!ec)U!!yJmN zFx7g6J8H$BKc-)ax0F3-v2LDHnOSAOdxMc7RM!Q z#8+ibUci%?E8)bg?U_gJB#Q6gUiYt{-j!M4w}N7qP;HU>CMP#}v9`_Unw31}-o|VU zzkSMllYSnjsrPCmpZDQub|GK{{z2(E{tf# zn9gk*H>i=q$gA06^u=BFbRLVeueGOE-A4V`-vX<_4i16!D0f=g-ru}2D@3|(SWa4m z`L1Q2Kl)NG{?gLf3hbP}IIecbMHAEhu(&bzU++{;q=H?yT($^jI^tPs&kgJis#`t?fa=eFs{*O(6<_PF#*!DZaAISP_>-K=RQE>YvUUz z2%zG6AHIdWoJD--l2rt6lyYy0ETzKAKph4WL5n}qLPj1v1+H5RyTva0AUixW^ZnV$ z+tF(-v7L)4=2c-=3)_vzrF}eQVA-}d*_$;(#If?%w~a((0Wcpo`NXCNZjAwQ4s99q z9x0Yg3C^~A#l-VfE6nwc2F_vIAo|IW?;AI>DP%1QojX3Al5Xot+x+zB{#>?SP;cso zJRfALf9wn?Mcfwmm_#)I6pm$xBngZ6@Y5>om5|-M;Xz#ix{GtE8jIF58FKgkc_p0> zbLb=8tejR%N~2$v%RC?^3x&G2t;oTHCM4q{`5UV<1#|WPj|Et|UJY?pA$XJhuN}ND zE6|bdWZL1bR|hz(Xr}x}zDw^_bq=1X81*8q$+0fct!aoT@`Uo-PD4^pX(!ToI1@;W z^Tbt+>V3ckK#mtp=U0$UFz;?*^NG+SyM%?j+x8*FFhWr! zhWfjRjyQ}UpA3#Fq?x(p`TO${*dyT2*i?;8qt|p}!@#jUZ{oocA3$nc%9Pg?v{YPE zA@5&hHFCE^H#SjeR7K*jzohBv451pZy&$=A-OE%o1QiggUjzeLZSi!C46dlJ z@Q;;EBkwe8k>qkJ+8fa7-ARa8-z^`&)<4GirjLQarG2%Nzlp^vCw3a*(Xq{OCT(|s zr6sOX4PU*0K4y@e_#Ov+uKLyDC6aZMDh_h6qiM6Fpu^Ibb4fJBq0y+WCUZdOvJTck z`izc&v{2b>_wl^buEJuZ%?&Ypn}Jgkc4i_)0o98&QnaxILPuVb0+`CL#(9Ll@u#M> zSH+F4<50U6FyVW&8vVzkW8oAILM`t&)pDV(sp>=HYganEVW~>c%!rs|@sMf^$(o6J zN<$X~)MT*|Ndc>}NVTeLMVLMbElc&&3E&EQ7rM>65Rh4!2_PLJ_E^mu^}E!tGv3_V z{vQqZzG@qe)o&-5obdMFO`~~`gxskwDu0dX3Pe_dj+le5o@M5$RhVehkJ=0vK*Qf| zqnh*Aoej91M<~o2l#|J>;HpqujjsJ1@GqmQH*`_dKk|)f*nP4Lcuxv-OIW&y&9A=A#W0a&Ooi!ts}@E!~Wg6e6B( z{W+&>?D?bpJ0s5%uPv{&qv(^G#ByXJ)XHVi4mW`RvEB<~v3(&8Mk*C8+9yr&G|zR+UIlq{;mpZ>W$>#V|7jL+VKBmzJ8UKUP-Pc%IC~WGW1sM(pu{{xUZN*u z#`~Z)9#IUU+UXpeEz{VMBU=AE5i}G34&F@I3EgcYM%45mDn>RR=y+n=y|*d%y#UrO zy@suHSc7|mu%FPm<5Lf~maB%Xe*2%+Q;K0s$Uk_Ys<-uJrzI6j>A;n}p$R4I(6ukk zOAuZKgZb_R+WAz8J{9k;xp4-iBCKoF3tfK!4W=4_3!lWESz-yoEYD}Tro>ZAQ~qPP z@SOQu!4`I8vQ7Ub;9Q+oNnoQ$A7JzQd<65&xZ1K@L-&Z?8lw83i{g1N(>WG3hCtw7 z9+Dl81J$~~By$_v&!x9*wvSt&Xo1Gt;gPma!YumrwkvBx;;I`{uYx%IKA3lsXk7EsV|Cp=Fs`*{D^ z*mW`LNfMvF`^FoNuJl*6zJsZ%_+06jHtKs=93Hz*d1@6hEHB9pH8V`+%ieA0OumV$ z-paRYgItm#UJv|c+hlDLcc2z6jPY`lYE*fRsnE7t78TJyO|i7?eVI$*oqO3tRYZo^ z56rjvez{8**(jxBGK`9^QiOPTiT(20#ksR(-e{DRhqRy2T!!$djE%a!pEi6iQS{?0 z3LMyGR^8kM$}eIrJ(AF7{znR4yi^2%myDD*|I0_TZ1fBQMGkoI#*P{z~ zC=wSx@qv{dkRO$!_6pOvtXPnt*r^N$CU=0$maa>+!#9Y8VW4kzI>?64>uTGzT zhoxn9`;c^;TD{ptiQ{pjvKhf>7zs$I{z|`3u{|6P*!~JnpIkP3wUTFPmnT0V=fWzw z5i!>s(7Nqexz|eg&9P%ePB-W-^AUPg)flJchQ%8StxHc8LRg2#IbrdCgY_&bw*+1F zHT%AZ5tbo_*etbpqA6A-C5Jd^E@@LM5$H~O=0#vBVrzD*F}`^_+Pf!o_S*YacS2cy zCr(J1WIotAzS2Jkt76k!U(LC>nLs4`QD%WSZSD82l5~#F)NKj>DdXtL0N1Ej?U2K^ z-K)a`#3Ww1UTJwfLJkQB*g;@SR;cdpeAkC%VZv;_2U`Q`j0+!GY^v?(c0-o7k)m|8F#d@Ndhtbeo$cS1PV2ot;5tn=hEu>Etm}TmP|@36X!?6PkTJh)uMb)l9XTIMfzp8hT5x7q2r1`C6$4Y`WLEISlRMT($N z3JZVLl>hQG0Pvd2B(dfYH8w8)FGdzGZY&tL)^oCee%X*WD-xO2ov^Y%UQ-sW8Moo( zG|A1B7TByirv?rHI}{9vh#9fn6aJ_Fx&0*y*(I#k-qM4SdecK3R5Hn7j||uR^~x45 zyW|li*}s1u(os~GH7T4qmvs`(u@TUqKR(A25PdV&t%7@Sc3Cs)eg1jqy1_nbEW9-c z_suQ)o_@;Hj=D@h^5F!KsbBPbVdI%(bAXt?>jDgf!tcm2=hE*lD zdh~|gs=ks^(%b{p7x5O$Xq2bLiY9^ULWNGQpKGRsQ^oz~!P|UgMg4rESc39lBj50n zj0c!?;Yl_$WlP)8VF6>db?=lQmRqw{t)QA2u+84jRm&6KRIn~*J_K%Is}D`?oF9t1 zGGCW>dh~klunB;By{FOyG_W@4zRwbK3UL+FQWySrX8#QRWQJ`irz%e1r@fdrZ$@H- zYh)op_ve&s*dM<8ilQ*Ve|0ZSEJqA8Qq(3G3j$!a@wNroUi8mM(GrGg<%%r&#pI(- zkVf>6&c}r}9F)7DhHd>aCAS9qMaVMvhY`>vCGKSDPL--jGl(fRp%W!ndE~`;(y8l} z27wpLSH#qWWd}Qp%~qa@Xc}tv`61C%oRSt74}%j^HMTKb@B`Ck)vm2xkn_5HVu|~< zuVa7Yx}{=VBsN}A@LvioHYP0Xmm;|#L0`0gkSo~9z9W>h`8lPrHoLZ$2lZ*o7xfxe zC0mnUi?(e-v9ymBNUNXr80jvg$MO&nd>JjjWL*{L>KAw3R*|R6qWo!W)IDIRHijcU zAQO}ih)(k1&Cl~>rp0FoBf48f)!4}XR8h5faFis{!LYPcIc&daT83C#x?{@K1V-CT zIZRlO!D<1|me7-IW&1G)KMJBkh6Htl znku#mnQd&|Ee7-ch@4w18xi~_vX zmu-!0PIerQ1F#VQWg43DOOBeK#jEq5miFZ>BTd_WDTT>0Ujzu!OlS!>zw6aw{fnwKqRC|BR?*I1*#gko;gM92t5s`q zzwHUlx`3IwI1E)g?pTW>0s}i<|8x}`^=83oR8WTyPa>6PEPM~sXvvdL%C7)O3-M6D z313?39n8K9`NucXwezTzAM|^*2O_#>u^6rUgbQkxbGEpZ%_4nC?aX8_ zL39k9q~o%%+f?Ab;3ZoGDW0}z%HEm?AZWwd%kWw_cQI7n^_V%QX={y15*^X`15ckk z&T~IFPuClYmt*k^(k6#%qPN~`Np~vVBP&{V1S3-xYrcz20x~i-q#S?zyvNG(cRNK- zM?mBHf3R$-okH`~#)doXx>S1VVU>61sFGaRKe@|)Kk&O1nVXUP`rgX2_W_nP9RxZm@Z8gg z|Hc}FDHsApXrJ7TCjzSIvEc*1lt@#*8z+D7%``sn8!A66c^JetLgvWXcLlXfHe0)~ z$;kd&bGps8$I*Sl&B(O+Ag(95f9gS~&ZtM6=9BN{AK=^5qc#VYq2t{>32aS6u7e-n za*n*rJM$ODcgpf7W31_O_g3`xg4AEgY7TdC#cO?q<*$1+*M123YD~3W^sBpW`taqF zEcqGtSBHmKfx}tirIG*q{v}JeEPi{ZBE?-q8j{fLU>IFL3?BZg+lBsqVcKrW;^M!W zGQ8_8t(Td94F7Rb_A|-3d4uai4E<$6P0MSeu`N&)ve4I(I-)kA=Qb{mNiOZXR*FKZY@-3QG z^vlbVv`iuKe<*zEg^LQ!VxXVXl~SsJQdql`d7`vko~u^(P+6Fd>|z*j&N>56GtG_& zYN*wL1e?I@1AylSr7Hd{0u?ZIIOB64$3b2n@L!@F$X5DGJuWTU$9~bS?0OMJs6pZ3 zZ-Q7gFh8%H7o5ndYy#2kG8D~9P|oCK?Pl(UypS68P43Vm?(&-VE%FB11@(i2>=6pu zF_z5XZ(XYFK_R4jztRu6^4x21eIr1*DkH+I$-?3&MS0Y+S#e1%GFW@Lq-T_=IQ=e< z`YK6&>{4~cah{c1(B8Ei<8*+=Xe9BIfAXxS$PTGceEkn5F34C`>PFpCREYh&L@w>c z%qNlEVbO!tmz(m@mxj&-Wp!wLS$Lqt0vb3zfPssvB}4p+l_y6j#V(s zS58*BXEmXM?~IMF#iN?}m^VO}D;r(13M}i@T8R_~yC(9!%A3mSL~I^O+^J`tHioF% zN}4_$8rQ53jQ##47Gj}!_zh2xvyC=Il241aGS#S@vpJ0ae8BfaqqanvQLJZ!J%$P- z=o}>lL?~9#%U_u+lAk_p|E_8*7Lg|nw)4*Wf z6&J^DfRrwZn#_**m;@p_x~5517nc1TOw20TrJG~_+dK6&gTL+%MdH zPO4;vA*wPTD-%PMDWN7%4`RN3pVH`=xrWNUX_!U4n5943;d4< ztYy;Wir;IB%u^Oai?Xnqo{90YVP5ZCKw2JCDVmSYy78-ZTb4PlozvGxbYG@W`m=kQ?r zok>8~lv_SYp;KEdAE;R(_wO+@dNEac@ezJ3y_(0cxBbTO25zF;{fN3#Uf;hKK&0ep z9q5!9LPrI=+W8f_DC{epxg`E~=0BFCJ+sZ$;!!VC;JtM!@ zX-y?F{fCz9;7(>>SgLBG^Ej}+u&YbCX9ZvK#;{TpxV^ROESgu|;Pb3f;|L);P%#jk zoyU*e3+}rCK7`s89t4#fny5et*jxDdeo(23l-a@S!dp0#l#J$*o)NjBLMYp~FDRG( z&gL&J{}p5_kVk1=0UHmmX06+ZtwZWi%X+r5e7l>;LLPHHG>^k3K>37*+Krw5KOxM` z^XXrwhyEng&~ZN>viRJoDKy#XO)VAbyZRM@p1vQiN#0gv9~1Xx*@f-Bq?1!7+4dZA zlLP4E1U?6Qt+9v$XT#R5!;>`96&nM5lPzc0z5Hd0=ug(Vxe3K6|MmHwM zWo%Hl@1ypJyMdJtHDtWE@9KOqvFdQ`V=7DvpSPA8yL~wO`nQM3a`?K;OIrOX{uc2+ z&X2W9Jl%Q884}?%G_$0|n=QN$Pvn-;Si!b)>E1u)G zlNUvfOyeI33!Qtuygw6MP}r^1B$iF z;{#^5qtkOka<{F?(x<15$HKd2%!r&CLUctLTA~C0hDmyvh|ALJAc%;SjlCF&EOF`1 zX-B)b$EuQ>kE20rgWl&!>X(6!PWJ(ixMhzx5%~c5y~a!EtSoKimW58t{F|8|w6aT# zwH9;-sB|0Jti^VwqVbbB_tYQ%xH&Vsl=#!ZWkl${d)PW*L}!FB$wW7Q)PUDI7w&7W z$s34LMIGjpje<6$WLsTK`VY&F|F!1(vo6>9A8j+fU4#_6HE%+nEK95xc!aoG_n9HD zN+*%O`Jcju-Hj^brV=xAL?aTI6EC{D@ndQKS}yG8qe^crH*Q(HYE?e;RHg0+7x~>X zY0n|{_VNkUrjYHaO;XitU3OWoP%0fk&kByw)>=;G(Q)%PhKohy?En{zEs7y+w*Yt} z0YrY{Il%=fA{c~8EmuL8cO*N@W}=FmGU?#L^$`kNX;SRXJ%(y|IJ>6II2mUU+eVm~ zanW8Tt@0J70eT8y&_+?I-G>*XT_vHHpfmD#zN`MvEOww-bDmpgBchRnYniAaMN{au1iW^NI|M@dnsTXumHr_S)pGe`o?8TBvFG`nSwpS&g2W86l#p~*i z)Y0rBJ==n8N`A*^$kt!*#a(-*2V=yFTew`+|8uT5#=e@UT3kHs1??YOF*qodTlM~f zRfNzhpP5fc?+G~;`xTYNh6V3^q^+$S)rTR&b%MB#mc({;O^)CG+Z+6K)?X5FKL09n zp<##3)P47Z)An^f)kfszXz!~I<>eXRgK|Ey=POj>+uoM)d^7ifXw5|THc7SKIHEiW zaIpWPwq}z@{r+KWKHv%dpbS4Q2c+2MDZy>NemYq}8@^-ORiyaVru)Lgw}U+ac79!vRx}K^^T_a=jg-uIt7zX!MwP3S9>!wFq3U6AlV)1 zhunvRWVIIdRAvP&)2m^I2>}0l%^z)+{BY;dk4r?u%w4$*>kX9aSJC;eMAV-hrWzkx zGnq61Xsd=gBIlHzT4_|jX*GNlNma==9F?i+dQ;frThXpCT^oB)+~jJ5bSuKIJF8Rp zAx{QV`nYwe2VyjYBB90@#6F6Q@wD(%9Owu)To_z|vor!-Sft-0$ifXj;1ur~W$z!$iUp064W2{AY1;&;q0~p`PrHp&HFj&FwcwNS4(AO>X_O(`&BrbQH zM2s#^E_4fconNz6kGsxOcJ6KH$)#*t>P)0N^|u!H=^*_toat2ey`iTYa=S~i_HyIi zoD)r}mwH2Yr)CNmOhpw)I=#p*uMG4OvCwFfiP2+btBl#fjG|PIi^e!{egvzV;KHGG@MDbDb8 zwn;59fqOhpArI(M`Mn__wMsR^W5&_U*ILmpfGVr%VGQ~Rn`FsTesb!{!}Xaz6^k=+ z(#=L{LqdHize4o^+%IUSCd-2_**pKtKbcOBbVT_iR!5qs8BCzagp70XOP!6eGJgbS z!Gi8d#U{JGf=#A*TgD#kCCO1+m~=`M)>+6jUw|znxggw_onWE8(Ep32nf{7mW=)W)s(|EG4Pg& z=t*Bn6>LCQ)+lIQb3r~E`E_T*z-w{J<=UNss!7qjP3ys^1N8cCzGFR2GtwnujdG6Z zqr_!fE=jGgu_4p1Amn#e-n%8a|Hr@yJ@+wG$$Nw=ce^|O-uEV;`r+GTh>_ZUy7;c3 zLL2VG>c>P;vRs$*-6iMO?w~<-s&&?zGXC%t1pQ5$5V@pK?P5Kcf3#Vkvc<{E*I@Q^ zUg3{5L}ENhzL?zD1F%acKPHbcEz89=JP)ZgHBzXB)Q(#<6VTqNWm_`@ho*6Xgncxt z9O34+UbTm(JBv<2#h|lH@X>15mC=Yd0-s%gSM#X==V4EBjqZw{b6sj-amK(@$goUm z4No4h58rv(nxME%?Y|rnPxw$^$7>ET`Pmq?jlql6SG!-#sB*#+E1W=%UILvGy{+xR zYc|e2gmte`fx_+ed-!>E-5jNYX_&G;OR1Zczr07Pl15rdG1?EB+Pv@tB|b7eT{g zEWLw@my>6$4TGyVpeMCAn*VEpb4!D8Nfa(Y2MbsR!h)N#hg+XlgPIYd%`V2p zO|xBPyML|!7vy7Cw&N-7rcYh0l=$O!zJqiFUruUTziONr#P=XR6!GcohU^^?;&xnr z;KrhUthA9yrPApK;zhVo0jnY)STRZZVQi^WX&M!ha+lDupTgwc?xGd4!4I*TTP(Q? zFPJqG_rUiwa5(@N&raFQA7@~2lKHR>vu<(r0^n5|#M|+um?0YBj>A%>9sVuIc9kb4 zDP=u6l|&IdP{3H0nzg5GKcoM)Zt;H|`lYzZEEMfo*#vNyKF{AiK2MO$loK7jL+Xeu zg2WX0mq>jVOL!5yL|nt_l%QX$Embmpy(}N;M|%uHs2$GZ7AsvL z(8nJ&xTUt%$XQE5@p*{>s2c_nTV8lFO8bb)+UK+a;ZklRzD7NLZ(ZbhUBE4o>z6=Y zVX1TXwO#0o8_B*B@D|@DTPlRagL*QTSpR(e0CfpW$N(#C<f zMLuX-FU}mb7EE=2cMI;|M?wr)`7GQF84nr^-gI}Hw8xChm1C-moQwzotb*LN^* zdl<64zZ5cdzr4rFnQ{wj)=N(Qczx8q*!$lF>rU*m>)9d|a_n$deS%>B-U8$akR61pC~^8ZON30WLpwU?e^cJU|Hn?#=( zNPnhwy`bWYK4HJ zx7n?_5ZA7`U7p?^Mc}`}X+moIqjIi>Bv({1+gF~24=HvPUYMU$=A~+{d3p~j-|^v5 z*}zEp#-SYOIU&DY8}p|J7g2`450!D>0DKf=xli!&wV+LiCe7N6l^+dLlc8A>1!seV zr)HGlFQ?vQSrl~WvSf)yMNMJ>MuYsxsuzY)zW01x393rUi@z)1Y-klgM=KzS=^-!s zctU_^llm#?+c-+?xMarAbpAn~`ney~QG2Nbpzsyx#%?B4oy;D@3tsLFZIhz49%zM7 zbQ1%j<)b?_uiEGpvIel)HxaP0_zpbl;P9QgJCE$D2M!$iJD;Hn`-3s6QYqi{72s%24 z+D&l5JZF#05zde6-;zDNN^9EFvaey4SQ&rU{hKHgBI?>0@Xo^YzTI7-dwogsVrqHl z>%)qJPJ>w%A&kafbC4O;Zzo%e-zygxB(A}?NBidx6Z14rVXC~x%@LkvD0DJz6|?qq z*&NT4TriMLxh9W;EsquX z0REjZB1BNeHBIfpn;NMoA=W7o9f6fdN#2o<_%UVVX+uz4d$-Glm{;{9$q3sy>(^2% z{%Qpm>)WO4{TUaagngg%*v4anBJ^MIt|Rf~_6foYAwGdtvyAI3E(eA>l9v$^howAr z)zj2WiKk-~09f>X!Tc_(eonBaeS@|YG+H3c%VTt`ONNo-RaxA7 zDjjwrEAvPGK6vD?fU+A#`G{z}BE32xQaweR4CSB~@jcb}m*%b=JsbEDDia({?+tlx zp6xgm+~2V%x6~)xL?UeSUB~NLeWet|0V_N<7$$A9A|f?&QS#}TVl9` zeGJTgFxE3}yi`4s4CFo*CJI7&@V`CDdMjEp!Xb}karVLTsLrFy&`X!K2|xzk0F#Im)we-dY~Qw+=_T&ly>raO5vW1unpTaY+s8x z^EIEUef5Jtk?7gbLElaKVpD|O8fpWu)*x-3EPI3kY`kZ-4knhMi%!`ASB0*Bd@tMN z-W=E_H{|ZMUUXVOwVKHq(bQ}&UoivD_E4Rf(<5`zj*Qen1hWVA5G>a5;atz<8DJVuSm?`EFw&Zvsa5iGU% zcF*vacF$1}AvOa|)rk}4vxa3e>2Cr~*3TXcpG(DK%rn*7f(~uG4?io0Tb+F_vOidI zv8LG<_Qsv{$6YB%!%BE$dGx8_=%Of710-^x6DRyiY=o zi%DVjI}?hBv0d`UbDFSBj?|ByjJJihYosaFgVC!m#^JtlfPJMF-KF39Ma@l(oxC#dYq9EQQJt7TpjS?NwFD= zg=$RasoJIBB+)a+*>%_ti{GT;4yu4 zcN!t(?u>CNEqDWk2$=%>HfMfY_rkv`>#eLr#{jJqiDd)B{I=Ovj&-7~a$$y{__lNj z@`TLhsU3$~Fu8cvDNV5R*^%O+DV@k+qGZVWCPcsR~@ zHqK4eLO0G|`ebl(^or+Z1zeLvI@%n`5@uEf$2E_fx7J($bX&*bCJvY7f{%uvFpxJw z$E|^%4H^?0R~>AU=Nfj|u1R)dB%xcOPzWW%B?Cq!$L& z{Abc!)|T?(6`A&aa~$y6DFcdkE9Y(;p~>sxcjsbQi>WPS<+s|>q=%Fx$v*6i4CwOP z``~kLVr}}4+D45Xu9U#saB0H2%=63U+Pw)>S1AQT%Nq0jO;W!jDH$Aw{IBvE5AZNa ztuAERAC3fd1s_B;zESVZpCy6sVVqs-4dQtM0Kv;!NGn@qz^ly5pBm3S6`DDy6&zNO&aeV(4z`t>`uYx2wJu*{(@dE+*1z%e|hN zZ$QQ~q9g5QML(7qaGah|ZMx{1%OMcN?FSVac{J7u?I!32#6Oi*^yWWAPmJp8RAhCy za@*|`$CGDg__J4_i--WQm>3G_rHNhc!yW;bGQ}^2;p*=Jj5NLdE&Kp{tE)p4^*5;K?&5H1{bR|BDFu zd91=VPY>A%iQ_W-0<$*yiM`y~hYlQ7LGnPohW-QJiR-gN5mhZd<&2rnSjhpf^w=QC zxHMv6NaV@;$6g`U_3d0PCwfFZn=CmG=P=-^ z$`c{#XXDhe6gk)#(qxU&yk;NV?q=BBhyTaG4&fe?mEQ(0W7N|9_Lvw4oK?OGUiRg6 zo=8?6S#PTepZa;Og9qZ?<_>w8Mwn1%IW3RNJR_tHpTD5e`C&g6b_THaGe$zpJ zMGRYF+r;v#NvB*+tCXoUEsA-^#>|{@Dw)UIE>G*THE^%jh2L?+_tNq7eDPoMnP}g<%+WimU$G`J6bT^$o91qO%J$2q`F#RPRjfUwn$E9j< zTqpf*8`ot_%J&&hu+P;yo&(zwne^r5jFTBJtY_e4m&7eozr9*OH)`|$E6WgL4Q@}1 z9HMz4V|JlPWRhHo8fZTX_ti5_MQBUkq_UetJvZSG+C^L4IswuWpGs+#JVY*ibm zY_S~oX#TvmUhO#?NecZQ$P;4djSH@v*iJ>%3_`<2mP=d4*e-O#Ge5+qcR!4SYp$CijYInO|t=D;f)UBNP?ncMQt6k@Dj;%hZ>=g5E_3b!5o*Jj)_i9^O(L8Lh z3mrY~X~kLXGNS!w8(EDDwjdSX@n~?YJ!^RnqgQj&?j{L8pJyi`zd5=zS9iz!cJAZK z-__AzE`KVZS>NO0$ z-u_!`akZ~C+nV$OJ^JMWXYaTTKl#D;XVt5s=fCzaR*NMbe&%^}2kR|@w!>fCv+!Z5 z9>M0>bFKC8eQ5Ua-WJB&YVY#}d7i7XuYLH%b3;8kD%%g_iIE>i9uc=M`pdZPljrb$ zv9@w0DZVJ(PB;I=>;K?4e+&QO*8dBy?I4Hg-f#;07>$pt{lz6*TI}P4Q)ltv$q#Vn zg$DpEaAyBT?5$7XaQ1TOt-bXD?zs2{o<36i@Yzw<4X0%9Lf`*>hZ}FKpY3^P>0*}- zvUqaX7%1`I3f7$eng&=a+*D$qr8%Q{G;_x%iwm+A{vR9!y!)Vr@9Cq1>VwTbu z;kk9^md zHXqiK>Qu4za}6EylwH)isE@HWYCm&*RQBqAO_6^M8lzQ+R4-q|F_QCWIxlgz@lwg- z;k>u1hQ-WF?F#pCSG17j%e-U#SnA#SC8y*3(;RXeR^Gd|VKH@_K*}kjhpXgoQEMa~ z&W`LdVR%%Y!?PR#<>+A`w(9H=5w1DXu}?j76q&CzGSW{&uM6qjdsp1%XNRZ0@A34DFW}N2KaCeo+<_S#x{IKm4k2RJOC@m{?O!j|a_B_ggErY~_hIfbV&lY%9iOXg#me=02$~vG%UD zf9&1t<9ElyF6S;0cZG?sG#>UgY2lL!4t^^&_u`9_$TS~iTWTqpOeV9{ABihllWfT!5_f5~ z6eX?^%L@PjEI=HCb7p|S+&x!MPv3V}bsaBLKk~&3cMp#%GhZDu<7VCUGBd)%w)xO>+uhp#PHBP*>p#JeT9*V>0!>3waT_IqTk_Mxk_OjD3_IXD<-H$LmfVsq1N zN4@XOGk(waOxD@8?dt#CQ?y%;<71BwPpMP_ePtWM>ZA(v2~NB&Et-%F8voq#%_3OV~hTdkE4|F z>GJhU;L`*CbxU&O>3#EDjskyQr;)GSa@SOy{At{=F7Z;6^4d|eGJNwaSLxo@@@ z;oKZ)EW&kpSLAtp*R|w04hMjD_wUE^58ofDSDfBBeg~E&CUNg`KSni*Emy;%h>Sk1 zU=Q`Aac7G0tp==9*j;&bbf`CaChN=XBHgwuiEfwkt@b0(eR>w_n^rVAq?gDot&5j# zyWz54$&U2`&+Ym;zP|5IaeHDO6Xgbc<>3E|slhb3#AV-o;3nnR~PZ3yL+fP4eXqN_UZ@rlZSK^0le0Y&}vZ3S<4ilY&!eyw>Vk z`((Gv$+k%0{5HJYHZNdK%ht>llT)6rVS0g{WCtOoT|y{K)J$)8eA@ouP_tlHl-#A( zKkflHq~POgdGc#52(AB>Ag*p3yGfh2rEi-Tl~OZ@58WGunoQb~rKOv^ z0ich8w=RZ*eNVZ*XSQow9aD}RYvKTiMj|WdW`;ee>3b z0eCM^Z6NtIp{66>%ERS|^U9I8sw!N#av967UBL4{{4w^OJRIG$ow{DifCvT3AJEEC z{UUIUl_^e^@c*GMCZXuM!u>ak9Jen-`lcvf<~cah)B;$!=hr zj&>@Q)lFgSU5sQjJZbwb0)mfg`epoE|xDuZLA2BUqdiyHie7%^wzQb zs2wJe0L9GqZpFpfD!|`%Cu8_G?s4EP+(pcCnov%%F)KkktS{&B0 zwD^}_+xzz0E9DUX4o267!$+SF2Ib1Ny0&V~_H26cHo&)Q*L5*xYDw#e+DoxLvcY`?-ar_F;tHeFi8voF1vylLC`S@NmdcAPo=G8SeJ zVD8{aEYECJQhb29bBNDnX+zk#rOhUtpXBXd<84{#Hi>_I(rpcCn;Ly#w2{?HRtp(4 zK+C1SV?Lo$q}Q}9Z_{wA`j4ET*K)0m^%KW?^1dIx_|i}u;bKdw)9p21A2^1lW%BU| zR7?hUMEGsRkge)sR{vA2UEKSUpL`Zd>nC5?@|m2^n$0Wymby(-DbIYfz-I?@sZ)Fg zlBbX8{7ucP^-~PH>Ut)`BRnqB${Qc~F;!liIK1MH$JUX)A-`>>=@i{M4DslW183 zJ^xKHwYB*;_T{*^9NA>l<4^O^leO)?a)`AnRG}T5Idv&2Oo(H4?CXT~pKDFH`xEVI zY&ikuHEhjRu)&hYQ_Q;<~MA@x9)xtCtv*m zuAlf222<0)Hf%!D>i1JU8niE}rc&{DK7q#%9l$*&B45RdkU3P2N+x3$#$)sCy4~+1y173n zGjE5Ln6RgZVfeTHD4v-N=4}fX*7_H1uEzAhrb%Zfm(Nw{f@3ZXRfDu_dCg@szbVMI zAMKM4J{mT)YR84NR89&q3-ZJ&EWUZxwv5&i^i6UN7}KH8U6>L)(RSl1+Llp>=R7T6 zcC3=s!L|#HA!-kBXM?M%3l`qzkkGc6oc??n<$w8edynSj{CQrQzhZsE%M7U`U6J#e zns%0QYVFO(Iar&@awSI%?DB<`^Of>Q{`x(=HDUmOk7u`xP(NyYE$5Hlp;V~tO!>&X zy8QaHxC2a+IZjTzo9MibPNRAgB zAj@*yYu%CDJ$30MinVcSNt(@Md4wgl76}K@t~J7~L21?4V6!PxZrC>e45+q&>yVt5 zlMO^0DxG`wH0_d{oXuAm{#Lft9dczf`j6YL+Bz=frgKj60%U*b+PQM_+q9|9lF&NR z1xXvpN3qXR-CkV4&AB=3+P(w5UJsvq^rJZY>6dVAYuXH;oBu;(w)1y6hd-cv8lXQs zgTTx{yPd@nMKk8wZ|}M|7La(kCWF!C>Q4E&YYaVYyBSXIk&QC86sdddb{vjp`HQb^ zJJ6HMx$F`%Qf+7ccc~)2j1-K_wVR7KWIvdG*ZN8JDaT|5;i363Y+a>HR=>KKrx@jt zDB9Kk{GM%B-hQ%oxojHd=4%9Rb02Qv?V$10sZxAZaDL0a^VLh*y!=!!xyI3QX&y=L zMhMNO5Az7~<2-4d=-AfzYVGC9JE*{oeuq*1Cr>~uJO7XQ%3?uL!tjJ%!a`SJhxLDZEN{fFB@!R0x z0ze_bi9{%9L2AkuMZW8z-d8tmQ~?D7UvX8^}M~LO9rc zZtkS_XNcNk>}s_~(VR`7ul_dCGOeT*dT~CKE4%bJegVwY#XskrG+kOd>h0e781I7WbL` zEp19aKYw|yTwzQRk~3s;QM*jT7#c6v)}Y=2tNX2`DeJ&{$gGf)SeXC-AOJ~3K~#b~ zK9Og4`TNVKx9M&JorlXWPNCkiywWj~>krY^BAuU26Ps_Tq>Z1r94RDq64+IHJQ~9t z@pL?`A78t?(kQN5+ET6!6JEWgF12OY6xKe}_-OKIsEtd+({Y{Q^9`&twV4OL`yrn3 z`5nq1$EvosT?;R~_n?+e(-9R?w53n(F!t|~;yhE!4W)DI)4ncx`{(6tla8)f_Fhv; zse`^+6zpF`(pfBSEtUH4urr4a;M84rHkMY>`MrDa!u|K+Uv zxU>zweCjuF^!j~xcK4TY=;l2*cw;MaXWzu!4QxF325ugE2vre|$){6lPp(ax7>qV( z*F?JtFitb`(P!%XGU<6dC(Y6O3G93JKCP+UP*p)=ZOn) zrNJc~srm#mZC|%qIjSe;>b_gf>n>&Ca>{beGGg1;E(3mGE&D^>x3bcC;{!;A@|^N_ z=aTWckO-?*aBn;MHU5Gj}IJf7T9V9TJ3M;=dY9`XK_b5M>Ksv|YM-)%=wba zFJ*jby2w}8%6aB1&t4az73njp%OzPUd!pCZlWJ z*wQSIig59*=hU{7Wxz?>1vTRsU$=7T^3`j2;q_Da^ka`(x&Gi;Z2q?%#D>Yq7M#=9 zR!XUD(QPYe{L^f*R5?=ljhhC;56NlR$Pk_B{M92@vzvU{C!{5YvbH%5L2z>IQ>j7o zaB?-eDn|OJ=G$XAt5FJb8o0HmCEoC@hkE}~v`*)|mCrveT-)4AWP4EB`?_5vZ7UZG zR-}b&yV6z2U5Q+cDa*BKq{YO~1CuD5%We^J*!J+t(G%B|GbamHFDP>GajD&tNM7q( zX~$~T673sp{7b&np59KN`u;C$X@-rZ!j%7i-To{t|WbJSF3-kKY{fVPYd!4(~X|()CVQ z|G4w1876jDdJXIPF`#C@^D;@BqzNfa-n@dPO*>Fdw88Gn?d6Yyhk7kh-u4C%tOF_eRseLO-mj(!houkakD*w@F0`?BOp;(Iy4U1Ox3>60tp z+RvjD{`r2Pa7mT8PURCDqa0KCDb$A{84BfBYKwQdUgl74xv{nh@%5!|Bg0xI>D{;F zS~P|Dtz&YEzby{0)AKJm8y*H%FK(Q|+{{d8bz9u90k<}98lfjXdn->pOdU-<&G%-l zEnJA!FyF*7Wk`RN`BiTW=dmpr2cV>R(lkGj=I^u^s=lImXR5)fjLvctKM3oa*a2dO zzV+O*xcIwY#r)ANxOMc7X!_HK4`E_y8GBEkMGu2vIegsOKCG#S3IihV*_pR6Cg#`i2XW>RRi z7A<`&yJNrw${a-dH*Om~Jin%gb!Uw`4ynGiY0@->OTK(kb|0l^ELR8l$4pGW$I6oF zVh*fOpjz)Yn?gDQX0V9y@bMs5g6>IMYit{YomC}@ zL}*;ofjxV0V9y?QulTQi0#APIQ5@L4$CE2eW_%g9h@PgIeU>jvx^8(tkkJf)8CQlZ z`Z6y!(>|)4^p+%sGU?&)=PS8A?O97f@49xbi{t2-ibf+@NvwvEBZ6Xhd%A+f8*%dE zH-KuSQrt`7tJ&$arMtn%^?mDO;OV3<#Kp*#m$7`gXP{n1EN-)DK+;lg2GxQEXgg@F zBuTHowB^!m4$epW?efgWbUJ49`6g(7-S;BbQ=U#=BV#0SPpCdQq>ZO^&FvrW@>A^Q zndIz_ajDCA8uz{{OB~n4XuNhtxZF4{)+`|x3%fjHxLCLBc}cE4Nauo0(*zf%;fWOV z=}W1#kgf}~Yi&&DNYw-rhx^QO2(^)m+%zd=4T@lTNoxlWhjeSW_w%tZpOc|zxY=gFWdD$Y^o`Y5rCVsyNYZ5i5Tynl^-<&uko3n!nP$2`5JYvoGE_41IzUR>{eSI zFU#l&t^R&HAWktmg`z_#O&)J8PiVCb*;7<&#_<8?6SD7Id3-wAUP&*hUurGCe#f8N zCuf)wP3`XopSH}^h@m$2VR#Lfq_*F9sC_xoAJd$N-hP(Cm^NhPhJ92a9y#{7pGS<` z2)!1GY5l0i=x-ZGS=c}Jz z5Bqe!B)S^p>E$k|E%wggCw)u@}Y^Q3(f!oo#RMxIA*VLXioOqekdnw~# zZm(I{{g$WeZ|R;=?ea8V-mV=x@YboTn4eCIWMAL96*snQ!G65U4x+Qxr5uBDZWXvW zc?}!NDQp;Qte=-9CNG`A#@AoNt$Th0TNZa>ZsG<8y`?0X9IE<2wFOICme!;$S`C_@ zCq&i6gI#n>NXSs2JT!3YF7o!n-}Y&oj4P6t$%D|`Wl4u24|19h^I>!XgmpEV`qnbK z?m?{$^k5U`#}^l!moF$N+tXazu&$QhZ{leEMP=05&$ho*B(Zd~eQge_p54tylyhCr z+F@r;19FvWs*^&FQOeWu(iOJ9Pi)zhsHgdrvIyu7B;GIPerS$a@M*WlQ^%-Xy1-gK z48k=koILGdgyiW#(q;Vg zq}fkgL)i7+by#tbT#-6)?dy(H&C;>y+RjtI1uN6}El4isc&Pf#KgZ{P?KD39AN>-J z9XvFiG5}a-Nto(1{uO*>X|2f7jOrOm?Q7Q-FUVJ`DEf1GaXUdX$iI7e$iZ5)Jf za!G!t;AFqGV!ndpeoT+!C@ZClZ3>Y}(`gm??edrTIQFLYh2(3}``50v7&&wgp#5U! ztHo^?-8H`{p2H}uwYRvgcH2v8XdlV?YCN@TS~vZg`;h^yzOZ! z>YcDBVDJ+;T>g3ZSYMmE$Hu8zHdPPNG;UsZ-fFW|^6<$Y!p3gPX*_&>Pz}m z<6_FNR3?@6#Ig&eUg`%m!Y_YJlI1Q0iKkLjFE!wvzhzh4hD? z!ZO73r;|2+oAS=@oAmJ*dYffb-vd1=Yn{*!+`s;lz=n(L5kB zS{XuhvT5tu+t#<(p4M55yBI`Ddyd;l6fv8-++W7OCg|GQ_9aQV?%3zLt-7>v531fo zgE^72_Qcc1?OZ>dID7;z&&=RzMjq-TlH-7TM|5qwV_`RL_vdhX;uZj4dD|=&_wL8+ z^ZyTKUivn^|1n^(KR@KBp@^`3FmdZDHl2P6?>_bO?4<4YGfmJ_r~y9p%zG7pnYhv^ zwxy*5e>~myD#}Vx#nnr?s+t&8u){?X2<6h~q(A>UUsY{Tbr;oy*AmmKa zoKwDbm18B`{$Od{a=QWH>5!#8wFS#Ezozr~J(n-%!S$Zsf#s9h@BZlyM0LYk%cD7v zeQPk!=T93dhyM2WnJF{YC-HvNrPgK3ZPAd9ZcqL;x4-3@t+j_vbZu%YS65_vzMC?r zc8!&)+hiPwx)vh;6qN}|(~a8Zul+X|rRkx>^2P}~{p6FuddyzDh=-p2A(n@qfTpkg z)&DGnHCwt%a$c+HYdVW$JN1S+`AD+X1BJX5`1p~t$IMeXDygNXt#^Fx>MMl>W-GU5 zapG2yx$0Vy;vaqnRkeVsN}Ho*tVQ{X-|bHq)A`4^x{eTv-@4MFYm=(s3l+3CjHaMu z=L)wmLReYiCW*a3X1R2#a2e%#9mj5IIN8Y1V_eKrQ_C=(4PzCmwWxK&adI4c>pZCx zc^KKO4)U4SPg*pAO>6wxh+)@Uh!RuGQ(v!Rt!bDeAM~X(>maZ1SEzSFH7XZ6Vt-1@{24mqlHBUn`5I_DkW6*S5GggyS?H41exVmy3zD z{y#?5M=%dpw(^|vAx;4^{+yI*G`yLx37FAM- zxVO6k?P-gTsRd}$+3$zAU!dw^fC&s>@bC-w--q*icYD@D;EAt)6B7$d7!0>|Q~SkQ z)y7X<+dB3Y=KiQI6x;Ll*|!o`Bd)I9#eccJD1M)|rR7SGJaIXi+!dtE0ICuw2dIj? zK&0jgpmN7^kC!S`7?gvtmSH_6-OS};c?sxG00kcn`FJ>#XSIAE(%Sk zCv5{5zS2=T^Qbv#_B^N9e00&NhWlc;LY6IYjMX4k9$6F0J2cA7`0}l#))wdXRG312 zqS*mHZ<$Q%!#SxonY67!xI-t~vYK6C?K;<|Cdubr;Lm;bWDLLhC}!{YuX8ArH{4em zg~otMq5C4-`Its2wpQ*+C;ghKJaXH|=8N%)!XSL@6yxCbZ(zW3G?!6X?&Ctt7*!6HTdc}&%M`{)?(cyr?%W( zYe%;h^}NzEUE%!Ry|}PD{u1fi=g#7pKm1GJ$7iwk(BDYfwB2Ko=CEA$I9qFrYS93T z&@p<#<0IAZE7Fv|$!l|2yN$kLOszR<4{IY9;Bge1q9A3AP9)nh+&pH^yn)FZZ{o^>pIq^FS*yf0ZBwU~R3m1(QVN~oT(Ze! zU0$50ZnkSdUg>a?V76ps$%(CnnCrj%)5{?vOj7_MfX~af{4BIL&b$y`4XnAqkn*)D zHJ82%%5=G9-|;prM7!$2Xv(u7wdFx+cjLBk;`$a->kP@=Z0+_km65aiU zo!_??&lLq8eCCI$y-)}l>doCfnD4uQoc3wI2vd@6zWNN}RyiG2@-$X%k+>TpsVzly zDu0Vv)BaGNBD$d>McL+q+?CT-afm>hnL+`9L#gQUo^QY^>4Zc3&<5iZYt%h=|hMixo z-0Ao@gyXaoR3o{;A%)^Le-1W|x4)m4UUqo>7}xrei;eYF(Qj)=yWgY^$)I6k`izb# zeVdRU7xVjaJ!^+sDgQ1hG*0z0Q`7s$qwk)%FZ;_a+10=Pao}q+ZdXZpe4At7r0SYN zdRkul+tr5={M?(5tu(A1&)X&qmw;MFe4X*b zgAoqCwRsa3H*E0A`Q49x1Vvfm?iXIh)+^Uhj>@d5L^V2H+nlg$^;8LqIH~I(N`d)RVvd+EW@R-HZn*)Zfi*ML7>AW$Vnm(pkd>D{p2>Uz7 zj+2&}@yU4>=9$A!Z+jj4aPAsEX{$D^gU{w|v&ObtpJTW+ zR!-X3(Cz4WniLv`g+TpKg)%q0D8W)3d-MBxuW9&7mZ^JZe6qN6qaEo|kArW@SPGBV zy!5d$wEYE!Vr#0FKd0=~qH&g=C{yogjAIy-Z!o;oX*m~+UOkcW%cYo^FGV;Fn$-8OWLKkX$ zhuq0M@|%aZc<1XwLk0!I1}Imd6yUkRP+lj11}$o(K@ESS3|xiF6`kK`cEODdj9B&I zni_7s`E$2UlCPiKz?)VVf7{VE=F61?8Z@2ea;=}bb)(Ks?qv0wXnDGvljsr+(MUXouvb=UuSj?Zu!y2>>fwe9t;k79aG%i(vNg`Vr_TtJ~o!=ad<=8AX8`_oB<}`E1T)SKNsHJCtKDTh`+&66i@{3ypx*m1y1`CKe80J8jml|8MLztpl zijOybs%;MI3Ky?l!Sd^u(3@XsCLSTPX}=lyT9ms$WFKnz!nR*~O66ZbuKz1XQ&Yer zj}*A@OuA2O!e}25)omJ2x4t@lpeHeEy!;rMr?GBbiN`c7VefN!^{x4|jg3Awy4hV3cn#gQ zboj`TEAbZX?qbmd-tiSIjThccD?dedEtG9&s!gr`*2h z{ik7LExlh(KL%-zjoacZTetSu*uT0-{@RM|rjfXc=BBzcj*GR84x0b4t2H+~mzwiS zCnlm2U)#P70Pxbi zcjM&CuVClJ%R{b%AqKAX(}2m~t`^2JtT%G^U@b+8fHA6%#Wgy*(Y%Uo8rO$OZDByu zo!Wfn0qNBV;HF?;d7VBo=NA@m`Rqk(fBkYp`SMA(?)_&MWx=o%F1CeRqZxkPoJmZ);u{}yxf$+IC~sasIxtfG(0Iw;VEfeKG!AB z5Z{nrz^6lWUgNYM+VjqxQ(+y~O&PxYI_AdkSvHd4>(Po$^A78j-lt*9 z)!hkaJHYi?^ok!Oas>Se{u%)r({7{_R`X@xs&C@%(eR zz3(1ec>EW$>hoTw34TnzyVZre%lK#JsKZ19iea8~+PE8JW5FwF`cXB=RjEm5fBTj) zY3gxc*Z1brxP%-Jv^}`fDZa#pKtRQ6kO~$#aHhZAzp^hi0A~AumKSz*xgjZTP8Tel zTc)pWDP+@|_lgYnN=d`Za-YSVrnlGiy^zjfMN75jUm*<;nzVXBFyJJJsoBsYp z;BFfT7p5ltoI7vjDkpjPw(WHz50$L@KvayM86$k&hBYI#?kMQBfLXIpq$N_Z`vt0D zaN6cIr;GK-=b^9e+>X~yp1_rzJCfUAd2#~h_wGSaRrv9P_u;M=UdF`jWl;D|VQsn+?eYt+ z?=+os8PReib~ewrUU6MzwhTMh!|2SF)8#|&8|nK(b|%*_Y5{pDg` zbEc(>p*5@~`^dG0th~H!DFW8FUnyICbJUs-nQ`g-htcY`r#~cN5aJ=-523Q}mSCV&@dMS7Z9yXZKku$p6${^v%nP z0qYKJWx#<*M!Q%QmpTcXRR&F@HXT3tPa#oX4^hFas`LSGo`WQA&FV|Q0 z`l9$M9bQ*_*doL?gh#YAAzdA#rg|qut}ZA%R`c^%;`%yO25r5QBOtW}!a8nk=`KTU z{4uLlqjvs)+xV^SJDi&rBqU!aBG+x3Zi)0-Ydg1my)Vpf8QAl|Xt(Dz)y(Clt;h|JbQ3_zXRhqV?NmN~zM6}X z=kk@~&PU(a*ZAm$tlM6$Jeo}Y*6_Es52!S0S2_mGok~d;;^lW5gaDS_)?6lk87_bM zOqSzMuji9_Q)qmE!w-Wzqt3d=|NmH_FrUmGyM_a_RN6pWV9Tle-zDEzc(7 zC+wFL6Y>4x&l@y)FiK7Mx&FTsMP z__}Ua2M#rKo)$RM&q9}@H%E-R&18m!-KXY9x z?p7KNdFi-Tx7RtQ(lMUgtmBp?^SD}6!^`GA)#TLnvh}dm7{{}8M5b@v<}%8a#2w|a zG33?_>^jzFGQE4P`7~Vl>2Kcd@iynuhQ76+y_iA!NIO+G)+eq;l8#Va_q*h}JKgKJ zTyo9xS(6%OhBu!(p9GeaEnA?1X)xQntT9dA4pJHP7x;Oe)qMYpG&0|MV_L_YO=+ds)kt{nd zTt;tnzIKKBizo%4g>C#rxuxV=bgwux)VgK9jj_$d^YdgM|d&@Yt z@f^-=Jdd5X_ha_ya{VUezMfW-N9J+UX>H&lV}DxNmzs5vN1CjD+a-mczHYfC=1|^P%(ah0_04Hd zzh|HsrRjnkeoZ7v(~TkC@i`PPGsJ5>(713>3g47=XNu4F3}i_M{QKcMt=Hs`h0Xk~hZdrbKVrCxcLOdOfwSG(&_dN=E|&prGg&hKyV zreq5$08C(j682zTgUbuD?bupX_PDWH>T>keEIRY-ON2HZKRS$hgK0FI{-QArYxUNs zuQ!rNqH=5P8D3OBSQ%4Bztl>$59K{tTiTK|e>rLmTUYyHe1ZDq%e?cln~^QKmeg)5 zH|<$_V{G~m71*}03!4{b>zYqa;OsB{r?`3I5ghry|3_>(^*qk}!heSA_k7fm0w}QQ zjUQqEm;O0s-hL71pZFEL`_yMTt?PS**rshaKq6I=ghV>=q3aG=JMn#|!i0Fs>0$5L zvaK4>fu3>0`A(yw;EvW?2YI@TmY1GZQz072)*+-H2&F(n%{?aN2!UiM&uLIwOXCk9 zab@eaxLXr`$BxOg&)2wPhu`(JZ3xQCapaCSJ)bLQh`&afo70X2EjZ12+PM&tDeV5? zq3;+UUVfaX%O|uc#6PYzKH6`}*&lG$`Dilu%8c_#FL5J zx~A}rjo_FAv<-0svMu??PfDIt$D5B*`z-uCf1ISqkwS4tSG+D^iqHMrIk)zyo4KO7 z_uVaWeC+7$Xdx%H1dWwauxIjK4P)pjV^?-=$N4>bTG#LGqldBo%)8hyw}9U8vr^`) zZM#X^$Uv={3I(}iA*(rijNYeDi_tIJF7~%+Ssw6~TSa8s)4cYc29~Y;;m+1^jsJAL zAl)xMei>u?lgDxF!Mm_+^Ooc+a^r>Xc_CVoe)x-TUeK*g-GlP2lGl z4zK!fGf$yoTV5V-yZYLPgDD@1iOpXfV^e83X5+J+qhwo}cAskrw}zEyOIaVDjz4k7 zy-X1r9WIZMMseHPP3@Oiw|!G|7`Ir%-<uT9YK9XaV=hfSorqSDY zWw3E>J9n|B`B&65yyMP9JsrP}&CO76hx3NU(AuIVp}86t@3)$`IzG<>&Qg*dB<-hd46PY-hdHkktT}Kxn_` zFW*o(+zj4?Z`)WvlYDX8EEP*gRO|W~s2&I-&9ILm#r8_8dsB_v+{Q{FU)}Oz9dY|L zrOXsLQg%2r;p-zU9+^*h^DtJ1Zu#Y5`DKx!;G6)ZiE z1Qp^phGU|S68+KFzDqp&p@(r{&+Y{I(&^4uU&GPY-(;h&mHm(g^0SybZ~|rK zm)xub>&t%0r3o8|)&jTY+N1~@NLnD04pYugbG`X_QhqW$9rE-ZbwzSnv@%0ZP#Nr% zq_vmU78>U;FHO$)fRvp5^6~pzX07eHi`gHHcICEGxrVLTmSohs?r`v%-*Lqo3*N+> zJkkZ8&c8bYSYHZczq!9Pl1`nN5nCx~bXl|~wk-er^Yhdw)*pHvS4ZeP>GSY>^!16x zKg4GxC^R>64A`atfz)#1>HNl)=Frg{c3~$|JMxX0COsZo57M1AInJTnbt~qqZ~<3H zo2TflX06%1b2T={Q|DaV9n_qa!R+f z+>z-*YAcVlGb})+_MYX^J)lbASR|%%$!y(ElH}if2s;lS!p5l$+2z#4-5wyn>8b3d zCCxbC@>Swq)79FR-QBvleyJo{f|6!aYQaLy9(U&`Pebz*kQyM4X)F&aYYZoA_*y!r zG`aaWqmDJ1O3E5WT?MPRc{9xy##%lHYoj6vM{wK2PE4qZs~o)BCZ3 zAMd(l_bZ2 zl7?4T5)+5|t1c~!aozq)$HYxH!{qrSR~8T3-(8KHw6Ty&seXzOhxBr!g=T-tuqsW% zL$9tK$M09pKNC=1nwrG9gM0DPy>}f`ve z2Qj_8mGvI&YsnWV(4V`3nRi~r#Er|i{NbNwrOVbaV{tuV;7gZ)y?cSl$(1i#dg5a1 zmw!b1@i8w?uBUq19E=yst9ffG_$78RMB2ED$B~+i&2-Gwlz%QS-R=xw4sI(*TZm&X z?o-qG+0>~rhbR@{wQt|%SW@Oox0QTYIiGJHg>=a{^mH?x&3qkAW5zlCmO`-{KdR{c?^OQXKey{as9~*M5 zi&#X$rZYH_M^PvqcWpr$kCynnhYF_;AHtQLJEL-+JaQD*_w2=~n{&YIrf7O98BmSB zEN!rCi3%9*2c@rU^V$^X!yYnbYEhC_pfv-@TU%)5sJ1+IU6Fj|yEJqob}?)n{?$>A z;W^$jGasxh9``5!py**?^GQ?%2TE?==@zXm#n!;)F|xS#C{KG(ocr&&M;^k3J-e}- zu!;Gj4?LJW6Q>pyuwh{l1N329Q~IH`ky?@xQtXj(!!&O1y90yi&A4^+UTl2#4NP3S zh`~lPW_y_5dpDLhZotCqUMz0ig>rH#u@>(?nvlVhxbdfdh)j1GnrC_^)5$~m)9d)4 zkghwwJaih%Qux#hxwg33=5Mc%Va|V3spE@Z8sC&WZa`DJ&lN9!?r($2bKkly0)V0AD3w+WvbXlM+=F4aA>M*2vT|#`?JD2#PlJ`l&6la_^ z_T%YzT6bRQ^CLwzO%5NAHpCq;De3(qDkNEMIW(Uvg-avT(O;UZs{t~aj(_c5-a4U= z!RF&C>@bXf@gU?_4@r>|C>;-wOj!rg%FU@u+wmH6My2FylUCbMoloKXh4L?yhF|ly zoz45i?;Jjevj@8Sgz+nPoy7FbdF+`#KZ36kxLdMeUVy@5{+2TbRsh#{ltT$S|0MDG z$U!g-g=3V?z-*e6+I1A1+M0}G<93+*wx~>3B&GAxs~7RTbCa7U({xP6@Nj*?Tc?$MFZBrwWtA{yn zDucT!j1L`GNxa=PT7F^3M`tcxz_p)NP!BkY<&q| z+xxGvVK9SVdGoV4a^oZ_^zf;7eg$9M_XT`=&sVTilz8CsMswr#Eo^=H zyO??VMV$N8znfIA^-8b3R$<$=VpTS6`?V9NG>?XsFU^*W`)?6K-HD6me zh3v$(yt|;dpTsRYC68U*w3obeTSmwG8}en=Y6Saz+cwL$*4w4wAd7{YB~{qf$VP|G!&e@$C2PnYE2F+Kmv&{~Pf ztQ9%NO<_-_OiO)pz6b@q;&{aJ=h)jk?+x+xjjda7dwOG3_H&mm;p+A4(R7+rb$Npk zPBQDbv7<_uC}I!505&>~k)$?m1Qf%2d`oq26w5R%XVL(0cvPeOrVJ{zZL^A%q9f?i z!RZ{IoAF&vY{2~fJF(@`RrCh~EP?wMVr^+CwC>P8E{3fueKh8NkFIQJ*mM6~z`ge+<&m<=xJgC+*>t`b2+vDf=SFPN62VBgQ+0XO8ZVrA--^T3Vk2!`FYYKsBXw=U-gTG-|I) za>{HQEDp_s99kQIT$`OWg{?N3PFf2TUhp7bCDK{&YB$cB;5h|OT@#1ATAi#czz%`E6{!bam8|)O`WcT0qDOFs*L?hF+Oj?|^l+sDj+QAnkA4>Lr^U zY3r({?JD(mGyFiYjTU&$!^!kYVnSEq5QXdz?Un8(JUQmf<)!g0lrr2jQkEE=Hh1aF zmzYi3NVL6akJvg(E+DDW$w(u6)yE~&`yoFM*Loq+$G7|~a^wh8I)-UVxtN&Bp;_=b5{A}(O)eLwxtiP84?ZV+sMp%GwO*%YlsZ#=4>_U^SHS2Jmw~D;bRw`#IYN9 z4qqRr`~DMWe+FMX^hW@CIB@GYcF!Lk@%8D2Vz7*@FFcK1-}oGE?>dN!PyW)_>eiKR zYC|9USb^#3)hRm^|D*H5wTV*gM88L*={lxsxO`3PBIPD1DUHU(yZf>0=ci-raDENr z+mzA*)9v4wf5t7f8I1#zgv)3mb-ryJd#3McSWC7RC+Wv)#v|9Sl4376Eh9xYwCj)Y zX}0DR_j2nVO+UXFZu6J0-YM2X&DV*TzDa4rynghT<*o@UL91;azMrUVzv}sUR3>H2 zN^EQKeT{Mbo^hAny?7Cqk8i@>4;{jthY!ay0Jybj6JEaiF7(P0M_+vdy=pKjxj=6e z|2Fr`!I%|F5+$!-Hfhs{C9fS&u?^eC8n7?d7NiwQ$e3^m8|gN@E0GESiG>@UHi|&K z`FiA}>Q7*C+b$GW&jRIgQX3j+Eb-`pPS($2q@*on<+Lqd_Ir5!&SO}fjGwS===8aB zxc0qMs5b46raixB52kOJnA${Y%}Z$NLwvu`gce*hWE#~S zicNvF3$(fm@)m5^^Jg-jbj8*8^dLGn;!}r;uHw0CGQ3GG&X>D8<1UBrK<90z0|l+^ zUG?P;-bq=ks`ndC?p2upta89aC|J_WXyt9$q@N}K7*J0G)oyLf{MOT_Q<{;T&(lY_ zWx3-rjceun*2i|!MI>cThGa^mP=L1$`TIR&z;Nd+L`vUyjIR-HPOV&<+6}fgrC1;` zmv_^EYm>lqeLpR&Zxcf-P)#W%Xq~=2s5|P~5KQfhHnz`dkx%xNI<*DRP1hO&lx!f{ zo+L)W(g>RNdnkMHQ>K=dmr>nb0(u4dQ1ip3f64C4Phgriuxn6l^^OTt+B`H^?rK{7bvWNv)jSHXJ%&;P)Dwec^vW_i7ACjM zpqNMx#G6eKeGG>0SX=(q9RlzXUpYMztF1vsG5w+8pbyB9#Xk}!+H0=+a@vvG`Tl(A z_|wiyA4bvfu7(%5+l-FK$~#}vB;_wj@N!+v(T1n4^Wc=>_gkc4FrR(p!wOnimA4Og zO4<)LJ@u*h^g^g5b)Sh=c8ZpDH@Mq!e6~WopZ)Dg)A;ka?QHYJ*5xknaThwaN#BO@ zrEZwe_=Lu^4@ZQkEmqH^kk0mDo~9+ma50q!h+``qk5Me;J`JaLaceGC(fHE*+RJev z-f8p2pC-*eM(?GQHa`4XI~@~;{F39q!{fC3a_0Mb!^3gAI_9fRsjrI{-4wb9tPt0x zOdf7E)=Q=Q%dk7EYE)mAf=yEsT!V=Mz5<@uO){m1&dO;zHKYM z^@)$;lYjZu;T?P09MHpsjTbOcPU6$={xr03`r(^*V(Y>z8^?aCu<_g**!}f?iDEFo z+yD08Pn6Q7wXh+3?UNk|u8pnZt5k~Puzap*{_j+d{#hWAMH?R%^$uwgwB_3!g={bS zI}d;Od8V~%O1dV#=I+~%@*aoYX^X}D`BrihWE+zHgeG$5wo^)a*N4%TG>+YmsT@0C z^(aruoN+OpR$W;dU;oAQjs2U}hTV;}mC{)s*pJ=NxaL`&w<(72Wjg8Gw|BF~-gEDw z*t7w=KlK2P9XynjWo~8$ubsRT{lNhJH&i@SGW^Yxq2P203y`cvs)N}U6TN0`#uDdfD%4M?Xssm4!T zI-Z*v&b~l!4!>{!)TeFzdAp?X@z2vU?e&SyFDFo)l3z;`qBh`q9DUP;zW3P@T{sd} ztIoclnl{gQXw?E94u}BBPqS3&oCZ3Uj5oDX>Hsg@s$4_PA3pRD&K}qot=|{E`3;=; zhku0PuHAU#zx?ZX^uGI}d0eW?1UNvWK+Zi$j00Mm-qwQJJElEoz`B4v9n7?-0mih= zO=y`~M)Cv1I!LCLU)q{O`)@5c{Xg=Z@8X#cKZ3LS!eil=zy6Q#Ctv?+FpZD+b^=Ov zmh?t_Wz*@FPz8N%X!1)L{N(S87_RnT zr{syJkLB0#*o#wB{jD6|Y=98btaEiRozxFD=|GR$%JpC4S{?;$x=Rf(A(L6b1 zLdHNfLiN&8H1@9v`_c{B_J8`Sb1`Z~W8>OXb*VLX8>+T;q(xxbYs%DS<4=Lfr7M`e z^+uqs@z%(<6vj(;95{%de*EM3{O>%SomX1kzVQmu+9zKC4xa<|PXbG`Vg5V6{TJB( zul^|(x9!I1zy6;){QTD+P!r;wyK(p(<+bZC&6yoda8THu57jw@HBu>z9J=Mpc{k^w za|+8E9z)eg!@BoV;y|IYeRwKHscqlZ-ZNaf?3?`ZoAGEH`$^%`lxLIlUGnS>6Swh9 z0BzU7)v{1>MtClT+qejhL1fA8q}*s0gC^N%QQ%@0F6=C7{51aHS52yc$^|~kmrT+ zyg-HN`FBuM=_hSV3in?D`ZX&~e0&t3G5mZzw0CwESMEE6;^5ZoyoRW6M0-k!$FpMC zd1du#*Lr-dtP2w|h!}U6#;H<14JJJz72=kXntT43!hq z*UIJB{vdKZfGjB-prq+idFT_gVm%aASK;6;-PB`G(B@kKw4Azf2!~cfGHL;rwDFem ztm$O;wOvZUR5x~Y<1NME)uax7r$;;Use6YM8A+W#Cc=ZMX@>*W&CSJs_&;w39gT%DK4)0<&!KghO1(D%9TGR zRnt~YsckCn_WC6^O;_o2F>#X(E-CrDrtX6wHKlT0|F)>#vkP!6to3~%(osvq;2--} zCz_A*wP=$5OKI`rhYn-m$T58P&whl3#l?gi>166w3=yZbeF|1v`+;YSQWykn?wA^y zG<6DU&+t~P%PUxVlg{Kawxm2$TiSIM3QS!&hl#msm_Kj_;VIWo9SP`GA-!j%UYSh_ zmiqlZHcV~+&fP@$n|}`c?9T%mnx7IjyD*EvwwLg=yU;Uml~HAawIhZMf!YZo8o#W8tVY4KLK-RX1rI!&5%VQk%n4U*3z-d;_q z3mjidva+`7TD1l9aYJ{!x})}bN%tXkPu;b4KIQlYR@>vBOYO&As=qh>eC>_8wMd~> z($>C}Xe)}H))wi0_Y^rb+ra+Koi(}h?AnbRSXf*{^_AC9J@g9jOP|Utk<;tPkKy&> z$8g}CGq~f_8|V#6%-p;+lC3~}E_OMxrYzDnXtR&{U?b~6Fx#+gRMywnc8rC6!=#R-v;cIu~vw`wv{O9`~hHqKKcr5 zjnNms^-Wy5dL=ubBFULHs!%*-dSB9ed?b+GR1j3 z&`HynE8j_G63^-~rTH0rW&0_vQF+Rg@fyO&9KUlp_5A+6=NepVJIz&@hLPKl92fF_ zGoCaASE^o|7)|_7#)C?QM^;K6J0<`k#JmaUf7(`#8xt_lT_ z{q3u7Q5hd~gEzZKw_2FEewNP1=2^dZI3#(>`o0z^)}QWtr2g>Kz6{|}YI(@5Y;d0G zW!f((89RfH-xN8gr>3xZdM2eZ$yA_1ALS5@Qt1tPqn~J|0b#0fOBfVeKe68{vT-4+ zqiJ5g8PiHd`$M~;VPbRNNZwmsL@^kk+@J?mxee%#y12d%nulK7*0MGBk3AWGtC47Y z^Yxhv7x0}Q{Ser;5yfX8272x6!;f8f42wmHZ|wOhD)jOAxlaKo@aE>%@OyXvHtxK5 z8T(Id#Qs11J#72NpJQ=$KbCtNF+a5%n{K_0>9=3T;|n^(Jb{+RB@q#-`my2gX~{9^v~^+GEV7mBscO2ww~so6O0#@o}RPA)B@UzVtbCuo=G5xFg9tm{*s$Xy=+ zM$u>8l7rD}(uTj~Wnld}=cX8#_E7;0^VI3xSQ1886-xAQar!U@y@_c1 zIT5c*h;%Qz8*##@FH++rYt^P% zKQzI?W;2RytH|3Fn-+BQ^Pz4m7f9=&iAvxbgTtsgLjf|IczwU);(qhBxQ=1Zac0D3cuJ35=nknV0t2~8y?zmMw0^SJlt z9>d8aN0ah|R~{ZFtwYv5CcUXm-43?K_BIoOC0#SV6DYAA^UV;O2T`Ff-FG-HU44f?+(K{{Q&eho{@IiJ`H>ouP|ZS8^eWKXOW z(zdNgZNf)(%9j;YYu1ym<%Cy;lAlB7&hzNYzozNWVF=Gnb|Uy!!GI5-SttEUT;2! z4C#6!g^yo%gvw0E*lU&I{uh63Vz|m3$-a_&W%#TQs>|0V&XSZP=SpJYI#(DMry-2lqf*+=P$am)R)R1^8KD zU@3hV+x35h+pBW^(*7;L``_KT&24s{%@m@!+w(Yowl7lQ(VKQD@h<0u^Q# zcH!|0Phe`W2|wEL1AKYk7f=D1Ufzs-bBA$q=g*@0)DB$Rdm8;~m$5vv6=g9AOl-p9 z^a0Etxf=`Hc4Pj~U09esfWd}oW!9`T<#@~1FKKvLOVf;U*5`c68~c7cK(71a9CPF1 zE&H*%IEg<^-hP4b^OV?&zJa?tvU;sOkEYMNC}Xwxy%#7wCbXW~E)T_|Bd0L6LwPaY zYs<5s?;GN@`eP=){I(b|y+mJRsf`p}(rWizh}N=fAJ91H+V*Yu(r5VBjXv`2?_$^a zi^FJiy}7zXA2yP15V?t+oAa}KWczh*h@(wJw*CrM{k$6Da1*7rQEiM;*f@1XF8Ww%*>1J`u>-$qdHbX9RChzw|L}QydAS50IeyBLNBAqfN=+k8;Enaa8QHMI*52cgyu2V zZ3d-v67iO7&(rX2%S{ig>CP=*yGwauLA=z!bVzE+w|y|Vo$(fKo2E{i^k8L9;51a% zE`q;J$79^lmrMHi%*j*dOS|VQCpQSbo+<8@ZWFMIm7V6ai{G38Z?jDjh6?3( zyFj&+D_?J~&AE~?()c#k=6v2S6biBVS4M8H(txGioXtm(1$;JtvV--d3&7<$?A*Ey z+qY~<%*Ck=Qdj6>Fan}>ewg#NEle`O<7xzTZLQ?_*EBpU(||x?+8WgE4Qp%N#?iMF zx+5Iy{cjoMUJ3G-Dn}=MZd>hke;#Kxy@hkr?_e-=l-z&m z32a>6+PR$XcamFMI8iN?(^lHZHh*Q7V*KcR@|%%lFSvYKDnvIbCDowLnev zPiQQz$2lJNf0994q+zDk(N^ioF{vKX-pZUL1CHsI4ric;o#{ zxq4}wJ@?2%=#?dooq8Qd zPrU*96<~vp4fRot@LYu+2I!Ac0_I4va)i8lFeiAM!^-UOV)l!}HK$^9cDehaZzX!b zV0B+Kr7o(6izgn$%-b(vdFwVT&uk@m{nSj?q|@Zm5}x|fSMZG|pTO;DKZxs3P2#gZ z{NM4pPyYj4{q3&-lYLbGZ4XG;w4F-ECu953moCMNy)v{`Hk8lJ0bl-dg`fC|0xb_f z2Ov(`b_109{a7>jf}SbhE1mQ}c_^q#H;EL1^sy#3xx}0J>B%hU_lnuJM{PNPbBatZq{d^Tx(b8H)u>tlN_P7@ijES%)LUCb+Ax$k{S!^N?U zt|^|A_v?zErXPIN9VTwuhii$NjHKLk<-J2)V`15T+?uC|QQ{*P6H~lgZ-c$Qbqmh! z+ZUDM!j&sH{hb$qZ@iHtwG6l#yj2Hr>l6~5^+%^$n>o^B*JdnnEL^h9-4!r8$;-aD zT#af^UudRrn*wH&wtVH8pQK%|>x!h|h>YUw=EN~Bzwh4j;a=Y72LGCmV5gzO?VGpY z*nxvMl_>et!U7JzeVRziJu{|-HZN_($1XgH4`28s>acxp^tS|1ZrY0FP1}XE#_!>$ zwGhx9C%y3oaOeSI%xQPj-SLx*G`4Grkk4@KQ%p}6;{N)n+4w2dAEBL=yi#6_CqMKdeDm+# z!rR4PVDYQ3;nY9+V_g3AtC*hJh@W}l$+48VxM2eT;PvCj@a}>A*mn6U?)mYHs8R3$ zB?|O07-2AbJerLc@wjFW71^3yW50Scw>h`FB3G+!$cQt25t-oA}q6_KeZFmqrh`hV{!;2-@3@bU$``20(lcyixMrKOY8Lkmo6xnk2QrS9W3X2)ytG;vntI#8Md zK`BF50hsi_fAdWkoKKnzu`+Tu;WQaL<6gwNqPRhmR+G3xF0B<;GC0_EKr(+LL|Z6eD?w{MY z7jrW+0Z9ctb_B(pv&qSgB<4ghvo*USAF>9ySFswHKs4QqO=~4RM7gtn}1rVQW;8RCL5%+ISv6nEe)>-|<~+Tik`cb4Rgf?g%Or zcw@_pxH)+p4_x{Lb`Cdk`zas$yemry#2m5V^SE@&kJ)=~>J z=SxZUpgE3UAu18o4|V`9`-ymbI)wZ=4i2& zi=HONgTxl4Nque7SUZ#2U;TwSOw8X%Y9DDYScyYpfa789ZvhjS<^Anq;R=fzH{jCl zxNl?Ejvct~&J)R-wx{Rkaq{I?u#5>-GOaJg#jbzCq|tMwonUy4vGLl20CAjkWR9 zZOQ4h+V<31(g)+B=7=)RC#TK2=<6=~Xf@;N6cqyYWbK$dHUb@|?OV3uBR}mtG`a}#4T8T!hvbo)lCc|Er{HfXFGXv`M7NuE0;QD znycX?Td6X`4$V{@7cK%uTE}AO6!wQZb~o`(-wGR z%S(7>*Eg~M)*blltN+DF;sN?7stJ7M&>v!Ic@rL4oW+KLE_+iuryZ?d{RD(?Wg7~G zBD!fW4RiX-;A=WvuXR1J7Hs+yo`%MSk#&DTY91FOb1rht(gPAQAJ?nRXnb?Fdwd-C zThO#x*ghmx&Ss4q9!>bT)P)PQS^Yw3n&DzymL`;sP*#q@*f_mELzt?mdwSehVzn`G zUinRZO!5Bn`O4z?nwGe7G%ow4+2)b;L#f))-GI&Wn>5l2kk2_LvL`G9z`FxBg_ZO(nON*EQj%Xq#H~V3AXA^s+H; zjf!p5?u}Zgwhqc6cMu$G!l{-Q_dgf}%dss*!xbiPT*Bn_t61E&XOx%X<6H{)MNCa8 z(x)g>Zh^O6hWgp!)Fj?LbO0~kb62)p&4@}sr8ljl6J1Ngq4$u7AdTATocEr-iqY!o z=SAN4`F@M`t+AFcsG;!gg0(|ysqNN= zEM53DyP!65gd>sw#kT3Rd&ds!etZYEPR{^$?8KS#=kee}_W`rJ@tyzfpW*3k-^KLQ z6pAPAz@eue!jXOZ8_KWK!qgPb?c2-l6;*}fub#q|YuASuo?=fE%dRngIYj*&-xb5N zwhgAY+rJG8w+OBxTCQ?*qVGst`7C`~bTO($h$>KD1V;cAsg}c5ph#Sfft>MhaL*n* z`m0aj2mksM&Le$Kg7LNt(9b9>k5c`UYtfIn)@ULn_-M%89uucnpv!LEXzNG`mFugc zX4vTA-CTvL$wc{f9Yk(Rspf1r;P2*>0M89dORn79^ar-aWok9!8|stXz)bpFhzD8y z!D*X<-y4s*>?SDP9i_^X7PM~0dt9^@1J&^rqkWJ%4dlOfC|Bpisf%Dld#6RthVF6E zYR_RxYe|;XA=?6U^KN=>&1qVV{_&Hh$}CIoo6kOjE7z}M$CkS>Gd-P@XKwQ*T-~_? zQ@0neaqc#3z_vFGQx`CwgR)zQ0e<4P`DY*^-F9x^ZAofbjB0DPd-L$DJ%O9HlWe;h zP}6obL24eF2KY&1G>3F3(oKl2rS4ktTG-V$E^G*$wwm3XKvS}9@da>g`!ZAq3x}bFXG#w{P#1`X}B40Sb z-JU1qn~&vl{UpA8R1!aa<1gE4u19}e3i5xd%pq#K)u4$UX^)RX{iC^gZ9ae5Iin^f zW9|rSSLYZt)i?SW?!KHZ$XD`eW90l0wvUhRi-2Ly?-k13a1y63d{+6RE7xC$My2GH zzm{mN%eOidi%_^8b)$Fa1{{j7a$5QMS6{^o|JN5${n?AaFF%%)XE4#n+@_h~$y)Vm zvzz8`0VPH_)?i-q+n{qB2ChHKT#}j?9Bpb{4LNYETL8mzt!kuPz~ESuhn~)DPWs}U z%_-dWv@Z<#(v91;)oqI|>^O{@M;;wvVX7%~t1z~S%MJNzuK@E6+x8x{DJ?E8aB=VM z71^+zvPsQ+Oq<>daY@yQA>0+hd>Vx{ex9wgp2>&5#!uYW)D?A6kCY7`x%>b=>Mgcu z?u%GY8@7G;UgrJ4Vu({4`?>3}{eGcl2x0t`Dp&K(!RfOy&C}M5PnUWjXZ$yBH;tDM zj?r3KAJ${ry%#9f{}q{G;dBrP+P?!(L>n2V%^e4`4aH%54S zn5B@F2C@P9NoVsWu-v?DLparNV>aCoZl0SUwb{CDHfYPa zZ%!n$?>W;DkpyghEnSd&A(Y?`X7hAb_gJ`VA+c|5H8N0nD^$G#-+t_)7)(rfOZCy* z?RhLNEn&lC_{2FEv6wfWdun<^Hzu!QLpg;9EyZt9R0_CAD2J+*Kpyl{TlWk zI)rz(p24*Z7o(fDyQExAy}q23R(ojF<)%mb%qK;RXL=dwTGn5JwqA$&HWweoc;*Fv zo38bFc)+(II8_d=HFdk#x4AFZ_8r%}ZDUvE=WULGeQColJGZ6oc%|6OUD>$taoa3k zIwwQjwcog%_$x`N8-B+*vNhuVyzY61({-y$X!-G!-FRTaKD_b!!#<$Zr_@nN1Dp1) z&ae5oPJ)&O!14gaV@FW@#uG_dF6`co3!nN)cJGO=ejS@`+(JyllJ(_RCXQ)GttMoWw*w4>#M7Xq)S5 z*v~#%jV*$4jc;4DTm8EJ^!2#=Cyc|}#RF3{ZJMpsgm(^g?UNW6HIXM5Px$ocIPA~W zpw+-BZRUfduC&5h>_hG4iL`tsPx$#t6D>E?YfbB&Q@%@i<0yROMsq%GD1}#Qd-{AB zvWz&tc(g@Jz1}J256Ru5mRsHj)O{PTTp4!u(MY2~nl=rM)0zXi2IOA-Z}!q<+}gYu zw>ED|mSD%$ZP>AOTU}DGz=!|AXHh=?BfRwgv-jpvc3k(F*jM#l?`ZUb2GH2|9mEcT ztGP;)D2b9{Ii9g*Y{z!&@$uwj9A`8cXC^1HC*#@9*yF^GPwY&rvBwk3@*-REB9oFx zN!$RESO^dRL4w%V#@>xy-mA(V^={pz?pn)xue;yJ1NN(`yVbq7?!Djd`_--fzr^UV z3%GFVEG|~=VQ{jH>JL7Vh(A0ugx+rZ{B*duWHEQ#b8i&w)kzFpzFuR^e$2@u@Ooze zq96zHx1!k%w@_p9T{6`8@Iji#J$$~vXEgyn+(yvzG zg_N>JLNqU0NA!+5aI>_QO0UE~z>3ji7qK7?7u|m(T9aI(-#nQl>F{DTaTB0U+;mKp z5omt5?JRQ=-8GEz2wflHOUIf~z`4f*KwG7Ppj1NW*^NPMr;>bq z&@6&=r2+&&K4dvy_Sn-QPhpZxPsNkd)s3Df%bZq|P9UccnfB*oQgjiDxUeI1B=HU^E}9^41ahC z;U6D?_t+}yI5NEP=tJ21`hN7^ycx4yk72A4Pc5O0AQpdpR2d;Sx&y-Vs2ociuf3Y9 zb;#6EUbIdth3;Cn|YtqK8gUwpyOh-PtWcqYX>)mE^j#Z%%J*Mcj zWLC%SbgTOM*QC3%Z1eR$7B-f&D4dI3Bdy)XW{o2c<5I`XFlM{-BO4}_-Cn0odnUom znp!9VHjc73dT~9-NMtYX*49>&HUn=vOtekzR4>A}&hTd=)y2mw6w z-Mj<8T1AqrMqHb`K22Vv_G_&ju}Pof?@_D}>`2LL!7^uQmNnZ!W)~)Dv#K{Oix-EW z<%qs=4K5v)g%cL<*X#w+nf1p`;C6o>CI`(<+atGcVeJ06bj-da!{XcRuR-4?xLGnh-T009Jiy? z*iQ`FmCj@!$vPP1C;SvILfeG39fb2+)Hml~>{gfgrIjDDnVr~BMH3OX+R3LhwvH+J z=2{TMb(FuuK(m1mL6hhl$*rDYPviRG?%ZCy^zmon zsx@Ib3P;3iA~@4`k?A=?jtOBT(m0iViJ;By_8oz) z;^-*rF||%8tVoinVS_qut01lwT|{JA*koK*sHW!t#CKY%R`KMwzJphu_yLUd*cmcj zc=Bod<-hi@Y28|^S-#vVj=U6n={?SA02mq{M#bNc?=SjGti8Rh7RyW<)ZtBeW`TP;GP^-GBfP7auRB*Sp{^OmM;Tnp zmfiDVNJ>~aoDb{f zxPRh5{w?15+t)Gl-#?2_KK&HRrIJ-VRv!{e=O!8JuI8f$wcvvM*4m9~w>@wayeFN2>0XA&i001bLO1V04k9T(BjfeID0Cw+x3tgl4(Ka!O@>CTS zCLDEcW)<0}_UNAEM3G{hujw@!m-1?Gc_5Avhbnc!v)Y`CjC$r+1a)`t&z?*M| zc=lNjhL3Msp=>LjuE$O)SR@5V|KOn>1aZ`2!Z0oXx4~8owqsC3U*iSh(ZQ6 zx9^C&#ifMDkZO{;xNkN~yNDpp%H1Saa@~Fu5Jw$(Ecy;~RARd4v_1U5ZYS(&5a7?g z^&&q0@S}LoA}P+Z{Ryi{tQoC_&k6R?++fuZ~wb7 z?D~Tx*!bex@ON&+=$h>bBSo`}xJ8#E2!JrB3`|Z0dY6ba$amz+!rfIoS%xg7R;8UL zP4)ezg}t1U%+v0i?7B*%NuJlGm-epn?t|*|idy%&J0a_=G;Z~%N~<0Y>O~@N=ZgBk z-L}&hZk$hUjo`($?Vq>9LV6U_8tEm6JS@1)f;`)`=sr@PKG;~H*)Cu9Yf}KQ?Cd#& zB@d@puPUNYQjB+Y#=p<3T8XQ}3*+Oq$tmnS@ODkoWWPfdeF=x~T^}K;C;=cJqV~Y= zqRnzwy2};)Br|HoU&{zNFJ-T0eO6T3!O`Uqdb|$7W;z= z6Sqcj=lnJFPEMv0`^9ontA!~Z`IxrP#A}Y1hG#R#^P~?`zj3#iba}Yu(kz^(QK+}Z zmgc2_W?h9fM;qs3!K;^}tu2b?=gGN_+QDs6?|U|Dog|z-Z98XSS(tRr+FAQgx_Y*a zV;+xO`jgt;lq{8fo7C5V&c;?coqbnYXdLYMw|rhxxdh9@({t2emoO9FVY|x2nnF9u zn1Tmj>6!B=S1LHN?EzFRUxKwk-})u^;kW(+0N_tL+A;E_KSuDCLpT(KIQ;RG0DuMa z=HdCrp8z_`03s*uyfn?X_U;A%Y&miii_cv^If%Hrhv<7(R4WEoQ&eYGvt^cpTl?O5 zKBneuL{RPmxO-%EbF=crhO-?tgPN^^s`9**!bdeeS2TQNf9XCiG%JU1hH@!)+7^+m zpr*L#)3$NaPUgeMvUN_+3Yu>I?h2xL&W@1UEooijx?ZzctkN(=8aj&G@hh(fz1h;4 zNpLZRH$U7&>b&Ga`Y5DzrFiWU)wNf9J2nLC zpiNx3gIMlnsi7CUX9u9WhS43#`1+09x=V2>$cL*%!J1uf%h%X0vqiEW*_vN$*TSjC z>!~X4{F6V!H~;Y{$_wXW&z1+UWWfTfsNx&WksCm$rO)j_2X>A;g8BEC;>?^6@$1|E zF+Q4m0t?2LW6Q{+ShD+P(Dm9$biVs4ylNG9*Y8esTluq;bZ7>mZ0Q11}%eH14@w~d^ zneMroo!qTEzUdsjmC?(LFk5m->UtvH0&lj-4Afr7xm@@vcsccTp#9zZ&4s?j6{A z_+9u@)tK{=*Ntl>iC;SoIj3ss*v+!8h%J+EEQK-S4Qk)1Vx6?3Fh0X>!#GE9yJBga zkJ{$}T}wb*#aZ2pTb}L z3UKAxHH2S1jNqrg3IMp`dHDTBe+d8IzYv9c;wcRF_2ruPdz&|5s@#SZADjXCPL_uN zWmHgMI6CFo)E%3)LDET^z*aZ(s}mS{^S5#43qOoX_gvws?TgRyaGvBJDVzA0s`&gl z-zxw5fOrj5L477?8yc-gm-UzPFIe8)FP-DDdTD9f7+K#;lrMntaP~w9=@n0i;;C z=b!(aoOIi?heGH|T+6G}^=+>_9f#|SVqG|G>qQXq5Q#d zpgb2?y-u5Au}?QG_jDco)FyNp@>#droY$x2S`M8Ur|%&;p(!mFt%s>9PoA8`QBk)t zSHHk)pI2UM)OxIMi*sDkpPQZ|Q~t1h?$WnYJ}oS>8>LIxeqKs5PnuJ9AL(pH$GrM; z8n=vmUWUmFMOi1@U}t@iK^8;DlWo&zJY?<}%~{gvhNPe-pa1f!?eO|2#{T9gKDai8 zE1%ne?He}cmNr39@^N|5Fv^t*{A%5I!z4bT^rNqrE` z2t?yn5WfZFc>;-kx z+9wzEb>ePaDw`9zCXcUw z#ut2>`(LTetA-zkM0O&qYq$-~3;xH0pABK`Ksu&PrenMjIHiB;$QlkSS$kg z2(bU5y|~jSI+M%s_^#b}{TC*2`tl{K@FX|(ue{_ss9x^Q=GD=H9A&+uE=68MFpKl8 zy>RYQT36#Y36Xy%s~=Hx5ix8eC%g1akEW|Q?V5kR(8%(*7-yTS*6M?zm-I!DhNKAK zao61Yo82U-B6sd^OTlGN%RFHtjhYRn>b5Ed>C!LyIS7Tn*=oU7v~E7wjK|aCPMQV9 zN_Do+tM7Suc>4~#`D5oW`v1O;YX?r@;4AxacCnA)c|%yYVnyy{BfE~ZPfj8zm4Fb~ z@ZJfOD%F@WMpTdNCWhD3^(ZTdzyd+#D$4wxOU$Qf41W~FbB`9GKxS^7+O z!;;r`dIOwY`WjpTx5vR}H@ z!OZL@>hVeiTZe7(+f-|5#zxU}*{rCi!?r9;bJxzyKwfn$7yi@s@nRgeZLDXmsHelW zD($p$RsF{x7h7k2P~149YMJI7)kGTsd%ihK+&nOe#v-398cUzuiIGDe;o?{JS6DGJ02S{e=VCu*$TSC)WruLys9j2TFTo$XjH$WvQr)}F`mf&WyaoF< zU{~)KaBoo;-v9Eq@ZNv;I(Gl&W}wZmFBAjbmA+WWMoQarEtpZimdu9ij@i5xQ?Gm* zm3CG%JO7;B$fIrYb=c14tX*F%Ru8rFt!;YtKRUiGU+>toiLJ|O@ld^NGd)%x#ly6L$4mz0Nl6E7FA>Hz zt>n3od1_eqUFr-AP<9jTQ_P+t8Z6l!s~S6PN8$ZyfWGUuuxtO@IJ9d!s-+V0#GLN# z=tnPg4DOy9##8fq@U6)T!e9L^ZvX3V;?*y|gU%n^0dLn*EE^ui1MAjj&imrBB`8;_ zSa$kcTtnoWR>^o!03%U{KUoy)N4Qy)W5SGO@duiVQ+$n<=dc_uH|<{`GdYn*0Bxu|7e znyDduqo)^4X$m?Qb={q$Epzj^(%L&;+l$buYc@Hhb>hw&&2DH&TPr5#!SuqMKEFoR zX4-p{k(oyI$0S*07o=&72vI8P{L+qA`8jJh%M)no+sW|R3=?*_+o6$*65Z@NQ;^p< zEW)L}@@nHE+o*X&`Q#g-q2!!2rsrY(ij}DR({XyuzOJ1v zC}Li%PuozFk**BsxpBJkBv%Vr@+htz%{(}r%cjj*DGd*4mgl`*%y6NXCpXrIzAkQ7E@B^A&;StrOQi=MmuSz$gP>xi{R`<<2I&rk!Xz0O=hP~*4( zGd9t$P01yAFsxWykpZDluT;>dp{QFq>xdHyq4H^W7Y0f1w&&g`hOS@7^`RkcoZ&|| zVffKaxOnXPqSEXlu^jCT&-{imP)oxhke2re{} z3V6VWYgZ?}#GEJE+uE>V<#IgvQ=bF2>;NVM9RBxzh6~3(0xn*{-D5W~vTGginayY~ zm+|oS9q=5!szfl>-Hp*XJrH->W}TS9{kDPqcv70Uk2$B_!RWGO2-@1L<}X(DmR;x1 zlD?~+Yp7kpe*TeR|3CXZocz6SVb9txV#$Jq*74+E=X+JT(s1YEET8&3&Fk*z!u{=E zgLgoE37tAGmvZO_ZuQb8JyZg9V^9x=ZB;niyUy3$$3D+yhMLaF94^dhWtRukLu508 z4Ai#wO(ykbB?9T4vGfZacLxTy`k4+6+d7yg{OnG0*=nJgdh2v>TyaH_^=n&SjSw%= zj)Qsk0e%dZy_+j@&}Qd%{!VP4)y=Ed0RLbOy4yQ&{p}B;lzRGb{p5L^{Pr;f>o)+t z2k)u1ShIR1I@;UQ-Jk-eSFhrZ@AdX#-rNy%-5bN;^&7Ps2x9S??2jGROa=j{6Sr3r zKo+W3001BWNklimd(b*Wy-JU`)wAu z-ld5nrIbgtI@Y&A?6k&IN$2;$F2T;bdHasT&={PnjW}$3vE+V2vCh3x1%v9 z+EF_a)dBM1WxvLmBi0g+R4-Q=UzsD%kYMSE7J4?%axq7K?%&hZwCeAis|yn!-! zUZx$qaRb3=-{`bW(9zzG;h`anxEIzMqF^kqv6*OPoY`pBaX#xa>EcA!LV7f-Cdb0$ zY@EG6G^#(DxJoD-+lOWI5Z&fn@-&C%(@m?Qn(|gV;hG#xv)^<2v4}6D&Sr1-GPmdh zV!I<|_I|`$__OCjVP}!BKdV+wM4K#|l1L|eIx^($8bD^~&lN?mQZGq;3`XD{Hw`P;aC@)Yn}XVLbt4Jdu} zUHG5bj7<-0qC0n6BdoD*s@nUpW-W8zR*i_fBCVfOYV8*S6ZZp@J3Yl9ERIgJeRL47 zi)#y72K^VOqbvIU8iXMZoj8v7zVZsj*Z0F)SRo4Y0Xv&gwci%~sC)2J-G zzrpO;gp70AuK!K*Cab)V_C9oPXR#)^ypT1`dbF3DkNY%>{%X=@PFc5jun9#%*h5yIdDLT?Wkit%YVz%7$EslSznZq7t6Ca`Y zq*eK{h$|ERcK{!ylmv9wrp-7%XHI6P?W7xpKAb7!#Jokgx%WAQUK{4U`Zw?}irX6> zL|E>~Skl=E*E!rRyee!K=d^qsK}2(n`f9o|rE#=&eL*{Kq;b@i#nm})r!DnN;LQ2) z(qvua>Dcdz>DDqb4rp6bdEcvvZzaR?(uv)3p;|BK%VJJTjXdlNMfYEqF~z2x+_>?~ zRdjLigAh#vH`h-ku(O z;^R*PAAcI(c@@_Yxu()OP$=coIfWXHy*P| zM9u@v)OIY2;)<>QkuRFf0WU4G_ltV05M_C)k&nYRZ@D)iox^tanj^ETPDfU^v99g% zxo7@`C$U{@`d-p`OBY9XJ!y?Mr)7)gbl4{0+_`faE!lM}v11f0)c4|=RwL%adb=9x z&{_*nxXxhdXFMA%Q5?%+82lSJrm?tHS^i$22a>XzjM}BI$YXsuh&)+`zppI}o&YO2dn(%3a2z zE228a|CPh_<@iMWAi$CLPvZW>1Xh0GV;CFm!m$rdVPI|_7R{fpjVszA{MgE&d!~qG zi0li`+CRkfZO3(D(QZnaVX;noDbMD;5=$sx*rra5O z{_eGS?Du~juYCJ^2>;D@aP`}#@Y*Mfkr84IA+mT!w+?+Rv zoAaVKu-m4luxI}PR8d0j?Yr=*VeNip(!W>RZ9A-yH~_U{;*d?G-RL>w-!EsyXSGR0 zY^nMQ4J?gj`vP%Kr=L5EoYv>wzJtk*4php8e3Zxuyn(_k-sHdnj6C!S3{CwhmVE6u z5R}_6wsB#3YIhv`?FZRyvyoAID|gZhB6Ncg;#)!?tzh3BOHi_If~sWYo#l9m*$sAW zlJ*7WdW(U*zX`}&PId-)PRICmEB|L#ke_)l-bTQ!KeU-~#+ z`0Vp>_|Eor_`aViFBJ~$*bV?#fBYnteRLKGLj-;arKu{S`XM`P(+^t*2vLO}uf8cm zq3BgrbqTVqdSn(b1q|h zH3%?1F<})p@O(^kbf7dr`=`&i&$A^9WC=6~vr#B^g56uUi|a>XBztHhoXs zt~y^E`L$&Jw*ES5XFt<9dEN1jc_w6Xv$F^z+Mkj!<#m-@*+plQ_AFC-*!P8ep0Y+c zZi{7TM7}c}ML5XknI`Kp%D?E$x{?weM|ieu9QBwK$;-eb9CeAM9MZ3SvB?AdYE!_m zOp;pkGIbT~3##)jk6`HXH4ul}N_!io%H_Bew+8w#k(UTo!?NK;ST?)}*a6@(z~s~v zrv5ol{jJw<^1YLoxPA`ny?!kB=3vg!A5$g z;}p?-{qa$BU;F^QV>j`^uBQ>S$(^?CV4kx9(vEZklE@VM*ZxK3I@JQoVTdEbJT{gOaoHOhBFF^Q8!z?5!Y zZ}d%9sg5ACgO5jMJPOFR8S%Urk9Af z<=tcO!w?siEFkGOR+{0Jw)S*=#DNry+oosaXsgE=?YMa$>#RA599EzZMe2z zeqoN=#NblpBzAeYEJo5w?*Ohm^CR%96)gMXU&GDqPvQE5&trUO2|~ZjwcAXfMV&kS8Z(&eIoIOR?BYUTDpNPd@eo0D#2{7T}?6+i`T`CcOIi z3gEq~xc!g5ivL`uj=P_E;wcOd4Q0wtg_9fCBPjXkx_=*67B0lD{cppoeP1c4eQ^q) z?3VCD)cBdl)H?qMbatYk20WhbC3_Jb^G~(H;hz}U)8)1n&B`8&W1o#j z*}N=wGfX#X(#tbn*SD|I=B*ZCn|I-$tBEw_cCTw5x*Vs&L)*-4Eh3LMnVUi25>fPX znB|_+ltDBM$jXwx;m72#;4Vs=;-(Gff;7$=Cg%n>LQGSoDcGl-7n(_+ZlMK0MWhL$ zrz#q~s2EAFB?W4_zjU;d%M458mFp3%d?Pj@w=UlmcQDphiItKn3O6 z{$oDK2czjnq@%ix_M$Gu1_KhG|6~$iGs@e}OKkfRkviHRtr}lvjliDJ=KNif9mhR@ zab2e$hK>v*4;(szLp!(Q%J4$teKZG%qd~GRgN|-o_{={*2w>Tt{U7iqCvfG-zk`Xv z;d&Rca2z=jMsJ}nFFvp7u#PX1BhPl&u8OkMo6Q<*x~$G-TK`GQZyLRxb`i;3c#drv zS&*hYHck_6d`yo7~5=VAA?S=))iJsUU6SfNTc3&ip?R*Y<6IwMQp z;rUHcXeQ~?aCGM)@^Ug^3S_r0>ZVNgmG+r*^TURftFU^>QiRV1xcm1$k3WC)Wd#4j zUjP#oeDj~*fxlrv9Cq!pWq4@Yj@TGQZ4WOD_BKjx>Nc#)xj;Y>G53`hRxZ^O#nr_Y=mYCtrV@cHMSLr+(ibNpf;vq!i)Hnv~}=~pc@2d2yVMCTYX6Ol&0cGK`|c#1qfb?D+a zT(X~<9cE3AtXYxmC0AMf^D8%5NL9Z1w~0JO@htm_SCpHo^d1vl?b~5;7H0D?IaRB9 zG&%3mht&0$hyQ~NvbCMQe(CSzN=Co?ws@VkE1$27H>cs^Gue5rh3Nrt4AF6J9UBl; zPH{wo@a)hq;&V#%R^q5lT(|=OVeJKCzs9~IrXGMiNtCsLNk3rjiz?Y0j-5aV;LNI( zIK5_N#OXXAlO5^4AZ^0qyLLxEo_Z!#eEv1)8zR19BrF@$(;2q-@J`Q^>lzv_ttRz z?>DU&Y7?KvPA5!@d9h`3iQ{@b3ES{$Lqn8`jbnhm->3+&T|Rn|p$L-9FQR3}mS!D= zTWB`ei`4RwiRb7GDiR5SMi@q^nO3_=;KzOH*&?nT|3}~A=aNbi4`B7 zfsX)F2;tR?1=L9!phS(5HF1wO)WQMOguqhk=<~+u)Nqu1 zP|rGO+{@2Ac$ujM0{7Ktezj-gAlYb4kMSbu^yHpG{@lhjTvnugY1xLe)U!Y8=YO*} zE#qVMju9paUd-2B08Yn=i>iM)Pj(rbRKk69jgO~q2eV^J9=upr2ASh!3oQULZes3@ zNomqfB$Qnb8uW2G`0*Nel_U8SSa4~*Qv0|$@b$c_iJ<+eq+R6@BFG4_t`PW)GW zp8&Q#gunUT_b}R5M)=#`M|kKG0N})9YY_ZGh(~tp%q8z?nOX{N3=U%dzP;G>##;cW zI~5VXQR9YTTrjc|YZE^6Kjp?vvs8{c6_3{X&8Q*!K{jbt%sjxtv@9plIcrgY>hP&JoR zmp$n$Ea!hJT~t;VW~YCB96n8bTDJYdRkN3;tFp<6N3wKeT%3j#xw=b#SC2XBvBh=e z+FI+hkc7S$u}^~Ai_kO{i5Cjbi5NCSh-&TIO!9Qdv5z3$8=HOp*zK=S(?-iR2kju{ zlc;Hbkwdm0=RmdCsH_niB}cSu9^>%6?DSczI2~!d_j>2xyH7lBSwHndDEwvZ6)NXt z@f>BedV5{l?duqL_d6K+=wQ&*U&TcmI&raA3 z67_p%L{qo8*v!w+F|!5&Px0HnzS1~rrz6Pq6m_HBWK>WKyJ|tQNGEOkWr2-gN+CCP zi=jlg3)5`bY>>@SyC@?DZ;a5_keiULGs@`~CwUm(^l%vuix`hvm}#&Ts(B-)`U#MK zu8O4#=1*M=Gk=-D`iH&ZbGuFXxFT)40cI8U=Klxd_ zvT_i(Gl9vU`J*_@i=BUg@=rYkZ|^c}TD2P6H*Cx$Z?bFnsdZ~n^-EZF>U6CZ$X;8N ztdTmUpMEB_$x~_GXlp+rh(;3Go4H~Pnh&2&GF)U5q2*!C0wEVl6t2mA`G|I83v=G_ zJR7L=Pla~3@`a@`?ylQ~&hsB)@wfgTTpxWNBYQuYxl~2X0F5T=dEQquaSa!qJd-)| zOle=$8q^eS=EHQq?mXEfDC)wex$X`(sVsTMt?%T?^>k42a2tnV6GxVDV^cg*Dm|m) z(-ZS`39rAFzFyrO)%n=!GP$>zPQ2Hb(S0psg6mjmI|jEfn;{=<(mcPSHHe>;#8sOp z^hW=xwcWl5dn4z75<++=O$C^DWdyt5JOKC}4({B6YAK&j3YUBz^9BZhfdM?Vcn&I+ zDzIidj{eFYxyDQmsbG zuG6&klEOKF#4$i+d%N{TK4X_G1)btCduYAe+h%QP(urKtv&k!c zd^IOd>#*&`qr432@X7PV!A=ubX}kQKV0)j*^zEUVFO&TzY4wx!M>%&C?@PAJv)sb3 zQeoYYTtk@Z)|Q{sKAF#WAy-U1A&jh^lUlGRgr(v6wB>qBa!**fzrbvrAzG*hY*)#) z4%%|PSf2-VMI}eP#w=b3z=UCAdGXhZ2ygM@tAxdn>i}wgN?~pH?6Btc9r04H=8(;@ zpHl7Xz#+(v+eF3n<1c8@FG+Xa8^@C`eg_^xy#B~TxZmCQFCp>DEOGq}Kx#xDme-us zGiUOA+wJQpjgR8WGe458;6k~mIxd#RgM2ilWhD1bzy7SAv2^f$bPo>y);Cf4r(edt zU->a@*t08^qf#nidd4g=(CSSj@GnkA0d3vE*1zvtR#KRAJ z=;_Ipmey%|I#phlrIXpQq9tuj*^!%i^lmjB zG&xMW611#@P8Q!rm^Ou#lWuy(>@2K@OaE~frR~aMyO1|SOh-+s)kX+?yQqwEW^$Y) z>};B8dtcgdRU|93)!^NNOZz8#svW`BnVhJ+O5X*g@+o2>959aClpqIjDI(d{pQ>WX zx%2SC5XU#=<2X&wRxV@ZsudXc;Q@qG0q_G)#@Ajw^bW3fRuTTu0leGu9)h0@uyfPq z-144kYr~n9DZ`69iTjO*`Zqi=Vs7nnQbaZ3QlDuGyIL#zfrezh8 zR6{iW%g0ETItO@X_YT~h+p9@c$m73#2wvr$ZD?uvo>yJ~G?cb-kbz30f+lIhdS z2K!eSXBYCYu}wFqc(KTo2ul*3FWBp$WK^PpEj<%*dk(Ywjs7E?nB6-J;79$^R2B2C z-hk%?*n0Q~j&I(CiH?qR6`{bQq1uUmP zqZ0k_c3@r)Hm+KQh4Y3|=Q-8hhNIiIVB@jl@GH^F%OzA9798|0(9{aN8<&>^+aZ8?&E5>4c^?j*r2R4q|HoCEn7uz^% zvuUXE%c4huElh7M50G~HGUby>G<)vu=WbAhY;-dkHgqOo1P&~ z&h*LmVpnfo3HRWIA=<_#;UmP30|ycM^vhD07B9v}t5>F~-Lx3Kd>QNCJ6UTTAL48t z#x+345W-NwghS#SB*ziDF1(MP50BvepZhgQS~}=QGMbjo#zQO$0e6m{6{0W|v|-1A zcku3x2kdp|o_0)CrZ9PH)EKlXarIy{L0Y6#!kzV~cb`qpS>afz8EP+CDEE z$VJX%%6b9JM2uzeQoZFRNij{|aS^A}8e?4IsR=4gO_rvrU2NOKt}XH*%I19B;=Px6K zhZCFf+i@EJI@;Q>U~pb^uyB5S{*m=VxIZz06R(Znqp!Y+V}~!{+O9S5erP+|+uQKO z?!B4wp6KkrSWkC?s1ebc|Ljo&Qs2BGB085Ghg4*ZHHfGQolW17ujTdYm?X6)ayxwRYH9@~NC!;6gJL*^g*i(YpzCh#ElVH(e;`sQI|?*gv!}7Kwl@uKmQQ6ed1y2@a>3dsf6>(mZDs(V8yAAP@bqTpQ>g*OHFs7 zB4Rq>#ViA@pTmjFod)qa+WuZ#PM%eYf-E_vsk<=HJHZ6*EbPGUAO8f_uUP4DA0byN z{)&9u$a7@K(q1j+A~|>$gxQ1H+7t3@Yg=8u8DLvZ+cCnGZ_8!?H=g3MPPV&Ol_e<| zE|gwVJJ0I*w77QBh0PCgUQDm@eVKK>CE-IMybP-Q)P=K!%t1FgFHe(q5>CcVu7UX8 zDfUk_CzL}hkIL?E>w6%tTbYu{$Fs{v%rmKv$WqkVc*HhJ+A>s3LA|M%4Ih`;LyC0V zZlMJiu)QwJ8p1RqQhk~I73D@Y1*42m_Dm8cNqIGDPTE23YsY@9VBl?_001BWNkl@Ec0xk zS_WuuAm?Zpay_y(__5zXbj3&SoqO2)?lGL)xE?nL%`Z=<0n5H++IW)BiFeH3k$LS& zYG?K^roO(&c{?lYyb*Fly(evx7(J7X#IxyvAjqQ)i?6pvv`c=1w7bKtIe(k9U7uAO zaa(p(OodI$z6^PdCAxIXVyNl5N@gW-T%Ls_nYIh3zh+O8^L(mgbwRJGh-$JlI-)E~ zOC`gk6$f02auFiLOrB$9aH&62SeN>;bCPVH`geD$U`?Eq0Fh&s1cY2@)~%O)@0jkk z9ns{7y0Qe2Ixc%CPgJnz+$EGN6~F_IZ`zpKC!%E_yN7lC_;XmkYXh#lejF#ieGuNp zE|mWC7`zp4!vE3TKxZ4au3Lxx-npsrx!vD~v#XY4+39n&dLcWD(f!BM%%lWVHnxF{ z$;2iNHh=Z}O?ykoor^w?UA4NuV5*AOzw{sR{vUh?n||vjv1#=h^k)4AQmrfzg)dpw zoh~hT&3OPO2ZwQM`(x;R=ey`Uei-BPmSAFNX~rB?aDVD&E9x~;&qkh@7OlE!CP$Sb zSNvj5_WW2CUY&>ilWyWpwll34kHbk*x0xUFbEr!2)2C4cl5>kqU)6KBjh|lxATa?m> zU`$w%A73NPhls_LeXtsFJr8`D=yRMoE}`CpMKYC83z0MG1%7+0NDA9 zKLms!s`n@G-q91d|H>(xxgPB(b>pE;== z#8g}xR3%~^v;mn+EJ+pO_){Lejj+^>sezTsFczgv9X^?pD8y18OyijI8@Y80=dWMI zoPoL6xN5ay`P4{?#q@jx>c%AJw`%9H{L09_BGGb8iqL$u&v0ub!vMY6(>3*GgNq<-?{I5l(6-ByUQ6E!qTnYlg=*tkr!jc=Wn6mt zi;@)RQxz)OGOzY)HWYnN^{lhB4pcg%F~sKmlF@84@HbMJP6|zV)P1Ac&m_c|S)weQ z{=A);*mY!Z6BXq=nCHhjPAp4PA68#BeOS9bX6B+UFVV8`#X3s+60It4^LevmQN$DE z!v59um}Il6usX+WHYGcu*_FwtQKaLxn9p=Y-t|-ToSvtE9CCfyo)60)aw!s?vSL{r zlA;I7py`#QdkSR)k*rJhd5T_M_Jpt`jS_-b@LhWPJlLJOZq6G-wNxr>M<@V*=V9-^ z`1=Ts9LC+>dmZ6NH{jhI$K{dhxH~q6E2l5w_)Ggy`ms*|0G1CAqip%LB+7AlM{UuH zz(Z_po;|YTM)}SS0A)-Ltq^!rQ5?X=u1ZRfjAi?LT)cJ_C%^qR2KHaYhkxg(`26xk zi%>Sa*iL(vZk;6ZU=l~P4w)=Px+jQ+QQ63g5Qb+eXKp6UE@oI9ro-A~I+Rg_t;4FT zT%7U8{0f%I-O7MXqyZxhSNLp%G2P(^P$r8A9)?~%!nvWzbF3~V3r}`X79F>Pni5SE zX|kI(@7BvYT@!X+0@;t6I&TxsN?AS2V|~UcJOpBQ=#VK9$)|I497{*fquN$R#V5Qu za-qJqU_S25O}9Cii1}BqVa11M&_8kuRrsjZ9JWO^$TL5_R#=8kt^<6#ur1no=`=cS z-NWSY7K|<5$mAePi_O#4`b=9dsgbbrr&p`dDwlWES7=(P&=#d|{f+nWVdwX;`U{V0 zgR>ew|J(fhxs{N%hughnwWiH1q;lGB#)`>rVow^cJj+hgf*#X}OpC3}F3hv_wMO(M z9bq+#oVu{`YxYFn2A=RY4R{i%LOQ3|{O(t6IC1TBCdW8cnzD&czhp^Xacw7^AtxEe zC6BE2t}2T>4Yh-VoDlQr$;h{RTc}Fsx}YhREURj;Ip&DwGZHjgc_`e4>SR3rJn5?< z2@aKi*)$0uLLwYXM~K8sj(`9GswmZ{H2Gwect2EN^}-M=qqjz4z`|rGm8@Fy_$-a%~o70Q_-Z{83 zGJ@4hml@O68#s9*g2@nA4?~-+Q?)Fn9O=qCF*S*U$KOK`1X%aeAIG)Q1a5x#0fy%d zVX&`H8<#gV@J{jO(opIjGVx5%waw(B<(RlIjIL9M(7yW`Ci~Q%4x5d})W*+DYBahn zipsyy_mvjnyd*n6lc2jV`!+N)w0z;t+f*i9mo#*OwJEQnpk^-edrJzoBo+Jq?QRE< z3o7h&y^}dFoQv`GX~-lXlM{uRv#Nz)xo|8ClP?!GLB(JBoRWftEL0R*bYuV%KR@T~ zB*b)@1ulK6QRSFzu;sRDUTgZ~xoQm63Ca8(Pto}(Y$X1%a%_~A$DJd8eTMT!lCBS+ zS_?z=`HH^2SX{Lfq}`#Z+6HMJ?K4-vir#f3uA{ zck${~y!N$kVe~H!$n z_oyysHts9-XS#PAx$eW|`S0oK!lKnnF>!hnFa7S$ob@jOaB!o}J^in2H)~S!}qCO6OCjBM;{#j?Elf&(ZbJU1w{|i&tN!(#SYd za<5Li`&8wi&d*d9mXnEP-i>tAN)?qoQAJ!IzI$#h+{=oYeL(IQ}E1ely`bV=$9 zlTK)23?k1Cg;@02;CTp`@H8ITRXd8|$NORX@kU`{7%x6UHy5LvGi1)uxsmdzApXtn z+zn85+-J%kaV)yqvo{rB&GA#Uc+pGR-J@f;F>eq6Fy7gTk)d=t_q^*PSas?&`fl7t zwYJ}PSleMcVD5lz2mYLVRwRs&jl-hz$`znA7k4&o#N@z2&3r9)x{h+>&xx;Gk#p?U zuYBzj=ISx|B+Dw^yDf%4wF}p8-Ne-w-^Iz^ZllxoSa&zB&7Y5fYd5sxvN-R_%c_o> z@0edd4&7`hH)8Uf9@LUzx|KH#(vo4;C_9~?TVk5y@&mN{;NeD&vq64GE+Vm=C~YE* z_W9)xp0udSz|x%PST0BE?lsMGpfXe>4gYK?l?W_{qsGVQapr@+~kM7(R9n}7IEgHb}KX?r{KDdC7+Q+a6-59>(b7k|xl@zlmm&#bVbSc8m?!&$Zci~%Kdl8pTpU0!0eHw$0?lk5sBKml_ zX=k#eV*oj?GOpU7GN&JRmu>{kpT@wEmvQB>FBCwwTd>7!nwRR0dd`8(FyH3YlVqd1 zdF5;pc4WEG*sidP?baqPrAQ+pXK$aZeaw#A>BTxbUYzHsmXwQ4{GBg>P9U~*7}jxX zJ~wq3^?8$cEQ7f(*p5kNJ3~_Rm9GR_PL{FfIJ1C&5M-AoyC$T-VZ<5;X5OkKA_^xnFI2VZ@o7SD^* zcz4@YTw1&c70X?((_ry}1$g`iKaQ8$Jly%GUjqQV>0poe#yUL{mOOaq$VhqR_>N2FTc4x>>)B& z>a@t;gC~h0du5GRVv_gI<{>*aYsbm+GEH5y@~i7NRHT*cle+x)E4)L$pEyI}vAL-n zvH9L-Y8Spul4**L+bSNOMO(;%Msx1zgzoO>pNIz@@Nn{Ehf%0tT25 zBi+6YOidM6#%vn2yyv;4Dc6+Q-~5sN_k4&uHn?w9@p0&;VnLiURix=Zl6w`b%P$#& zy!agZk2+_Q|A-58R02OvgIpE$-k|onZct`)hd`-M_FTQg{ z?r6Jp4V@z+Ky@5b?X-jIoTU-hJ57gP7e`h$p4daE?S=Fvvd_9)&7}w&Iq-&+t8nl0 z4`X8IFossFG={%9Fn|x&uEy?bHvz6LWorTc7~HYz7(IK&^e~KGnwdX88gH|pIO|yr zt;x3jmi-gt@hT$RG7`+_uTbuBXaIBk>xWW(Z202`OfG9wXE>tcCCyM{SQerX-mq za6yeel4G9<>BGao^;;OceghstOm(#5?cKZLobS%|9c1FD@PG7 z+W;7xw(s@!qUY`y{K-HYjx7-}`A`FnzKkw+8Nx%ja4Aa5*P?HKwrN&u1wSRV}|T8XV}j<2k|~%K`m@4 z<{w0Q445<{iM3RdU?cID2;N%`AB7i$xUh5yLf=E+XLHC^VZq=ap8vw9@TUXq0D$1< z{~RxOwBzY7ehMoV+4EuYBDR_X6Nv6V8XIXCV5)5pm9{y?=hnV&@*|;)74k2#7YD!O zqukwrN(0v2;+)LdY}Ag8jdMn7p*hg(9I+_mf8TkfXVP7=q?|oH+i_VHMnCSG*ZNsr zGBt%)l|u!&JwUt%GdB_QRPki8?ogFe7SG1%nLn@Qi|h=qn^VM6^QqGn9Jy|%v(vJe z`k$_4b*dqoHs5EGWuvP`-ci_wFU#EB((x+Y%8PF|u^)+HWNEqfPgVIyIJRdb*BWe} zVEYN{XwAD=laMOg8qW*(63`>L<2IX)465~(4eGhh>g)un)nXlyi$YhIo0H$FRUTHX zkYC%nm2aObSAh543(?&TJoq5JcIZ%un>WpQjgJGBihbD{1<^+)`K&|`Eq|h2Flon% z!g|6}L>#yICxX2eg%4``TJz5WISRqLiThy3rjSvv>C;SHnOWW2Ly4I)!#GtsgAry( zoV9t20v!{H{UC_1&AD|KTMxdAquaM)?;HEEf8QRAcXldA0Y3<^d;eSTD^)~}+N{Gi zanSbS?a!()1Lv>PwxRozlhK;CA07F~@41J+hoP6gjGH^2#GTC#DN1RlA@ids0H)Sx zo@`CC>aEEZDPP~&Vr+aIxr@2iCAs$(GgcyVOnA3KfFB(Mrb4kO{#$Zby_iKv*NYVU2zeQcKeFg`CI{i9vShE=^Rh@6|VAig{?~ zcHHXk$5eY;uAhn~*s^9VwyaqTJPF_*xy7ZW*N>p8F+^rIO@?U13Xv~y$T;-VbL{V^ z4kDvMapgU_bqh+9RV=u8wN^?wZH~-8q!-(c-{v)?Z2qY94&d&>jp!IZ2!C=ML3^iF zZZjRCRMbLtOotlH^7N}1#!QDTUv?9E%yWm0IaFQ}zD#18HsSblX?U@`Y`t~>3Q_OCIcF@Jwad=(7 z;aAB#Ormj8eCEr^@^yU;B*&37oH(6>K?}19E^LSA!YpqMx&F-dagPg|48b$xXy0ov zESJQJ&eAVXkxwK?A){YGoHAj=WCt$#G2>{QB~IT&M5Z>e5~|p6>;yI(KaO+Dm*M#4 zO|DgHjk!HN_~NHN6CFJJNuaHSQk(f@Y1R=*#)YZ#Gb<8{X{g7Ojw@%;d+sgVUqr-I zc4R98)b7EalmDiOdI-Nyn+=8^+l&`p{#W>uC;v&R((1sr2>Vo!8YD9Z9nZ;A5yrio zw=Zml1K#59tzRblC> zgk=(9Jx3vBeTQw=5Nx~1I55u|WKXwg{h_|DO3!{w%Ch#^yxGHz8zIi0SBI%qfv|zo zuJ1?xMC{t-al2sWiG>S+g$t8)x_!G{J-_o#h)b6uhs2`b!lB*bBzvDMp882(`y@Y- z(>WvQEyF*9h+UwmR!yH;cDy04Op~zD4%tB*(?hf)H|5-6EiZBWjn0=4#J_3&l*`kR znT|gm6Pw&!$Gr*c{r;N>;A7A02e>keV-eXUn>u29HRtRSswl;d*~FQf?66I_IM2(I zqq@kw*)n_ZsukRN;8EP(^iUj@Z)<(8k^3;vyv!*iQbphBHBD1#f{x;X7^5G&DbvuZijjBCejS;4BvbxG0d!~Y=sn`-ZwTOlcMiixh!dMO;LM5@h3+`!3bK2+jLfnm zS!NjI!$+Y^xusu4vW7+7m`qzy7FQwonv? zhBS@m<Ur{tjm{uxv*g5O^3qcLnpV+^EG35SDzr_UOaf&nvsY^E|YXFIqW%*(yk|tt3w*Fj=+{r&0SA zhM4M~kBNoLCCt=*%u@9+v25b_%=ZzR7X3$G5vDtw*~6>tw4D}7{>!p>j|mg~@`Sre z-lclpCZSu%AEe!8BBsZE)whhzQYX#KxpifuYgd(RHOYN#*T!Q0VqW#J>rswO?UqT% z_%f@7v1!rSRgA0VSUSGTj#)PIt5|Y2Eir9A3@tg^CX_4Dv$8VqGqR5Rs<<3~-mkd; zvN72>;%btuUHN*Jy%#Y@UH=W^G*$gNnVOnItN1h9PsA{~K9me&QyvlgGpBw^X&q9{ ziPgr$@ce56;Qc36ASn>v;gjgjB;nwFXTm4n2L z9JHg~fw0pyd!9NE^Yu^al=5?Wj=cj~FA)ac{43nv@+j_Xc}Pf8&g;b)h>o$IBz05# z`XT&J2LRv4`d@qjkL=lF3_pD7GPWLim)Xr+be2!Hs<>K;AgfCoWuTc??ahZ7<+R-_ z#IatOtzEs|?QAossFo2nBA6^kRqN_wn@q^I1XdjIME~M3D8=pk_>99oN&8+xyZ}@a|fCTaGIoF^dq{JV1a_T#6*jhGBL^Aba9$ zpV;Y+W5+^NDjwFZZFEWUMT_gsY&3KGn#!i17f2X=n)@nTwvnHatpl07*naR6Lhnm+>Zk z7EY$YUKjJ%^Dy=Os4SzlpLXcfjfC$dkp z*nj9bzPE{e4$?H_yxGPdK*zgXId?r!tpc8>e|K}|P7hUKbK5(2fVbbK^|xn_hdFbK zDPvok^Sh-DN2wImYZ}-pP*GUBo|9FFmgU7-8L5`cj@E$qG$p@#CC*y>Q%pnqV4oy1 zR8Bs{`nAjI+*L?=sfhjui^giDvYk$0{F={Aw*@LwO-P8%mblt zl>F**W=ur`ncvZdvc+2;ei)!!t)PN3s%2@)5P>3 z)cImIcD0$<&MJ{g9+rn#8}`OTIkigzTVj`wu*ioK)3MDv5186bBp%T@aVeJ8P{E#e zgH4@AXGDQBiY@Dda#55wCV;CC*>Y4SPq4=_(kwTU*!CY?ICi6mLo^OzGX`g3HGIUq~-58NtRi&rq1li!%XOGRzsx5Reg>fm-+Is`4a;| z6nf9=`*Cp34&3SM)0QtrdkHA{c>BGh2;X0i2iC1OM4&axnj>U$8!083Ya#)=#9f!c zb*vwsy9ig-JcHg-2XSlDBgXLdYufr_{dx~8R@5)QnaF=kXwH@|7PiLWv~imWGA@uc zybVvb%QHJqHt}N@UL#%?87H4de!MtqpVE!tq6nK5XvH?5s{%fcY@q9`Bp0IPQS}{u zT_`d!wR41e=PzA3#IWjP`85?&RM}E&Y&SA9ybf{(tBynM2>iO7O-2xu$!bh;Ya|X?sFkGFl{`A&+~?LJ-c&y8Mzn!k8y}2xB%(_=e92 zy!2~QfiN;g$3ZRUDxyy?hafyU8ohmZvBNhNe?9nNh`yV*vH9>ZRLeeBXE){z;_Qm$ zrmD^bEDIxb#nvrb@8mc+o6BGxxANjpA=56bfKAWy5n)Jfj;TLka7PqR7ON>!(7 zenDd1Q;YLAzdLAHap%$A@k zzrHO+g@T?F>oOUi<=|p`D6W}Te>x^0Tdk8ciIT)$muqDFN|k6?)P566ev6zyyoNXr zohB{bi@mL|J|p?*(;s?*Ra~&PPLl4pW=Ez3;EVpCF zI`KUF4AC&r8J4Sy7CO{khNjOO`=n5ZY!Z$h%PeDro$+bNo?;J_+f#N+Hm4%ni1{(+ zCufuM5J{7`SyMhqH#w788QIcNg)`~6O?WrGJGuimzY{k*cF}bCv4rKbLoa_7*B|)| z?yY)&yCyHM>)N*XQ7iy`E#3y~vSq$(YD zk)@06CCbT~4df}S3A8GlEmWc~Z@?DACrK~c2YEupk}`U%BWJe#hd*a$a4?0Vea}SL zljqcsg_GZn>PotP6J1p~7RX4ln4Y*8QIlo)7&6lqGcDL7-&rMl+DX%q4D8G)`$Uo2 zWS%4mku)6&$7CO}h|UoLNu+0*LL?;;VVk^_Or>np&PPIZ6@)$pwYQ(+4^LM@bW|od zhw|NT9DwHm$F^?9ZChvI3@BBrXq%WswdR~n337>fOPV!9bYvZK*wK|5 zQRsNe8eF0?gv`^AcmeEZposyY3ct3`dRS}S5FPg?u-Bqk;& zjp0shSOBya?PfIldd6|Xes7HUPXP;E9eQm>=c(Q6Go=+>u>q%~IR9{b?<9}1GBF{T}ezJUJ zDXRO0j7!pdOm$7Kvr+<^R#BW-7oJ^T$jc_{VaeBMU4%#(Co`2<)pyi(m1JC%Ek#UQ z)dy*KXhN8tI(qMHzo9Y?UpI2;iSK=SJB3}l)SJ`hH$Jt{f{3U$lV`YE*;71dd zCDA97a$L$a$j6rX&nFWe1cY%6BK!hj?Tb|aFFjM1$fg?!z(IVKef61g>nPX$t2YJ4 z8Dh?zdjL?VNuX5X55kD^&EaY6O-^>S7oduucTxY_77@%4P%h z9AD#9FekQv&hZJXKXDQ#H<(^R2GHLL@9*sbO8OnKSrGYNJ;%$}KwexIwicu)o~+*G zWBK&ryUl{+(_j-v7k+wh@8r6tdCG0#9_f+CJ*rqqUZ~G1O|8C|R@ZX&n^cGNW0Z=M zsL#9Cc9OHIkkspBVc9imNVo+>1PPO*2Fdv`wl(Fa)W?5W^<$em#rApe#(Yblp8C@tT< zcMljFb6d-`wE;sz&RMl!3D!Z#dbG(IdoGOgCJJh_VHC|FK-KEW;&;!EUdAOm zY)724gb+ZLbJFI&{2VeRV!1azs?*X8y!9fc=FY?Y#cNURo|_my>Sw=WTT73~zktG} zjNa4h;2k-Riw95P$onTPHV)II#m#x{ab-3Sc{p(eXii;(%L;EgquflSl10l*k`2w; zt}L3Zj5ea6E}p9>%`W!!gO$xLr6K3_X{F-dI)aRKbKXTah2YF5C%32);Fa|_LgH0D}$Tw4Op8u8?D3EibnkSbmFIg4VlqnlVtKFtVz z?W4^kgwM=z>>cv2>BA+hOfPztK)*Y~0A0#u9HIAwx-fZ{3BD5Sxy^hm#xE z607i|Jw2G{>|pMO_OIlc$)+aV z43jKKZwxv*F)_Fh`0!+=^qK)5eH5Zx_ON(ywse|}tJq-rwpx8K-Rq|r`lQR6&=gj+ zBFVn)%)%>^Wl^QenvG>)WHV(lZCMzXcGmM!Ss0m^DwZoLJ0u;XO!p_IDVD_)M^+y3 z9KS-5OBWPL@gy0J=VMOBb8WjN`-M&4k=s#{E1xu+*lb}k-A}Tf#Qs7^_ zu2it{^ha26`V72kh)J}?FDw(MWl}EzSAYBnte)wayzbpbY4mn2jvO-Ur`45j-8iapw40!6}KzFw}PJ9P;b4)t4#{2rg z)?Oh(w3X)r8?DDRPL}-C@umZcX&Vft+=yZQAB^WV#T~#8ldm4Tq8Gf5|c= zuklEpS8)_ixGtMjRkqNim6{E&as@K=A6E{}+Nnh(S3R=p?2K)$C%KK7Ub9;#kUW!V z@K?z7AdbVXQRO_F|4UYYXf+Gk|_N2Yklo)2AXdt6P3 zv1E3Dq(a8pZumA)*=EE#CuxhNPqv4edyDsG*N)R;mTSR`;b9MBVuatf9WXf3GrF3%a7io)nVaZe;MNoSD@0v zI&8DH5dFFnY~Ci2TqF-f;CRa`rxbP}o>6G?|nIFq@AHMWTLU^Zsho1|1}Cd09dOgVmn^K^!h^3LF%|jqug=@tCOknF7wAyby_quLn%I~5->Q3yw>FYR7K>zYUqp$d)DpF{ zT2iaKt?}5Hp7AmscwYQ4fc@a7u>l+Ko9#D0*cbx_Y}keYzt}GgjP2Qa(3t5>Ew$8Y zNt8%Yq(m0?;!-4wRjl>iKf@3CpFC?sX8y~)w~F@=#hZU-EGJGxoO8Ytk&zk@Mo^Y( zuda(HQr)+gV27x%yXDh_{qakfA`K{AWf42p@orSsv@zR=|| zL2?vg)Qc8L^oR~wz_hUfoxnY>o~$0Z9r)gRNdMn2kT&lIKKJCnR^$W0(eJ*pa`GJ_ z_h#)Nt{&RNl?(6R@FwHJ1>n-9-R2^u8(6HnPB#L6?xWpr!@Tv!xHqn$jFF>~HP zMPn$&V)2HE{)Njj*O44@7}ew7sC{;kq#qM=`Sy7Z&k`rm{TwdNjh8Ym=K5vN#y-Bz z7scA*G9qp%htIoDtEF3R0X8?WON+kaX;F9BV&VKEGEr$X+GXA-uZ<`97*vCLwsE>e zo=t~|TiwFvL^7t;%c=I7@j9KzRY5LJbL;s$EncQg;PaE|w7`u|uHeyM{tD9r6KqWm zh}O6Dethg0E*?EnkYh{-uV2UAZ@!I3Ui>wtn9N>Y<_+8WbT7G(Dy1O%!>5&harp|S z%>>(oQE&NWl!&O8*kiKi zDzmM#QT1H=hK>DvR35GsfE-H^O4c3*dla^9ail?G?>>tAtv|M+@A)xPi)WO!a(R6G zBJPL2mgyA9-km?ASGFTsch;0t8GW=!oMcsW{ycE*-2Um=%cMK* z0M4JU@c#R&^_RxrZjZ5j6tD`@>KPVkr?Qvg@wm1Dskn2*i=2(4~&i=-A7KU+HfDHR`(V((pPg#I?oT@*mVQ z;-cE##^x(OM_nDo<@=w)_Tl47rV)+NS$%k%?V`1iK3&O27)y8Gc_$`+^EZL3Te$7i zsowM@+%w$UUNkaxb5m6T4?b8e<*U!5H*J49x@ENnXlG?OUt3B%=7YpC@6EF8A=@!5 zxat8z9(c!fm82iJAoGysykva(7p1u@3u1h^$^7jbYjN%&`J^M^M`cp!qEaL9shtz3 zv@w^Zd!?SV!4EBA4ZNh|rb~-kX-|T-oKUK0o|Fq)BRUeETBaTWYB{F7aI7ry;Z(i{A6n-sSa17JDM*Em}`E=WDfQ2e2PE@$#4!}zL{CQw&*vD=5JX!tZajgFO zlwTOukvBX4^yUq?lJjvs9nF;5O(Qx+CKcptW+W>YjH4JNFC5pZOpfPKnJu!cyWj0s zktV2+&;VP&6VLu)mWEO2o2T!=nTH?3rNf(p`eftERUG-`A`X3W8IS$qC2V00soSV6 zPuSL{Z9}yb-EY|vt#dRs+n#LT>akO}e%nbSrLm-SZZyUcxHolFf`2!&xQ84|x(D+M z$~n4a;}E{_n_tEC{~DMaAAZWVl$)f=w2nu4t?tFq;eEPUXw^6^SN@GLnsyc|&f6Cy zSz6zGo-*d4<&P`vJ?F}|zAEMP{;o`6f93En=gZ-fT>Uc57%Hs?M)*wL_jpl0m-t0n zUuku<)zYo8xVzl8oGc^Ky`=M7pR0x?Z`qRgE8C^p)Q9JW_MKio@z2<%Y7`e?J-zi@ zkFfk&sKtEI8mVqm)MnZL(!JpF7 zDYwTCzEo~4r;7AJ{!q74zJAOdm9u)h{r>yF#zw-46E}uMzftJ$Vc^&?;Ny?S=k;rR z%b{|)dbE|&MiD7F$E2oXq^-wj8L2_#iaGTB+nqRa_Op)A`nM7s+0EM(Cg3kX>&O7N zw7qIXJyzpuIchIOe!WTKX1b=0+I}5czdS9|+0ES|qOiS$m#p=$UnGmR4aT; zm)aIn-sc%Y{b^(Svrho9wl5M*s}2n8B(1V7H~P5Iz<4P2JFUK+yfKIzd8(((mp2l= z?7T{igQEFzN}QCyw=dU*wR7XB#7`bjNAN<+)aOq@8tXijf-t!@=AXknx0FjCfn5K_ zY+Q0~<3#M7^%?7Yc{=do?;(61jm=0d{+aFj+_%jWDmiC)(0@EpQ@+7da(cZgo0r=>n z)$z9qz?>`7-cM>4Mfoc6to^OQG0Za^nxfn^p9oSm-TS_rf=Z;5v)irIjVP5sEv4sL zJpAM!Ue*1lw>YP+9rX+VOWh_nZMTcnbX}ps`lV}l=%trIAb&cUV7k`sg!tgZ?YOjA zUbH@S_AJ(}Z{eOd-o~->a>F)l%GPI}G3Nw|tMH%hH{bX4R|YP$G>1`Md$VOu;GhQa zL>slWhSna!GU&1UAHW;`=F`~t?MHFvV~-EcH*6k8mJjZpmucCiM|1!QccrcUP1`pi z-AovF2(5New!ikp%NR#P+8YPy#-+T^-bURdy!!A1*q*H6>Y)uB{^XOa4DUMoE*}2XuhF2! zboPa*_FA8?txp4!c(-k@#K$akz-n9K`j$)Y;=tv1alxdwSagUsl66VM%RUoHRR8wN z@G@6aPo@5rXlr{L7e4wJIC~M#eD-r#A9%DBy%HbAh+>b>|6Vn!(Gg(eGEewE`TFK?F!F6yBocpA8jQJ6|YCz z+3B@;r1f+>OQPXu7E($*|C1`6(Xx-Za+x}Y7VBt;`s8oQFY{L2y0^aHh#61%ukNHI zTiqxL<<^C1b)4khV(VJuA?;nmp2lt0pk*0cPlalG3u_;q!#f&N?K+@NL>zDw{dy2oc0b=piy0sV{4zNXfUWO^k>PJTkD)~tC^k0Q#oP}+oV)s6p~(cZ6Tya2RRN#-T!poahjr_%T7J`M z!uB@s*kcurwqMT0JMRE*zS*w}FJ9b@1^=B7%|xIW(Aui~og3fsK3&u2fB^}a`P^-Q z=cd*{ya>%3yxS7dmD8r1DBDx>t#C3vn4=++=u_J<9RvgB-Ee_OFw@D$M3!a$2JcS%0nTF$nTJ0Vi|ZrkXAnPf1@-prL_at zzU4UTt9ie52rXhKKCSd=!?(NN-c{E>FP2#?mFmmkvm8ckpLva4DmTtEPG`)cU;5;n z$0YIn90rVJsLLLP7o){lTW%>>9N9qmDc~G}*0@sJ_DbcWm(ue6Uy4WMsOrIJcJVTY zkG1c{<0Zmx(E_r529?8NvN(jDzc+O3L~)KtrgE%$teod3CW|wpID`HhMYgzKzl zr}Whz((&_rj3O7&nRny1EoZoOSj5-4_15;&nLqt0*LM9nkY+y#LvC*enRkHJ*7OP4 zDYg8qujljJaR=~)FU;@z&71e-mw^{vSgkFcCwek0kHsf;7P9VTw8=9~>tselb`I&f zB!;dtqnI{d^K*Vd79A&yWi|H23_bGP=B3w0wFg}}dbu_M-GXrH^0W46x167R>m8hW z>up@P^%!1w;xqW#_x@7YI&_>;$?axsUJND-%<1HbU(9v;Li5D58Xfo6>Pm?oJogsX zKK=lyUQ=l$fBlQd5IsQmYS3~xr5UE{WB-Q8#x45jgOAVSkN)u=;_`pS-NmiG7rzt=q?+yFvY<*i+P>tM9$t#-GDz+4yi3a$N?G zc70>{buC+t!?aN3iCb*Vy1O!#*xNAcb@yQv$!oMeo%5G(3ttZWJY zRAG9k-!hMl*GC?Zr4*!-X*C{~t*g`(Z@iPfn(c3Tl3XjfEZaur&)Q|pP2aez9LKUO zjyY>NHL4YMqoej$wKRDQYP@GwB9d1*RrvFpKu zE3RmtmQJOJPu^ll6x>(7-<-?yOA&(e*Z=?^07*naROh$%fBApnNB{E=v32Z3Co|?ldI-a@qPPC?ncirxy)%wK zL=l;!vo)Rk%C^nESX<*{4CPDhFI zWyhsf*)lyyjh<*=X73H*D^6L7|Hoz6ni&||ZHG}H$S$`>i>Cbxl2JgRlp_j87V>$d6iJHglqrZ|1(b=-I6wJxodb(+;Y?Eo=t+@5rswVQ5XI(Moz z_e#|GGrU|+xrpe5Dn8%&ttl=iK}-!fc0~8eDCfiroE5%mQQ=X&CBO+ z-ZtC$whGy;&I6gRZuU%lTfNToI5~%ry)5(f&gHK-z?6FM=W4F&EJk*D! zBqwDoWZUG&th6^W1$j`M2Il`V&(K&zS;ltJQ>W3Amc+iHj>Y(K6m1x`SWNTj(+qjB zIl{$OMy21S_)8PskIEdPFC~vGx2PXv`|X$^`N;S|n<`i4kVW9AEknG&Vez$jP|o7? z-h05-R>F6_!*&13pCr&h!H+#wA*I!CM$XYAk5qW%5&r$jC%|{VoAA58TdB?5pKgjr zSRaPTl@sS0fp#3ddL}kh4L#cbTeW2g^1VKiCZQjOkqtRvq!q9Xt ziSmhmd2;u3hQVtzxaFhEc;x^---A|2^Z)1h&^et!9I4Y z?Q;15raXQcKC()=hRU>zS?w6I5zjb1r6mi_B##r(Wm;ZhTovO(`SNhoFPcNX)_xT| zuf?}D`L#A(ds2PK-h=iwYk zCsDW84;E`z-Sv?8Mn6u@>nlm~uhvluFmO2b> z=IOs&HX~owv3k3+^admn(lIrZ`Y2Rh9*;4h& zEn6Gfc~FVt+PFP+w;RB=aanZVYp>(+7hc3R+Ly?aXa)0Ki@Ie$&~N)pV|OhBPgajF zqmA(lzBy=ZCqT_^(T&lzo#SyY$YU?NN`1V=fY_$slC1F_TEB)<%iDD6ofN--7=c_L zKDA)d0%{M7Xw}FjeGh=?hya;{p0gzI{Z~a!j?lWhAGiQ7&E??&B^>qwdFur=V z{rvQp#pTByt8nkV!_)6JJ@5d~G!=gFi=DRbIdB^T<*^`{o<(+7-j#Jh%q=;iB{#Y@ zd5TzTXKc8NuBzF>FwcD2VlCfduDjm=+bx1UoUiWmpbQjJo9TpyG|Np=qCg@oA?q_b zDpjVG7qy-?ZBNDGv|X6ir)*cWCL0MDGn)Bn+T@RP`RHi!b5i*>|yp12g$CK&~M_01m*(HXc0@m>#Pcs^%&V zUif8K(keB}(DIk*3*QX17w}x3_A+lREn9x}M2i0UcbXP$Zw^(&wG3IT8Gb_uP0}Hzuw)PxQp*(KtD-JDO`WFEp-hQ%UVr zneGO7ZnL(*47J9C<#vy|l6bV788s%s*#)|R9Y&%-B|1q zr{>45cvze!qXAGk>8|uJW&QCOEsZG7FIOeBJhWUmjU7Au+iv>TGJ;%6sVYdrT;`^}+M+;m$w(1N`J4{VAp!hebJ3{*o{G zO!j3yW>an_j{z-nmVvgKwhh{DlO=fcrC(!x`#OI0*rUBX3?ahyZM>q5d$jlKZjV4- z*8OD@|I5eapI%z(N!w#+*}!r&w6}TOt$@UkT30tEcdAc(3(A04k_UoOS_@ue9;>ps z&HMG8B zo;WC0iTwI02RI4dOlG=QzcZ_0HU(tq7rkK%Oc8w)iXk9vy(VaG?Gl4B4oy-iywq(^ z*p`dc`jqLU@>C`*18kO_3@vET9T5ZC-O*qKUKiSrvef|7@tebk*sI7E)My02jsg;k z(O$MCJ4a*uO`W#nN9`W%1s?J=G%z+MeZH>c(|l#_-9FJcM3VPsbH0E3%ZG)ntor<2 znNQ-eC@;+Os6P8#a$=uHZL@hx_&UNhQTcuR3{BHd`qU*Vx&41BxUI2{^ucr+#^U}w z`EkOYqQzmvzg&vY7@n7&t$)MimE$s$L)MgQQ*KPiXHss`n?mqBKc-|$^q9B(ks}>j zfVtLu+ZrO$2s)15a8Jp)y>~53$i*&(P(F5N)9s8_zHkBf;SUqO@|BjS==04HUjEwG zDl`RGv##}5qrUKk3I`9iFEY2cY9SOM@hGRDMO!-$?MYn{53{b}_?e8p%4ZS}x6h}ua%?P5#z+}sw_CWYjvvxP z8VymtMl42BsrrO%c~90F;a!W7+gch?b2Z}%sIdOdYnWU+fUU!Ki~iSRA*Yj;hl#bG zCjRBi%n=_$bY(}=)Nb7Vul_mkjen#4blnJw>S{OS>r|MH5}Q}sa~qQYB2T0wdrx^= zH$1@n14K^B{H4I$I)-L*&5X{ zU*)o`KVY%3^_6pY#jYduQPgK%1AC3DF%EkcRVELA!9z!pHU6{<>?xFV-BA4P<2klR^?0C^IwB%@Yd34R z`vGc9wx_t~wYN~EgqI$Fte2k>J^0EQ+;`?R^|ft#@S6Uot#NKNTRASvHtbVNVR&=s z;2fK0d9?S<`XcgJrfgROZimv|>Zd+AYPsiuxCNh4O0A~blsV-U-OoYBp$gFQ7+uR6 zJkaq#s8ZK#T0Lk2wCVNb>pZ@UGL_TH`lTzueU(&eD%VFkY$Cy~mt{X-wE6nl5RDL< zN4HBm0&+}h*ULH+mZTe~ozxs>eQnXLh+H+!UmAlpFFm*8atu!%KHGbK4Ds0UpXKmMWEOBgAL}{AX`ZyqDZ@YN{a90Q2JlKkMzV-z+=NfwLBqaa6RbP>0Ew3k6i{B zR?_llZ=r;kyzen4@7R2MUn0xGw~JxhIPdO{(0;A6Oxmf~i>=4&3~B%Dl}_WawjUFI z=_y7=i?%+-$Nrwxn$a^GhPG*Pn9*YxYcajn&b6jLjm@F^&ErS*(WH-+LmWE1>n(pg zUVRK9er~zdxfs7o$l?MW@rbZ`WJ`2kLh;n!`lz1aI%a5m&eC)WT)a3s z8;;mDsUF(g9AC$$iH0uD#kBkgijC)0!L#VM&Sy`3f|^}kyS4di$n7MuU7VxA1U$p! zUz+KR5*cr&8P?TUm^f&8rS0HJl!NXIRJ^^Yf<(2_x>7k-o_3L!IN=T1@{33On^9WT z{q|T`N3M@8qxw@#oix3#GC0 zs?0Upedf^Lv)_M|meg8!8|92Nw)Uptc@npkH`9?9!d?xR(f~8R0f>D%S%>y2QYe!M zCt4mO93)d&NswQ~h)!c}iP>an8pqlD%#W04DQ!$1+sfY@W3c1J<7Yi)ygXZflf6TI zzX{4N<9+slH9l=rnuJSxh%!Hx@-m5ql`s{Ec7OY`F5 zoi1~q=A(lLfy0OA&p#ILL^g5WygB>lwO;h{wZ_a^_xiGRsazK4(E6F{(Q{PSEK7-^ za#pswJu(8y^IYp$*$A&-c|?8vEp|C`F4>E>h8M6foog1=Z$vb_KTl+d;nK59lCM_hpt}5 z_UtQTOxClE@8{>Mm(~zn?Ptb5MYJ}rc*^6Qs}hegtprvYVzEQP4xkV7OIOVE)h~N%^2_~f zgAi7p9vDYs(vRg7UY95rc;_I73@*s$E!E&)o^+a$@wQ2u6@pyc=pPz#vFjO z@Y0t}pP1sgE&-c{>XrK36vIb((ph_QvW2GvU+KR_$x8k!%bIG}CvMXT+k9fP{XCLg z$cA}lt)SFg9+3Jz&GEZ>-+V~PpL_0ktTo$s>z;dx>3;A3`Y-Tj|H=P^AOHM0q+dOP zryd=)aeJs1Wn0&mV`#dVgEZN|^YNH;RiqeIlgk@YdDg5TVy(! z;Qc%9KvUJTjZn<>5Z;zUUb4IGRY!Cq*%TcC8kRo)Y-e!m^6Oc=ynerUo)V>3yy!^Z zEi9kc>|@Bz`rI>{B6?;bXu;hSq{#UYZ3^uPw9g_OtnIW;9rKj;m&^WhKc*Z$mm}*U zaSo@E{7b9N7F7BSNtH*Iy$^H7QqWk-=CD_O^+NYiqxvQZ?&Q3zRGXx~qveFIUD6lQ zIGD?{ILrEp(vOi|C%yQ_CD_wm^-~`Qu>M=Lwo{2`c3cx#Uk|F??15>#Y{!uF*yI|F zU8P{JP@eK0^+$y7_3V~$1oqoFh4vdsI{e~V`=t^6B3qlU0iPr8^GP|Ut|o~a+LHQo zfXCaO=EJ=^?`wVX3Gl050gpbqqt))yl4&gdmN+_RdvzMWh8^9LrRdm_e=dJ%M9&D? zBYkcuTZd%QNFKFrA-;Kba*B4*^ZhmoaczAa=Z_!nt*1n1 zPo2WXm8&@M&bh#z>G8#NPn2XTCk1O?`gOasL$c1DL47wKtt}>+Nc}8MeZb2Oghj#j zB0z8N(yIDoxMS8Q*S#dih!<<%iIN-l+6gCR7N>1fdNs#&`tcnZcnt&=nh&V&)3WLAyMe8(HW;xNDFT8q zMSzL#Q~vz8m2(Tw5LeDD4m{df! z_P5+tP3^XU#vEzrS7-j(67A{Qm<15MhSkt7uNQQf6z=a>(m{zlHK;KW+Y$Q9Y||aQ zb{%V5+r4=<@3|cZ4sYP<^=r6x{rUjT$CI`1i<6&A+XoNf!_!aT$Scp{;sZ}2O%5!v zzMZ3o9|rEdcNrz=K*oIeV_FoyF0PNnL5|;a}O!d2CwJ8bO!Z zZriIl>LZQKlH=C5%k!Hc@vR?=5|c%;vRKX&kCW24>+7eShh=3e$C55z%RN^nKh@9u zGEZ(a<$ZCPlWJo5%V+vp_g2a8ABT(Myt_}^+rUdNB|P%T{@0-vq0LR;&O0l-^2+M% zc|790M$)lHKgX=ClTpYhjhtcn9$h7o#?MWF=O?ALbJMrQZb_2ZSMpkSu{)Vg#?LfL zoQP|}yVdNZZPuYll#K2^e@&~sSECV|Y_wFM?n1*SzxlMZQmcC4W=; z$tNEp)e~$VI^uNbFg;|)mDaLDNO~%^ES872r_|mdbZC7Y&-}*cf&ca(aQ7XUtWcTt z&G5aX-*XiEFUz6(?_cZ$#Cd5M5?>xJ?)R$}EpHJjMah;=Ig7E3yz}w9$oSVhEH=~o z`a%2ZL(9|$=|ttqUmDeDY@*lZEN*7&qopv+Umml@H}<*3D;6V5-fcWQ${R(f}lG=cC>$Dy-ho-hU$SBQ_Jy`GHJDE=EqPg$J{E2>=U^* zZDTmONQve^uQ>tp8Pl?5O6#r5@;(mh zP0nlWnUCAqJT2u{LbaZdFEHixtL8Y4b}*M(!?yVtV|t4hX;@pv=9%Yk!dqj>$H`|<8wCkOKs(MPx4+SZyX-1hDV zAPt?+bZg`^Rx4$pWZz1PN4@khr6rsPh202ve$}+LSoZutULN2cSN4t3ovU<7G%c$i zw0pmZ0$UEPa(of>fo%(Vh^&#dB8PEhdL0mK|IvnM=CVd5LZ@^JH`SH8I$3{8X%UYN;!iqj zNJs%h3Dxum0;6(#n3L*_uOphztL)1~eatpo!cJ{bSmF(8)R+q1hx7OJfBx^_;k5?G zPnS>S2B2iv8bko&5}Rcxa@PSzNN@945hc-CT|evEAS?DJ{H$1yzC@c71J zVX<9SZ@o1>?_yYZ zSh+qzG#n3mt*1B3$Z;=6ZS*{e{IW)k)#c39x|@)#uA`crC@FQjjJ8@l+&NoEtjHPi} ziS1bKp68qX*^?e~w6VU9-+1at;HhC>YLaAm(=F3HlJs=+1TIHTLVE{!t&UEgu8=w8 ze5K@lzZ{k07UT8s@_RLo%&fYOa&2+?A$&zX^U&0Ncp^$?t(;CV+_R+nRwKk3Vt!hF z-^xwD(jvur$)e_HLl&ikc%pr4d9OUj%JZ+EJSLXp`^RHsZB6}eS%*DYT1ThbwDxRH zdd~dWYnG_S)zVw)lK^wYXhr%4AOJ~3K~!Konl!GBY=dr*#=Bl_bW{z?utpQ4v%Tpz zZCB=ZG)oy}`+IVOHp@%-3t2(?>Q!;^#cJT^80JO7r0C zeOe7|ZUPTJSmCwT=C`3^v3GvtEN|pVoo;O_&#!)5&iS-xexAYw@`>Z_#`@w)6mVdEmqMu>S5ln5-Ye6gi^oVn+^wH_Bc~S)ig7nyuH;7^4y!7;8>r03Ml8er}aF z2Bh_M(X|H6bbo%5<@B8dp_l8v(A$Z z=tORqAHjJCZ&(}nFU!dS+T>)J3qV9;4d5{&H#OR_J%6#2?As#c$iO+N=arD84p2w{ zLiemo9dW1SZNne76%qe&zvi7JU(PVd(^qbuwzq+I-))_leOeA3Ki)3*pEldl{cis5=PdjM5nWLCZ+o{Cbk&a)+sqJV=ntF7gUY&IggF) zJzqv1$7tUv-`;%BMc9~q2kCXi{+C9Gx+Lw>SnO|k?fY%*eIyNi9s6rEW^zl5vfMtr zB*(brENX*(7NwDx*2h(}EOYlt^3TOrxE1oQPa|Uyc3f!mE)g%4EL+b$y38+qeTzV~ zXYD;{DZ?@*-lv{d8EQyZ>`=h8H0yQ`C>dwDJ90WdN&2nES{!xQrpR|O)*B5 zzlXMsXCqxV&`4aC80RCL#h6%cBlieRB2ABj^Sm-{mDaW~rP-6T>GW-lcRgm5^+-*B z=&54Zn-l=bM*ejp)ak_LpSjfN^g#i!jtkXizr^C(piv_fOu5X31}rB=b){ zi#)N|zUnRhdzI$Z7&j8-=3wq#pFD>8w#(P|eKDpSd9)MpmXGt$^OFA_;iqxrebU_X z60iBZF)oc}b6jV>yvUawOVJn|GZKf(Oh1?FGdiurAzI@8h$U;W*=O*$L|X=rS?qcs z`y4~5gq6#&j<^r<7FJtoY02$BpEsF08gb7e?HIeptwqNbr_}yJh4%F1Hcj27YB%0e zeGNF)FC+6h`p(`(IZRL^*e47@~{A4V6lZ>0RJ z#P_lGKK0RL0^EK(@ZpEplWY4HW4HIpI9%V$>mxn;to`iw8tmO)f%=W^3nbX=!5(4OO4T)qvHi)>i3!M}P5`SU>k3K6vK$arMso zOg-9y>()dgz)E5$#pso}*5qRr(x>5T+OU0P^AN6VF836w>+1(`@z@a@{`eD6)P-Ly zVvit_g^e0ho236)nlZ~f9$_!rop#f9!ku?k%hc2Z0{k<=f*!7|g2%xVi^y*u66MG*E8y)v&!7jVIk!U1!`H`|iCgPdmbXbn!DP zJBhsdE|1k{?%PtVgPC)w_UY3^o14JNlNHXK*$uQj)G}$ZZhILp=gQzYr30}3%o6&) z)~*_mCqT_f34z;tjmXXOQimO-JlgA~tBEy+-1<#6C1KK)Ctn6(sM_A4?Zi19YprNL zcxc0rtwwFkrfnVOY_DaxQd;&pIWA-1ou?t=OQ&H;MQ~B;T>Hy%p=S;k~ zGe50De%_DGrHtC4?UF7bMrk>WY;kmX<93evajxdf2Uzpi)W$k&Ahrt9`31fxxGVG0 zi(GMAa@Nt;Z6(T{Q3{@0Z$=|R`!bzvhirqDt;c40FM_eVyb}eCDHUU)h(}H>@idP; z?N4$Vzd5^7`SiH-oXPgun1Gg>9Siw1GF`O9ksL2kTq2rhG6$zfB8BykDQ)Bd>X?d_ zsg5$p_=M)Wvrxc8LNl*C*B-gJoFKc4@bZ-i%eZ~?x7{c(!Q}cj zzVPFp;*Y=cySRSv;2=KxsBRkE`q4+IQbJO4Y&p{L8#+N!@~f}C)m=8axUuNMg*Gm@ z=tA*$V&8$yVgNS3k0)j*n7vd7kP)vm~FU+;}?!R`)_1eJnc_VmSyZ;$ zHX>o_jPP!R8=|ycuk`7Sefl)fp+mrzzg*$_-%q%B5ooOH89kLy+3I@x3YTuFwEFUyv;gey@V__iKaJP# zzYoi#4^G^U^x4PprSJc>;KNIu??+fk`cC^~sjh)1o~W?CzIa({vXjP=?VQz{?!7e} ze0!J6-!kO6n<1;=b+4AkG9O9&-{-U@#rKN+U0QICfwV2j&#V58+ur;}zwLcb8rURp z&x7pR0*AelX?fL$T+O=BE+%&)&Zvgk+3#_g6 zr{AZ3+SmY2odV9D-HqD&N6Zj_EdzJ*UZgu2D8i+%b6=*>oN9e9fm{SdQuj%^xUD$= zNI)0RA4#kXS8_=eimwLDA?K8BjPxCohK*9o+D+U1+ny;=b@y3D65`47B`~+YwY-Lr zw`cNM-+R5X?UbH)k{{XTcJl|j6Dpi|?|oc6c4VoWwh_wKdvo4X;#S&O;jNp6-uk(; zDSHcH?JZgakLC03eTgr7RIENuFphNl%HHizA|17C47`dN+V9QB^;$1m``u)7*~Uox z%g=^jWQ|lxzOF1IM-iXpoH@-I<35X*qqO!VQ?2<+mLTFuV!oJ9xp3=8IC~n>SJ5a^ z*G#-g8wqjWT*YvT(srQnK6V9zN9=_!Tfz~#&1^V)g5Eb1%QKKHRFnbvD)tqb$< z9GgbRl_Hxgv11f_lbE?uFBC^uTh=S>Wy~>0H)$)FMsPJ)UonbfDOp)WT9oXBw!ZdE zMW0?i(^^@kt+%$2>Itsic^cPlKjnCcXv`R7UC6J5ORStaT`eOWI{E#sE7)FJTgqwM>({Q~E8qVCrdY!k4#18GsDCUM-YhR|l*PzZ_cw=aZ9HP{qp@-H zv!5lbuU9yEa%by}{MU#|_`;XDT#}=w{T|gCy>(`Um#%T;CuO#NMzOdH)Ib6bbWvv!x zTU(!(tsb*g@GQnUnsT_=Ub7~by2T!?K~{?_1aGqSm?_^jS-VWDPvw>pgG#}i)}0^3 zCu~KY>%qSIfos6Z6IRsqRL>%ufN0HTE7_ey64uZ~JLOy2aDB zX5M5h$DbXAp8pDV%xRpg^|^npdscc5+W(Z}hc|FHup8v{kv85Nkwh|~_DcW8j&$}( z$op!?O1r6^+Cm$*X(Km;uU4zNm>1scEfI7MC+DnNbblz;9iDErzF11_*Pi#+otIB* zYrr?ZS>ccWIN{Qz`N|lJzw^bfr1r@wc_<660~I*U6OePc5RfTCY#dO-Bu4}AKCWH8qeAs%V zbwc+%XXO&?3)WHjL+n7F`q0qcqUjX)?spS@`?o6`IkH$;Yl}2H&bv3l9-g=5^R?H8 zOr$Ip2j`K~KY#w+7&AGJwK>Zf_k20pn2leQ_H~pDcj=AkWl#)^`I!aReBT2W3%31l zPRG9iEf;>~jVA+6c}KQI=GOfo!yE0d_R5;11lfC<2MN{T+RA_PC#3n2RhcK1sNDu> z7}zD%23fk~TaT5>$VJx8DXdYIW7m#Foz8|beE&w{AeNHa76f8F1a9vO2=g4Gv`I!sadZM1=#{^~9E%O!^9^v?%z;pFLIwH_%fgTA`6R825F zaBQ9?-K10wnB*xQvCE(+xUzV8dzV&Wo8mI(ugCgs^YcK@c9%-nxe{83?@JVEac=IF zn%M7-?Ry@djBSIa7=zmT5w7vrSle`IMVTMYYqyF?o;7~dQmdSNhMkz_eKBn(+cbod z>)S@bXz@+hDqnWFs>Kddj3m^ z$1h$IfAU#g*5ff~E~c?t)HJ}K{aM1dzg^+*;oauu#-_uEfp2`H!XN!n+NDo5MA;&({Gzf zR2j)Fip^P9jV&jizQ&>($u*6gc^r?`6;xoh9n zJb7!y`J|6TmJI5*q&EN7<^%ZfH~w8*K7C49zg&5m$FU=97_PB?JjXzMS!I8u68}o{ z&;R^S@yzF*#65SO#Lr%O3D3UxOPs#zF8tnCe{%rGkv9_6xg7kpPxI5-Ug?Czm9s5x zZ_~2d8>utcgFlTZE$bVisBt0FFlfQVjOBrd2l_1AZJz?9lPy4hev<=W5%ou$V0TDn%DOH0;v+50+AWUF*pR<6FW|fJW{7wZ(&EOrH*%g)+;)v|b8(f(FZ6lzn6q0AJ)gvx9_3OR+}9QA?gTbU zQ_p-x&LL5(mM359KA_Q;!1mL|B%};; zrq=u1BP|xC^BWt~*v1+vH2CuOe~2G{J0v`Th@)P-BWUOfi}L<8v*o zCnm?g^|Z>e8Z$%pX;F&jel8`E?ZL9{&FM~hHl(+;uNiaY(=XHdkHwqgWwLm^Lu5I& zJc~!>o15CtU2ebh*q1N8>J;`s*CuS>=!`!9c z7Sm|_YVT>^r83uik1eUhMy-WtI%^>FVt z4H`60Xd z#`*9QDHA)k`hHtUS3%qKcw!Gm>Mrd=G9H#EX6p^wfIV$n%3W{drj6cu>=V&z>b94d zFUdvAeS5w+M?7lqc5>+*+5>^K4fHR4*eHfY5L&J!?WXq!ECXBb6s6Rje!5SqqpyCo z!jFHPaQ^(x)R*`0hxwDaaw5E5!qfCzVo+_XbzQ!8%XOp+BX5vqpv95i%a&L^dd`1Y zzf0YgRC?RiyqxuGjuN|hpUBHfdjh24ZvV@FhP(gS|ACL5{uVy^{NL~H%RGRWqix3! z8WR)pHOZDoW!NL!pwjpG;lKCQ-^9lHK>)z?pFEFi|L7lM>pNcr25#E+b+$IXKb`kT zOQid7pT^Rl^DWDh&?~fIW$s;CF8Etjnd8bEQh%vWhA8AQ<;_PWAYH0`jI6w&&~P?( zbR$3~4Oy&+qhM{`0iMSxj=)XiHW05CQrOzGxuk0bF&3D6AnE~@tt&cR%(vUa37J-3 zTiN+AKwDl5N#j6??k^3$HAuE?wEWp?*&?b-x0%KSo5$Auv2W7q(yY@+X(QN1&-3!O z4qk42$Ucs^;&k%!Ua}W#;36771eRr)H5yS~+y|Bq8ElYqQ7#onqgR#_e-f-TQ*EEg zx|uu4nFPl%jdPraQVF#0)83@20uCK&KeIiS#(pHc!p@FmxD(GuJe%K~k?W^0WHwaZCuOBCR%byOI%62#4(>m{Y<1MUBxADu* zeFoRo*D)`B;m1G4EuUP*7S^zhwP2B2+ZyRH$+k%vs{4odk22u05#P~Cd5nsv<@&T|8YB8^ zO5Ao@NR|uBvMmxTdrZb$Q03@*rcRv<--)IK^c4Ew5?UPO_~0^{Ki|H=W|?pZpBJc=EG& z_pXy!o^y2K+&Mh;?9WkeH{HghA=KKIiTG__ard(=irK7^hRyh!op_ED#XVqs1F3<= z;BDzo&Zo1ZnG)48FD;JqB8)pvd1VY}%k1-B#>Pc#Y*XXAeu{k9#b)pO*iSd9ULT@wN4YE5OK} zPu~U-)@HAkagRr_9p+Mxq_!rxk-M5nndB{dbJ}r4U;QNhlWw^M3!h>>7JrwcHN!`3uAB&$^Ka|NT5Xq)B*q%javpnAUW4+L#<9$? z#PXGEt>%?^_p!Rj3u2j+Jb=pF=e&|%nMdMlsjbtIFXNNPUc;sPAI5ZJQ&~Y@uH|R^ z7_$`hN;A{WeKsrhD(2H=hs8l+kN@3oV(XqG_|-@6;Lm^j*ZAfazto$*>c&KDf6?8Q ze_M`Iceq<0m1pQa_0w7;=01_eDq?v4MQPdLm(_%G_AZa}^v`^GEYHK+kORCLbo%mQ zGa_AOPZmylJ_yus8XI_S)5a~KTuG@xnk5~`r z4MLh%X*n1gGu*9ITCR)gmpYMiL8OpvwTso(QkQ+B$g=y8ruGQz8`3&`zFZH=72tMU za=M%ksMFYcEI;lOX+31mP#fC2v`Ec7(_%HtXNnqko_!ZJ8vNvozmeg-pPIUE7w`iC z(5WUlVp|9BClF<87SZ7|8BVX@;Kx57nCH_GG+h;LS_S@GZkc-*%eJKb>t#^9VYHmX zlJ_3)MYR9`AOJ~3K~yHkl%~^L-Ck;IsjmDpX)kRZk(QNwSxdq?JI2=j#VU{Nl1Qsd z@TdajPOOh2OlGa|@G+z@Yt9-<%QFNw)(#)Tlq;>LY@4=Q5g#(OZVC5DQc`H~j66Au zJ&sD`tiL+ zxRV~3l#L!we6E{ZQ1;l^#%p|g?A+q$fE{gAi}t8lYV`VHdu``eo3>G#7<5ljs`d*f zRHO9eq!*{XZ;13azdy21{Zv)J=H_Ctg&h9y>2mX5}Z!u3c8MvYhIUBPzk7!CZfNeFnjgwc`Fu zQ)MeI%aC5wsaJl0kG}LBT)OWGQQj&%e{}8h<3alol+w0DpEjuxJK3BX39ml%0M6ff zd@lYj96gGcA9)y`{rNAtIwzQRo5RVzRh=Da>#xCQgC-$$Jwt}$U>@t*`s~wUq{j`B zoptuEz7zFcAAZS|*hdy)EMsPBFO|!luOy#;aUPeWfhyHszPzEP*T!a%DUZsGvBHpg zC_T@1Dd7^oDY&v)-`iJ>#QKPBuSY60v!wpBc%|eo=kPV>lelhvKe{}36Qta$j4bWz zQFimPe6D}nAaUZ5!^!h`6iBM+X$@$?9;{p1494VrxHleNF{ zGV>!S_V)T|yzJ-cubU0iugx=LOL9g`~robS2Bx#>1O44|t`iNluMandg?T%3b@Gl!H!DAlC=i;O^V-v`r&{ik6l9 zWRL{SHh)rOmUwTSq?UIErYT5CH0{7B$8y8C;XRY4=+8m@cuT z;UYb;7af?t_=|+EeXYXr`PP5-X;0EHa2&zEeo&m-xGl@jS9*>?m1n_iJAYaCTHs82 zp;EQyUxJ{!`qXW!StW2Ly%x=KUaY3YOKCfGc^34;J(qqAg(J29<3pL~u5}<%*HeXQ zEakvjkEXOjTfGLVj&*C|MlO*mw)(IIQHSkT@4g6 zuTfztB$tF;Yr=7smje5u2G?Kga7??P- zm_?teVKGdEb?LX=aO?m1`g6RuK7;)rvCX6JN?a^AM3E=Nc7zd@q}o^#YeO|&PGXVM z&a>G1=vV5b2gP1sQan~&dnm26rY+HnQF7xpk3a2KQf*RJ)>cO2Q2TjW4p4vn_|RPI z*aDv@r+pOmRU!s!lzFgLh78)<)t*~DyNzZKUm1#Y||BvL){ZQ5e zCErGlijp6n%d<~=pPqWE!t>83T)w>8dh(-i{t=VM!%{c-^1c4DktRKlC|88q?HuLu z+q-#NEj6x1;Tok-&5UbV3vzqOI?0Vs%ztd}O47Gh%3ArH2KAcUVrj~A+mHVhuHXAb zTz>c&Om8_FXkl*+Vonomzvt8X(tSdL6#qYDC9jq?rwAPviDHOCK<2f3+uCl3E}B-N(nnDHm^v)0Tg0Jm&As zLvbDc5P(JMkv{M|d9^n>e_6WBwhXD!7a7s^<>v7`TA3&D|NioZ;bJ>}tfv`q6V+K2 zWG3yZ#roc}jnG6=rAHRu@+N)b%G99!W!wIt_&M(n%QVBOQr9{z65&P0+EF^GXXFNL zis#BrwS+<>)&^`}(kNnIh0B(_()QY9IH_iqjC-I4&ypI9uj%`Z?HVqvJJYLea&tLj zJiB3=`O@ud`JBwoXtoriK{~XAw_aC*13mKPCUfn<)t#-jey8nsI|Eq$(Rl7BA4|~w zjvhZY-XQlS@VJqFPh-Xuk0*W7xsPpVxwEe-H*GiFcu4>zvn}#%&sU&xTU+jF6wzzV zP4_$rdHN_ttRW*b(I;oAPlmo6H{NpXW9%EBPMiRy(+aP=lJLO?J6CU?Rf|TJ#o7Jk z=)7FI&E@qVdv#IyB^1kdC61@x)-&*B&>fvew_UHVON=Y|_7rKoA*3y_wEXtDEI$FL z&V7uvYwzNd6Sv{|u{%|%TElZW@iR~P{_*LC`9KmC${0!JVx|y(hc+&Q~w4AbrmN9HdEDCf>wOWc{-p&p4HtulrYaM=%EQ41zO@dmPd=2410%yhLItOV6c4J-k0*#hP=GsH*_INbDV2? zDm=HKS;IM9b`)xs;e{m1U?^gNWUcD(WqY&CTu?g6Mf|q34*ay~WNj^&u2oun(q_}; zAeb#rjq*H8a4iE5x=r~Yrg!=DEVM?n<&hRhxm^i-(zA6!~%Q!IMVXaL=b=OF)ZYg`O6ZNJ~N{#M1LH24JW}&bOFZS2qzzmIW4soDM zC+j82`>=)t&w3PS2wn!x!-4ePSfJkC2GVYOb^Fv&1YXPOb5?43BPRybrEnC_VLQ)t zP*8$f`pde+m#j}lOQsC#3#H(SG>rqG;vZW&y@lKBRjGGQvx|oEAQ!a zkp-}NRm*1x<;G(EKG&fCc^{|Bq$is~{acHBsDSB$-+h~|P4Lq%egU8T+4H#Vy^lIu zMyIdvOJHqiR&J-GfUJi4eJ>60NF7S4TEoR7k0MoTS=+PM>BSclnx?`74=h%W^i>uu z$J6j~$IbBh(&oLqVd<7h%g2dSp0yoAbcuh~&tGJlVr*O<8_UAB^OvRbmjiQF%CdER z0c)Ku@|Qi$>jV2*%g=3GBMPNTyW(w4?j`1A{@J|oII6Oe)L1=g5kFxIGU;+^)I}0) zEfTekFfo4_!t$*DH9@;1uYGgSBPNf;$%@iF`^5@5ijuj*h)()`<#CsLCjE`berRtA z=Gx|y*E*(Rd&!@~2GDkazPN<#3F&2cpRfHrRrf5%)O)<7%yQ#;_^ur1Qp+TDuYYdq zG-bRzjCR)V`Sq_89(}aJ=H`x7c~jHLlfX+a?Mz*Z;^849jqxy#@qE0`>Pc$lYR)@Sa>(0*I!RKc(B5)x9(h>^~L$4x`vnIbJ{w}_}1sN&thzn#{+(pcztJO zIi_yuY3lNH%s5XGrcX-l9NCp)jU#)^MWdeTR+IftsviABdkA?S*pI+im)hUue&_p< zO|o+G*qY^4vQ509R&QRO%nsR*m`HBmj_?;z1OB?h1k<3c+~O#bT+O)RZO?17l=>Ug z33P&WrS3{JB~J~nMB6HHpAHm}hlkmX=APd+0zvX_xotqNPVwe*2&>%YVvkLJ?U`cL z);4ROv=38TipPm>o9!bxcIdYqPZmG>aU}OJ_~%mY6%wu;TE}~L>CJ;w|M3sc{e1OLYAD$sEYkg8MUN={Whqa_u6)F3DUkEub^ z!w<30rfrLDhvgaXFGlr5<&^jt!mCVE<}ZTeUt;(ta_=$vdeBkrBvVY6fOB%rm?__Ad2l*2|(kP zlv{7ZI_;KbsNyFi=-@yLtr_&S z}5s;SGdfeFiIuK*Wi~UD(=imW4K#j02-8v~(`lSGk zKytt5KZR2Gq;%TKr=1%9lrxPJhTKwmQp+Up8|xZG$BPd`G~Tj+^E_~8k^1)O=A}I7 z)c5iLRNjM1*AK2`J_ed4=)|SiP$Si?`H*LXkp}j`!wBL=KAYCbb`uNfGYi8dw1T^C zQ`P2o<#I(f$6I)rzIN$s8d)D-%hpFU+=om?Mpo|9Ka(%+M7{{s6McG8wd>L%v>fG= z?OqJeMr91?-@K=nf@^Mo)rtQ5(RaM6&^+OY2V&*MsN1bVdx4o9bCb;XZ zB1@cjjP-&a>sBsOCNgT^k(ulT9(M`35$apOd95DMv&xSdiIFLdeu3G33LMaQx_lZK zbEwCLoTn05Cs7-Z7obt)a_LrvRri!@8HRVY4?f1PiON|_1231}d=of*8vC2Jmq@2i zSJ>W8xO8cJ-uXwCrD1q@Nd5XABgD8Yu9wo}ydJFu^JVLKY_)4rCHb1X&eYmKa%lAg zKqpd4ZN+gszUOO|CHZSA$69=e$;qn8v{EP1eWD{TKZ}n)`!#HB9#+r#dVD^Lv2$hq zderVEuC@DY^HP=Y>I3)V`oV*9@~3HgZ4GB0eh{b6ypF2j4R!qW4#}VNSSt0~THYc0 ze6Q*JRZ(37)eb{=>9^!5o}-aAq4a&th;`qvUY6?srSf>rlt)m>*VK4um`2Ez7s(_a z`5A^|Eeea%m9;28N#T9jpRy+FTSNWwb;cUpmz#@B$ooBjoEPNA;G-B647;-;=XDT5{6f_`EhAtMMdDN}j5%H*7OLk{fRI$;cK1`Ej1Q z92#@Qt(N$w{nc{QmP3}R0<9`Hm~;q;!OcZX`B8#Q8jYpZ}Iz-!TAeIn&L9qOnv87WC&_bS&ykuJZp$l+QuM%H(7N&W4=- z&$$U8%RrJoG#Md~Yp2=adg(k?eCWfNUEFDm+-N zW^cCgvbkP}rk-F>D;G)q>1f)d!94SBg5^p-)yt|;D5JgKZrtV(BHzx^##8oe5;^Qf zWj!vX+o8vNehm5`h#xn44B7D#xd<`{!PoMQ=qL}%J=V3A;Dqn<#(C|Wv?HJ~T+%yn zEKlvI@krv0|5A>*xgN(0heNL=%7y&q}EW$))tnH);ZfpuItbwBR>@xQ>wzx^#V3!bWW zb5L&7_UW;hN@ICmY^-a{l`_BeuhicmbFut9Cr7_r8F7-rG{a<Bbh0+!KYI+7R$qJmy+;t?P5p$d1?P>>s~??=m{Mn_Y+D+I)gr7M*_qyKHbqHjMLc{4ba^OfM}fMNRA&LE6{k@ zk1NV&Pixnoc8=sP{iGNdTdkl+zwOz&lcjuNnU?um`8PtcbdM1$wMC9K?a%YmXnsqI z{h-~Wy~4+*ogR1qNU6fBugmPuENNX{8Lqh=>90Vgm#NsUupdG%1HJO-!%N$=y>;LKUV8j7-23{QsGDYH zNhYQZdaJ4QyGUXjE1}Unza(!qy7%4+0}fnUDoMYEsShv4IwY4r>fNDV8O~9J0rE85 zzw>2FAIxgYGR0VAezJOkabXU3bG@D){w?RE=F!`X99Fb#m3-Dp2SnuqQ5?bA4{2@U zFZb%Qb5>Q`#mEB6zxoi3R#tWQi|V1xn+aNXYwgD+(9_D4<8`F>OPAp{Te}jIA1~S# z`SGW1QajJ}OV4zVaZhw&GQD_o@z_zI;xsK+Y}2c0!r==SQ6u5v(Zgsawc``;U#r}_ zbQuS(Z+F|OE9hu0pRcUr9(=Z@#&nwh z%J%CQ5`j}MS$iG7h+m1+JnndO7_VV}1fG-uz&kzf85uK&IN(rws|%FcU{ zi&B0Zk^iRsUEMYv)s=C9$~-Wl-z`X=PgO)EE+aTLx)ouhiPeiOH2k&&!H` zOn5O*rRQFb3v~3pJlz7nhq?PqR(t2lBs{vleaSmCo_ujM}s!ZGE%P>*P{EV_1*{AVy zzWrOPTA-fge{(x5kmN06QbTJiZ{=mZ2n$dn52HL%hWqy8#;C9-sa((e^DgodthcE1_OZgHp}f8@*bG)Z#jOXe#h{$m|k+0XS4%t&&U_htya>Wan6s)<6@bo zPerDizb^=SL~#r0u(mY)Q`KbBo9; za~0L8XSvi@bT!tCm6nz6OKq#~(Y4fHw#;hUo(6XAtN%8xo;aY&%KYkZa;y^WYV8uR<`y7=w8#sTT7#0SRHM?`91txx%(THBw2s6 zGW|+qV^5skmnZ*5X%;2^+N-3}$m$-D%=+KK)c zT9cgvnrjwj*kD2~+zrhfr?Z@fg=BNRw9G-wOP)tIRFiQ*}9Q9nt1) z&y~c=xkH%X^7oJEVe-n&cUex{r~Ir%pB__7E6n%lBx>5wJjDc4&A338?|$4Hl_2X;#60-zJ9Qi;RMsJFGyO|w84Sv+q1iq8JG0528}ctrL@|~ z_!^+~XP(D?omtLxs}J;8OXkjaU%N7Y^)nuiaePLOCr%^fPMfsr*_QkXrr18XhGs24 zj!JZGeI4KXt*>{#pL+J^xby70sJG?I>P;s>8t3v1cUt}DS#D=~gM>*pj@tf9m>MZX zev!uid@paU_GzE;w6+EuJP2IBK41Rj<8O_F7pXIvH~r6Y5y*J6xX16h7Ma(_%pyO` z=B~^ykLM|;jZyeklqmADz0ahd&7L<6(z*Ar{ZIZMy!ki&0k)3ZCajP5Ld*5Ay;*#0 zvFxmW#sAlmC6AC^g<`8jntL*{0F<-+g2kz~-oe`T6wf{VB(AT||MK*Mubjbsuf8T; zMUs(Z8=)t@Iaa$ZtSZY@w%nowEid2aW8yZeu|GFLJal)Y1GDwgEo?5ZVoOxhZ;x7WLi%>Kz7Ap_1uJtg=0qR9Um;K}eJ)V4MLG~YAb1Ln& zYJ(OVISZO~-4V}vgnM99rarLTpGKCW|7o=vFCN;BvvxzR|CE(o7RnCK$nFsp3mTm_WC)6$ie6(@9 zo;e3x6H7r#v`@!N2p*@A?nxYEqiYF{VOm7LYvDTB&xFah&UJb@PVF_5Zm;f5FW2^( zKNZH~rX3mlF1#o3ebVN#XLqq?P5DJlmWvne)80jj@up(u&Dqh^qUit$_6Va^*EC;kjSE zgvTCu5E};%;>=rb;{1gRxa-6nICaMzSssY&LUo>J-b}}1MZXLf(=fkrpYl}qNLbR4 zbiThA)3I_6crRy2{Zz^#ohwSQC|#~fz{yi&NLg}kfknmdYq;C z;vnq%mq(BHsbz@LVq|Frau`{2LRWn+Eb6@SS;Y4k(lIk_E7KowC>}YK6p%l%s-1<hltl zoG|8X(^aB0?E|gK-`QC|>e40P=+XA8N&B=s+SsVDzMgRH+W5R<@o)~ql(dMgV;mmV zvq{H{yk4WUHl61e;<@zQv=#FCCfSWBc! zma##Zr%T^7IPlSX*nIB$cGIpHzsYF_VIKdRkO3(`qN20;PETnv!^OA zhez!(DRr$}cT)E)%9dP} zVq#HQ!{TQ)UDW%f5#domTyGNpZ&OO!M(yO)$F^MQ9k;lp#a8kVCRs8^8`{*oiB`uU zq+Qmwn00;0_wLtqDRZq!0);D_E16)0{ zfj|AdZ}+CN^!$^b!?d2@zE@tGZPq5*M#BHk-g^dFl4a*%U*>z|tGe2oX>VtCx_f#& zX5H*A7M6%590>#g2qB3Ih8Pq@Mo5$*q+bk4AyT6LNI^*fh4@1uQIrA%DGC4yEf%|2 zi#6l@^h{6NY2Vehs;la~O#R4r-ZA&w%zUQW%+!f^Rqx%r=3IB~`Odj{?+EzB>S9#T zx!W?#;%LUx+V|N|8`V4YOk+ zPkXfC9G0jTrKQ%xlAS-ip}UawbQjg;i(APs4*5}#pA9xDuU^#aGDMZ(HN zJeT8=!#Lb>7A}x7SNom$i}hrzO?olVXfZ4SkSD%%xLtPWY9YO;S)K$HE>(8C$QEL5 zY?&cR_*Q(^XMhz-Om4!{PAI`>215)qDOdR>w5^|9-ZY=SLCw~bTA(PIj6I2R%N889 z(SY2b&AB8dHw&L-n`%RlU36n(&L3B{uAFz#?%HWAzuU2+|4V0e_>w?)O|%|Uw(Z$G zq)kQuR2$3jk#xPH+Y&4<=U7*iU$#R6d*U3#cYPIjh=;@5sp#ajn5>Z_O^y?`kMIWh3<;WOcih^tjS5#cz%x2A zt>c|ZlXO$)zSixpscf!W`BA2mJZO5z>#yf%HWNJZ$o=NzlSPLP0eKD_KYl;CDAxt+ z;Nc>d5c4Kx_Q?Evd|0K8Y5Sc{nVVl0hg;cZ^@RBPo|yc&O?dO6EYEB-X)G_jQ>f2Z=TaTNOkbcpYU=lkEsXu6@8VA; zoA}GW{xxh~zrI$wUdeJ?hdaAQKS(nFlR~rwfT>&$m9izYG{x*Py^+sPXxoX~8nvur zjhOSd@-N0mEM6J@t2*Pk>Y)FEdL# zM<-tAoqQ5;>T{9z`JIp8_+tl=)z}?0w|+hT>}P%&jaD09`1W^^wu=qPP2|Xtp)JN) z2D(RyP6#Ldl5Rb-&eme770K7|>9^G(IiBUY+#ZmqXI88A=e2xFC2DO>pDjwy?fwP& z|C8sR#np`)oU;0-_a1u`OU+U2`QRjSkX3@lQ@h*Fv?C#bv|LnEXrsuxp?)9qv(m=O zUe&c$X>baqNZoV=m91)Jc)W%3jZO_o-iIO_$yl1_s1+j9Sg9M?`TR!m?J(;7oc*;EF6CGcgu;qg7_j`DXkmr2z$5}iq37%_EtmA8; zEz?_PVhD1)Q@Aw%;%BnuEub%c$GD1>ZTPi4YP?y>rmleAq1~uw6mru4r72U)fzi) z^w{#l=s#cj;qzAJoK6HMym5iI&(oMnx;?L_M*FX$u?AuE!#gTBZ5O47<14A)sUI01mh)hN+Xt7tF;kFsHlZ6YHo|1Tmi1s2 zHm^%0dwO%-mDAvP`M9JXt;I8_#>%K7-8bbJ(o5@Uck%dsIsNvvbX1pVfOYV(<;zF! za+7*7zUW3GA8*qOo8)q`8?-gHkUDROgDu~^yp&jF`{0!oc=4%?nOi!OOm5buUZrg+Y>Ji+!=w{KZXOQteTe%l&X;X1 zOC;i438y99u}8TB#nsMs<94IdYkcW5Up21ru*P!q#Nsfi2UgA6`Z80F6?Wq5@g!Tt z!^!qaXYN@&HZ@;#vWwN@*lIy-n5vT4u2M*$VgwbaIPHufbn~VjV4DR%eWdl`unhrg zr---rs&2DN!zYVVtK*lA)cT{;%g5tIhjIQE=lSbfh@o>6mY8tMgSYm_@U+ZXul-VA z_Uw@wH-~ltS?74`d)POYPOnx{K8ER<^S7|`|M|zrfAv4a>3kXfjo=zz_p4L)ny$P> zLZX$tfp&G|4vo%E;kQry6a2G3`QzGUgsVS21FE^^5k!=BSNv7F*F+l)`FBWGD&=Mt zhw18CkQk4Y^XQ>9KW#YE{rOrS`^7d>$Lmz5?xD^f+K|H4K>yY$%55GpSD!y`#qvn% zdp>%Mg_8z~fTuyo8w1jQE5kiL8D(n(Tj(picIL&h2G51wVzUZk6D^xacm69XpX=5 z{0l%1eCCa}F?0PEaxwmB^wAdX1a$7R#+*>$@&#R%vewQcNsrjx>~5MuTbj0g=0Uh; zkCBL1+AC<>z4ZJuxVB+EvUIrH>RQbv+KuAmb=F)GG|@tymf*G52DQxi+FKnO1dnT}Rxi(38v8tq7wW?{UbVKUwK^}Y z)Cc^z?AaK6{X%mZlFqvxE+4ym4qLzZPci$>U*PIfU&ZAYe;uvyDG?{8QHJ%XM|unl zq7`wANL@y+H!`NxCFL4R`^zqD--c8BcB9=K4BNJvO|+X0(2*xasR`1~y&A>Z(&%fg z(RCl*+VC*1HKU^#%4yq8ALx{u#6z*>hxk-?+E$ZqZtE`}J+y{v>i11iRcWj_W6(P0 z?sr*UIrUzCxdEX%t?re?GD zVM5CkIOTTWcb+I!LpZ0|45Jrh3Gy@$%v9Ydu5<#(mXoH4;&~2v1vEV^{>sa%q!B1b z(s8$ja9WQ&s}3h3RSb0N9`Y0(&rlNs%~p+-N`v0YPH)o}-$UoL9)DW#wa#fG-p~&* zZfNwfc|wkv@a=iKQL0Eo?&}=%X1bi+EP=SKrCKB%RpF^_y-4U@iUtzKZj!&)KoR z_iMQGvwQK@hac36pGVrbSZyRHtoy)(+P?Ej@wL8cdQc?!{a#lRGt%p%u<5-#3mQJ= z^ttFiKP_R0#qZ$x5dJ8>4=X=yXseqtj#lFs-q(+-C@#e%AK|m`spQXF!z4%69Y<1| z!sV5%vNXM&-RiN@1|wHpyUt4_!g2U%c&aYd%%iYB%I2qBk2M~VeVeG~I-bTajA86| ze(6*q)=b3l$GN=s36NU@3ZhL{a_y$|j@{pF6xb$J+i3}1rs{jq$^|-3qxFy&xFMcP z9{JT*zx^eWE07kY%(~_Kn2a3b#TadOT2E>(p+*(MR=G+maT)O#&YE03ml#y{rNzNk zo8lHAbRWK~>^t=3c;Yg{vBYz-=o!03UyfATf?aH~Za}{F&f`T}xr*O>S|H0aPrALoYo#PG1581UNPCnww&S`) z9>lV*KYOjgvX-?`iSu<1z0Ea?Pi45pxH3G(i?Iu1`|02rWU@ zHfJ>}t<&qY{5{OuJ}Z+tI!~*Al6Mwxs}!_w~u!oQHlXH^ccI+i-gKuAX_# zlLR-{tSP=XQ#88%$zl|wpku0vHg0t5!x)Y?Y)P3?SkWcA)>a`q*J<=g>r@?0u1x+} z$r<8mimx$u9GAC7nt1ccBe=R@1G2`-oP&Ddk*yeATEec6PIuatUv`#u3#pY+4U6%X znzlu^p45{unLzRGhhBQGsnr5rdMU>fPb3&0zu(+^I%s4B*t!(}hOu$GcO1^?s_;0) zikDl&)S9DA9ZSQd`1yNz$MCqNay%cV)wVY)e?toOLz%V?#WeO1B>=$2AAJwA@BBHC z-NA(ye*<$zzlg=z&3*6?t5rQ|S9hGrIKFOJo`!yt?m|0{|wt3N&h8XQ6)$Y=8Gcf;VL!TZix%-{dvN1`H zC3~8-%tL;>Q?>0I^qzB?p4t2?(bfh)j&uJU@4V|Y;0^cuMtV37X(dRZuMyWq3vQ{H zlq-|cHjjR(t{hpVhnEf?PLL!yPMuB@*Y>=!?P|!fQ?8}73hEP^tp%tI#afIZjfLSli*9_oa#yud**qyH zmbQK#{>n)IwG`(MNn&Y~B^)VV3NBDcJHSo4f9!dr`sHWKH;?!Nr4ZW8L_T)=0J>-< z2RgY^4!NnP#c&cyC6K3v+xw)-dVqSL&T&q=m=_%`Ox0!*c1Sa7Cp${9c`oZ% zB!ITyk~ez;g-wO8bkz+}J$STxcY-X-@!^O4 z=W)OAu$PaL%Am4wXvYfcY?2c7@i2YAXyxZW_XVt} zu~|-PM^g986<@tmy)+LO7JWDsi{50T0E;Vng;ER-?I zG{N|WZ_gSN#^o5YB`9C3EA>MB3N5{E8RA~O7I{b&>RE^}s`Atv=@^L!4=rE5q%OnI zmV953#mKfEGPUJ|JVrLA)#&B%Rz>X!jhGKtDzs#ZA>|)=wls&l3D_+PoQV ztkuuM_%dd%QZ?*rJJ&7Nrjl}S3-jy8gnQ<%}xo_req^1MxZ<$UfVSM z9%r-`lOMkRS|;0g4T+WMkAID&sf=8OglmrQ>t`7@UAm09_3Kt_)Asz-6mG4V5fZ@K z2l&6$t$WdU>ckudMt)E!O@U3D5;RsXW4Wg^G6HPd2DIA=-hDUk+aFETD-P#$RcloB zEQ#TBn@cP$$0^e_%JQ;hvkVLM)2h^AXbjWyb18>?y`v7<{MWtqEv$d-TS)J=ac9SV z+&XX+^N$?B^7PthzHvNlZ4a9FcuqF8PkP<|qmmYN^B>#g<|kd2&=jT|1$Pfg<1 z>>5?3+(TDh_quCMT*tKWKB;R>o&%RI^}qKrxeH zt4}<+NPrKPucy`yI*ctikCo$v^D|DLitzY?q@RWD-~qHSUYRkvY@v&dn;1W#Q<|1z z3d_5py4P8~_YLE0B;jAgsdX8K@pY(Qk5JH+8Jv771I!F=_!%!U4BB)!y5W4%6FZ_) zw9Up^b}GueY`>HFE$=v*n^+Fw5v5)3vjI7x$`(*LQ{p56 zJ*8t~QD~A6#~>>bywSg*oYQ*4L#o0$axck|CwiVWI#+-oPgJpFE+gkg*7;6n%<*;M zvPbhyehK)@hQh$n2A|ko)JgXeuO0N1pXoNERxhVA#b;2Zs4mc7r3aH9f4tbZ{Yi3E z$Ml6FcW*ro&Xznl4^I0NgBei@>SxC=3ei+X@ez-DTnq@%FdQ@npwR&cmrmks_ zc5aVN;?};WFn)0nNfyI;pInd~QmFCQNmGWXhA|_m#(qo&)=l3#KOSi*;NzGWc|6+~ zy^KOns(OwV%p9piB;r!uJH^@a7J~6WjyDr#4inj8U2@6nLj=enQ={MWaLl7;4+E*r7@bYafth+g@|9TrtK1W7iY;_ zasYJqRPmH*Cto(8m+aBa!M=14=#j~s#h>|BqH5w=N}1{Py$pwHOByfj?q+{Gu1*}> ziyQ0KLd)h3Ce3mjd-XLmTP@M{d6xq@_SrT;C$#5cGdIt|v}nT5PX~>U0}~U2_x5n{aJ&p6Z7-^aiNo+X?$(@oW!TkM<6-?YZin(L zkG9Nkt+)Jo{Kdm8c{L1IOR4qfXBOM$NHBKg9M-)1Bg`HBB5pkTJo0qJ<;dC-2B)}= zFUyp=S1fK0Szo?qvaStM()!uinlTfxo`)I)^X8)_PlK2C2``Nf{j}iNdqc|p-XS}e zt*#_AknYMaUjVb#5ML67TfuFpCm%H?Oia9({X@o!*Heetc%B3gNw-%&Qp2_vo#5Q9(D;^Hwk#LJj&F%uLdLL(evqP%);j@^X~$i&^wN$dymw6;f-I}D@12GxWl=k;@p+oSBtDxYf^pg$7pq{wh(^Cn!|u)d!v z4NP~Yrf_lVX6!z35*nLX`+%>tg>mRZt0ZuK`!<~1yJsjTZ(iK81xc1;_lZ-Oox6bs z3ariRXcoLqK*x$@kSI=$_Hykwrips-yytqx#K%)v`J5~JU)i3c+rQCnW9O;U`0(I< zERT$MSq_bo;A8oc{KYhSk{We%9ABgUq}ut@6xg*3tDCm(12vn#?%lxgSLdI8dk5=)n8gm7{7D|v+w^Hvv2Eb-*j=YF# zPkj}4H*PP@zYdadHz+>$lPl>*+c2|F9`sYk+XAp@UJ%*6f%jA6kdJ zzWgMwHGB60qoaf8)$DJRwQu(E0aAZ?S5cxmJqD_CH3-TCQJA+MFDV&P^@OBN$7 zNQ7o0mpsUo0J;>3w#8znXzS6W!+WW(-;RF2;lSdqpz*b(LhVofzPKRXQ^HU zEw40l3ZB_mF1NZDe2`-_6TkRm@U*jqm|gIcH(fKCigsiZkZy0?{?xOwU&3)@>tz)H znWwI~97j2%6JL)P`Y$*9qkD2&D#jeeIlui8ymRC;&IkdX{n1ab{@OLw{(RzG+AXt% zX2Px-S#9ee`H(Z&E0y!(^DJZ>Z_VpX8?c(7r@i|co?hv- zj^u;qP~RCoFe`_Wp>Z}o?j%IzO^E%WnJPN+#+%rB?gI2>SczHPq-oaE%KY|BOuSxY zd6F+Tkf-VpB%Efa(%-I&2djcl;<`45$BB(4y(fPp2!;j03ZNKL_t)omKz_N zRg)~wwu8rCRZg+ClvhJ9(v zOvGQCj#oX>m)T8ca|ypQZjs?dJ88?3#M3^)({Ta0HkWB0WpgV&H}l}Pw@PYhP2csY z()zz#apX2+dD=E@X(C+1^^kTacIQHr=dX)|WD1CRM>A`NXdXRJ)$QrI@~wYvDIsV}Q7 z4(9*i?2$%#sR?-B zE?-50q;rLKh6GK}W!VX!?hn&_M7hZMLgR+oRkp9cW)2IBdic9OtzzO&3T@n2IF3)9 zy0_()tx8pTrIkW4Ozg{iZCCO+({XwI_0sS<8_p-4S6nX%wHjHbubGtdUbRuk(-19p z95>|8!@mH~xN`%uZ+;hR-}p98{I&laOEc?Lym&qy)fo$3?luldU|$EY5?1PC*6N)h zMVe=L^sRSs{4JTQ0vg0Eu#M8Y~%tn+bp0(8WY$A3% zBR&*H_YX^EYfuwp!R@TV$zAPx$pyK+IuM2zq)LWTES(f3% z*)!O+?GcQQjNrnR%eZ;x4%W`B!RGbVFA;=gNXrL@>2`{vfhuj%&b3uqrF%h-JOZ3M z2P`cOmQT5Lt}1QSoUVtnnEB2rK#LD}7_U)LWWlT-(o5$drT7u)Z=pGz41MOOC$;=(?-W zjZNwJ>_+X*q?X~|#B-5Ox1q;B10)IfV@{~@aa}%FDI^VABqf$py$L3!Kc~&>Ih@N2u$&K5I$N?Q*Xxp>g+)Xvnv2`Ew91b^g*ClO~37<)$ z3&d~kVG7sdMuyo<4b+=WwD8{HM{#BIMgTcl%_dsSrpxE6Pd|x9o88S@&tJfyci#s| znWFwh>$Q<05hIo^l$LET+mpwNZaE6m@_^G9se4ywJQXq~8)ETS>61%98Ja5csL;~%1tXE?QY_fWV$ z_R4G6bn!CsEK&E4pu4v4OI8{-`|YP)7Zf&#j8Bl{?asGw9qGRxA3mUNH$Nt|S~ezi zeEd=$i`OA3aed5Zsj64Xj7)w`WzYDV#BX&+hSXVOyd>Zm?eUXD_~icJ|59JB=1odw z&Z7*cS&17;;P|=~@*Pj*Y5No|F^R>bQr622mPK9Z97bwyKDC&h>llSg+V+ZeIENMm zxt_)(e;6K0tvVF5lTaDF3hFc#rONMoDl)`x#?5;3a^Bh8%owwQ409XTVosbKX8UKy znX?$5zY8G8_4Vs;Wz)u>4&E4CbNwbZUcA!5GqgtXtLCX#m#AK8XNv)&W7=+@PdiJ+ zChZvRm*3?$r2m;|u?#6#esF!-&?8V=wIs5qev%uD(G8`t^WaG${_F6#Y?W(A()}%M zM|#X~xLwWVEacUm^Gm^YlVYab~qYX~|{j$SW4hOqSuP zkl*~fjV2Pbu%R_w(txqWSMi)y4txI!RIzL~&dtvf4aW4m+ zzn(4#6JEp%ed{5@4DAlKt+-6SZ`PB-UOQE{yS0vZwexMcIz3B=EYgakLK_;F=)Te~oLU=48D{ZxYT}jgPFy?bjr!BPt4o(-O|K9% z61Y$9zxMCh3iuh@2&9G+Vmoas7<8gt;rZ=5vSTbUjKCP4_z~RFM{{Hym!8dLXLNPs# zsXo$-=`Quksm{m8_Fj%!7m)Zd&IfDZ@=&mFiQ|It7UQ>wfr~c4FEAro&GWZnaXKyFb(s8+Gq!N;$*t1G$;htX2Qo~jF+-<`H;{B8Ive4O&DgXlo6ifQFy4qBN;nJEVsgWd(R#)d z|2Hc!x%tRAb}UiL@PCRUPZ4W&uYxYZmc~bGITY+^F=uz~z})(E$dO=laS2bo^m4Z+ zbxjI41}kH9y*Q61o~_a~A{Csn4b{0wQAMi&dX?(Y=qRvfPqA_P`0@VosOLQN(#1w; zeL!5V9B;F(2Xv`y$)S#K4UtxY+O$%Sva5O(*wzrwmL2K=n&Vzt(ARzRZ_8=Or>`0K z7m;rNpUTUo@7ne20=kmKma3$&0K5 z>vTG`w*rI`ID@T+Uc-DG97Bt#QzI?qb!zG2*IT)1V=t{{ybY7Fw016A^lR5n*%mSU z!N| z+RX+g@5}?padqQHT->^)vK;_m*U8h^eDR{miI*HZPvNK zXql?p{LCb-ZCDq)9K$W1VC~#>%-p!u9c^?jUDjEtwd^Qbx!B&2biT`1mZdC`eHCsT z*4l|o9e-h7a$f$7@u4i!+Gea>MOq8w4QBe&?&4#l1-6a7yj(?BHg4>mST}Y14jSz? zHhp|a)FcUb)bm011h=A`SMqfYE&H{e$&$t=PQQwaSE-z)r-7Y26P!MM@3qkK(HYlS ze0*Cz(qow24-d&2`sPK zi7QWiK9avJ$H&5Tc@5V)s~>s2BQ=yzYLjfHn+ExG*TUMFcEWd_K8rj}aca+Q+?k&0 ziFcrQ@n_em)7W+L6f!gf57sJfk(X?Dtxef=!lRhIq+I*6RBb;gr%(R6q;(a)XF{wY zV<#%q>O>v}w^{ZHZx?QYR|cj3k!RSViMd z57m~nrnXMm=kXi86OmGf>wLrV$s-oxuKtMcN7WoyvUmFu&asr6mgYm4h|^+2EFG?t znfwUx%k_a?ex_S>lTN5zNu@ST=OkBQmAb1?uWejM($&q=vxdg<(wM!R7A{^#p68g{ zx~?+r;@oY_&)r00%Nneiny!rR@m4RcwjrJI-;okfypozYTJf}FW=-8!zn)?c%mjRt=1v#bYB zPE26z&CB@ckG}={!a4lh@BN+9^vfe7SeTf=$U^V8Tv{EuoK{vBscVZ{00Ke%zNJqu z9XV3Ww{z!!HvZ_3Fn;Ylod4?Y;Nlm4%_%$NAk1@6Ox7RuQi8u;OAPO0&`>k>Tlx!6 zKhym_J~oCc=Pu$;-#v*Phxg-WUifSeoRThF=LMnOsrT7gZ;kr2tTj!4sMM)?ydhIF zy@&>BPHUj5p4N5pvry3I)rvl^Y^expN3F+OneZpR@-9HrVA`g%06s2=wfRd55ef1v zU-6cY!EGHgZfvmMHBa(sFVkF>K_?Y@1_s~cpx;GGx}VS~%`>Oy75&CDm!JVO8KI&6 za=sRNb9_y{W6A@tvUWVq%fW7JNtEd|aFqY0qgJ+(yskG@r$7}B#@5&f-ah&`u5Q|Z zJPGSebbDq7tL?z6<83tWwp0xZXKu0enPy!>T=uK4PnO`7 z&XJQFw)wtZ!n@C&jPG2XT7B6O?+{%!2`D=8Z@`)F0G-GL^72l%H zp@f(6LC4RX@Ksu+DjFXLrl;$gXnl$~ar>w0wcc}7#zuY|$ohFP4{>lRLoL^q|J(_a z>wSy|sh3I(Olw4gwtSWL9CL?R$!s+Ozl=P1o{0as^Sz93t6%x!fc3d}{yFF_jY66? zI@=HBnUJ)-F+;KSaBN`_yH1@(f*dFI@2lW9PLIF!HYRV~>7J#Ucl1XZBXZTu!RBUq zB~r(WBMnR5cnTM(s=E5- zys#dASoqxEv|W~qmNmSVB?w0ipVP>=gKrFoVPt8GkX(g)$~on&2v#qy!Z`I;Q?7Ar zOv!lK*{MJB>}bY}a>K3se`DQRoH($rdvbP+PVU`PyDpLzCMR%n-7MD3-RRaR1z{e# z%_$A)fo@wQs$TLF!^3ov_`>uA&hFWP)4O+-^0@u%Ic&ao2{{ssEG}d1wK?P+oSb#P z6(qNFNX*V7hou$wCyyF!N3(iL7|Ilv=~C-S5Fa=EU9Rw23)Af@Z}|$xSJq5%dFv*; zefaU(wvsZsGd+b54j#akk1qnC3*8gQ`^ogUC%h{yXWEj+x*GMECp&eEtzzF*8U~Gw z0Gl=emoN99N56Qud}WGbBCou-o>yL$?-UO87CYCZr93QCuFSn~WAhI+Tgz9q=3GrS zf2ooA;rzX^a2xAh{WFYTyo5`i{j0dOcUO=$hOzo1Z#|M)kk*RiYUXJ~1->L3H{Des zR~ZDqGbGr3@)T~Yo$YJW_UO_QX0P8+8WKcV6e7!pSe@m#uo}9gn5SbUX)xPNS-ua? zTF1Ah7Ubbwz|LZ+@z_x(^CG;~PfLe#jrps_%KB*;#?tuTVg{YF#x34+k{^w3y<_cJ zeOiCvc=PQ1uC9H`?8+-5w5z3M!SJpxl(;h;tx}Kd!w?Uo$jq5M<$j%+l z62M1og{9XkyVYvp<$w75$lDoS`0xH*G%H?gJ@xGKEHemUqA5&_~k=?4Wo_mE~nL{#dS}5vAc}=S%;rLaum(K)4-d*^cjq9-Bua@ z;?^x_HJW((hc9<^B$nMwdR?*4wI87#4WeUI>+}y2<$1A5I8A|)?Ix>q59r8|1bLq0 z)TzPq8q_ykZxq*G+p2U5DwA>@EFX*IJ*_Ux&wC!?c|UG1@-S()kS;G`^Y{NHwtVNC zXx_b!^I!f;c=vDrgJ_y6j8}%yZTMj0B9>l|jp31cmYtwz0uCo}{V-(#C(d!yJi)B-gG;PE=x zI8|cO3b0UUg()@o2~{XsG%J1TBw@;KH`*c$O}1*@8x^ zjeYN*!1$eoZq15wy4#)Kd?j=u3|rhr(qZj6PPIdtK6x|2yN^AF3){D%T>_d%mzI#H zMec{*J&r~zQ}ay%WgeGw;#ea3fM=>c6O7&1b|lJWRgNT0F*zEN2lhkqAf??DAWdJo ztrIo2GJJS&KhEyj5uBji549T&oZq$$jaD1`-}?ZK#p23v+PGb8^(W(+G{H#&i|#W^ zy*ZwJGulPT5Y!Sk3F?K!GteBZ1ad)^yZ(|S+&SgSK0^~xeo;HDN&K#m!k zChN%giTMSryEX^x@2M(^ZmgZf`b*c)SRyBRQ4%`*FeTz+>*CeVQvI|crO3uMVB*qg zEKjXLJ~CD-6_;`Uf%zkk6dQ5|C0@^o;`(*?Ty8etXQ3W#Da5^@L|7wJO>p_J8}3%5$$vZS8dFU9KY zONO{^Pn33_(CA?qMVPrjAo3OSw3{~Tgwkz5?6~Gc@wfmibLAlRwFdzF}@=90L(`?GSJn6R2(P}nvZOeMR_T;gW zGJB`2k>b|c8O&V2)oInXXvw6*Thf&aH0D##3+Gbam0zn}PWM(GtkNfsrl)~p#}d5s zQjY7_fxJ(nO21CQ@(~=@AG=$YDJ3>g$-faSIK!#foh=t?_zI`bNDL2{p@Ax;NB78wpw_)awPQh0!`x|MN!6A??dxOoqVII2bb0rGh_z*&xr%)+s9gJ5Y3cpFS6{*L6CVOuj@BzL zgymP`dIq=zY#7S%x*oU&f9<{ymJ%UBK0+e-4+Q z|0OJJ-4o%cO16YPmonV`pi$n{#LLG}8x3<{R6RQQZ+!&^e(Ot>@h)uJisj}Ap8C-% zMoSJ?#>9+@u)lhn5rfUp2eV&Snws8VC^K}i5~+a!;Hf(@WjVzLt{ocwS&QW+xN=@% zov+n4Pe@vaPFP;Zhp&)^hR?EI(2gU2`h@M~m21<4hSV^w=avdvK(>K&&cyTgC^l}i zk}tzO18>~O!|{r7MH_d?6(-$$(zuXzKnk5eMem8~job3NS3OQ8c(6Ss$5maSB*$>I zBH=CQcJ3zXdq~#Qq8*V>HZoZPpk>yTYZ`gr>zNU|KePn^W$t@&s-aR;XzYDsOn)|x}8grTI2ZGI^LmHj>*|BN2?X%fNJ5PLNkkjxpxqQdQB%3u8Q8y0D zM7;2miVu|`;L8dmAir~lb& z3cYsjhXzf*N}qh1ngX_NO>pw$UV-B3i10Ubuj zQR{)0E5CdnlgsB+LNBHviR;7s%4Ca`%~q$jm{sf1aZ_0}zwzI(wNhIUw1f|9p`TbS zJPT^Zs5tF7x(a7eF$QVFX$rZiJCs}AZ8RbN(DABeT{%@_=jxS@dDWPPK6GNgY*8Nj zdxix!rA7IuRNm9L$(G zzGixsE*f`Lr>c~Zw6Dk+mV?KHU0)ItH?*_xi_JG?*W$IOhPz=K0Oltr@#CL*4xjt( z_c1!Z2;`}F0U=fWorxA^R4nZ&fSkKlFB=S@P+oBv@gU>n#l^z8Tygl{Dh){E3q zB>3Lotx3-pHXIYBHS6L7q;^oAQ73n((%SsIAa=dAclItz;rIinj zE*i2eWU-{2zwtJR>7~|s(%Va#cqzkK%^;QL2!~Fus?U##n@-VlP+AypkY1 zwvIH!p-x3<;p@y{-AEf}^u!~qz|JYi^V|R*MTD-0nIxi?gSrGNx!4p=Jjv17KS}#Z znd}*4U8+k(YqcvSV1`uPlw3v69XX2R?=B(Fay)nRiOTqCvw^hP+lFl#p_v!~A+4Nj z&wuwBwEn065AA>TCh+)ST)cV}FTe9Pe(?)mAmLIb7y+I+g zfpzC#Li36^}Awz|U%^aqjAgxESzG6kk4t20;A=w3jaA zm&5(~`QwK33Pqx45V2|49LP$$-MCF#WZ5arm+Fwinw*1l?Y&xl^SwQv4#eZwRb2=E~)Tj>$94stgip%4c~3d~ompS}Ww;JhgW>HeI}gv4y+c zlC$pn*US%JXlMI{TigB)R}w3EA5KN3SGsZ~$Mkf9>FN8;$)|(H$AN9z3XnVq^=q&# zAK7tv5i_h)o|HP4u8P+%UZ|V+27gUS@J(y15)g-mvaogPmbNHix+l>+s>D101m}=-kfj*l_s@rf%Kto=?JCoM?^k zP0Mn$$hDv5VlLu_o6zd5DR~04)-;f(T;9V**RJK5olP)1J6Jxc8WX&(({G}1UdS1j zfMunJsNypwCbP=IbvZu1s&a5xr=X?~Glux3?77~&>X#oUiGG2^IO=jIW-Q$Ai`4WJ zrzyj)TqEBuk(o3xdx_;W1(?+6x)2MB$7Rx&M6~Afg zCPZ4sR^h6sQLn$!>exKCv}rVMSMXbf@(kCBa4c9XtmDZQ)UJqe+YP_WTztO!xzFP6 z#Nf9E^-PTfjdr_>F?q`Y;ZBQ*^=aYZdMa;5Y9mR3H;*2{#jRTg<1tSOar(w=EKOSRp?C7;$jx*iP;fqGYq~(zj{P|bD zgfD<NqtfLU@Wf^DU(&>oy+M(M>)*nE0J{awJKDJ$vpqC!c(3G=LXhOz_Qb=D2gG zI)04m;><8z6&|Ko@iJ|>F)b*T-s3rrhjlEQMy|qPDz1-*F|9u2>8NG=^ou=1jn;A_ z+9PXY;}8EBi|e-H!i&Fw>xVyY(#3Idy)iO4=BhIW6BUovOj`5l01`Turhzma9u~Yi zK8|mH`9*yB>)%AOtZ!oBwJvtzD3R5t=z{7v=Iuo*T&3PgpP24p8mR%W#xJ#RtM^De zRyM9JZu4wn7Mtl(q<+Od9gj$Z^ek(ngL1g$pGpexbttu2tCo79)dgcOm21k(lNg31 z-&X8d7{)orY$63l*JFV7bp&Z_IiBq|RoKJFZ=Q|XN0tdr9N34;n>LCvV0Z=&z4t!W zU7N$X?T_GW_m-fr-}WE>5F4&sMGiV*iC!nwM_19y&$+-`h1?_WGx?Qy#1*Lu{~o}n zar3BR3$tBAuo%fq)j15il<(B1#cWXirXvXtlW6%3J$(|9CRnS)XJ=d ziAY)tWF14jGp-luc&oHZ_m0NK_%j^RQngn+PE>|^y)t`U1MPa{V{lzUSw0-E+*V*) zCvK|@DQ07kG1Z&aThk?xvkso?eHnF%n4`BTwFi)Q{}) z^uv1T>W>R+3Dv(@AIQ)^>g4RLxWk~0SFYgEx8D;lCox|%QbNR}!!2oRREPr0QhZWr zejdn%V2*EwiW89q$8zDfZU=PZhRzTDJ+4$)3WtXT@-l{2FGKJgDk<^uJq0q%Bg~5d zXsE6-nDs=jSB|V7wX|-_>LFei%1Bd5EPdj{4D*+9HLxf%-sm!Pd=B%S$zeOlQe+7+ zLyk2Tv1?g6q{+OZuYKl|wb9+6O)bL^+n$Ta3#R9$)-_2~N*PZ4Yu8_lbPk?Tqj!?> zK|&pFHEBSRrzT5-@bwMrx+hEDOS(0?2D8_1Vr+g<)FBsb!y9n*Sr9Zz7(!9+X#-M* zrSUO*yz>zpKXh;)UT>_M#q{ml7+qNEj6&Kl%zTm=CXvGG}tggI&qB&Lj1zG6-4jtoFmp z$g6`jX8Q5s8e>`9egQJ4X3!hUCxnxpK5W+%slTw9lyB0ge`RZ3qBSH3-Pn+dGGZer zw$|j`G-d9N`fJL=PiM~-w+alpX}d6`w8ZaNJUt7f_9gqK>Lpf-52_HKcP+4?<oK*xmdbjJFn5HWlP)JzOU@+))aKZv^TKk0mXnUNkvIHu2^z_BTa%kC>&7SP zS8rZa;Tc_CuOxAZ#lloWId1e;cg7Edh1=cDQ7MX3Et_cF7b(3kF@bM=<;(cux4wg< zB{x!0@6v_>ZKct3GF(sDB%I?X&pnH48`lrS=bfo3eETae;>B-%8)=q5kvn9gzT)WWfR3^i1UX%;}*4VsvqVyUE>(9zlX!Ak92lK0WmowYO&}Hyb=}P#d z>o7-;CfL667tpQJ3Q#{dr`n2BJ?dj?e;hUHv{iVRIf>~rJ|CfN%i|{0MMLy$wX^yO|t= zo}FHfP^%e3rI9Ga;w3v5%C$OKvVA6PE7ArOqjGu4vWst=ktvyz9Pt}l=s6z{!-pPu zSP@Q`)H3xe5K?zzTa?U4=2eFOrJq~&w~R$~B<#jLT7SlPr}LiKwFB2StRITLdwtzn z%ui01#(DqILm0n%7q@4oOK(BS(*);svH~}8XCC|CKY=!K@clsT?qA+^O|8Q?SbCl1 z%Pk%bwlaw0(XWu$54Cb9`iBTA7LUd$kB?CM;28=rCUWzsLu;m1%IU-?U!u*fd&>zgde2dn@G2BN~OF)YG-0@1gBWz6j!#9xpXVV#=pG zptKb!OhK=wTggbjGo)BEcN2})${f?Y<-$em{qQ49-@Ju3nh5XFilP02y#Mie-`hO* zblP~FRa&LqX~PC!|9;@Z4~Ls?KX_cHXR5~NGF5MgpxSm{kB>S&07-sc_0sBma!j9m z6I;IbFEDlHIIit`7I&ZiHC)-g7t3olB2Rj`Z=g5qyz;WAZeKETm8(#-eMhhBY;jLJ z9+Vs#FI~p&$%&!un;TtR!t~ACSjLFb+$Aqo*9cJ;YyF(gv+a1RdDRNPx}HdC+P9Z| zla(H*Joxy6GO0F%{}H4Iq*89a}ICAjTSOA zmZW(l>4ea8I!%n6(#5DGMcz84X^t?@+5}A{=g#k8TsCC^QAjo{oacUPhI2_8X{^}R z@S0jH!}9pZ{W(Pp#VOXKcNekiqtlR^rQ~=@(T3h+z%o)gUD>cgbvk$z8 zeC^hcADU?EQk@jxdMr88_{7s`Y)zz@mRo@w#KWB=iTM&(&XfDPHx~EG>AOh7D^Cy9E4{EdpI$!YsvK0SN~GJgjHldo|9Xn#c-Zz?cb7> za=tzki|xgcG5z|6vEpqP@-8h0mS2ejVi?&zOS;Z(Ju}PJ7VjC!u|`m5zdd7ZY4v?? zWLmQNIoE|SF3D0EoA7Yn{Y|e}(@9|H%CbaYZ-DdG+hW1DUKlt2dad*fkf7PKpNzfW;c6gB+shF(Ond@t@K7XeT=}okeHB#is zVERm+B)B_1j_-cy3;3xY{178|m%*-9{rWxeMq}0DcPRs6`kps~b^UdkUMx5|zAww= zf2pTvj?&JYs=h{iSft0Uod^6qKA-cB{N$@V%GHGkEw8Z&2Ld~{cinV4e&u!oM-!XpW9Bw}Ii&);dA80g% z^wt{vF!<}0!ZE}+Scm$WR=A$?8r5nx2VT1^71+1kwdN8Jybj2}aER6#SyL?WH=;-t;U>8uM5WkR1Dd8S;=Eo3BIwQXjTtzXz?+5%s)W))(PxuiwCy^A}<1)SlhW z%OTc}T+rpsn{aDpCdgx@=-P&QFPzS;TZg%I>$<cJAuhY7@|gF$&h*)G;UX3$CvioboPMuK z+DWu!%|psXc+r1!92cdr9>B3Jvsc-F!(&p}KO>wJ`-2xxC zx=F+zY8BF3OZ`T-#?j2A-r9BYG(OtD7q@4Ix8Z;5g$vky;uL1*ZlK+14S9c=-}XEv zWF573=UG=ht*>lM4R5@y>R_uBqsd8N_wEFFp5w%c>iE4--SwzCpMt7Ku$7VZ%l76+ z49l1CQRaiFj#uVc2x;u<$4GwsZ!mlA491ohar3}2%suxr$aWvbQfW%Bta_Nat{fRg zzjK+@ZC(eBh89z6MJL&xc74KAx973;+T2h!ZLhz24cpG0SFc;fjsVfN48XHkYh<=c zD?v>Qf{COub)4X2X;sTUQ%ABW|0Gp_P$ z_!y2Ydg3oV#pmqK9r*CT{vK*DT#`nw!e}hFCs3%AMGW&a+|JbR6gkfB*fx|6+e9B6 zJb-qRV(*71(O7Pyfuyq`g2#t8Flq_S@6YoU(cEL&=tE>T8gm=S-yu~gN1;;a$Cun` z2^6XYbyS3QmSJIj9=NuEsT~`!uyhw$mScQu6wOAnGX2{}52Lx<#^#SNi8-Mi8f9w{ z&*6H;uumJXU0MQKEudN56{|EvN|Ivp_QC=N-niW_D6XCn^#BmZ?jPL7@{sX-U~9|d zc$w2Kp=p!zkP_L(S}B>p8fh$l4^+$VzC^y)GOUhtwQ@Q!;UQctH0jgwYN+qQ^1 z?|j@YH^y6@3EjnTt&FR4_G|_EL~{>!N)6n`u|$09Jj->+FprS*4M3JdPUWwcVLY1O zjN+tpq_vIm%AoI_(*Gg8QT_c(y?KMJT>C9f(JdW1qq$D~$fxQ)sH5v7;)CG3#gf!_ zIqpnN4SjP|FBDtzyfJ0v3d@>I^jLxWUw!HrZmk*428%pNaA#@?FF*4%j=c6JCT=e{ za#r_2Zo=ei@)8pl__w@=wS7yLIhZ0Hm+W-jB1t?t$v))Cevi@V^B?2lwQG3p@DVI5 zF5(+M`~d*qOV2)snaQbv_${9CY3;<5?Tb}fr3ZzcdMZJ?4ZQz;j;mJ(%WDuk43y2Q zYCTKxP^1Xsdic^SD-XVf`RkCl)n3~jV|CT*cieMPZaefjh*Q<3m2`O#TfX!A7{783 zSDyY^EbKgpd}Jh&Zly4AeJen(V=u%9S`RKO^W3FNICJ4VjvP3MZ~f#)0D!MP{{kjz zym+QHN(!sPZ*Nq#=J+_aU)}N3O%1d`o3_jGjI_9fcbBH!m(Plq{^*qHe#twfneh$t zA>)?aV#R0Z`nWwad4>K;o?R54c6Da?EQfqSR&L?5WJj#6BiA0#TLHC zT-&%om3wOc9xRXcdgVQ^Zf*{X#F57zc zJn|&L>Aky3PuuT>He9}nwb$m5bzX5V8!P^}k?0x#^q30Q0ohg@FU+qFX?tN=zN@rK zWi&Yn?AwMB-oGJDO41VXuCdHToQHCoMaX}WWf+~ifHfyx#l-m& zSUCM2mNy*0#m7I3o4fX4XFIjalZZqfJ5rpm zO*chkNHBS40b9>sz=dsF`>a>7VSDe1kFfF574w1+A3rKB=X(9t`iZ7+9nfBnY8vJ& z`J~yIn=$Zb4L8MK87mWt9Ho(I{qFQg4pkkh%lE>4gJkjDf_s1R_#0zFqId2*o^;BP zr&wH@rz|}ee=Se8Jy_i=GiX?TVulFo^x?@Dn)70PZ1bX)NxMduL8lS5pFhs*xQz2D z-yr3UtU1ux7|UCYi=60m;{qt~#%+DtJi}%hb$KTypB}_ef?>BcVoOC^a_tMo!KtjR z>Zg|?np-x69`~0dyrC}VPd%S(Sd!)(iD%r{T>n|XrP5Q zMjhE5lMo)s@#*)7p2IqA-FlKjP~YGx=TTU`H6PUBWA4Tc{HuTdhe-aTKg4gH`d{%! zKl(1N&)vXRo_ikqckf2hsDGqYS$W=OcR!B|WFTG{8YVnhd3ycz9C@B#_wM`6$)}4( zMu4CG=>&iFXF2BQ?;jt&t|Lk7M&)^VdSP6XEX%{s$9v{U$T&}aDz2lqLP|rurMffS zYrXQ-xV&CEz137#22|I}HLhoBgRYmSUUSMIXS?0Tzx>9Z;%i_23TCHg@V!@G!HH9+ z@#JHV;hCdHk(O+{d;7@a$dVL0KRRRdM_nGDIJR;W=#mNj@paFKfwBz9b70WDk7PzE zz5||?b_o1Fm7l8%I)OU zX$u-ACN5INa8db8wDZr;N9z@FK7GqQKMlXxII%jFVdvh6^BKKy1>67i?*UnctIz%d zZtpsb_Lw~hR;RiDR&Ggh&9mWvZF{|zSL;o))6+<{ZNuou2o7%Ej_>@<{}JE*Pumz- zKZT#kfwW4VnKNq5sW zArgMsk*$^V-ENCy%pS_PLGg24s@7Fv>FRG1Bbx%RWQp@h(MF?#`EpF%zJu8tH*jNi zw%024O;dO7VAsjh*!9tAw8iTt{LvmvNjc~!LOla1e!F`(T#j9*&Hzb*Q+syf&UC#O zY^!MVrOViS{vz6FAb0tdo^vT70V^^1e>f(!EZ5%wDLcbfqPVv0?28J4O}jgLIKH$% z>SN~kr1MO)yR^e^KXVRAlH=swJ!mzXm{?fAwe|H*;kUGIZVuz~3*9jy+n#@OYv}P4 zT2bvsw;WSUgI`JA^+C{!(-hdedG(O62bIRhfy0N3adPouKD15S!?p>|t3+ z@U0&{V*c^494}5MZEFc**Dqo6v z!EYUJ4G+V$-$sY|x%Rv5y*|}l&mIO_aZ_)4^__r#-T&No)4m*>kN?9D87k77zzq)UU$DO{`L84F5u0z&&ESC>E7HrD0iLHeblQck- zkBxd%7;(ypjXsh;f04_Ppdl1<-d0X2Xj^u{b;nlsvrlkAH#E4-7nuJsR%$ z^kuw0{Wg~WUK^h~_SA5yQHy9y4WaFm5!_w-43Ip$R?TOcAe0KoC*X7K2qy_lVu#>bZ~Agxc2$MFPO*)ra^{4xOGu?iHSA!PH(H@;PHAtH{a{moLk?{`-j2k zzDf@V?bwmv?%f>Mt__}7nI2OweH~2Pi>^|Qi|a^{I?iAHERJi#^*qLhr^OA!BI(z- zv2YtRAH9S1ul)$E@kv~N>;>H1`vkHPyQ{w%|MoWyhA-9P-Yn0G&pao{ap=AGas1Fh zESk3(rY9#c-8mU|&(59r?tzUsedQvKYUxYFE8CRBV`RgZ(3+&Pe?r zwY1EnkT^`<3SH$(B;7!k?e)9lqsW={Mu}z!Tgvh@*3-GuGmGsPrY5m8I;vul&(Oov z-FC<_thsTko9FGBsp5t<6Mu1R46i>^{*vJ2{5+1m@)|NEcK#z?@G=(_2yLf001BWNkllu6_}pkF-E*xOnp@@{Bu!mTuxaf+>QG)s81HhcDq@x`wT z6l+8q4LoxCV;}?WPK;yIrOSBx$m89TZmwB_cB6qZn!SDlNuJ~2JMUxm+Re@;|Kgh3V68p*1ms3t#xFxOLzuw8zU| z9_m-N)Ja#?r~Wg4g`m~J(~hcbF|x$Oq}8jOT#2NGy11KE-vFd#c(}gyO7oMGm|M3F z&7~H`?<}a*gLP4PJZ;R5pM!lh9On4~sa^V^2g$Y@pM5J&>ZEP$$cSB9Yu$Vl>Zt~l z)(7o=?l#PZ$75^9jC>NhHNxjs%?Wuf6L9hwoha+6vvn2<&P%reyGXry#N9r=8O}T9 zyWIHd^`b2?+>|b1Ub&&g<3+34GFQ!keHMxrI_;SaFT@#Nd&8z;=9U!nq$5aq<96Y; zW?O zM1VFGFH}@fk|Y=%9R)f@(_i@f7x9h%WC@oqTtfCjZ>L7cxmtB%HrLCZV7N-F^x#ml z2|W93g4bRf{90&WP{VFP)u!Zn`PY#{b;_*D$A2Ez%rXJUW&%$>`kCGtM*Z6wfH;(n z$E`>0Mgt%2-H(l@-o(uVPogzGQ#8NYgX1&y%xq+QlJ02b1Khry!DU& z2(9@=?ElR#VrEa(6`MRxth}hZGV=d&4bU&!{!XxNd_C5TuIX;bXm%oz9ZK8zynGY! zsm9KJcyGGlNVAEfhYkUU4%JR0tqd8o4796&=F8)4SQ`H-tC#~Ntt7@NsQ1}Xj>)Wzy5D?yyKdR0DVNBJ^L;pN+`MxglV{$;^r^Qne)$5Dd;%9g z|La)TvDVLrf+!t|!~Q$} z)ap8Ro7nhhHyT(P9YvA@qj#486bD2tkBy+6CLQmN-rbd%k!bzFIi#LbgnaPWfxb@1 zo1CA=PyOJBUHjDAPaN+1bn5xZN&MjRpY1E{Dh-#G#zv7hQlxD`Jrdlex#4%BI!oEOV|#RAVp)j zjgjSLERXd6a@5%3A|8F`J#4;ksl$7scn6?()P4ayVwpnw2FJFy9^|SuqE+IxSdo)pFaRKA!j${2BFJaT`-$Qf$BfR(5 z{~O%c|FnaN2d7?SNm(EI&+>}r@!V{Booj!XzO1ISUUpyZYou5n8|+2slY95zOcf*D)hm)H714bueg|!3M1eNDlgQAXw#N-gQjB8N@cVz zv7kCK|mPqrP3*O36HbQtT z*>EYt>8<)0zx}A(GgDLe;?KW`rRC-BNn=$cS3bMK#6WaeZj`PnPA{|ynpde`nw$iV z97*ubJNdv)YG81uWc4c7E6}Y5rZK&$ET4LMNT^YkrKvW#51)EnQFPjvY`*{UsJw@V zOOq25c;-L;b)?M{ljHSHG4c%FRy&6KjAux^R(+a~@(klpDKI%3Dt@YLx9K+f(-w_Z}JC zJdSe!7q)K2+H2P_veW|IAjM9@!cdopyowi_+4)Qt8dICLyZj`eO98zxA8W&Y40ppY z_IWm$>NG1yt#%vpXyM>*e+lVm`E3Z3+t%Uv|N3{)dhJy_`@}JfbzWTEyM0GAO*Oi& z)@L{-pOsdJ@;t}O-}nI*{`6gJe0o1-_H4$LxjD?;x`~;|DQw+17`~5FtWLhJ$8%24 zpRH3{v2AKgCw+#Iw1Fo#KkMXczn2rEc4^g1yLr&O=99x#o;(LK&z6`~w%qy<0k=- zyXBoNmvk|BiX2HoTiN(#Q$Jtws!2R#ku*!Yi(9wgwWp3@VtxT%{N}d-6d3W%Cy(Ir zrcFa?mHugdauVPC>R0YJ8>=*A`pNUp;^`m1j13pBAOYXxCT$`_^?i$+hcAYiiG)f;&Bhd;shU;JE=N5v+yB=4DKYC|4!J?P-Ia)Z$}{;=ZT$+``{9ZIpS?E?lH|zF#6FM6 ztRw5L>aOal>Z7Xf>I+9VfCex)2N+_2A#FG#lB1QlT9GSK+@)l)<(e&5TGPr*Mrwa( zSGFtBmNJt`%hlM5B6l@BhBKVu3bnx z>H6qwHobMaK1Y(L8S6W1S=oLSNQ9~A6ei8U+b zCN@L^#PGQo&W#!Tu-vGiVkg_tP#jv@gf-JJz)iQ&vZ52yrj+D)NtTwKSzHys zYZ4V@?NrEs%zL7gVQ)IR)4RG*9Iw#OCxhAr97m>jZc~oHC^x>2#mQDzzI&gKKpsur zY?rRY43LeA)=(EQd6?!GmIhCew0 z{PzP`SX#oV!Si_L=&{&-<@3aWABg}FN2M?}p?zCjWlw2*9s zdvR);=*Tr^5pkTTa==NKR%mB4I6tA1&pz&hmy`cw5@Ttt^6 z!u@NgwvmF$GP3$suD&h1yGyPSz>N{bm8NmyqPVg(sp?3g&RfAmZ3l9quv6d{o%nHK zKvYWML`c$9(*#e0|C`am>|af=GHq)Nf5TjRbi~6CTlJ0F=wnWAA3fL0QmIWGCoFZ6 z+H-o7m!6?^QKbgmCOX!=G`7=NrpBk+r$J)B04xvegzmc@Q*>oDS ztu5NUVz`>uzIk>ItF^UQt*bG{Bc;1|ct85DTtoNp2-2%-P;L_fE=YU9H!Um0qsU+L z=wa&6V#QZ|3)dCw|N7Qugje)zed~4s0-CeUmwiXL9oA4O9%FznoUVaI0C)@_#0ShYC&B`aKgjH%rveK-9h)}&IC>X zzCc00+sP!xV1&k}=L%8{Q#^zl_RfBnWhvh%qb2R+iW(`9PN}^oJHOEE!1Bu1${TW7FgWASqv6x2y9L^Etm~ zYi}j{pYqyRd&?JrQpiDIE#j(Zvl9mLgG!?$nc%O>oW2Eo3?4dw(JftNub*+Njpqh7 zl$H8Ayz$Zt`80A}k!!0|rDP;S=~?NSluL{oI)s{fl_)<;!tFO+?j?JjDo>Hkj!ai% zhv%G#^e3dD_w$+sr9V&_Epsq!Oaz1X~X{>iOx_P3Lk6Xm~g^@%HuQ`3#lu=kJt3EXTw#vXYIGY>zG z#qIkySe7VGaqY9A!?@=*)L1Gd*U3bQ+pP+nsXz#+yr8>rG}65Vp6lYFk57Yd93&zn zuC5BVlX@fY8!hagwsF>!`;R{OK;r08fsT&y^GGRS)+UCT6csvnN_B9Jdfzk*7oS{q zRlfc#YCPi4<0DkTNEfYzuHNJ6lmnhhTgb4?#Z9}w8GY9_0nPp`X2`V}YHgECXf=!) zXjOfpW)>2Fc^&z4e$QOQ=wKjj_A7s?UfI11YwUPFo}Yw3DwoBci&p>u*LLp=kMc7? zWZlXN`mbI`aO9HDz#oAW!O|=DbpfST0@RUiTu3LwGxdndOB%V_mD1`N@5M?}a;1LU zLQU)>$WK@N7t6DFny!uxJp9U2a9szRD{Oci?e0R|(hAx~CqYVTK86b^l|kgQR4Rqe_V(D^br@S*D6@a#!Uk%4%gxnZ?-gE;&dg@*9ljQrt4bW{GlVPU zb)|vKuZ)iLv48LaF74ZkwVDFQgs+3P-?)XQ*}2HBXJ4y}-bTKT)3sepEItcAe?vi1 z0jp{hf3T^w6=+Nrd_EB+1(EUZ>r{ATCFg6DzrNy`^-NlRlC?R$FQT)n&>YfbnR2Mq zuc6mvy-K-alvII|ES;%Jjv^i}aoIOAjSgmg3O!Q>rj(&ih?AlzpQwV0 zuTRSS5|>vtoemwSqdX|eH)dN~@YzF0B4s9}L!X_+SXU>;x;hJ{yKry-4kX$qrjT08 zBE6amYaN)c0!NJ;Qem(2cG3n{g_RX4yusHfHTKN0y^-qlWK>LHX(IpN+T`n|9z}mY z4kO$va(o|+^Yehz9duN6NZ*P?z$KWA@J2Fo&=ttW8C-m?<}}++tfYLeXe$< znH3#PK`MJa=}Ri*I#?c2J)f;6(XTGU@vrB?pX)eSXzk>yCSR2mMs1v1z>!bR;M8M} zVxg&m0zCjBB^nnN;P_;s<}Kmejr50hJRc`p7Mt(pw@RvCs8W?aPg*Y?4)RDk!fldD zvAp%1i{W9j6f>VB@}{2FCRN+(7l(t@+8Rf~_u#Cp0KPMv)Bv7JFXmH@C^bara7D@ocrwF(a+%baF#*KeM=m<@$Q$QtR8y zTf4T3qaS??52<|c5ia?1eqrx56XQnjbBgPoDxat{sSrmld|ckQ2VeW>)>e+yh#rnWG}0H zJzx?_qM@X8rW3afCv&8x|0V3h9clpzyyY{_mCsQEsnuW;$fGAtLOO(30*n$k#|qzv zSf!Z%DdtRNYYS;SD6%#=-Kuz*Q*fYeyb?WE_^7La@X^b z^0H`|n#GfEzXumSK6>Kug7#3?^YHkGAE9w}0iN%$`ti7)E^`#-+BLoj+x$kOcXzV)Z*o*l#Vp=U6C;5jVz z>_)Dk5q`QBpC{SnrNa7GGflL2Obw#VUS?Y@`ATZuvz29EiPb%|w!18i;u1r>J-D)O zkF{;(kncFirqdC=jJ)(g0YMbM*ZYrqnkJPmiCaeXKVM`zd|05RrFgnRloAm^3Mgh` z(S;3e42cR}0N7vkHc{LJGCzFu88^7nop_^n;RTO`I^B?NE_=lmSly%@HSDXr3o!;= zphLc1l!whhJBfjp(#F>(xW^-ZQGLh_J-!F*`33hTH+NvRwYefw^H%?kf?y<-%fa=7 ze!9`u7psV=U0H>6L?~!W0Nq0)s9jnOcbx)i%qu5t7qr(k=o@_>EG=DXE>Hw-a@^)) zl4cN4c!WhMDJxGR9H?5+vcGnqr2{wn`}XI2rqexcZndvBDo0ycBIYVuXXP}f ze+S|$`f4omDqRN>QVMLnc?X{B;(C8SR_g1lZ7-L$-Moz**KVM0X*KVdqALSbUE?@t z+`KlqUn#TBQYERQLtu7RVtl-Ed6v#w;_^u{;>%Z2SE8Q9@~Bi_ltZNhBs=6> zf4=LdIA~6zg!oGF{?-+oWI%M_z(L#8G&YZoW4yC6GRda#2{g?uAcs_5qBP}>s5@)) zIx3;q-YK1e_nUGHn2|nmW#y5ql;lAF^Wk%W;l|Tsp*V~j#csOugTe$ZQ^l(?%KK6( z%CsH(Dia7trg0K1SEAVR<6|wp{lS-VSUN>&qboP~aLmoq67DQ4aq}oPx;{fsS#0j} z6SSlNytIoPQglyiyWTc3qR<>x`Kex4me}JGc9AkjtxTYu47VT3cK4QOE10x|J0?{my&HrLJg!n!6e zGGzshSq0K-S%`XB@pdUiH?J+Pj{`5%=cx4Y#8-LJ;{;E1EuXF{ER2ie^nCznP-Lic z;xde>vEv$7?x3q%e?|p#RUw#q3Q;GAz03jtZOG|kAt#{!|2iY(p8?C}- zj7>cvSX7G;&r#!LpTh6aJErXLWiSv_sj?&lpj6IlYn91!y%;dc35!vA+|bnLms%Iw zd^2S|{ySPme7y_Lef^p6J;3+jcsbNe-9_WA^KjNy(DV9tAyaA0_dkT;U;W!y?%Yvw zSxM5AE69yeLkzWs}O)^{dnt^F)Uz z@q6Xa-Bq!$*=Fr!=O5t1}xvs4|J-mti>Hm}-;10_=C!;g9m6L6t^>Op*f;)kp!DVPr zfmuNi8>&a?GER?$=E<5~|^ zg2Qq_*mA%=%JtLN2xBU}fR5;?j(VRel<&X^!!-nmnH;x8h^`_~dMaa-s5huz zy^!mf{jGlwQxg&GN#0xLeXhAMaj{KKwCQy2580@kdeqkgM~(@0uX3Ni>PgK&e<)!mH&Ns8QHL)jzluL@! zsB38+TB*v=ZJ6#s@(~0*-2oJD_=_42A)eQ1>{jCKqvi0jJSu zD4W?hObV#WqomMZU!HAajn)i0TwWPgeK=^En?u{wG^X1(?&#h^w0UeC9pjV8B5h$! zCMYsnsDq^-g%18Ul1w0mGRrm9CBZ%2Nt>_h>K(g45;e3$g~I5{s{YTnGnmF)RZlg3 z)O_>cYU|C8Yd0~nWlP1JwuO}F9=?m+m#-kbl4WjII>+R*nD>_1V`}x_$|1?#tx}cl z7uviz0L8v9F*#Yee5GYw*f>)BOqV5-P+=J@T1u&T@aKi|N%n5#$yDYQru#*SM^ZWe z_VF?kSDYvXxsvsKCc*g-Xq%kEQbVR9PTQNu#!CLHxwz_xxMwZ7X-C zNyouz`xev<-v#`8HDB*fN+AasO0Jw^+k2Qh-f>k1tq1(D%i`G8B<^5bh`55DBTMtt zCUruU4_dEyouUeV)k>+=L$ydbq$`TzX!Cp?U6SQ#RsC%3Rc_IWrJ?pE-7un2 zwC`tHTJiqVPohduy1uI)H+J@6^XNDp{`ix;(aH@CmFB23ajinWM06ieIDm*FO|Dl+ zHe2qEf{^Qccrr*j-2ea}07*naRLxAD<1r^~Qk9a6t-6=aX7R#Le}*?+d>+dQjsKM- zWq8(&&D;>J>d$8`QPdnuo1dO~_dR^@)NxE#_~a}){fIjT2lceia+3<7SsT)p+Ow#x zEgHBYYW&p4J?WQh?c?jPlONf%HG<14ic<;ptdi8Yuz;_;^$vWgM+T!vVD_W5?VL`( zE+(g$`mfUTVK(!MU3RKcl{jtM1ibvR!0IaSlb=*>q*THYu*@B#wh?nU6o9l^n3!aS=-wS%h5DV9zFq7j_3}vmWGkPXSpvRcm~A z119@2kb}1%|MDZCHU%*`3h|#l3S?^XdELO`&??gDH15`{LcBH*zW+hWMNPT}dw2Aq zv%Ni0yNdIOLTlK)=P+$gZf#NUZ%PqWd zFkZVue6x5NRXuC@lydV%CR0qXcPkAY^PuEFsMI6T&{4(ZejfrrC*LU`#X?6~or6uS+>w%65RO5q#I{K#e z*+V2*dYi(%5(eqYn5${TlCVz-U3*$et-v6M&}vp}9v#P8UG3-MwB0;A7dlLFB{X+K zF?Y1`wvpkKl*e8k2s-dlzqo|vxjD==H&?XY3UKoM$WgYgQYwm5TJvwp*CU=27ZkW@ zLWjvzl1+(YDh$-f(D?@+HTvo*pd52J09X6aJvjNp&;l;hIyHl(h749~E3+f;z`65q z*E|NUq4kp4_t9u#HlVEcE`LTnXE#7_-axa_MoA1!rBPMb`f|~xO@I&r*RDzAa;TW| zHlO|F=RuU*NNrmmiJz(MWu3R-4nLqlUZ)G;}UeS;T~nP1EstW9+`p)o+` zB_=0U@@7=E&0AdhsF99~rQW@0K6e2kSIIcrm61&EB?Y)ncdd_8pqQA_G)<^9rpY5N zKjlzut_^Aw^AT_2Q3*OymEKiR!*%Q#q@}!o=xn1%wR)XRY#t}U5K^+A?nI;C&zGmi z7vg0oJWj{rax)91zqNfkuI$|%>DNN!3+J9kIDU{w3IPa;%0R0mt(>|-Q)!I?;v(sBiLvNG$vZRHb8`luB1A@j{E*bE1KAwL49k}pt>anAkYbjqZ(LObWhfjWjtW1H9 z1W$pE1~)OW8r$4RZs&Xg>WqfMW4~lsri^)XujgKs?tc;@i1PK)O9F4dEwQ@#dDqBJ zrAgQ(pDm>vJC3*Mw9CmyJ+qNLeKc*;)zj$t>Aywo^j$OzU4ax1CLjJPF8s#7z*6@v z_~}}B^^Ne;HK6lhl2MX1q7e4A;s0b<*(T`-_T81-uHt7Ysa!=Nm0BL0r|6hP>05bp z$`o99c=*(5oI89FBi&mP)Hh1avvYXtqZ1HX-sFC#Q=vYI>Ss(HOFTy|Mh_lVy&q_J zYcH~8yf@p@f*bvPL9mpeyYL(bx3_PD=N67WT&2&Ca-N5?S1x0qeAmGB+;?hR}|x*yqXO&DQEIi^x69NN7HLI_;Cc>{|}OOT)5 z1ujnj+gl+X--ea7H4I+6O69+C8B>>rFxguR40HxJuT8@L!yf_woJTT1M?+BV4?cpt zHU-f*0P(>h2(2}~y$Nn_XAnt0W$FXux^ z*X!xIISgLAicPI;iJi91dKF8@1JA}|?D9vmY2T?5kaCd=g(;h$XOdlTh>Fs>P*(ah zHjN@&;8a6jiL(fwM(?JFR5uG2hyZnw2%w ztgJyP{+!UEM;DuQw;BGuNvxLaYw-ooR5Eh1t7dI1qP&GshY`ZKlT3N6N41Q?G+G(R zJg>lYYBh_@;u4k`G9}l&TxwWY#NG=R(LO$n9E<3o4Ans!%xGQ6-zPZd!(k3J05?u{ zjf^4Xdl)=8fW?M}iqyMqWd(IBtKi31k)e}=y(suYSU-J*vq4OKow2Qlx>|!%oDd_8 zG`6?6vW8Z3engm?Z>wj_H0350D0cT;xCB6AXxml@DdG5jS;vVuzK`bFIY=Ky^cNRg z!NPY&b1ur;9_0XfA4EmSV&Y(V6t~V)S}-anzlMeYgjMPOqK*!rqeEb62{?IDVs^GN z`BoAH>wGK;6;p^8DvQgUrPU+42E-Y?qlQR+RcR_`z7~3?obPJui_)bUT^h5=#3o`O z4rAk=6tyylKn83YpG3;{aPIKI$SE^P>EM}j$Sf>{PEKYWsV!#fY|;p<_e{C6T$N7k z;&nLwed?WZkBB>Mb7yNuyADW~yT~Mg@SgsjnHP6}HpxCmq6!~MtMI84J~xl@)bmpL z*h$H|e1Te;LRF^Pj` z&mq0K7M?y8U8SP@5yrJ@2l7}+Ip7Njl3c^C5r^uKa;1sdHrj8Z4K@^yd)MI z8*t{xVLW=`ltp?lwb{JIBxR{Iq?6J0+2zb8n`WrW7w#R+wKU`E?p^R52cGLzH_xt< zMkgoXIu16qwPA628DmpZ=*JiQf*IxzzTx+O9Z+8#sYHJ~X4nWF*IKBf*S4S~2cLO_j?}Gf#z6$Z}BS2fg z599|ofvgX)wFS~`3!a(O*N^Sp-RSG-jXo=Zq~)L8x>lT$uT#2KhTdL3aT}?KOcjgRvJ&Okh*esS7)ZHQ`7l)h-x?_t81J#AsWboe1r6{ughMxS+3+9 zn$Oa>=6xIgb(NH4M;1z!(xphfX7+qHf*)^GzIIw&1+H9?=77se5)4;xc0-h&v z=MIo9XSZNNsx(F~T$WDBMrvtx?V8zfG~T&@_A_sy>DGBHb@gHRnQvou&(TEftVB=5 zwJRBZw%5db9@P>?%NF5Zsr^;&3GFZE6=se}dc|h9rN41~63@-=1xW>-1u>vP3Oo|Gg7VF}E1`;0 zF<3&PKH#OCh~XEY2x@Bbs$=9du}ccntgMCUvNb74mme7%q+e`kz(>a)kEu;SU8AEo zaP~YFG7UKKWZ|?`sw`dFw-?w4^k2P>y@QwX%as!vr3qwsP|+xKxIjdpqYxWXsh(D0dd8k3PKawxzRK?7Dmvy*G!D zL&{>5)*-I00HCj^N0PBAFH{b`(Rw;XfzsQ?I#<5%`+7b6aBR`&)(z9NzLJtgonjC? zyS(M}U-V2xENQrbVi@N0%To~9N+FCfC4|mOj@JNcF7%I_P5w_twoJ}PH@lWEW8^bHU zOyD`-^0`oQH8(h$_>|*g0g45rHUJyy^Bf_|?!U z_k^DoCqhTRvhpnhSQIpgvplJ$S)2~|30 z;s*m$v`%%jun!NJg(d78yoj~B8VvXJV7RxZta`gS4-cLG6zvmJ@I5EQWGZ?UpqpRm zTNam6IP%oj=IGjQ;%B?^UG`;xXi|tquwYJOs$t15m%P z1P2m3FI`2?ogoMSv#l+-vS&AH*4A+3)6XKcmH_G(m(jSe$c*{qu#J4l<`K?Z8%*Oz z*Hdu)iZseJ>%lb@`u*r{o?n%!RB38%296vNICrkH8<`b-zPMPWELVqY$HsBF*=1Uj z6US5S^e9@-zl-Lpr{H)wq~@lOo}I(wu@|toeE@zcjn(!ZthRQ+uSq6nmMeGIzFRTu zYfn>t{}-o1$k0T^I?p5Qus*rWb6res>cA(*9>Iar=iubHZH3OZvT3-(6C|KZQXKb2 zdz0g1{eF^f{bjxR)_ZXC_2RXqK# ze={iW#7B5|{{UK>nt-FEubbRGgLAvO@a)lJ!0{*aJXkvXN5#Hi`P4Q&jhfZ0vAQAh zSCNft@LxLWD5in2*`6vx#q?A*%U|%ETa;D3Oq*Fi6g4?OKVF!IpXnTE-w@^^St*6& z69Esd)(*1r+1e#o3eF{on@Om^PuxChp31BIVN}2>h3p7l(@7L=_?Dl4gU}b*Z{tp% z4|CSZ(iCDOqkZa*y9Hmu$5xmS-_6Ewq)*o=(@e>hGGG zSGsS$8-13PqHoycy!EVWjhPI#c5OjRg1}-??KW>+v6|SwVquEPb97Z*%L`G;WkQ~Q z$O(NeHxvuF`bG(MGQ2hgE?w}_Cyaiaa=d^K%QIgHNFm@#0Z5qFaG3ps6CKpA30pMp>4FQ3!`0KWxZRa3Q=Af7Ltq392Dxp zG9OK!c>k#< zA)SqByWzgJvgD+J*=qh&!bCd#H{UAZ+VZP?mTl}j9-;3uG%~g@k>Uos;puhAD zFS;T?&&`}cq^wcLKnJOPsD0Bxzw}?c7UsHTcmx6xEA@4F^M&UM_V?!TaXk9*DR^*@ zMH)T?bMP11KR!N`63YHfl=2|xZ{_SwJ*CeXKIUws3w2RLL=xIalTekuxa2s2GT)C6 z2wM`7@~X0_D5}DQ9&u`&q56I`k|p z--yy#NQ`xM;*+C~lw3bWA3hlvi5@z28ePMq`C3s_7ZpoWaTg_{+0D^5X^p4SP1Mo% zqW3vTAvS1qJvfv?4uA)tNdY=eR;0_6!FO>&m;b9yY#N<_FV$&Twqu)3!?<}Gk_5m_ zu%r`-Y5{a@0Y|u8OQ2e9U(ackm6pHCG!LkespqONt`EK~o;$|_3JH5qC&Zb08HtAZ zB{a-00RS>{OGq!TA(hKv)98dzTWYlz9--|R|MU|{OoxB_2J`5cQT-An)2LzUG%7>I zSAj3PBvd6%?d`z+{Q{RRNlZ^yHgB$*t8Bgjm2dnl4;vS1OL4Amf4gqt4%!CaL;Kmc zkRBhyN^3Wk_6%U<(6f+^i-o>JSZ&(^>A04+?e$y_nYFan+K%7ox1CCnj0%^lYg|p6 zAGeh0r}7AGwZE~m57TXJ32S60&vh~0xfu`w+&Rh&(V=t5xG@<;$2KcQ6eoYN4aGNZ zNTkyO?HhYg%NLdwmzUu<4jdt{xV(&%>!LZv5n^R^6`t>*p+0(Y?EK;)vbkJvv9Jm( z=YY)(SXo=eU%&efq?CB!@h5QU#&rx`yor7N{Wx^&2*#$TaQea^zV_tPVP5Z@{saeh z?Z%$%I{*X@+r#5yIC1t2X6EP7+SCNcaWMD4zJayVcaVAQ5T+aQ_I$^|58rtk0MOFd z1lM)2u(X6sT^(wNC$V;I81HV$U}1R)ZOzSi?V0EB_W$xWW}d3YqXP#qGe3ugr6oLj z^cZFr=JDgUTFlPP;klQe#hV|0i~~D&VR8F*;5UKxmKI#OeGAVYV?oEh@=SbZfBV(& z=kX&CS<^d?gH5e%cUrKV}bj*3r@$IBb88bl~iHG|n#Mi+t|EDNC;AXXA%h zPe(^|?qu}4cwxQc{(;qRIvtqNMvRgar~Y4@&2<+7&JirS`H$k{kKqpSVh(W912rH4w5NBLIyklj(C{$051` zr921oZJs`kNHwBI7$Y!EPVl6tQ2nfqPorJM${8ejL>EF}jXY#01%}MO52RPJc>ZsG z7Pf=eJ#<)*5^Jc@`c#iB=E66|4v#*^``UEv(v@$tituj)_O$%5qbr@(lSh@Rq$r&R zUV14Q7w^9>F*jGaylL)NR@63gyB8vV95A!xSWMxqr`=c>QqFo&tWNs#;sDxAXUj1z z4OdpvwaKG6*VNzPl8bU#(+`I9G2GjO!9xQD>X)3jf!YSogAKDmO4Hb`b5J^Eg13`; zp?sQe+zZbsJqq#{iGuIIT^RM_J59RLw*#BTCsDt+1ZAXAas*+ zsfkS;m`Ug`vDDCjxz-j)0IPL%MV&Z{(Nxv?U!^>))zo0PryF|*FGd_}bd_Bcuj(9@ zb4+DKD(+yj9xh#u@>}QY_EwQejGNE`gB=iT-Utu_onNG)N>Z(y&;YIS-84Fmx|J2o zwzgoYA%pIryBc3pJ>NAlipKdx06@#kEb5n*!wK!6;L?&>ITB z@)JE&ZPLqG^xPVT0FXmeXUR1Ks+D@bD_l(1dgN`hL}=~e+629yY|>e2WWKXrqhD&d zKmY(B07*naR6&)h#A)+p!1o2NUX_@ds%+kc4Seg(J4(s1aa<0C$}4Q#E(NXBjo(J= z#Sf7gxdtb@iq*C)nBD#`=C>Wh%C>&2w%xlU+iY#Ie>1zGS-%%et8=dMh_AG~K2dI{ zt~o}Qp`@ZX>+Qa6xY@TI%bBQiYI*fjA)o}vsz~RLAkRUR$AnGD`Lc@oX(di>%yzK*qg+H^V{8M88ElBl{p1pI zpWK1--#mkwbULj6d#67E062er5tnPP;>OYxeBVdT^YHz*-q7-MnVouMasubCUd5}= zJcobxgYVqBq@3&5##J9fsG63ME|Mwq-Wqo$(B2uY9Mr>(p!Y@4c0{;Eq{0IU9 zHR%*w$H9@k`@-}TNxL%Cn91OqFMhRn!Uur3tK93ZID`8o}Rch$J1v0Y-_(TxHP5Ix6bJLP+mHh6&&A(>v`}h z1nN4+#&G!4GsxvP4pQ(is(*6N16_;2+YsC{B?z0ow@QU5l|oK4b%?ys6eo136smib zn#G66tL$^k!9n8Mo}FbMeHuqAb#=(4Qn=Z-19y9Zodmw)AX@@(-$=S&>QSZjlkYh2 zTsIWfx$CG7xfGd@yO5!J<4G6O1vvZAjkrPW?8@}```oZ*!ZiggRHR}7WvE41D|MK$ zBZ17q5}tnJUAXXY;)%zw%#MEJ)HFYjM^1hcLK6k!Y*DRz2nZ?RWR)YY8Ig+&j|2mP!D%3#<6b8}C3s;=`w&z*{bR+Dlk)*zgf3)3{Zq_P zYAStf*Cv!C21zaD0AIg0)eLGp#6=S0Y}+h1=qs*{SEJNq?o^^5Dp`Uf%M`z&zUN;+ z)zHt64jPR@O1RlTidVbiwZ6`CG>Ryu#)KYKjD#tER5%Ge=5A_T(H4dEg+xzNNoO~A zaaVz4M2end@7&9Et4jATDe>mmF@aA%m6)6?oW4}rXyBV%W==9)Jqa`jY4JEl6Sj@DI5 zMvFs}xbf3Zka~6(_U`C|5QSHr!m747Nmm&{x$071tp#Lced5Nc%94(W&DE0|GWi{; zy(hw&>8fHA3pioxNrT2WGY9xco#GUv66hG4!sf9FOt-gUv9S@`ZrzIXg33oZd}rns zv2*TPgy))uWG`=qS3>W*Xj=GtZx0BkX+Q6edE8OOV2K9hire@HO>!@2D&H&InGmEXaheEwV)KS=Wpt4zSGp=V8lbKs?O<6#Xn}$fKl#faJxl<}P zE-eN+2pQ&T#!oYmxQe_@XH6j=jzgtUqs`HJ2w~1jGZQsNNUdeu%&sDD>zkR)vBJlh zsha?7k{8{xkv`MnXnpHL6%$vf6bcT+6liJ+j%OYpuUy{u$`D*Sm9Nb%)TTJhCURNS zO%0>z+Na2jUPsOBIC7a5OdWg%^E)3xwsCz?pUa`--=%mun}$#2Z|x6bl`6DiaSfp@ zAKglzYZLXbCc*DJJGNEKVOt7;p>4hBxjhUg8|B)nj#0gVd5>fHjn|VD=Rx-e_4Ej| zly{iPeNPk9Q+VU!6Zqw?y^{EyKY!zOJp1TTbaezLRSjOhhKcEE4D8&AAH4lmB)#YR zcy!6wKcT>fTtgR1YkICQ)?T(`NE6V{yVg1FCb~& z)z;MDJFmP7*LCsI@uxy(_$n1A2Xxv}AiZ-LTR-&|;5M76%nZP?N|r}<)LtlUbS1Rg zo_T)esZ^AgLW|1I&b75Fg`amxHJw^jUIFg{BwU8FsRl~RYU?rGg2^}W$`Cyfncs$N zgC_PdLp|`*pwwn=)naneCRcqk;&U8-cHrkv2eermb$ms2Q>Bt~u=)nbqdTezfN;$6 z-dB#%dQWmWhL`Gu+rpy`&}Q`QDE`)UFad&9wbeJ6`w+E2tj$q{ZY$T{t5p}Ii z;343_cD|IpJ=rT-zu=b_+L@L1K=lHj*#WuvZ$V?3z9$bQCqU?4>G^5Cs5!%B7G0MX zH;WODA=|TZWT2$)(ArU@DwR&Vb^)oBz}d6+b_B)ElZ`J|m1U=n&whsfKl|s%Hn!u^ zZ~ha^3>=4_uCcsPeqGCHXWTn)>ke-~i^Eo3PZ7!Ajl6L}^>AsVUh3 zvPxAdmAJEuZE50WCR&cD^)xXs3aaK*;ddVugfH@{n0 zMTFGjSp$IZebg^3!-a>3PM(JEa`$fK3@za1Jk&0%cd_DMUwkGh2wxbX1EiBo_haA9CSW?KtuQXf5e3aPam z>gSe_Ln>Tn`HIcYHsDNEhy47z>Z)z75FiDCueF+hH+MzWmFhf>R+M-y+`&N^tEryR z*xs~*UX4Ey3Nt~;Do?(n-i$=1R6x3*rNh*yi6D9y7WKP=@;nYJKSE3|oBo-w-ez{t zg(GP7(-m~8e{J-685AA_Lq?U>PnisG=#aqRpv2f%W%Jh8iprBI*%kx5I+e!BlY)4= zw0-|lJOEZy9BdbYYH>W>UYGbX_54iGZPrcajyk`PxU+RDuJ7tcrD&zD4!Lxiac!MP zan8xds7;=vYc7YDKa!-I!u-yMuH>P!xo=o;_L+`WWYcL3 zZSM_^^)5g+`*r{TdWMG4fAu;V<`%=zr=++m`}SZtW8a)ur7D>;F+Giir6tJGdEmx0 z&|C{K&=o$HpAG{nIdnd;7b}e}<`;s9%W`HJxHt~fxDb!@Qu+&H!0bwJ(cJ{Gy$w@m zZ{p*B^H)e;?nmms_$GGr_99gzszX$Aj;bK}dSsVwldV&J6~&#I zqb5}IxzZ7+h~diIsUmKx(~+p>I0-aP&13)63|2DraI-lKoH-w(iq?mns}#^1Cq6=7Z!h|K0?ct|bQBk^ zU&BkspG@?AHkZX;{Oo7Q`Fgm-y*v7_skIGn|A!xA@%Mj>KW_XU#P59_@(1*(OAAj-2>v-Yu zC(zp11R!uszINvhK3E$<{XcjPwKX;P)=Mt|68PY=Pcb|`hQoXIV(;%i59EA|c}w`& zi4WnrE`H(p7f_Q*BU4`=;;6m-{n*~qgV}`z{D+_X7y$6|&%J<5p5Y%md>9Y{Dc42! z=FNEZE6*0hU_uDELZH5`4!`nqUq^jykdNaycLMOJ{sm1!xL-FlWX)(;rv;I^ckP_Z`Y>?Vb` z30o?3s#{U{*Pu}*wfd?$>!Vyp=<1Y9{_XVMLimo^9u*FZ;(4o)5uoV6GOsi)iZkR`wuA?kS+czX|vl+tP_k19ZYbF{)i%#qsw((5&i;lv}xqGOxD4EB9=5R$I_= z4*_>nn;g`a;WCm6aYs65H%SqCzH~3nCT-Is>voVrq@1z&nWBm-xzK&hC?JY} zkUoU(7tFhK(xr=N;0-ev2g&)imX@n$B{{K*z2hjQAi~hLUQBN8z)~ht)S1vrxwzZY zjgE;)Y`t{{Tx4?LVer5J?)G+99jdFep>%5SJZ9$SAm6wO`N=Q z;nK|;n4X&j0LT-!(d{(iz;Ath-F4uK&EljB(#a|LJ6uREjqD;dfouQ@LG`|3e*{VCNGa1fUBG9h3eY~}fLf;KARw`K@FLb~Ya;blbp!<3#-<@Wi5%Q83YuPD z-2lzq;B`>WBR`W!VghRFC6z*V(l$%w?3%tlCq8C$1(X7vGJMYaST`5&@k24X3CJQG zWgLnI#%_M}i5e?G+W7g(dqRya9#xFgCp3nrZzXtCG~O=NCwB9A)XY!UHl>l7t}5tM z>E2UQlRAn@Vq~Q9`RikPV@9|M6H7N%mk!1Y8LZ=Syce@ON&Aa~ZIzQfO(C#d9F!L$ zQX$(wH$bumT}8{|t2Q^EEZ5gzv7w=?n#I?cLvo#;>Z^Zz->hFDWcl(!AlJ}>n)$mB zUi8@D2Zb^jf%See7arzY8gb#^e#|#FmGtg#Zx5sp*mLnRY8O}FyAI}>n*(D()yVmU zqKTPl_`Z*prY6*;1O3PH$_nO}7LiV+(A?OF$(dPfZfk=O0@HJI$mW8%m8lDi`g4m5 zTAuRiB#`rgtt~ix>nd)I+=cwX1<3#NBcQJx&fk9u=no>P`@j7?U}PST|K6`+^3hGW zz8D;XAy3_b{11I}ai9z0tGj{jW{6)tg6to@kJk@%;X6P7 z4K!tvO&|%O$=rZiL)B(o+dIjrQflwyN_2(f3gZPGr;^!=o^Xyt97P%B0^BUa)Cz;R z@Zg6CBX~mYxV(mRC#qBhbbd%_xnfx18NxjLBqt~Q#~q{p5jK<1?L$95w!cWR51L89Nm zMBvJhOuY)w5#cnWl!H9=utK1e2RB&jX7so^1InqN6R#unKUd;&14Hy4H$Fr)2wd`s zO8Fvk-^9C0=RxUhn7A;GF1{MvTYTNqBhdKy_@h>79n{ta?B6f&-g_Hkq)pDd)>}?M zrH%U14ZeI1n(az0&7cO!rg7haQkb&j)lI%kd_Ftm7+p8IIi!DVc;bA zw@|urzj+)Ew(D&9JG812=Sa4-&X*Ds)6;n4Pkw~u_B398;knRpw^&_Ev!@iNWHyoL z7cbwIQYA%;E6d2{a=38)8gib8h8y#^{SW^w{$|gcc==C%7Xa|~sgszUp9cW!*|7ur z`uYI?^NWl4*@=%ZJwJ!%AA1}PdC#iBYuB){x{A$hZFu45Ujhz23Lg?bow|b6S9by( zX&mY9!FIJ%d*3SX)Nx=}2LNDmTU+R4ymRYTEG{i!HM<7ab#|vV1 zoko3K9iBaU3_#!*uBfh-9BNXoi^hae?HwV|YzPfJFCcKxZmO^jt4hhKW_1k@pFEAs z>>_+WIOWJ=7=|McT_dRDN5CfIavT%o;3hKV#Me9eT}ax{ZN@g9$?qx5LC>V|Oh(d> zjaY;(wF(afdAoU}6x{Pch=N-c=_DdvlD*~%JKMNrVV+~+4t;ZK)K05wnYn8>pb(xk z-cZ}R3GwO<+h&w%pXC?D|LQG@_^zK?#iMSkGny!0IvtAhY^k->bhr*k-wtk~Lyxt= zw6uEAX9d@qD-2Bak&y86qsD;;6}eiSMFmKBP;T5#SVvwTt{LHB(zur4Zf_5+?%9Q< zhUBM@tkl=x!zZ5r031AX4s{DFMhc}%Qxx)hR; zyzXa`5?ERSD(?SSrTd0bso-C2E%4-%!MHqiO2Rmh*~+ltZLXEnHO4mktc>KvIlg*VuZ5CB zOueVjek%@7>wLh8+b5=R;M{qfKX|~}6G^FOco@4bUk$mlc|wJb{G;E_{zX)OJQ#f7 zL8Fud55wDfakGC%Vq^4dOABUOTCmX62my)STSI}!=?Glhw+}z-TM9oXL2{qa-_^ zs8G5QUmaN#yrCdEDG(?fu}fvNzBtgLl%#`p$A9ynBYL9mraa*l)Oc7v(eC%l&wleL>z&G>5EoU7*+W#~2| zE3bK_>JI$6`ar*DDq!?EVE@OJ zYaD7rdzWTgJP=MU7@6OrFjWPvDkY=VR$$jI0U;#r-rdNO%2y|qLZut4O~6u0SNZ6`aJj)LcS!?V4mQ4no2fZN=8_zEtyv?hQrOxK6*U}Rzf zo$VdiwQXC%x9mhbnk!r5zQx9^+oq`_KHY;M5tl-_`ZP`-eHhDShUB>0(+$scap2r} zEM+qI==kFmu3?pmk>`0>S|P(oLnZ@92rRFzAeW;^ZmE=u`r119QetswDY!Yc1T@v6 zt}z4O_pz4E0xLOSZUsm=Kzm@U`O&-YU}cfpd3TJwE!E-$VVcK8~iB^4PYm1@ehq5Wj02dHvhZ zhd<@(SAe(fK>XTcKtluY&%Ox&a76Kq1*U3Ke+JlAVDq||N;WCk%&W=PBwG1xHPFpp z>JG=ry84#NrTAd#SKz$tK{+@R3R9R1pvX^P?{iE;cU7%*!@sFSjuOR)CZ_?geCPx! zjxTv`5_E(z)rR6%5kgjoUe(PBO{FSg78!(Xb++Ls-*QTp?yybxDf*ATDOXS{!z~?m zOs&w3x+ePLo5yv`Y?6+e>1`3Z7N~Kd+^6)T&q~zPh;^S5Ql)!OjuS*lUorhK zDn#b`zL8{>kZksphXO+0kjo;qGLN=%@1Xbf@1k~k1UFy%ElfQ3os#n`g@o}}f0o49 ztjNTzg$>PSUhxL!=&D=_nJcZS5iFK7KP{sW<#IW^@$pAk{=>I{Uwf>iIY7v<5)yT_wdmg718nbs1n}%oJ95W@FW=eLPR`4l z0QA}G+1${GgS+=&b&b4ugb?WJ=!m4v)YXNNusL$DOu$68FlGm24B*1 z(Vq*LmS}2&UN3H`1Zevz;Vk8>O}1biZ*fZ?w?Yysw`o#seIwZaZA7?NwNYsIRLQzy zKGji2JRCoAt^H(n3>Z{6-@A{x` z309t|L$@J$bE~zR53$DEJki;K;ohFeS5W=9?bdCyO-_Y9tLhPW8>o%SYJ{loK{^uk zmT3!zR!4FmzqNBa=2}{?*wlc<#?m&z_>P0Ajv&~=;K2dxzHk}Mv-9xb=k*$@RHY?C z{%keUspu%3zK8m%JeoY8edf5QZ>IMwpR+oaj?Q>JulrZls?wK_QYk=*bVrT|oIfwI zxcK?i$DAJxkv}+0rrLk!- z)w@w_u4_R}E^T|q#N;M_153l}BemM{m6^6fDS0E{xK5q}2Yflbmc^E#5l9FO9vrZ= zFB#1>H)Cp3JGL&|Vf9vR<($X%jfB<*TtZT9EY1tKWu$nzDgh}65@TJRB}Weffcd5- zT;JIb;Y;+~8HN-tZtd8PTx#PYAXKS*x;rrr&-1XgYYP^amvQ;#4It-3{$LQ|rM=iQ zum@vPli{v+d3_2PTYz|CdnB(tJNnR2UynPZBbb<;&KEETd1(UTxt;K(#M#T2;pMln zEx&acbC-rO-su7d^2a$}o`C-^e*mOiI1kqYnP8{6{OA^NeHz%m8De?}a(E76peryc zujZ%{qb|hp9l`H?n;{Nv0eToy5&&vlq%yVGvv(K7fj*$G9oSDv;*J1|qhKK-H&Ii? zs{Wd=FK$7y3DA|Ic(FPtIi5Ky0o_ci-zRvc;zS}$N3P7ooG8+hW64P!BgJ7PL0xK- zo|nj%uh*W#8P0O`Skb!4mAfbFuF876X`LMlD8sjMIH$;B`e@(>6mdn1{`I4(1rBGa zZuHv?>u9DiRRH=pwJC~hhhW$Y(@~Q%5FN!j+*5{V{teAN*ghzlSRvy8S4-KS>iw_R zCR$4!*y^q4Vu{^B+f+Z8V?@szk+Qg`7p0^^O_i$j`B7UNuydz?lp7OqTTx-2R_U_J zfeGt3zm?KPTOG?Sy--{2s_nvHJ6;{Gr;UPV{XXa5>e}R+aisTUlAh7k=<0W=jn5BgnsV6fgXpU%B0U`hZAOJ~3 zK~#VDui>ud;QS9S1N%Dh*pY`Yuya@N{1pKIu*iparO5Lbl9qn~(K=;Y;q5Z7`P}}L zujol-W4p0Aer+e-Q5dC5jazVaCK3tovP_-bq2asZ3Ddl~rxM^HVWN&|T7TM$#p`}!B zN>(zoU(%>kDU!R;axNx2RSgGKN=B`%L1eEt-(>d}MA9 zqW6t|hn8!fU~cClxb(OFDHe9n37Q+x-ncduDytB-jKj4=Q4B1!-%)&RY86StYp+9G zoo#J0LyjmeXPy?Bglf`h{PNdc!T<9=dst8#9}|!+Q>c4HYAcxPDV3U^BJp6*z2ham zAFMm#9(K=-p&=}KJ|5n;A59Gn*tTU0d|#q5lfkjycny8qcZ6xTc5SidQIk$%_qM3* z(dHyA0QB`1kK}Hn)}|%^rQ5%&RHbq#n@;26z&`A{d<9M}aL*+CBiIT^C-5nJ#W_C5 zDY^`-uPw=Rf~DG-Z0lFFB#x;H%PJ(zb1X@ryHx%rFN)TcA|?~Q5?T#79JW@gZNcPw91H!L%!1>57NTG7al))gQuO_9xS_ie}R9otKat{q1cn>WGnJnX!B z4K35N;rI-`Mhbw;uM#Rmo@sqX{tYe@n%X#huITuh?iHH{Ut)R7PE7BA5{o^1ia2a1FS9TnPM*G){g|f_1=1C> zAKS{%b&@cCN3nPmdvjUB?)4MhFcro1>J8F^^Hy-V#FSZpTq=cyru7}gx6s&#n|(VV zr9jWkVJI}MH1Iw+4skl&nxMN3XIji^GaFLfGvk3OT+LvDiUC79b zm=;p{sNq>Z)>n^MO=ef_SWJ1*QC+HSzIMma$|j|<8}5MS&^=n;sOgyRH&*r4BaE2` zO+_KH${SkFTq&TNzN5L>4*OEQ0YoE;>7z#-?M%><;>vNS1yTc06axFq(_@O8QNi_e z(CQe4xoUI=~ME}}m4Q%3RanhAsNvUd}u2Q9`tqs_{ zTfp}v#tMic>!s*S+Q_nWD$Q73ejN)dxXrZdqf(94g}`uJ8oLQL4wRcJZ4+plK)qNG z&}tV~cU`?1Pt9|4Xq%eGbbDKZ)a6lpdu&b+971o*dc9KH1z&u*owlpAarF8}A7W^1 z6ps!Zz~Mc6!~1g!3;5paKe4{^(B6G$sL$ZNPd~w?)>gds?DN|5pMLlOhJNoafUT_% zuLiqxrIf(kIr#th2LOQY{VNY*Qv-5&M{D^P=OF*=EN&g!hVTA^$snVg5C6aZbNu4} z&)%EHNRnh{VxPOmnfHBHH5A*lT z+&m)ksxw|8DkVAJbDN@P*OejmZ@-Cezw8@Dquc?Tt7Q2pPwL52P!N}ln?$5& zVeB=s*G0@|(Jq1RT)&l$pC^y9o$+y(`fg-AFXQ-N^f1vrM?#1)f|X^AAim}C(|DvU z57paBja1E0@Lh3-Xz$PV-#X!SG9#PWyWGK_^fN&hdR^2qJ%*QOCx4%=a*fb9^{<^p z)Z&ekfm^tSQ%z~!P$@zK06#q$JVYNAvIZ1}e~Xy5NRN(6N`N=spz-#}CoV*MlZ_^I zo!o4EygpnUmWxN__b#FQPyZz{hJ!ob{I4;&=LDQcOnI`f_R0prFgzPp+d}Yf?lgLB zyqr#FXx5d%^UN6z zKLsd=7qq+fwF z$dQ}cW`Ir=lKYA4l{rt%t)UKvVN+|S`^`}y_YaV@+eY9|#%1)zMQ(ZrZE}3J;aVo{ zw{L|37k4{5u$&B@5D;Hkf$4gE+VWrkk+cm5baFP4n~m@c2xMupaq9S~IVyFfYe9>4 z@JuZ35KZl|G2GIGyWJg_t;ioGcC5Z0WA*i@o|=N?I;bBW%Q`!Ij@ttLsv0U$KdvEB zZOG(M?tKomHE)Q+wxH3bMwqUPj@x%pIW+?po^C;Gem4SrC@{6xcQ*5$&{+iZ8~1Zz z;v!xy(z8ioe_v^-fvPGO^YhqLoAsk2GrfY!o1dfk9a1gb%wTM~~;J2EkcDQrns7%^8_P_n7a2yBDr>Ajr&pxl8 z4w7T`!?rCLJu!g;eLI1#osj#CrQ1w$rDd5f*#JQ;{c|$u(iXCK6}G^wW+BwUVlt!Y zAu4A-V&UarntlryEkFd1oJ9xz3bir0@_Gtd!-pxl^1ae+$PNiQ!>D|hzc+5^6~AeJ zuipGhP?RfIyt!mF89G0<9tWD=nX4t zq|k|7T*Tt;=W>KG;m9wd!UN! zELBwjeSNa}YhnTj37EQO(v9O>fO6x?6=fAdx>T#HquNe&4zIV(s{z{K_i`Jeb?Nkg zTs2zfGFE%}>D&Mc*}~!i(mI<`*8ou7m-S*{dDdh zedwM31mOJJyJ5Yx6SY-U*xj=oKm6c5e1kb|r!yI(zuAX9{X1b)Brr8QgCo25VD{<& ze(e4T<{x|&Z+`8|ICbefc64^3wV?r*>f5mVtrv0dz+Oy7(l~YQ9KQLr*MJX?qr9UL zU$VVT#jOnu0KDklTUuL?OeFBls@IT+#qstlC*ZgaaNuPmtIH9KMzOu46I+{`fmdzd z+usD5Do~nC2BL~(@V1Um4;dzs6u9{s{^RE2O^`B8qvm$Rgpw|ZBO&+mBJrY;P|EN!BRS&k6 z^A_}kWY37ffO3&XI8rDph;jcTWVkKExoY@4pS0h=Ea z9K?InlZIb{_ep+{b1x*vaC+I*uzUYc~T%(j->e&Ri-XX#^$+%r{p>1O0CDCE^85Ah54GV z)9i|pxLuL@C#W|TJw~V@*e@LYtN2}h7SeC|YEY9c^Dz98Av6pr*14reR=a zeh!IP9C3{?Q%%chX?Yn7*=Siv*}%{&(C#^Dd~oJ7%*@Z>;Ld)`F3jV``DsZ=d2iJ8`T~UGKZN2#5k53}@ z>Mp!->^T1X@BS7?_v}SOO%1-Nt;OZ9+{D(_Hnh~&{xo!H1Xvl z$FxPYH8!HHu~B>PQ4$%WxdV-=bavS{4p;c{FTjE7h@%=2<(zZ<&RuVv^Rs+S74r=x zEuflz>3{E@jy(!OAmbmw7P(GA;Gye14r@g2jsg|+ERx`H z5O5Pn6+69cm{}<0usgy*TQEN(>y%DMn}w-}GyYN7VSl{UBtk&>t%@Hmgy~dvzD7t1 zrk|6#yPKQC-B1BSF4tvn*^$HnQ3~aw<|?~|h)=l=jucVM@_!RdaqGB6=?&g zyc{@unBM=-e&#}mQ=3V|t2TesuN^MrQZuNUOI96+-OQX*_cUl$1 zhk@Wssxx;a1fb#KE>-tk0Ba~;N$b>u(hcf({ppUGw=|t zjg4q+Xv8NM&cmKt#^ith7x>8^I(YT9mvH^=U5skZ6LhB*;r{V2VE)q+KrDjs=_#br zX{@ADXm4r7?EE|?XJ=5FEWx4ve*E-fa@;<=dk^ZXJ$zl7EWvnY2-Yv{!m)z~k+E(3 z^wcl#%Apr<_BS%pu3yD}9w&P%Sem+pAea8-4;;rqWqCPD(rLVYv;-gw`yDNztIQJ3whHAyz zB9M@5o(@YZYAj=2fn2;#TSAKJhG#;DJYuryv@1;M)Z@Y4Rh8Xp{pm@^=WU|aR3Bvf zk&hzrHe~M4-ze_^9-o^VYPrH(#-H?E7*P4vZ!7CC9ehs!SZ>r40u$PP4ZwO93>Wjw z)@t-M)!=Nfx^Y)_!>_w6brCWZtrDYCXlw*o;OC2p86iffXYv=lE&5-KZ@MZ+0pw_y zUl*x^q#Ipg4DflsR(x8dBCUs#Ng(nVEH3KU-~94KS%s6CPNC<|{y82d>oD``uOrjC z4XKJcIMKCRx5C;QR) z!!-@eR8|&GaNb}tTo;woGca5ia~0*ttdcRsS5{E6u(+nOg%rM6T7s4JcrQEybggeY z47g}~I09?M23eiNMohAW^0l2X3%6DAyYfmOt_M`pc-nE z{|?qa_?>T)R!jB1^X$vR#ialP{PIEj*^;S0<5N@WisY%CY82b&vq8YQFm(RAwjC>ywrOK<%)(&cqIo>-kF zQU1NU^x^mPcHv+dx$VdDwV>ser=|OP-V63yXNy+#@Imdl9FQ}Nf5@IgDu(CvBZ-jn z(o8Ih`HGD@v1q=$443FREtW9$Jxvn^u%eaiT^R4mgJu}BmXGc)+>pZ^TM@r}2Uh{f^I z`=_vd`!;NC-{Pkgw6wH@zxs}29b2yU&aKiAl089b`-)AbEOga2X{rThk|fdHh~4jV;x`>%ePpNg#)(f z8}`UlPo_^1k4qf&LxxR?SdB)kaKGGKQ78gRDCU6j@LNvufh zXcf`GMGL7v$;c^O)J0q|VG8GFeA!g$5t&F0R#(a&;ATvn0)%=+#IY78SJ4Zqf$$9gF4EIU zpIkUkn~4=lrPCOhoB&)GC;!R6!^#_7FdECHG*Dl<^SF8c zKI*Hh(NJ51SS*T)(o(FXQWzW?1=2R~q zT3>;d`UW_TgA*?t#+IgLB;R=rmF4AFT3&%=ntl}fl~f8Z?%OZ5b>EI1C@(2RSxE`D zG&Q54rWODYDUGA$6*6emRg)8Sd1DC)$a~ulno!t0SL*D z$nned>S;shB1|8>k;XyfNG%hmdr_osvB_38*s5n)>72JkQYxn5Px9EGSQ___%OdEymq!OkAXAi#j_EG&OnO zCnj9nzyD~<=bU5n%aTbq8?BW^ls>qDnyZ%)Sz18q$hVO0+y%swnjF?ox;o_Q4;?lQ zOA}^j4#UV{l20&CT06x(La6kdy2gt1x!yV9O_x0(awd+)B^4VH^jx`)>wUeLFE7{T zyIQK8oPlAxlIB*`NJD9%tnYR~dRt_9l!~Qg3R}C2>-poS%IO)raQahZA`zT==@=GD zOP^}T?Zomj($Oev%gUcPS3XNiFg9R-Mlu;3`S>(U+s4@g`!QWrwW{Zvhla5I%2mxB zoh&APdEXtF$iySK(%*-n7Wo9`=aH`V?SPSS(QC+InjMt!shbt+G(vh zgyCuRdYF!$V{LH-QcA)NgiE;A)P!1d(uxwUpnJ3#NaZMUom6{kcv||TRQz-(!tgQz z7dA*a7a3>r&A9wTB?AuJh>6kWMqJplwo~sf_wNJ%bltj*_M7)$rUgotBU8J9`q7(} zwLPl#huTWtsf|)JYs1A#BEIf5f1$J#XAU34k&_=IzPJL@C6vl*BXlvcUI%`?$@<{c z_47jqu$(CTy=^3F!0(kL7Zw#G2?Lx$Y$z%X_=;wyhdN8@+*hr2&MAON? zK2vexj}(mv;4IqsikfJYYwVTLy`w8bSH^ zg6Olgtk=&wNlx3Yn;j%fP;wjxrfH&3ax|VfBEJX2!#I2SGJfgAYk*|{w(EV$mB`wv z48Sm?s9}!l;-{xip|7(GV^dSObn7Nu*F{@nBVOp=jsN)GyMA3A*M;*(AHw~IaeT2f zkBc{N_-%Au7v{_g@Lzo&-;YM%l*jyf8is-0J-ztu*S`S(n4FoxUp06;{oZ-)btL0) z7^dkDwTnI5F+MYe6Ne5L)IaSlEog6P!PM-m)URJX{xbgl7bm5@Z*Oivdvi<9{Py;S zAA$4DFTE!H-ow&vZ7PE0d}O#Tw%)yuo~t*IMl|5aE5~4>r8WCB$UMd8PhpD`frPO8 z;ig!9T6uX41J#tDdN`HAa`7Mp8J*R7P&94$K$Nu6)~^5nAOJ~3K~xU=5>Gm;Ob3S4 zBCe(lvN&EdxyNm(Ms(Meo+U-Fqx_bmd{DG8-eZhU&f=QQqCtnVEY%## z4Z0Ks++(p890<58`rlzW(N0{hFc2e*!%=Z$l{ik>MT8lkDe9Q~UF}KvEs7d>4BF0` zkNE-3o{&KGmixx5anKb+C@;vFTqrf@sOW6}8$scXo12B=%YVbJ5WzgRa+M#qmEIC;{=^tAWeeMDLwbslWC zv6|;z_zcvgTnB&;d3G&eJ0DmJGe(C2a}^-xGFFT9Dwq!DBg+arFCnvd-^E%UBw5xH zIe8q5YQ=whvf)M;5ee z9!}u=zxh630Ed46yNH&18+)hc<^TXqb#>^-Mx4HU`<6D(&em2m)>3qY`Nc(Czjqh= zcl6=RmCK07;z%YExcT5dN)sL?y*D(7%Ca)_b#-G)b2ALXz`f`q7DflLy=A9=LKEOc zy^BO5Xs)YAOMQcXg45pZ+fiFpjjHl;)Kz(!>xUyFC`lx+XU}%v-~se>cHxH~yobf5 zC3LlIK|@UqYOAWyQr|!g=;;FB$#W~|6t*@u`w^(iOH0w-+=7vbaafjxZCkd6_N_Qg z3h+*0>T2_j_-k$OPFyNej#`h$V(4gTm9Fu6Rc(-CNs)-Er>4+#>o#h~CVUB;$0(L1 zczLCkF<5W~SGmGkjWO#XZt4n_95i#0=`#3~Y+e&6*ux2?kAT3^8&IQb^J8tf0y#{r z&atsvQ{Kj)YTC)-9L{a!jmsP-6E=l%l{WZl46@9jn2#79t(xb>>nHk_w&FTIjuh_L z+$_m^)bw={L3}1_2!gHUm{*QmZ8Ho?o0~1jxF4)MF_y)dTr_q>-z>C z+>6mIdXUe4ailZ+*7Dh|wuxWkh`CU?B=>p|oY9YCeJRrONi{X}y`sXK5s$-ho6~0F zVk%dZ=aIEMkE&~@(f012VtV^)7<}c|V0Y~XVhJVX>guO!Pq>~n7kbk1hu|}XU|*gt zh=0{LqQ|r0_*Xn5OHmvtsAAyLoc8 zlw4Xu$DO-yT?4S82@7JfR><`yZMC>2TMvTts7ARct%#%7N%(|`uIPukDU!+H`1>aj$z*(|3ePH}lauu$UdCJ| zY(%i<^YbvWHYC}e;3#W~{JdR2%r|Z+5qX=iaenU}j5n;kFP=3LtDYAmLe&6rEGp!D zfz$Lv?~KxT?^wTSfY4I-NrbtH)@8yoGH(pKt|B8|wn$6(nQI6LeadCa=>(P#znyF! zsQg`Sv&v6g@{92#v$**InH3TnIPZe!X5~l9(Js+t2?!ntt(@xbQpw2d1~{d=c}P5mt{vW@GrX zdJL`J3ziXHmmq$Y)9dpM-k0SoevQ(rGML_CAdT*sH2tk=8;I>N{NC$8 zGc&6G@Cw|qc^Loj1=Lnm;jNcnrCaa+9Ai^c=xj_AS`EeFp$waC8)3T)B+5zVRyX&2Iu_G5qj@_b@d( zi{tzDqqA)bB5XHwbwve!{jIkF06%!|T`aAv;Ps=&e4}t*R~MW$tm0MW<@oj+Uy+>B zzjXM>svP8tw7JxC{RTR2-}S|L+S_VDJ^)uWIESf?Wp!%M{HiX^>!C0)Tm_(N6kpGs z8c>~{WHXv@wB=?u8FcfA(*h=$zDp||??b9%-aEW(xgGLValCXeo!VwuAuX<}P*je- zttzox$Zt?(@O0!bsh{oas8LG@9;3l?GeCzT@p_0ipgO#(2ayY;x@F4jt63M$+cd&Qxas2SY6_1uHXJ z2L{l0=}JJ+XlH9-v6?!5pNqF;1F%5HcZ+wx#}2(|b!^cLlgR*|W9uV6&hi8GM-QNj z^lZ|RBL*DD+tvQ?;p3@;s^Z<;vWS8z-+aUklZ8I97Qmg)ys1|xhvyxpfR>*P)>Q@0 zJiQ9^gW%Ux>Z@}3Fe1rAHizgAcI2wk=7)nYZ5tQ%@5x(6KH7ERA{ri!GLA}0@UVzu zvQb?%ay*{(dToZDr-v@zx`}z)#b*PIxow+2fbR?p z;Ni$Hn(OM(EY8C+45ZR&T)TS*0MOUjg;-QXL{LmwY}2x780c+pM>3JX`1CYtD=X1Z zQ-iAVa#WO+VMk|||J=@h^i`zNDfF~=NKV^=cK7u9-+M)*Y=z28OR%SRyOg$PYdc!& z8_?O-hWhFn?Q;Oo+Yy#$sT9q+NKY@7&Ca8Kcuc~>^7d7axVlq(~PAMWv zmB5)48zrnaxMUD?idLPYb*Dh7@{bDx!_7@7onJud+ycwpgm8=_`9?<4WI*RLi7+^y zg(AYX!1NK=c+kED_qsZ;l+1tR^gtVJgjp;t0Sq9L&Y*2z05(h*SqBqQJK3q6P%&*l zpwZ2ZBlIcGCZqmRoifB7L;5Ap(~Tni8dJo?McNoDF9*813^>l?!^FU&#l>EEKw@$T zwHMw)?fIW0lPtyP!I!YquoWoKuoy;Rn)gD}>hI~l7iwtcX@eLzh*b^czDRFKX;g%& zUX#=DGG#3=X`hK(%Pv|TwC<(nY64H4j26`C|_ ztEap=h+tuI*|J@^aFW}@5wH$-a4mwEK@Phj z*ITb;=6Y-q2x)naBAy9c_}_U zc6dV^wsmz=r5xQ%&{+_K75-7m$_BhO)0X;Lmi@$>@H8J5n@Ot~>3n{L*QL;wKkN2@ zB0XQ!-R+$KJ~jrNJ^N&#gNDz3jOt4t;nIKpN0`}mK$Bu~>l?(cYI(Wuhv8_RE*E~z zm8YDCx_)!5cF^7&#MVI2Z_AOsbMG;gXNq#<=-~Rk;`-5GeF}e{10$n&@6*#r#N+to z*WZ+a0;}Zd+*Mvvq$iCc|KTTp2LRaLw-cF61{vGN!00GWo%;gz*gWQc_xt$EvcJJw zfBP>`wzVFo&Yi`;=m-Fyv$YKecX}b(7nYXrHy^%_`Nc)Ju8R{d97bJLHO^kUf{blr zYjZQ|e*4#eZ~qb&(<}JfTj%ihkA5HT-o1nadv>9|x&~*jT}9-(_1M+X4OAy3=V<^q z@xo!e`^jmq;#LF^%QGamH@Cnr3?yPPKkch8ya4-vgVJQuPYVEBnwn5wU5!LM4#eXC zfHz-!3ASycG?`=ubdPwxZ@zdOj^p}KzyQFqtThdB!!QtM^#xFnV| zXoGxcmuild6%-UzOjaYSr3YD-sAWEQz}d9O%h9|)84{C1f{wo6s%-vABZ5cWvLr`i z?|Cv#Q;oQSj#T3&ERZtY1|5(kSik9ir`X&<6^QHqrd9#6pvy38;Tw_0Ph%2{*WUmwtx^EZ^0PEPLz zu5%?Y2ip9(pmLRSKOx0%wKO+W!{>&E&s)h6$#iT)GWw|9tD!w-&!b^@6o%sc8IW-ykZI>VT7cp6`NZ*ZX?Vj z@Uz@Ts+X?Dx%-QdXpr*;@vv-yRb#8GDb@R`voqh^EaNy`ja`T>u`Yyzv)CMKKp;i_ zq;TR!mcIu3RDDxi6990W$#JKx;9(vk)N9vrNdi+fRT^0YxZTx-s_AJ|Pfnp^egPHJ zvv6P{gD7OA>G(Bvq&@@)J@b0;&CC?L6sG4Weq(zNQi|TO5E^atf>cybO<}UG1~uc8 zQV)Bz68Z;GXR0?J>9pBdXg5fY6~wjlepX{N=A?UWb!$kGinKXYRtEI;$|H1SWOI*V z){)H1H<#j5!>GP=3RPFmAXV9b2XA~2ON|}cTCIlEx~~@h>hI?^3ajbVeDWKcgL%rB z)=L}Y(B5x3bd36p8+cw{cV1(Dx>WwZ=D{J%R#vRZX?rP|#I0@JXuJ0?M23+20!kln zi$zeMAW*%EWrMBHkBRPBSfAn#~)KWP4r$S?K0 z71BL!&j3R~yuQ};B(Jsn9Ni7_9lmW<#hG$lI6qh0753-AiCD;Np#O-#kTmkV)0$jF zrMIVlR@RKDGL9^t5O($Z)iBnCQS-Mc?31s1-rq*ehrj>U|A2kJ`zvTT+>49<%MWnv z#w{4{^rNPt5+`2JMZ{I>EcerDC~RH}=k7wvE@I>&6$!8`?=M=I8%e>m9=vS;X!^xp zqT=Qmj2wFhGrfo5TD*dVZibe_eLI>DtFm3xd9%+xVMsD zSPuDY5*ts?3O|bgz|`z4QmGVr+dJSm4yNX2F*Q327&febbQH&qzKBG<2fVj;cA~w- z+jU%$plB_LSPaMa(=Ly?s%pfdQ5@*o3DYnUkH!#hs0A8oQDNKodP^nh>gw=XYb7en z%Ms6}H4Fn4A-gY}PWOr>&pPw48Vw%tpsMo$(jRuuM{d#(2<*> zi>VRCot<;CYH&1wEAdL!7=YZpig6=*h7!B?bbpTu-*Z#Q5VF0NmHoVAfT-g*FZ;UyMA z8xOW~wJmrr9FQ9!>GWJ#2eiHCbP99Tu&e{=Jgv$jWIpY%G=MCZcvppsAzx{U%To<( zSdb&$n5dkZM*qc2xU{Q3&{u`h-OdgqmX=XHF~#Hsk8j9^2eG<~tywykbDeP}KTjaZ zLUuLey`C=Xg=29(x;|d>sOiB27mRmgQ}@If6u7glWRBx*CCF}+r^)BwWV{sM);SUi6hw!zXH2C5ff8Y)zWyOdQwS| zbOz-!^Zr&~PmyfG2Irneb|jjxA&k)E;4KvG!6@du&OE|)FlsnI=}EM0v8)8CL<|%4 zwYc5gg)o|{D93}XThKT>f}ZO)P&&H+ep-|IK1C#J6T+?AWPKfcOZ>Dc$FgvK@1Au> zFPo~a#?`(Z=)ZUgl~XeSkd5sndJpXIagtL!7nF!U^SO2f(r0cg%2$Z6`}t>ck&5)> zP)P}}Zy$}*^XFX*4+E*xqpyn&M{Fc6j?avt{_M|CdjB@Y_kJCt$6gDqNj}PrY1i@$ zVa2d#g8Aw(ut=+7Q3IN{tt^KfjbN!H z|EUdOWSbTy>uOLrF$2@}P`LvymN)S{BfF7LU}4qnqQ|@9K5vc6TZ;P3&7sn{1sKcA z*m3C!Zfx(tWL<5}^xJOSM8)(h5(`U+EM<^J1hh5Idq?qwWms^~aq})3hDNk9BBwAX zhwAYuShhamv(WeOwJ*AqLVRh(FGsZ_@vW*N4bMZQSM^z9Eb>!(4NZ+zd7RKi&}mzw z7iFsXc%S^c2s9IP(54_X2;@igF2rUa0u@nf9+y;h<@Rk@mg%1`wy?B>kG?nq0C;Kt z0hA^wAlv<+Azb;}kKz911)wYr<9Ckx_eTHE_wnHF9IlsU(|6P$^QBG<|H~iY?;AdV z^nJ)~b8j+OP9~5_#C<#>`pC*U>T|3th}J)$H_RR7Tt|;?{R`7o z%Qil`uJSiZFVf2VP0t5)I$#9yl985|AO!EtFm(>g&+w;pyjY!=97_ue z@kYPJ(Z&YER#ND=d6)Gmz-0lspJly(5okwHE)lW1gFT{e%eA|AaCdM308m{~iNm{g zuc}RYErz%!&JNE_t6jNv{o}V$(bWV1XnS)%rp706#*YjhZUA@SowM^m^;tl{X#Kx zE`BUu55v%U*?^~$uc`X!Fb%j4Q=7i#m2-5NukdH(u%P@;4((bft$K}atw6=M4&dd( zhy7D~*Fvgfw$bv&lZ3;cq`K%Ra%}HDe0uRBuHC(ZL_Chp);2^U5xjQz2mru%*+g4w z3(V}Xbu|_GUDK9jp{2eda9!u5qr^PMnE!72~`F^G+8X%PBy9#5L^_v$}vc)VJkP~0_!?cGQUQODl!?%*X7?j zaLb_&wTsM*UcRIZ;_3(v!uj*To{>`-N^PlbL3YibQ(--QH#H>^vlS{f**V*hK(re9 znH-Gi_k;E=n5wOo%HY&@;WDhWh+@S_?85g9ypG>8hbagQsn=D-o~-O3!9p0a#dXV% z7OozI?qInriJQIK;2H)d>g(W!2nCC!rC2B{@!pl~dhK#N$S#}~99Cb^2Ahpd!~b)o zx_a}=mW<|emF1YKS>G{=nMedeIsT!fYJqC|N069;fp9q28PTOF^b7@?{m zM9e>7j#v%&mRA|N_9O@#g(?k;^n6kx0c_b~psWm7UIs2-e*B|Wo<|!GO7fMyy8PA; zxHlSTtLeh>59h`*5SO2Kr8IhFz5J}KCRc&Knv*JraWK#8;C(J9lNf1i#CmA9vH~}D z^q}kdZB&m<`toG(fNGhaaQRHgn#5A)#TMJm$sM57H27;R`k`P>}#pZNlb`DK7%AAyr8Ruh+TxzuX})+#|9 z8HTM@xz;dUzPV)WFnmm=)Sx4q%r^`r7s@MGPm!PHuib!fAa;}|)RxFbM{ej1_9N$h z@?AYH76_25qvh{V`hczl&#h9UQj5*Lv~ij6q!Y0)(NK$X2lgQ!RZUN0&ll&BTv*Ct z$Y^#Gu!jh_d%V!n@QBcSySX^o36M{pf}evdQ*dW)Iij_VbTW#&JslWmZOz*TK_g9# za4Zu$E?W zI51H%zX-TAemuu{6RNx-$neLxJRkX5Am+aQ>^C(pb&h*|p~~|`JX)luf%fe2M*Gmv zqmQ^PXfx)DwX}$u3m>53=4Y7cc_GAMd+i42d^OfTqhgxy`@#HW9314lZXo|Kyvz;5 z05=L#IkFL%@{_O2*GTv4NNITaa(=4bo#!W?HF~437ZZ7$ar03s9>Zsc58;JVpP+nZ z4yNNkoW@`Rz7AOYaeT|AFWz2RMw4B-*Go?;A6Z^@kxChORIt?xykenZY8Kr$Zlif{ zNE+*6GzqF58%JWv3zC${Iy?(YiFmu>{F%i35=!P5l({227IP_1eOsR8L~JdSuZyx& zCuKgD!z6K4XC+%@s06ZE$#OMq$(Q>{5V<|;g4(Ec$~{K8cFf4;s86MSBMLtchscx0 z<spXLy?6oJJ33L3^$B=5GJ=JrMQrcr^vZS|oW5`#8QX^Yqbo4FYk?g>{{yKt ze}5e#pIwJ}pbaBm^)N(a^$!35k^d%zgU1h{s=NXKFt@mXdslD6{p1P~zj+u( znp<%C!g-|9X}E1=So-8HCNEv`+PSA0#ACy2YTwTqov<(Lp~BCPi%u! z^_rxUl-EA~e11EUxVO3bJC2`nT~~RW?in?ms`Cx@m8wHlb;sU!bsVa7k*zN{x%yYA@-;9rw99QoQ(T~UDt z!^4dbdaN28$|2n!+8 zaS+L5R`rZ)7)WpQ*@;g9&6StqlOu=m>d)Sj)-O6QNNmTX@3e-|$|bG|11Fb*Wh^R8 zs1Af{69VZ}gd6;xi)i&E>0Q3+O8;{lD(53k-w|yT`8a-lGIsS+@H3NwXYBA=f<0M? zjzD!5;Z80*XBC;ts%h`4qoh>vuO?fGFs_h;d~4<=Rpmz40UWKN-e3@8`IfN8A>;(}Il%GH@dXuJrd|q-ph= zxyI`2G4^UbN){IJ($7DV-Ubg3zzz4R>|;uOoc%K$%vF}-)bV4hu2U{rC@sZ@uf7Zb zc=c!RA+luqb6;S0F1mrRSexJb_y?b&0%G+hi1(ly5cRwhb`r<$08z{S=Y$Q4GEOtC-$#RFg7)S*yjrx@YuxJeE@H+mZ%FNu(%6UK-{@pB6^|icgeR|z@MC(uJ^)ivea&liVP)fetIxGjL~0QMXi}Y$2&UtE37WL zWFb{93D+{~BoFn9EOE%xP*aQDJ-t|5Uc%Pq7R-)J;`;P3cE@8d&BE8e{4%XPg5!$T~SFyxv?BC!Q)&k&5IwY~Q}^Vsdi*d94Rei`iRs z{Zmw4{{#ySO_<(s6w7s6Q22}uU%m9WFf8A&d{oS<%U9Jlht(&X|I2lDrSCdfoUi6V zjW+2g!R~V|KEl(c)$+c+iE%C zBLNW7l4rljPwSCO*Ta8xxvf>VVgZi{kuLeOV z^&MZzsdr>W7?mskE^P5sVSN}22at{N5KJK}1YGu8ynjcE{A?kUHBQ^O-?0_w(wY#SYS?jo_cl8sz?I=>49MMizc!PZp8rD_Ebc!lw!NGEA zvLJ`;K>wQt?sj!x%iRaC(!z|MjkLz*5zUC87(tEz+_Bv2_kk^~Sk5Z%HiBHk!2R~E zFl`50@7zOtDdjuvi8mm6S2iMe_2XmH0I7Ec(TL{?IQUoALP5pddW4JT$FNbP$3xL5 z(AnvIcN_!hv=?P;Vd3%CYa=NC%qe`9hjIAaptq3guJ)b^dRLRT3`&D}20^RJeZ@7- ztLQlu_{yu?pj_sa8$}a!wJ4jNNBP7ogo@vjAyua_;tx85jY_1z z<*gD___{t*RgJQ_VVLQaRkf=~MS2ueF*}Q6ADzk~F&8IaIgYvV;0a%aQvKK%_J8(; zbS>Oq=3P(4VtDuU*Vg4M{2pX2j$a@6;}PII zl)pdtzYV43Iyr&20|3q(I*7^I^>1ntE=g{-&W6$k(k`i+hNWcSa+Rr zk;TS?EU)PLjbmYX1GE0x<5P}@Q&3O0anfLsisVs$zk&XK`aLlLeEjjF8)+MXal|ay z@hAT++(--qul*)wy7w!o3M)rfpN+)6YML-(b79z5UnbXYs@H-zIf#2HJz-g1t||TI z{FvInb=bi=%35(=7RhCTzicdtvOHN*oGan_?Q(p+z^yAf%f+KukM$OlCyP%#KC)rK zMIavaZfDq~@oug{rBNbzk~? zpU`s_eI$PWP^rm5;XKOpsnGDd; ziQbM5G}U@R6eeb-5wRkOMWZ;llNf07Hxn42@-`1N*4Co2whpFYBC@X^hj#CQWqIq% z(AX#}(?U~I6YAf15qN`oZ`;-_SV^VP-@Of)Z8oOP-^Icw*MWP}Fg_bV>GmBkrUp>* z?E^^OnZf9vpN4z52eo@THSeM@(($1}c=Mx|OLLcIT+3>J$GMk3b*<;<-vH@qO(k`Ze{epp)<-RmuK|V7N;-x6@1Di%yo-)^ zjv|##Xr^Z@3*&|j}iXH#-9UR!b8_`IlfU<&b zo!3K*9)Nmx_<6PY6lOyX&qpU4tC&~KPhQP~@`8+) zDNVi&&0L-U_^DU?d7U1du!-tVCCeeQu9Vs(ujB??hUSSEh@3W(;>#;&8XT5*gDO=4 zyjMgDUEr6sN~}dHgz`%|1(KDq(KI}ap_XPiX1LH*q}5S;Wd-%4V{l9pLoLl~G78s@ zk0ZIXysBr!GPj&etosPOreYv7s&Ovgdh*c41yOng=is)n>MlMz}d^kkzeSMn7K zutk}L3C%(Oq^O&@o#o%aoWmH%i-nBrd}O23uNieMc`c1prJz_d45Qx(>?c=1?&` zi{#vrUw>hQ_Y~R&XiUt9vba8Nlfx0SbTv8-gx#%aeiaeaF)497*w!@+Fy zYBGQ$E2@ygM^Mo#ix1gP0~l&)SykVzhVFKCz;Io(-Ftxe;)>rJLMU_nF~AQ}r#@Ak z>}23f?W8qgV}-J(#h@@X<)XUU01K*7r00mby8*yJJPypxx|o>(W@jH=`5Of-3Y%%0 z1GaOuLB6L4+QIz80eSE_ZcGXT+LUKdIj`gJs;s30+cG~8&vIvOk=6|91JyVeRHA#o z7fVYpS+{W!r$-wbP&zk{%86;;T}y3`%oVs~B@>6-db7gnd4O%MFLLp-K*v8kiBpFT zV5z_(IK!xFY8rb#KZi^tf>SRad#f9zLX* z?znJVZ&o`naOmSt;hKcS?r+_Sn?2h?^Xor<5w&9z5Oc$_Z8&aW@5O+NrLrVGIePfH zog>SM1m1h?1de_93z%t#ZDaP;{S*Y9^e10_sYZV_8Mp99* zA*GQKtjJ4Nd#WuWJSJma9<9#>MVb^PIxMBD&6(0W0CZuV|l)BH(Cqj>MN6Mzfs`}8bIW*1nGdG7B9EJ;QX{TGbr zPAxQGE1R=q<-GXL-HhA~(4`BUEu589Y%V@6II!7CT4HRO$~!QCO<$Kz9zTx#pL~(+ zdoj`8ybB{k0)Hdtyh2iEf{v%^mHD7)`7k)-o z=gRv5%I~0lIEafkhQisWiuu>a&xmI}Kk|BCpMm!L&}zddg9uzELj@zrd!%Z4D9Scz zZunWYh9@*q@62F8}>VZugjyad&;5?r63!LITuT$!6e zchU>0)7#$R*SV&$5=Zvzh3$BDw}@q7@Ae(Q@9xm{yJ?y@ws)WQUTtL+UO9LuaD8W2 zxAc1@l|pZOJDTe1rR&=}I{oiUE6W%k7zJ)m0=t^fGU5VV4Om=W#^v|V;NJiK6S(Jx zV6<0bVL6SH|K?o)z^9G__iwHO0FM0gUtgEgwnzFgLw9Mrb75ozeywjc&-HW|KUQ_K zI^-(rbY;D7kk5%#Lp=#u<(WY}baq z)4=lTT<5g3Ry-|crI|?~IdmHp=RQZOVLK-J`mj=7hP7hoT(dn_T{jy?s~B3w*Wwz# zuX|R9jVV7>mY~&CoWDH$83RnX6JBW#7TqO9AjQE9TS!`tmRnya$uBy`Z z^lGVWVIIBLt}~r-uor_`1k#-Ac~AK0+-N>hh`#t)p-42HUiY!S(R3P(BO~ZPe+jl_ zVXUDZwq@mi@Cl@{`FXf7u#nviyjH56n1EqB;G)%Phm;GTd~Oaqu3SSV5dvIVRp6L`3_?YVZ^2D~He?{szIz}O`CvAUiiitojgjiO?? zBjt}P^?NYtZqTF}Mr#GxVjRljQ5^+pt$5vJ$8Av;RecSq?a35&OTH$g0+Hur zZ8h$8c3>k(I5*l5igCG))Gl#~2Cw_-3^1z&xTW?oOn0qHr$U`BpKRV1TTbENr)O|} z-yY1afjPAd4x;1sT^Jb$v85EEMheGHp2C?I4sPhlAdiB!-MEQ{kx>jcH{o`7mw(-| zZ5;aKGtcQ+K^H;93Y5++04|xeI&R)U%fkUFtrxLP9^uKQB}7-!*?bI1>NemavXYU? zY`gmqbtB{OWUQbwc5-16k+dyc6Hdk=Pr2@dc;>3gae42~r|unYB)NuxLwZOHW#@06d=Bu<|aSov;u2kv#YuUQ8v z#vTA~b3N-%`Hwa@yMFv?jxlvTqRJhlbmvi4WEo?9w3JNZ^s%Ej@W~k%wpTYZt4gOx z_EhIwGT5V{l|&qdNpZ=g<;uoH0t42MfdyGBOQ^W@Ia=QTGjiD8+6N~R!)j)5eteoceb_bKJ$>Ff zO|kr}ifwf`ndhhKkLkKx7p`Lr%1t^0v#WhB%#lssH!jpV>iS1#g$kqh&wPsB_6{^F z&XFpG*C{v2c9+6rz~J-GHbtYrCaT5*r(QWNK!CeQOn~P5zvoYZmHlc1q`H|3}#YGFbxAW@v>}wUb_}D%UH^!kg%dC zizXqYmx+}HxGqo`OCn}^*m%iKA?;*P5lu?vel|6LiIsT(!0xIo*jH02wb%tv6)%Hj zM*TPRaB&8s%d@CUR3RBj;GM09V8GKymB&iZSG5H_70s{#)FonR_0IRyKSAYpg%ypqO=rWJ^r%xo}f%7gZZT;RI!t^<`x#bh}&T_Fay+; z0&#f)j1G<9i<4*Ym0$U~biFj0L_8M5aw>)ULqoXu-luT??@wX;vp3-W!A~&zoj%wt zL$rIaiwuzGqz5;v1?MfVp zgp*F=qLvbzBZW{QYvpSAt*Y0RTQAQZu1k==larJgxCbc>&2HW46TF@>E_4IGf-U3s z-R!I(%dx;jGPkCc4eV(>Qc>SpaBay?-M>ontE{9X=X~RGf_^;ZM{lG#m#xyIu{ZsV zV|ok4`pIxzl+Dk>a9vim%yT@P?fAMYbrkVG4~;u0Sy;q;S=px8oa@HM(R1yFuQlP) z8<*|?*?JMQrl?jDzgO7vVUq9K)`%h%=~V1Rca@B2+T-sMTg1X|;v#R4Z ze^y&wM_b>@6lUb|h$o<<%osF|2T|Ak99yMN!heO06BG!lzTOe@blzR0sJ zTneKe4ks62;agTuvX1_F=0%al;Sr29HLlrc5=m#!FfxkWXD`5kiT!83z~_e!V7#st z_9M^|L{n)bmzDr{Mw`_hi(EcC2ZK2zblkZM0PAwfaA9EInX`zbGT_E66-tRgZ)%1h zUkWmaz|8>rKm8(`9~~PkgBDkM-uv_v7MVOj)g6{6;6-2Zble9S-BZaJ?sj+J!PYJ7ZVLch+qnbD#U<1a zk3k%{$%Q3xBqo1D+)yFbO&2CCclv70AbZ435FAsjsVYHHHLS%6|M~Zx9JblhmDmgGwIy;Y@7cb-5j_sJL zsb1Cdv6U1mre~4KD&gS*r85iIef9z_@7lR;#Y;Y_8y!d6y$1kj4(f5IAQ=nr`{lFq zNGvVGO4+EGob}Tgu8Yda85pixkkhs&+Y!QuE@u#3&iKCp`KVMrH|*?D=`_2^X`3SG zdU=~G4oX)R{Bg)}jHrtpqEO=L9Uq&Je4mL}tJXO@tE5{mgT_-YB{yYqb7$CkM0yl{ zLKPo9Jl*=&8WjucaI;)GjVgc~vSp+h7KK|bk8;qh%B1L}-(hXg&pmD)RW%Pp9K9Ie zk-l@0PSMS;nQ$a*xtvUF*oKGeJA1M1$_5NH#5{V{Yj*?tWArH8x!fNNY4gYmgl(5X`L~5d@6LU2!GxqYiS-e zmp?-1U;S$g9sf3_`;K9uwFgc#j@6jk^5at=-;7uBr0!lge+<@xU(;b#H9vKo4&rDT zZ_@KJ{?r?o1rL((bMQE3(nYI=?XdQetVQ=pzFyr}nVy}+N-9-w`n40s${u*qWO8j#1`=iS5$d=uGLDV770KpHlo64gO$sum zj&QPS1vl_gdXd(J?K(&~HVhbuTTzw^FWtbs#VP!F;2cUKG5luttI~)(Gx-1)rXFB> zMKiwK+z%H9(vFS4x_<^KCxf@Q97J1*ciP*HxiLIkn8cf{`=qkI+ImoGExAh5tbTjT zVgI`epto`hdMjN&cmUyV7q2$$hPUGIwtIgob_xc7m>Gd#STNxt<7SX@GBDvF3L8<& z>#IfE!OF@CR#sMEMItZ^z;RqeEDNc08gUlAHl4}9cBsUWiE*4dcNXuw_BsF{9*yGk zh4Z*SG$^Gr48xBcy!?;<62@;I1G+s2^N3}^vMe~4hmro1)A(USiS#~??>m6*En9GJ zZ~#MNWBBFoeFym7cf6Z#yota0@B@rbPvOw-{hAb&duDD9KW-?+KX~ISh^!%Kofy|< zHh2S(%n5?etzPHnt?;=|6AQ!QdTmY^>GZC$yspzjao)AU0SFSkB;?rko-Pymhhtd(Ri=abe$X zj5ajDvCIt%RB72ZOxs~+kr|5HpR8%ihxSP(;+7Kl&k_|X8_{!NGe2xi3e#%IDT-92 z$4lun;JSEhHfDc@IvJD<-bB;S{uJ|zE=IolJ-E^Q8=u2u?XcMuhH;6)^2>+Ob75ay zxj{XvoKBV}R2zeuR$Uc!n4AB}7+J>NL0nB71b}~^WE4j_QBqyONp{iM0tC+#sKb$~3_&`8}C9gfaYQ>Yxxo?U0$h z>9@_x#e@TxF4D1$+q~jLOgK>!Mw;NGyuQfCLGyOV?@BME$$xT0v70^H@NjF}hP6ds zrYum&6ome!@?1W0Z3l}Z(Uf>PgOcoTF3nghiDvx()1TsIN794QmL^Ko_o%rScEs;2=V>O zajK>D$UD`|(CX4(OF7Iq_I1<#y&TY1d8&Ay1jgdMElr*Kx>~p}k$xK3cD3@DDoY8X zrQDjvQ%t^MN(b^=fQzSWog{&OWx88!_4+0MD+D&7xef!%|H%>Cd3Be(BBXFcI}FKKx>zj>I)pFBiEUHZX-&~Z4se;+%~U&3AVi4HOc zrT>c_S2pHE+N5(v(U0cnNp3VHG23d^2vwg`EuXegnu=0<(|MDgS5iqVHj_R8= zry_XuIZg3y(?Hlak7ZqCj%t}5C6>;E)$q}HxVg2T@wSb-#ci^+h2?xM&OgFW(V=>C zZAl+@rc9##YswX}j^piZ8+ui;qx}wz=Z&X@8i#xBrCJt!-u-X>75e$2aj@>xO1I3=}@;8TG0>E>mui!mR z1MF%Vu(m_G+?Yf?rWPTvO3CJ00ZaZ0e{}hK6a$~HZ#_<5ZFHdhqsiO+@ZLoLT5@@Q zZ^z>}g#3#em$`HKH1|6?89H{H+L{_}+_}S%ef#0r0h#U*Y9r$NAC854d!FI1bm^)Wla`d>Md04jkrIvJBE02-+t~q zIm$Z+`uO^nzNFPj5(o*wDZ?Ui%`RyH?{(U1Ozb&p!aBbc?{w^C(*f&xTlKrVDZ(_EO6r5bG{;p}lIXV=+fnGdYc{=; zsv$G=$b#J1qqeNAKqwIk58@g`{iWU@9Pu=}?|H}ggXAo>?TT&`={+H(3O#?lJT_h{ zTTrh5I`=02?om6lz=pgHF2Yt z!@f_>u%FWm@7Tu0-MiLZR)E24!|b?lIX=v!>Wo8UOz8celnl*vV-XB=KCO{L*o6HSsFp zXqyb3Oy4FyByn;2dtJwDzBlCz@mn>fPRG|OuGTTPls5!&@JlzzNZCck_my|z*-o-F zAs$i|6g*7)m!Dta#qa%qAH4kHh8=QR3yC(+s4e_$Ag5XTXQ<>n&dDxkg|kG*kLY0 zX$m;;Cid)B#ef%!j$J(e^e7BNaFPbRVHn~VV>1-Tp;Uc?<1n|dz`y@b5wQRIE3eVg z*a(ip2WL*>IW9*JMyJLJLvWo$x+YDuwesHaqn!BBI|x8+_P8oii!1I0bhFeFbF0)o z+8*vgr7xpNPjo8yu7=7h*iF@3c?OO4UM+JJ!&TZgE#G9^Q0p}(ZUNDsq0%!+D5UnY zS|?dD-Ozcet%diGKUt<#R!27n`dRTZ9Qg2bsehzWb2TGHXPVNuUKLiPFk)^^=oBiF zZKZi+D~Fgb9+78l9fs<#G>m)QuI8vjbGOF%mB0e7ylkhZ9QwwKfO$L9#{$c+QTHn>U>QvUy>J?Wl^PW zGrsz-DWU6Yeo_XA!s#+Xp!_T2$jxQ*yIK#`LzwQ1x{{2sS{m%F?&>^s6s)E%?LATr zt#)@~ld7f2Yg;DX19J#D^WYZm-oH#|O(S3F({COPad_wcC30?#!)@D@QSX$}&`pT- zxl?|m2Dtd4*jv!?~bCXPL$JigxqH$dQ(1^zn6j{|M#_b`P#r?nzDtstlrvtxxj7_!Wx57KZBE3B!P`buGNsy^E|9 z;^W~GPz*!CmE4|Go)PaQnOk$w9uZ5~m5p%&M5Iezdl z4)2u*l07%_rVa3wS6?9rB^JtOb9kOdcV{QR^wLXlIFlU5zAv1H+nrLrYoT2iF48}I z6Y2g*+;N-KvZ#pDL<;)Yg(RL!>NzCob4kyq9970pwvy;IFf}kq^ip0QtnxX@?_9+3 z5i?E_zw2dF+fnwnH2c*c~DXOnXzh88u_!#*rZ*Q9Jj+MD`-P1+a=g6MBOv>GHL<49_{^giw1{x>Yl&T!>- zf1faup&UoH^VZdu%fz_l;@Wll_Au!>%_NR?G)!vB0j4fpU*S|;v)oHFWdu_W2(-MU zQzNx3`bsQUUFm{I*aeC5sou9G_c7%ZNq2gCxVUE*A&^}za^jtL2?M7jJw%uwDE$`3 z;ob&#uZxZ*c_nEjz@tb=7HJKq_pfk>;wr6?#yiUCbCcoF(h+^KxwcEn1f>gBLSXBa z>$t^$3;T9gjJWmcFxxL)Wrb`!WPL@5iw1na(D_U3xOCYN=aM9@|IoT743&-MBt<#M zQ)oiu6&JY%ngEmBz>rFxq{_{NIZ+v&h#{r^*1RKi_vNcK7IP}$q(pkZDY^2ZSlMDsVRQ={(JoOS66#lMjOv76dwQCOioNNdY2&CJd5 zXW#p7{QUZ}&(YpeenYyNeAT=+lIr@}_^liNC%NXx0OhrB{&#%;cmEmJ-@FKl(r=?k z_D3ZH9nmM7!pSCWQX0+A!&`4{oR{sj0P84TC0fnaVRcIHa%Hsv;k55*n^3keHaR%S zuhZoLJslhG*V7Ym)LUgt89~ZkrZ*MPmGc68i%Ti>D>Tje$riEqfDJ>GBj?L|+4=ky zo_X?Eb>WEseKGYGhNwoO4%Mk>)<&xAY&wLchSp)o?6pxCo*+2d$Nb^~7p`5!aU8bx_A)s=&GhUn08I@I^mcRtQ1t!S zd)R~7S&F_7Q!|X7zslIu6l`zh{I#p}Lm^b1Eti)KGpm{bJvB8< zQdg*wANVXREonv`r%rytmaiS7mbGAH`4NY#bn6zB#Edo5TJf)pA5r1{OE34 zPnp7Ll-r_Mqvuk=2y;5?B+NY0DAnW}fH>13kuB>vM;u0zhv zkjn`Jn;?EK(o@sMcpoA$l)n2LvJ&|G`N&7S+Ow}@Xsye9_7N&g6tB(R=la|@FLmw0 z3yVyz%=4|05BXxxemZL!2ys{rmRTq+;^H%3T;f}|KIW@^Pf+7UM(qp!5`DET9BS?% zLy?wjhA(f~hXZsM8mafTQJ>A>60onSgQ5CXT5<&sh zdYXJLM}2KAuRZ;Y=E1s9Q$sb9e<7czkk4Dc)z{Wq-)B58_1mXOyU$;s_vUTfl^`CY zNz)=#mR2>MCP^)jiEP$~l_j@I)A`wPblMzE@<5c|`YNyUIE;AWn>1ThT>=CK?@RJd zn=V+OVPV9i*2l#2W=TNxk{&9vIV3}9DW$j-N>4*g+iV3<8nIezxjusLx?JBrn9|i&uwll+rjE*y5@o11Tsn_V3s(+5 z+rp&j{mtDR$KbUh9UJ!6F}BVf)%`S-a5|xu2fv*NOW9DB57qZ-Z-#ubcO^Fy+{Azo;dJ3h z9T2KIN(DC(^hy%bP^6*OPZz^=IAD?pXWKy2ORttkd`$ydc1o5@P9{KUZ(WoxpN5?x zQP~BmaSWO zd*mV%T-<;B8o@vQHcR6(0625=FuzDRHBa%)^Ei{UwETk?c;%@RWy_?Jt~v}$Z5PJv zrvgjc;v-;OP)qh`94h;ag@J@Mdel3_AzJ^nlSnWD1qvjmaK;=uMH}n+@wwVJkWy&aPnlx^78uATJH=@r|Q$S^V90X zroT^uZTo6fK8&5WC3&@)o@4M4^?MR%N59j&Ve9#u?^PMqR3qyrpuJcf9%%8)$;`HQ ztK~I&_w2$Cf>>59M>-c)$(Cn2Mo~F=d3jJxBh=oR)Nth_V@Fb;GQ4`E}J+w;;~r!SWnS{t7*XMx}f(JUdQzp^3cbF}gU5=eT&T$Nj}= zYP>9cwXG$YF2up-=KKSe{3UwxIXsH21k2RY!b-8o?a|TrD&^6MaW37s!NTGqPwv}K zdutmX{P+iqe&=HvTb|<^uYHLhzW*M+@6+Ah!T8h^_r@b{>p>92M%#W6Fmmr608c%3 zDDrgu#9=PqxE@~_-Q3v7uC0Sy`C`a)TkHJKENI!o0yCQUnHyE=P=19iQmD zosHTo{&sU;K|JRN<5 z%|E}s4ka~RYO9sgRoUpn^XC|x$SNWsok_3|h2(rWc| zHtK9`qqDV5d)NODe~El|`5P-j$6>Uqlh%6^;7cB@s=GlL6sY(3B}Yqkd6~AcamL&A za%?n7`9)oe)siH6R=GJ|P5ZA_9;sSKu!giZX_G!J3PTtjg|lbFbs2512Lr1!sb=Cf z?I*uYVRV#<{Vy?g_!&{sHRWH9$5wt{K3ozlrGHP;?Uuv9)na2)6PV=nNlYu^*bXK; z#1~OIJho8q0sn^NVEpMVk6|dm7d1OE-0@)lpEo zH&gE0I1JQx@_JvM8ZWEt|H^*a+cJpjm=~4{lL6HMmfX3a6x&YG_neof!^~#|ADadCR#swYU&~_$lM|a?%t=dP~c{J zB+Hxf@-G6_&CHQqT8V8bbZ@|JqBnIp-;SuvRXsUFOq3?x+E8w}-Ow~1nT&1fc-0UR z59=ktsG$gxG$Yn|o@?+r^UxBgdSMfzn=R!St(6{5{Hq>I4hW4LqO~zH4R(m!e#v!` zxWrNip|32`l)PBdsnjeiF>w7RE+N;pZ%gfqO0;$OIs?NusF`1gb(gXYlK4`#p3o+k z(v2QRA2GVOaM43fTtA1#scH6}J;!n`$F06C-0!T;c(HA4oS}=Csedr57&@!AO36Qc zltsN0mg*!&Xe9sm@r}@Ou4R^rblkqr!KG8Eqv7h#9TjgB+j;&XJtMctF0E)~_2b_{ zdXq;JR9>cQlQ8#|llsnYGEPC)=SZiF;8Iy}_N#5U=Xp`|4_eR|`Zf>lcz zo*o;a|2zMZnz0e?zW6to-Cy25&D6D56RtcZaj`x9>cW{gI*E&I97UHKM0lOEi0|r- zlewCODe=-UwZzZ1drtI2VCu7!FQOY+{rH`Do@r@dc-vrHpRta1f-<+QhK|EzYYS%{ z+s~eJ=PAraSE`AFL-X~uT->{h$=20505NGfpJTSMK9+|cI>1>$m1u-$AR^04^|Qm38_Z6`bU*1wArvuUa$;#$dA z<~Oswqc*fbD!DkNr(pwU#J%=sx6UzFT;jEkUbdA^dN{z{u`#aQ8sWsD$0_3Bxi~~cvw0x##XLv9>3r9NGe`r602X+E*Z(^MH z&zuIpbzNS0>I7LY!@Ivc!O9bD6nmT4($qwuriN3uMrr!bkMa7kqd0py$z(G8@Pqd_ zFtn2=_UvW%KlvSS9qI-8Vc`ZwT4@>M?>}eV*C* zc@7j-|Ml-w3@@Nt8uL`cRWGO|V~Stp$a7sfT3Yzhv(MAj+KT6S%$?Z6mhM*i zySl5&O&vx0ds!a+U-?~J305X zOMNXPWRo`O(FwXkudLiX>-{aoG49~Q75)v}CJjW6GsIRT%#iP=j{_%r{AcVW)F@5w z`})hgx4V~|C)(V!mu3Cb+SJ6&Kl(l+Pi$fTufBle!0F4EX>Vz< z8f}|=+ac0%`9_!|mBU|YdcM`u3rCJt4C8wqA0B>!XTJ9q`S~TK_tkQmoJW@(1ZS$B znPva!GyLeq=hsl$>ZtL-G;UG7?a$;7m9c$jd1t<_R&q~DZI7mMf0H)JB;SY0N%-J{ za9!6ouOCxHl%1WU?UNr;ck2R^`<`X&@Y7UU8O!Bu(@9sCPMT&esY6b~$|iQTrLXI~ z)s-o^8mr$#TpJD+@AUg#WVob}wjMX>MO)nTDBsIX8A;h7r zrls^vAE_YGwn$IPxRT8Iq^7Qik#C(+4EuZxIW>8cj+%OU3QeW>QM{GF=iU34Iodu% z-piq{0k-wS%tyh)PC#!>T^y#?^Nh8i^sfUic5bI3sGT6p$@-{eoIK9?-DTHoImPYJasz;#YY9!Lp(~xVb8=HKG zIC!P_vlCXL001BWNklG(8{P2vFArDdEjWVEZZY#lo8-)Hd3FwGNFu>o`uuT&>7 zVm#}p(Q&n2=7=I+r%~x5qjuSc0p5~N=j~C%cyjS^!jQ#6jghLlqXIp*?vPpXDVFZL z4>V(K-EV7h9Z<_3Bz@%LKSpHFw)3Ie!u2lniNRc+O5(&v_n#b`{d zhgOTN%~9X`qd%r_|0ZLPzry{)udz~>?&QIg0#;L|a&ofzy`1(=ge!;JlXyCbhjq?r zreR7%rk>oUKNs&zxm1_a#c%VFm%fiI({vN>bt7)EQfDY?9Dk~{nc*FS6?vD9M!P!k ze4qT{A|3bc(=tBAbW~l8)Wfr5 zOf1iGq;&v?NTKkZyXSeaYZnDC$9v<~>8NR9(O=>6%w4(*%^YqWWVX1>JEIr)QqN9C z=BJrjSzxZUgZHM!sdu57J{sz38R&^T9J#K`&VfO)nJo7wC+TVLprfUQwwHkABK7_K zbhPNFKAw8)5X;3P9D|OQR+{P~(BIV15P1#*T*slms~gvKdFoeQVxixj}g89-}Q+ z2*Z$-ovmDGYaslm-y+{!&$Ivg-=`W9qrS4i?86s9SGORoRYj>QnUe4zsZdUC|Ek|n z)*1D^X$Wqcdy<4IFPe)<&u(e6OQ`!~t>kPLU{TE6&`2w-MC+aI?a2$F&qyq4< zSB_CzQ;6qxIkK&;>g=&81EfM&oH=uG!hnMxpW^I+eJnjx1ZIv*If`^1P<~cbKV}}T zP_s#!^eE8O6kNQxUh(^3s*@_0&0LFD3$pFs(!qE&VA~9*az+uyrWnxWSvv?ffwn9| zI^R!%Z9SZMt+RRR*;Fr=Q{<=D8LbwPY~bJ~LTwCf8M#Hz?K@g2)iQ|Rx*|NWrAK96 zA+bxPnGgc*$`bAG{T0hk{Vi5Hw-b76zk=&gCvje0c=+;>t!_I6EaRyg5_0rGB!{Z9 zW%O?KO1~(+ZMK`^NlMM?zv=Rz{$4dmS5d55-kFs}LZCL2!*k@tYAb&bdqYP?)*L?Ea>TflKL1h^b++d+uKxd*pt$QCGM3KYqd zwoIbl{!;fYJbW?~$+Ch+6B8-(==fuYwCCQAPQLom%i6p7g$45Y9G+X*Fn@k=kzjHj z@*dPAJ@>!xbsW~*jJAENl+Sv&d0L9)c&9!$ZF5I@yEeDV)K%M5HmhOH z8_sOTR!KdQtuE?%qLy8~ep0VlL;=EoGw7SB0%^;XKMiH*OGl5xzdf$K+tELe8eV!w zDbEMh-}ZVW*FYNlj$9guPNWO*}L%=*dDGD{x#Dxd4EzL9(^;*pzFd_T&t!XXk|$LHZgEm zx^_9x(zbd3O5$VPFf`eIVVs(DKqOKK*>~nF#cYOKeOnUoS4%Yui#TD3&gV!xidPhBSMxW*H$0~9<@i6`UR=T)-yuIq5DZ6F@k zQ8;~$1GrAevDV&FET5hA!kDLMX-`wXmCRSRQ5feaj&zsPY1l}l);!5mMS2cjO z$^B;Qs+vFhhg^(k49|nw^bquUcOIbUCOwJK8?}E)ByUGr9K} z?mzh@RvKE%#I1f-Cdn?BS5CWpIQ`kw2I^?dl+TkZZ&D_(?G4-H1T~IsYnEIwg}mTm z+NC9rD%p*;^;@hWZd1f1V63x)x%yfrTU*yENh z(MG?LraCf1r(cikXk{{$V`eyWIg#7WXfcV?(v@yydQ93dXyKtqp9Q&a(e0}ZTSWk{blYfJfNr0BsbL^Xs>AjCyP&p zhFk-=OaYuM?KQ2`XY26s@EniMng$#kp6wW5*>C_EEM<*umeV;zVYp*aQ2N=G6 zi#y*x1=CA7&kV-z?~IOe@%R56e_;t4^RT0h`|sU^v-hCCndx^f5ndXj?r$CE+0+_H zk^p2a%+kK>iBa-t3b*CwqiqE1pju4_%l9;JEt#OMkV?WQy&P)UWWF+#ZFZYAR=jK-Em3XP38j!S!Uboe1t!B9$VCHuInR5DvH zsOigtK$AD4e{jL5LHI2o^%uox5Dzv+JQ5Z4X?( zLBsSkLKT!$(5T}@ExQyP%u%j}ks-?gWgTdLo`jK2+9VrIPDWSCjE$`?orlL^(`RA1 zS-jdf@>^P(IzQIQ4z5jQbsCRf-KMmjj*2C0azgqyl{2Zv*7CbJY$`c-@`SYRry|ti z*j8G#7OF=mkz(`Y1Nv@`Fw(y*m{&LwJmW@=VnH^G<}z^ z_8*Dg0sQ&Rlbq<>&DOehD5ZR5c9c&hZ}6*IrT6MzAB?UD{7)kva(U(+N85)u-m$CX zD+y{c8UFUr7oz%?;yl;AUu#ow#81#~44x>}RT|gtZ0cvIsSgx`Nm-SlWdN>@ z+~mTm2YLP3wRz?hBiGdWBsY%q?Oc%3y*e^0^X%1g_2gPuekD!k$EE@}P4R4^EIaNs zc^9N#;amyt+SZUHYB1Lk^}up8W1_7{jJG;>{dpq6*=_jA#9jI~kfTq1XSTX9ijLkD z$wcx*5N?=`I#Vq2{11MF?|Yg|AW2F@Vhba>uYp(tD>lR(T=H{EJolp?^ZhTpL@~3m zeB2EJg3vq~CuJ8u{%wxzh|*@3XeSBLnBVIT;;K@h-(^V%3CzjurP!r zFJ2}NDan7a^lo0?tom}*J(Y?L=Va>$ek!!=`Wo)zLP%t6?W}#B%@m6~`=hsDg_3cV zMD!6plKG0g5{X&UdAC9{ISoIq|S;s{i&q~ zG-Yylx!O1neQrb{A8+Z6^Fpaj)`dNdUF2OyGXYe!H^~E%rYxg>3zhoYJOfiIqgj`7 za;+K4G{$z7dZ~BTm0N>NlD(yx8z$EiwJ-Jb9cpLi*?smrLB^w)$!P0I-^d6ZqxY4X z5SP&*B)7cG&4GUAOE*M63gm<#J1<@$yR=f$G3uO0P*P47V>{VHVz$_NPUwPkO3p4F z0f}c4;gac>!=uTvl-GYJ^}%Y|@?8>3+jyNc)%6ulV!9jD>k-DSDNAeea!;9yA_Xx6 zqV{&<6;RAxN?It9TY&JmExwp5n9k#L-`uh$YPsFzfUetjT9F4UBt0qX{avuorQEFBokrU@5D8hVNKaj zl#_UTnC)whP_?}s?Y;em5?w2$j#2x5fGI~+nxV2DW-8@%Eahl}6eydtNvos>58&+C z)yS%LT8-RfQp>q_=zjOlcrbK?vB$r#DueCSVQF?>sYpY9Y)?#k+NggDfxVrrLw$+i}*4sB<$Rd-~&9vbcHq;_tO?mPEr z8yjc5y|Oc%rR8Prj*T(U+govUHT5Bq%rT>KiXi52Dkrz6pC(`aV$sx8i075|E^DAQ zeX1uYBjA-AH)qllol0^D%VDh=ZG!-ULcFjURqE+Q{|ZW5I_wZdo$ih@T+~!_IBgT4 z^s*#N621R$;ySw;dnjbG@c_NMFvZQeaT;?4b~pCMF+QHS!E#V!XJaqTxdIS!Z{Y!R z#YMI^bZI#RPL{BgwNEDY;w;LO^YR>O-9}haXhkBdS88F8j+z#>)_0b+kV9}h9&g=7 zNaPW2TZ1%k?x}5!>zwzp9B%E$CE)Sq9$X@~{_VLe8GJ@aryYI$so$1YR=6;HjeR?Y z@Z4xj4Bx)RgP9q7gdimR%kwxd?0|axs=fOkU1j3J2#de2ZzAvBww;<>j_Y@BGd?wi z>v@oIaa@;$#YHY&AI1q`@6H`$iXqM`yP&&)TYvch&iVWF2+zP@t0niN0h@nO@)%5?Ma7; zX063r6Ml;~s$x2b72v8dOnU3vT1c-=Woq8rPxD?mrw;Dil^RyIoL(Yz{j-fRRk7ez z98Ib>Ymxfe#%(#0BS8MyjG*gIgbpSFxTucc`6R&^8v5>ROv< zDC%mfze?rXHp%Cz?~B!h)oBw%Z_;N=)6;P8-e;G8rCFICFAcb?wH)S(Z_mrdjr4CS zhcLl*QWCcTZJSy)nO;)vPs$0lck273{1BxhucI)S$k?X#!<)TrZ!l*c4t; zbi7kLGtc1FVM51Qx0kWbd!sZwm{B}|n59?wpt_x*tBiFram?D}M%Q1a`RqH4y!1N$ z23>*usFD~(Dwj9C;wCA1ejnsP02g^Xl)6<^&Qw)w+}OWG>HX2wclpwmgLKt2#_vUW zB>t82)V$tQjU(#!Z?3-0TycqC>U)B%bx9**hcK2De{I_{wC9^*gKB`G#y++;^u!yK zf_`P|2{MisZF9AjzIdMgt{!%7-3q{syLb5E z`|oM_Ew8Nb#=Gy}y5$XDzwzo9`K9Nc=Z${?wlar8ihTW99x_|xyb3BXrh z`T`Bg=Jlyd7nz-(=fvxO4gO&f3R!RqIC%55ec(IY97%X_VD8kTR+xiJq(idH}RQTrgTXvn(boC)m7R;Kh7cy zxLr=X{Vwkxf0D_TjZx66+X7;A_{MgDRF_NLhF`kbP_9?e%9ma7dFi{~=dI_T-7v3& z*_9QZ|Nf8gR(!=DrSNGdJZ&cRs5)mcwYHTsKK6I&dTf5Tp0z2sQhq)mF*G&u=B z``P+NTN)-^4Y|c-9{b<^HVa*YjJ)!nG2gSJ>ijBi8dk=)Nv&D6*w?0oxASpZI5jxyc%3M1 z2<$z54$t?wF_?b)MLDWjSme1M{TO#8D3wa2t$UqaFA09QTJ4L2ZnPLZZ|X!Vk&prO z@h*Ssq-&)@?OBE}^+7fVK%nj?nYt~R+Or+oOL-I#*f4o3n^|s2wXVxox9l&4lqQX7 za&|SO=ICJaps(xx)m1`I$F8#zYXC+%B2E~agjRQJwMa)_i;@zYDU+$+7Yc>MUd_Pu z8*v>({-)uJ)MG&F!~~PAEsvDZHo#PKGnthlwKMa0E50&XbuEJ!(-M)0W20hqlG=^r zGjXc6wa>Pmm0ROhqf0dTq9m1YvL5;LdaXqi_zOl-=YNvtd5>W7^5 zl~a`qOdWjEX_tOfM#bN{#cQS{m#e#bs{HQ~GTqe3`TcvDZfs1n4}{PrI9&i?BhBON0-Of)yj^mkue`tx_%w5UoYX8R@k%0 z!F3~kREaXela4&QCzLdHvir!D&_a^xk4ARBDFm3)b8K;j<)El|>5_DL<{rI;W@L`#Dl}71i6pIwmz1=+7zEdlcT!tblWNJ9xv0G^mhrP|Z(X=q;mXzFBxWD*- zvBhZ`vjzI=qRH-uA?K#=LKq47+v^%=%X*9~&T;nEO>SnRk<{JZ!S&m>+1}sJ_1m{t zDHiGN=%l{3mhlHuj89F)c`Yt2@!px!WIPYg^XTvHW`1FTi`R#lQVh3i@_7cjd%zC} zFWlmK+ak;LQQLI3w$j|t$o%*NR_;B};sFFfWTHO5ut0ZvJ6nE3dR3d5pNm?+aX9uX zkCRor3teey!g1W#WB6)G7lL)T2g&g)-^nL+ann`7HhTC%bCS6xOOs@Jpeo38hMWFZ zKAhZ;HqY-;%1@L=ko3qA8edd}oxO&t*^L{QfOu0{PfwCmiO6UD`@<(Of(s%hFlwE1uKK)bT6peo2^TI#9iBtTbvQJAZA5G(L? zm1we!L#>n{(hrJItVS2**3Qf`bn!C2=W(}3zXfJB)O+hT%@b3aN0Vd^NZH<2TG2vj zU)I7~yyZpeuYE%9&U;Ml{U7iP8^cE*Rf-IVJ#GBzK7k`L<*Xl%UgGl1D0`c>aI}3W zmOG;~#du8`Qp+@w2EA$gT=eu};Nypp4*)g1s=T+!ev*<~u3zpyN)U!LWD7B#)yort z>+x&bo~J2S3y!O_MTqOTxQ=U##*n;gdXf$C90%7Cn9Wfz2IO29G^x}+2Si=n!*ybksDk5)`A2nlRws5C4pnUF2)<9zeYH+V2JOAv;v6pQ#JjC$qf4Sss+6PA{jsVfv>FV^3F`z?;_+fRE1 zL(hCZkLx%*|I7(iiqVZ+HMt!5(m{%BCd043`b7Ym>gzQl@B>3T3Br(kO&$vR4Kz86 z_a)bLD;km8$O%JEyz?%#a|?(KEvb)*Lm4u>iC;+cl#RQk%ebpu=h76C>EDw)+J-&# zZxT%<`B#z`nnqbFFO<)!mv<9&By|(!7M@x|b$eguiXqb1l&j1_ahsmlHuiDJpn4rM zuW>dpq|9d{>4}pc(l$1sj0Ks#*npMV7xDk3$WN=q}p8U!C;K11f`>OKNl16oN zb3FOp`(&0^D3V2Nd`r^Dpnde2x-(H9n;uO~@8ROv&-;eKCOvvIItr&wg_PL;r%LK< z%T155`(OPdF83W~<;AbD(m6or+N~Z|qb*Fw%jx_$Z8b>?uZD57)kcQ5@p4r*7teOA ztA|y+W}8@9yszZcM8&I7nmR`n0=wh*q}=s26Fv? zp-Y#^_(iVn*ltOwJT2w({Pe_ej=%F$+@dKdNL-}*<3#zTmQs?CJ;cBE8aj#a@_CaF ztcRrAE-}_s`6?-cs=wv4X~Jg8#<~wubI$1VGU@eNm8wM;HxVx>wTQB*>BxHNHINvn z+>TK)O{vFH>yivD+E^{4ILPNEFhY=8E;TLTC)kw0T!KVfsC8eg$%E^VtgV`(j+t(3 z8(?_bptUtV&lEZi9~_Nt9Xt5RDLQYD;ufP-RTyR~niVj{fw?<|@+`HNP;QN@M9KBm z9(Q$o-u^qPw_Z22f0Oe|=bO6!Wb>Qgd8#3|OUOz-L+DAYC&H`TCBL{F-J}E*vmV84 zMw{bm3uTvz1a4FUZ^c*Une>qz8Ar?BHT49hF}HdLnUENwn4VTs!I?!_qA($QKRFxM zS1)f=I(eMSQ;f7#CnCa#+P3`t|1PJ}3=v^IoOG_NdOFV@qB`Mu#Tkd4&$Ls{w z)_IS#KhkvqDv5Bi|8;$acwY^r>)|$z9;OVI$-q-jIh#h?oAjBH6Zm8%@8iDx22(o@ zbMN_Yu+*G>lf9`Cs}#oeoQ9*z$)ssv($Y>Vr;3kNT$wD39!{=Ms%%}&A!o6Yn%YIv z1Gjm|S+2Ia7j3yRt1<^(gk?oqA3piShB?PD=}vDC4j}`>H!6m`H$KLXK6sx(eq)?i zigrqK9Hoccq-tnl0^WHiB$tC{pN-nBrUufs;WBFDt1NucFLHa~0j>l6wQbr}yZ}?n z3rsH0Q^@4$sA*0xep5*$1er=q{nG3>50>ZYu9X`KLSVZ*J4t=Eo|;T;V(LZZmy{+T zNkxvNE3*^SX6q?rgb*xJ)6;mq`v5xp4;iTMVxYbg&@aAup?jZJrV!|_??gAXR=>)! zsV%+eFEhS0TQXvo;qNU@Q|skv$co7*OBIA6H|NI*L+B|qllL-AEX{Iq{0evG$Jx=) zMb35T%-1nIH^yJwKF5|qBU#s_Jzqm>Hp}Um2b{clpThVU(+3aI)X>0NAAZ2r-d=uo z>J&Bk98LB0)YsNB`CytWH*ab+>+R@d`1Wl8I$B!Tw_^x^>v!(NVVWBnIC1Fl=;8Qr ze)Pfn%q=Vcuy4l>w)XTg(%;X$7solWZ$CELyFKaUqoKBr7oI$74Zov*Z5|6thedn>9Uk0@1|dPh|csrAxNb&J-jom-%Oc6Qyy(5({_>^Xa${Olq=8AX+1 zs$+CDj{GhS1H{&axHNR|@-Q9&H@EgPynT?ly1I3hwQX#ieP_;+TUe%8Dr< z@}OJ?#(H@3n<>NV;Z#sv4rrSzpnh^WsX9!m6Kx*GYyexV%t`+mV#8XGtJY~bpW{Je zQ@n<^j!oc{4qXZ*w#wHF^9$@fdv0Au+cS*~G)_*FU06=Et0Yy*JrF2NEMmmrJ9bxVtdPTcZ~!cv-&OcUX%vQ;hK2 zTya@bF{!gL(E41*gh{e(RXEzy>st=foUhkB(5T;Ssic32MpRR--dHbmtS>^g=IgX~ z;zS{Q~IWLRe&e5;Y#c4jA zxWN~D4*>9N#}5AL&S_SHWgG$){Uzp$OZ3p*D_i#Sg|6)cVU$KkzBXPt zwiN1V$!6)8nBuj|SMd)$PUu9q_UQhD)Z`hAUqUOajX0MGSkDS2Ob`S@{~8yc;~ z(>AJ4@g(NDZk(n`HTk^t{YH}$h7@KOZ~}evC@9?smPCAD;*Bz?SI(bG8`9OKA<4$u zL_qx+JDON-I`9<8Kk6&_%pmKlJDMc{o`*nwZV{J&y=TsG zY0pmXb*;Yb8y`%w|I`@@vkM8&+UcX&)yk@WOV=)`l$45+WYdQ^=!dDQrH#hepA}}` zq(`5MMJTDp*FpS)QAAWwH9;y0yA(2W_cUL?kUPPvz#`J!tOLwX+ zCnQ6$tdSg`j1W1RTthMutmqw1&h^2l1r+u+Rgq!iw92puQd zoeCY?P#SDn$pIX7{VBJ`s@S6vGLzb-_ntoX$a%Z|d7x8|9b}(#mMzzBl~%n7VPt@n zl9{WHT2urb8SDCq5kl#^9DkL_A*l!42-5j%^0&!L)p#Z^6>)8cn{A%=O~)PD4Oec+ z=_3adUffN3=B>A>o1VoXJWIBMI5Zvo8z8(?qZm)Ah*qp?`U(|j_9-Dwe51R0n^s_G9RjT-^8BIsWPBJ(~&TiahNm6Hq>VaDPHgB{P#?MKqQ11uP&cfriG|tXw z<6E|v(8C9%d6hl`&9z?`WruOOMO*1kUCe$+YMxAq$>uUZpON=;@PXJX*c8ZWt$p~SP}p=Mmxd@)VYMsm(dnFB&Z`!}q=yjqRtOc4%$}$BF(_$_N#XATgjv zmuL77H%^juJ$`rBOXM8kwJQpB=D}Uwxqpf64PAVt|7a{!h%l-GLWdJ+3r`fHkg35B zb?Tb1rjR1)b!17AuccW90D)~ShX8~>LMf;im|0xnzOZdt~?QE zUe6X{TL44mic1iNG-UHkEI!~nw?E-m`k$b^rXkMdr}rW4l*89k35 zhP=MzF>1XAuFl+MYH6CsTl(oKG;(HgnC6b{{N(->+VgdMrEfn?nH(NIAw?Q8Ii6~1 z=kXo8IlE(sQP-ulsR_q%Xl`ue$^H9jYl?ii4-E`3G*H7dk zY|T>Iwi9(FvkFV>3{hpGYIw8kp_Z>ap=+igYbk0GqO)uX>PqUbSVbZYbktTzSF4)f zNq{Y{=u-{0G4TJvcH*vy{%R7e>SMXIs zZV=EgJ;UJ-PU5ckN}HSFVyGxNL?4)&*Rnn~ZWvns)Y2~#|Y!5gs&E8JKAcNRIH}~ zX%lSgS5?VPs^rCu`YC9khE^5!b9J?Z8CR?4cw1Y%iR}gf$A9uu96zLHb^+Iq(1CiK z%lABH8X8y+T^ZUzc4>wFYc~l?YV`o=*CVQ{YqXWTp3xy`Dkn;)%S*bPn0%Jx6pQ4? z@6mYaea`;g{{hY#JnvF&raXEiwtZ~Mr`l{i`z89AOzIp4M}3CYl0b3$VTi1`a4%l-;)-aW@_ z-FvvVFvaeM4m|2PKYb5B4B6Mz8^DoktYk8@Hpw`3g#vXJuM3^6Yxi{f^GJS4_D=e9RJj7^97Dw= zQr-=<(U-nfnQ~^O=k<_{uj*)Dm-3USFuAp+|LM0vsC>@!9;h01+2*rZZ`~WAJ*?my zGIbYmBv$wOh4xOmD-al4=l03x=&x>Oj_sGP;)LP44n6_wJ#&tl`NhO_&Pmfaecb6< z23dZ&YDg}tk4aUMk-ph#XXe;`=?YE|a;LYa>hd>FO)+%-5{;A7sMk~59RtV}P?W(f zt%f2*5ch+i5D$5aU+v61+b&(D>-Jq7V7jT1YumR~F6YD~Ll-a8I5k}=pTxwfE<*k# zzokih<#k_`!zAg^$Do6Q(AoJ}mtvDXOBx-G4ll2j)`EefcoAi1Cu#op$8@~?AMrce zxc$;^6Lj^1#lyBOFWW3k$I5msx9xkHE;~Jp%8_KeWcVbuO^c(;*ESBJb3n>|m%QEF zWS00K)Ud273+qRdl1AI&&W7=hHg5OzvYgLVb=$&xeJxHHvg^V{qaKlCj2qhq*5w!@ zbQ~sHTM0c^YZG}_gddweNp34V3_EdnAuA@`GO3)MIF$bF^G!EygyeD#YdA}`CX&4e z>Rm2rVFlTw8`T@1m@Cp}s+9OdO0HtUnzqiECV(L4QI-{Kb6G8`8<#?wi%T7qF0H88 zUdWb7ysS$0p^;vYD8~m!jxf>M3PAsjo9sD%-qN1(*R^fixH6PBK^ zvXQP8ipELwE|S|LLsoe>Qy$HgqesRQ<4oTLRkekcH9_Ub)H~YwY<21Aq@x1)7g*lu zXhWZoI{FZ6MTV95Fv7b}pJ2Mle%M{5pB+Dj6H1+LIXZpt0Ab0>#?N>h_~bMY8EK0e z2g>Rw>Z0yqN9ER6J>jJ~P(r(LYVzg_d4yW%|3YnjGBw5ay-G)EwIqfMEiG$vNFjG| zrCvw)&=#)H)KRaNQ@j)A-$L*1l#p$?u_fvydR(oeURHT@MmJD5Z}o^s*h)nqTy!)m zwFJa7G1AhjGG3A#qz#rX`RKos?(NKHY0#aNLhUnBt_12q|D@Kqk_Nf*Ojp};^_=D5 z(8>yY|N9}&KI^b~*60_Pu3v}q=RX|;ppN{Sv2i*+xrE>SG~-V{MNme5Du-!pVf5$p zx}{-gHNIngR}Mq#D~FkuS+1n4uCHJwhf?FY#yj=d)H<3rXma(}or$UkLG_)Czz7$G zz0=#nnS*wxvY$2eb$0Pvzx-t!oY?VlIWpILQBVDLN0lVMzzDPPGb()_NH5XqZj||X zr1#znaU9sQ$H6qM%|uFfeS$cII8KJTOrDJE#fo|H6(Hkgsms)m_j0j-Ax=%ptsSXM zv3ILVQHXubTZuOQbm*ImXX_MGRU^Zxpj$2=sz7DNu@Aome}y27KzPpe$h$(kmf;*i zzIpv;{Plsubk;P+`Bs85LPS14b%SD9^9Ps3CwC(VsbrmVN9ZMKX2d}B`A!BMEJUt(2~@Jhh2C^glWgIj``fhA=f zRJ#asVpS|?oSf$I4?g6*r;f2)^1QcJ8oV~l){?=tAFCd85GPrvEN{6rC+Y!8Eg==* zXz5BnYd#*Gx9^cD7CCk3Afe;1oU5*0P8d>{U*N>s?}8sHb+Db8)4`}vW`rfcFGiq% z&f>}{eGWPF-nfP92VB^_1rLNy5K=!g%hPYYW2lBzk7Dxlwl3<)15RlpSnm_Z z_?|Y}s}n>Xb%AA*Hfd!AE?fv18CiQ8Nx5#lwEFZ`GZT~LwMnz~)x?&DE$=k2t@HOZ zFin|na&t;osN2#EjrYk-YcNkzi<8i*Z^kHJPm?X|8`wColFP=j$f+kD<3Y1(jHy%L zy1e`J2>_12^HUlp9+bY6482{4$+i~WKbAabxOx&YQPhe;W)I0AAgH{OD&mAHnou{d z_1=Jui}Mz&*flK zXB;E)%V)|=Aq|-f4fU;v?H7Qd`sUL2BHekRx%a8}T=q6ZVUsN!fs~PAj?!no7<%7%45!UljrKBt`Y)e35`S;^BmPcSdeN; zCR@YNYU*gUQ`-SN8m4C0cJ&$#A$NMJH*yx_`93=@UZVHrZJeThU_d=YYxV@_V?-UJ zVtkoe4Apz2jOE52%S37o4`vy>I!x2l1Lo@MxH+KTucuPS=zZG8#;Ki~r*&*H#+lOF zmXu^v?5Q4gcS>q?(KkX)kVe`N`R(&deG}E9erk^TsoAK^lQU!&mo4K}m9(I4c8->~ zoT{{y#K@{?VR9`{NxTcS*46t(r*hn{+OUrTwYEB}^HQ@-dcj|)jxHahVOw4I zo#aCL8f!DqPI69(JCX;xbn_}bj(&i7th1fr9fORwRexY`v8INRfj+#zXUC;0h+cIG znQCcT_pOV9uI<>y;N@%N=ax~8wrt0xR4S(#eHeK4QN+MgQ;`FNPuFPM)yBENxM^h5 z3#nLJJ<6sVRR}z%%GOCkXOtA9k_eBkLiV*uSN5I`A(oS+8J|3EmzKA9a*cM7vs;cW zmw>UZb}sJTrL_^jd~GeoOmxe^$Uq-so$Z!7$~>0x`KtG6HtEx+t2=iPIxc;~Be*5~ zMNpFLr3ON-hpJXWN6lh}2|bV*&c1G`GjlcTTRDuZQ*|kp3#0Nxod-w1Oq3B>t`uWb z;+1wzgN(;}PaS2Zu^~3FE=Q|5j3DMDz}=p1LdW6Y$EOIi)q;}dNbI*to*jMn2({i& zjff=kT7~Fa5T_(}xYe*K328^tjo*tCOz78 zansY&)3L`-!_j*BX}Bz@b(L{V ztewQsrjrthj{~iIGK|iFqy?A24!Q?z6?db&msnZ;>nZp`eSdZ54(|4Jvy#nfe1ENU z_7DG(b0^Q>eB%&J4fTBC_=$C=>AEg8x$19QRePu0&WPFDrlhH-DMx{QO|M>xRMY%C z)Bn%jn+Dl&W#@rk=6kR9eMJ?3D(nD3fB+Ye;LhIEQnz}O)mmB(Ezu*%Bgs}+p_vJd zWm(dA!m?+q(AeRT!iupXG;T}dR!de(t#&uXZn6nBR}dgTVqdCI1ymJk->cq|IY089 zJm=iJ`IcG$kbH*$)_eJG-h1=rz2}_ooO933WP-n!F8LT30J^(@{riJwPI^Lll6%!V zYg+L??E3-G5Hm;!Uciy|y*Sdo7ap82^ECxVMqPCAK!Qob27R5E756~9`Lz2FLP6B* zKpFu|*MKA&@O6>HpAEi>@s)W1z|-CPajboZs7o*yhmXPH`t;?nlJzbpxq}Jd)vnjM zY3P!_+7$;$o&rR{$jEChm>1H%c0K}{c^CJJ`HQSWI&fXMaM3Woh^M}H0^j}kN7l7| zq*`H{hfyvjIk7H7Z-;gQN8cvGkswz+1-g4kpyT#9KKA?zSgfzd_nvzu=wFd%t6N&a zGvEE5a`3_!yIdHWr%kbxO^mXUaxgia$dCi&zu@r-j@atFIgYNIW8u^LF7V>VKZ0y3 zUeRiro5PbQUI{aS%V3n8;h>hY-DWb5s-*PSZlZ?xTu3?5_k8&Ha)my)bo#W9v9UYb zX5kf7*x6J{J%yl&4e%DPyR>qSh4bip<^84^QA0QzV3xTnOmm=VDvVwOOnEQ4t<5N4 zI^^V$&%}YX$=SndT@_yb$TL_AIq=~+o|*#Vot-#+?C6^6GfCrw906(+5 zafL|hq~>pWX4l_1kM{3;4NGXi$d~`8av$ZMrJ*4poAvSV!)ue1q;E-yu1(MStpud? zf76V`2Mg0&=67V?5nTt`WU`!F#krYb_y7*I_M^&8Med2NJ8sJdaC2!KE?n$w=z!FA z&9yI|(?K*#xPA&A3DT0PT?db~2Z4--o9S5f9Qx}h>rpoBVZs3(ZQGWg=ee-fLfVlz z&bFCfj2B18U$#aol-3nxm`-5pjho0O5?HOR!9+&~=9`LV;_n)}jrzq!%(gU#+0)(+ zRJXK*9oGlYcYP2ZTx3wCFo~V}0}_)+ikgZyo8skXp?hqyHj4D=dlXqk^A79G9j3d{ zM0u`7HflQ)Nej*lW%eaH0uo=!6R86E5?pihEtzlB)E=m9c3B3SR&>y|gCOvwX?hkr zt`5L=9E_F`Rg_9+&_5WQJeBq3hI*+@xax_cmI^&)#0{N1$8p4e?2h%r&w-sR5%N$U z0j6%4nMc#iES4JTk;rDnYT$kVK*#L~v`tKkx61gEo#hGZbFqbmwtG?VHf>-Iu2BxU z;OS`lm!1<^ueO3DPVH4T$k4Rh-Q3hVH%w$|2sO~`3{!0^keK}U&KoL)&lpHVrwo{7c*t7 zoih|KW42>j=A+m<4*xppUKv~@^;;9ydSN|L`O6YYe%2OU`$-!t**x{x)FD#H23fVM zs^GxKcvlCe$_UsdTCJ|ewOza5<^t*8JA4x}?X6gB+_)Vj!`ru^_vS6sEUsE4v}uQs z*tPui5$73^$n0LF_k&#WkjTF|dS6oJn+4y z^(FG#tIawj4wU$qzPs>oyQdR3w{KhXxXJhGz{hG$bx{nNuBxg8WWUd8rKSey>MD?@ z%fyZBe=Ln?l@<2@OAF2Bki?+WlC%KG-)J3~_9-pfZ3xa+e89H3!-0q8+FG1DazAF9 zn>Rg{A(KjBY)fF@y6>HHptFk!GrRdT5CNAoZ3S98p-kJzW4z$00u4ik7wh}Y&~H0M zwFpz|h;CysEg2e1n;r$4T~7E6LGN5p#%;ElxJE5(VaO>x!2TTaY2*5)pF{eXUE>*O zUQ&j84$kISDHqzp5M1@ddyea|)@8R}WzK^-lNi==zAPyZmgjDj*pIWn0Q-f2FJcNU% z-h-3#jnUGwNxnnv?JJGn7qjVBD4>;<;9s!0$j5;L4hL;(aG+h#92f_2ReomW2LK!- z!o>pheZqY2I+B_}*~nB6%b)t@+mdbTW4zcY z1ynDu;@R)MgqNRvy66!>A0+A@7{tB{mkdXg>6DI|QYC~m%h`Z(RJq-FKq*_Z|85FX zHoM91rXkA)-?X6hlyEemAD0P6m3Bp`OqmvvA>Jk|GfBFdr5TVzrZ_}9a4vJ;wkyVg z0bU|h8fbqs)y)CUZumWw&fsIuzku&O`^=g$ZXbO29D0Xt3R46b8d-$ejFD`<*Ke3} za+{_P%^~PGt6+D30#fyHkwf*;DxQ1(yGX#pD^EWetHiX-%;1sN-wHEyd2o?M5L%)&OZK3PHKPx*Md51L3}JXT+hQ(FP>1X0K5kM{Qt5@B8`+-&r*%kMh)$1 zAuyHBu^DRwy^D%j%OnG$j z*u!vqAN$W=MDNh8yu>ZMIkFtOxPLz~$s~4NzNW@X{v%9cJ4?t;r2}YrPyNt&bf5fN z41MYs%e?o4OQ>D<;Y%tFu-^*fRWhVIUZ-bK$ zBs6t%T0@ch;h?9c5y93t&b6zx7H(V4LeB4Ee`abW$_sd&o4B@+E>cL>ci^jEVJTCL zq;_crq)P*pt$iO3`mf)B10VI<7cte*RTg&S2-J*v1 z1@z|wwh28&-!Kz#q_}rWj>h$3U)E(yt1Dj4@->Z+h@vu5mj(2^w_)VqpI)Q%-3#TL zv@>yFiD&drV;H%uM7AsEw7KSZvn*p|+LRzMGVw3^MPnR4tSfjIyumg=Y@DMi2Nw9Z9vWh(yuY~iDgNC){An~%quTd!*{39L`j0p#y z(;H47`)ckWWihk4wY%jd$4!5sW7Pj8~E+thb+Rw3+XE=n%CqS}b}gawI%T;irj?)ln6g@i z7skaVM%MB-UhV@>_h>vU1F|K)H6@r?-sWJIL8~r&jQ4cn>i*pu;#|(AlDKg2005wK zd>ljl+cDc5e_GXANspU(9WX7T8i$dzj?Nepw>Y8f{&3hm=jMFeyy>8(23SMfepy8F z-}G`u5py9;%#X}x^Dk*c31jZF{U>S%)1D~WaOa46gL0UgC z6RQ8F%|q4?QHs9nlrroWmwlHu1N)fy>YudT09t-imNI*#$3)}@~xCl5||db6G* zT7NNDd$b392U**sgw~(Un(RCT>Ylqv#rs&H3NZ~10^{R%w#}w%r_uH1H?WKxIdqQQ2K=aAV9Ng}l8)MU`J41f6eB5b3i|<>?!N5VY+6|X zhKGT4+DDQC4t0>V2Gut63ID1UHoime7NuIEp>3vtMo)&tY#M)c;|=_S{>M?B;Ot>! zpn_;4YS0NvXT1ypXEf&vmyYI7_wGkSvRWO#tbqYjeIlXQmJ_Obnn5)s9LW6ST9K7) zL>Z?UP)*M($5|Rg${`7C5+Soge$+-^DLTCX#J$uLGiNjrlp{UQWXGu zIdj%(fk*fG#=Oy7fk%q(H~(?HJWov*o-}LdKKr6xF?S8|&v1ke3kDFHM;KhnnM?uP zQ8NLJuKAf9;7K^h0=|!AI*a44zJ`;JJdDML`V!v!TnM-Fm^DUA={A9FK+Rd8{+_VRIj3I!qKg5+YNFnMPvE{*|KFU00d`-?| zn_^?Wr_H1|NxRWtw*sImv=(~(^dHCZ4|VZEwqB{?VH9z z-}sHMo17pD?4uyrY{ONYOv-=HQpN`VBzKHTSd*hh&B;NKwyWw0B+6KCH?Hp8ja(v8 z))AK`(Y=@U??X0`K;OWP4draPWCC7-Hh~3X?#`E@!&g}o*6X!2EFnvp#x=sYbj_wu7b3|oWPjM$qcK@I{dPp(66zpg ziE>P%Wc1lvre{#Qyi~MYE|I`wM>`U^99pNQ-#08dKswlt%0W=^aQ*1#R(Ul3Nx z*ugGu=vQqWVat;Kg<3*b&M)%46vLr@U-ow=4bwK`v;J$t!qL1{I-8(0B5Ol3%Q@3< zuJIkac_lAN#Mq@+YS4ybfHQjm4tO)Oexks(=H;_5o05t*G6Uq4<-Fj5RnCWl`ng3s zaOw;)RVic&WEyFon8fZYSH+1(Iy;z`$CpwYkZ(kCS(CF#ld%()Cl@;Le+ot?DQqG+ zDaEy&!PL4m4i07kXR+2{)zKNleRDvW&{?hrqf5`?fkN!vuspRG^v;DG6P{B#WKj0U z70+PKT)84lspcBLb8Ax5<1v(fqvVUf8;LpZ)w(M5;h@36^#^R1s`CV81FD(4h3?nC zj@sJ;nA!IzCXak1HekC{yc&m9nd~^&USCu;n{rTpHg!aZ>$bmI&(<);L0p1LOGwi(DRb%HP(80pxqgPFD#y!*hRbz$E)nr&?^sot^431lzb209zi zvb7WSMS{oe^Tb9P13SidE@NV3)3fs7u~UwW03#zl+S-79`|{)F0Bvo--;E@#UrDTL z>cDypYwbpFW^^F6I;}Y+kyTpKWOoPVn;T)1ywqCv$SCUPmq5B{xW*hG1G{!$sDC?F zt4laq+yQEqmod@VSqa##P)L^s2Qa_52mt76YsdB?rwD2LpNXW{wxNlT8J*GRz{dBu zjl%f2FvZtfh)TD+=+BH~ZF+|03mV00I}`DR<@#FO*wKeOP1$4;H@9!a-iw#vx z)Vn2_?<;gpxK3&>gh2tGA71ztePis{7DHE{>auONk77(t;>BE8k33r=OifA8HlA~& z@wmdGKpb4^J@PrVzGu!WeN{dWJ*SQ^h~iq=)A%Rlq%l$^IjR<|bH;o zbX*O6bFDS9JOjM2b{>B%iM1Z(8=q}9Gj5}Fep0IKtwI&L6Er#LV}5>Z_m+dJiK?f^ zu;rDnA(39j#8Y2{+qVmGE20!!ZO6K$_ElqVX=Rg`R+l%ea?I;&*P?Zq<+Q{x`Mcgm zW5>>biHnKbd)E7+cp@jPm_eB&vg)2(bppeEYd<~5r1Z=p&iuh&yP`IV>zp4348O7h+_-@t(>4$Ye{JMK_*s)pmDVpyzGBmP$I4DX^j+2>sW#!@ zBi(yZ>-unzMW6(lsw5y6yxHG}TDJml@`t=4qI7js)#S@YvufFCylT3zXYF1Xzu&|)&p;{dP z_nkkFOWr<=b$8?aLRG72RIR4LYb2U?NededuGy95!OsW2@~CK{@h*k=*c5A^RHfL2 z2YPPAwP&tn4UMA0T?#>+@i-U$<)9LstI2d%nsc0V*{?I(-&?(#5qsy9)05e(>#6NT#!BoSR1? zlQTvx0n^#5RT-NQmHddE&eV4fR1e@@P^$)g#3O^z%YmJ}K57?M!WK>7>BAAu=!ELC z38ZxfYksrjItS<|LpE?YVV`8n(m73;O8G4YS>AZG%>L3C%A=s;^4rkJX@h_?bm-Lv z(S|8MdCo>xmhJOe3~8H99|k3=LK{yD3+oHmUJICxg9@d#Q)s3a2G)gSZs9&@8K=2E z)b(f^8gl8n9CgiCWlf1&3M_yRgu( zamP2W)>I=?U8PLu#b{`B6l0SUc;x;=CEp{l63HmiDedLWnN(W;r0&>w@91+Y|=w7rZ}8thEEVgo~BB8g-w^?TTTiEBp3fw5PD6_WevVtt~ivrDeHxzc zpnh=?etsxOv(*8*QihPm&hwN;S-ONIkCJ4^(V92c*5tMJSr`;%Sn zNmR#ZkC22Lk$W2PE!Nk=b7`dlsdNU_tE<5{xDJ-;YeU&3=d=e0sdN@qtE&jG5`}e3 zw401v(bx?6=VR1GtHTlPaL6|^UO$gM!(g0r4v)O{W;li>_V+=Xm*x2!jE!ZM>ZqCC zv|>at7IRIuG2}pYLx6IQ)0416)eYY-^;L6J3VGMhqTRmSXBh}BH6zoa67)z19{HkA zvVFqL^w!v7!CBu5TY`c<>p*zc!Zdc*v((&}9rq68d*Hc7?dx|$bHr{bwR2{>=DfKS z$HyvEq0OSTVBxCyN%Xw@=cvDV3Adj8NlYDjri}JV>qop*E6x%YUpA^Knp$_X&L~DU zJy{x`YMiX`udOTxU`svT+@|6ib!aEEnU+IK20z@$CClVe38ZUk;J`<=Dup+WKWZJt zji9p+94@Kcciwm%bHDl*aK3ODPygcQaNn-oMenic)KT3kDltqRTj9BOk~r9PfhV4D zkVpV^bpbBk2-2Fq4H-uzy3IyJ*K}$Wot}m^ERcRY(bZU>)hl5n2d8GL?Y2>#p(0KnPV2JCJJrk3EpeN(k__VOjnXEHSX%S|RbMsR7wM4Ad6cgt&i9h3vlxL{fQJ=OLNbSq!Z7?N`?TKt# zkY&7&Oh#eO%|beHRIB9gdfX{4$%Twi;%)GBC*WDy45A(6XzCG@651S5$p@nPm7U*| z!aK^*&DO%#%As4gfbH9XnwsKeD^#JiQ1$FMdQN;5bz=h;oEOtH{d zkJ;81EZ437lqvw2UtGk^%Y#^X=@Q<4ZS4(h|K(EM;u87>Z=i4BMi}cPr5=$@PMPwS%i8VvmiK2KC0y5Vb>qT}Q<-A8CgTkyOPb~2tbTJE{4CbjklFRl?0WCjk0cpDOyvTK1CQY+W+nS2<6hz7fIm74;x$so^ z;FxBaB`W~S)CWFxSgRM(4N94=B=D7n$>6@mnFS<}!|vQw^bXyE<_0|a9b*%4azU2& z43eQbky8QN_8?~sHO)6CugkD(p0^ad?twB}2OQn(rG(O^n76+XGYDGuMb8XY(a6<7 zdyeU7G3q_J(Dgf|y8=E$j(5rbY@}7sK+TgXBXeli=wEctpIklKL=$x_@tA3arSJ;W z{eC~w&Yi#=Jh`qyA2`~m6;QYy6TlWLWBVRw+%B}bZS6{(&aB&Br#6mjtuG3wp}uQC zZfcEosU!JtR6np`0m-8i0%V&Rmh|^rc>m4q+c2ES!CSX* z`Y&HZ_00v~UzHxT4a6Bw)?O~Ejq`QDLCd=*P%}1w(T{!!>DILcno51^UZmC4;2!`u z4siOk5620zj@1`A_#~I#@=KCfYx4lDG86alXS$2$xVgjMQJ!c5+S)VwqC<5Nsmq4D<&&AZd(y~w?Ij#|i6BT*21x>e&YH-2 zaJ@hq^b!ep39Y+Q0J%ASxxB+`uDKa+Jhpj3FCP?|Z*0WN&pr*;^YHXbFC)2>h3oT5 zk#a-6QPc6pWq97v;lKQz3Uj*k@Sjrdio?IOCK=&rIch$m*7RxffzF~C4NS>}G7qkU zTrv@k4fW~NqYq+HFtWaZ!SM96rG|RE_QdhnXWM>b2>UNw3|jUbxEaEKL4N{bOBcN# ze#dfCGg<$5<3xa<6Uc#1bn^3v8-S{bT(~+30uk5eB8#LLK_|q;+LFL;KyqFE<{aZY zz(|voFG{HyV* zuGgkBYo{>Fcj~K&lO@;Z^F7T#ZjFQegoDwoJve{pKI`b+Evimcp{At)PF)QWB?iIT zFfDJPDt1?CJl(XxZU&X=&$*lAdBBMiK`)OTbI{rfB$Ft4Gjkl#3=KZ>|K*yrS-kZ% zy-iKqg=k&y=L9^=w6);M{=JxODINqd)VCb~&^;Vsd6CxPEdN{EcBnZEa2^X!}D%)6+rb+D#|lN7dpC zw!HdR=sf*A#*Td&lZT&0A!JYp3rBI09aG!uh~68Iqode7igmeOJBE(hzs>sMEQ;j+ ziu#PTRS}l^s4f|k$-&q%S*R|9e7VJ@dSq&H~)M*slFk3NXTV$Mf{I>slk?Zz-XxJaclIC%CP#xLJ? z9#f_zq?UH{e;LhclEi|9=S>-~k+^)b@pmDeYO^RwL3%+4Ojnv8UNt)-l|88>n+|3j z#wIfdKr9$pTXZ1IyLEkDSY9t??wh%^Z45!T2hfC*^>Yu|J;$z~Qi8TgMYSZLii;W2CpIV4WXCnrm(f{xvnh@qKK)aWg*$DKOg; zvp~9^q;N9dw^W_A`h54PnBknunZjMObaR6S#JZO(-wZpB9{G4{TMy>*Mi{-e0mldS zUb+nAg8FW5>&1LiqqXnyjcgwrM(yHqXco^wzB^a-TJj_+L+g-1G=~yvF(JoB!qY&k zHBHZ=d3r|885%u+z+5VH-Ai+&nYBuDSqHYaqPd*}^--AVfXw8SWi03szeyK#%rZ$3 zavN)YX&MBgLC|b|jRrxR{pRN-w>tGznkf=tKgh5_yu2XSOMQ@@PX zZ*rfw^6^01H09DgCU?_PCr;Xs_N}vzna*mK1fJrkI=iSWtEJ-gJ-d*p3Qm5R=;*+F zQ)6T_H-hFH8!^+`g08XKMaxdj&0_4_0Q!cDJ8UL9+R@OvfUaA`>oqAlzv5=L-5^>& za1N=tDJ<+hg84lUmfimQk$gYMu#x|U>S~~;CvaL@%Y(OL@|xoRb2;f!Vv3qU*zj*| zPt#@T=x3=v+le(Dx$b!VQM(iX9mS}e--fP{fh!Kz(zS#URIOJyZDXb2m1uAv>#jk~ zX0BgTue`c*cVr{6q(|O(3vCmV@Zn&nZ#ypCSKbkF{zjh{{sAY?b@B4EPviLaUPJA| zGJMcBdzwG2le62&&Fk@A{v;!bm02EXG!b<>l}irF$?_xRDfgz>-P(~RWu&<=S!QXH zn=Ask$Lo)Sw{C9RiVKIL!6l~AcBsD(!}-9JV)J=;`!?L%wiQ5dRN_-FzKk3w$VzUJ z^}#{bLtgNoYlrnWf{py?HJQT zBG0RWwsLTh03b7Ldtwd~4)x(iT4mR>U2lxKEZC|kbFAyU>QQMxtBUNJULIr9RXRG| zbXV(tWG|ISRT7Usxj^(-%G#p=+vf8^T+`1+HWeU#rP*!Ky02@ec>Yk43l-XYdi!l3 zn$IS0~|c)V8@R2)g|>QKuUUvn@z8S*2Jis z_7&;RGJVZrV?Ew|;80nc^@sYlhr!zwy0f$}G=Wtwi<+)xRHc%bo1O#47JzNdfCDtw zH(({5#_HHCkk4#AF*A+RS1;kme(uLHGe3uyzWxFZ@7Rsuu~FRim$9e6AA7rcfi9i{ z-+AM8EdJVG;ql-6NsONx#FZCM20#2iZvbQSfa?I;n(^}Q{TJ@s^fKW2sM^!TK{emF z7X0mMhx4ZU7CP@WM`0(`?o#;rz(l39)1{|t%b9_$I)7`E!4UT z))nj0caLn`Q_4ud`M_QG7yV%ep9w@Z4uNKLgwZ{ zj{^Imd7tr^OKg8f?eg&h)KaWgPyiTxQt5vkV=x^~DIEs5^JtmHh^DW0?Zr`X&|Hd(y z(!v?V(WWoi{4V)6pY9r9YqqD$jW{{gx4~UIaBEv{{4keE7f-#1GZ!zSYIG58H&@Z{ z+n>V^KKay|>!Xp8Ub%+(1!R*+EZ5Z{n@pBm*Ork{?6`Veco(7xD!IL=tz27SG;$02 z%75*%$*!4{OH$6A_N6EdU2iv$N=!m=xow z$Cqfjtrat^Es^Koe(^8#EalLAV`J!`t59)TXl%gs-8U9n>A~$tup9&fNY%+61Pw_3O=IJPqpgF=d5!Uy`rxp7Q!Z&} zYxY;Fi?-}$wt#K@Pw)TZ&(ehC7-gd76`Sz4{Z>d_-zeI6M~J4;Q6F`64va(@75Wg6 z=K%u)L58ulQaLkzEvusxKy8+Z-ea$$9EY_DlI1-%C}e)tAlfDsxGqP0mmCe?Y`Rif z#mW9c|0v|h7PKvOYspo^j2A9&V@E#*cJDwYm9mcQ-J1gji9F4IvT9RSL0_a-BW+#0&wwdOl&)V%>GA^ZEOvt{D*~Z=1;XkTtx3 zbkH^jmvFlQnHXNLelM(Rv9TU+K6(tc87{AwSlld|Nu~;B7C8OjQMg{P9W$3qtoi7; z3YAWt>muO<^Nlt*km1yaJgc`c+drF$mzT=d<`9PNST_jTJ&4El0JiEM$w=E0W|pAqIXowiJ-!&mlNzx^PeHoHExBbx20PJY%iFSE@b z4##KB$yMVhQ(I`QiDVMgieqFeGu4yK(KabPg4}OCB4$vvZM$C78E&>AKGdDa- z4OHXZjl`gZ^qlzLv^3f{zGJ6%-}RBrI_SGQr@B|@E|KpC|2CT(09A97=>6`0fmgE+ zL!bOI(#>rp17usV!Wg)8d>qBF`X1Z8l6Oh&VdH6vCPU?6l23V7wW? zlnr!E-V-Hl*|1ajWA;JC#>8_jUi5MGD$vst1aPmF*xMo3A(IUkYrQ!RJDb{r2j6k= z`tiq*uC7{he=B6C)pR=4DN~7Lm@(h;Ja2S*82|tv07*naRHU;RRkkXbLeBG$^Kw8s z7bH}wt3t|6V0C&SC{$ksBpkf)Fa9&GOpjsTuYCsFxAo#XU-<^SKYA7J?|%kZ&f*6@ z{t=wNcnJf4@J;wHUJdTe`DpBJ#o`Zt5?_DyCHVi>i+JB$kou0!te*3F% z{>js-Up1`_IDPdpoF}%S?uj1-0QeWi;QyN!ftn=T|MRmz4cia>ublx_vgrHuPvN;o zil4aE|4Uy2e(6hPkFAYNv=9XB+AOm29=jyoC|_~32I*%jxAwwVx)^DcB6}3@1hZ_Z zl*{FiSxLjqdZ=m+0`*tZX;h_Ba4fQQW?>$G`TVzmg*1NRM?a6oh6ZG^S-6f9IaR`Q zUA+FpV|e1F@1t&hsYp-aq?u{|mZwlgk*#^%-cs;f0czwEmx=rGY0GZ-)+kt;QSA7oNt`~aUgI2Z0q%acnjb6lAEwp5jPfqVZZtIqMn=P)1ZMlj3 zYArRcNxmURjfX3Gr^f7SMnQdW{#`<>U5 z?pC`MdjC)+bB9i`@;xNyrm_9M{vmEZ`WZ|d{WvmB?I^_G_4ji6p?$)pEjsQu$s1%@ z6EB-_U%C%=ENs>p!aFGs&KcZ^0oNnf)3Zft&bJmgYINa^4w*3Unr&Wz_T zqx#wacKq6>@ytJuKfSCJO5}2Ib6)tgfCG5IvG2bL7amSObOci!?Z_n($Q3x*Dw)l~ z^*p#aPk0@JBpg9hEqfxpuq{Aa{e9z_mS-lJNH0pIj{CjO-)-9IMv=(0Z5~0RKbc*E z@tRCPZ5o~Q?r5#ll#@Y>6hty$1v@G9{c^xeh)+)`cVW;IQ4k70aomC83IjhsRV6$$b5EF=#%x){^jjt%E{|T~V4 z13!Ewsg#B92$E{cT?B4mx*&UM*+JN^H;V-pZQ)5n00-{xER+J1>5$mL=tG*wz`;D z!35j#o=kNTlbzl06AmsN*thPW%-KsfF?MAb&Y>+xC6n0EyZ%j$y=z8(LVzi|fvqzpqa!a|9LF;$^+)Fe%8f+Zu=m1t%9aL2T zU3nNrW_qciJL>tP<6y2AsI}m!wGo#|%w~Lw)3ex=LK#+Bqe_T1M7=d}GUvIaX9c{J zgSQ`jG<-Z;yY{CKe%pC%09$U2;&yizuI}9hFOk4X?dG3DS#jRq9XkEsQ5-yT4h=I4 zpbeICTeC?~yeo+@bm=;3bVe4spXT#gIGNo*ZPx>&Tn_%v>tB{5XDlE2o(nPZ^*y_A zV@KbnZ%$gNsljWHAIBqayahKGICB$uJ4b+%gQrb|+)X1IX&ofzE4g?9%GJf$yJSGW zL{RbBsZC9STc?qenun)03EM3de2tyNg!F@61a-)k$#xp(ES&E}>O$ItO>>Q8xh&~g z`eNJmF7YFOrz4T21DvqDqxt~xnbu}h9@xiRkH6MNO*giQht20JwC?Tg7b2Ub+HOnJ z^_aY&Fh9EUluoa2BWs1;e{|}UkLl^P-(Lw)04j23T+&DzK^f{{kO5ax(Wbz^5{c2uyZE>;MVv!zV-bRs{E&) zeirAiU&FQGA^6`o4_ukRmf!t6p51;Q{`|l{0sy%G`qMyvE4-l_@V|2fmshg5^2m00 zfA%)qfBP9A;llfkzr(ji=HUI^1z>kO+&}&z0Kh*#hWX$9d;Hn%UjY8Y=kX)o`QOpn zm_La(;Q|h@_oto%5{5nS2R{{L)Rw`wpYnlU{kh2mzp zQFq7jH(f_uxsBnCrEposF2yXH@|w-29&fX!u`5L&zio0X5%N8gcgo;3 z^LN&T996$(v@Oz!;_$D&H;TngEL{jko4nVC!%YmWZJ*qR#LV_Gd|f67 zv!y=doQ zef378(pg%Q3rF>Geezqp)~GG$?>7u@%KY_Ek~87RWosJD;vLfZHTq&<$iqEz;=0Z* zW(ID^2c(|R{ykD0gED5$S^E@`OP>$7_5s(yOnXc0JyElR{9Us<2f%!DW6|U3#ydMP z9!=p^q4x=8lSxdsx1nWnI&?E~emg)avgVwz0WrEy0uWQ|%5Q5?cFR#RqGffDZFLd* z)CO!8&Nid83@>H}wFe{|Om?*6?2*F-cL{9-4escN?>N|TZ2;AaE6{s{Wmq*iohfe> zLp^{%YVhprm}F2(0mVF0(Ve?-Y&>e#*XBxX%1;<-i#7o9TaqfBAL#*QlZ4=yG5|eL z4Jg07K5m(Nt%0h}q!l&FLrDkOe`$hn#awfZ(e~BT1$`v=&%oTz*O&`eEw4$tN~)!t zcEd=C!($kgYJ3c|`EJd2HxA5}r_|VhyRDuI;I7bS(CR91_Uyedv*L}v`g`Hu?d9yw z<+$I?`!#>n_h`^-)@1|xcCZ`;(I$suGj3Gg$8+s~3+9C0AEz7WU~MvjQqbCReGQiD zYT*D_Y^=wHg9mKGUKUNy&0+ES7zY3PbzHkTfR3hTQCCy5Awk>al5{`NXa?r;sO*;a z@F#P|6_x>QZ+;6+=U>O%=YAQBTl%c^N85XUf#tQ(!~`%g;iI7eNG2V$waL>@c)iH6 zh?DT+OUfsJJx3>0RrKT2h&6V9)A9R{;YD6{}U^l5_$H@vC*0oDh!W+EqO3_C* zLuZxfO11;=sw;%+7-ee2rt=W%^L<=+Sgx(bO3mhPc<@{o(`~Id_3(o@eC8~YE7^Q6 zJrF*m{L+LG{qUK!Em3Y|CmczLjJLpqIYU6`j_{h@V#2eDHvkj%lCD!*c$^EuWLg_R zSTDl5$SM$|Xke_*o0}alGIl^xfyW^S6CJ|%CRc{U?D1RL^z&$aGHQ#7B3Sb&Wq;$= z3$-L?I?Z)m-dCmMQ}G-2)i1oJ`CdP)nR-NXkNe|``WVUIyZT8y&aO~}0N)4RdB?}t z*xCd2`^<9D zb~J9b{bs|%ns=MuHI9|nSPGHNRBvNp{atc+Z9U{0SVAB2XzK4dng>ZDFV>lp_ ze@b1$ZXscc&LBxzYRTF^yp&D{$rP5Be56vq(WB+bE_031XQ^*Q?=kIBa@~2VPMRUv znj~I*;&EiE?yZy7HjBRTiGPkqe&vbD*RFycxE_|JAadMUK8e+QhO`4p}m53;(uu8Yq-_fgcvVD8q&Cj7*YegXK% z51@Wq2LRysk)ucyNgyJ%2-|OQmVX(rZKmYXpJl>^s1!Bdw475~lW{@mt0*Mf1#P;f zoX$GcA!A@Eow+r6ug02;W$AtMXh`ddxs}^dcgpJ=%5JU^gniQ3*M^z(xRNb45ym%> zokpIJ=to+QBTi|cy&rT>aEdhY|Idjrq@Z>hOSZz;d_i2NwAJV_b0A0E)>jj+>wDM2 zKT5rCGwgU3`f$>EvTT=1jW^!IuCM(cSlGTBH$L?XNH=vL*f3Un78k?THe7AT)X{t8 zHLYjsw&^!68>cZuEvPz*N87n|oqnV}ZQUf9XNwGqT6N8ss%Y{rjyW6e>B7bP_QQ9b z4LgN(c3~dhJn=FB;JIUuqQ0gU08m|31vj}qtp4E1Q)rrh(a)vJl2W8> z@%!%-ZG;Utsh1AB0g5%uuR=SXWso+jBEI@f|1O=@Q1@x~0;xs3n8`TiC0#7l)vG5V zl69mqS=21AAeTsBrnLztA6s9l`U-uxXt}NyXC69?XPtCfzqxR!mJ$l^fF71Yi zx^|)_<~Rvd+B)Smt@~WKZ0Tg)vzb76WBF5sKB$z-0SgOjzdwG3Yz(cfemV0?0oH}f zXp<_Jx7TNPM(e(r4m8fE!S$MeTysxp=rl8bm`6C9!Dy_}YYFCt_jC3N7e3N;DfmeT zH+J-4XoJp)pIcZ!CYQzOS5D&UzxyVtQ&rgaFMkY=A30jm{mE<=^^1#GtgqjY{#31| zQM0^aXid=^A6i>rIWOOF)I2X`RZudyu!!#Gzk>OF4`Xrr{tbDC4;n2j0B^tTzQe9 z!L>cRO4>BM)KHJ5hB~CHsxZ;nv92+kZ*0VTW8=E&sLL7ucBsgMfG2zEr}cRcS8ni%WTi|y9*OLI-wrH8Mt(YFjFf5 zkPq61xTEwuroQnnYFK7&Pa)cTs599jDfgJnPiE>$YGlR8>F1JKo3@f@1HH66II10K z2{50IWs0fWnd2Op3&xn3c3J+;edGhM>Etd7+vfwdB{Gg;Uzy2G&H!3%B!!D_IF91p zjm4&$iK8p@;iB>JI}@6XT*G!f&TVJ@ zE@d&5jkXnSPh(f8drb?VO(tues=1v+Xr@G=wxvD~#0PEL__Jx{b&8kA%-YA`-nWmY)4 zCqG;ti;eYo_sAhE*R7#Ln?P5GZeVs{0T11G5CD+#a(MpL@8ij%520}lwxZ#&QJgw| zKKPQ(!uvNbV)9rgvb~Ksb>TdQM@InwE9o@m7Z-PLE65*dGWj9{ZoJRB5oe+ z#rbD~gkqg-ZFuDVLwN3~CxHL757^m;b62mTv#kx!9eXsqZ+dnXC(ob5#~*tf_|rW= z)&sV;;LOQ07#tr(UsDr~{Mb?8xo3b~ZNW|d=>edp38+hE$_N68XFsc#)j}(ZL!m##b?qO2=(}e9P^DkO&!G4GuZa7 zvyd`Mi|Z3(Nts}aP$BuSz3?+_vnDi0s4~FxjPcBkw@|$zYpP6$##RAFgHk8dc30{@ z*R7w)KJOWUOAM?>o%JuBU{2a*WhPg7O+KX@_Z$6vxVcp)gP~`;|IB-+TUY|6*&qv9 z0y=Qp2XAI4+e5I0p5B88-dHY2R3mB{73u~5&fnz~iNwp*p~}bGW!b!|yfK)o_X&jUXYf2?>I0 z5|#wN#VN`R5(>G?)~CEm&|@QJk-YY8PNU}by`-+B3a7*8)C^_TCV_MO|<_tPK6 zVHK6poyF2j73{iFNlUna!gA`T%xbxt<5)31cLo-UJ|JseY5@+t=j7@jbXJ z%V>N3Bqoo44iiuO5SF|8EoCbN04poNtFQX#aAVuzfadX>NEX6pI61g0bxh&uV+inb_YGoDU-JO_kZo*tkQ^}`1E!Nj> z*k*(ZZ7wY=E#cz8^}wnA^>aWjhy6eI3EXy9Fg-UH6uLeIyfp;0)&Ue&({l}@E_q>a!VZ0(fF4QcJ0_nQBp z_(4?e#{Uas;zU}Zz95ACzvrMd)aOkxw&?L|bPf5_n*6*|HOlMbaItAgAu`V((S43$ zW%}$|e&su5mKs~0Zr$hN6tyGJd-haq00m~VLxJ+OQRurHzW?BxAI>fZz@hE!yRfSyzQBbgxor>ldh+ok07$FQVnjd&o3)Vf>+Iu+Vq^y6QH6w_#R!U9Tvc z(>SEEeLA)IU0W&URW9@W<+hjxW*loni@1DWolQzlLQU)nC`TN*Lm)rpnb z8r<62YkvV{(9PSoG5YFxOucj-gUi#X>1e_OhY#W4-hGjbwS}l}@CIs^meD;rhUNNN zOq&6jWsu|h*mdn1lIg6~l1n46t<6zQgnx%BFItMUEhUQGLQ|Ok$H}41CI``gs?DTa z4j2q!fsb9goJh>ArqcM4X~B^9v#-TLbj=0pB%4gEE8F|!8-utpGJ@{*b{yKXw_w?u zx5qFsJ%c0r_amLj;FVKv!}EPSa{v9fF*1tVQ4b9m^!`+%GW|9`B5bGQd> zJsn6b)}dKog4u-yy!GC@7@eHJQx86b>Z&UEUv2_gYvF7OHcr>p)F7EiU`tmg&=uGN zyrhGs`UVxC+S1sF`r0~d>F5ADc;j}WsTO+{7tmN=kIvRMpkF*syM2RqRVszfb?}D| zI_kr6VRqF&*q1eGX5TaRT~`-*e~4~!zP%_X~bt~LLtPmIe2<0S7e z5h;}`m1?T1QBx%FdM)I79_~N;9;#PX4Vgy7vP_bU7LYiPgVv%Mo)c>3*mRmWpKO5B zsRi-?(|sB#+$zCi zX9f~_kocP4Lk{VhYMeiKU!+I#O^vZOob&e|z`hHY(KI_3-a`S~{MT0_O1(DUgQ+2z z>zi~3nZdl!8gWV}!z5R4#RpxXdxv}y zS3idPw_~Y3ej`>nbaCK1hQIzM=1vb_{Lw)7t*)&>S7+yj1#ANdGHhr4yd36Dd=x-U zvXx{3$t@tNRYdK{P*ThsS#t}yxn&IbR=8fMw&cuU=@XU5aa4-T*$jPkJ$B>r+9}^& zkfgzu%A8i11EPTIsBw(1`EW$+J_Bp1)KJ#2B(h2YJ$?8nMtXUNqk1sk$H$(30f}@r zY=;)=&EBmzd*pCQ4?EJ^6Wd0G?lJQ7|C2$~zVV%|NuuB7b=x%nx5mcs-(NWq7Ws!i z{MnKLn-ole!^vEFcVfwxM(bs13~-p0X-A(F$`U}CpiyVtlsi~wo15|algHQD)3p=j z(BjNcM0PU25yS+MX#~s(5x&K9{7;KjvJsE1LT4M&Umj zFwBhLq{L9*q94BD;E-%L{6*GD?>T5IIOxiR(x$4c0XOx^{A3$t^PY`VYVMRWQ=tzB zwX^_FJmKKQ7dL-amAeYeRTh;2er#D&PmWUbcg^wrNZH~bTT2a_vDPNPCFj+3YnhFF zIT;3p@LtKAZQF+!0?K-|(V2r*ov^J9o)^B4zk2-FF?VeQ?yoIu5E*DcqVEM@>}~c5V#}zL#$dV*8dY7@wNP!dusXx+);y z0vB#$c3}Z$E?)#PIrx8i63BYUEUw~~yNrpM>7eopx8c8Z4d|$cbB=8#{#Vby+0hE8 z>H&1s><4blVC?^W1^%gjCj)qORMhA^Y~0F08C2wc!R)w10LR0H8Odl0%l>Cxz)!K(A-;LQn8S z!jrafXEYc6tmjU24$0ay_a?3`ks5ubepApfmC~r1q_uWSODSQ)Z+y4LnkK?Er3a6- zblTe;8Mc6JQ#UL;kEL}$*TkDqz6bySAOJ~3K~$mGfIL7OplwW?3(OH$*v=B%AuSNm zqnx#dEXPw@tF>%4(S7tDsPd(ft=`R}>1iJ`GY(2PMArB)VV! zYqY=jGL}2GWBllG%ngX|z*(|mW-^A`qSK;NH&@mm&n-=vV zK)qdww3uwtm&v9dm=@wf6xCDLgK^8%XYKa;&8NXZz;S#uHU=`OxoFI^Y0E11CIb1t zlwHNi$;)uyj;x*A9K>_^wL6^99X=Me;e6Yx#zJ8>VNnqRd*tbH|+Zj!W zP*YWnzMiPBytB2n5`ewI)H*edjtuNwe~9{WSg+kk+g}`U zYsI`u(nluK6KM@0YW?1LTkTrO@qKiSj=|0N$Reo_n6?Hw#<;LFw{;IS+hSQ`gWuz-3>=ZZobQ5p}7$wTYHeLN@BEk3(BF%&JJAlJnXu14b9Ut zknhYBbKlK>BZ~@qw`OFm?D@EcO=O1XxPFnsc$-i{oxm;!{akCaN_^>>ZE4O_T*lK8e_CCYFx!SX0LeX4^E9b{lt;l6rZWm5~~!)nU^prcL--;Yq+l5?Rm=Kw4z<`L!pGW2wFl znN%valfL8Nd(S-s_&y#w`8Haorg3@yKHTW*gO?~hJ3xirKlH|L{wXew4#W9E-pM>L zh1x$kg)hAM`}m9Jzm0Sz0|4;<L9QerP-O&Nj5k)>I_?Z-l94NTk$^U8- zVF77FjT~W9-O(zI2Pr`9M6-~~1mI7K_FR5nZvdL5vPS!&$<572Ld*Nj_B=5{(NPUX z(hS%RT5}_coXnstozwBBKj>C$L}g`Pf=_ZsTJYp9XxBIgX$S8U2*R<+fWf9FPkrZE z;)Jd1zQ|b-1=rFXvOa@7&xGQ~Oy3DQf8Iwf=U~^aJJw`{?jp_10B^jp`RaHfZfGxW z^7+EQ$JNPv$KIYPCw1NN^_XRBdO4N10d4tQQihv4d^Fp3d?syqug>tu+&vL)*7OYC z9rRlUufFp1lUS*#DTob9rTL{r{Pj1#4e!^!j`Xh_hudCJ`0sxM=xGcxWB>i-ppum= z{Ieqf0Ox@ooO$t00DwO@4cuM;I_u#a+m5PK3O%D@?L2)L&W{}dcD7+(-wrtQ!?@7U z2K>}+I6rw5sYDV_KXR;Oo>6K=$~=VKWr4U~mO--U0j zOFA3rj3e$91p-s;0qSx?S111}b2*#6rh`f z6W--t0B=Wuw1?kr_8z}d5#H|tUhGw6EbZ_#<` z+n7G^1V*0uajdq=z>?D1E;IwKJ zuc@xi+v9Mvx$x;bM{dLMe5Cp^$W*0D4&F{>GT1UQii7W-%a24-Ni`j~D8tYsdNSWO zlW+YTwU2Mss*|&Bv&pmzZ#E4K1g&k|3hdeAps}&|JwAYi^gM3P4+3DD`<~`L)F-Rq z02o`I!tJFAIPkEXUBNq3gE-Q<9cN}n@@FguvtxTr4ffX8!GVu-CWDIu*Kyyj-MD^p z7-uhE3WK)y@7Rg9<`%3>%;DNsPaySA61Z>A9$Xt9LRB(_o{moRbaY~NejaBpUqWMj zJ&x=@fJkyE0PW4qXlZQ1@YpDli3ASq*$dzIQCC}o?)G*7L6Gyr%rp+~-G`d$Y8>9b zA2<-Kv()u^%*deay#SuJk5zAHmo=EW5Y^Sx;PBpkW!+PuyGy+{Z=q&sMWnQ|dAl?o z&~`zY?a?$@{1iA+D2{jsmvj$OdKH5D99ZrhbD? z*dC9A#9EB_=x&LjZHSE#pgCf)1ba8MuOq5Cn0Q#)Js4Bd_aLE0kZNVVrE%RG>~42= z!Sy_}OwXWUegW;{li{2PD1Lymobv|pU^_I88$XL2Gk$KHRYk9$^6_+qD)eEd`kNQg za{g5~UJf(+AHzc5L8HXxpbU+lqgHlZ#>Cb(EbXgnRNnLr+phC9jicEo94Gl;lp(|? zk)BQF<%Fy=<(`LJGJ(Oqez@>4uyY5NHz@JRl^cUNd-)QkW@pfSd_N9<@j2`&VRK|D z)Hpwn_VEc+udJf~+92qpi(Ht_iAID^WCobq>+!YQWON8U-=(#Ns8ynn)y1@|NHS-Q zyq75+yK8xVcVy0;unCviM$%^NfOr+=b*kJptlB^&ozM^g+kvslaecgY{5WP?noDv> zQM!p^PR z@X&pMP+MAA!8cEQ4*=l*-goibzy30=RxRP;xl367?nU5*3qhsnES4vh@wKDBirM)& zc$77JVi8yj056*x(Cju??ZP-2cA3{ z98KmpKvhd=M}oWX!d)(s?2Jak&H!Y`nYYcF?j(bXGr05LxZV(_h?+y?cXmRX8905{ z-H^bnwUU=`kxiu(52HNFrc2i`t|9*m2lOI*$L#o|qk-A*;HY<8nmAyyEWuko!kNG{ zJEf_I^2ShEDwq1Ok;eEu>%S3?dyP*3#}eT)j_)v!#uP@${KSg zp9!v`twf#DCh>ucCh+%EEk0=HIX#{13Dv~_TGp@I^CO?+Y>D`;qG=XEZ^xE?bJTnt#{aRbP*m)%v^S!ohX( zNN1Y^TLNj*z{&T}$p>aR39!vQyi~?ZCh*$v$1&g7Saz_gNjGob#%pIzBR9T)#oziH zxWDum(AR?J9zTx$p58DsQK{tSJS4KYpvS(ChWQ0NdEynke*7_H^I4M0p+q(d_BJIFP*!gn?{k9i@vve`0c^W_@rU4&}& z=;?JIUE@*176(CUmmIxiKjC1yqZMyI!pA39Xzi5FWH2*7udcN=H6fKuVt#QEuIs{e zUCb{oB9%;{wW$d{d`wQyz#EtXx*E{b*@~K~DlCmmVPR$-=x)T^;sU<=>Z`!@DSYxv zpTXHhcrF>!9ntKA^oG&PR3wpLhTO;7=^U|Fpd*oRB0Bzlh{?9(P?s1O8!BSF0DSFKo^x_!5QO#y1 ztzxK(H1cw&5C)cgiNBLEhel#?sHZgYeIJuE!5nSb-Gi#8IxH+L0f0L4T+(Z2-@(HN z??>O3(odcvxt~L+GL!imXAz~%TY9sWX|SjEY!()2G!EW9WdjSov3v~f@WOWNTdQp* zVQr{p^k>>SxJD@*sBheBo6S^THMKM8w$Q&x*`ZgIwyQ8k=4`Ig>`#AnUQ<01^z^3d zg?Nl*!t3+VeHY*VC1PUBHdCvAg~w?);eySugH#p>6(dFOe}4? z-?ScbJEjh`cb0f|kIgI(H!cn}bOa|SfW4Qm!dwHj{4r7<+43RtsOsk0L05-i1(rzouN2yev zY?iy%__^%Qo#@-mn}Fx}IB>v0y~TZYd+`<;sv6Ods>ghK4kPnJm|UJj&d*|Keh7Vy z+mLcy>}c#kL$U_Li??xc`Z~7Mwj%9i;5rVvYnt%A+n2DIUB$NACbXog(3o)HBWUpd zXYaj(^GLEg!CzH<4&DOR3<$GCKp8>!g_Vo8U z(EKVZGb<}IE8qLQ_wuFVIGCK7f#W!snV&~}O%3X^;lG>f>rq=(g(Ka)uvgDuYGxL; z<6v`h3pO{mWSy(E#m+_=!Yt+bK4 zM1W=6XdWAf3-6S@*m6oaWlvhJoPdN*H?#z$esL|ioQ`Wtu2}f`urce1uw2S3{XHt* zQ}i$M1h;&OcXnXH^55UHi`LA}qwCgf*p`Kf<|e#f6icPh_Fx!2H~Ju=W2y*@Y5~>p z5pSgG2Y4EfFls4Jnrdo5IvVk34(&7XOtBG5_9WMEim+31TePr+%2TMs8B2T?x}Ydc zSTuuH2(Gh{7+OVmI&F|7z1CHr|1f8nD$$3J%17^@ z<@DF!nh{JMcpi(L`|=mkP%eDUNr#Jrps#F~B(o3xyOSb$`fUH^3Y*?=kzJ0 z|I_O*KD!6T)>`c8>P9M^M&DQ8g8Pc+U~StrCgx}G&3^}&i73W?`&*cpOd^?1q4jge z5SfbLmEZjij2}LLjBR5&tFd;j58{ner?J#oh2(RcF!nV8=ZAemw^NhA%;&u0zYPHH z|8o|`$97`(r%$4@Z8L9p)B<)ZO3(Ivz|0EJTnV&RBN30GL8DyBPcHetO57N$yGP-I zUT9uFam8J+%adLKpFfSJ2c1+@LpzFYSK%}?Hj2x)`cP9@g_8#l6=ooi1w;Z zp|4*L0XjEybA-1so89vi~2Ee-(plo($LOasmJ^@y!uqnK=UmNPmo%IB7F_{=$6 zI=COJ1w<|t)O-B~YNuu)jzqQn-P5`_Y&s6B=r!38V>(~b2wd-SmlZ~voC8QVrW zlSVui$I9v|DoBKc)npQuWqC(GXUTCKEU&Ht04mDLu#!x|ae|Wj*yuRE`>j_2!vN~b z0RwpP96t0|Lb3% z?a4jp8@LD4FmbR~ue2_YCyL&%q@!Fd6YnEO%jPE5(_6}Uw*}P5`3)4}6-%H$(Py1TxEkynxI+nOr&cAS3 zMMd}}D$%1wi;KW}@2zcy=9<}t>maf?i}r8)AzI)58{GTU|AMi{KZjIxqmnaNM?M^! z`-`HuQ=gvud1`sO%6nu6>I!1!pbXCWs*0&~*f-oXDc4*YMO($!>gHsI=u99LkNNeS zJN6io>pbbxwr#8|tzdO>9^bif9?q|R9p*oO0?+>Dm(bd@c4sxyaS%@?0oRN82t>%+ zII!Rui!0|Aaq#Q~ym#U#RE`Fc(l{}R-C2k2OcwKIviO%C%Ph)>UiH>_84-+11^h3l z@sM@#`#RFi{a1SLi|&z#$MM`TZ?oyKy?Te4%JwFFD!L}V%{xz{ybXIP$%l&%G? z;!l+8yp;aE=SogYEsz2Q84w|?y#B11U&QV!*KqOB0nF9bY>0k2A5|_cV%OE{0jGTK zu&weYI<`7}J>76C_3SL#sOe(9whAU(^zG@vVr6B{b{;%`0r8b2%9oa5C1unkc|w() zMST>XS+L0na62WkBcx(CnTO6VQCjL!IZ6DilPJ}^{JW6pv=4)KRsDndCHVm-N#8G3 zR(KoiHm!YwosOm(>Tz?|PVBmT9TjtnkYBJkuUqu3IO*E)`&-N)o7Je-T&Xx(B_TgZ z{QkkQ2b8Epf@~X@nOR%eT>LFD^#Dz$zK;0R2*yr)1`D10HslM@S^7NU7&pAUzATpz zM4GxD=E|qzM{?cdXYcX+93KZQn}%|ax+m*Sq_TW_vv)sP7DuWqj@kNJ-0WT3DN-t} zrjnSQU%<-ZGQRsi{vOT8dQg6092L)XVPEgApxv8THmE32z`_w0E%fAlWQA3Kc0#}8w0 zbOaNB^BzzUgK?}Ki_6OxxqKUu@7;y{zojwwzyA%K?e#EL=ivVF1tj+m!d^;Z@=x9b zY!}9-b^&v%aR1*SJowGOh4GU|aqtUIq1N`CMC$iR$%slq%T4Ga(C&Nt7XVaCP&U-)d^{7Wk<7&>(wtG5<`KR5)}b@A4P z^EkX~7s?Zb9g|V0GJ?Wz$!d87Xu%fgbx?IoL8FAIZgvS*nW$%i7Ec$^!vJZR280VV zk3=VSNb3y8^vM)%OIRJ`3%Z(gy+m_!QH_g@@~w4|*?AwUJMyI3OWdQvoeI{e(#Z|9 zjlxy0r>Xb|QcjxirRxCg9}h%Rb%slx8|*9fN>#wAJsy^qmMH=55{r zAi6d??0TxH0S`8}!2pnnMliKb<5}Omdl;S=2LLQCFQcZi636!K$Ch;h?6#o?Xc-xU zII_xx=d@(H2I?kfu6fqKD`px<+i-vJWqjeS z-$LE4t$6jl(@1AB*!y!I$L^o|IDfG(ect=`N2OynUizf`{p(6c(0e~1bo|u2C|g)T z8d11er5+&UY>@R##Tn}Ql^YA|?yG4Vv1U8r(r}5=Y@*s_ah7 zg+&UJs161&)mV=U#|jT9l8ap1fonS$8XLto|NLu6{MS?X@xea&&}iH zTW`aLi8Nvi-OKYOJq>AMX$8-G=heViQNBT)73IkoVdp0pL*`BT#Hqm8ch@Z z=V|6_(q9fl#Aku-MBgTsS8??8dwA#M<5;S!c&LusR>nqrHJKe>Zk<&Bgsy~+HdZ^N@Scs*i5MmU#_=wN*+dzHG=%lD@}2$EjBbxqRy zA!j@+T3z*mNUh6-4y0Fr#X#dCm24~U4;EO+vrER?-vp@fH!)?Na z*2D3!{LO8_VfhQo$JauN&4bbg&m+@#v~8+`lxWh?=Hu?d6fN3F$D_E{y$$y})*tm6 z09L0KkeXe>(A*^6x_ceQ>?*4M^b$Vyvp0PH(|8Rd&ha9|=$ zoVA7SS@f7gHY(Fz6OPmTEJH49>13#&HiV8?F#LzG>^qDTs+t-;gVY(qpC7zWXRf4h z{GRK&xG!C2-zknBhW*;(9r?<(-_03x41fX8<2#)X?VkV>Zm zd1o&VVBjln0o8FtKEEFk%kmBFcmM1)RPWr3^tM`zzjFg)i!K&_WEqBGpuVma?!Ij> z8tQTL-d#i@5j1RX^BknJ$BebdYvEd(VAR*4;S*28c(w~Dj{>naps4~#WzhYz^)Oni zfTLT1NA-IPCHWMrP-rKa`GBQ(ZldA3uV! zP11RzuDTkQsgEuuSd(zZ(zjFO<;*7NSgdn4R@Kg60!wiAaHWh|n~WYNfTl1>%Lv=j zpzK;qC9q?~PAJ!BU6`z_FH6(7!c8Yhql%uP+`?2u#ONezeqJEdBNUg7_K}A{F zx^_f&+#5h*c?I>8GpLwfBoVO<2ySb`Letm;47jk;HkK;N1M@)el1=wVVK}ZIO-CFB z9qcJpnox~3It0cg4optK?7s#l8pp&lUqq@#Y?jp-usI0NP3tvUzkjmqT6ke$B)=zB zQ6|&El^s|3ooKP8%6%qrHiO6FUP(eJw?|yJvWE1z5c3y z?f&a;;)UP(Sq#)W=)XS*z;o)(TpPv9|Lo6^{x=`RU;N`Me*V<&yoRAYn{e)<9(LZ+ zvI)-~J%%6q z6bGos8LQ6*R1<{*4_})8$a+XjwBEaxF`$Jjxo8`8(iSyPp6LBjH|2Ub*~=^E6y-TO zbjMM@d@u1Xs?JDPgXAx2WE$Id*p|`PWF$7ZkvX^>4DcMb-+bmtq?MCMI_?c%N8c?U z>jEY$IIuy__wwR<*^pnV1vfhm7T}MFjM^<%0@-V{Z$#hfzWZGF!YPQURT&{a#$6jO zFHwmoO-=&m&TTvoicgQC{TqLXn*Ou6{4f4HlC_&cW~&~T=AuIHQyo_@kIYMvi+WGA zk+1X|7mG4M1f)-+*8qsL!X*=lefef1fa70^i6zgI>$0dPii|HEjka#WmHm5j_G2-0 zTPOQ}PcBe-spvH| zf|$_Q>TxeWGf|rPIpR`{$>MoXQlzEQD=X%MgYb1dmn=r_sj|}dn{?moMz?Eb2Ke^3 zUBqHQb-}GN{E^^k+!DasU7`|s4loa!n#aa*@Z5O_8;xo^qVl=!o^Y$B>EdJoiix?y zwr=wZwF8>q+z~#Pl4~WWeBTUTKXd0Vblsr#JaL`N2CSDWs6~=;W@#f6edZ} zh}qcuKn7OY#?!C8j@O@g8p{>sa1A4`^ERDpx$+y1oE4i!N3r+9m8>(CSiEaIN;ku4LW?oEf4>^jNBL3t^P)BQyeks@I z^T&n!dJNFn>q5AN^BSpjG#7E)uFp?ryvcf=>v2`N(0fl4;WK*UNLcV?e^4Edl!R;TxIt(YE=?j1&c$OfvFL4RlR! z4er~$6T_R=_wm|}1Eg)hb#eYb{1qg!4WQA zx4IraR2&}*lR*o6PQIGfN>o1`p%-cc)IksHM*eXI;fP3IDNo@3wszca-!D00 zgKKy1VE6Ve-_Uh`bOecb0!?*wMc22uyo@_T_x)@4n|-))<|68z>BYk6C}!s8002{S zv*fS(Poud%KU@o3Dywrv}iZ}lOa;SSrQlasI=8*Nop*x%CwR3~6`?*IVY zxO)fft*xHJN=*%n#zwU4=mAC-008l56#IAf0=sts@SI-Snwn78yDQkB6W&ft>>~H5 z)A^^A{0BEqA^E6KES196fkD{WUDEuh0)Q$Hb!uks7biX2e$^XA_;H|1od0j3fK-Zg6X^%oF zP4iLiAyRc}cq%~B{pmb{jq0>5-QmO=a-npjtraUI^12xDSTcpS2P5Q&I*%;Ue%fEM zFT8emWvJpp2HBkz%og^-=f z;M(uK0w-g|3kPR!t`pZP3y<=GHf47CoApk{iGI9GF%y&$osH;hf90eq|}w|A6Y z<}t~6^p&7nm71oGvZVOfeMI`M0Je?k<1b-p8<)w~GNU~T@|uk>@;pom|yt;yu2M?jGsX1rfZ@m2$4)^XtQ++)y-n@ZZg9GSjZ9{u& z8{Rl~2C--qpLpsSeCOSFkW8fj084*z3T9&kZhlHRiaKS(`HgSD{KaRy&Ab2(?%aj$ z_IBJGet0pQJ^id#<|{`~+1h~q8<(-8y+fY5bTWg5kADQ;xN{N7R0=OW z`4lS3%7MMdJjd!v?;P%EBm&bgkcfF$`Nfk@qN<{tZO+`ay$hXfn-PgvNR(HwCckj} zaU|k#L}`eX7=Ut;i5yuUErnvylHs~I_V#HcmR6Ywk-P2E?E$8Af2P-J5gD2*w)N7S$I-oVq8~&g=|U(tPhI6& zC{c;lOLcX?{{05do-Lj;g-M}h zWB1VZ+MlChq#sxQ=if!Lb`xN(&5I`&4%Tb=)Uv8}FFyuWQI*aX#qliwvZl~_xXw>- z*NvhT+RsL5xnH4|XqHZq(66^A0IJd@#v%fm8}G!bC!vSIOd%G$H$o z4Pf4V`Sl9@xs#ngCHnA@W!re_wKovSWPGO*iVD>4UYD-J7wRTi({X%zZ?Rvyo2}1L zoVHbLOV>dj)(POcJ}Sv`ZLA(c>({wlZ&J+qrze4Jxw9?pXT2>vDAl_xjlUm9mmcQu zu!aGN2n7!iwmJ_jisv1B`!r0$!Ik}cF}i6}&bQio;W8R0Ct<+F@aE09zDMID0buu) zt7sk__uA*U{%I0)e05_=d79*HV5LlUNA`y3WwE7dv8EF5o+v!Zwo13VyO6OW=(*A7 z^L5vke;n5HfGU&8i08S;fCy~G=bJ#{GEIJYd=3>hH@OT7rSIfhsCIaok0Np^rHIp< zA2#vX68sBlmcr{1f$8!;)5$xAKS=c0V+NXd`@-`46P8ZW(u1OM?S zaQ&zMBbM5BN7f&#`(T>{BK`G`_?UZ=Bbm| zh&Vk>V-whS;gWyKiVSAMLzYNqY--Kt8~aqvgG5DA0^~D{OI>o*<+J29l`Xj($z?F^ zZ9p~C+!mv1apXNZ<3zitrdv-s`*ZFATA!|0<*kw%+Fm1=b8 z=+G`zRp8#X&NVlBU}PAnbQ+r)8&RbgUsW0$8AfAWJ<1aaOwP<;W`R3ySh+)lnC&Oot;vCr`8WAl`k)& zZh8js)ua!=sNym>(}8?nQ4sQo^x_vJQTIlY3bb=Qmx8TatyC%_2dma zy4~HSbsj8VUPjc(plM_R^xzTQoTcU{Pk@pKbep~cNzN5F+p}DCtyg7<9$KHkp;M0) zQ{P%tmL)3Dqe$T#r+6Suzx-UQf@&mIAx#iatGt0iANsGjr-wegyqbrm(e}}Um^jdu z>o5i6G{TrrWC{%6^E}hVSZfOm!^Q2ME-aT*ugKzQC7Hy~z5B?#brrHdpvlhepoL zT^NW>45RY;X;@1OSlIa(mbwpUXSWVahmp!N__e-{weziwCv_|~u1@(qhsnUAmt6o0 z=~cWodI_K1vJaNw-8D#_un~FV+!-t^Edv00w{3@E0CS6rIJmPHi_6P+{p=Y4!06N@ zY}-aUoxzp#n%s;lw%frEhK0>8Bd=xzk!o)S$& zyl$?q_woR+Obd0@*;s7ZfA{z7L?mJ{TwhgRgHLR(0RXf#Gt8>S2t0fV(1tnrJ zhM6f+XhUMOC0Mg>NiL&dMVFUotAQ}GxUtJc3+8SosoZ~gYyu>7^l=>D;1(fgyH0RTiJQFhYIT50ox2iSh=4&p0G zB@~7iEmq)G!KdWe38K&RYdGzBx{WA^g}KI;a$J}E(U~PVIyD~aW{_-)UT+U&3SWp26AUM;^*Me3)q4 zox9jFG=#~?w0ssLg$6ViyXrs6%)-v8E9d}V}$@<_8I&HE6^<*}VQ@G|hXp<`zN9$zf;w?lJ z9|T8A*2nV&xiyvkMJ`VtD`fn05L(%zHmGYnD%s{xtK17K6E63vSeF09^19cM=(Yu?vd zqDP!u7f7e`=PQJwOS5P^|1IqJ%D=<)pZX6NJNgM^%4o9e=hF8VW;SSoWR1=;q^^>ZFQ?!!@^02aq(}06ySpuiCK8;J26>!%1;ifYg zyz<8DnE17?!oK(b#^?88-%r1Yo%?qo7LA75j*6kSp<(pg?1Pov{7iezW)^pvMz^Nx zH|xob(}MGY^&^*$R5_H6t~&Z&87TKC4wvm!XMlc&$#&>ThtFwSMR|ne)8`L=^4j>3 zUW=TIij!J$lK~eIPk@pGn~OMm=8H$hwK1|h2?Gu~%c@|RT#*)5``FYZ(iuCDo`}cM zSX&F*u`x2?IZwZR;XD?Xm+}0u<9@`hsAXYV6MeV;{(V%Gm7_e7K>z(gT)x%k)fJSPah}JAps@+TUR%ne-xC_fKPWA%)39Gq5ZRr!HPVV@TBP@ipy62UV^jt0`V zZQc@E=EVL3dFw4veyW?E!Tt-EvZ`4tz-suS2XGdu0!^8pFC%)PR$XR-U)95-Vt{yX zVWrH1L(KQ9{e@Ef)HFKp+#`%qGKL_0hJR1o=K_dSvsmP?aP@!-&W^c~2-#4RU^>)wTNP)33`udweR?RU zXgggS)PCd927)QMDfbuqr~~H`eK=@o30PcwSf(gR#mscN{)Q>-!mfkQ)PreWF1Y6N zl{XA%b3hh^ST0HDc_@gMZ42@u8dXfUTUxY%M$a}Njn`_FGFZT5b0aPv+?V$l%0g%* zxr+Yl{dniU|2>R9IfJ&p{bw)}UevO~yY`@^pXuK9PLHAH^tWIpS1@>%w{585%+= zt9{(k(gK_x#`RMdfS(6CTHEkod<+2a_<@5+#9|nkoWS77FuL12(7bgkdOA9gh{q9$ zM9|aGk*#NwAECElT0~}2RId)IqE!^6<19LSsYijp;sQ20p zR4gqM-lS8%OMEJ&3pxX&0^d|*h9KAD%6cxBNyI4(#)3a`)u`A|<+&2e6Op`M(uv!1 z-WF@P8Y^3JR{4%}^aL02>U3Et?~YF0tTVarH>A(v*ip_Dt~(GLgjET{!@xpviDc!o z+dbVF+PVd+Wr^^C&q3*E6r-)1;8@-_+Hh6firxF?Chmzk#}IZ^Dg6G4t$~km|@0q2(b+*g>r>$EG3= z{Wl!za>No`OL)4dgRU#;`Y1UnkD6^L&r|h`CQEYyxR>f1EyByZHQ96Wx!t`TOI4Ma zugSgXuuyvU@hy%s9ab?+2RT^h>%F3;?MHa z0MWM+0~;rwYMjlTN& zsTFFY_-2?!jcU5Z7z&F8m%_M~%5!Ak@{bAAwox}di^twOi;D*jAQN4C^!loW1#G)> z7ncs~UvnKBNv$IzC|h2^ov!WqGZ#qJbMxrA+2@ZA{Z=X#mr=I7f|lec$`_XcYqpN0 z{LP;cPbSyZPPIC{%JmX~={Y|GPKW&N|E zVq|VD42FE-{|0qaIs`%Qhqs;H;T9>q{%oyMH^;#8O0~K2(Go2X+k;GhG{m(HX$dtU z@Q0{LIw8kaQZQDi48YswX4jq!JUy9_c2JgH3A9M!U^-^}l!)MOHOi*c5zvtqeFFcj zMHFty`6gPL(BIRIr40x~kc!2yT9)w7tD-$EH#|F}CxgAFYCl}%nxi_2+o^R~YExu6 z{VXetJIYy*FTW}m(spynq!7B)cN3N66|gK5*IqdVymJp_Kldb_C4NH1kU{>XD_U;S z_gx{qQKAx+2q+sLK-0NzV0za{jGg!_(pB|v4RcL=FCPUlvi>Vo(}UMCU1vWQc~mT{ z-t&G-T`tJKf=_U)&ErK&sfIgrtD0r?1V+j!m#QmpZSQU@RIh(iG5{>zpTuiF^ItGN zF%IYID31T;kD=kShf&+!vLOL|w%@*k`l)FomRAv5NhuocpqADpJ;${cR5PLerX%D@ zJ07XXQPn+jZ44iIb;M=6bXZ*CH;&CE>156PoYZCc3nQHjr_UF}32UQZ|LUKYyFGica4|H4`^T}EN1FMczAZE%1YSm6*CA|a-HkLChczN(N8se2`YCnXPOd7W1MRlo) zn5c_*r82gS#pPu`BG&6?&tP_8!GC61JPva?gDNA6XI^>^mSy1|-h3T()zyeaqo}W` zK`N8M`5V_!QC5bQ`Uaf2b|ujEkDfT`M-VGdBv4-?BX&J`=&+x!wz?W+sT7_#cnHnU zzu>12j*MX2mMwVl&|^6}aNFiBIUT3NsIt5qFPwP1=yD}`e<_wqA+fTW1#TkRq6)TE zFv%58VJx?>k5?7R9}R<)_x^S$1W*CDEC=6IDi(MvW21a&8Os&xi@v!QiltK72IRvp5b+M%<>3 z-9qst-3+*5oPs#vfUJUD4yidHS7)ex9vG}2Da+TZC$BY6CC zfs~5HaOU_C9DnCsSQ#5-%gcynGRS~_<u=& ze>*<@)#C>$z)Kryn@8)Dvq2!1FjOV1!VWRQXXSS3>DI zeBg}$03ZNKL_t(_K;<4fKx@ESm_gm!Uq{(sAEqDwBo@04fX)s|lAGoxU0Ib>8DPD% zQ2;mhGl~W6o@8@x?iOZOr?IJ`4RI@u`}4P98Yb!z_1O_LP!p@dow-4vx($=7v*?=} zL}Q``J8L!ru7kUS|GdNdR7BPp2YO1O>B%)u5K6q3+GmA~5qlm7i&@?(hA~BlarxNfeVgSWgl2lGdm43Ot&s>T@ zeqUclxb};ZDp3a|Y#lz5W`173ko(1Nj+I3jaYB!a`td1rnI`UZZO3d~ZO)c%6q$~L z?pyuXeE$KEcKyxjI_K>mUY32T=F&yfHWd!*L=E(Jcl$F$<)tnRlrJx1>%jdiE~dr} zuCR8?%5!AoD~^|Cs|zu?$eE)15_l<{rYWdmmvWm0 z8+W_6W3as)$wXY+nnEcZjp9L;C+xU!i}b3P9UKdraA3oLIv=F|L9a1Vds^3rhTpeT zpHRZUCHlc7bxkZE8%NFUYk*;3_Q3N>bN?&^R`UJy))xueWDS-&xJ`Ksp^5KX60wzRCQhaS;h4Biu|+%A(?O`>6Z z%FpkTl0u^wN!q9%pVq9ydS`0gXsXevbCIr&uo zu9lZ~Bvy8ndSrdVy2*RnfH>h+xE;$n#kopidnrA;*drM+UF~~7p2`%Q4}hE(l!pnF zs|MoW4%^ZZi*7>}V?m#3_@%v?CN?!=psQoUHiZGeTulvbcXwf1{~d^JT6DbW?58tC z_toj=m~P~QGd7o9g+HTEQZ?woIz&&aU(Q;osjeRJSQI0ZlemBLF5JI7h03Kx;LmeA zZ6_0PT;H<`-Pij8C)}=(&*qSiD7MbErse0}B`VPmCRN|Ph?Y}-i`BYTj6C&aq^cWG zybP~O0{VNozH?oDM&Md!A>{RQ2|z_pRDzIvRh2MQr)*k|;%XhbqZR^wy0gQ4q(nXQ zbv3xXqYKmZ^?Ccb5SqDuA7_5!e_-f)7h(Lw5g5m}qWOo8qHSl;HntYpe)|r#3=E-c zc?I64Qz-}7*^@WKpB<3>f~TwK&j+J8oJt@naeXzQ&I(>H#pb#IwW`0IPC`*zqMLEy zluH6Aj>7cD^1l9V@y{&`)2~-Q&9)_HoHPIzF*6FsbugEl#jAtg0^lNPC-G9p3#gA* zBWf6kng;I7KfvoFXJHx!;${?zBa=zsLo}Jj=vr~KTQ%^suO>b{)MSE*&A$?e)A3%y^GB9l$9rp&& zb?bIkaY^H7@Q8~+pshM}>lF!fq4P)u+;Sn{`5q3b#%JCF+2$a~maV1m-h;(7_Aq@< zZ?ALR)C~5YyM%Mc4C`P!QNqPO z@zz{WR9T|S%5jo!K$*V$T7v2*$~tN9n~Gd3Cpqlp5UU2XrtKYZz#p0fZCIHMnkFW*C#smpWT86ZozT&u>Uar~_0Dp#9wb-L@ZG;cdH*Ghef%ddx922+ zGn&pG(XKG4U(DA~jC#B9db!;Ba7gq3+BX4%W3{UriGlqY*@q0brvwQHGN(jfiI*s|~}zp04g- z6OPoQ>BtWMQpLEPZ9zxt5|wBz)b?PQMNg}pnMKRU7#x_{gA1ubl4E1KZmQ~GE;$R* zqX4cDl&kJWuM2vKyf7(SEi3qg#MPe6PdPYU$Bk?s%GzAmh@fe70Qz=GG;^burWXI2Lm{Y_E;< zUtd_;^@iyn>YzA@<7s^wSQ?cmyfhkzRBAm{tgA{NbORALk*a9V_J132{Zpl+-q+({ zsdx+{n>PW5fqUDx73BPxkCuj~aP_ZV$CcJJdNVe9I=2B;aqQ^mKts*i+C9eEe8B&a0<$n zvTb_&Yh>G`riYc)VQW1VX5k!$nPgTSm7&lf2|UZl>Z+-@jI z=TJ?ZLcID!y2+mFYT8{4g_T#opJJXM9GeX#Z9Sy6(OL65^EFeZ(Ma7vT^^5TX^^qu z>#pQjd|gx#Lim_T#3sIdgY>45yj7XG(6vY6Ux|y|z_a9h6;Gw}ms`TcmQWd>3Xq#Q zM8A4(E-j&+>$aQ|(vs=fQPo*V=PBhY{I2f%Rvod$Z+#SXox?VLXWA!0t}FkdnKYv5 zG&Yh}%F8g`(v0o>w*i36K+zuAu3+zpQIzvVO;btCyP%w?%g1Nmt(og+t=NppSaoRq zxhW_MY$R`OZE6Al*tUbN6MJ!ca0W(w{>??{XcP~&Y)03O+kU&kNJX=PIL~>%aPInK zoA;aU-**v>8qgg0SfURw&CLN19<2XME+4psx(jc@a2$+1{zF*k%yo)YVN}@HQFz-a zvY`^7PJ_WWM@u};ZO9TQd-z%P-I495K2?*=jhL&g!D4kK#>wfgYoWo> z5ll>ba{R*GG2FElVSM=jj2Cub&(0oHZE0Lr{if|;`<*+03v9ms0P&S1GKeq>Id$6R z_FWmpT3%C3OM6~!TDBnrlW-l0{H@2q@?RHxlUfj)^K?Nxjcaj(I3NBqf_ZrUT%`XZ za`PKi2T>T&oQ3i-o!v-JYsK%(Y5V5XWh67pIMVtArdB6$>cOk{V$YXh!o^qnzX||& zbL2F(R5W3CU6)_3IZ=z3wj9DA-})~8sQ(T8O!pH2fKRpVz`p7_Sg_&1fddl_wY9#( zHUNC)+2?|->g`4Mk30=zk5d29Pkf5qe)7;^7A?C(CE94(d-)1BJs2V8MT0H88D^YT zBZ+Z99aJL91(OmNr1LKlI>lo!&w5=#Wj(T0E?IyjnD^oe(|4A~Q*m*^izh71d4P+` zxkWtw<~w-p`DfPM)&{ zU`uYtnkQd>6P5D|kcta2-g0NTm5q4rK+G%|-C2|pPQ-G=3^GFeH&uLiDtM|`p=CJ$ zr2kim_8pzGT*wU0Q$BO30O|z(=;&S8e-NXsn{xJTv2^aS!#H^E0-A@%VP@yB*B3_M zJ!E8U`Gx3+_IobDgDSanYe$Jn^n*^t@Ue~fI@IUsV28@V!`eX01{J<4pw5?%gKrgH z>F;~x!?u#C`6!^)?|kM)Ynty)_YU0dmiS;J=-tbgaQ*-I8@PXU8ODirH2?cA;M31& zu)`W?+wHsP?(2sG6Dh=)ib5*jRYyb`eMgQphr&|c5x)U33SnTJD*CC)M9Njv*yBqg zF3|GzKSkA*w=wjizlz1~0|mT!5HRPLDL3NF3R5KHCSC50RIC@uTRUrZz^&NQ%jz15t&ge0G>3Fs!YdV{VjzN|ns11YjsBu98N} z3S=Nmovzp{-lczeBS@MWLmN3f$N&PaZH_2b&&@!b;ix zY!Zh!yS|y<0pHwAV}a6W+kC`y{2(}|B;J;IxX`&5tV@*7uSQp8KKd2O_jD`+H+SuX zW3JDcMMwQRx&g<<=KI5luBL$OjCHbF1dx6fS8|@H#(mX6B>45n9{TXm;vz6J1B4ue zQKAnZ&CCFUgX^oKeB?H2?~cH*S25eY8;e_aa z1t*%q&K`PAHOM+Gvnn%+^74L=HV&&%EL^;im`W)dMN)UM5ppxN z705IxEvYj_mTr z+?Pt>8tAw^=*g;S8w*vHXc-$v^Vm2mE9a->&tC&3$`_Wfec?8nReV(fbmQy70FA~g z-d5NW#5Ju?)uhllkI-MiF{a-g;2{vT%vwk-zg}nRhf!y+zGB}wXyFNRB)JV!_PNRW zpK={4(W{QVToVhZ>tc|@>gS!5uBF~fd~5PwnkU#V`g9@H7qa=8Uh|glz7*R&z27de zcFM8>;du_-!oKWX0Rm}=b{X0Hq7`9s4)0rT_XYIxQ4QqAr4GsSR2_-;=D`_AXNk@Z z&@efP<;rqQG&gDAVLe1~B`5XG)!9gce-*}|xICzT2Ghg14hH6LZw%gXYqpOy_wxRu5uk`p0oEi{09Z$Z~pH#(9tD>@Ba6>fh(cp$KDvbbA>Jq=XB!z4`*P#YA zCVZx-Z3teg7>;vsIx~5h+&oLi*TV1!efxYAl-9%Z(blXD3+3jug|>x~@3d_I=xx~N zi#rX8Mtp3Wbe8_awvQujT6nVc7^2xW^wey{_No>{44~XH@N+#Mfe8l{mW3~E-HU`N zhHecnYm|hF5XoFvA{$!Hl&-a6TX?C0QCCLP z9Y*=o>)|={_b3bCX<-0Y{t35Lsw#H@*x9@hc#)aJ!Mcf+RXq3I@8ON7pF$=Q(bm6_ zBvb^p&pf$FS)|E#6W3l}QS}MGmcmE`HX>Q0v=CO#oH&Z5s)~Z%@$`vfFkBbAu3pEc z;ZX=vs6!kky!qfjm>(p&6GD*bk0Xz^O;x_s@t7+q=)uoiQ9&KHxf6G82FF#+s_I4j z5=I(TsH7?mH~V(fG2q;h!XhF2m4m` zKkvUFAeTK`49T@7OwpF_UWrQdu;|(~7Xt&|k0ov)Vp z@=^aj8DR}-E1^bsZ!v*%?;FaqaFZ%J*TR6z2rs#vknCF9#=N|G-KShb8kALsZAZ&xg6d%!jV!3JlRcv|n5lVHC1J6Y zUu&gG>_J2&Bz>yHlnzdklS<4aU0W$$77i>nTr`i2!*GCm+d5%Kt(;CNWh*OLNBeA> zOcOKp((AKoegUym%5N`VpmJdmJ=bm`jfld3OsEQDuB??~r*a*>wO!?)-d{Qq#qgFk z+}gP|XSW-BcA<7=4ppi7Z2vjF37@L9WiQi}nQmPcy}|W1RHGr@&Q8KF>a9AEWCL1XOJc=|w4@^y! zoVI^ZXk`UhTwLF*O-$ZL)1|kNPPAZp*DDE1taGXGSQ;|w6IDz_t#%6AEwX&#ixv~uDL<|!xO}MwMGfz+Fr|G#l zoc%8^WANMOVKh|&0AgKD==}B1;pxYYtgG(wLxpby(Pf40l~NT z@&j_*sNq=0%YrhV8k3E4E`epa%pv~N2&M9V5bsi1u&^&9*!p0(Fq~K%ehf;qVb9Z1 zp^`>1Bqf@)$qwquLG|6L)FtKT;L0Jj<-%E;)=n{lC+(SVvFX7m;JO&zyjlAO;u)Lo zKS0yy1aTYjz6Ws{>gKyc{u9&))j`)4s#oWl6&}V%_6VK1L8;X6|F2pD9A)0?>Ovq5 ztRAid;!fM)a%ec|Fd4OG~byHhNOWiz9lyi#6qCA~)YgDF<%E%5OT}x|N!*OR5ulA#Goa&g|jp7)n&4_md2`h|SHR^5%KK zUd7CzCos3;=tFx}kaFqF3jK;D2j%5CnxaxHwF9e2jQ??tMxD0#2~|$u9uMLnqiwsU ziK)g07zWVSyAw;56$STUE*gFF8qQAK#n{j+km}?a*r6+@S5p|QElr^YyPSdIMChmz1Yn1qGQ)N(B$s^lBXP(LO z={6wB`ss6m(iWBIKL?zmI+J5^E+8zvtej2#| zw`n_wB-8A!dVB$o6{U+EMOmC4tOu2kK}CW7m8gqb_6SB`Hv4;EA6~~6D<$Mvd;JsW#Wm;PD?`S~?a*G9E9eovG|@+#9=kal5+U%4yw|m ztlo=cPUD`7HgmP0j6O!yBw`-W2%(Z;8Jb^GRhgSXQH7ak0|(HQZF6OXpwti){JE|KXnk9%~d%33!lU8o*gJ_ zS$l+0%eHa+)VqM~t+t8fRahB^aA#A~8$p+KRV|^54a-&if>a>V+($>s zNUoyt+IwjK{a?e#7ydbBj(-g4%39?)l$#bu(paOa&I^$-i}@0DEi0_N%6&JAbnmT_ z7#D-|lo%hbU!(gy14^CKOmh7=sjJUqonBC=ECrg-J@#{ZL6wS1X(B5 zSd=ur292aBQIyuJQsk#Ce4j&AClP!Zo=)7~+e+N4n!Ksrc;AR6N?7n&p^;6S< z@f4eZ0Ygzb2e)!@g|vJtsx49F9W`cWCKkm|`_^?wCtWR1pki?eMn*XANNy@)tVz6O z`ssr7T1v6DOB6?SB_=5g(D~y+ew)Sevf^Y|`h1R!rNQL=Au;1sEtsM7t)cwUzM@~C zq4Z+7Htz?U+S-8b`~m1o^Z}uvA>huPwUsqo2eE}Iw7&6|aBKHscHdE~)EDZ_zwsKR zurHD89KC0A*@myl^82TzNi~|b!`2DCj?iKC@hDzW0#Om34sYw?V~HRf7Hp)-;<($h z9V2b6>+Z+7#YH%dgSWr^CWfacQ2yn|Q1)r>819DJT0D33*t+VEuO_j*{|>ec4zcLk z!RTMqs0=0#@K|VEdqDeMa!eiORJ9GV=f%H4jfAu#P?^z%I^t@bIyq9+Gzaq*O1Wgr zLhxfDPY|^gN_zeA+G#ECA+Rl#eLZVQfJQra`nGCZCQ zbfZcTvb+e$L@^6}Z@%qPeLqo$N!sZ85^r$*uB(;^!*}RN&AoDTKWyEs2HRV^N){giS9cR&l1l!;LRn||1Eq>IJQ?c@?IGkWm`np zrh%%c212B&_=Jxp)qAMAh}`P}A6M$gui|EdY=AO|)iu0lWx$Z)SNR90Z{XHf-^M3T z{EDA8yD*Q6vT{THAET_JOekGvqppzNH^SQ7L15a#zhNX#e`kpD2o2mSV z%ON7IYXgR1!jz*Y4`ROBIw(chRVAL!gMVd%YeY;eSCk#!@iDst&~|#V)mvCvHr%t`7_ur zcBApj$FQ?=8}@XqUzwIzSw+X40kjVcG8>2Rr?T1G2Q?0&2jKUF>@lecQJtf?wgccJ zD&;px93KT`P>}jnZA}nU>t)U$hK7=!8&~u90sB{d6G1Ajq7)_<<>UN?VCP)V4X6Al zs1R8iP@J~)kK#g(TB%O7)C)VsDML#1gF*W*UP62|$!3r`3v|;tOc|j&3aesq$v1xM zDA(uWz(6J&K}@txE~=(z3mk2vVcMg%|x6$?w)cm6VL%fy`>T`W47j`m%;jQC0t23!nw zv}0^jOCXQox;Sv|0<4UuKc@-V-r_=HHiZkE~0XF5pZ4KD6Jk{73>j{zLdTBmubPFPjNj5;`Mx2mTkjy95|*~ z)Mg69bz#}|hMag~I*#u^?Hb00yiY#bf8i49rltV^_dDCsx3j0SZIh!ET%WjNR5vcNKP9r_?+1uY!!{(c0gP;fCy(O* z2FmA`@x-fdDjb79hjIV3ffKL2!`vW*^A?vhsGdXo>9%cgr+nFGoa@k$lkYCE+F(aJ z`g_)|M89zOAoicXgyxYkn2rq#2Ar%@kN8>~@}@56tfK3=>)(|l>-xV8zb4v~bj(%$ z7{-m%85dNW=OSKOY#wv{Hn>WTeB`<=Qt32c0P$!HsdO6dN*d8b3}!6VKDqDu7PBg1tNU7kbxKl}k))53!Td$Ag#AJu=0dFp4s!}6=E9#5w$ z568AT{hm&$P)&m>AL00xUh7bl{%jAB-@G0kUE9e<-K8AQlX9Ghg)95^VxqYzZ@=au z*L9JaUBcJC^$jequEPD@w-GtH4F`VyGuYo#xZD~>kxT}L>!SDi4YWQOAwg+^PTO8O zH8yA4sMtbe&r*j~PfC%z-YY2#)BgLa@9)bGT-M|xD@RCYn-TTujLZC4!DoY&%SA!_ ztCCJ)4CYx2-wM{8k8(*K?+4MoRV5waRH??LrXhob!yhF3xtRawoYrU%y+t|?TVvUM6@ z%H4E$SRG&bHOVhVC5~rZKSj2Y&IbBB|HvAooU6G;$UWI>@{5L_Uv0a5mXXz^NUq_+ z%xY)l=3U!=iUT?mR9QpRETiii;60^cHQq)#R`Qx|ItlVHjzS+EMUHhK-o|x-ub(}G zV|({wQ)BoE#kw_wN@tREb0YV*t&FS^Pa!-A<6W?4(k7xe}G=(WZd` z7q@P$t*n(?#->;Q95X1#(&6XfY}vM9?aC*Kq1n@{y)INf4KX_3|3! z=`KrCwI#AF9c@~NDhsGGt?qgGa7mE#?-3@41#5J3-Y?|IYpE|-Lsi4h107Eh9 zVlkrBJUR|5V~2cdqMSZmMq-v9M%Y{xU?`W8OoG^;(k2-BnyPduz*3`y1r3+FKQ2J) zfP!xE3}u8YR8Nx+eS+GDmB)aY=0?6_zmcjfXH=Z)sjvB+|*|MwBltW6QvOzyCaAzB~}j8xQHmEoPt>!_7jjSn8Z< zh_UBPTioNYI6t$YWjVKyrFBo@t&#Ut$jSxCheu156C`MrTV1V!Wd0=)HsI2^cx1>ZHNpo|+1_v+=&_>MgT!2_y>(yU+wPx6t zO~EdQWU8u-n(qssn5WSSlHUK35g=28-$ec7G%|=lf@C2FNWL%A zEYiC=)r0I|odSfzWyzr^sSet7RCTHob!J!-<0yaUEv#L_a-U&r_sNBKwBLzVNXZy#Jw=~@QmjwnNO ztZg0AAs_XKcitxYR4Mg~u@EOsiGKDlTn1Ja&v~)KGTHK;3xevD!ko`$X3;Oj0%gdRPk0xhl@%OKO7p7_AM_&3Q zzW&B*nEutT;@MyNC+PksPZ!Wu*#_b4XhS+5nc0o|!M>z3r9>qvQ5Z!RrqS`r@4;|v z41VJ0k*Zvq{-08z`ZCF_|9|%0Jjk-^ybt@``(DrVOwYdWD=^pwI{}g)2~v}%k{$5jic}@*$u^I z*^st=ha5{Ti^@4h-ctoY%}Ef?v}G6N4cZ|}k@Hr&oE=|z@<~jr?f=bBBs140@tb>o z3a$B8k+=W)X?*;r{s!*dzklGk0pQ8+yn+>zw}3q9ya$(=JeD6|?OT7FH!i5Rhh6uO5 z$Q%<|0th3^Hm5^&X$Ob3JKHZa@S0Qcj!?Rfw*{a9dc#M7kqLWHnu$oyTFydC8S4+m zvf=us)*yt%(@vOpjdNYSQ*YjqdI6B!ph&pNg%_94>^-L371*DhH9$^#q=A^L{u zLF1C+*-Fe3)ZIPQ4>24sZ9HCFTGz<-*4*08jB@tT{X!!CwCtZ@o|!*{o3Zs>+JJ0( z%iMVULxl8e#j6QB_Bo!yRsUvwEXS0JQ$d%Y56q<3ldiUFNs$_}sgF2lj5?q1>MR^!Ff%+-@p0Pr>2n z5SF#KbenCgJ&58Av4XS-$l2eE(dN|~)0Y3Tt%gSe_e-ATG`mjK7|Vh3l7ja`){T$j z@t0pK582VBa-0{LcB1lC)fd8fJf44=qvC!BFMC}~5!1elvM38FNxOyJU;mewIe7we zKk}a=+rB66_kGJnUE82_%f+XUVDvNnJyHI6Yq7Ta+SO1wyJ=RK8ut{L;Mqld=eO^~ zI}biEKwW7$|3|OmPrmd^z?x-9zw#sa(&xU2$elsPN zoc5YA$0oiVUIb=aM6dE&ONc)3M{CiAP#F2Ya1TXtZ2BGN&~eNy!{sKd3>S(GW3gYD z<5(ONwrWo4hl5w4o9euJ61R89mPi&!5MMyBB8j_^O+eSbg&*&hOf}An^gf+VLCMJT|7> zXn<_La0x@Rb67GvkBwKZ0tm^26*~xrXJ)YV;$`)`TO2k%`AOp4C?;%ERltyqDHb!)Ke?AbCW4bTRa z1iCl*lOX>Nzw4!TS$Ep6oi}{lQQgm~^bL;}{s#CXh5Jx%^!d;~|M%GYBOk|=<{Yj+ zcNl0ku<4nDfkC4x|Jvk2HwfCY#V2T#rL6Yz*GVQPfg3k+?AWnbAB*z-NL{QW^?Wyf z)_mssV_GCph9uM0O`-;Wo*~M{Gn=02igZ!NW4B&q2F+Ls%Cq6^RU^gf6`%at!vK&M6Ej<0)pQC{`Ui{=!nC)_SqS0>Ssc*lCW~-(8 zTeHrxrQzleDv#4DiMjl-p2f{wVk|Z``Ka1Pjw_*2y;=9MXDK&mq#7 zo0?_g5OL7!;x$sB&0IQeeNU+_r^kN{GPjUZqKf+bzfKVBmok>hp~w^=8=|p zpaahGjyKA4$d|jTO^f?PPRietvlDpb(x2h`_Wp3KGGs{6a2D@-oqc+hb*oq7M}OdR zNRVL3&=9gLLpImK3;)HxMr&#Y_x|+vzfURmu8;cBv31&WQ5NOHD#O<pg^@N1kWZr#G~Klcr^X6BIo;^%?Y!+838KZSjJ_AJOE z^Hbk`5hIhgfh<9*Ja$b-rr1Kj8$E4_H72!|0*UD;v_v83xOyVv4O=p_g6Qv3ms=|d z<<+wm%e1}U)mXXLd8gZ)aSfBBzF zlPe#C*;VZLlKQ&eI7#dc)z$HJM`}8J)ojGPFaDh3^fspVUv8~;!dtqn{^KxOXIULw z#FiuJFh}n9{MKS_OWA*@Po`xUN`bj?s4poN9h=_r9dc@RWqw_+UFB$CdnRp7&&ph~ z57umSxIOLor>)LuS#HuIygk~tE7Lg@!496ixF>Ep8X@@3rr_7Nbb%Mlm>%kAq4c+DB6wzv)?3f8xyQrW}$ z@b$Hxi>qYeEfsb9R(*W3D1TMuz4vmQJ==S@q1zMK`6s`Ip|e+T`OE($=63Fna_qQx zD546X)Zx-~{7bE8ZIR)K)EYw0Msh2%eFu%bKrB=4_6^O%v-MRj8Qy;6Aa1NH4xG1| z&4GFJciuXL(_i^x?GF^L`UlX#iJlAqqj|T&cEkYDlr8h&IDL?h>EcJeTE|9Fp_PWqt z*e2G6P@64>uirJltILOC^*r3d72_m5?tHZ{kFf=6F0GLd>lEF zV$=4y^JN}-z4>gG+XnV3MMMcYtAscs%kzJcPD-R4odX`B2Ns&L)a z>sWvFnhDAA+27Jw0O$p5CRSk_1cG8fE*3_YjU`d;@j)&9b`#Hd0r;E9!*ITW$;vvD z;Ju-guN)8lhHX8?`AXN;fmNoyXmA>m=Rv@$Ch1ILEE(q~q!B3Z6a!IDe$AYo_5r%* zoD2>e55=O*9WtzJlcLP_UN~0Vd6@&fv49NO^7c)J9Fka5y>k81ClgJSsZb2_OPUM% z`lP89D=@Zo3pQOI1KqVoXMkmX>VQEikL)wO_8Uox2N$h3s-A0ONgpY-Ga%1#_VOj1 z{Oa?-xe44mKZm{lNxeGE)Pk;I-C_c`u=}d-C)SooH zN<^XcxxaN7&U0-NmPkat{8-*SHc`RSm{pNHq=b1L&75-x7o=L=z6tykyW z^3rRHalS;`D;eq1vkXax5zE_4c;r(U9&rg8vu%9zh3_Cmjzf<=j62JhqmDdy=rA^o zUP00-UQfPp^eUd5d|9Pv@i71_nVG|q>Df}dESa7|18qF^%4^6|UKH2wktrm}fn`(E zNODF$)X#`(CRvW9)3a{xqoW}b(KXQu`m@CQ?5fKl&5q2PyY~Q(LvsG~+nfgNyWtIM ze!r?K@@6?L{pXW!5|VsWGc0`rBkN7MZAt*iKsLYgDmgQSTsepBrM9j^u5YzKQIEao zAI*Yjj8g9*S2*d>Se7GO=B9YfZdQJ$nmf6u6FGutopjo;FmVyz-_cAFm>!u-&Xll#HMpWSRvu9AB53N0=Jx__v? zn743eeyYsVcP>7UyVl)@4a?}DRsHe#ezL+wnquYhk@EL5Pks!~|AQ%9yEulqhc?&9 zTVnc>hb2Ngo36d?twU`n<0sqHB4=Kd54)T?1)MwA+Z?}q^dz=@`**PH${D=(_rH7-Km4tKhUBgdKr_Xfm8&q+?Eg(K zBe!qk;G1tF2e52%8ttr6mWDQH>jmW)cC$56a1=l;Fmp`<1qvV@9Mj0L^%mO;Jnm|H ziA5JSe%lN6_atzG^IWEFr4AQ}J*isP=@w`A7_0L$IJd9n?sRT{UoXen0KVc zKl=+?RWlS%n1k9F;yk#Uc(v7gU#=c|{>Aj20V~(0V>XCl@v@ylPwo!@&4$z2!~WwZvFgT6YR!!*NN!K`7eFj(00yM=h0m31D%XR?#}gd~K~HZITIBPOvt)|HUN z`+2S#7lGbFv@u76V|zk|m8)zUsNYPX^=)eX=b5Q%s95YE_r|e5wwaP!DkEdoeZ~5) zWR6I53f+Tw0h$bQl(WLvR=f&NE>e?FJ84p^UtJ|Bjih`QX5^q(M)D2n{*9Wp_PEBh zCX^J9&&V#MOs-yqbGvt8^W`y>ww}6moyPB`XNp=S;goJQW7v}?X2#LZ+gQJBW5-87 z;??}Zz~x8&;g}j2*pcPy>h7A$H@QpmrJgB6vaOMzN2L9mwBt08QBk;9trx2G=54~1^lW178q6#o z#??(5acTRu+I8#6nM)VZY89`6e)omfaC!a~l4tM3%FjQD9eei;6gL2@yFQNLnHg-p zJcdo9SIXPP+HL1^?TSEuCv4lM!QQu>;Ik`8-$FTJHF<^EM zH$M6~+`9K8B6dxrH4Y1N2;&~g;PXz5lJj#PmGmav@k^b&RHtCEFvXaQJ|ayJJgRwF zjgHnOV029wvk1jEOBWkT8d-)_HztuH$Ng`;gRI%WnZ0{3zJ6UauMfU;7#l~gAeqn5 zLK8U>q_b_Tn4JoGwk{(f$41~|`OP~@$8i~TER4-1=GGWJemk%>I@xE|jp9!ba!EEX zvQDL&it9?%TbgS+Gg~obvxf!)L{=g>w^)p#Nmu%=fgxjTUfEPs4re`t2dA6 zbS$n5=d=||R^X%Co-W;Q&W_{F(UYl>d8ln8y=TwK{7e~jDP@987eYTeRXOg^`c_S|F+<^o+TFoYIuI^0_S~>b_-@w`5dj(T_SK|6pTd-o;5T5z@zk|&m zzZbpV=%!`;wd>e@<}A|rf-}gaa?63GJJqPf{d%FX3QMGRX9Fp2Ew&toV7+2cfNXLe?9_ zPMlg=+2lBG8+Uv3(;u^d9My47Dg9Fz8P;-Zt#7((V%C`!UFArz;p%nlIe8jq7U;(3 zH4_uK`{?l!N3;!M;xVAnnni;0Q_i8RJ#!UWYd?;eW3lX#-a4k;<$NMXlGVVr-}6yy zvbxY!68we-dF&nlmdwm!`?-q%F!09h&7))3dG?&Sv6bzrdgGwPYqo~8zV~%M*F$`6 z2y0B+j(U^#3vUb}2Mz%1;wJS)`718X+c&Z9$hWcOrGJNG|KZQ!_U;478`TGA>skxD z%@^In%M`1gTffr3$El?o?NbUlwRG1TvD;{(1w!YniR9sD)>cRpy#3%oT-mY-tpN@t zOZm=Qhj8MTzmDnlJd&UI2zEYvH|}}naV%Z31RK{5`GiU|001BWNklB=9_{vgHX+P)QYT{dp7xiNuzjvU2`$*I!7w0e93Ysbei zGqMcrw1Fhgaq!UFXm&P+P(>A>lW!cLGT!_4yJ}c?Als`*zL}4KJbmi!62eRmNO>J2 zPUuq+j_)V#cXHsiq_U;x-od)XX@3tMr;NMay=mPOYLQi)J2Z?9#d^hfr*_;8&X-_dlptSH4b}ENK;u$=RvqC z(R5IMvLE?-a&`houOGsEHiri{egtcV*8!1M=}kg%IjB6a|1Kmync&P19K^aUTYAVv z_y&U57?vT6=h`gsVUa3*u_%kuuN*s;nTx&wCZ@_KEY&36KIv7Xl@;fzn|{%B{w| zbiY`^OLDBcb^{4=G+J$Jy>z)uUEkOYY`k<8X)Et+*k)}|EPK;^F=5S8f0Q@zB`EIx z)+YRT``BkZj^taO7?W1@AMcsOTpo|sWnrFQg&JcByGMYu-Hr zSFgOEZ582$bkAg@?H6G!YCXx{!#7lgvzPrt@F{a3$Drk{R`beo#y4)m)N0r!oQ_wA zDC>kn%QW;GsifxPe#!MpH)-df7xBuLNy_}n8sgCq>l=1H(KC*1M~hA*>hNFnNb_h~ z=2yqa^=RvrYom@F{q^TCvVA>veD)Clz|C8?aPq==Ja*sxHDicN$djc#g@039N;k{9 zLu((fBpt%G728X{2RA%~+4c-Zn#+tn49BrQvh`S@@R``Iz`9)C1>U=CSzjOb<&dpT z`owZ%`OOz?X-Q0N4rWp5C)^?@UX%|~*1r1!*1hvBTzllRxOvxO-<33d<`8EJai(GY zgsgDTm0yoKv^-R}93+MLk!tE8s4PCcZt;EFIH9gm#l-J)q zf;+$SI`Yet7|ZTpd_#s!yVv29k3NQ_OO{~Qj-3O=zxC2(ti3*tk*V8Qcl}1WY|h8C zBVo=BrIsQow^5QijmDz)0SVfmx5E`- z7@5)K0;$Lezn_(FeGl_#v9aYMtb;<_!YNA|3g2+-vn0T81Iwjt@9}yq+$S2t#&Qww z2f7bv6z2OOw?Qu73R7W@R#)`c_sS8vhtI3r{eB+KbRo9Y>HBsLKbM4{H7Cu>mZ6?a zz8P!hqA#%>ipQ7Dr{2F{nGmPK&naL1=nY*0`QLIwIRZ47XIEz4RC1K#R+m08C8hB# zSI+f(r0dAzFwzI-id`j|@pMgCa?Ve#{tBeiD0M1X^HL<8HT2=zGuV0d0+1v)vu{tN z_Up;I@p0@uc^d1kjbk1|g7@nS)4aLg*AY-<_wXFo0oNMWsPu0~xU@B}tL!y;dp_5A zZv1Mi3iS}WT#kE@-Lwq=OQz?r{oF+~=UbwTg`Z2?w{<=6xAXjYjNF>S>Kl_-HF2xF zaHha>jS|<%LwNd6)`aeBTvNI>!#1+GDHPe}e^q4t`UK0CebBjBln+9NZckvtq35vW zrGJm>2S0=H2cE7Ku08^f+vxkZWW_CE(%P#zx1Gs6Eza>u1}N8yC8M;*f%RH)@qK#v zGMwA98%PU1n5F&WMF5zYoyD7Pzk~d@4&m5|QPVB5w`1H}&% zm;CNIbq4FM-#{A;%y-t(?5*0~go8k)uIe>@XIE1BlW)*+|fCe%Q-JZu| z-+8U{-!l8rX^=1wW2i5cob<<4=yf4W@`(sg{S|TY4ZiH2n0Tar>2BTZEeI%Uc`(Ta zjwS45;Vot4FFqVY!prgdr?2Y?*Rf8M7M5lHq!P1)B%I2mGWKua)&?DGY}EPF`3$Kk z#UYJln#B4Ww`G}QwaEQVlW6&@NVC{B=TuYWj+t*iUQq8yX>**AounAgD&SVVrWPWM}cP@`(_1%1%>EzTDmJJVA zzAlrsudD-IYU!7s)ytU#hheYv(>gzS3KKKe0RU%i9>t@>A9M3#Qwn>nKLtwoNn<%h z8~xsEe*gacxPSltK0>lVf^t;2@dyb=lqaEH@SpdRul{tV)Gv#&C?BNsGMWeNvAt;y zO@Lzrn&S--h71>?38sbgEKUV;<6qyy&_GBF^<9~47DR&1f_09=j~vA96)XCyOd;*r zd0c(>9RA?c8)*MuuV7`Xfo7wDk39Sl?ETbJeaD+-8Afj3E^GAuw~kvFjQQ>DOXN?su0$ld_2i7oXb9!+(9kJKu*8M3CsF*3she2&=AUEe##P+9|4H1s z=Od=qSW+#;;#!R`WgbI!9ZQ_3h8)lL7k;lAb@hm@C)N0-PTGEM>g1!SDQ=GRonZB~n^<#gLe-7#Gc=kT0=vro7emZ;EEFP-F4&fkTCIvBQw+2a zQkOQH|n%kimk3!vMP+fv&uST9J#!IlY_xV*Xx>$1M~ zy)<!z1tN9T8%rdYaUNv*JSPdSN~u58^pV(kEa-FhPk*tKf6h>2__x$;G>+}Gr` zeL1&4w1Z~q{Fx$Y=eXRI)1|g%Z<+4Y~;$&h21-FZtpJKS-yOLau<^2ISwB?ino8|>zMxS*OBa7hn;`- zd$IRp_h9{+HQ2Ll`@m^zxjc$Jr_Ny2#3ba!MDl_nx!5d^dCMEa$cC!#z0`-8ttB|T zJ*;pq#Inm6KjiO>A=#hBlI$)~y`4XNHyLM`4=>mCgn5N7kAB|U+!5l{SekX??G5kN zl~~y{pYgbm#m4~QU(yD&K1^&;qByp}^Yt$Vqdziaj8) zWn4GdQ4+>rkB(YKkeA;mTw?s`TwA*jr(h2`YZjd-f1wpZmf1@?#@VgCA)Gz*L1;Z+ z6i==7fHu@7$~Waf@?Lpif?pQSOA_Qsm)P?g@-Ytqaafr*eN3Be2E?%nSKd@ygj#lI z8e1=29%$3{y76)BIdvKv$F7#Qi^^3ADY>YZ5DSF55~@^sruJ$^?)=c!B8U`NBuAEg zl|H34N%Llusp;+BA=V&VCG`OP4NcEu=c)4|wj$J$nK?|ZUL{i2bqE04FI>dPt>Qw; z78=TiYj52S@4@wI)vvh_e}(Njn8fkbqAbdXO@@xYh9$54F{U@}!uiksntg;!N#e$8&Kz>t z5I6Q0PcMF|;;!QF-R%K>niOY~fs1^kfsQ0E5>zt$W|%Jls=U#fL1zY_SzfD8cRn3> z_ZX6QkE-r!AzBMf%wwoj5qSxm;+v+WI+BA6D7KO2XsYhX>2fSIJh@8sU}ND;z+p3l zB&CkXK~BHr0LoQ~x{C+A2NipZcFa5=>!8Yfz&9NCR$s9?Zg<)^=AZIlXd`4Rj9-JYz4SQI-~&Jqt0iHqA7q>9&0Iy!y&J`Bt@Q`IuKdL@y!elP13&uG zzbM_l@$yS}^5BEmvANz2&~?Q2b5By_XqRPX5JxdcvG4%^9^Cja9^Ck_NF{SZ>OAF6 z`^vj6YuuQ96i?Ge zO{huBhsVhxw{54z>z`Xont1W)r;rc$s^-@899mPwJHRJSUdHc!>3_tsU-?ns7oWxV zfAVRpUo+V4Wl5f6<>Vxu`u0m|Dc>45?P~;4)|NC!_@}0`^35xu(N-Es8LLVh#{Mi9 zfr^vkVRxNgGB<;jFMJI{H?QO7W6xmfu1A7AdGYDl+Bc+zzdd(Gh<03fBcdDD4*grd zo*&J>>PdG}UUwdoF>2gNInwRT{UnF1d)ll?$d=zgQ;gQ4-$}Gx^h+{~p^Qngj6%Zu z2)XYAfPB#>`3w)&TCJo@XALhLrpUb)pY$V_M7+B7+ADU`G)n)TsV1J=Za0I)dQGg~ zEyRK1LL`n1$60J#>9JA7BY)d8s_W6}1AU7-%{tnT?U7nf+CC}EDpTjt1oOnY$IHOu zkNLALqish&HZR>U9a|6KEKo=WdRtxLv#1AocN4#Km%?TuBy->*{$lJ(J>iW3`CTt= zhjWs)Z;-Dn_%7!>X=6YcUtRs&3oqFA?Bf_&#vAEYj*Q@e{r+o+b-ycIpuVvkLx;2R zkc9n(Q{t8?o=LrId9s&Rn{sT!MQDT3<&xzI@kt}gvG4dPv>FXu*trvPOY3cTuPd8J z$1prSt#FjYSd_;Y>b3KYt`$4eg;K|+u_%l3LCd8}dF@Tx%g4@O-8^yrO zD{k_uo0;Fr!^&yrjZ+O#v$`f_ZOVBg)YBpRkZT-3*#8)@6cXd3dV7||5}HSZ+!wGt z&G%>LmR=-=n>8lr#)<3V9?QV}=e^ihyYu0GBysaVD4bHZ$ldmqB5#C~$sZwk;>THM zMSu@E%HAlkzf83Xt9#ldI}A-O^183EEd1^&)29c3V$FTD4KgZ0_Qe64`&tQ7vE~ATkkzV-p!it`CH7e92Uh7hc z#;pF;YsYqlG*fO;OWjTh+ zU)3A8W2sbytC9reP1}}2go#q6$;Qo)paCKZ2@*8GueIVXR-B!dw~6s4>jDNbF{!hmTHcz*bxXPR z;?x_-W5c-a@TS|%dlhM*NK8r@8WI1!cWb{6t#QPD50fV--HA+SI_h(x%(y~dMdR*FHn~BlWg5sZXbX3HN5foqZr+~a2wsF z95{9iyHA}JpiaLaMic6gNYj`OH~S>!d+(F_`zQ4Q;G!&wly7}2$DKPLbS}D!)oI?d zZf=Fptj;6Ge+P#&K}$4YQAJ1(<>GUyp6Tt$?B0e?zH>Ct!o<3@c=e-C6nPqO!!`iC z_p5(|7yqkYEq-iYjp48SDE{^re-LS!B3Xd=*W8%E6ED4@ZUP}pt~YCYw}bM{6Q?&s}0l`HZ=* z9vyYXwzuVmy^5Ez#qQNywR>Ogj;pJBdm22G++1^Hj!&{P`m}wK^=cy8P0x`!Z<5z` zs}qY&wXI6?XO3Hji^U|xv*GY)m;G7$le|;MXYbeNW6*TdAE%O+^`&Pbl;30dm2-h* ziMfeIrl#jQ{W;>H_Ux_clhTMGs!&f_f?L$cLkwg=nl($&so z+Ab9GLFU1-{;9un`$)?w9|g#9;JxF>lN6VBY{Tr*rCm#3M>br&hI`&Uis9SSokeHa zM|55#stxf=D0T2c_b|O`{zX}o4_1b+UBISSzmBBc#@Lh3VsihZA9R*_5T8efR!VJ8 zOqI5<8?!@=Vh=KhuV`+APSp8)|Po|SG>`%j@+4qqi$?h!C<2;%eRfzZ7QPkANLD7Jb*wk~H5bLh`u z{qf-tt$DucidSZD9%lT)>DpU;HD@mV)8#FEfH4)mnJMTV%DKu_s$62tU08eQ62xoO zaw3iYwV&?XG3={4Jpb~!XpA3r>)GL$lA~9~)}34GIJUHsE4tp(( zz9L4WFwOONG=-YiD@nMkLi+(^o5@nG#>0-wdJ*PAX zcgh?|W-bvHL{7+WrtGvD`O5W+EO;()S@=ABQ%X3mSPVt=sQJ3B=}@Y0M?V~XQ5L0N zxpfPeo$c;#`1%!WdHMITbnXtuKKW%#Z`vK1_Cahj8K>uj0tR{zCx3@;#gJ%-4Pa zSH`c`e%qoaL-X@kIe80>b{hxZJdC8BgRKQcY1>M-$}7?Q{XXr^dWoIQ>?Uuhnk_`m zg7!Iw1N@$0If0z_tauFAzS9NHuMnTfbYh{|zs1RQE+UGhtub9aUR#&b`|*WoYWJ%6 zJUm=&Cy2L3lRbD%YhO(xBe1V|Ef%2UDK#K3H~A)LL*BsKMhZS7SloE6yQZY%+##j0 zNuSKuuU(GaAV%QSPrgd+Tn!=}LuL$!Sl13)7o*Vy{L{4AL)1#K)j5SWj%1*hTyb5r%aY})tRY>KIZc!= zZ&XYF_Er&(HcA3id5mI6js<(iIcxX|``lI3ZKx zPu9p`4z$?mx@hyTJ$bV`%?mV_$eD;vKC=TP=`v8D@I^A;6Zlvg~{Vq0H+ zPqGY~|KQiL>d>EK@`rvFckX$t%zub8!`>$SNk3Y`yv4|=Ujkdws<8D4ZY*{`*sh|VjgYY!-AB44sqe6d*6%SEi0gzmD=Ij_CwSC8v> z@%JNsUS$2-e1ynfyM-HO!VNy`+t!!eplx#^w=n0hc9?Jsaw#Q$)||M`#%f9%8M+$?62~ZhHQP|t5|*NbzJ_$mvM9dW05&16u*~NhwZ;-Ydxsr(+Jn1 z1&{Z7vy0T7Qe&io&uV_m8@3yPpSDONLpIdFwapuF=#hu}t^tzU)6=*!GmXnn$|?)t9h-^=c$ZiY5Ct4ita0)xyZsZKPR-hh95`w4Ik2zm2BapzSR#hwEmV z_Yzi?cdOY}(4SJLOTEpEtoRkjy`GM>JxR_H)oE+IqcKMv>|KqFBo3_R#Xc9ZSWikX zoH)jdWL)*;s_MDZLvr0DF?A4rmnfauNg~%oxKRG+U}NFN+cl|G$qrVqgABG;$b*jY z{$+7g@l>OFSq9m+q^sn8b#=DS^+H}8_9-1M{#>_p$R5JH*oy|J9(k15i=>hu-&SI^ zQNNaCo#w$apo+80^mI+hIZ7YEv`iruTNtnHdY#pvo-p>OP?_SxlEYHkyzfHB zkOXmRzMGW!mbxHOrP1XKId-UJm@CV2K*hneDmhSY()8}S)@+n=p+~kJ(Q>SJ6WMB- zrNsN5_N6(nL`w9A0eibSr^nikHgn52Ysl8kkf1r&!V@pO3PJ<#Joo^vZP-v*z6TD! zgVi@~innsmR=iYf;`Z5=e}owc1JP5S zJ-FYK~FAHOv;@`J{Do^!==`%KH;0r$c^6@Bi}7!^>G|8 zar?l1X7l`E=ED8tZP_wl0hXo~JT`D;=tu5R2WW8o=-{NfbH`SuO=)_ty$k}Kk?QAh7_kv8@E|Q@Ed6O7Gw{RD)frjYFZ7~FxF!|LcJG#E% zn!1|2tYPWK^+2wingp$7gTOGV94!Eg-*Zw-Q(DQ;v_EY+<~)ucK1-`xEy@z zZEU_ghP0hIFIKfWfy=^T;jstEeDR5X9Z1G$FUq3)^$`zjhe#pz%##o)a9A&H*1l3J za(B1@*YXGCwCn`flZ@h7@D0&b9Np?s_hM9`qhH6X8aq( z^!;tT@iQdT9_Ewe+8!{hItt3VUdACmlU55OC*Q)B-~Cmb`q_VmnY$iA-drleTCAG5 zZk(Iy`9=F?v}VKj^G!(a>yXhZa$c1`uMAaWITR0J=rp`^sNck6E&2zebNahdVg zOSIBPqa4@#uBit2ja3voBX?VOeAA6@C?X82w}ne&%Q2EMiurqp`*fM1+;#o4Mk28b zqg8QHoypec@uovV`O}(KyM}Gw+d;n=Pvtz@4djE0=H@;^4)bH(CI6|)n~yc6?vbg= z_MqRAd4#&ae%H4(vo7WSn>nE^SMr znKS3d=EtyKavu(PoYkGOcWN%IbzHX^E7GtVmURBYd?muI=m}ZJ&Psl=PF>TYGR;Cm zbMqLUo&f-~n~lEkUvs{NkAM3mOw_a-OZ*K{c{8j2`;tcjO6Cl*N z+|n8o@NXS56sh|?Y-r=-a6a$V@y6noPuRC*8XkVpE*eu?7UPBV*mn%CTIt4#!xTTb zjoUJ2*)|fVYL*vn`Yim>+H7&VDWg!E?}97PTUzD2X=KflZ+X!d=hfO{5)nrZZOPH~ zm6=s>_N5tuO-t5*j*r=~3?<}ER-5=*5q6;i=>;W zi@qw`mA`XNX&qPc?2yk&9Ur!LOs`0e%poQB)vOw-?!4Y0Z2@xqS+Z1Vfk;%TSW9^t zJ$y^KHzom3v)M2_U+Q&dt!*Hl={*88r_*|8aXDh45nCvBzvLaa6j^7}b#YKFM+5gA zepmH9nLmjK+DOqtvwVxNJO(FM79{(XBgk@X+v_Dd;Z)->@}(8}xkVwm{yAlfS&Gf> zspyG(C@AT)57jf-U-&S6TK=Xj_5fX5Nu^6Wt&?^3LTSWOg^{^tC}n+vHnmS?);F{^ z)^lnMh1nd1&#i4Fmgjg`Nb2K}4@RDRGQk2YQ7y_}5=pWQcmLa80FdC~XZ|)O4m`O4 zvG$IXW4fSMcP}5T^`slkgjSbAjdrV}?fSD^Po@=EG!lI0sgGfL*|K_tkI2mIEPm^2 zUq_zj$o_{v0#1+Pv7dex2Y=x6f!`nb-p}?Nf0||3bNUSKI(DMuzNB;MR&A+=dCsGQ zOj<98Gg1P=TK@dQzd5}^EDzD#*F%U>$Hp#m>fUE0PG$_NbEJ8-pU{kki)v^q>v^s@uY~Gu{bz1s>tE#PLIA z(VKX?$7LyjBrhL+Um})$wu|9+;M6X^Y8VBUh-TozC8GDr#k7T zNlK!8g(b9Gc?jM!r1l28z0+9}?OeIg7>z3rJC6N$<5XJ{bXh*#pW@_I(|<{kGVo1e zY_8(IAFAoF=Z9?;tA|h@=us=(B%BH32vxB^d25}skU}-ao7Vh1SRJGf0{AUX`Y2vQ zDBZ*Flp24se$(1n_Fk)dIaXSTmc5vALFU9!ywf?R}v8IYG>H$ zQ7tuu)EGKGsY$%^zM*+F1>bw9DQSjd_uP%iHLGxEWCVAXFYmc#tbFs;mvL_NGG>pS z2ez+9^2Ao`e)JwZe*Xhly#Us*yN?~m_H!4oWM(cfAk$fIO|#-BNPiO(x_$e@&v z)Os_sA9sv;d#US$KNCGrs)Er1g$pCROv#T!k83?Ps6TSw z%}O71$Ug;Jijp8EdHb7W$cggDy+P(&b8C+ybDVL>MIL0#>|*mnIsoN=vWHPV=%yz= zmP&b)JdE{AtUq!7B!`#ZLcg(>71ML(l9`H4-v~y1Iqht!;RVjZsNF6X9+NyD_)Q;4 zp5wtohp}#K94)bhFB5snopMNh?(ubLdC`45UVJczR%#=Qwy z&9WmkmKQ!g!bAI^)TL?gUA}QjAIoK}lPQ12+oU=(S)v)pD?bbTH~;BC@dAZ@-GAaF_MSLhmTV47%36voFo%bcQx%3cnTCftt-X@` z>E~MC%6K|CFWqU*>QYkm%f8vl@>t7pH5Y^OOFlfYI8uj;;dt*?$S*>S8H-1!(=R9X za$Sct* zW9t~^%e%a7S?0mI4=S?d?TCkXMsM!(<47QxkG^(^#g;z}YPu?yv6RF4!yBE<5hY5O zY$ddqP;ax^FcgbhS?h(zZfV8HZq$~%!7Dp!7+Dtb!*}{JHz&Q!V@F<^$79W=Sp4G4 z^*HC&LZIuq3NME~xg?U8cN@31#gkH3FtgYB@Gd*c%m2C#?VORUQO^gwa@kFpe`VLrOXfe z4iSmGY{pt2fUuuPU)(a(zC~X9K72TOgwj2hw^Xb$7e9}SEG=ej-0=THMx`EktUvMoW=A z6)=63sd@RPd?aNVs>{jcH2ueXD3l=4dSV#s>*7WF6}5#!}mbecuC$x#~}aTUh_xhh(0@8Hjs{ z+~O~94+C0gqKTHu$HuX%m|ngN7k2Kbs?x4<;Jss5e(R1hXvn&k?f|vF1!J=RgcCQ5 z?31!y-XHPXWg%nlO}1yeiaiBKaDHj^JADFSq*Cppm0^``XrKb;peFeQ|q~+jv*ix zR~>8`<8iUv^-h8*R6Tqg5`J$+*10a0zX(+^FXm;IwDgmeh%rG9y6J#;W$gHumrvjL z!@e6Tgf0`iN}SS00^4`2VJVDH$E&#o`L#S(ZwT&JI2Sg)K~R*|3*Pfy-EIBFI80sl zELzuEZ_u;Qm?XIk^;wyoEEDHm_RDS}Z(ERkmGi@I)!_wX&ABv!&PzX%eS3Bi)^gg8 zWyRwp`oCtsl9PuloLq|y%X0e%myR~+%3e`~<5%%=`E?07MNhbu>}(P86B)m4A03W! zS>(H2*1qOCA!o}(xD+||oH~PMyM=e}AB-PA@ye@MbA6)BtF#kJyNjH!eH{kjulTMp zoW6~(fi}2Tgor@9lZ0cBdMMqBoq{%C({qbUbZXSc$(BUps91n#A}O%e)^M@^}P1_4LtnXn?MeR`E`Y+oi1rXs}n`>5;8ljyI{yy|SeBoQT`cJ-w{EdrffB)S$@b|wk zaGWIf9(fNt&Rq~o=K3|w@@+V>21t))NYFwP()y5z=RB8$R$h<$TEBp&hZ9JhTZQ67 z{Ty0PbQ+9H0q4rU<%9A!ql1t$N<68hniuqH1eaHEA zzw@V#S&nqZW0~N(npKmZ0uiMKKl3rgMAg02OF4AChWYa`ZYunlz<8g+T0LICQ`W>4Ks@kM`z5#jruFa#aA*uf~x0Jd<9t_gV zKx242vNR`4pqWCkqL~Ue%0*iCc{|_5($V@!>tS{)wv$phC3i0l%*qvBh%vEsyYM+Rj~i-9dQ){$hL?V9nsS@IEOm@A$8mY1}gZ79Edcebo+))^@4ovzuS`jxTClFN3aUKq2aczO415>`|D zZE10sS37dl$oa)jt2=h+?nmo~4<8qwp9k^}Tc#GJFR3~hoy^Z+>5JdMl9?PgAN@FH zHg87WX!e{&9Qj#)c6RWebx$Y6W8rVf^dt`Ukf+T@7RYD|LQl9|C^VQwKC+B(@6gD_aRxk3?F;u6WG6hZ(s3BdH9V(STT7EOK0bRHto+T zICZh6T>O?62Wws6XL=Tsb9ENfl$@z-SUal~5}WCCOn%z|)%{M24KFc_#hP|ygZq|c zJ2Gv}*J&Qmh&jxq$CM~9GOsd^AukH^WBq!p#QSCQlSks$t~M_JfTYbso%y!Oor0%y z2EVdWI9oCy>a27InolyOWsJP}loq9BXW=fIM=Dd^GOZz=?qu>*G>N2LJV-R%_lXjh z7r}F@);!;_PQ*F3ap{ophO@-L^Jz=sgSh(Q=dl;53LkHQ`f+;GQs@>AH(%X^b(}|h zB_>WuKZ`!k=`h)}irT8nqzoa`Cx~rNxWqSZ>(Y88I#eB&KvTK6tXf(6fSkh8SR=!m z1rtRmTA1cD(0ZX-#vP7WIfkkYAF_-wD#$P4ljUN~XsMSRTYU3#-T?&}8uM*zKYtNf zBgM(P_oLP99Vn8l9lwEnCr@Gh)$3}ZRFY{#|2(bBb(5&tw7^Z)ng)(ce_7;s@uqP( znlj}gM?#n*37Qh5!lzuwU>TXbja{eDV)@h^QSu_jQ~UQ-o(^obTDa@@31mpH!J0V=*`4}p!4)0C$-6sDJtE^g;VC~uuIv0yFsI=R_ z@#8t>=X(!Zhtv)t-H?Np>gV;4hn#IR>efh5>r~bx@@{{AIkJ2`G%q~p-+42|@w*Qo zL5>SMcPz+>=;^Tuy#CL>ieo2FAYZuz2k*ZZBhReG&MjN9ZuRPc;!fKc?mBS-+s|D@ z(#p#PXnrx5Cf9Z`S{s$6nISwCZArMikHjO+g;+PK`dy1#III+wBpA?}N{WITSqjr}(7WsEL70JcC$zozo)kkaySvL2n@B7fX=z}&3P z`~)X%j)Qt)i2p+d#_@%(lFp$y0JFeEsM|ub z^sNnm3AlWu3t~OcjzVr_zHOg2?LyR!=3vatW7^j8DgWi(wqIKfqvyYnzi@BR7dRxK zgSB#grOgAh=-Fsz*mnLB(k#O}2Oo&!uv(sc`4y}lpFo~Ty=U)U<;7^twL%-Ht`DwB zxn#`Uj2lwew#$)ZIT~}tZDz|_ z89wp+w^bjv7L~M}p)p4iV{vo$V|B?dN{o$MvQC-j8mMh3U>d{&I5bMfvbb zl4scc`(MG~zyGgrXY2lQL3ts$u*UYDzI-3rU%DUo{N1?!u?O(zqYn-o zKLFf+_z1RK8U@;9Lr%+M*u2q5{!U6iJS*9mNcv@WyJ3sM@jMCDI)JaEJsYHl2>F@s z?uGO1n-=NmzO6Ye`-|~Sy`9mIN2eNcMq4AH1t^ZvWXLcN)tuSq{vk8$K0kVh*N?AP zu`v^#(WTY+8-ZJhD}7|DeM{`56WX?k(P?s^zrYk>FdW} zQqfqDYg*Pb*AT@@?s-`!R4eozLwW}yb7zTnik2vBvw1nvXp9y<nAeOCMj`ge8V0ggw>WAKV3mdLn zLpt9^h6d&_gdBNBa$f^2WXw93i? zV5xv*UU};>r6R$ybklj$_1i8|laWG7BF4W>TbfOIO!%!A z_D!wCWlnYIm@cs}Mne=!abyZaph*YvCgft{cCk#Fw%gcy@-)uu+tc@^?RDeh*mLSM zHjZ6Y3#D>`*JY*eAq=yC0pgb|xm`%1+L1s_l59>L;yL}-Elf{Rkpq2Gn@oY*Pnz07 zvs<|Ivutu2yC=_fV&Y|rEJ-^X7(;EDqu8{)=j0jCDZCaM>NU^>$m4}-t{F~SZvxcu zdu9k9j``B7j$b6Ri}Kx+ECWuRDn8#Y@q2Xj$mu=`LL$_g@JQCPjn0GCzSgh32bztU z`lwD@Ea?`0XlwJ_vZWZ?x*6?e1E&|@wDPry8@PP+DgfZl=ncGg{3IUOw;$<`J&Xq* zK8TTJ%La;ncxDD$E{!71GVD2V8d=`xY}O{?Y;OSJ8nFaBht|auu3hSBpG#P>9OE2P zPg}aoQq^}tYQ1#q99F&gJdgvIzxY#_-MFKSMdB74&WqLOB|02qM@>kp2%~RK>V_!IbJ1al78dd+$#gewGcST;&J_~PWVFf5~F6M zjCV9Qk0bynVpFGn)_y0@nvhAN5g;^v~ZdhvXD= zU!l@*Zeu)~=HlW8=ybk~jhC+AKBRrUk!so0H1amTdBZzYYjH!I7gJeSKZm|z+uf{o z*Zs6=fkW0axyX$s33NSD7}|i5gRCfd=|-crSmtemmX>n>4Ok`(T1MN*8!29U{P6|Z zuzl@~Q+W9w{u;6@$F*x$ksldD`o(>C{Ij3N=Jo5ba%2UT4-dwFA9?*vH0S2AVsffn zV3u!_qEfT%H&L~rxh(=+tLH!F%=(fNJx7MKo6mW*&W`m54~K?NEnlV7EF!fw7M(u( z3;6*8e>Tq^L(*|+-0j60XIEit{ag3gQEMPI9jHQZ2_-z^MBQ|W<^K(@L5^rlADMu&!iE+NLujsJe zXy+VNiPi}=)!yb6+uyz4-Sg)0m>jyDsmz)A%vD|6xk+MpJC?FiOVD4YtU9cH_2Ez2 zKIF}XvKB(@T#O5TOOxJ+nyQk~oSp-q7Hz$Poq-Qb=-anry+5=$=`v9- zAUssGKaWZ36$u)kqYkp)ahnJD1l|%C>7rdjzu_>7iPumb z0q_V!e`50^TL?kDB^KbiFRW6I3rlFywMm)H~Hn4F~zX&NY`H-JFoh0zZ zsSx1S)1)p7xnx0Z<6uCRMf=Kw{ICMZ9sisI3AMde)o#|Wg%iauc>?$^mUKRJtG$3ygrLx)Wej1o?T}enrzvXcPO~Wmek(xBrl%ZzSla;Rj#H6U_2Av`s zrTDfsPN!YAL0(eawDU>rLwVhE;#d6$U zy#iA!SK!oL`)ZZDn_PeM6b^s$RUAKe7Fa!urH}2xf&czX`1qrbA?fqASR^C2Z)5eu zO)Q_fgMG(Of)=I=-7Dv@@U@MaXvdxvwJXUsz;mM|)S6#}t%6SY;u&D))m{;K4q)k( z^H}rRH!ytlEXKe0Z(#D^Cqz$)V`oW%ee`XyqDG2L!6AIb&P{tGAQAtypTyKd9{BJ? zGD=ILbsoLvRji?k2(xehdEN;fj&g~Q?XnQ}54szWdLrGOl8M+PE@uAB+gNGQnhuD? z*k=q=5%#yW#?P&rY+H|Udg;5Y6*#+QI^hokBH{x4A%-yAivmDv#PkXx`VB6EOYkAOFvjFBPvXABJIi*^*U+EMGF0bzXBRHw??8Y_c{(D~~Os9K+VPMFT#Y)9+pK>zvb&>GF+UNjXzc zpO%Zw#Y|GnBmClU9*Oq$u)-JJ-cI+p%Z-paC!7k4-KtKT3iT%KhH3}8EuJ~D?puEU z@^Yd_NEJr0IIVvfG`yC2EM!sss>zWfIi{xkXG6Cqu;Gp8FmmMz&VBChVs_QWzS5{d zJ%frybTQG`Bc7KW-SQS{Y|>%&C2eGT?$L3k57V^k&{XE`cn*Yf*%bc3DT2lTdJ8Kb3red?X(fk5sOekaJ_#0@eHcAoW z3$j$4?@XmbPwnAmUd^MqvkiUiRPoHVV-CqK_1M%dvgV~_!t2jk_vyYN^?)4RwvYJw z!}4?;udPp6O8REUW0-F_5_2bxP;@vyZqiJ;CFFS0Yxf1OOHdrS%{rW}2%VPoM(mN@ z0Nq=xa6T;ZBKPoOLGB^8msl+!4=cp`Jf)VZQOamXGRQ>y4(nZOL;B3bbBK`gR&ze+ zz&u)OeOV4~J0Iau9^Va72C2(s-z8VF3A64fp2~NxC92f2Pw<9w?nz{|mM!MZy5acl zMd~4`MOl>Zt_+V~!urE6V&(aBxcb-+U~>PX$dj~tzz?x_Bh{O2J$z`nw`F)z$FbIs z7lz5hG&x#BO}-tCWER;iPbze()DsK2obDqCy6-a zg_$9PXNe&&Z_bu6NvzB0Ooy@Tn^9!Qz`UNDt51vAxXNyLfqxr>-|u+c@;V)Ny;gLjwG6-B89K z%QwX&6@c9|3dr6O#-!U{rd9mbw>pQ$5l+_|EeyhCoHTwC@GEX}aGB*FI=P^ewIsA) z=cVYM;*dZ*7h$_A2?_Ue^IOINlP4PjrEiar0=k}LZc+Z0lag&aS%+He)WGGE;jRC0 zjLHd>X(^E^%2|rM+#<|%m5VrdLv;>%tH8a7-$S0Hm|kAo%5rC9Ii|bZP`YYz5<_$I zSUNrHyo%V~XeDo9(VNsPJ?8qMvRUB9kS5gE{ut3U9@f0pl{Pl=TM$sz)pV0NgQLQn zOCzQM*@p^Bo0TqdGNsl^%I~3GBv1wb(yS1g3*?qbS$ldxMN|D$r035kRXVWl459%< zH}GP^bc=gY7NuI+ZD4%7zp%;s*u(1ea6ONN2*r}&nD}Ueo@wk7Y6?z^-B^pr+qT(I zI6blq=lAWxgi~eI2R38p=byygyLJtT!+yLWH6}rNpoz3C(xy zTQ{-n&F8V~;z^7@`2(1I_)}(H@{x_Ni9=EuGAoU`{1)`7u_Vu79(3AO`HassmK@vk zY%aS!w>hk{ahucEF@>X6Vq<>ZO@q<-7C}bopiO5))e9a#Sz@xdD}1n#Z1I zoSKWu)FlJe8+y9U;$iEBy~DPQ*Sqytkh$~Nc=5;96unV9Oy6ocn>Xzz>^ZiKcCJfI zST1S7$)wKVrBLE>Z4q-`hURgSqS&~-^}=N&2{7MmB5O3O<#w~fV#t?em zmv|uj4e?u+TK3NHJ{AZzF2`JEYRwyWlJ&}bQ2LBh^0JP38wo(KNzOY~SE@<*dh}xH zzJ+2V6#2?JVW=(Tfo+LDrEsb2VLFM|G&lCF2D;B_EhV3G&C8ym^JClW!!5n%ar0(i z)26=+Wm}Y(jE(|xbN;iX6Jyx&_CJ%l+9hG2f*o zvzSO@hosa=p%##TcF|Z{LP_h-EFZ?HyY}JowyoW&qf*X|UdHIvtGMyj8C>|&LsvoDm-@7}c=SH`d7=F}9HEgkMT{*l|avH!$LY`t(9boeC?4#4O+O>$Ga&Clb> z_Bpx9n&v~G-h3FMycnB{`>19^61@R5D@sHcVmU@&e%u;gY4pr49#RA>OYtQ{Ul8$2 zH|f6{^NjOZ$uE3A-dr7%c+KhD^eY}qvgMO(OS)26$%l2EQY;_P)((loV>N0SoGiCw zW_m5ka$rAKp5*4!rdj-w7AlK~!s`SiBJ??*p9h_~&mmDh9JqA^22YAN>q6Xy;?0>q#3)_SEnJ7wB=T;nTz8%)qFvVj4xGXW9G^Fy%71f zG(hrGsX;wH$+}T8S57H0{^BCXAn5=OB{@){{%Z?_X76EW0OASj7h4j|dSzVQ`GeMF ze&6+VgvYw|FD|9D?Z|mp=C`nh$b+|ust37!TgNVsReL2Xo@AY#qj|l&?U`<+=J<-0 zZo2o`zIU5)Em4IWzq0@9ahM`}my<;(vcBawNuc+)BxT76b#hLMl2Hyb&|TRURk04X zH)-=a48I#iuTI2fcFr%?FR}AtrvcsKPnVTZTSA29o5Cfg(%9R-Xn@<^jypZR<(%Cw zMv!Ax>k?Tbc0TNPrl==lV>yP06ZCQJa#216lIOt1i<)B(k6*%uLw|~uXOH5>z0Y9u zW8V`E-yQE)rrvkR5EJzim*mwPPdJ0HJItqMdkEaL6|c}`Gs}iCwslLb9M0XmgA@PH z^8kQ1o_`e^Ha>w(2ex6;4?cx08#ZA7&Ru3G6v_23szTqJ>7eQ9FEVL{e&O zfHkv!5L)tV-zs6SwE+ z8L==f*1F!#IWi`hhDL@^pE86*g)wYu=NgNcWcso+Re0CVWnLS~Iaf-UpQ?0Onw(*t z-YGHpat#eqbphl{J6M6Foh^+_R44^{%?QIv*?m2r3jiKfwV}KshFzG?CCDa@DN7$N z*um-5jR(*3if3LLvZGezOAZsAg3OgwES|)kdBBR?^+1p+O2?2_e6u7cF)466g$qhr zt@y?P&XMjne4CMsOB+jwvdDC8i|F&p6gShDT>0Tt=#WD(W>_f@;gD*A+Fa96N?lSu z3(jNo(u3Vvoy&aN_;r8IjT`&1G$IT7D@~s=KRjjFT>ImO@Adclg6&`0NBAlIYQspO z#psuYIRpTTU$mf_cfzE|ao=0-f?&g$eS2|X=MIxQO1H?z{cj(^n(>M9wa<1_TU-5> zd0`4HA}mvDj=z|L+MV0n z3K!~;e8yVlk&FTaqHL}yuUrF6zwJ$8Aw9Q%kF|!Ze_KmZb6R+<{rY`5Ce=Fs{gDqM z%|-ce$n-Su>Z^kg;qDScO`*Sf`LMX98&aYfLE{g9rqy#&s7F1$$~ss24{z3PqKziz zF+aQnXYSh5nNJ3jiCeeuXJ2~`$1ZfW{0 zahb&)-D;+B=N9JPc^Ol;r+|-s4wDak5=jSBSlmjpxWrkKdszQ4aab0|KB~uu&5MpJ zOqF7`qFJMl%lx?fvgzkO?;)R-49C-zsl>UE#)aRbCWLfm2g>1YXkkMW1-q6;iKDHgNJnz&KYoh z%6!H7L#TOdJ+sw;Y#8)}=2>EEg)NbmbCc3yn1NW2o_muV*nZ}ss8L<697%`kQ7`o0 zek7NCDWBdQU!ML6M}lT~GROAjyb#NUts>o}cITVtX*|%)TU2)Wf@C;lkQ=%4(%O=P z`x>!Ylqu0O&6PQR&N0`5)daRq!^3nT&Pp9OUz_;(=|}3%Z65|nlHzYs{_;td;s0mv zO@l2tuJo|4>fZNWzg}K%ulIe$+E@u<5dp44ayY}0N8(s9vL(la!?ME@b|@6#usxP- zML1;phr^OXvL?bFhb?OyR*WTUJmhdR3keQEf&__uZJ^P61KsF-f7`uP{!#bT`Oe8x z_uluq0Sw4@5D$HCRaWN7tju%1FY{zxoHzk=I`RGX)J-gX|2>qgHZI-u#7C=KgUoky zHILL`%knc~Yz>?4!B`kcdt>=BoZPt$C%11~kUk72fQFXXI`A~v?B3KrIFbP_gPqC^YQqa+7Ehbcki zx*5!(2#e)7K)cen)zh!y)b{tXeDENT%hKp1E58;0=QfkLBpI6$p3Wme-cN*t>~`dI z1>UaENAIE6=B*s(CnxJSIdS<4#%5*%Yozf5GFG+z8cn4q>FWs5R?!g}jh|TNX9N1l zeC)%=AxDk?D_3GMX!{c?Wm)~2l>}|Krmti2>9C`B)p83t+Mt0vOZ2m8P1)uuT z6PR4JdWd=smQ|N7V{~>Fn@_!u4W~aaF;f0`Gqu7w>`X4quUVy@)S|#9Ud^#Y5u!`^ zHt4hEE;2`J@i`w4$?uJ?#h6{MsfH2D;#nE>0VyKW9CZ!Ia_N*8a9@=&EV8pQXuM_a zlSfKvde0kEQFPYC$F07K-*lED=0OV!+!mcg+S;g=o~19G6;8>soUSclchY?oaO#e= zZrycdNx~9teW8&#vM`mku&~W{PhE7hwQ7d-+*lFFO$mOQa|~28&(hT`2KrGB@l*m2 zt5!`+$CG87kJT2YK5Xzy zs&xk5{ms^gPiXH?snhXq?UQX8uAfa`n(y{4YpA_-iTtFe%(_^uKMCAIR+BiO3M>|? zwf)F(>^O1^3X)WKDyQ4qIadALhh3Pq!NZ=W+dBF&uVanh0|#uU=abq$X<5}KeQUNy z)U&=NPlExr6s4xmvc+^ z;QM(2%eDJ4sOB`*iuCJ6lAhmmKdvHgIZymXbN!pkv^cc-D{7=1S<&jcT|fur!dKN= zR@O*PZ_{t&MF#Yd`E8*C&`&rc9ah_v6+xWZv8% zwaR*}tu;t34r}IXX?2bDAIu}zCxYsz48EY2;5iMgx9y{hTmX50T`2FXT1J0w%rYcf z6Yr<(lBou{*%L~YFQ-g43ML(kM*?e zL2p9D`Zv@mfV6Kk^#{o*=4KY(c+?g91WnIRX#R}WSc7Jd;?cTCIGS(Dp3=Nh=Ih0> z#HhY8uO8Old4H<)>Bp*u^~=pU*!Nf=47he<;WV`M=0L@CohR;f zS@PNUgZ?WFDotD4(je{hgl2!*p6Fq9ZXRJx=uK-D*WCt`X4D3%k8P7-rOAJ!cBff4 zws*2oQGbV3dXNtajZgG#4mxLcEzDHxaK&-tV6F^or8zjG@gJK}SDxe#^7|!b<-(qa>bvcl`*QNL9}V1>g>$kc^+Ej6fr(|^Uzpe1 z*Z}=r)_=^E?Rc~2qS|X|;I{s{fUS#d?+o%w%yuK31Uzd^Wky5tm>nCb^O+eN!%L4mSnGP%n{Q$Dg^L)O>0o4f4!n}C^9I#CnVzmL>|5U;_q-~F zj!)Y@sb6K`YyEJ-t&XTgS(Mu;t=TE8e)}hweD%BNj*a8oLtpKi{&w^1`HLMv{dh#G zYcsyHK7?(8T6({kg#CoI)to-nxu0CRdIdjt@dcorBm3J=;)!4Q4A!h%In=XFl9eS^ zT)PI8z+G>=g_W1D81La@bo2l)@l|~KwtChS^>NLmRXs|}dRCZYOeH`2-7;cE*r-3n zcpOeEn}fx9mg%#2468ZG|C!Y`j|}xCwjb!VSS%X!eMr}*6{}f(7I`GV=jlrvq(d`@ zi1>KK<5N`FjHA5|_1ApvK24iDY^1Pt_<(Ojne>+*yega%|jPm$WPJmRB4fv8^2*Y%y>-6X?g|9 zM0@+g=oP&$dISS?3i}2!O7E|h^kmcmO>eTvkj8Y|(s#`xbN{zvoXxws13vdj((*Ob zY0_S!x<~qH+86?PTf+AwL_lqz?8Ft#l`6^UVL*-!fEK-XJtM7}T**zDKER|*MsGEt z?|ZzR;$iA&Lnye%THwJGKDK`|DHX_JL7i$NlL6YI3~Riwz1GtiwC(w%4ebR|&%!(d zh*hW-{ad}arh(g_)|d2!(@$Vme+#U&=QeM_Pp`4H@C(>X`L(5N-z#AIhG^~kX6(=6 zww631->#n*Wl{d($j3#XBl^^wcFVcq0F-3Q6c z>@5DTZ+{D&-~1QAg&W9z>kD||-}^VPf9I}S&Km$e^Zg%Sbb1CwnJ0Es!_al}OV`v= zmpZ%^mwW&w+KlAX_eJ#Aw|s;TJT_(;-tT=k`NOr}|9y;oZ~~Vf`aEvj@o?=y*efxG zRlO7!ODZnQ;=m>}6j8&pCak~bMp^Q?nLl}^W_5{ErUbXCzA2B1b!ejf{YJFbO8Zlk ztLmrtmM0c`Js7hqkM>XS_D01&a@7Xx`(F(4XiU+o*W6AfMfq{9%cKQ7zVIz9pKUue zp`Fa6i7}|#47rpqpMk(T4nHR`ai$cpJrLVhKQUE5U zwKn`#G)z>js^*cK#X;X^^i8y!X0mlbH#SSTa^jQp+7>)-E)A<<+u0mgt@ZPEW8oZ` z^N0B)Bb@WG0o;)X@fafI;$B-nn)G`A(Q3u|KbwcnX)q`Ewb%M8Q`De)3CXYCqjEq= zqx_S@XX5z=d#Wg(dBq5+W$qVLg8FzySK34PN^~loGU}3YwaCPthb?17+qyJQq_{=; zv)$M%VedQ=Ga6aE$w4+L%Vy>RIul_%29H~Bxw+lbKdFZ>Zau(*`&HGdj9_FYh5J!D z2k|Jsod5tJ07*naR2kd%$PaT)^OFciEXtzXsF*b8 zO6@J_GZCKBygXL(TBfDO`NTRgwo36^{~VflHKVWo+?ewo-a<6DRzDx?(V*fPzj-`! z`Du&sHO2Pv!8smDYkDoi*UGY@6!Y5j{ocA~nzp|+iywU{e{0&Jk)|tMo-uE>JyOP- z#oC;ox8G7*YcJCFY3|*FrCQl(mZtjI@;#20^R;Eeuhu`duJ#0TA0#R{s~t^)c6h{B z$eXP>2d7s5%Is%c9~lKX)kT8P`FD)?_^Yh9PNz&n0?7Spn%a1_pQuX({Xc_6^211E zkJx%iNurP3kFkGbMJ?m7Het~C9Zr9?Exra({-ybx)xA#gi@Ysc5}o<>n>SL{np6J~ zyV0WGqipicm0rxFW!5D})>~bbt;B$?AIk=F-BR4DTU{(Z>Zh%3u|elP0NNuS{$5=x zbD%TQs@t#CvllX2^KOY&r;DOjgOWxBTeE^{o?1$kL}%wV>@>yeMID~yYB)3>^XE8d)|K6y(8VYk=L!O?^0I63u^ZaS*>$78EHJK z*te#KA6U`x*?&Bheezh8MY(-amcZ<6^)CQS9DWHqzxj_ay>2Ux{L0_P%}vextsj0E zvh=?BF1+_!zU;kbf4$>yTgA+&53!z>@uR<1{S~bo-I4adT6DWz%-oy-Zp(GQm;#;2z6*t0)I-suvO;-GDRP)BY&V~V2Hs`tAtttVc~qCwBQQ;aOF>4UkW z98w(bbL4ko@d?+mAJbDj$GyY)3caQxxqEJ!LFaVUrzneKysTU@9{o4-^rmY~(rzMJ3Q4&@eT7QH8J<;ifr*7R3e`(4 z>ISjk)mPT)#WbC-H3Q}*v1Br?zbEvpR}9W==gV9v(pfA>_u32=9iVo1Oj?5~wOlKm zcInb=e1i5ug>__2yq*>yX3((yjM}u)UUx*NX3>`6+rSdQG!UjLxrE=H%)zQv%BH~7 zvd*=vpVaF`{ka5hU8vx9k8{lm8$$QA0ssD^q263ne`N78BQbn8(m z*Zc+vJ7r|)EiXQ&Q%==ArR#eB9s`Y%KBYE=CkhcP5%A)51pd4;*LNj9x+gAQ&LQBP zY6@#42%D$d_#7~~hF)99lvGaoOY3@nV|9+CdOtQ8UM*8P?)=j!d{0N4mQ#J=(G>xK zLB4KK8otkYFUq3a4!Lv*c>ei?^(v2}nq*kCXHie{y}^2TcpuR+OLVPmVJz%*@Z?J; z19{xD{k2dNFcrKu57mG7CkBYBp|Gxk%;zf%0?Nw%+< zir3TowdQBpQ$`pxrrJJDvmf+6Z#cs2d18vEJ)^K#nWsN=%7fW;ny$jlF&FPIP1x4k zHOY-Pjp_6Ka7{n#Gl<<S^$ZdqN5jzv3Ge1J$C^b@y>?PXfB){gI5reO6@zN`1ua#%K=T03UTTyLL_uf^Or z61MT&HkSK<(kR0(O_}|Y_cVYZgYZ8&6}n<;T3%$IOJw!W9!r1mn``|NuC3ny+VVEcAUGp`vWO}K(Rz2(G=IQwxMZ=tP~*S|BH zHVpN1%_4Kxr*Y%ddE7j63E%v}Z&er9FUN}i{44nMU;8q4Y}!0@UQM#>#tq!};wu=x zISu_42;NvEHr#*L>o#zRlY@2f#;h^lh&u?5(Axw$X1x zOamEtRQt4k)C($3PuH_N%pzZZP((DA{nMf$ z2V7R4eXwhRHabZSwa*E1WsF{7Uimk#SGlS(s+rGDZRLGS@>sXny2AEdv}q(L^UWba zn(7^rYz8+F)zrxW!YBIzNeQEcZ8Nq|tTx9N`w5hBb_Rl$Uhe#JnTr#x{LA zFOYt=ERZ=^{8_%Y>b_$Gwr!u%&oE`#7Ln80#S#_B>Q!nPE6f3v1?rrHtwUz6+x{Kd zH;;&PWuQgJx3tj3l~pV8+~bcnzPoKFPU4=|-l+A~*}fbw8$x8wSmq@3&^ADEk@iDt zf4L6)TPQgSjA9Nye*AIVSU$gvgjw&svb51b*Bu68Wsbo|XBtpM{fWBV5RK z+Lm3oXDYu^k}h)n^p;I{>%iRuYj*7P`*`}FeG|n$`5{Jr`y2SiFaI*e$HoRe*H4z- zyoo2j_YBH1>jh^k%GE=^cpHuNgiW&v7B$;h(*6fx!laGTz+BTgT=A0Xn`0KAzDpZh z$w!jd>%RX)XvGFnOC9*#TkQlf7L-Fq<*N5rRI1O(OfYlf2xlrY*B159h(?^Esh0jq z%BMX(V;{3+JWWCG!yn%%LrEc!RQxZ)7IdL4t_da z=&;6qVd7g@;bgOLYgFNpIccYZ-=2V7nzl@dNc^6px2CR3O3;alh~)V9mm8zSrRcs? zd0I$;E}sE%QkX767rkAfy8JFvS9a{#5o#fMbC72f43PAGB=`{z`lfdZ%Ejs?-`HrW zp|y}fTTYEB8|Yz(f$h^xec4(DTRS$)^8W1`7dt1@D!IAuiIkp#r#WZn0=-kOtZndN zB&p?)ymRBC0bNK{3U5yowba==3xC&6B8j6-7p)7Up`BoeTD}rlYzJWK1QaG`IXOW3 zKfg1XG{}1IN=nqT#ESa5Es0yj*UwT>?(2oAwNQCJM@_(p+SySEI&mD&|Lz~-`ak|2Py+ei`7Ck(zxeB4 z$C9N>FtKbo+O7V-GSg31Ub%w%UV0TH)3Yd%p@VkqS#%nfm*6YkpbOG*NRbWdW>4j< zJTE5M#cS&c*h{l#wpg7pC%_&6b=tJwP`@g=So7U~i4`w>59h!7H!!_pKhSQ~9!+yr zFW}LzlyCh4_ue$1Pjb-bQvP9cvuHX?%CK#tY>=-r?kr7S5x=ooSbc0B(X(1^ij(7( zu%-6%RZZpkRM93yt+A9Ot*^gHWpfe!kk#11;#oh|vp_$OYx#SM*twR?b+gat8&Rv) zjJa)2JkpdS+L3KXa(QHlK71rEJf)_wCu>EO|r=>j0>g{LFybwyKW^ zM;1%iMLIo+`ZL#B%Sw^F{O(js9`6k!F2Bp{$F>F7K{D!}$`up5V zqeJG}O#F&)qpBX=-lx3Isf7F%m2O>^Ul!}41fL;g{jJ|VU*%|n)=Ky1XK)lb7ur)a0|ys{0dqe{1)`O50itd`l&7ig`y?=|~&Z^fH%g`E>)x!s(1Q5J=z+XcS= z{SsY@6Un-BSbgxv7`=QRryu_-AD?mylxFP1+^7uFssC0_=Q%gyK1L&{ed2965$|e} zZnul>>>N&h>nHfLf9rn$#z%lgRk{tgvynD-i*Hl+4K9AyU|;-8^h%gCQj8P5$5&x23r{a-l7zKB=QNankL1M zakxoV*Hl)2y3QtgE@l~ENiE80>%$;``WIDwf7cQOh4u@ISMhUZwq1r3Yo$tqJoPHi z3dovW#X$f$l{$mY4``TA8{J+&HT$0;Xa{*ix*?&B60(w8)?BaBfCEuwQ>Su?0%taF z#M^h>*;wyAhYn-wiIY8l(dpH$1vw+Q%3U|Xmc7VG2NlQn7{;T5lswSSQG+r9;d_w7NE=P3IeRP+9p%{aGy9hP6aj)#Bp0{BO6 z`1b>|UdwhNzjZESK@aegcguEI?XI4_FB>pg=%Q@r`2Jsd3OAN7>#JuZ$9C<+dt0|) z^~FoL@1@Fe8B^=F<97Dj$Y;dqQdB!AT`FagrioXi7|%b~Ul-4}y`RuuaF7EYdQS~u*LG~& zgfD#hQT*vY{sFR9hWr)|7XyG*moDRh7hdii{FU`)H2uL|JS)rJnLD#3w2@dvc#ZjS zIy+&#cZx#NYbhS^^BtB0Ah~X9Q@9d_j}1-l7j>!34)i&VZ`9m8cVw@TdQv{4+w)nE z6PbGpx{$m}`ph*Ezh&{6XY^Wb#1lQIx9PaVI7Z91X%yT&h;OHop+wt4OWO!seELeH z$)tIBsw1m&<7U$?VAZtGaQ|~QOXQTZL3s8-AbZo1|LMNX4IQXP9!+Xu*s%Ei$vx4JVIBvixuZ|_ zn{2dWf(@9r0A;WB^~rQ}OIjONq^8@~DsF4m4?(KIlc&D^woIj%8W{JFpz2kybuiHUjF>g{7k@yb8@Q(XPuet^jh>+tD+@b3b5 zt_J{YTE8Bxe7HrJNH(1L09#L-L~FLd*!5|2Fj7w?i`C_TZS`%|o3J;sr*NnKEycI~ z%o$yZEX{^@?)2GtUM>3lA zoYA(3-J}@fbRXQUf!dmj#WE>Y=5Hxy)t+g&PyC#h=63R-&%-|Fu@;abR?E!vnf|%k z+RF(wb`*Q75cfUiP0C#SJG^z|(=v6kwmsG@wNui^Dm2QL&i)n;=vq{sFGqX2wY{?0 z7?h{HC(jMMm1Qn2cVt49-;Cb~X_2)J<n`U_Q@yYQ~aF4%Ey-|sNkHti8MpxKJ# zSei6V)=r<$=j7dFrY@Sg8H=cXocpjnIC_qGNJ;DmkmX%@i_E3;E$J3q?Qi1Kxj*r{ z6D}9oJ!#nt%vdX}Bz!@_iG@>kp>|B)oW4DIpKOQxW@QbKQ7+8W{meUc3wOVkFHH$u zt6UFu5CMjGf(_#m}Yn@J)BrR zGF(~xbQm@dPT%B(6ag?2i?-qLAD;?lxz`|h?a(`T;eY-E6#vVQft_oR|NXDl_kQ^+ zU%}c{tA@&_NmgFDf=8cy4h1q~1>DJBsI9V`5+=3xd^oPP^+q;;TlsO^vMI++d4k2k z7B@4dw7JVQn^W|jW07?dMOU8nRS1!>5r>0mKAE{Do>TMIbczQnQQToUog!jJerY*Y z7uD3a1GhrN>{35v`Q30FdN@C)n%-_{wkh22EDlz5%r%y`&+`|){q-IB9EWcQn?7ZJ z{h#C7#LwBWla?mPDjM}ZVB4Zq|ZJ=CR~CV+*>OkM+0DE0>GrubBV&c36m5 z7Hly(i`fv_LQ_!@8 zP-pdTEiguJp}^5SyYRur^_U$U!_@eAWBm{B+k;cvwqWh~3)uJeq1x8Vac6oESW#O{ zonew-T4r84Zg^%vM_xZW)P$#XoO%u(OX@G|xX^da_cVP;X`}vSpUsl~Xw$?RrXxx7 z<8*4Ncyu?lm7g#1^-?dd98Iy0U;WiyZ#NNFf5&$3!kJAQYt6c?7N*CS)MdVY-@Rye zI@o^v1U8*|zgHibgOQB@!s0YqfjPMJa#_{YnN6-&+HTBEs}txoNKnwy$z9uVboZ{l z<3ps=Zllv~V|H{DFFx`R9(w*o6lGbrhH_|aXAKBr-pPGS`&W| z?w$2*y!zmMIPlVIJso8HmUa6ovSHoq_~tRf7$V}<3$@G<-@e^4tbX(1`HS+&maA8R zS6(TR6$N(xtN#-K4?*z0C~~~_*&Q`TJbk9}K%D}u=`QBbHWoKp z6Xx~g=r|4elWlWAW@_wPMX?s&v*;mhRhVb=bBYqskV6wUu$zZUmtSeL?>Ao)p)c_+ zjIitsyv1}D19=o?J(u-5mIIdX{Ws+m8uMkfkJyJijU<(2>Y{g+r1hRt=MMNPm*YpH ztx3w!`MS;{H2dT>gVA`XSC8t$rTHGyv?^CW9naO}ifi5}1m+58{?TW7UY-=q(r(*i zZv2!8r`0BHqHX$b(?H7L2bP+NxE59qPh`?TpBi7T0~?OQJ=HwPg7DrTqaBei)`&Z* zHE7&&+TLu6Gxyz}0+E(yuSOH26+IC%RfMj9m(U{N`Un-4^5lnx3a2@Tbn+=f-0n)H zy^&0pv$(&;lPI8ck>TJGFJ+{G*%_Gf!`=5|+LkV9t%0_6D^2-L?!mh}|70`VNqdR! z>1=yMQ?`533LJVXZnaed9DZv|sIoe>b?si*axxu@MqpO!1bRZh`x@&r_Ro)wI8;s- zexrcysJ(T3Xjr$xk*a2T{&=+@-bD+161{G%;1k@ueMq5OtKN@iccEKgV|RP8)rR@5 zqCwm`a`mUFH9SE#FR=aKAZ+WOGIzhp*{AT!E_yG@qWmn%uswSaP8s~n;OCokNvWG6 z(u_XCSREbvoYoWOoc=DYS&iAz(V^@2>i_urxU^vu=hwG!WkrUKfAceV=r4T=+dg;S z(0Me;)|02O`r;)ly>=55m#_4uUfa&<#(~;)>4_0nw2L}3Eo6OUOrBHBhcJx@W7r5^ ziq;n6T5o~g=X`bsBS+uBjX(TdbieVpaPyu|qg=9-JfEhuh*$Agio~k)>Iu9k+bUfe ziR+vi?n2+KY@!+phiIX^daFUOK8}>{t}23&gzTG3{$Uf32Gz ze{3Zeua7Wi6tu%um4h&~T|L*RgcsD+!sV{qs{irU zYUT#~Q_`*aB;OR7T8j$UbATm`Q?*i$A%UQ}=vG4dk8I#%X6nUTN6Xsyy+mW5IT*7k z9-;i^ye3UHLjTVJv1&bd8C~1Z*Q-Cz)%(6@4U%+BD31{>x!vuvcKeyNAb)^Lj;4kWBWesuA#ZT2ut*(xUc-o(XU0OjJ;m16_dC@~!P6O_= zrV@5h7;W`8+eA;<*lf2jTa?7ySM`#g*Y3J&ozPw|hRS-niDl59Aw59@V&wOyWd19! zTSPfAx4j>S%%4>g>4O0G%Hf$oD*b$aDly_(ltmG_c@y~2kL)SiKozt-di@-(-0^ED z^M(J4(T6AOx0?M0GcUac^EtZD+}8&qW@ZGIE>HhmH9fLt7mn`PJyh+wfA|(U|MaKG z?pTM(zxzx0@-KaBN`V-1|#r^!1yKtJ35gOkY>a37HYA7tbgk z=29uX=bFkV#%KCm#A6lTacyi{H(?nrHNt$JHALK}bgdC{-V`@7LhJ7bW4{-nOKtgd zL!-sUC8hSBKAq1_X9O6vEmV9@oe$F!UDIdn`}Cubc`@i;%a=v77U4Gz%JewYbKU4o zYDguQXV+FekBsVC)@vN{e;r}m8uM?>=4W;6THUx@Y2h4Y@7G?Wwrl}&`hP)NYpTBs z>(}D_ZCfxmGJ?yi`)}l#S~`xIB};0}?tJ4dj7-nf?7C_lSrrmXUv1|(x_1{&Zr_HR zOP3C8kE!u-OpT9YdVCxifPHTt>a_&WLI*$_B{H&<+=pcIq+s}}rF8T$9&aA!O*~Ye zZMORSE+gBiZRKYSQs2+@v(MR)m<{+I>5>ZT!H9(U5&MHC&Ku=v?Lc}hvJt8eb3G1Y zYoUV{3cPdYe%xHP6jvuEaC2F6AG^L{IRK#BZlTOFY&rQ}uaq__ZrO#5c*P^i@t7N? zvj-6hN!N{ae01HvW!?AZBi&XD=hsc*<%b@?J+Hli)@--;F2uI69aIl5HL>l?2W+tZ zb_4Xxl2IJI_bzmA;TK8)U~XgtS0^SQ;pNqlfA*crVP?Ae%;-qHY4vPsh1Ji-KJ?an z>Y^;lhbv2#0K3-T#My6s3nSM~;Dg7$j;p)wLwCutk6X1yv7>Of(Zznt`#{Ewp1Vi< z4Rs3j)Tu8m&GS+0&oDBxZV4{kyBh5uT*VvjzKhR1^f2=F@WJ#uj~v66yMdC*OUG1EZnt}AKUNN^Tx9l+FAg6X>DN008Tw^yITNUQQcvS~8*D)MBSXNv8){g`oh-_=~23iI9wVPr)YFUB=^uIBAz0 zMQ>-ePIk$sxJRUcD;an!#B{MqEYyc7gWFcqd7y7o%F~ig_35_@hQ-&hxh{j~x3^u* z&!qKI=U_i0`B#Dnc*~04aUPp_KX&=Lx@!HwK+rWQTebqo*>;jb+V=vuV+^t=_E;;xXWt|lYR9CXP7G0E7ssumlLNE8h7{sI}CCKh= zfAUxcyMXS2fm-$|Z>_y7^h-cMS?8qfuOS2(?E6+I!0qHWO*H$nw13=Mfc7FWUzFP= zSFZvmPTUG!Sg0)g*@c(uQK4E4d*4zwy=J{n6G8JfT5KIq;_$vbm>C-zO4}Fz{_kP# z`V@|wJB{_*?#JHk+kx%dv3ge+3J$VW{j~>I)t2c>UE5Yv4f-_rd`5Ym< zC`db9tgik|PZ+bU2zXED@u!OQg)mxci9V<_eFgyXnJJ9F`x;jM>;D@c>_33(4?P8p zEdd97`^f;gQkw6K2vzJA?>`vZTc+U|fW?e)?ooPOlC|VkQtI{0q)T(;5}N|DEpqaC zd%b-=k*`e2e*fUjjB0F4viCG!y<$haqQt1>qv;8M*M3iR_I--4c|4!?tF-KXID_xm zDKz14@hDCiATz0w(#3tpBTmZ&Q!Aijw{TDNW2=J^nLklXwQCl({r)YZ@oEhZ9mjy2rHCckfFl=dP;9KZP@Ld+QdJ* zYncPHOJ(0BrP22gGilM)K9L5RNIkrrOSfp~|80M@Eu#5(Zmqh?b6%5MK|8}pnP}dW zoAq`2wDxI!`+Vl8KM73dR!aAo^Wzfqz4^&|nP=hi*el^cf3>}~wsvz|iYAIWN1lt4 z(IewbP7KQ_eOi`m)t6qJ)ofnRCa>z7_ny^yRjgU(k5Vqrw$^j_R*lfQ(2W-b@~p)3 zpZ*j&4T~!)FJHl3Z@g9O&M25|xQsb@AAY>Dj<&B=At>TYnT2Qdm0RVkF|JvZMY&y4 zmcZ1My*ByEcTu!QarRSR!Hq3@Z@G-P2jAY=oQPWtN^h-#`hgUWsjbrgd+%ev+YKj` z73_?RU~Y8qDPFI>^EM8?aS%Jd@Bkk8Z~i()wy(vCWw&R6f8&`m*mv+9w5R7Vhqm!Y zU4xSB7HsCPjDq9ybNSz>6?rLFnQQg0Z+$!S0P|Gz1YC)dd%DhL-#_P(%81Wps z>A5n`aA^NNbX)%PY}HR{zW1GXF*4WbwOH9(hpp-_!RtInA!|g_OUHXB6AzY|u`!eO zj)QNTx|9Iq7qN7sbAh9Kb`Bk|%`&}Y2~KU>imWKH=g?u4K#wW&mQ>-`)e3i+^ao`f zO?{VxIh(liLd04DYel_HjBtnddUDPBCYuf>otE$OP9^Ql@??|Ow3bc16_+3L=F)v; z9+!@5o!cpE9@p;mtv0$ibjLotw{6SNYXksrZN&;4-?anRCRSia#Roo!i!&l$!vGC8XW7 z2I&e9V7(V3E`Qgu!_r*!dFeOL zv>-Y|s-84URA~#0nPR3*V8ugYts&=~KG{sfV*tmC%gqZumK=Km5!ICer3LOfotM_h zP69=x`qqnv_bf5XRy6?GoG7?$p%K~jd*N;Q(@Uzz5}NMpbJm!4@B2M|av z=2n!adC!wQO-!dc)cokeG@#3N9)hRm5ybQ}GNXe4aTBQUrp~74c2=UVCGjG-)+KZK zG>y37XakotXe>vr6Q-T4LFO7szg2t4A?S85R|F4)jdWx<#K)Vb3vs*eQBf#L>*Lx93Sp{b6XxHgO30u)OWbKs)JoXd{ zIYrFwKG#42c?YcTwG}IHzQ@{H-7dDCI8|$3Eso2d_EtT+fP+f>UsVU|LAiaj*J*!C zJ;K7EemWi^uiJe6qbJad^2wCz*Maxm`?$48<#zU7@As{g;lFB?Bc$nZo%IP8RnYaU z#Ic<_2cELs>2`7O=n=f~Km9)D?p%jm|M6FG-xnXny47puTlG-3oj8fS+r_ryr?B+; z4QQwmTV9LUbUPd`O)+AQ7N@N@RdQ@YK($4qEsfq2ddkPXn{j0tU>c!o)H(OC!1NTx z550m_-~T4^(GiUP%HPE7NE?h6eGjRgwiv135+!ef@;-$_q&zyaOQR9y^VHdHo=f?k z*1x1@eQq#!BEpKgya-7!s^RNR=->Oa$j9}sgY7M;5B4bA>S^(cNAhW%O1k1PtD=K` zVpBDE)J>|!yW?9j|hGHP8rM(sHaT%XeA0kR{}+X2-j z?gjG|&k203QVS&LRZwS%j2NX_LOqW{`E1wOC|h^oG|E|}&3Pndb^c=A<#cTuv>l^J zDWe5GHCuSNoJ=G^sd_4M;k4v22hxqVxeUW~xt4=ON{soj9j%`0l+=n*-{HRNb8Xf~ zN*Z38t+DDM={zUqCp`v|+@eKS9@FXBD87&CvwYfii)?__Lrdb2Dxd{9lUjPLZe*6p zWBJ)2WOf^Bp$wQL-3-*pE7;NsdfC~|ERmYd6#VtRZDTAeNqyz&~#QWo&j zzQiY)^Vach{nm5_j>ib|WzLZ?N$R7cXY{#+^5-V5yeNw@ADMjRyV&rPZ{q6i2XOwr zFQ7XbpBlIj9I;UOaLQskm!jR&$60o#&nrG+3}+c&f#W-O;Db%W1<73f|6az88#l52 zZ+sRT4h(lPcR$(v?h#B}zKRkV#&1qx$@Q7uuS>N^Yu4U+K+F35A~Uy48ld{DVW@S4x$-=K%?}%Tb|6q8*<7-|LQ8EKJFEA#p*9UCan*1uF~bh!g;5g z_+sA4IJ3IT{@rRDk2OY8K25}l%b*QBbF+G-9D5k)pT0k?PCae29`-F|F6VR;G~;My zC~Rp!IYxR6vU>4-U*G=q*Ab_wJ^y5$nqs!Hwg`$L?M6YpXEAfDJ{6b8s0s(TfbwMB zigu2ZJGPq<$+f$&d>PKIUx#+LgYCypAS>g(>z@@lw{9J-O{_52;*HO#6nT#0yLJq9 zn(at;4%?5Nz{vD0DxBYjzKI;V;ZiO24Vnx~3k?`W?$ptq-&LM89wzw}aKl*VE26Xx-8@F!$~EXq;s(E&E`#0m?C3 zJ@iqwGaTKq3&(ctY}|a?Pp(c(;OfK#R$jV{9Y>DUT2%a5w$Dc~DU20(euX7Y=kbQ{ z)-zi+;ppyNiLIEgoZ7Y(TTh(ClABZ1W->a2fpbJiiX~F7#RvtM9$$h}+qc}3o-A{t zBRH{RJ9ZyB+?#W2k=Ikatim{Ykfa`SuwU0FK0222(MX;Hx9}r7i}F#+`SZZ@FQa(l zG%nr!1TNq47>f4bjk_WrC(n*hXp>*;pJ(J7k=R!6Ut%BQ?OVzcbCkHUYB+3k?$SjZ zfBqoKH$TAGR}bLsJ%cx?x4Ku3G7FXpx-U9l`(^Y@rkYwfX_<)J(-?5st^zI~3C<7j>{Pxon? z?x$%~i*_^_;8pb*Te_?-tE8v73)(4->i?F|dI*qKAT=o#wzJ_GZ1U_dNgH|4lM%>_ zP8{H~6m-!>2Abw$YuQw)4Ad0#vN^Gx8nEr;OUxj<4d?H`nn;chYUW{|*2@~u>T0DG zFP`h-FdHqM{!Gc5mLMf_KNTmCQ!ZuT64G!Z2~>^h2UDM{H-(Z>8GxLPRJD|7Be@j4 z2x)sX|zGUU`s8tRdutQVzui5c~EPolkb;Kg0FQ#>(f zmml=Bn`i@t2Zjs?#D#OvhPJNs6%B;eppA^iMn?Mb1`A#w_qyweVlsv=POir6=xF^e zFHWw(iS63~03&mA812lWK!(Y)=aF~(grdF;u~r&tA|O}lUoER^@BsHZX(0<}*gI*7 zc3c7Rh)Koz<$mJ9LY(GjkF+n!Cqw4r37Yfh-+O%-*$^Wq#UAX5?8KVdW02jlSc&OT zx&d%-9Yp3jbNJCKFQb_2Apgtv;I1bhyybxHcBg~&XV0QUhCAMR8?E{z8~*94R&9lq zR12E3i`eWjtWU6u*OD#`(w2Ps(P8hY;aZXXdfL{U8)I(%UgfCY$IhO>#81D2k;`Xs z_BZ}BbT)16Y2B?;3*N9BV%cB%dy19RpR;X`da4g`wDh052?XJAH;HHzK6V?@{k~-dwu8BEl{;Wd0n9)v+mMf9sLnYkFJ! z7HpV_*f&3h?1(O4ai{$ZSk7z9vn*QL*`I8io+D#*}1kc41nvca(2t zT23}PmQYTqJ&R8(YN6|}c|jI3<{2gBr#85(HDsP=!>#>Ea5g~x%Bqz(wQVa(0Ig0J zcN}~ND63Pn1vBe8!tzvJ|HQK{rnTzDHO0~ejfRX`DrR#jOT9Ho?UcQ4y^Nn1v1#J_ z`gUx2>2v+H>}M}DXZA9wJ#A_+9-khkq+^=BIQLD99Q1^0<)&p&qHK)Mdviu2vawmx zRh(GfLP00EqwZ6_SEPtRO0=Ak$D9p@&QV}?$tVu*+nu~`|7MroxQQJ{j@La}asa9@ zlMaB=j2Zo7b|<>pb7|}r39DllHztu$M>h4jXL&#;e@@AE0686oO@wS5*FitUO+mOZYtJnYJ<3EUX=wCrOSfwBa4 z-5USh|Moj*&vr0*?mWhB&eWc)gEk=|@n$x(s;sZ)NzIDh#rp0^l&T_&e67th0N4F!RT4w`m)d$P*}M@SY*_edxkvWwMpl&Adh!&;Zq7guafSkD0cSRCz@a<$FDRgvWo~2yZ{KwX z+T9M;zke3_oSdvJJiU6$62|TAgP&Ja&gX4ila-vG%$G0Qe#0Iu{Ve(TXRUwIviVpz z)xnpU&Zp_sm3guVSbWcWeMT@jx;VFC9p2r)cX)g^KrXDC#MtyKMyF<}JRL9kr`|v9 z`K&L%eQ0XgQXJiV>ze_+q;o~~o*yTwr@iCHzkgEESL$6CGX6hFym|BH3?G3zT9n%% z=g*^f;T251@-EI!?8NzPU;MZ=0uYbSINjjqQojYn{M!1p%w1Ea2bV6L=alEYA58;+ z2g~Vm=kV_LU&fL@KaL&0@s**TX?Hr2B$2q}qE{+;2U( z={wM7$8M`0L6?ZMdWWu!3VPmFzyH%((Ku}cq6e9gCh7_R46Nf6l0!dYZ38p`!0rX{ zX*Ewtn`+FR-=>eu4G(tKKQ=aTo6QGa@d;?nX*}t$qW!FDJ^6ppGZE5)Hi%l=yM=Ue zm)laPg&23+uh}$KVWNOvluJ(%Yhx~{kEb7Ua+ChVbhTV1Qw185?KS0-hjetP!Qq`8 zJYKxXv&eNeVFevv)t*Yh}E^hsw+h$X7Gua}<+u;bDG>-(^EJKm9| zPE`7CyWVu5ry*DRA$`E!Vj(sVlKoJ+)1CjHMeF>}Lsr z)_Yf0PM|x|f&vXa|10knSas=2uk0#ZJ%j#8hK$jwt~#OCt@RdLDLv8et&8hoAYWeM z@|sn(Zg1axC$3IRg#Bo4WCSli^Z)?hz$>p|^2|Bpb9Q2qTfYh`sZJdes3-yE>_KJn zPJ&|8KSrT&X^=MG(;PoJ#a_&#l9--aITodV_SXOQik#JbJvF*e|2?m;p#H-`;pKEQ!jUaJw8Jz0#mD9KWi zl4`q+F%8cYUuJ9FbSfFZZ`6l(rJmbTW2R!6$<1PYAbkh?94`RKwUJBbu>9>8(Vo76 zD_{OM(b>GMhx{x@QV(E}sgOMl)Qsx{`oz;Wl5=|BqOp{7S+16u+$^oNWqFBEvj3D4 z)HJWCOulCGNb8b?_adK}mc$zClb+*R^lj5H{$*Uux;K?;YvJ*1gy6l_DOVoMmgBsd zpR}Vc#mPL1^~A7r!=1&=8Rd;2e?KM!_c8}(%VG7gZN%@RKss@F8Fsi_z{J$`aUe@_md<&zbrbkOe;3wkc;Ji^q_&(bOhZq1(y| zr0nz^>i>OD@*FvRkNxaiI_JV|to}pO`ZU&e*zfjVTkc>CAZ2@R;Oom9Ml5r-d8PhQ z^zuHDEtQT*i+y;Gg#)$Qz3(S?Y^#4s#E*^9*;#Bmev?&DrT9zZ^-RZOk@Lxo^aA zC-WR)i3h^W(BhMV?A z#eka9qe4bv95Bt?D>F}cUsBTZT1(3!5j<--D{E-$YB_y068h!YPb`ydO5co`nGG}c zX1%H$GOCB?;`X_WYO19)l^W?9;R}zb?X_X7sjZj%KjnC;A&(W&ihEl+wopIE8)Y>> zTR(Rp2hv5Q~-W%Wv|xOA;i506g#`m*+xwEfi&%Xf>U4&HMorh4;Jw?hu?--qSbu4Dbw z*}5!l<7zI+p5AZ0L2B1MziyIiH*TOPORQYJ9CMvHoWFD#0I*^0TI3DCYQ^QK4*ojd z^JA@ae~UbKQ9j{v=@RhFGbr9Xg3EXP0^S%s@SzqLkC@0$49C6ur%QRZ{~r6Rm}hz0 zmHJfgUy9l$M|S?k@@1GBkAER7kqbA0Q&+Hb$r9||x@}@$ks!9+IGd8 zJCMz8srG6WJ)gGTlJBLw+s|l6Gu|nhuq~^S_MwPF>ywHeO8D3-^*J2xXzxp2sbBK_ zinZ~0#d=4HJS*xv^!F**)5{${qa)r@kdnnzRa(Xi9#3%zyxCA|Qo2v<@i;A)2iG$3 z`m<$^oTHD!^s@mmf6mPFS@NVWou6-K)Hq%VX>11Is+g@>Tx9eD;)wUsU2g{Z{YZ8U ziTgvTG*6$u9rpa$4jOA3WY87JlY1%P62A;f3YboKvQi30t{oq^F zVrgLcU>S76ne;6i@-BU*1^GeP+!-)FohgU@yj6>S0-8l!k-nWA+M4p?vRU1xdLmH= zZFK7I$f}=*wUaK|$6B2(#-?XbEqk|Non;9o)O_AL2WwYmu~iRw)trYo4|E-U=|tdg z6HkLB1qDo$Q){5*dxycUFCFPIXkp2cXRIBt_Qg-&TKg5*8S9$WiAME`|M=uEcDOdI z&7QTQu%XPddS`J7U~GC8?amyOR?3u}oXR3SSat+Y^>Y9^HX40w?PfDVB z0lf-jnHy{4`NuvL>eo+RyZ-?0#cNo9`W#vvwV$52T-k%`OW$7o_>$HfMC$Nr0dtP?78n?$>G;=0;O}c0me`giz2@7*B-7_h zcZD@h??+noC)BY%_N_3{XTGdDN1LwnTVbAV+T7fvf7DLCcKy>g-7AypQD2B`n~r2V z6_joW%%H#2qT|R0b~87YF~*v4TWj#99r2!nTRl}%$yJaz*V49BGnb97_2V*JqAyAM zjy+?cvY{DT$mkk+?ZW}p%s*zvM{!}@TB>FB)X`nLaDByc0Knw=^OzYQ!|3!3)}1|H zTOzAf4j;5ywlloHc?&WWIJ|EUW|oXK*0tMe)d2zP&Yj2D^mKi%tZP+ihKWn{ zWTeTcw_bqnq?;r9zX$D0-2P3^_QMI*w*j~83p zr2Zo(z1Zuj-I87;?<3mC9N{%zx2a|0II(j(j_=&j_x*@WjgRBqeS6XFbg=2Y_mP)+ z;DBzpR_mmFU+0b(lj!@3-c_aN^_44dV%K)Ozh(1KI!1D2ckfieTFZ8y=T>GOUdE+2PhxW48f=`L99n+>STa40Z6{7* z?>q0B&B*=~F!2y+&^B*POt&aDabNbHo{d@tnwfmKMG;=lk~>lE-1g0WB-K)pX^dHr zT+LvAHN|>n#V3|;GK*$jr5n0=Zq>3Z&+6i1Wqitr9edOiao7}1Dr@C$yawu9%C@HB zm*yO~-hAbw@rzcsj5KcIn^~RGZ{W_tR?l23rF;eE{xBLZ94wES&6BonK)1?S&dvY;AOJ~3K~%(>_uY*v zt5y!E-6vn(xnntyfv2Aa_UuRY*nPl@fAM;Clih0a z#luNik74V}*pB)qnr#xZOV7J4|5jgnboVZt+O~B#ZGU(S<-d3pR}O5(^KZP4uRZxx z-}FnSrg7JsZviDEnH=5T5gt0r>X~NhL9Exe-<#Kyxs`2eS{@3Mr?jST+oU~e6eaJ` z#t~SJeB7vAC-a+|m>>9-;gxc!Ilp1~Ty0j8r@N4&RwOrOWl~FJ>$V4R8!0cngQMnyI9kG9pySX0GnzUYP`$8h| z0Ng6z7n&Ko>+@P=ogm5R`(Q0#(rS6>{rN!1epH-IgG{;E;mW%lbTIKXJE5h|=qbB8 zW!0>K4tSmf;Jjs_NS@NRkXn{?%B-P%xPuP@po7Gd4Gpf=s{rbjk{{tw{W4UGKQ{Q( zE=p@abK9=m>uBxhEUzz3KF6 z-1FKS)wD{PV`Od)a!z>Gb3jtJ40>uB>i3&beVGR8?x&JksL3=9rlZlsqJMXs)~AWm z+CCFaTBT=WYW__m+UF7LoPJk3z{c1I+_8bR!0XZpW>F4m>ya9gxTx&AHcoY>)3SaG+ITsHx6|im#$Cn2xFMyA&LLQ zk~;QShE2C{X|@-OvM3*wq&={ikPeq$zjP@EYQ{wtbv8}BG7eU+lbN)BGL!cU*K{+h z{KR~QG%#UCf<0f%360V(Q^19VRW!r`%nY5(L9&XqM7v zCj5M67<&TlUyQ(fc}kh>H6_7SI|zC9Z7Htz*Z9CDT%K#(19D zct#nMV*g#r;I_z<8Z}Ew*!3O3-DAQZb7!li*R8)qW5r`*DMk5MQ(hL&_&4UqP0ELx zHlr|RjzVB0ADOoEBDu?kSU;wD%<6)k#mB6Po*$s?CUv*`#_GcSc0Q7!#Pt=+Fuio# zT$B9QoV$puC~AA!t;?0oCzW>5X}{CU#&Ki$Qe0g*fy4Xv_SNJ3KKUMaHlD7s0&ZDsvuMn>`Gee*xr>GGOYm>nC%va2^RIyKX)3wr-DJD2}^yx)YG z^{MK+^ofx~Y z-HhjN@+9b_H%@cl{JKfJaqm5Se?EL>$rxU{Pfyt?+c`G9cN(pkF11Y28_{L`pFN@4 zVlEEr;sp&q@0Z#ywOKb-EXC~7FcIB6;!Kq-ySi$kaZ`_%H-G!vc>l;rJp9)l$G+`5hOA!|u)XEv zdv(CJ{Hm1HL{9=!Z_qX0)$^66Ce2KeTT7O2xn)we>RZ*Lar>`I%9uTN_9gKK*`POY>R+bm0cYOOW z$By#$KG9;nh%4K*k3k$*%V3FdVrEK<{WO=!zMkuvK9iPi^NS_Q&8M9&2eA2D&C`)+ zdx?Ix_A>+jLbD#wU=R7RhXFC3o*f&*GoSAt90OFRV?Xm$^E&3ws=T{zFW%j^7n@F< z#yu~;j=b)Lg|WN0Q`mZ4Te%!Ref-n6y$mfU?SFP|CK`)kInud}iYsOGR5Mo|ZeA*$ zKhe39$Y&sU#`-DGjr|O=eI~u$RF2e@=Wi{dk<$IPXw5;^Ynv=iJf~*s<)2fVFXy9| zwGD`4Np4MYs$tZ28LF6;g4&?ThRX^yKhF~PVJl@>qT5@OXt!GEPS2uj_>CbYHRP{ALA; zqCinrwrXrmUl~0JvOL zYmM4uPA|M%Fq--hkEv4bC`i3D`q{Z)o>NX)7K|oZre*y4P9tW^I!JoO#hRPv=oUR@ zl%qU57&nQuqe&E{{<=)YDf|=xPZE^$EI+|f@Jg?31?OY>ELh0u66X7ClL7REzz$mm zm9|^kfbDAV@rhS)KxA{xdFW;?Ut3PP0B8qh30=BMYb~eI-Y#kNerPG{Lxt5~RG(~E zd{qlMiH?J`?Mc7Ybm@tmyYTj%cLb%VJn+)X*zo=tNPu?LBCUE^uRx35qdiUR!rHZX z{?mg`=smM>BhGBBer9%bW)`3Ov!{VxJ*soV_0%CbNvs8+1K!2Tt)pX0#+03=l+UT# zknzj^0@^PWbjNw99yZU^g?ZwP;965Z_W(mlNlao>VS{JKHXHG*zV9`S$OpG_3V_%h z2~oC=m-`W)SRM7<)k53f_B-n{0qvm+lL&S!675C#S(3q1OdcuDM;N&_=kGy&I^k!jAmd7l9rct6 z^%>r_WhgK^I)Xp{(&y%7cmL`yd>P9Y5cP5Q8*gIEsrTx|=~;}pFe^SqEJddA_8+yF zae%g6z>P?@Z&_|hc?h&0`xY3~VkS^nI2F?Q(~W*&VEQ};hwFLI0c z1pu#K*+admWkrK+=wzB-)ILgrrB<3Zvoqct$dd9u@2~9MYxL3x($FhRz~!3Y*)-Ui zYv_A8>%--6pV0p=JaF5WYV&4H$))+c6<;&k@j3$98#C8VnonG#W{sm(l^$$!j?xdx z)sB@28~c%IpObN6Ic!;DOtlbVJ+ypjW6M6$G0C6HcJ(Vs`h?}kV>7cDot{m`fVQ1- zf%%;9nB>Z%iTYbdBECh|YWM$iFPp#oYKP zPVC-}6FaugOTTLqEAZ<5_u-)zUPOT$j1IK45kd?C$%x9+|R0I=uX z!`OE0Bu1v^>NlqUDZ|mxR@R@{Rx_6cxL-GkO`F=QSmIG-c`sXFz1EK>$8$|E_w2tB zKkrvZu9>u#ZMW(^x109{EUAS`F-__>WrEq-fx69Fz@@dT@xmhy52#lv(w{b-I)i++ z;$||{%XUD1qeM=CR-BavSh0PRI&r!=5TzY?5*Fimx>TTy%c=LEKz-N3Evty$R*3--3eS0uEHG|D3-iP1#5@TXJ zhSR<#zPf)eAItzgEQ$Q|ha;y?1Fcqx2Oe1D?w=INx*aUJ@E*p`9mmNp{yUgnyXE%f zJ#;$D7zRI=`m-pn2>WRI)c3_{{Pom#GY7UTvhpK`?%0P5lWPao>hiT~n3(o!0vZIP@+2obur9JeWL zgdNhHtd`cF^8#_;!yVS)@+=cmE>&q#ByC~qFFZKix}%<28FNXwduDGvIw&v851Egt z4$SqCXu>UPxm-U)nwhfg)4pWOGyS-09>FZbS%cwxYm`@M?nV5+%Aa|3w28Z!qkEq0 z^<=wK3{ltl`f}AbZlQknqR}biNuJ0l4F_ZJ%$VXjJ$-voh7+|i!^aNXT3H_zT1?BX zc#nLy++eWyaa%UDnA)wuI(eQe`Ff6!&L7!y?4vY&JbN5*@O0Ko{9anS>S@c5rT=7* zLp7u%=GN*bJE{}2=3_%-0yzm6LhKKvqM>odR6G>o6M zGqg=suV2367wp`sWm4=Ptgp2k&+=}IPluBi-g*>o6;UprQyC}`L<=VS{}fonV-q(wvBnPuSwHr zYg@|8>S*DdVP?|tR0CXvGLwsb&ghfvK*J4!X!>Um{IkNPNO+?)a7^gfm~prD#!QEQ z+wE}3&49C~@~Dwbjl1M1C)KEF@?^g-*L_`ODxeA{lyJ_XE<@_i|ISCW?)IAgYn=fb zO6@`NNzO(pdoa0bH4YwCLsj6dd+)-zjqA~Aw+99=y?)?cUD$j74DNjMV7=reT8jzd zUF~N!ZN!@g?j9;Yiqn)?1_{na@Be(tlXav*-FP99X`u}F7G1YQ8o2f82k!sTJ!=*% z0rSAalWj|ut;z=!CX46J=TK)U3+t*&tF15%yfn({MUkpi4c1T0* z1Rl*dU|Z_+!XppkzL#Ic+OroR)9mRIh6FuVr88_$``L7&n~viPlWXwmgZD2;SFg8} zSGqDi@YS)-le^93%X`vqaT-naVNA~~%A)+d$smuZAfNqHI@#;-Q;Lf$pqH}kB)Vb& z#+^QRyBNxrUAlS|-~P^@0swyhyWhdrzWx=go=4#JeJ{U?b*ImwQ?`u;_H^y^HzwFi zXbpUDw@1*HfNKlJpDS9a1l_l|zb>tjauT6SBnzX?3XZ{Ey?;pp^eUD(~ zjswWEvNzdl@l2WM%QjsCw8eKlR&VOx*eD{ZCH zrASfz{CIBkUO7c<$(nLw>}z{o=4zj&XUm}DNG6;tuC%x_@8N67FRG*TiWWMg2heTj z=(Jn7vSt-tdg#H%_S$viD0Ut>R+lQ$Mh9}bpOjr-{=Zlt(rvZy)5jm_dx|j2Pak~* zKxK>9oWF>?(?z?}MF+wutNP~@K9r-2LwokmJ78O6YUwzB_+)iD#*^Q924hn*5GGrn z*xLdwO|HT7j||?-+)obg-Gi)KVE3UTkl)#g@U>10$~7Hb%%OoMEUgy9PPpm+2aTS?l8O7N2EV4qdNj2xia~Z9g8;f3Ay5B0tx@RbHc<*kUT%dhu5^0kz6i@jR z*mB6P2B5Bo$H_cTvnY%5Ns?|Cn4K;#cKIxJ{^4)q(jAZE)R%q(bIVo^d^Y8avBWb; z{YOlS@_gEK?sfP)qGv2_)fuojfAwoTpUghCG`33d`#7}nOi>d{?l>%u(87>iMcdU~y^_AI}tmg{a?!M0uX-7h`+ zIR)n3ibI>&q~)ZR8S4N2-G~b}@!<42YoQ!4<;k}qv4v8d5#CSBj(IQFB}-bRDX-zA z>A9x1^Qp9#@qs^V(>x!L=cJVMPo7ci$=JF2yD_m0FFpLwg6jP9Cg(P+!yEVCgS%gO zvmQIc`ri4Vr;oBjdSJFJZ$CLDyU#D|Yk%!c=lyY*fjpfPGhLUSp`>yJ4^?Sh?WUfe_%jex{ zRw7i8^6^1(_TmM+bnxI%C!j`>woy~M;qh#0&zoiKs#W;1L#J={WtqFLxT(5s^RRxGkywfX{qy~N z`l2k#hbphW3jEIR08c!D>}$UW+`?f4AC{k=pQLlggVINOv!7(2r}reC_i-Lm`h2Rp ze2|XB+6*I|fB6dL{?%*99@>J*|KzLq!lRE3d?qVPwC6gQ!5C?&>nzMFZ4_mdM$jf+ccQxipjD2!%2zP?mK|1D<@nh7Rito1wQrM^BC!LjoFbwQTB#CFXqeQbZ2yA z=$}WN8yUgeNVTi+{jHl(<{9pI{p}vTLfv!u#IhC&6s-)iqw@y|bE6}8_Q@yksppUGp{X+i`ZodQ4otio0KX6LT1;HL$_K48GV(^Hg@}>Sf)kY-nJc#=+3nCsyFq2k#qN ze=oD6qj>Y)yRrYRcd-8S2fZ;NC#mpadr3iSy3NA(Ee)Pe-$mKVZ`-M2M|bZA$_(3% zousk^-c)0pPs{L*E|L2D=pFRz=+a>P0>*uG=Kd*9YB)b2z^PS9$^NqYIleowS z>R8sGpOmCWe#PHs{WFxfv1}<`dH8{$YEhI0Zca}CDque7bAa zMRJl@w?~fI`tc5D-BxE8wgu1eVs`V+XF$)9j+TY(bJca!_hHiVyRhw>`ftDVuDSTV z-u$=xnQvqC^a;!ycnF={ccL{SzoC*^bW2vXj#Zygtdc>tG1~K$Bp1Oh>e-bx3Zg9` z3(ZQ3Q{m_Idv2ccn{hL`>p30MaLWhzdr3L)(|kqKsji;erFb^=m&|3AdfUZc-!}2& zOv(u3GFTfQie7yxkeNDjPAQi|_&w#hnM>Q`LkIg-X+<5WO*z>e<@V2B^Jnz?Egi~_ z?F1FF_|UR=Nl+g=XcxerC2WA{5ps4Y5}L%VKE33lcgOKlZyXYcRTcA@U0 zRNpMcf(w-&J@Gg`{p@pCdGSiEp`GpYUQz#zaAW$8nx!mDWIZENmL-s-n~NgphhuH~ z#%)yfz2Ug79mB&*laF4MMY$dF!3V%=&s@R!SHFwxfAYWLPygwA=q?#PKw}t*d+);R zPGqn8jSfxEm|f<+tk05kDINr2y@+#JTb26T0ZMu)OQ00aGFY;*#GXU%V#kr=m_r*K zw2jA-Qy|&0Mki@A$LrR7m{)Er?*-knmOkRgd7a*;(|lt5pSfIxmFGz3PQCxAo{zR^ z+wbij_vP}E*Ftsh=eku)xY97|1#4&EQvK=XLW=SE4fBi+YRl2;{hi-1iIY3Gp)=CPjUngve%_@s(#G`o|Igl=M%j^M z=V4!FzE`jIeL*cKps?>~01fosJ-tk`hds^d;W8S{h@yQgQ>3jU9!sKV+4OSwhZ22k zA8JhN97~jSC|jb(6gA^nNX|^p^i1yyb~GCMT7?2o1=PO0dM`8mBVXjbHzM-Ae1$?c zySpw<;k}m`8F3>r;@v?dRwfK6E z2ZW7(22&|T_%*)oy#O5Sr)$`tOkNal^&u^K8A zi?}g%8$W#OO+0hxA$VT$4$(`w8oc+=LF_tm3SOa_o&2kj(bE2@L>bQ$o6kJ)h0md- zsS&j`-a1(X&*bx#H0z#bM>%bpI)xO|eR!dGdYW z^l9Lq{1f2dLEu+@1=zF+qocru3-`ANt+a)y+jb_|>`Bw_Ys16lb24A)Gt_MYxyhts zNym{;8VV;D;B4#k#En{@!_nppZv zO(`$^#g*!2rj^K_BYE{{o@Z^&p(#8dHwiZP$v(Yv2WHv(=or6)4HqwI=$|(D)!%{H zyAWUFJxKXTD5_HTy;A72zPuIiS$_JvqV%*aCdc4Wo`jx>KM1Q>Vr_fxrjw}&gV~TR z>EAHs5-hdNuF)~G^h+l_r)~A5Lu6iAnL^#;DJ3)fS-u{TUk|mX^iB;ez3nOUKH|#C zW72Ie#V(L!SCQ$Ykh2AE$TV`BdOncUWR)Ja!fU}@VQR4I0%WYG6T|D)iaPQ3oN8&t z-L4LVu7lniqedI(yNGd`Xluj8%^Qt2tA-}p+Tvho8#!T!V+S6vzP};Yd(~T zNt@J126Cn(oX&0Ag1hbQRq>)|sip?=_4O>6mv;1Z5g>yiMh5$FYfTUGwaWtnq2pkx zr3J_KKY(2)P9Zm+2V#N91rYu5_e>*z+=miCas^IrUGL}B7|2QB)vmB?fZL`HZ2(zb zm)Goyu~NUIAR1~9=|+@e%ZXc?#H`(EVLI8QdXln%uSg>WN(XD6-n9dxeZ5r$Y%9v= za>(a$Sg5N50Bk*Z1|dAq&U6&$5UI-Ox-WVh2X8j>C=_)e2}A)llkKfIyL~HWnwqMv z1E=}=dK7B1OlC$$uLsD+b>ZzxieAcYY3T6ZA?|c_;KJrj_rxcs#kyMLYjcph;*(CZ z^^dh&7jc`>4kP*V931oiZ9H+X z7J4pbnk&oQ@ySWN^~2W?{^4r?fcBOaWXd>a0U%Q>V(-!8XuUHDCkWz@DuRJ>cWr3e zOSvT=FFY}eb;u7TRB||)8mQfuVEBD51`AC_?$Ax;r#K_#XmyRQehfSPJ(nd<0 zXdE3qxF1uk_KC~fVjfTYERu6?Km0Ieo5(5USCDz1G`hHHBZ^)Io6cM)xwafg=UjkO zdv@YxU;14o%hB6UJc0vnA4cQUY%Kdm2YPX4*R~bO9{?_G+<>CzVe^OQ;g+-+Nq zVH4d2fOa&kK9 zPzsl?l)G7)skP~(GzwvphhDB6aV#8JP&RCz)F+f>V_u`@OrJ-9Q@eLzw0~vBoyxn? zAN4m=ui5GaBc-Gu2=He={3|^F=;LT@YQh`Gj-tJ#1v@ruEc29|=le~LHn~uZuj}KY z&mx}xtWnL>6godRkIOIpeS}pUf4+RG6Z)vyz}rOOtrO^;fmGi_kWD==r9g_{pYZ2>(+|tcb@tHy~CrR@JNY$ZM$Z3Y^zTw zOAokB>)W+ISbB5jCkgLLn@8fNxJ5LMARpjq+QDMqB128R`=}uQT@teV7&}GCE;RvL!2i)KQnLsjvcMe+;fq3DMmV~ zj1kg5srPxC9M%0D(yjxz|IY=T=%W7ebvcZ8RlgJSr-{y9xs03R;{c*vcz12uoa#Bd z-=#ba^z>l#>`lyW9jo$5pkZzf+fRR3aS?e#XA7SC2Y(~taqqf{y9WcMdG?wtlcKUO zahXoz%#ML{yls=-%eP}q>`J~Q$~y@M+v=m^p`^GBT5PMgkIA3eB6N@IBVD(+F_Mki zjee_qObg3S>DpFlWm_nC616oqpn2vfnI#Q?AEmhLhrv0SS+bm)`3SU`VSG%}~Z6BV26L9}Ox9V*6V$$_; zR=hqMY`WZLH!Yt&30QrVK4zMq2Y&Z=fh}8ruY3jAxf7_Z#liwGJ-xgvNlx7#vipSZ zHBWm!x^6Vn+U-wMdeO5A+v!rc>bi6_qJC>Hy4upm=tWW|KnQ-aGnKCE1wC?-bDw1W zsO$Rnw-Q4WnOcGSDeV3ZnbJ&c)zl1Gk&asl!oJwTX&{@y4$*SIVvYiogOWSNpOsBVzO}8nFRek3%d%Wdr zbG=Cx9=+=%J(o1z%)UYS5dM}JTk-=)``d=$`E?y5XDG8|gG0Zsr?Y`j4u+(&fznh` z+qQ2K}-Q=8~WVzBN0HK^7twW*d)*`kA-$DtxvhjU|yAWWNkn0wzp%h zu>q46oR>?v94>9#P&K$;sH?-B&h!THawv2hjCXb7!=2l)<;*$M&CN&GOQEJ}m7$9O zaDX#Aw;}LcjCFS*p90J#(M)p_E^OI^P3JC@t~dxw?`U{%0M~{F?>Q(H0Pb{l;LMI~ z*mU*+>SyMmf;IU_QUT+9z>`?v16X$^+IA)~1(81R%Y%z@211hhG+~b%H_$$9(1IHt zv;)0fzRneKkmNL^=czP(B@T>dsXV!drAldcir9ACCO7|?o!fAuzpv~fhBUNPQ-g{2 zwm5%1_+P5g$kk11PKTEq!kP{fJQ< z;bpF}1^~%;4w_@IoL@lQk=N1i?yJZjd=$ma+kv`Tmfi+U6`#tI(PD)Zs{r8)ApQg2eC>Z*!-V^S`+rlRm_q@o`$Sx&VdaW zOP=h3+jio1xWu}|eR4VaH~lG9wr;VN<0-8aPTn_La%Jxwx?2U1vP-|FWLWekB}E`? zWR*UPB0|r>yN^7Cz;!X-P@fopUC3tf+LKQJ0OlGS5V++hjXufbdmenxV-skEl^jF? zG=3(tV!`T#Y!;ylaED>wIVff_l^;$?zURTuWMaRF&+KVsU)!-D+0=xE&2hLK(y=yC zxe+Guio}dIJZ#?A9p<_YakP8HZ#l1;lz|k$&4ah2cdTnfF57JNH+3sdXV>iNIprt2 z)!T!!+gEN8fW*J1FHeSQ=--n(0{j}iD<3Yr(ypS#jJKkTM2LTBS0>w-5pTSW0mL3B zb*<7#P>V}T2*VJs9XX7P|Lp%mW?eh{|NINsy?IMTepil6+aoO&UZqv~xTxXgMRdRS zUCj2j;`(!6N8qLN^{wpKDOZk-bkCZ3-OR_PWpw|rP41gmSKXI-TlyvC&Qd@zn@w-$ z%`E|i0NG3i8LzV4;ud|leh}{#rIr(NYu0wk6vw^%=w@mSGo;R(c$U^N0Onsz!o5UE z_IgritB$aBl+A0TY!kkyl3F0pYHr_*Nard9N>jw91>}g5L#T5YWm`a$!o%ofFLboK z^h@O!FqEx&pTqu#C`(;aHUrJkM0rUbB*ze3>Xstm+9H$4KO zR;N%)SB^M;^fdo%FIVQBY;~ID=;fP~M#3i5Ev@-u^9E1 zJ6#*-3x*C&n6T)u?a`FX5e(;Ek6&dkl>%8e1j4!w2f4$gk(EnumL^)EeCMbLKj zG}zmR;@|lKnugY-O3&YL&C(LqjNYsmw4G~f#Mb}xxvF{NeNXqnL^4+DV$P*L%B7sJ z`>?9#&yL|0?{wY7z?@f!?Rb5a{FcE@G2p_~yp833vPpFPPra~iegT7*ui@Iz;EM2@DHO40WHb)T zlbhSvmnKks_*+Wq;XozL#@nP?x>q0EDt(4&VgmTnKLr*RfUkWm4%h~O_I9AJ54dsT z{uRG68gKa|v9ZZZW!`jY7JWv~@;L)proJdw&2^3p^keEi1!XkM&SCABf= zqZ*iAUWub^=vG<~QdXJT)O;5bq1#EvO}ebrwT-lCWY{{dg}&o9VQ?QFikRqZ$K8&0 z%s15IW?y+bb-unH^Y!(}77B2~2urQMd==TH0-TafT;$rrVg^%(gs0$~Bs zU0dxaU%AzqQ_73udXA1&TXXcKza=|n=RE20mPt$D^!~z8I`N}yY14~M&r7SX628uG zXO5XIuN*`gUYsh3KP?%6_7tqw^gDJcXM7~(Sw01CGIJ0m4JtmkqCaUu1#BlFwR@Nk zzEavN?M!fK(*_hX8LbVYy4BAwVBp#?ik^pyn>NObI|wn>-Gym(L`)@`ZfVAJOZxO5 zHQnr812^!o;lgD!%*@5tRe-aL5RMaKw7>VBgI)n(v9=c1*R6#Y_*i%03e=vtE<#Ln zw5>?MwxU~WdN6SHIvQqXg%~l_5nuz*^xZTi9CpO?+fS80_#sWdeeVq)Us=0Z|=FjdZN zr8I#}gPOWpw*}37xoxRy8k=1ig3D`ueYT;Yv~o5DjZP!{{)a%;gY(QLI5p{liS)g1 zeapd16lTe_j|q}(hbYsuyG^^umf@gF2kL-nG01kOU*KioZDj}!N6A)@`$!!vseMa!n=2%drkaZJ5Y6W_uMUQS=N76l1 zYkp6n9(#K`acb(L$r_q4rp^If<5xKP)U7hAHSwZPHq-wmu;wL_vpNhbc{vg0-!O(b%|bvj(Ozx)1`$?zDeXHk3{78rjZJi zi_IP)yrxcoA~{{iX0cGeG83~p4-kBW+BL2R%ytbewbwl`yiQ5|HovrlAHVxHo;ma| zay69~&r#m892;>5I`M4dP}U={Ovk}<4?lv&`g&|1+JGrPiyOBmF~7K&ns1R`+^1db zn%5(D0M}W5q5XNCfycTYJO|MIYP@}ubhaFid zs(qq#yyk?Yq*X-dNj3|S+aqfKGAai! zr+{V6>AmWUm>uwUt`pgSCLTA_q$T3mY~y4yb**k2*i)4&WuwT)}y`@u$G2wC8WjeruQki4AaY6 zdE5~emSxhXj$lIZoIW1RYf>YZyRY)sF}fnYXErZQ$yL5^Ug;P&)_`FgQvmQbyNbm>I~0yjB6#IZc<;Rj{Jp;?0=5Cbb%EvX8FFv9_+EQq3jZ5S9;NN6 zBM9}JT~FG4%#jX~8|m26t8}+|dvIyv262LECF*EtL4S8;|3~A@EC#P!MgO%C(5Y6D zoU?fxbPQF_0?=E+^ui}&Bc2){TR^{##9Sza%dT+#r3aq-Hgu~&-vW)dlG;`+nm?QB zXvNhH>oC?`oqb-&W^r-z#<;FEi+MNznkT2xI5ivVKC^y`BeIC1{_2)2ARqi3O^Le6 z=VA8%5zdD8oYc`F_`9XNk`T141wY}6zlEqR2=DW!b#DumCT+Q-&17|Koel#78E&9E zEEzc>2t2Cl*|IYMt!c=m0|V)l{mLnD38(Z|p$|@VO}dBlqn>5RiyIFta`*W)9!C26 z;UdK4jYEk+$n|sc2ui^G@}{ARlh>bgy3yYcHwe)*J%i@SX*5ktL%j{|@LMU$=W@8R zem&M-xC}M1bbC!V<{BGTv>bq(Z6uC3MB)9o$zphL0DaeQzzKQVM*Y}3AQ?-UMo)y^mnP>WyTcyt)jgJFUQ_FjHrS*B5{A8N) z>C2Ctq-UiIlJYU#no_Rn?pNYh{VmkjVR-F8S*~KbJ&W+i7m(>_#Ewmyk;$YD+9p^? z%MH~ML#5I532XBxW0{s~e{*76N^Jd}T|+5uE6F$gee+zS`>=2=x!0W;?$RP^uAW2P zE8oUkdnXp2cn+Cdjc7S#=PB;#NGUn>7RhLuoL0M_2GBL0)WGT+KjzB;pEytx3(-nv z!g7S|q}6A(zq!w9vU`H2ilvpoHM7c7)syF_EL(?N<$UrKdJg3QaLDqrSr3&#wJBGU zY;73Vsov6UP_EzVcCPJvdP;A(IacmWS*F{S{FgqJP#!Dmd-q453ypQSux;~wKjrC@ zN(*&$7#OTYs)>IKxHF|1%R|Y@%mpJ#>}-b?D)Gc+*8>m4kcbV z4&)MzesifJU5DHOr#szDGDo7R<6-bB$BNWwy2j+%f$I)4luLf{a*0EUzX=Buhe~&l zbdtffdcL~9fy-{aEZ*jN8}Pi-Vzp|>Z1YIQs2$u%7U^}h@nXK~q_UDI2m%b>x&^^|9Qds-V~blv z+rZk2&ni7<)5olYME$l5Ztv;oRa&K$B=_<~_#d9d%-~Kebgj&8dzI;4Fsz<7t+grf zY4RM2u6?AxR^l#+zql6Rc&u7|G5Wv!CGywr!uk1aaCWEP9aY~!I{^3O%AL1)8l77^ z_a@p*#=X*)ZIi2&-OojJg2C zx?GNOJemF`!w1X0Qw!_5%l@12HAlh8wuP>}lpj;#=jciR(m2GaX&+H7?H(1Xt^6Ip zgE}{v^P|ej6nu1!jaPlDdJ<&|1?)I=8Uatc*X}PHX?vjV&rF|xd4Dp$r{g>wyK#i5qeL5mB>PoI zq4Jz4Aey(lv^jmi_V~mEW@hKm-_wJw>xU|)Z@+sN>#kly5gCRob!<#Bie#C-Ntk}N zhF&{rO)0w^<0-Rk?RZ)71>?D73re;;zfPa}`?SBKh&N9JZ3nn9&{uW9woVr|Z;HQf zK6?($Q&ZO3a9c>Bc6HKoP~t60qhlcM-vDUYzTS)Vo=iyD_Fg#`WS7Yv&oQ;^C(#pX zH*XoyENvHlg+6uMF58J;L|Gp$)6 z#g!DH$?0|DfuIfLL+Ujtz3Et%bs!j}yFYc{qF}R15hT>#5l=~nCyej%ZRsWJut*w0 z=eBNHv4DzvE{F5mwxIv|4OX7cZz$SS@?3c=m3On4G;;eE7V}H!YHvgF@*PavnE*C) zpf;CFwdzjsrSq2LOu1KncWxx(q^*#_#%wD(JF7EzY-QR40;05kJ?UPZ_^b5UrIC>k zV`KNXjC7;=qwB#OMoPUUL7t<@U(=1IyES#-oOD1`d77D@!{~VQQe4MDcY6n1r~IO& zOreOLo3{{#q_xT&0ZqZ!bkt)Y;AHga!(1_~*C;evL8bw_4)8Z!jpU-YW;!g?E@Jwg z8&op4=`#~!sDJlW)Ly@c_TT&+_*t(sLCyEYknfD!EmRNMQOrRYJNr3MQ_K5wM}zwG zw03lv#jF4`O)&75v?C$g1hs_A(k6wLYmze}WY5Yw^fb5WOufn>Zo0s2ZXL@}s}tpG zCvJ<&R;Wb$UGXRNx>X|Xa-h7EQ`>l`oPVWjNjN~dRwRa&V=Vg9k5HGGxsa>Dtu;Lr zdHyWZLR}rkyF0Pr!X-$bM0pCs5Xa7Zh^23z1SS`-@heZDbAS1X?yKw8VSVum8fNB% zTr5Y|ZjR!_EAL?8>?qvlw_@8+We0AFL&$}vYGf+6oT(|)_}5)&wxtqwuT-TP>3G=G zXr}I$m|oXfy89U{Pd!LmE*z52>SK|QKeHARX{#_OF6RT*_B@S5&(Z^EllNviJ6|T6 zw$t^SqqyUmdk?au3EYOd zdeo#iEpDv43w_sbpmB0m(;sG!OGnk=V*u!VVkdg5d?tkCv62Ow)Ju}Q8s(l%=BWC* zuhJ@|rVAI~9X)}i#y*ViefHz#CKaWz7j$26dD8Wf%?^~4jyfW;`;h5gwetYsJJ*2e zMPTO|pg-O5&bl_1K4odqO4;Tb_n@Uo+Et2LPg)ODrhdizUWp|3(Gj@)kDg6RLnp_o zAZ=yKXGGApl;)~bLYykdS+!wgaYQp_YARONQCdZO;#Za6#ZRh0H)uIXOGC^mu5zAuyZ52ySKzWGDL_Q zi}UEsWieS;M3V;uVG%cHXE46ZV-DL|nlU>+k3yjsUmJPj1m6Cge*>qj4&HzBEWY;Q z7g3js0wx>l>rr=k8pESkFj8MY#`DlxI_>$+|L`q@zq}ib$H$S|*ahdw4c0QBIrK30 zZ;$4*KkV(rnWr~nO-Cml+4}(UOH266-vZr_6E$WtH?!A z3JxOM!jyE%bF1E|(nn^?QH?{?&&^}c@e}y*bI&BUdRp>)A5Akeu?HD(U>&urK1-p9 zdq((~$ka;mZK_jDqW!GhxE;5gIR^(JM%MN(Ywp|$Lo`oMW6#kO$mR1vBgb&`z&?z3bygL)oy+GjaD5n?&Rr;N^~kq^)c41= zSpmAusy@x$9a{fZLJpSK?JMI|S*1@M%`XARPs2ZP7>myyLeoo68A%owfyKqYem%(4 zs4K~%Jui+D?PcpyLP`Ng%Y*x)xkOJZ4W?#h@a~V_#PHZn>={Zwe`6wAJBCh1p}e+S zKbzKrS+XfDRoj@H=^DX&F8Uo9S7q5Yq@|}Yy%4$`!)+TEAr>0y5;p)|E-mG9m~F8y zz~pUPlP{oVF%J)b+A-Zh7|;JFJxjlNZ2`jGdJs10VE#_SI3?GQ9MhV%mhuWve)R4n zXRde-ET53wk>@L$b=GmYKB_4niOb3QbC9t$B{5M6yz_~29h`HAhBSo~8@39SD^r$U zp7bF^|C=T2TycYqyK__;eE`X8>J>}VmX4A05oA3~w>GD!=VzN1>uWLJSdZLn1X%A6 zq(+=~L?Jevzliz91}yYfK9c9oiOZ<(X+vF4>oQB`eM=5n+Kt;0_e|b-0C%#BD=j}< zwVBF@K20~L{=BaElR!AM>r}R`W)-}%*H405*<+GgPnFFDy?K095(KfiKBT;G1P7I< zSS(^}{0_pix6$*+c6c@E!Cun4lK1RRRCO<@_i&k4ySRwPnOW<~yDK9jn3$PHHnRn{ ze|j8eKRAPyuO32sbGoBa6xnyDNN*N%Gc_%(fB9jofBE55X)C#KX++3BX$ssgX|_tM z^l7K+0I^+CB*{xVytCzTkA+m6ACLE9q({ph+mhK8BB)MbQ0h;XP46NMRE8opjJXnVS;8Mk}7&~fVy>oaQ4 zC3OICM5^9g!XR!3IrjPZO&Sa3(4kCMIhDkJHk>SN0dvPN-LE9a5!ax)cI5T3T~+Q# zDU&%iA-5%Ow`fNx-CJR67dt=6?UbHwjE!Mr^d{Qc`YWcLXm3Nq%v>C_U0w!CoyWCB z8q}UfzGgBR?A@|8{=H!!uj;RT{4Qpin=sk7T;G+Xo?Exj zI5TV5h?ROl<$Goxx}QS+mNtM+tGIiW?hC#CI`YRxFmd2-W4=HA_^yW1_T1&+BeM){ z-B%`E|LFKy;$Dd$Y>3dNJEJ`HJ(DZe>CyFAw{HvDThaw>6ZcZyntvunOWIvq)mF#G zytR1Vs@0%<(@`?m^-8tjSjExWmA^BaX3^~w{UljBkBg3P_Tb}Y-x}m|HG+SYvsWyl zfA|Kj4X(wS8@G@t6d8JsQmfr8`6f5!JK{_G6z{aNt(5t)^;9sW(v=bulSKwCXUbEC zlheI`qM;Q7zJ^ld-!2%BT z96*ihq2Mo}E~Cm1QR8J$pUI)djply*FvNnNM=>biPp%xrZw&3mkH@ZKZ*vQ7EY9QG zx2|JibObdu6s)nB&m#;&yG^{PSM|5N-It+xCHN z+u{ADhvVnY0sz{Yn(^Y3PXPeF{re7P=I8O~*IvT9zP?m#wtZ*=whvKocdn)eUwYcU z;Ax;|4F-DbCnYQu3Mdqd@O>Zo!V+@X@|$jXzK=|yzyctnF`F$E;Q2oMGJeu(C{rlH z^L=pdQB8gckG}pUe*D}sWrI*_n(OiM8-K8jQj_dn`KeOgi>;vNU5?UN`t)0BU0pNk zwt+oRTMyP&x=P)PIM?-BIWBq1NDlh&(F1DUI3or0-dBadu0nknuqH%T>kG}pUg3yWimmzQDL$X<++zN_#jIOI? z?Yd1EKy6eLV&CDTIC@|oCfeIj%w#Icl}xdS^_Q<;=)z@YP09AA_M+bq*X-UQlJ`T)MQpB344zr6na- z%9UGQC)%EoIRihN7$M*Wv2=brsXCyL=U!&z*-`@Qr)PEd)rPL`1eYgD9POTAAFgNBUl5Ii~+b zZAC-qSC3=cwcywHlAr;OmU6l6r*yN{$-mOom2L_VkXZ zygje9ly0cl2PvhrPX~nHE*o7G=+Elih3=E7<-^Z<$mepHZfn7by?d&v>t~Th`uhPN z*nZ+PXg9~o*GZl z3Owk^?+viU*j9jv)|6Rs2B$btRF{m1svwV4-oVEZ$h;$0Og@xjZ`6|Qce z@wAd0?K5(m)h;YzvF_fE*V4=3d_`l|1Aoir8z|=#N(YXsg&eB@c9mACGNl90Np>Wq zvjJ%nPI7(7b*9w$(hbNR&6TOUy&XGuZo?b<2GITczlbkB`MH!&O40$aoTPS2z&f(8 zaFS=0Y?Sfb$QMm5z=u%yOvQ6T$s9% zdYrN|DLnyBY8`r?#G^t?<#i2BKA4USZjTX%9MEzoY}?`6VYQI_>L9qBoy>b$rFtZT z>trBq+N!EnDrcT=sI}F-Qn`AWR#Z7TM>!@VaA_0kHb4K)$JatbEv~O0Oywl{q*54$ zxN>6zK@g&^yBl?E;&yD}F5Y_eEwoRC*z^y7EmeNJebd-`j^m)Stqqxs2kh(ty3-wd zSS_vV>x1))pF_j-t7vPk94s}_-iG0&wdlMx&g5rA5e}rl86b_^PlJckk1*~d(94n- zk0StydreKpC7(p3rqiW zHV;-O8>BRXXz_HIOSjM*Bd_YLv-H$4eh0M+c|)Qm_e9b)p%^btyf94h+&y{=b4?8^ z7PLKZZ5S;RQ}JYrwBwSzKvGZh-|AZ0_r$3j(q5%iT5%c~0WMxd-l@ND0o!(3elIuu zy35H+*KekD(zS_xjhD}*go!>$3g2GSjbgTn;GHjS$JQtJV@*fp3C)f>cTl^qXqES- z{}J(IvU$oB=UBfc^-2K8ay_Z7lC*%`&n$5SpGgSCech*Rw>4Bv)xMbgx4h>f#CT69 z&Triu<6fO=mX_cJ0nY8%iqLbBTa4PhX?h0rvkURGXj0$gtwQf0A{Q=-0MyRidMl~# z>d!voNAI8OPID2p#Heb%fuCT4_&#YhWpC*^kKUDfH()uDmgjY$8tMLWUUR8OO$^I> zM+z*FDqUq;yb>jqp<`#dUYVm)H($Z%)Hw`w?8mmA@+Y^Xp%2I2g$oC*wH~lUAyqgwV&c|Zh0xr=b66!@i+_MV`P33 z|L@iJLGK&*>cB>15a7n*JOE(rnl*Ut;YZ>;{@wS#hxx??Jo(^*Sl62zKa;c%BEj)^CtEjJ%J)J zP{E@>6l8hgfjt-*sJt*V4ej{gG}a8?ER}QrN#Yzmv`2-!xFTJ7lKQUl{qkeoW^?Gs zz!fzx)5?;ily(p;6hi!+77%g$WnWsAYy+uHq*N;VDH^0J+|pB#eGok#mQH=pZ6Hn& zW(%}yN=Hk-EVWh$Wrq~u!2^)V7xC1Oeu|$y`xNrE%RAY*>-HG-zJIK=E43H5oNnpq z^#^MQRa4Tj%A4WGt?r2D$)-|1Y`?UB^~Q4-;1zwG*|9Bk9h#!`;K(tA0M2dOipv{^%JRGQ%vr3xa$O73rr8B< zd+?r3_0nxkl->uo4oyo>+MeY+yAbJC$``astAro@2>$7t2=_mP>@zz*R#xnuHCwuJ z^CZ=2{N>?qGY=)NbT63AXKZ@u%(D}!q2Lc*MR@o+oL%$SICl~J!Pvix0oc#OUBq=T*I#@AHLo4%L9liV;lP7BWm?7{s4~O&2~|3g19i%1)SBuv6vZPC z99Qp61$NW>4x!H>n;6?9^2RvYH65>q$gBjQCI^D*-xk_fZ|ocE;Gw($qiYt&!Q=uLP*5l0RlsDhvJWOG(XgTvm7(mBGbAFHdh zN~^RIWCAe$8GV;7E-ASXU)S@IlFVV(rB39lYjxO~)?U7PZ5XeOUqr|6{Q_Qk>giO^ zD9&t-InpWe+?W8K))J)YRZDRBm;^te&z`+!M(zNgCJ2~CSh2X)5 zTU-LpUqtcp1oE4oK(MDj-V4JMEfReXJqLm7l`Ie-UzfuhPs+)p-N#R&`{pe;K?u+H zOI)bQ+Q`nMT~6(q!9ft0%C&z4YN=J6xZhDdX>jPW4eGv8P?%%JG+kN$rjoK*zdz-_p~Y7OH+n_DdQ3XSd=ik)qne46qX8j^h?j6qpusyjg4rit3!QlE!rmo zg#Y(ZAZ5_D;6n>gu~8U?IDhpjn)eK%<@v3s-&b9GSK}J&Xl+3@vr+5 zm%1nU{quAt64m<-4|c0WX?C7hR5!nXhPk;oUurelnJP(|l1D}H?6USy?c|mm#8G{s zW1Ryu%+8{AaS@BPE3-g&^SSeAnw*J)OSl#%ek4hY#)*!6mGdCoA6c3esmv~=I(4+Rp*Cgujpr|-_3k7J zaX??hjlvd$ak)*;EdztrTwLgqUn=#i>2J%I+q+R8xcF`}P8W2*w(`at-S)T|wRaBGd^hvL1Xwm)cn^ z7z)^wYLa&*dNx8_Vf@={-6(y)CTIZ_bVl!y&?g~OZvTWvo@7@^t4Tl6M7O^6>Tve<8)(Y4_6NY+67UaG?DEYzh{wjV zzD3l%(7q!_(Rpi}jbp+QD_M@BL+`wcmOE2rFqK5lEzDaLFp-!+RXvbe{BTaqqi{K+Ja*T9w=Lfj`2Hq;OH>~AwTIK2AKO~BJ(7k#DvX^> zT&kzlp2?aviR_qAN2t=ntMAWGSkJG{RtdxErjG>IwyjAxUIx^hD3_o%KcbpF&^G~P zj3!*SSvvYzS<;iKr|0?8Q}jRKJBhya@~O^}XI?f+bJ|R2uclr07saGY{a9;^(tX@0~h{)0Zv+00w(|@%e`zt@w;|T&AOrmR9`Yv!BPG z;+xB1Gc~>V#8beJo&a12j+=HT@Tf0D6MjAlacGKMb80$oWv{F>&{bcowEL5EyLV#4#Y@<9_B{B`DNbo;4_<3GhLox`sOLHCo$)C^&tjcXo9Mbp*S(Q-NQXwz zo~y(I*-z>~YP;p8O5?{%hagVeI3?$g184q*bf8SR>kEi&$51IZfsSKMvO9K?R?}A# zFlw{c^xqr@gceRrS}vw8N7B8N79&S#7yJV9{sQV82hG_U==eaNCb{2KEEe(Rv7@;A z5B>w5{k{JL9gl4TYS{wf#UjGlJe;;VgtuqmtZ4#wB8St90Dzi~Ce&oJn46zRKA*?; z{`5Nt!w@h3jW40AyAunGi&!cYaQ?e*;qdSMdt^3sq3OSU0mv6o_*ZWuTqxkJTn6>K z*5c5v-PpWt9R_;VAbfB?-u=P3`&NI)aq#&^9t9q$jK4W8M;BeZejV?;dl>zVZTR_@ zzfhSsRzmf9*~HGvrSkdcPTM4nN9k<$_(En^Xi|OOPTJp#Yhhi&+OWGW2UQE{GM|q8 zbxZPIp>TzYCGO(Vm!IZ9x{D+Fkkurb)KmhB5rjT=_CAYSGZ!&Fdj$Z{(J+WD-H#z(oWs%K@8H1Nmyz|-+b~(L4jVfk z!a(aT)OdBM$<$-tz!wpO0S;gL7IyYNjpo{J)McCDIxbwtMdLsVJlDS2)TWNTa1g?C zv&guaQu_sXa_|di%r+zAx^TVdeQs{ugktjmT*pIwrVi1f01pm)O=bd~wo>eTR>tV{9CbAHYWjK4`%uw|7^PGWi0WAnHfDoRWG<-I4dC{39xl z`z3a=YcDBjYETq78ZzSuJ!iXs%*#-l0~K&*LqP*D_49C=(x z|407^fY2k{GpYFG8)78kosgvtz$u2PDK4SCa0d^)@ea5T zg}UJHy2M2P&c8F+u6}7aBf(4!Uow}vp4hT3GO|L_zJ=OEwYWv?_gVr%G(0vec>x%N37DPl)m*X6kq)S&Jz#9 zd*l$D+VmTId=g04B^-G~Wa>II5BXi!&?I#!4~|l$w^jOzbu_CaiVGibfWrqL#C$_T zRdwFAX>+Pg8waml!_dXcvGz5!xsi4k_u`Cj(i)O2jW_a zV4XrlM^v9mnJvl{7f)v+=}aQtP1Ath@=6lDD_4}oYsy3Dbly$< z!$(@Wo!qM9*K{_>73sWuyEZa&E3YB$O-HMeR>AWs{q>-a!yb}4jmWM!xeiLw&+<2f zge2*ybcLxKr9LIQRPLwX!pE)N9-Q92BV9#<5b)EtZ`<7o>^*!emSc)%-SQLqJR*UVA|NK{SsXiRBQ;#BQ{CWE(w_!;SV=KGP!@_0W8A;GS^$8(nb z!UnE&B8*6UBtKKx4wrR6;xB0RTOK7nS6)8YMm=vw!qVky`@zIzymR{l3^jJ)%YzRl z%6+5eVTeMpXibZP9~E39$3{&ya`+aDMFi@|=VAZ^0o+^`nM?*X*(`qPx##g`|1c5Cm`@e;VlS#L=^7aQ^BQpckn97r%n8_ICXI<4>aK`}n4Z zxNeU^qzKx+ z7qZn~X%|~BUT#}SBxGW99VwajmA;XZ*W70$uv{kuWbR>1xLE2tonyW|-Cz(vpKO=N;1-aq(Y#rCg6p6|m6lm-eAA_Ij3 zxy-V8^>nL)hkDs?unbBswO$Y)Q!FBMoK)k(Mwwy}hu(e{x%qrNDaSni? zsMn}n-sqo;!7JA>bma=hyE}1Y|9<$H>iNwSi*Q2PB_)V=1yjq~Odo>XU#xfsyJyoD zlows8>@QA}M)&#Ht|vdcN}oAeSOC8FJ>V-}0S+7hE_~Dsq_N@D_iB2msoRpTtC5vt z*U8Z@r^qM={zoH@OSAxmToyn3+>@zlP$(Ah=Rf)ZmKGLLr3Zim?;S?N%v>qB$AiA3 zp=?FTHPu>-VUORx{wGk#h@ZMojPmb8#AcPwPaZQ!?KZJ`63UL6GzU*9jU-T_xlpRFZ z_zr1dJhjX7`R(t-001BWNklyrm_yG^N{Bn9E$B1%c$|7cq44GQ7aY^})4O@!|PCcAYqd_OZJ_ z5h%usM!7Bs;e-M996y26yLMo{{@zdeit?8GO7lf5w&hV$FPR$IhNaVvEW4bs+Z3Dw zy*%lK)bXxO>)NriY7uqnxmSwKaM_>U0IdV_2v5npAiU|o+G=;W?|`l zLSnFTHVdbvLIJNGc|Y0+{ofq{9$bs9&mY9#n%)XeR!_xD29s^AaKaGB_wR)pm?vNZ zQO#-!1?)O;s-&A0P9<#3tv7|4l{VGi4(W4xx9YdDzD*k#P+{4sHz;gHB}6Hxzc?%> zs*By?<=^;knUn3!^Sn7}ONNt+PNT@pr|rd>V1On)K2EZ`GtA~RjWp>%lOo0x5ciu3 z#UlRV_16#t0iJsBAlfP@!X&ypGK}MA&jMHPBKQ|?#n;_`{5gdG&vArTConrdkA?gq z&OEsVBVWG_T$@1ge|sI13$ys{|Acte)S+Fwv3JW>gkPJ(!rVL#?b*8`bxk72bI~wR zd1nnpx~fb2rrtbu6u0l*#m-Heuz7G@I^KkWt(L>ICPk&Zl0Y?mS7{wf%Sa_C)sgN3 zET&tw1lM}Sb3X#-=@xFJ4xT{-_zTew2HNoRG45bfi4u=~VGoZPc}#p**nMNKY4 zGbg1JKq_C|eM3$x0BF5Ci9N?o;KT#zc40`OEoaZ6W9$wxi^bAvZ35Gg*};Pvl0mWT z3-Wi8RH!7E(&VvxTG_t4N}mooeLDOYK(xJgr|+RQKup(7yN#aW*Q8#QJlJ%YT~q0j z3*b^rN!-zaK3v$c2}?CK>1%m@48b4120Zuqvgx{Rk74`i4^fjZu$>YmV6r&?l@k@E z9ifw*gpmy9J9W?}rIWgyOHUIJ(>|b*cptD$YwD0(cQ12I&$US1v9}Orv&cXE6#T)V z*bN-*)Dp0LJ3*#FL9c*P=;MnPDzXOsin zVN=Q6jc-27YiLg1@FO>+WvstnX$J+&-lC_-W>PuY7TifaZ`PF~F$ZAf>RL9k9C%)e zQ-Dui+w5R&6`8n~=d)78>txbLt9SL9$vt=NByq4DvuU5P+4nPZbNCNG`hlI#Z=C|h z=i&SvI&Rx>TzvI~FQ7J;!z=H;jT^UbM`{1!3~=c#`u@i+;f2SZh|_=hnP>5xKLEz2 zCjkI^wrs@%+qUD{10#54M;DOs;QsHw2;?&O;!~ePYg03R`u=;k^c4y|=jL_{z^w0JC=wyCXZ@OygJiC{Rdm`1RM4a-IpTt7P9p6tX?|(C8t}dUH%!{7Ub&E=8mS(e^Wqaw@ zd2VJt>Zzn_bdRSYE+bS)xGNOj=wvDWcR%{_-S&38^7&^I?{7MP0UIt{g7RAX@tpuZ zvuZd=?~EHy80%ISwznHqC#aT&QxwBb@u)5iE(Oh$Wt_RYFVt(Ez0Mqg1w`3 zR4=_&9DB-sqvUV^2Qt`*=b)BZM|!GhVg}8aVZFe#36w{H&X}YY^x1WN_ieo$bWEqW zBVyhW`fDF`kxo}_%0sKU+?BmV1(2&CXipmh_8@2z-&3A$iJPDl4zGSG zsiA`SQJNER;x|lj2h=h|w78FYF$Hq#J=6@yPMVwH_NW{soVYFMz}62d5$}`o`YO&{ zr35M#fr}S`Kl&r!<(J_;{Rq%g`6PhJ$q;jM9|3>&NGpSbbPUaHcxWS5mK{QlW}7F_ z^tMZ1fGzKGbmYU+n3&M$uZyy-HsZGf1 zsyI}hSpJ;NU&2wC`tCFRqTVWDee=`A@3NHg{mpeLG43#N4ROZFD`$Eyf3dg~nH zlW&Hs4YH|dhizq71?)Q6UCPRe_>hRs^t>RxLTQt%O~>-R)Mlo$I|+Wu>q&4^x*5!G zw!H35ye08k-4py-ySZu7naQiTG(7?bA-ZcD@kF=k^ro;~`Mq9&Q{VUwhJSDrI52?T zzxgQkZrv7@7KRv~oIvp#ui>@-Y!DS5fa_p%1PDU|MV;V9udUwI>4 zuM*U_B@Sht=2{x%cu~1=8Au9-pr>vEg>bO<=y9Cdvuj0G*Smgz#_3sh{F4OFicj9E zI&9<$PdD>I?Nd$d10lRZfV$cAJJ=-A#tRqGIx&gb*@bw5TA$?Q5?S(Z1^_4pS~{#V zuBBH9(0OYddyb#LiM`7U+}?WTEc%9TAiKB(ADPnXK>LwXp=e9av*JkBOI@QpxFcsd zCUkXFtz5lda(I@ zP(GS`){mkJ0gz2aI+Gk0e8CehTaGDp$U5TO36QJwI-1pOH%X3`PPZz_-NMuB(*=~8 zf2)N0_>+|+Q6;%n@bh@%^1nxj00#zMLUXMQl+}@bT1t|Um!~e`)Yy?Yjpt>nE?k_oGmZ$M)^V+MYG|pl2;ko;d^fKH6Ja@cbi>0RVC}HTcUnUc>0v z7#`fY3+wy(5kB@bPzaD|m!~dyo`=sr`2>Q}P5?F8EHa*l!Tvsc^`)0Y+J?G1xUP#w zAJ`WMVrMcLIF5si+Jzz`*TB23i==SuOv26;mq&*2=CPy5FD>EQKY0aTdOA5+g<6no zUk4%f9XX0qdv;;0J6)i3C3@)1chEFBgCHbq;e~$U4ho#M4Q;?s{{XxycIr^QP3>S6 z5kFASw1t=NU8!tWbF@^6`1t1n_y-q-Q9Y2JF5AFNk(=>%B1wHw>!6n|1RGc)8V|qucB;VbhPgQ$c;_%eILIyJ5r)JgUwWUs z;7|1vxqF)$=ln!4vL2GjCKHJ6A8!7rXmAkNw(XN&k53i-@gJiw_z1ig4&iJ#h-+8x zZ*ev&-kxrG-We{@^?V#AVeC(uJW9REy>~huHc=%H0pdEYsP8kBKr?f5_}&kGgu>td zk8pqM31BE4CgVQOB-sVQA=&wQ3z;~LPutqsSLej^YbecK=~*5c29}ceA-oeBDR_BO zb4x8`ZmGd{pI#}dbYjJ&jT>-%a4kYOXr7wJ-owXAL0W1)M;&%dM7v;*5Y z*7bAq7`Qepf-5OtTWvz5mcXk`q+Ik552Kh_kNJk>%?D-*MXbAe6@!>4d2(@(cH<8DX0R;F2M)AS5F z$L^GJp%bX+>}I8XB^p*&d5cr1k;KzZd`0G>=f<&}jzqbJmO9&k{+20k*>58Jskfdd z(ttgyTP>khTNU~QP+$~2LE%y4rHEQq1#P==p0rg7udi$)Stl+pbqj`v_Xk=!^7JxVJLs#Vl?Eb>E+Z<_%H!0P z)bKXy>jP3A(6CDPO8Go+{ygxFZvdU0z!$y%^sfAlzaJ%4?(z55gLS+IZN!=wkYv0* z%5|h_rm>e>iO&AZA7F0e4xFd=1MAyTJ(Gl)p~)|48Sv-yTJv1!(?ybWlclPXb#6!s z+x_>v29k7-io?DK;93HfI;FLtxWCj!8PAJ@vYlUZF}pAy-<$a08m^tXisIiQyLRi) z2GmxuLELhwn91PE(0Xw#UzfvFTMI$}bqkBpB1kA}llIJxJ~^(6-jJGgBg;a!LAXas z>2{}-J0b6&l#A+hfz}@saW8`UZL`J5vXl3y9(K}g>5K%8W~TQ-+@z;z4?rJi_p0QR zp+og)z*=A`KZ$G8m$0vEw`djBfOqpVxH5Ya01$-5($f+B@YY2<-rkK5XYOEKZ7pVt zOL+bKSqv{!UM3X2a}6l?a2_8jo343nGjM1S*E93TPSQ&2jOXF;ef#nDp<&$0PXnV% z*t~8XdON#tr?kpOVWs+$xx zxz697?krRaE&`^0ymFY7SKZt^ww^hQv)i^Vs}374T*TU|*HN>OhuX8HQV=wa0B*YS zHm22i3OuXbN4LMxDH{6t*6hzEBZzsvXNX8M<7?#-ebCq-k98_l#Zj;o#bYJL5Ul_2LL^z zt|_aG@9(A@`_yOn?lRmK<2i9K59pKH5=bk%LbvY9jk)u8PU8B^WdJ~X-5Tufd8BOm zN_6)28)&KP(RK_YUKMBMC`5>b!Zd==$MG9~g&k|2!Q{dX+?u%e+|Z8k&U6c{SM9vKIYyE$nd8$kNNeM|Un4_nCp7HF$dc0J7OET-QZgb2Gm9 z=3o!5$n`m&*YwIKFi%6pNTYIgIeH&SK^tRSMW9c|`##4l;`cxcj7;eXZRrCVALPnIaOa-KGq8>eJDoV(-fj%}MwASEG}sPtRf z1#%Av8LI1QLEAQ)p?uvbC|mB>q$WUBP1KoGe0K>Kv^)Fz zMw&<=c$&hE?(;xyw-}&iG2M#Bj`2I#eC`|^KSa&^Qan-4k4d(L%IQ82($iq?EiC;e zEXt3eR@&YT0yIs|;NV;D;^@Ks*m3d$)GsWEzNN}^ive=;i=uaOKZKkpmy^mom_?r+ zG40GGTx|Aw+f)lI_p7DG1TON+t%kr5uQK&5n8G|EdqzJFtMxN@Y6Wg zM6mKb8!4Nbj8P}+H=E;|Tu@3d)}E+TiHD?RAsugtWrjv{`b}m8UE#txVUNs#U+Nyv3EL){!_zz4B~(BJ0ZWZ*(y? z%^}l4Tk25!pO3crMU31U`)WIFkM^Kgn!&z{X>)3sU&g+R*HFm^Sj{zI z-{q^wmr81_5g(ywzS_~1_21aSMLIbEco@Ao26!IEMn|w%!%pF%rqxw!zk3e{E?rg! zJMDlQME3l15#u%HX!X}kBdf>O+|%_BZI#mq&F0knS-QE(qrt34&mcnwG+7g*%;7T0)k?;)%OW*weYpfJN>uxHhSZ@3L zJc3FE{SPOqGLUo|y;5S`TI<_@OXHHaT97U!Em5S$5#A?@KK-A9!7!3WQU`5eVGV~d zUSy?}?`N}7*9ludN_*o5Z+iko;{TfJO|=LSu0KAFN?5{h_ffPobve>xH#@A9moPSS z2?zR)|#Pzg)e*}We#E058dE5Jj92Mc$xSenQ9;(g>i56Alsg{Z9+yLSu&04kLV z&Ro8PD2i}+&mOcEsvF3ITYz#{bF&!$hQGcSgRdRN;N)ZU2qx+KKK769MESq?E{au4 z^2pFu^mccnx2qf7hlbJK(u#efqnY}vrMZ9uJ9nvPBPl1NTAG`!v?fhVPvP3wZR{PX zUH+EIDGZK31cP1=UKC>Q)oZxEcMn!KU>Bo#rHI|vZzKyo4Fsgoj=>?|yNxLwdTr36 zc5Pb4Bn9o}QDppOvJJK-6tEQo$ugw_wi)kAJ8u&tsR$NZAM6lI)Tsz;MGD~fV8e6fV#+jme20$ks_2a(qp0PBA^QFYj^ z?R0K$R+F;;*PrT55j!PFW`l{3T&05TV|P&wa;Q{!_k(R)F`shG){COVxjeU876uIs zn#mQ(WjJ%G&9)LIjTl-bG-?Ewq;rAh%>=|*b%HMnD1S;DPvheeme&w$e?6eKQ8_5f zT3@+YNCP?z8g&{MkfvuOx9GVG7N*goAD_dc-+deCX+hWP`*Aq)l}EOOH$k);uIhJP zGKbo);i)A3-EEkVu*(gq(@29SfVXoAcA53kEzVyZLwRr~%0oLqP|h@y`Uo*TG_;`( z+eG7A>+6?Z6ye~d%kahJ&>AK}JO=_qMhgJhG9PFz_(UR{@+LjNRk@K6dd&_gl+gB#uM}PYWx(fpULgc(>(VS~R zQ?3QOwj6~yK7;Msk@o_$qdD&_n zrK-zjJa1bH1q}A~C1rV@hk-4Tl<=v2Mk-OlGfGt}RPj_(}9YtO%s@dd3b zdkC=e#w~<_zrJYOQG~8(cGxC^SMu}Pb9Pey!~}LN2+wbxftuKo;!Krje1})Rx3I5HVUNCw$&~paS^Q_;f|M>mdda_IA+xghMq1Jm(=_^Kyi@<{VMiA!72mOvX}Y1A#>WjPnACnjp5QL)EG<959d zU|Tp>oARl4)F(v?ZS6RJ>@bdecA;8lTT}E9sa60K0XG0e!j*C|s>;ZyD&yG&OZKsA z)@mC&+aM^Pxc5mnU@eM9jP2R1uc4aG)FJ3?#>jfK<$L_Llxwz5Y-97<>2=C_JaMyS z>c-}+tq+aoEccRlMYA>@KjBr*heP;%Tdxj93cpN_q`*v1cV=gsCqaHCM9<80@_nwO z6Q!oL2lH}K=eG{y$ea6dbf10jJqv}ZkLkMf>eEt$!)MOJLnLm0ipk`NqyuaHopO!w z2kGA-JoHXXVzRflVW;ipVi5xmA7QF@3p%G~fl$f^lDDCFLUu8h!`e+)&O}elL|*UI z-g@MEuQ77Z{xnX@+!R7ru>Ub?i7?mGiOBbGecv8T_SrV3G@9z&f-8si)2 ziTflbmHALv@=%H#WyaDpinjEk!%DJr&dDa$jJzrq<+jOo*^cI>&573o)s26n{r@1D z^U^Wiw$d~4M1zjNJ@~pswqEUJg4;B-YhHE)UIUTubrOa z>@O|dxdZ(E?*l*i3GlD}6>#K;bwlMBkLu~MjgyH1T~@8y@AC@fwd_J2fVrCWUsJ|1 zHz_qW;nQauzm@*Tp1l|ztiNYDJT`{G@kfdOl5J_QYw6-jj7vk~xhX;AU%Lbo=Sp6! z`!P)U?zXGAN@Sf(mo9Ig;L+7BmNwMb&YO)_r_s=BhcNWoA@%GhAD+g-(h_Fo=diT0 zg3)c;aCC31R|kH8!QSlp(t2p2qXQR@974WaN@R7{+$?gX*e)&mBK|)gpVPBhjxg!o z@~v3oCtZf@;@qpTcEkDyV{T84nRe%99XK1-HPg8;xy3DKi&J>CcpuHVHf-20QnnSYE>1%A+JrbI^*xj@`I3b1r$y1JK_- zijF3|iCZi$;ri5B9Oyfaa#%t+Tt$Qs_vde;r_h6*LNCf;3C%$>c6RPUDU6lxQdkm7 zqK6%A0~l%ROE#g4}s?Cjg*aE~8W~ zBLZ-I|9;+tKByN^J=)su-k5bc?DX~Ypsy#})dibD(X~lD{`eAZw6xZD+Mb$1|D%a2 zsHo1K2pGL_3wK6_*X^|3vb>DZTemTK^LBDlCEYZ=F=QI_cww937Rl#yazQX#_@%w& zYNMw(P!4hky;%4?8XUk*XasytgrtD@Pi{FX>_p;3%B6v}VksD*6dD*;D#9U{mN}Kde6k*r3oA4@; zGQw3r(G+OoIzVKMgWT|uitojJ~6FFL#PTBccRt4ip=k=7nT9kFxWL*JS z-jmN<>VCF-YyW2E>jsG|_Zo>XhR+@#`s@L`H+G}5tqliv?W+4q+rlCSlEZP#Yl&Q@ zMlEL~f3h_OSWmQ}z|<+s-?Sd04HG7uHMyiMt=aTyf+HKe$A6o~ZlHARFe*KL0!}lR zhX>pp8E!Z#=tfcm4|hj)V8_@U1go~=wuGznOqv|z!AO1bo%LdE(g5U$cq(tHhe(~5 z-ibdGG^Xtqjwr&lm*83IS=yi>p|Nf`oBXqbXBTibsjJY7u0kJ5;VKqa=doN`z~#v^ z06ZKTco{jrw)4K{dDzmr1HPX_XJHV{eeHNKcLg^mKLVl%-L2cOrF9rNpXXFp%MkKG zA!(hRXMn*Djrp2$ZRjivsJ3|khC25l(VRRF9nHOHYw7|Jp}nb#)3xse-A6;zQ|N;> zl6eUHJcc`l;TdU(^d^mG{F9jHtF0>xZ0W_}=Z@mx)FeiRvRxUe5lFnAyQXKc`}z$G zJbHxbo}Nq*q$D*Li`akp3J^tA9XAk8Bk`!U&o5y2^&7acXLmz+r%}t&GCHT{5?o{J z{mgG{y_sqj|6j@{TW)PUr6DgZ&!yaAx$YaaH4irHL(TdEUmpzbX#jyreNd>Fbnj-VVS$3bL-YTesfi;z6XJQPeD-mYkeBsaLX9wgQ#NOAgQNxhL$*=Z=>SqTV}nqY?c}g;dgzEK1%MPQycl4_-Zq)#fIw6bdzO6m3~rP7X)bYgfIzYEjebDvo}7 zF8Ti1GsiI1yRnh`>IDmvWMTl?ajb|vLSJwL8c|acXgr~VCei*7jlYkwNJHKs3Y#B_36E}-u8^o60x|` z+ejfE6OJm)qhO9M9V3nZ=1|6G&mO~4n|q(K9?f)jjhq{f1=I={^=CjL)B$HK%CBe5tU`5-BokR{td>8@T-6fG_zdiMkPKllOg z5C0)>{CGp}FE0a*7y_ASbM?aPWO9_o-v`Xy6w24MHB%ZJ8@jX~t&>!O04uG9Om&K) z2y=^z2*bv1_jK_xTgpqRXle*jUZ&d_I1Slg&00uK%jxYoV{%i7{?j@%`Ky`s0xg^P zFUfz_W@K%2@U$?o%U8gy_t3JmjOEsrHS6e--hAOj0KlnppW)WMdw4WCi9fr4A1GB& zm@ng(-u$_^c71I?Q-GG{!kTVW%|gqqE%@M-lganvpPWVa%nSgQq<$EodASHc-x#gs zotNktv87(>FmW342;^AaL^MLS^pxu>N=A@F%X#8`)`86TP1%*Mds|N1E9E8Jox6@O zifTG-&ljgKSDZv4*N(R4EtpvzM}PZHJe-f;-O@IUrPXOHmlgm3t@$o=wG5(ES;6%3 zeGIm1fK`j7dhl>y;B^4N)rt2}EU#c`br#c0_mecOOe+^wqk4BkWz<$GM*neu9lRnA>g4cSHL%i4kVYd#!IV& z2*BZvPPFeH#l@<_HV|Ly{L1lXYqb1JNRx}`oC`77*H<^GYiZCK;@(G-=$MCka~#7x&bdnwJ`094!I{2a3&6I3)>ADdi4&~0Rv zV#kIXCUDkUg$$ng(%e9i~NdzxR5sBRC{0+c;EZvW(y>zjnJS`(dw>G>= zGY&&Hc^X*PR60EXK<* z_0``9Xj@#w$gSHLzIC^HJ*dkl=mJ5qmAXY5te9=Jf8+0Iz*%!g4anW*N6+{q>tw@j z_t-}8kei=H{_z#8wjM{=)(&4e$W`m-MYwe6Aj+R-!~iee{PDvO%_~K8PR}JE)|`J@ z#%q&-9bHTs3?d;s9f(Tucv*?+ej-zFJ9v*DV<^+)Y|4XLmX=^L5LkdTT|`Y|1D7yN%9t3}tqU%~cON z^G0+9lDpb%k;g84)jGndJgPEEbA0$G6u(PuZ}U-GPvDJE880g?Nk+Dd>mVamRIvTd zz4+G(u+-X;)VX7B9$Ozg5VeVWh_F~iX-|5i)81s3hty0gEPK=~>tZZOlF>sMv4cFL zPhTK%dp^ms!lWJ2SzAW5W+xDCk6lN$TSQ5|R05JseX75V&qitFofw*noBwow`bOWI zQA=fiyL3x)hG~7XzUHpUwcgEVS$INYSoIICTc$?K$8#z7M?qI69$DVe_9u?BYaR|{{aCJUa;N1OwN!S1 zGWZT1KXE2}>D>?DBf^>Ip2edY2aBHn;3KpwE{R!c-v(0-a)1YX^4y6v-`up)Qov7s z?#(s5yIJI(i{yGK_k%-d4$repj#C93xJT;5CZ40uJ|aYcx9;T?`5xYV?Nz+;&U@&X znMV|HEop95ED1$*@l*Oi_DBRdBPg*@y?dEXU@Ut2LLIyK)%2$0(nz)`zH zRS&6;nKf|XcgAn#?Mf1V^DMU=kWsC_#H!p@-lJ#l3px(X{50;j5R7c&JWXBIMBA)E znp%@*)Suqxc2GLcs2A@#oBc<;nvQ;OC=`~#^nZJA+SHuQ{&o3{$o83OW!-fC=GZXN z@3MDwy?8XuH|s5`jY2w4>1T_gQW>j%@g6EaJ%`rse;@euUvD^%PdyEYq5p*^SyYsVkKxkI8+iZIvxvrKQTm^MfIq^Y z#5MTG-$rF;H%=aV1_yWThVOd_{PjDH*P^p0?86@2(=&MKgHr%l>+>riyeL$CN#jsK zt~!!o@{X7EKkY+QAbkQ!W8t@?%_JsMS2juN#4i2Vtrt>B@u!?AXb0Q2qa2oS>G9c= zVq=cE&N(T}jtxL;jU0OPEe(G*p%|4=`=7m?XI`osC2p`maxz^CMcdFubzmSHLqP6J zJ`1J6od=G-EmwK`SAuBSIx}`B<&P?W)~9qx9Qa8ZqTyS2;6+HBDQflo?rS&DH}P0) zI7}OFBNBmpFsSzqK~p zO)x3Pkgv0&F^xbQ)MOZ?^Unb);4{)}3YVmTs^@UfHaDbw{1JOk#8PM3um_{#U>iZ|2RhGo6VDKG7=7XN#& zV;df1jg&gr0StCvsILzvGThiQ@bD3K-nxx)_57wStxd4#mh=)x68zDcva5gfcZhy6 zxsZgsI!&6vL(6(u6KR6AL6>~TL+-&CD&1QUwYC{!Cn0rhepy^y#r)DDdRp4?=!46^ zfdTaQ^&+t+VM3#$nCV6EP$$lS^kbAz-`*P;8 z-bAJmQ$noS>eJAiPU1Wp45vGG%d}pSOSVnx?m{2B3jF{)93D8S z=2@dO(6I*t9gW>?m5pliK6?d3#&haDPo$G>^EwBaQqKWtres}^TslJlozt_}b?qiX z-^0WciemXiqQ^7SxbnegX#3NPxc2wQuy=T*!5lnP-~m;~BOeuX%+6!?wHv7TJ|3kw z!*|WhqGN6z5rDSEB@ExZgEE4ui!eKF$19a1zU5cT*n0m#W`}SW^-N7;*NvO#d-xdT z#3@xrG?cnHb6-;un9_A~_1Jp3OL?zbA$0*0)oYy0Xef5&jYp%L{9eiVxW8?ikiIsK zp}$@w#MXP`)&7kVJ}v7J&l!s3L7Stx4aAR$E9k9NZVg@KEVr+b$P^!Rz?u6pNJ^9j z?x8#5;L(rU$5(1{v}q}$SpY=Lgv;c-DnNI?@Q5eWEon^XhEruq_?p zrIWeqC_b$3JO+B*r>{DVqs`yk>7UY5%0!csz=t2g|LhXlUj7B(b+%tmOaP0EYstkbxetHwpuYVhDeO=hv-;d6=&EF#{HaFwSf&Iz%(DzYTUP&~W_W1>L zPR~MGWf+l4jfixaShi6wYpiR|^jOp4eB(TMv`DJPGCr2h6of?MVSqF#uydl1`rHHW=f+ zFqtJs&Yr^&kF`2VPh$~OLR64TN|YCZdx+q95#D~|b*wfwZAb*aFA{kvpE;O8C_cxd zLk>UE4n|}ix8*ewCZid_2Zj9c5aQIylbGqzLFLv;r%t|v6CZto?unUXc2LcO1S`Zd zP&yCO+%V;_wv{oT;W?aLt4Pz#xol}ym%sD7F>kHFpYqOKQhY;m_fOo$B z`nqrGmPDvW;%QGHKW>BMzFH5Gy(8zAv}j6PO%b=_GPTu~ken}`ORg-(6RK=ZX$O}} z`^=-pJjraGw9p11O@lcnhXjlF@MBpg9iaJWG)q(JZx^}s8^X=n>O#_1<5a4RY^8R+ zv-?$!UsPT1VKR0+qUOxi{lxW?+MX}!YU?3sl!l3!JmXvT00)hdInOsf|IMrWQ(8OC z|Jy%9^wYP|`Hkm+|M)-rysOgyxo7KI@U;DomaDSNG0ADzPK^XKsK#S7RoJdD>*JijS*s715gUHI|0zM-C-_~;Y#O+2p3Ot#^BAcyP- zw09vjCq8INXemfEJHV^nn!)ohz5z=D?-gc~F0) z(o37tvGO_iU>xv(GtYg+qHC{_TtY5PCVk8}n^%g+mr9wgrZ23lAShQbJaz}8H*TYZ z9QeW{5+3~D$gMGifsadv)*s=nWoa3QKRb`ksriJtx`mSl4JPoAq(w?PnTl-I_b9cV z`NC{O2f6IP>i$hvR4eGl7j-!n$t9szP{rk;pT3(4(#*_+zw z*{+jq$d~huH`>WDA` zhMRQk0%$ASOWH#%V&G3tU42LWFYCp|4SNlzt!aCvnd-Hk-`Usd`W3c~2E0!J^p}$^ zU5c=@^m*4}ZQ!|fezl*Oze{jjFQ2sXOijQSpC!DjM@uWqC_Xm??_2xe^<+QDX3GQf zh?JHQ>3PsQl5=tj`Q5eAEXiy)b6XAVeIt##ZoJt*9G-gKj#-t~GWXa6u8lKIle06p zaQ!-79^Q{X{k4Az|2KaDzwp*K(9ss(u+h@oT=)9!M(O&#J-EKFwgd3ibIJBbVkG093c*f%dQ(6fo%JnrRFxNgCH} ztB|STo3%CNy@`4Ph4SRV<_gOB0FQO2ncA8wmC;;YMeoEUJjYd*5$J%93%xM^ z*ISOV=e22^wk^pP79%p^?BuLXe4j89UtCy0kRU`;!;m#_J8kP8(Q*murR*}?`eZ#ry15kRC)^={T9kxTG4b;aptEH0{l@}YB{iNpHr*f33 z-rD)ZoGbCT24W`5{+Hj${GHbCQj6BQsGH0*b{*5|Y`*`Lo>E;}UItE`0)F^Ict8L1 z$i1!uj@-Pt`4PZ2iqfQH`bslp8f(|-*f+Ain^rq*N0w>Kt<9KLo0>4arKeu=001+W z@8a}t{sH{whp}Vp*35@vB~CPZNj`J+VdPAy<-Go^-*j_5Th>YxMen(7<2Lp&Yry}s zeb*elTGXh0Z*=Q6jQ$!QKwmBvQ7Wz?ynhXk?mfiBgWK4@a~BTp-h+;|HY_eLV{v&I z16wv92bg$y;Nc_expEDiv-8PjZ`@m^9hx?JJL3?Q9I26`c#lw+*Mzw%m> z^GoZ=ysk`5$xCts7%ekWw#U&+d2Xl6YN6VAx!dUcbG^S2cvz2tyBs1~ab#CvF3Z{^ zs-N@@8t=>4$LS>2X3f*9xcL!%mO7{mUPICTJVdDEg3tFBxd!O^-8&e6{1~r2d!lAK zmsNswW9swRximzeIH$e7;K+^oG<25bc@a*%auT!MU5LDmSr?UDfOF3r#r_Ld(Dz^h z_R5qf+H*Wlvy;{11GVjJYoYp@e_XD{%_JA44xz&O#07*na zRHskAh@&5$L)+{^vZiTHNta!X(6}A0{x|1W2tI~eQPN1d8tc$u6{FoObxgaUI~WJ0 z48RK`pJ8+sIAg{QFCC~ zj~bCfv^t<%Dvy_`vJ9ej|)#tV`%bGBH zH4%vBK_+&$kzrPvnV-iG|LVu6EEIt#f>+2j5NTU;R?TCy#584+xfcuo5*HJ>_KX3j z{^52rnG#Hw;ri!};BB^1*Q5f8CAoIm?}`un=~|g3M*t3gdJzbK+q*_FHri;wpLFtl zA5FBk)2!F;>nEPWYN-qW7=Jv0Km3ayprfq~-+uM=4J*GMMV@D2lylD2xs)llCH8#__L!l%(}_<$ChciNprlcA&3KpO#pU z;2r5Xo=ixaA*@%Jr!SN=NH5h9_xoAQ5OM+1cYA?W5G30c5j-FQf^r3w+?VUraw8Om zA1}rO z_N!u4vtSLVB`cb+OR;$4)7`OP(@s?Z=nw?~OUlhw8F_~2O?ICDt_a(dhlIss7SmDA zyyRJ>nl4Dj$OFglW32pIt_Wx z`#$g`3+nNuqZeQF@b0@2=H@=%dYGmo6L^`a*HQxKYZ^V%SDL+AqlDM8+~GKfE+B5o z+i^Jl4pNYjMmO!5~Q^HEY-Kc<6d{m;DC$|kL; zNTVkG)5g@3(ezlh^!&f?=2o&x~PcXTxD5d5=9g{CHS_4i<5bPIaBx-!2f z`5-%2N7XeIAAD$DT)~M`A6Kfcz~*J(6DF)c;%?j9Kv znh=@9#y&z+@&O(X_T${~W6nCdsGQH?qZgmYi>FSbdvY3nB~-QH4Q|=r@_KKRj}o6C zoFw@%r;<)46tRNPJs+`_a+Q#)5_on`3KYUfc4-b#qCqG%1#i(q*n^qy=Z>O5~pP_3LZ$Ho21H9865C>nm5h%rC-RcPB0!Ib5fFL0ekU^xuC2 zZ+-3cx=!1E7@}itu3AlPi)T&O#koDvGKqgV6>sF)9LvqELh;$oPao%z`Doq3%#~#_ zNdzSAlvqj18~MJiIWb9D+9u^iAU(|>PAOf8}3g$!iDSC z@Y=J_CGTwM>Vp3Su)w3i0fd2%0~ap?VTAViMM%eN(wS^o4e^)cBh4PdK~f_GSmUA@ zLz)O%PgquS+s(tv5qKt&{wqf>3)Xe(#jcI%bh6Q*l+!X@{X83)S6Ml#)@d4Z+>S&~ z*Dt}&SKA#tF-AOgy!!cwI_uf&mPut1Zl?Q?Y@A_Qx1>JFBTfN%mO9#S>BvENh%yDl z`XbPk+qZD$_kV=0@gnfgYCCN|?(f5;LkF?%;??At(l5g&crD$6;nqUDjA%++_=HY;VHo*ga?DSjsRYc=xJ z(P<;NT)sW=T}pquuB?MG4%eCb;}%DO(r)F!8%H|)mFJbgXw?#?|@1O@4tE-FaP4#v9+&1)4Nm$ z=5v6{I$-t@@n6&0s%47oBm1x2FHzM`%tT}wr2(enc4){2&N~t^nA<3AxpC{YomB3E zvh%jIOH-+31c?JLNrmR+A_7#f>-tUjVTfD1c4iuh^-x<&E840t;+mV9(AnOOmEtP? zzn}h%N_YIg0W2&np;D>f@SeS!Ua#dA4qSJ4cn4;By3w+@j3b|&2Vr+F(T>SR6r-#N zu|8EvMoZepX--JX5TNIsl(3pyvP{mIdX#f5Ycl1?tCTj1T$M^wX44w5k;YCM4pW^o zyF1=+DJKIZH>BcEHe%9#f*lm=`Wqj-9R~mjd zN+3(jsLBBLT)u|ASFYmzj_r6jG>8))eyoH}BAOz0E|KasIc$?D)B{IV7`b%^xpD>P zj%SNz<)W|s<1Rsk}hcA%HXzONVX~lGYdVJae-c=p?xmgEW|i&Io+i>v0C5+q}gNN9upI9-&F0JSg>(#=Q&oncWc8Pf@ z*5yAE$^qCNJmw3zs_Qm8i<|wW`&X(O6%lvM+?>{*C6Lzh#s=Rcq}ZK}O0R$%x8uGc zhj$Wb8k&1B%>u4jC!L_B0uqYP60BB|h=2T>>>(1aWE?>hxUU_xX>QIZuMn`aGBtER$F+Y#je)u+RwM{~=# z?}=y2h{j}|O2-(y6{WYC$=ROLNC_4J9@gBS7mpkQ0PMbg1G}%?K(15<;EDCmD8=OY z+8C>eHmy9!`53A1_AJgqZcZSvETwbdVvS_9%;%JhF6bSJGNQo4qoDzO)_}vdq|-0G zh!;ONjjqXAcpVkA3P{5!97HfqY+lJf}789JsBry+#N4k$8?7`rqPPm+>a z;-@&Z)~rlS$@5!cG;>5WU!vdWcWS>JeR;zZz?oNS4zvLo!VUS8j0C* z#y39uh!6!nO8IODS<96QimR*fHNMl!nVQ;ET*WJIzgM-d1_nQJYaAw*)LN02_tbAL zT&sIa%Q=#yF79X6K-SbOo9nK>$8v?y5lezlMB;(ach)$ zwQ?>9FuSmT|L4a)N}m1d^RJ_|uM^EJ1q7QM-QjUxA0B_L4=qc}c;(&q)NgT*=irw^ z_~rO;G2bkr&?96da|E?u}I@$-7^yF+RwS)wQT|-wX|S)Vr)(RBC(ycuSoq=+YL?bWzK_8)SY)S zDp=_5z_tB*G1=F{lqY9{-L<^@~FBsZs8Y77?{&m(xoFYa;RS)SNk%^_Lv+xT|YL1rpZ>4 zBe!()ll7%t?hx#+#ac+1q=>+7eYE~v5{*ZVMwDfe*}pWlu9>tJzECgU&82JCBKW?C zo@|%-Jf$r3qaUGivjTtr9{9(10h`2kKTmSofh9%8?`t6w|GDa5>L>O)X?1mB$*dN( z_Wo|X_V<1T?|uJY1BV9Czhe+Bg+kr;cHOv%EmPB?WE*GeR%uHhBUpYD)|;kwt&zRy zm~Q%{*_ey+F)hyI#V2jNQZC1z$q6_D->^eoXRLLRkD%5Fq-B^FaQ$A?Fc^nD1sk_=)XUK-iMPw$n0E_?GPG3#yXDRp^QA@ znH`tlMIi?7k0XdGIQ#6{n2R5#Z4(0Ira(}ylFS&I(-IWXtfFh>S-r2dhD-%ooANy4 zOZEB0H5RmB6Bf_IWe=i(6jERAMlykXEr=zbP*oQFivGe*(08w>Y*mN~! zNCW82*IGsmX_Vm&P7<~f(ovK!%9%hQT{Fee5TqH!R51ATkB)$%=dif}D&eL1-Hu?* z?IJUejG;}D54o2}uvMzPX~vayDLLj$k*Q?d7~56fb&x^#6e&e=vz%QJf@Ex{jylE+ z%M3TLmI@{DpTOFXrmMqTW(iYHNV9|4C)&tur%6-!W!kk#Haj0pPZmIXo`(&*x$Y@# z0!8bYXc;JNrZ<*8E2SCZ0=#Q~n|R1oSbN2yx-)VcgrXJzFy> zArMA5v}-qB%%ETGxpp19uHOV58Y6?B_CcuMvnH69&&|HoeI<$WaBYytEfFmzZQaUU zf^@)@ke_SMW?LE=KH&`5vw)%>H9~=*!+h zK(RsN@u7pUWbTkU-^%S3vyWWnc^(&+R_uvS z9_YBY>}S@&XkC$msB{opFity@B-a%n?1*cEGgvq{M z?7eagyKmf3=}Jv`{N=YAj|%-oBx%@_qeFT$BNkqhQZtR;l?FmR7NqZTJ{2`mJ|Ywg z&G_qYetli-xUpw9%DEg4eRdHh{*~G@qk%BtFCM(AaZPSHx$tflS?1yzX(TbZes0P+ zmRI_1dS;^rdY5EgSRIWD?hWt2`J+ebwxt%GKKUX}oc;uT4<`(H3X}k#ik%2Idyr${ zCW$9`l(-F)524H`nUmz+P4Y!bUs*d>*`Depw`rbdFCTDbyeV9S5l$(hdO8Hi?UQJDP}&X?RI{!~uY$r2ttiWW8PE&4)TP z+IQO__~3`EtH##u?RnRhizNBJdu`X!-rad+P5+d>0u)8Szxg-7wQIm{{04C7kda+lFxAcs6-=`~H3W<$Lb}rMJR zNBHHp!sKo07mhO(r>RtLR%8qj=RGj~2ul@DBc3-`Yy_c_nZ9e)?G3hz+c(8_0 zK~&YRDZ~q^IxIT`Cy{P+Uh*>Pn-J_To$Qmv2 zi$mK71~K*KaYW-Acl{&l**5Rib5_a@R5f_{3xCc!r^=NI&R)KR@K4X<;D7QaI(80b zsEuhd8xkezooIbf&wZfXh3s|T%F^U)FtI2F_~Jl{6jF^^A@4D8Sr53*GQ0uT-!9dz zH`kTsziV$kmi1Ln6p&{TS-FX{CrI3Cvh!(cioShA%KS#;yeqAKR-13=xv}|Cy0g&4 z1h8WVo;q!B1eMFcJMRD=e+=*V>+qgC0`zYF{?+GAYteh%`N+SL&%3dq{LGxgjWJD| zwFk{NwLGa$m0}rlH^vb~5uVw%A04f&ncnN2m_+O15=zK9Y8)Y|?nzUNyy_F#9*v8& zOtAaK-0kI{D4fnEn_23~XJ+VES2&P3rR4l<3ugWv!GqM;LSduU$BM#KyKn>w&f|+# zwJa=S$E~}_t(KCxtW)obuqd0)ajt}d~)X#oOgj`9EH zTQRZh<@IICJH7tWh~>4HL{|rceYZ;K60B=wQBt|s95TUjHnL5YY5CbIsRr8;&@n8I zP<2rVLv&2f;l=k)L|_Hh2E zPrir~AAN$t;tG(kWIp+5uRKqErzhrmA(mZ%OH`OjwR=UR%{&`uGH9YQT)@dZU1}Pd z_+1Tvq~R!sGR{7K94jpaEVZ>ZbUj-spU2HzI}!Rmc3-`o)Xq10fXAF64bL(=;+W=t ztS*pqa|~d4T+I_u1P|kQlpffz#Y+UPo6G7RlPZLSzkr00wu81D0j=(^YA8*=)FxolC!i1PV73K^nZI%ie#(H zI3WATHX!KV^!0(RzNPQ3nrXd4>rFa0{Wj}h62?n2Ij}mi5B}r?yoGrsJwmV(suzZM z@x4U?9xbu{nnAWgk{m)Oz zj`Ix@Jz3^V@18jQF(RL_kt{0$VrP;Pu!?3J`S=_n-$TA!Mj3ov@KReV-hb`oFNMQ4 zV9OjP84+LVzMjFaEx;pUD$rm=HE%$b8N5v0tZT!~6m4V!q-2suVWr6oNxF3YkVbBcnC@>bS)1v!yw_+(TQ}qwGRh-doI?dZD!8?0 zCvNQ9Q>Vt+=(A^!;n2B@7`*q;sFx}Esg82}Q=QF7Ox*fNwVP%QMTMey$$8On02!fL zqd&9HVWpxJbi6=rhH9gC{F}5+P+l-f2Ozi--M|&2d}<}dIAJFnK9tWrqa(3!8SKa$ zs`5>|tFf{R)0=vc-7=nclwR{{-Evb-Qk``F%S{Jq)sgKppPBvbIcq4(=JGd}YRmrh z=KaOkq<%^n=(m3xSY8JH(LVyd{q4`K8d>zMwPWl0F*WOzWoyG)W}0$Ezr%=1-(kmG zW83}v$cJT|J&_@3%IPsgzxCI^PzU^f`pZC5ZHMj7xjDS_{wYx++54E7$FjYTTWVte zNW8(RBnKsoFH7KeZ9UGmH^``9BzxFN%g#f#fl?B;k0ALj@osVzlG5LWq0NzX190$Q8U)Y6RiKRt_UV`Bh-k*!@%yvei~ z)uU3mgsZo2W2v~phl1+RN?1X~nbyUj>(2ob#{q;PwH=1On@5su9ItgUT|>#2Ol^%y z*7%Jgc@r`wq%02*aa&ByK^~o!nu#5?+HIRKgSGHMWnGeaz*&Z812_~&jORI;wLHMA z9m%!Bx#`HQLmtTfmpYrq`()!JtCrbX3RXgPFnWXRC0@e+smAhf7x$5TqHQ_aD!`*@ zqJz!E#!u->K+DU(CudOklfOpr%25O_9QaB&Y&TA|SCMD@wSU*#*_FR%r1cEmD!HXg z>&ZgP52x|j@BBM>-`tBMM-QQ`rM}bl*8308yt1OWro3l?T4d^6cAaE9w2adzUGiQn z4<)${yGi~p`-L%g{IA$jz@veFYrN>Kj`?|XPt8E{+BkRegQDC?pXdJI^jZcJ9^@m{ zW#p3mk`NJ^7K_+<^_GyUfEPwsZf(JIPY>oh^#QZZqP-&{z^}#o)(<8o(0=z0(7u4E zcNxX$1zfv&1?46m(Z}~Ncj6$9e&eN0bKE9+uzf4GkKIGQSgOj{FhNpLG9ogRo2TZO z)-g%%;rZ&)^H~DdmZ`Pu#Ep4_IH|q@ng-Gv1>h14yO@fpC`L(lq(=#JGbdA(VdGY$ zhDHBlS4LOd1#&Qq)A*GNx~FDv;`GPxy$BZ$AI4Ifo8c9fS8(Xu#iV^wVU_id;GtM( z#<^oho%v*;2V1vds=8Q~TN`sg$wI9yEx7w|9M|rQ;lx2Za*0W%88RLTidn$p$788a zMbK|#_DZ|@S-ZY!XX0{G4vXz=Yi{#gXD2>;<`@oMxP*?``6{brb(_q1wCpQM?PPo_ zR_RSAZOI5~Db*~Twc*H2l}(|b)BHrX0%04QrRkUFvY!}_!sPElXFC?#*4F36LIHP1 zhB4FKjh4k_9Jp{fF?L3vODJdrXujB+?%W18fJv~2>a1duss=<-rC^gQJNeq6Jk5~e zf~^u<`;Za0)6X%RDvQZ~rHNRc+R|K($DaB!67yNYd6-cFbmQEghZh^UYin z%>k+I()EtE(&OAs$8D{^xm7mZZ)xLTI%At#Q0}oaS4k~3o%&Hy78zPA%~JsWlp3LO z88~w$!s_bgm9a6~GBQ7VRo6>nlQw$B@0h>qv}XPqV8Y-8lC#Ae@5+JwnCi_2Tt2*T z9uFoaGNmQDH@qFW)iQ?eJV<0xXz(c)57QeIvi`40v;Y7g07*naRPUsAp+D0bzT=3Q z2ISmt=Ek0PM42YH<6f_TB6<=aW{eO^u28hBYCI^kpwc@4e{Kf;{4Ao54$*$D zNyqF0{E9xgy%uW9=h44q3o4ZgzWwTJ0DyPSe1e79Sww$&9v|QR3tVk$gLiBQ_}*c3 zwzaM4)|xC7c^+oEIkNG^!-vphEc}kSdF;DF~~LQOXw}N?c53E)s>vyK{If^hThM2%d)x>(5FMppp;N+|Uu8r3_A&>5XqJ z)yB^CIS7}Vt`pRLM{WWJkP*$bJt7SJh7WP2Q8}MO7!a0o@d<4@&tmCgr0l64qqtS_ zI$ttY+mW?2LN%S8C8h)*-V8*oeKm(&2ZOb3Nn$Z+AK`f+9k)^CDlDtmq9E6Y@`aUnO6P1MS@ldFTul##qiqML3)QV*04XEIm;k7iu9 zj1g|`P7e>gh zmej#ziFZR$Bdz_|oSVPv=lV#CwkT2>RVR^;>>FumZrPuOpq9WCqtbmS|eu zNIR@-C6^qjeU#3bdA#~J?;_0kIQ8;N8*(_(_kFZ9i?QtI&&T%d$G*`~0KntvY5dWT z{sI6H1U|m|wKtL9AYG{zRe}KbhPPv~kFS51^5p1e=g>7h3r4yz#r-W~l(M`g9ZBOi zmg_vy+6Ke&kY%!*Uu&0fye_kmEp?@pr*>X?Rb?g9T4d*%&j0G+WLN8J^+?)pwjN{K z75Hve4opREk+j}8I1oTbCFEg8#^ky@sb|x3={&g}8L<|cnV-k({5)C;%^29yt9~1Q z{20a6RrGXqp|iRdxU#y6$(dIh~p3dVAD6wiTbf{W1D~;n@b9w(XJBPtvsn*XP>Uczu+8&SjsU>z&Ev zN(J{PCh*4dFQ6%7(6Bdq2hcG!kFxPx)+93e*B%jVyW~__^4ig=ZHH%hbBCD+l_Yrt zV@QacrOxAl0_4d+WPC3(#1rXk#`T5DO*(ArgL={y5G2mek!q`pv<-_xcCmj2*#ZFC zk&gLjQ2m7ul56{C{LOZV4^`j$qJC6w-DVzf8Tf^BV=X{yi&Pu(B0_Z}=pYz-6hM_J z5wpJ4LAFvK;FI%@bzRvTS?Ke^)K9Ve=R}K(z^9)A|M$N|ICLETH{XJ{rL+Efn@F3f z&!ltmdSs`Sd^zn6X>pTvF!_pnOItOi7Q_74Jd{!_G$%fQwP?Axg8LH_Kp_wB@4f_d zWV4a%xq1z4^GgZlHvRH6vSv4K8{cZaD!HYMdaY%iwvS3O5ige?CbtZmIDVQwkeEW^K%^#jdv9yXu ze|8nuyi16NyRdgS#`XDp4%_+%HoP8J5A4I1$tg4yi&ed#QkA5n+ek|Z*{r4GHvR5i zeJc?;sbaEH%bly)LagX9OO)F=p=z}} z2@xgf0Kf|?=zH`S9)JVhWvn*kK_)`E`5KhU=zTbu)Wvo3W3Hu&Q@?-pD=un)Vh-ayCnykH7kIzbA}3N(X|t&)OGZd{T2-H4H`w$dPBotZ`oL22CQ zbw)Fp3`EjpUT!1?r~rP1i-!)OxXw+I<(3vKx3r*Zb{4TyxDR$={p$FUzQ9R9nAHmC|qhM#VIG3ZB1w6h*+phwbG%#}ktLfcE%de0n#`Q&P2Va}@@~0x;~{KqNAU1I{OL)A9i2%n zBp}}CcqNzDGQe~BM=bl@8=y`1?y*OkoI zxba)Gxl5cv;x;KIWRz;kPa;*SsU4MC*W8ZyOx82Ag(j|q@gxn|g{pM3Uu_GNO}1N& zF5SeD+7e^tZlh;zZKyumPTbr(W^H7dyfLh2hnGYFqfwMAH%jJ1s6LUD;PRx+)n2X4 zxja?29l_Ehos(Qw8$+9kqo2}~rRabEV+3PY;l1?+@bU{l`^H8J+jz9FKC(FvkT#n& zmTi=5tY}-uWZ;XKe@*uH;_89)4N;=ypI*iM?|lG__Mqdx{yM(?@~a5yI1Mkhx8dxG z<2d}uc>p?6v`g!d=$4~9GVin|)%kJPT zjio*)`9JBFah$3MemO+j+yZI;s{n;$37B?}|Zw#f?Z!Nf2zNht)^d2^U z)7pl6%*Y19zmSF``_E5m!Pj`l|JQalx>#NEB3kLB3$hMNbt@K{Ghds&QY@laT18j8 zj?_0ZKaWy5K48<*TtGgT!`$LRYCe~4-oT}sH!;}ThgXj4n-tzT^9iOd-@&nChq33_ zegMGS!UAsGy^C%A1DKqhMR!LBa@AYtu8oc1!jDd2XcCzI)j9NZ)^-^45^k4`T(VCh z4A;Elqlol9`#kqN4}IM|sQi!L1ppL|3}<>Ta@LgO6*>6;dd*3Fn&;+bXeutmlbxQ7 zrrpw9z_(t0Wlit8^#+&5#wh8%Q`B4BO~2-g%3>GQ+cZd{jzq||lU z6mKg8QUdmtWmJ!iMllsb-Hjg z47p(DZ1#u7&^jm>^ZG#K89#T+n_^2d#&(ZlY_$H(#}5Yw@ori89UTBBtWQB>$1dEdaAq4WPBrlGsA;_+zDR$-WBVC8ttoLg~%S5KC>XxHFOs z)cvf`TxTbyw`{@IyW4p#8wIg+}g7XBiC<(oV29^Bb5P;8ZCdTWdP*QWVE4cpULfuL@$l44|%{q zD^}*FhTVgvdLnz1!Jo@v8_Dkyj@mOP2I4Zhn0C;P+Zl>A7q_PZ=`aPj`LZ_P%GQU* zXHuOgoouV!6MEg6&X1&!%CUCwW1bT-H?Fxhrr2*uNy4M%&O=KPX~a!ir<}Sm0BoDc zo{ZV+DSg>!brraF?PqJ|tOq_x9va-WTRop!TtGn>#?D^81OV8-b0<36p3IeWE7e;~B>4!@R4fAU&^z%MJyX-* z2qBRgsdyX7OFqksHt8K$qlD_WNR25y)sj@}98#BFJGo3aRC=v^r3|hYA>7P&V@YZg z^>R1UYTeg1x^eHzQDZ{}b2`FlvCbT)G$Z=++7A=$)UH{aPn_c7uWag zc_IgrH-vgx(EQR)?A*3~2VLfv(ioVAGXQP!MZyi^&k&;u6q}lz2RYV5#pY(rba#o` za1G7%Z(4+C(~58n%{Ga0+*T>OH{ATeEn{5ivf$?QGHOR@ zRw56_yZRGn5IG}wGmuEGbbwd2M$OV8V^gU zY-(SO(W&0?XFhfXkffLMhWlO~7BR<&(wI29mdv%^X@t`AU#||)7(IFfw6y^v_4kLK z(psrh0{+Fn0PfAff9rMNMuEdDBg;|XxhG8QPzgurwv}>gY-S1J6xg=TOLm# z2-CMVH=0_S3)nj{g61aeJbm`^B~1U}hrm!Lmfl##gU9iWWbLi3c>eH_O|KWt-PNWh zzypTvjaOrO#gep~I8sJpTv(#|U`vITd*%$?Sb4NwJF(^f_GeR@-zciD6VxW=Ynm4{ zss+%h_QaZEtv0SHl@P*5fDoGV@cJW5lf2QDEmS;TXa`EV;!8aqC?~zYP+moM5W(}} z_ipbR#m(KjGWF5DM-MUf-~rxz;YF;h7L(^6e0mm-XJ!BZhj#BqZ+AD|{`ljXd9@Z= zFu%BnAHMsp^;^piZ{XVXSzMog3;-DH-GaAXc@^bK1%Gww1HARhtLPTCHt*$8JPrc9 z|LIwL=k>2;Y73y}qD#V(z8rsx&=Ta(o@++4A0&>i8Z|*YOE0SyHRbd8rLX^7<~EpQ zm+fkwmPBrHKlhRu?WLyKSkfz-*8pJ-H@A|~k>%FLQgg8ggw*5Yu48IKx>mJFu6*}? zrfCD`$eJ+H(eLd1>?Wyk@X=lV%r@H?Npq+L`MZqoN%<0P)Vhzvpi(no`yJKWbe1;t zB(A@XTrFiNyS%eT!lCoz>W{=PZtPEZU*C!*gZ=qx+*mIIfYA3*ZptNn*;FjSk1Eyg zGADLCXE{T$K&fSvKU)UK%K%1SQLj_aNIM#Tk5n3yq+B$AcdgDeY7E2M?>wb15LGI` z*ckBVe-4~G2fXvnhGktY1Mj>Ot;HgweWPkJWT0p+U@MJ_^&OwYvXmdq>qd= z(iRx=*zxV#GdXOphqS#=TK4%jlP9y3CnsjvKeioHw_D?4iK{rzn9Q4?Jw%9npwyJN zIMmex`*3fKK~y5o!>N-m0RWDj`4oc>9wDeys%@7VJs&pGmIxXClzg$IojbWpY3orV#FDUn8By%CtyzJGMuq84k=BjuB>iy0FmIfw`{F z_Zo_$q4e6Ohg#*h49@1bm|K69T!8x{+cxA%MWSMJ zGj8qNiP7t~RA1A0hpL{Qvwt;3U>-of^7&QHg=ZO`ZkAUx>Gdulm`d^>%xBBI z@(w5uSMZi3=*ea`Nwt$&-I7*rw7Z&!jdjw*x|xmLja6tP^kZi=F)=bfHfGHjX}7hl zQA@2>8?_+`HpwOk5FkL9LIH(>sX|o&<^6k^cYowNdCt9=&y@k#92`WU>gBt6^WK~H zo^!r)&OLW&3D)6lXn$fi+MCMNStM|l{LSQ!x>m|<*STMGmN8u)3y&4I#5TrG1|7*( zgnz;(&(PnJ+fx9MtWh_u@`feeZ|h;@@JS?Y4#K%Vj_lGRR8c#pnOFP!HSRS(RS+BV;D7HfPN0-xE$+Z^N zB=j;-t@$Jok1DkB2$zW}M_LVM!PPMftuM|b%!_xDMm`tCNI_y@0}zjJfeD)A|4)d;^^^BYT`YkiGWBFpdHzmHq* zevHh-Dh7W0)w1r6|p28#`<}@aLx+ z{H@Oj&JfDmr!A=9YzJ~gGe+ZjbUngEdu%4xo#}-Tw}~}Poo$DSKEU;cR@NHc zTP|&fbf@Iy(L51a8ND7Izg41Zv_H2OJAd^BOkBTcy8amtBQMZX3t|iUYWpJ~v7nV|J%R7mYcL?hvE|HdrsH7ex@vaI!uZOl$-s!V~ z=A^A%DgEqlzf7%kqr^6aVr5ttQQ$SIBCbkp)Wj)KpILX2eWGuDZI|sKjEOz*w*|I~ zux_Q}DL`S(&EZdmPUAoCKY+GGJi>NYoOX0|V@Fpvre_Oqz=N;D&TAj^c2Wz#qMl`JNSM zyRZyNrsP_>Zo^2GH_&siogSp^b2akK+M0%;K$)waDz>wLitc3>iJQ5a-y$=Tcw-(C3A~XRLpEm48vI^Ghs2Y2%Vw&&y~s{ zAMGAirj@u`1&h(oWZ=NVd|eGjcJyMrozw1r(&^5
q`S#*ziz<;^EI;082KQ@jR zjZ{#hAfPmvO2Dc^+sX_WmA60Yhj+n5DYKhpR4ZLiIZugFM)CcvWXZj z@7r6(^D8G?ym@K#qJ67oKg`dT@kv5xB8E^hYorV}@Zl2gjM7;@&q&z@Ig*lh>N8b^ z`Vi*nx*1<`uW)Tr5t0sR0?$#qrX_HX8a)+UlUr4y=Oh^+{t;`r7Rc-?jyOO=Kx@ZQ-5DdYX$!;RRXHPln?s2vAoi+mp15^ zQ|4jN!h*u=to84M&-5`FRPO964up%#u&8HjWY$OP48=_MTt;$8sgu}H80qaPE5q32 z^fcD8S>VNf^uBr=J!NEQt)H1e)xu(kgR>#uY$0IsdI^T3!JjD;%zO2+cAyJO=_SkQ z_euaN4WxkH4i(hS=3lOjvy8Dcp`fVzPjd@$U43xwPat+@1lisDV1Z4hl=s4Ss(ILc zdlZ0$;r>1>)IOYy*Oq1Bi310N&v(Y};ogJ$n3(KtB;GEDmysREseO@-@BzjB3nVV)zzr2F1=Z&d?FqP$hUE2_AXZ3H2^?IRU=wb z4I1a?EiUVqj}uc5aP9~1A@ki~ILQQd{l-gW-Dk>&C``VU7`-&n+%rST3$1+qHoD!> z##7xsQ6Am??irl_@%v~!u?tAsdFxfXy=I$$0{e=+}|Hq+Sic?*P!_53i* z;ibIR@$LF>Ym|=gaPaRZ1!q5|JUw^-eEZwLd+z~X{VMR{i+)=35_Ibpu)12Z*dwGU zi`GVErfxfg_|fIHd{!7`nszuP>ND+I<;r<0=D_J`LQPLC2Kq`n8LO6-&@nm|piYyg zMOh8)prkn-VT{Yyl^84Ldr~?wtNgFe670^8S096Z1 zpfFDwd0!`CG;8vA3JisKx*Q+o^psVYB#Vb_BX>mxVW4(y0X6gUSgxwVL|f@h=$k=1 zySjnj@Q)~HnHWcXZ7o!K7MM<9b!`n7hpqtt&i|j^#q^7ZvH$5KXvl0$5~SJsI^5XN z4@)Vuj73Y48PD=s zqKU8!EQEV2Yh$^xHEbo1qSBa|k+rF4zPqyyIl5`yW7dubj|GRw&Uuxfu{&cG3NDy5dx`xH&WjuB85bA4d@oS&|V(^_j`E66k zD*xRd+Pw#R`**-`%FCuKrH%Z}S}x%`6QAfCnJi;|>wHnaCRg)T(BX6E(K0p>NSG+^ zmx+^L{2hh3qU>IUP#Jw+9u;0+%mK|7=oSfy;ADSX#9$$t4=eVOM)krHo`3Tce)9aY zo0=TVjN&k{kuO1=d>d_J{KLdj)qH!Nc&m&#{Xk(?gm`hlbMz)%{pp-Ojy2NTL95pn|^W#YD>aPHUg3Durf6z2OBj6}>KIziHp#~}Pd9jsbwA}aJPiEN9|1!{z(4(`z>y=5xEBtac2tSf!mSf@bbh#y4jxiJ44G_q(o}ruQym=>L zj_L?zq_=0wgS)@<;>$=R5@`CP{{$zYaCQ6+&R@NPKmVhD1@HfOANC*oTu}C<6Hk_P z+M21`Q_#HsU2#;(IJy$zmAoDba-N&ZTsBu3O%Kzf5z0|rF9yU-BcLp+*QLWSQgWoJ zgs!o3g%w&lScP3xGV8VneMEV8V6iM>fNz*{;KG56<=QlE?Ad{dGA89GiE65vb0(dw31!D6hf>U6Ln!F0lhQ? zL<45iG$lD-Sjh1l;G8YGDT2a7q(hgXBh|#uWn+fvJeND6Wgo)3&3V-H(Kesv89n7Y z^-~o94m0;v9&&-m9*}W>_;&Fw82Oop|$5fh1 z&yvd3W4%sO9*2Po-D7F@>*jCCbE%XL7|0M;Y`PGZo54SDBwTccVs3mNBpEy0ZRUetWD(@qwP?-m!zV%ZGbX zzyhtSu)fAR8_f(l_EqYEzVl~v`?iM`ugC~R+S(~fJKTUfyTnQ0^wNo*H* z{r0^vv@|q^9NkMRE0~&{MQ2;(o3RV=Pe7kL3KmX3xPhb{$9#4P2R)!UwfWh|>uWP; z+tZEl5ANXH_ueTxXxns*15r|ZGi*}p*D=fIF2(IS(HLa?G&?wo^vFCK50!VM;Xq9t z`ZD#x#BEaX7U}juWn9(qnx5rFcgV7JMxsLm*TXH5n`sgJ<{D%fI`7VRf>J^S<|ky* z_UkdT(Z~R~FkX&oH)Bz=WqJ>EmjgSFsYYMsk^VxMlU%wK{tn2j>^v&br%rKy9Kkb9 zEG^%!1TwNm;Ixo-g*l-eH!@rp9fxl9Vl}n24m~BMA>_z#@4iR>axSp+MzICSA*s1Doiys;#N<0!T$D)jG*DcbkM)VY8H(T zrXnPnmCt|4(u+8y4Gzj?oGiUr6tqS5U_C^l#X zzZ=_Yx{z`bApOs><9L4CGXOl)Cu`xs!j8ILkgq3`sKu+DPs4&j%t^z8!m;LENZAhL z+wgx|sEsA?rH+2ICS+Qf($u%T6P}m%S=%a%>tp;TrC(P6t)ITZl3d5FIx$+dgK_h~nVxBlkljvNV*w6G59=-d zRdZvuSx(2yvd!}3yj(sRLlXw~>=vWRqyTh}+{X6XcR<-nC4cofp$lK`a`H4TXG6Cw zOY4HvS;JVG0tFr90LQ}VC!d7p*jT8kK`vI<7PFdS``_U1-N-pHbdB5wSppaxt6*dR zl2IHJ!0*-pp=POD(7T{7;Up*K=kO{G(_^gtDWo^w1g58fFMbht@<~A0 zy*ElrOTd{k3Y)~L3(}*QktWtIOvSOce~oz)^RXxttF*GjDRfCx9%bJh#_}J(1w2>+ z{`4JG|LWIZm59T#Jr5^Ne}MGTO29GQyv!ttBl}H~NbhH~>>?Q<`LbDt`1ak-?HK9p zj(qQ>c=c9MHXcVdue(mPwc`BI!#MQedE}t$vt$$Y|Mn#-y-QA&LDo?U>t@*?^R5@N zL4>k$=M-YOY=m82r&unxxq}ix>6E{@)M>0m62L%JKRVmmF*SZ4r`A?{n_iyYK6e&R z9yo~JGLqP>k4P^nO!95Ws~cfyv8bh5sKR1PJNnwgVu$6Z3_3|rPRffO1OV+5D;%^8 zWcVGao22&9L9FCx0Vrpy7d(+)s1@wMi~=Wqptm2CLe6Q0s{?y5*{UBy^|L^`dV1jg z+AFvzL0OGd}+Y3F(5>MpdU_?k4|m`7CU=7n&-5cGj_u+T_a+Eb+aouDPF5)e_>cZMrY?-&Gr#*~ z?C9z$Sw6M00w>3YY?-fGntr7-LzmOsMq6BqHrV=~rK8#Z9nMx0tsjJstFquBhMdON zSE^D_mKm6u4;u0mlFKVlun-Hb+Y$XjATeBROgy-49hlv=6YsTAIS`bhx5aytD`c5v_L>c)=W{dM4XftmR^eE*$y04R8W z`8ModT){gN*Kv1Z9GF|dp58tje&R4O6I^wgzj-@(swd3kz^;Tgw*VZw!3^0BCM# zL@b}dYi@B7OUp~z{cG7Qe)Rr(P)gzXW5-c1j#wYQIE0I*&Y+>a8P9#?mEiiRvuAO5 z_Z~FW*P*t$CRlS*vorX~xexL36HlVGv9f@Xus*AkbR7dge{CCXElviUPS+Wu>mZ6} zv&hWOVXm%lR>JO%4%lD)3_jf7flLJ(LZYN(xEF;#EA4kFTa*fwiN?+kUsE=5Q#o|t zcfN!Jzw@PvpQArRN2TRGn=NMYF4i)nvsvOb6U&*plEjkSI?6Ue?Wa@Me6GPRPlwR>Crx)6gPWU&Rea!-eaRCUlCvwMH@Iy&hE|TM; z5LTxwBC?Hc-pOp*E_6Lqw@|QCTS{k=5*~O17V@La=Zx{;)H02QT&0rFOXN%PS6+#d z|9bh&p>pecjH7>sXk`WX=p*3kUk5H<2L9nc1itc>vTpS}U}gsEawcz`p0+u(5nH%U zQ4(0^;W}nyo=ZGzxjKcB{$8>1wJ;6czJP(ycX`O zC(4`7A^@(Pw+W2H-~)}FF`2_wKH>oVy;X* zrzZohhQ!z{ZVOkie;3Pg3ptpZiF}z|JF|d8XFr0jZSY9l>g~cve=nBG%-*(MO2p&% z%u^=;0B`+wG0ZM3VEV5v;8yA?@IoK<^!A}4lfl&NOmI(2Lu1+5d<#)77Q#m}&QXI8 z$E(C$`unVk*PuFH1H!=mvu!k`n}T(u093`RVIhB*xt&0Bx;fyp3LfecHF^HQ$!Fxu zZBJDrjx_+~2V8tog0we6@wF_f78c0o!4Z7n3P@qwuyau}$esC8B12VZ5qyGMyjsI+9*7 zwk`Q>rMYjG@nGjqb%2!hXwgo%-X`i*IY(oP-z?2uPID5HQ-iXkKT{`8|WRriTVfAnnVXk51^!j7R)Tw zJij^QJW6*Ax8L;Hvd$9=HcPmO!Nq9THcYm)U^SI2x?YB3F-)|zA~Q3K{-I&`o9!If za6w75e4fdPwyb>bKHi*6(f^!HCGhdV{g`fSfU4l6003C7O5U&I|cFO(Lo3O9m zf&Jo(z-zAoo2;w5E-*X0sa1xkkVhrDY-QIAeP;!EBsj)}HbTsU$F`_5m2ttdhYc^O9ew#h>5!9@%*8kJA9MQA?A z&rw|8h6}PW)A<@^XgFZ{1QlBDO`v*V5%ZZ^4DH_eFop_MsT8VGDb&@}AoU-7QTy)0 ztCw;1@+Dlm<=cgt>l<)%U@x+{EZ#bE2G1Nhf^;$!v1)XRTESr|Jpap;jOE&yW9E`B z_pxT>zJaIs19hNYxGulGXqBLpk+RVDtl+aEX4b8PbG??RJMZ$fgU=qyWv-h+N-1Q;E{b?87VN5VT^FwB!M5$dsZHghc0IeE zhumrwSl#?x8N8bqSja8m{~CG|0PyQOUPfcG7BJp@F(Q~#iegR-b~=u8fBY>d$HK`! z_^qRA`f1-K_PEmplbMUfeeq*JfIt{ zA=)bg07&W6v%2xIRk9^|d*zNb3L#V4m{a?y9mL_O7cxVQZ!D1c$9X-GVbxTfOrw>Q zPL%|jMZJNI^MgvMTt(zDJ*H?X1!VQImCZC=Hc3Fs^%nx_{6q_;jFZkbCDwpvl$8L} zgA8PLV@_EHzicjBaqz&w^B2%KIh8jv`ld!QIfk9q(Dq*ni<7-hJ+wqV4ExYpXbGco;R(=P&Njq5;MQ{Gu#>as_{6k>hzOrx6 zW`TF!d3g4BrYQGOX}fCF{krBFjm5%NC>_^IEl_uoS}^&OrQIv9NuH%|G`ZE+Q&zzC zdMK95A-S>|a620wa$0M+*OI5x_~_mS1lNgco7xCr`zULocR6@|9J7!3}HBaMV?2lVa$2MU~mhSzxh{?l?8W5t6yEsY zG!~YYP+MJ%7rF*e)!qOk9Hf(}va|b2nybs;qoarL+#9FzBdhC9yn&48RFpqT%1&B$ zk4jGI`k?+v>S|$b5~ip=j7*)y(%LjyYImWjx<~uY0#IMI9j@mh?i3FymNq*DU}@gw)Ur_gnssD$g2! zDZNP|WL~2t9^ju~MS|>0(J07AkuCtsQ)nKa3{c_qT{|#aS9#EUa%B}e2Z!J)U+xjY z(zhX-Tb4`-PUFLEmaIu5Ek7SZrv z8m(g!24Ap)yr>fAu_c#%%!FLoYZ=x(O?fAOVnI%6f0d4Qb>LQCH|8>h69f<~)YM?1 zrUrAF4AxRf*f|e7u3pdkNq7#C#aUu|^DRhCP>#30Nt-eDN_84TyLV!ut+hbwO4DLZ zH5O~CF;|y??Rn@Qx&dDUqs=>kdm#Ad06|XxFGp0LMFlGB>A?t$?Ud{|iY>DOs&hJsxHn8!)!5U5uMg zV;vn>HBL1BBvURH!&pZLY}doitJmPH`5TUWZz!Qffc&TC+a=9YUgdKn<=BO7KmJt? z)@Dg4Vq>NI<(+o#FtK9N_;^p*%i3 znwXlxw@1@+n&n@!%@o#UYg3Lo>iN&icuCZa|gOU_Hvx%UTXr#fG0N9&{L`R z9O6$Iw`CBStM5$%&sn#D?ndw8Qgv7md^J~psn-xD04FNURu5HKK(T2Gqos2N-2Ef``^d>{9Kv+;(nMv=5-S&>-~~W zW)7&fMNKB4wuAc$%L&Q1_4~s?;}-nv+NWN89sr60!`Zqz{P5LRv}-5deGi%GS$Lw& zY?@^=t)KhXKUUFg?||3Rj@Zp>aPEvC*WK?w8w8U5O*+0D@#V8$3&CFsO0x0PJMRT! z>WQ~+Lt(zI7Vkd$biw{?CcX01Nhqc8erFFZ4h=%RGlIKszkz@IKh7eZNa9yN|Aj4i zE;$$ha(3}7VxmzgpLAVLQhBJb9E##9CT=cPec%wFiNq2tib}7&^6)D^y>e|^&rWRO4PB?F-gvNJdme1h z+f*ay?yH07xHT4JKB4t%!_5cb(ltVyfH_7|Thiy4)PqdBmJEpSAd?gL$cnM0#HW%N zpYeO}0@o(}CKocJbg~FhU#J~Q`%G<>dYW{Gb7n2mVXg z0kuij`lz=&eq^WMzR1}nB@^qyToa91m?Xa5s6ATh52f{l!hGg2eL~6efGbykfAKH; z;O*c4ePHk2N8PFrRXVGpu#`?=S5)|(s9IIQ?@djE|1P8*=yjR6S#H#^;lgp#-ou$4s&$V(OC;ADg5WJLg- zkVDc+@>LEF;PKG$zAwwR-MWj;TemUY)QB@r9531j&$c&JFFLquckp*hLnA)_{0sQj z8$ZTZKl>`adF&ry;WrM#-O-3A4j#hZzW&ht<>>B!zXqJVt`*j(B>rW+mXVqs@LQZ7 zg{+e6iCUqz!Q?K5=(t&* z#f(xq>vn7JS0Zb$k1hZJAOJ~3K~!nhU!tGH{u;TGbgf%|w&@!PuQ2Lc7+-z5srmkW z^j^Oyl2(}5fIU2>J`czfnssTx?@k$a`4T}txzEQZF8pnpE#s3=mW76?Y0PJ8E82t; z%jVE?a|GSPw*XhcMJ#x})VxhZ681cXEz=0D(>e(In@oFG)Eo+P9%*5SB01MhyAyxM z^IC5m_kqUR)CXeuaxPl$O~A8l-0bhgOnp5{QNz?U8m6Y9U?I7>ify;<=JP;1h(dzg z4qY=c?Hjr#Wy(b!Wy|<6{mF#+WWe*i&UW1D>nSU{=>3*v+;3^dTwMm1QfR(6DQ1a@ zUHxmyXrpYu`KI&{;Xc}-A8x+`4-Z?*v|N?ONN*1kt7`#n^`FM+Tl6uO7HRor ziv4h{i?ubl)z^*D?b|A9XTkQT(-`UNf#bU9ym>o+GNqqNjQk6aQZat{riEJo&h?yW@GKo8dYKkF0?8N zUzfUGICh2aWl5s*Z6)fFS|7*6Of@y)K~s5&Zmix$SYJ7SbbA91?A#S3aVo&mbnRoJGbQ!rwEXPG)AS za>=%BJbmmKP8>djLm%L7iI?Rk2dMiyMCh=Iy^6<`cPh+vRrmRfcuIEB2!1|r%U_IGYvOKqvTflwS zTV!%>Y9qur=w(bWNM+cGZHcjxrfu_@K3-Bb`oCxD>v8tPv9cVs%CbUZdFI4%*sh0N zR|nB?_g>IjABg(xq|A}DwFs62)zl38%6X)J`Ud8@cYv~W0F-Hr0~+}VD=Uy5!Pt7b z;f3XZLhbB4p8mQjLs=9@qIAy!sb0RT@OI)uLM z8#B`7;xWAWnHO>L?RODd%|)(-D1($grX1>})7Bb@_1RZk-{yD8t0bDrZ*RGByx1t1 zSXpA=LiOlcZxoNTFtt31v!id~)g52cS}Jk%@Z1P~I`%FalMVQ}zSjXL{JR_9!*Xr~ z0PuXr3Cym|0=&RiZ1sk(#3;5>EH}RW0U(E+@EBs*eL)@4j!;?*Yc&4R4cq{X{ zEdF%p1N_&!4x`p7KX~K2KRJa%yY|5Pjbk{JOycN%k#Vy^j8TlbJ37kFHodK-)z7e9 z*7L(F##~AM|D^YF37z+HT@dwzx1j27xk~lRQq(#zfg@+nL4h}@GWz0n!Dt81%t9Q* z|4#NT3WHa!;pm#ME>F3A#dMNzeT)=k&Wt^muOjYdaee2Gid$KTyrBKM;Z>LDrp-jo zgQy;aXG-*@WhIUlcA?|tD6FRQ9|b~(9PTGWwF&*Xf&2v^q%fa)$DB^~(8TL{1~Z9X zc|)_Fx6j1>2>N7dOmqjKc|zfwG=lE(u_aj{{a|-rE0cKx`RyptemwwD+9Vvfn9pZk z4b73fjxf^OgWKJ{j#)FmfRk^(3r5P)sz8nz-+fHm*xY#JhVrbF9ROUbBlX*nA?XXXIT57a$!kq zN*R`R5YM;ZZzzhnxspfizH|N@uKusz1eVs&`+L8Lmrs_)O$x{d(&;(`{aDaX4z!H^ zo3e;%)i?QYIdh|uf8C3$>+F$Zp}@U|!Jpm{C#LNE_%gQNx|`?P4*bo_q?7TsGoRBF zD)Y+$$UBw&mXnQ~=Y|E^&>Y5jdKNVW3z?}oyzuvL=J~#>-AChcyQd46_if$gi`uGc z{L1T}N6c~X3-A4JK+MLEKRAsKE?&TyOCM`xt5Yfba{eT%Ql!tXLbSEm)|9uK<0FdJ zul?HBS8rFtp$*+{wt>dHp{ldY8Vgyybv$kAF8oZ1srf2@E@ZFgS_@nFXoc&_-BC{A55WdXc!Imr}D?in^~y|E9;vxWwDz^zt$qA50;>mc_2C*9^Q9od;M3 zYsRJjcdp z=QgyCj>B?2Q1(zt9Kvsck}As6w#|0(>S3Y!O8{p&3qSa&)L%VmP^VV(HF6m%w z3vhyY$hsBs?IuYh+pNnNnr%|Uh_>=pLYukvAJZp@vRUBLCE!Ot0*)O6UViygpJBTa zVx6+E)GSP_Tbj1hLRvJJ3ER=QR=zH6uOu(H{Jr_T?8a zaAaSQ;C8(<(cXskyZ7L%=Ag?;X^W5=66=>fv36?(voy+vK`AIDwkF+)rB2j6I_14K z9+J8arw`LZckE0+ph0nJ7KGIO+I5GShaHnazA)alstb&~P2=rSQawDnqScGg0_{ z{-4eFzREAbwcKZ*#C6#hHvDs_pJYxJfa|k&Fugj9ldXHjGYR1NWP=qm3ku^a^Z3r# zAX2uC-|pT4%TicPCgGNmO+wPSt5+~GdKZB26h1Pr7oU0RBrMBew;fSd=k`oO@k?O=z=(}#})$3_Q~j-$D`87KB1DA{fXGXCKJIx!0} zfj~_xhF|aV9Z>c0Bpl@O^+lUoS!HF_wOmRilSrZbqZf2%T^JIuIHvO9Hd~-zP;*`B z&ee@7(9F0CeNXU4LID;bM6{{FT$d(%+ia>?Sis@4=Rgq4-;o-2M*vapTtZ_Q;~!S4 zcm}cIhn>Fsru7Wa655B~G;tpOMhSr|MYapd$Hf_+iEHsz5>xPUn`JP0l(EYH+ibTZ zjOc}S0Lq>)EO+w#kh!M)QnparWG-&z*AVS8b0vfgZu)oBUhXdd4EOh8Y?}{28m6W( zaOsM8!+u6HG8M^ycOu@jLjl_oV9OwRU5e;=z4SM3u4nz38(%Bt({)*9($+c-9@8hA zJP%k|+1h7RI=c$FH*``F*Yz1*-gEWxmZ-O|#-MA`>~xXWY3DR^_?2|J@~lzyX&_Zz zb|)Rm%T{qKbtkiam#Jw;gDVi7VT`U*a8{I&p^yx@vUdQ}O*$aY#bO&eGMSFby0&LG zJjX%jt=mwr^6o1Jz04!?lBBs6UUMt#l_davV7Gsdj}zo!ix$Z6%kqlHkh6TqzS^*0 zdoF5b{h%lt3g?a;!O{kHY?njHL;}e~0*H9bbH|Rs^ZYhm`@?VHd}0mO3;pP9Ysc|@ z`zwByvMem8(}1PxAz@9{)Xbs{4N1L3u9rt~6-iO1wkREUvvl5aFmWjw zy8k{b*x1p0qC{O5u01%98`BriUek@P%udX&&EWgjzkyf!emRU$3o zy{3`ZB)+OkHfd63Zf54>-571VJBmG*u0pw%IL8Oj5mXo{6`QGgdA?Q-Me_z}5h`6n zDMP)?Q$?XrEM;x&dw9zK*(5sn(FL@QP9U5ajFF%|)-s$*x0lEs$vfnaBXkP6!B+NG z$7-hQJL=7GPy}r)W{13j%5S$NSH3>NFn$wG=1o?*uE)4h>NM0|&Tz)KbG9*qi$@Md zj1<$h+oR~eb{&M;DSs((3(B-;=UY!9*>=!MiHv!L(s-Ex^VCiUImF=N-nMoO4*17d z7PBiV%L=}q&(z}G=by&YZ@&k}KX)22_(yp9N53=Pm6^g-&^yW$L;T7K`aw1tsg)KQ zJ#&rf_6=IAk8$f`0`T>(W96M|a87;}@mHS#cJBrr!qKgj(q_!ous&Ew7KQnssb5Ro zJPKbI!r@Xv=z&En)1-Xxxd1=I_B`0Cv@VzXzfZ&c_9Z|8*7gtKJpWwDdzjO3c#|9O zQa!Vmi8*9|xj7zoKJR9f!&%C)@%A=c-4}gY%X<7fn?drKg9E#fi^b4&<5vEPACOI) zn@?@D0!}WawXU7%+2M#ohn>A7(|lY_Z^lvzwi~UlB46kBTX$i59zH%$IUX&CEXxWq zxX04I?clki$B=b%xODwGE?gV*3*MT+?En5#{KY>9zWnklNF@?m(w@jRqLAGd2%k#3 zwG{2YisCGQ$?>ABLghX4;mCQm+(%jGb-o+cMd&ZxTPCgkgpc{2LOqi$FxwNhSA^e# zuB~^B-osil@u>^iZkU>e?RnTaIE4DCnTQPAdX{bSckzio{CTFaE}uD&dB28}6;MAl zlb`(TeIq35!U6eA=}E}fX2V0(;u4zfKPVZrUA44??RW0Na>E-ym3YVITGHDsKSA`R z@N6qY#kGsVL~~uX$gDT&itHzQ)W~n>fdn$9m`|2zux1+T;l|ddOU%~S;p)CUi087% zOw9)P&1?%JJo#q$Z{~QqJ=gSyL|J!c8|rXn-vH)oi=R4LjB>FUE*w6H7wKc}=-$3G9-$P=18?4t}1IoVy zoeH=@l-w}2Ka!v2YuUj3;v%NsyN2ZVuA}A4&z5yhVs#A%KDrp_UU~uyFY?)Qbs6O1 zPS8F8n9F3gbaU=T$+m5Dw6q{Mdr0S`-{NR8m#UHIF5t13f9i$eS49a znL}oER@3UFJmu@UE+{oD3cR*NIsJZ?(>mv8kAN=6bq|a#;Yp&}T1%QoC($}O5$Fxs zL;~5kpX_$Fz7Dx9^1n%n$6|Ql_z3{OOC8&AyQvv<^Q*YGx`OewHSBRxxG*~j$4&(n z4+R@_$vUKCRY70r9q^fAre>z=4`iz^MNwL?ycUxM&1FkdgH*Ms@4^qMOvqQls>*ee zg$IYwjYB73#Y~}Vj!~(?dgm*s&(-c4%fBf$CEenEh*n=ck1jJ z9NN7bbv3o3!jGflzb{xw;jG%j)pJurVOsCW1#+U|{mK%D=)utVAe z&tW!cu1ARSg@O0RNQVVc>nw_N(IQm@`SxtYSF<>L<~%MQIk0I)YsYm_JGYRB@wzEq zhh6@4cGc=_mqfFX!cxraVRF|qWw_!XX!FQoPZNfwBS1I4_EY0dx*o{t91RTf>{DPh;huy#eb>`*7m(&!MBG%w5s} zFAD1$KL4ik87Mr6dKi{Z{&krhOP3{4Wuk(?0iOpC4(txqKT}^H1X*u3Emx&6+~0?Z zwiW;uY8Do-=knEj1{^Z*+kwH_ZEk_rz8$eE7ZAU92W#zJ`JU(jb{v#s8c0|dH4PC)k%By7sT`_K`x$(;Dp-4~$=8>49!~rRQ28vkbR{~oqe+A(So3CgFNLI%-d?q^ zgrjFZ#D~X^Zn!V8Tn>rVHIXk^hIyH-W^U-WQRlXWFt8GLo7`6~SN>Y2XX@546D!N7 zQd{NUIw#a^6!f=)?YBqa#T*Rx_m$PQLUi!_1+?CqfRl5L%xtDJT8?cPw^LtDRHMuL zC<}*lZ|d5n^H{HbmJ-{e~6U}zhx?>OMB zvkM2gAjA1+*ES68+*$FaFweFzpUL3;XPyKUaNwhhs9IP;4l$68!VisL zC$l-0VP^sIV^2B~Z`77=wUiu>#<=BKkRQ{hl)nCTsJE{p{@RPMkM98*>wtLqCnG+3 zD&@*4|GUEX6n~yszv%%o^?147!;(;c26Jn+>)q_@EiZH7+%mAZ2J4v~;I;BHr%MS; zyn+#&EJtmU*BHM^TPN`|c|wHLTCVNh6`YW|mP~B3S29MwTs;oMWwX{Q#&Y(oAvLbwTiGGnyvZL6XTbabx7+! zwJMAxxHRih(n=W)#G@5OS#miytJD-N#Ii1`7Z%|;w!g7{lgRcwR4pxO?{6*10UPC# z{hX@tA44kEs~hUCgxfI{@F(=xjwCslIty0WrutW+goL*c{Y$FPF zy`LhrxC|)LyXhnz4i6{mF3(yeW(sS}EUP(HlnUDGlesD?v8|cwD!hJVZOkiVB0H*w z=dDb&N0Nn-CehgtRHvWp%nj<{CpC@TN6Xj*e5~ad?bQ945+id?Yw6XM8MpOwjie+r zJqz+F;ZbGOZTg($mMI&`Umw*~I9p=AmZF848k{?N1TX&Z4UkovM^yKD=+aEiAMSOr zEe2$9u%VzV3rp2$oI7>|E9vzoXOXm0okn6Un-6@ZH*AAPI;@Y<`!TtUKJFeKv^3*R z=f+N;EJV3j3?DrC1YY>@TSzRffzO(Z)*4FL!^6^vNMCo4=`jHS*4D6cZ3x%?;;*r- z?*LkV<#VvAHfK$41wAT_czu{V`W{PgB-2kCtpV$j#Z0eZL1|@8fAd-@S+*`Vc=0MO zoIa1P#zs7U?0CuYj_aaoX(_LJl78i4HJQL#JW-I3eSCO7=E{l@d^EJYvVzrYR=Z|d z7G8Vyd05Xrk01Sme}>_=&g16d1FU@iGM2B7!TJxMKy^BeFFgMuGBq`@EDMXv%gE;Z zq_T;4995CY$fVqq7I@O=U6TCb4qsQX18&dfN?Jxq*6m1FlmXr<_!qYE0LY*7$eJbN z3qbd3*jhanVrw~^c<*#xw?3NRoTY1po^5aFq>VyUwX}r&AAO9IRub7vHFAhyPhOY% zY}-!!`K|LoFXyw%IM%!e{k7W>cM?d)stT^$C@PNc<=w^oQUDN(GQX8-OjHBPZ4}k? zFxV=+`mwodumE&qc52fh3P9YQyN=1l+h|O;qOX1c%h@FiO`XT#wx_f{lHybyuf?{S zE>y?UfwLL_I;z{@dO0K=|9V{_gZ+)WQJ1Jj!bzgLrUQ;`=Uqq&9aT+8$C9EY{_iR$ zhJ$sjNZS@*=~-z@(YBTrB;vlp-c(l~3ZQ-zR99Pzx-xf7woFW7`<=TWF(k#7G=iAf zilx9Zi5++ZqfHS=H7K->O#mN3;J#ovox(&%dB<9pqTb<~=(>3u>BW`&j_WA+;`h&Q ziw>9zt+6O*SBT_VH?Ny(0g)x6U1HJo=}u7Hv@cEC{*U9jXr7par8bW{@XQDwP^paf zA2t3_PD3e#OyFGjU@{8c4rk`lLAU-yDF~(Lb0OaZ2UieZVo@#MgwleF!*4^Mg|^lw z%GSsIasmgn-><=e-B?S+4b{P?^x_iwuMY=2(t--YYj{RdZz)$e^@-p$9l9)M5A}hR z4RfzMAHThtPU6b0epnVT-qBt#o9${ciShhV_Lfq(bYLGWPod|=2+|8n!SguNy&bg9 z4qBmtzi9k*qlSVs&PJPn_0Q70TgZH`^9z%rP0XJ}T3P~TW`1_s`)Q_`8Q{i^t<~5b z{#!P|N7z|Q+4`Ch22*M^Dvkw|5lR;Af1Ml&B9rn%R5D6<{f<#jxB!k7)JqTfZ#3} z#wmcS{{D=nAJDS`UDmOoYztTR4s7{O<>sS1&OF~&NMqfw8E z5;{(`^W4h`?zM9+8Ydp$=-ChP(II~$4(jT(mhCP zzFholepgr{FMc1jMn_<#`I1&-7*QDy~;FR!8V<{i{c&tSQ_3Refp3sRGG;G>IZ zxi<+b>mipvCY%GeWw5-|XmpK;`i7u?{EgldUDq*x^sL&PAA*hhxqKDXvx}gUrh<)bc^jvWfAuj2N;{fSS=t7q|b77y0XB*hALRwD{=Bl9YGIBmSvcSN?ygMN|_jWxjKz&1G_@wFjHT@X#q$N zgYI>-W1*%7wX^f+8@dr(&mj)h&FSO>-ae!Pd1|5!mQ|iM7kpy-Euk&s<)0NiPuh>k zqF_@vQ>bA803ZNKL_t(A*_wxzu?ZYm`w*}#TsU;_p=2ztPFJBi?aR=HOa_VH_>%U0 zjR?+PTwcc2;bADH@M3q5=p)HV8VPe9nSo>G?AkgD8tZ;xd-QsBYH7)kc{(!3iuje80-w&h16(a~($u%+Act;l%qNz;i6T_0o%F z1seVI>8Ahyhd(@zmhnlz100V|3P7M`n~8sHc(5#BuAw%lqZH+0F}$5W>EXotAE0US z0c_>vkpgi@n{f_3#|B3FdN8!BvMe<#sT5AV@H}34<1HkYS79s4Aj}&lDUdsi$yf*X z---*`=IvAEwlY({mY>b_!q%j4E#`NuEyy*(b6eML^v^7t{1^f+f6W#CR~u}Jk~UWT z`3Oc!rnPd#*~xMSg>4wJ4vDE5<;ii=ah`0Gjzvw~$+A4GRHbq1rRO8Yb{%8^DrUpV zAusdY;K?+r=-D2k-)Pt>D)m6w7k@A7G`O?yOG zr(*_=yc|9{a;Rt#%Fz+at+%ihT0Tn|*TT3vEK&G6 zKTm1jQEeu_wV-f$-(K9?)?Qv$zIz4g|2+rq^<&7nImDdeHvi1r9FCni3ooW`gu1qO zcS-&4QIn?>T-Qhhw3-8AHqKtTjB6t|wXYKK1b*eU*Wox0KJ%~ttKj;j9Xs*<#S2hM zVR2~*-}u(I@ykE|C8Ux`ymjUS+!?06eN?q(Y(NvLVpr?%5`WZ*Z&JQ21zbmqLk{+#%1siq3=KKJyd`nF@a z9G-gbr${cX2I*9#^{FPF#&7Rx-dw&pT?+;?2z85Fkjv%WP96Kg730~!- zlZIC_jYQNnxuOemiC9=w;R*_y=!#!6A8Ixr>#pMF)M)@fcjIxyooJ^)l*wmw<^nS5 zcGMr#!VPc;S# z5rymZ*YyPxT|uEa-HhgRb1*dq8g}H{2`G5zukFYi4a0`RwBz7NeG6n}v2tifS9e9_ zKWUViokRW9bl!<;!W2tm4l;1NSQ2`6b8#L?db7ThlmbI-WTxlPdt(GP6z+ADDbR{g z%fuwA7MJpQj-rkuX2-eCrX>T=7xqRJ-ROHI%nrNC7&5bgicPV!icHq5o9O8tGFdQ_ zwqSd}j%(MUYzw!$yEe4jzj|R2-6OXkb9w0@y;AjwW|(1B%LJNXn66*rtSe?_Fa~jCSct4DqYBd*i5`oy*riBk1>s^Hy`9Hh+>CPuWl>K{SJY&v-*-AN4)u4m`LC z2P1vGu%K|Kr?a3DEw#J?FXjNALjUz)I3DE>W7mm%7aV-f&{NJh*-pC4bWBsG1P2~g zYEl^9(T6)-Wn}IVq%12?EIr#s?~P&9%q@V9pI4v**{on3Ig^2|$jEhKgEFY`ypkCY z%7qG228vc=D~EAC}S^~z$A9X8yDz+-hpYeqabLO+c-$wx^=0oO63`-Y?vh1j2 zK%}seN|iQN+7{4M?f-5_!-|*ZTxlP>ht$d{vWRP3)HlW!0&;S^^bDFroLx-M`wIA3 zyGHu@gYvh#y0Dtsn#|c7rPX8-w|cr^yDoaK--M;9<34xJ)ilDZ+XiQ90@$%vdz+^A zqr`6tjgOkcbj{BzZGrN{(A$xjOH8s|51k{ok#l0Wv7>)OnN`ZA#=1H**41IYwGGKO zJvjT)jqCXE$`xetf$(jO&FE@x$Nb_VZjFs$fByIcvp43PiY8MxqdUu^%`pz^db$7G z{H#+UkPZNuR9grGQ+daZp)Iq!;x?NafW*H1o#|pLTo>Qr-dQJ7R&X3Sj ze7%m}0@uoGgR|-tH*T2PslU75zo%hp+Rw=KDWul%2{cdMM|yD?bq{9X<^yl#woh~O zjLh|9>dYod%wy#_65XkvVdLXu%XQHY%gD4()G<1S-WxYjGrJ(L zvA$*0Jkv*)K)R$drEvIfc4Hy(b8#~5NalA`6WMpY@iMbHwJ+*3A8JW`jKXBm zt5u07dHJAc%2v%7^L|?k))K{KnP=O$*WMnCP-1lrZKLC;o0<&*M5q;H29_ItW!5>} zA}Af?(y!LHI_=RX zQ)e>A(*Nz(#qx_JgZ^IVH_tdfbEX0XZr_JxdDs(+Ls_hM-Ro%I@=ct{cmjRfi)Y+S zrIKi>ug82Yhi{LM;&ZKCfMx2fx^xGkR#jn&E)!n)TS=zns}#D|+Z^SKDeR9fJtomu zSLz%ax0>^8C+&uH|FD0We%rxa^uO*E@Mk#0b!kuX#N9d$;uHZkkk2iwb1&A9vjF_i zLEpz*J3EJG-hKzCUaTze^XQom(J(cwy=i*yq}@|%cU>ODt}BD0#bG*sulWx!P zpz^-*s1?O`=vND^Em|Mk8s6e8z0Hi>rO!)h{T3*jynp7fm-q4eo51b-`H7Tp$pV70 zkS79B>&-a~@En#NQ(dFcQ6bwfOfAB%kE0i8)L8F`)~R$v&i(`DuCtkXoO$|Kfzhs< zR#GYa_?4IO{2Qm>tmZ%&&-I>%X9D{|b=!xf{qW2%v%_u$nHC==|G9oZx=iM#W9w)= zw(uC3bamt=-oNk>n(G_z(i2bO8-M>j{PL@>BV8mxPod{UQ`AZ$TgUoFRgOfda_dJW z<+r6=zxZQ}zX^2i9Po|rqAK2teSi8}kGeIRO6!>&mE2Q4MyK^zNJCdzxpFk!FmIBU zTNT(`Ir(Dw$zX{_CnxcDr%vI^FTGr}+)RBve)QSTgsyMqhMcXU+xN!s#_9L9Yu^9# zU07c^h$nyZHT>G=zo>mjn{iAU=t%!_Ar%g~_wqQMbW1ZXfW6kF#}Q8^ZHKfz zPs~t>UU5Gv4VI(Ka8YbzeEu3%vx{h`?nF(p#b~%f z*7Y5#s=}K^fAo*dM6QXCb4#;OkVD;Eu^Rww|8SQU0P z9Rg21s#W%xKl3gIa#EPbq|@^y=#GAYQRBMRO3^2U8mFdEH!};)0>#Eaa%zTiMTQNl zM7k1AMnzW6IUBPQti(dy^ep*|~e3wvDfmyT!);cJcKg8|DppXr67%-ap6#Rd2Adx*R%0BuJ77W@_nqN zQyAK{6Sn6e?&bgwXc?PCe041_5vC?bdKN+Ho*N@@9S3X4 z1n##qR}?t8UaGCG#!mjghV`uzt=X zO!{S*9~Qa>K-9q)zN6XM&%*he{Et zb!Me1k)?H2S9Mp*=~0~N;c%8W9Nuzq2dAr-&sEx4Q;tQ1wLb!G^6zaJjv@0qzpghytSXimLCRz$d)n{u=F z-uIr_v!~x6xKXN`o5z-+5lK6zrP-uua`z!O&ho`cgseT{s73U@olD83o#JPb8H^_q`F=mW83dUUc3cLoA)nl}vmT z0Ai^Wx`#&mcWXmMqcSF@1=%W^4dP_EC*(IIzb*A`(nes@H=kzVMoir8>o3_rD>l|A zmzGdJJFC>o1R0%G?jgTLS=Y(;N9p($0|PGR8XEiv)TL4;8pTjwueTBF-YCqBljD%$ zt%x|*E-POwSyMS6>2>OIfytJZ+)1fj*R-1@fXl8T)em zl-qAfYW+0e-^E2>Yz*jpx`Puv9W*}==c6-Ny>TDaFTD)>?9T#a(1%kg;NHEbd!%g! z3m49pJN$H%4_As*@x{{hv$JTPobqev zm2WeismcHcoZkb$aBmN?Q7h07%hlCo3GlKRT2G~L_390{-@A^;Zvy-F?LtL-;}O1B zs;V%yr3>x%$Jsm7*^X%hcn)QmOY?|Z4_>14#TZBj*mCq_F`C<>J`+2xgSi`SX6w?v4zld zf|doktG86>F^D1czc&NLDXnrUQ_?Bn0%kVcLY`1HRJ-V`e>y}r( zWqW$_gZ4Ju8qjY%RZkmq4P(O*_XM68?(IR=ieTII+Yrm)JsVpvpb`vhc%g`GS-8G? z7c!A3I!DG}!P{Jt1>tTJF0Ss|g9jb?Pks$U*+>NEj~&LIi&s!Py9gRV;v@vq?{_ZK zki$fL3>s_{5?|->@ z=da(y`oH+k_?zDczVO9YH*_*3w;~lvRVqDRd-OAUD(Rz-fNy^rh$UeB#7iy!dqEY)<(wcfMJ~@v)j#wrmISD9MVTEmO8^^9aehfQ;VtO9%I3swLdowsY66 z;_96{Fi!TM?YF;-SB@Po`pjl@w#Px4Y!=@+{Wh{$IVi4s`YzIcb{?sg1gie!7x0yr zUiNN$`#6wHprXDSu@EP{0G>}YW}0YgYQlf<&94J5zYeq|0gFaRA{N&!_|{RWHXgCO z+Ito-q*21<9j&e8XIzPNq_N4`iMK^gwU5jB3q6a1<&rNzO-JQ9FkKhX^$bqF`+;Bo z!QBIx3^`_1GT_3@I&fU>KQok1zO~YTWk%tlByR;=Yh^QD?ySYSoyPZue(bNjJJNa_ z?bW(X+l4qpaaqfeUnHNIjS|bQ7by4j1sGUdpTtUP1{JZ|z@qJ_mB6mH*Fz}=sxn(& z*@Z;3CU9Q|u!BS(KvpTqRnVT?ijHKzq8Q6*^y;X%DvT9^!McH-^}ajEuNZQ3raTpX z8kDKJxq0;6zKh1mS$~-*9c|?Gf$I1R8irLS!{0Xir$jECnTWo3;DNoG`9*9Wyb05B zHne!V<>4d-ZVV#6x{fTO0Y@pXxo$_U+!{U?WpJd9FuKcQRRoETXWj4o&r!L2*@rMv zQ9j4f@I(JYrzgXn0 z^2OXnpuW7N{5Ss#9N{L_--aEFV5YgTXx*hcnI^99-UYymq@PITHt)b-btU5-aa`S7 z)9rWXv)aXKbrnYXx;GrfK&8pS&8O=`|yzpo@40}GK+Agw%)DZMOdsm$Q>L8+rIqA}sZwMEX-_R@c{1pR7S$O({oZ%OvDf z^TR1bGi$l4o|YKRE+d+rK^CpPoOE&v=_qmwX%*sKlN^?H1o27ofWu`YhXN=%rC&#o ztIdQLNv7}CU6^n&+}DHIhI&7JIvxuhxo)#`U|?s#`x)ED2bV6Q`%6EAmf1yAr&pvN z37W5ncyH;bkSyIesahVdi^>`FIC(QNIP9}31`eyo^Jlrv&K=8Y{w}D0g}x6Z4|3e| zdhqz!w6RSkxgA0;B=@20^5NWA#P|7Z={0P zR@Y!9S9GrE?15w`6)<(w*w+#rDqhS)UHUA zak1^jZDgz{w%)#t#Cl3wPX|VBQ9L=4)vd&G6fvGgXP1D~o}i6O^p33i$a+t3!+kau z#Y9&-ZVv3&@H?5WuS4zp0;(340~QAvr^|Ju>xQ;1y7bg`Z${2GHf%b2wPTvNy<;2N zMkf%@WPQo6S_8#fazKj*b)RBJi8m?Q@hFI_I%4CQSY$5iI%?fiNiSxGJik6W{QOan zZF`G`pHUH-orQb;5;8aLBYXTL@ahr3D9_kQrGVSF%aT>uD4ffu6jHHnK9^I_iW;%)+(O{JTUsb5$KN7cA!ILDex|?Bj>`>NOsdK`BPZ{L z&T9DIfQHFgG)~U=Wu+?OekAURj`p%d@hV2Gjg0^rQ86=%fss)htZf2dVK$S&vh79r zbe3oFV132c#}ZZ?J;@Hgr8=Eg_Rn(KDBs&WzYLC$U>#j0Eibzi+#8OHTLi*mW?6d) z)`H)Ml)_+FT&Ye1Lpw^Ivi8HVI>+IJ$;6TiF?YlaB%R&ye~DOma&R#Kh@>(&`q3x; z%%#$m{&HPZF0BAAAVT|4J9#SzQQX|Q0}FL^09>RJ2`pDXz7sIgu^3YEc%T_<2&*g3SzBLOrQi*up6KYGL)yhiT*t-*3Z`?t{hHTdF=mV_H{&kQjs{XymJ-*0V)exs+lKhzR3i z1CR^a=ql_CUhOR@Hx-p|p2j0&%YoPkp@|XCy^{jFt4OpEsa8>XDmX90Jf8;?i`pREh=r8I_erMu5Nk zOYfNFU;R~}rS7p7Z`)qcrP8C~edVB_%+vAGApg@_wsrhdw#@3vmnD>Ut@qv#QWbH` zHWv5WuKf9Vto`5`jD78hw$>u~7y?6;o9^5n!Qjx4|JzwhWBOlz8*VD+v-tX6?E2Z~ z(f?oW0A4u>RK{TKXhB^v=TA;<+^-z5EY#K40rjQLC;mo*))ub4>G`FKuXKTun`(5XexCGyU3&xfb0@sLYo86a=E1GqrN@>;G|CbnL`gDrPQm=@*v zxGx?$n70pW=jSnS<0f1ea9kn%W#5My%tqFDgdPV(%qWs(3|ZI3v9_Z)J@y{k0qO$bQR>QEvN#UJcufk$ije3)(z3%Tl*CzmT_9Lh)DC ziJ%%upjQVVIG`qYAUm*y5~o5U{c;<6U0xc3Za$EW1nfqsv%7)G1WLsl3|k|f~z9Vl>r;x4iN|9KqZQ9MQ(2w)r%`Q zbnXJu(HPDjJB<0dTDV0PR~e3ry7_tRyL1_mbXGc!I2hrITBAa1*@RA{Gp)1Iwdo5f z!F+rdx~_v|!eA=TaL&TL86?{3r4(_PMBj_tB7S+jcZUD~!+kwitEfOUlR@>;a^5y{ z-y25j#AL16;K|XW2JM-Q7hP-?f#hejaAdF(}Hn{JK!P z%|Lyr{pnZ?tJRf(>(}@0&PCXMvNSR=j=_&Fqr0mU2TvVAP1WX{L5sCDh^8_yvVxn7 zBOg7YcPTs0_&qMmIOdSueyYKRptu}^65!*{llk5?ErbPVHyTn8ynHExCqO3@G!N8xRpT4%_8Gwk&GoJ9ZZ#$>UZ6Y4(ALh z1>dTswL2RSrp7?M z1Zdaow{M2kkA~u^d~=VDF_Xo(wfjWTH`tzZ-CoipQ~7 zTV4ZXd_9G_xp`DY5_qGn2M#QJzO@%wL}A0i+1W7+E>6M)u$oOH<=B7`$?1a@S}I!* zF=K270o?LLvnrnts2COY5tWBzu2E_^rD0_CT48=F>-A)V2&R?u(rGFxrk2N-mqM3D z&Dmfz5>LC@I|h4Rj03V-aYQAsve*(TW{}VlO~*#<^a5LGp?@nv6Xm`&p3X-YhKuWa zcEOHVm}zPZMA3e{M6n0CpUi}VvF=VRG}K|Gx+?r>4+UtosuIJ!-Ed)`Yv?{4hQw~~ z*j85lvQ$%pbRzEaIF3=c*3VIn_^q2$rTBQlr7e^yKYHg@QK~)hIkEsC$0rTnr)+|J z>a^+AK^75)Y)yZT8>|#TL7QXHk}qRt>UsJuOCi~MT$t+yzsa^Y*&-H>R>x=Y@xS>` zFn;A2jvqRR%0vP;?%hRYMFqOs+6z8gims?q{Zlp9aO&57 z4pmK_-E3}g5!3T?a9tNWdU`cwhv{W?cJSH-^HVMNVJH@jqO-Fd=q%jNYFYVaDIbr3 zJbU!^+5DtRs8UJoht1*Urw9N4)X>NX@CSbY%*+5^|2nYsvvW%B^ zD$m13P%f!BN!Dc`T_*|3bw&d~?ZP7BsdV19NHn$pJX{9$g-iZ4(1({UB9+Pbzh~dN zg6TIe`M<4b1gC!W>##&L@Lerv-nPX%`Czx2+mj*njndoX5?@Ay!8}YQoj@@z8#gq5 zynEbsE1rUqPT+WwPX+`A7r)4}qr(%rItVo4V)>Zj-6z(593aBH|4$VL}9SMGN&U(+zqUe$)7yc)a9@&rdT|uC4+uu=mr;sF`14 zuvXpq0QQR?5S^RA7LZEB*rHP+G1eoQETZWwV@JfygnO8rrGjnc+?rV%doEqU$1gmG zOaU+f0Fi7KdoEppm9Zs*24@n)NXa$LMXx%iRMtkzI8oKX1H? zwph6l@8x0ocSOI^frtd0z1YQ;pI`Ug5g3jaJ+g6n2751G(Y8Y!FWliw{cf@A@~&vz zZfULpsccp5ea_b9_+_F*2L>X!-|0jggS!Usu&p)kyU9n>O-;D6e=iQ6zlhjc8ZOA` zEFYcB`IyT-Y2PpxN8-2WO)(y5NxRpBcGSW|M?0?V-JC{qb>AMuQfV|lm}JWcc^`Vc zYJnDU5Epl)x*D3#jT#lgP&O7pCLV>AvOy+L1G*!)WkZW>mQrV%yr4U10@hzIKZOO_ zr5N=}rG*9H_H7r34?hF#&qyX!GmH zC0u*^9oQCd_{0$)Z37EyK(n`SGg(;)Gh{ULi-!;5_y-@Oc6I^2o69f(Q*4-&$C}V% zT*g7=#fAiAW%NPk>cE$SbdQe}F4w*H=s{!yhJW-e#ar^yRL-yB*ax35IS!mVb{MPG zRY=9-kLCEXrn-8(dh9q1*TpxF9LLEIK7^5S@#gG9^i?%tA(O(oYv6E0C6==5k`tsd zngk5em4#7(<0QkMUxm4Y=&e%7mC6*?Bj zBV!=n@JtAT=fw2}k+%um+mhR@I-g}6AslZWcIdu4g8sXAG11wMn>%-4t%TzpE!##_ zZc(<5I!4FQb8iR$uwGS>ce70@5tkMqMKc);3=aD5)qsl|J9mcKSSX?o_Y4iA_x3$R z*E4<|LSyDJk~!jWA||F=n{esifuiLs)g*ED_)-7&;WOt@H!}~@COISeT3~MgSgxtU z<%9dM8Zv5-prO8AIHrlMx9=dbmVx8HQGuGQfUG3G==dpVw8@4?88h%X71XD7`g)M^ z<6pWj=glon;(c*U!||(UUNv(@Ps`6mNC?v(?E*2$`i*W*yZ-ZDkJ*Uiwz|t(b=A$w zs)pi9dD1l*DO1b2!+`5S>WN4u9L&|#|>6tPZwhbK`a9 zRt~P0sk)pvn@#9ZgF6SxdYZ+R1AB37dH!FZEs0lRS_OK+}DF>I)mO@LwV}xeV47sa;-R*e;ins%6x`1Kg;CKE&|{EI~eCa zhV|92!g@*;Y;TVAGA5twDWpH?Fs7<4>+>s|r|QU4r7O3E$(l0pQNHnOaMu9l8|n+x zipc%{F2cP$ftB?&tgNjS-R0EMEG`Ysh4? z_`!!Cpr)z{uO5F+yJ#B_*8AWXGn8vWlW=k;dyv*8zUe#{VhJTJ;06rXAZtAQXJk3& zMV+WOWX2Ke&#MCa?K!IY;pNlihPv4 zrm{s`txwRaqSjIVo&Vm(>KY_f^T@A>P&@P4897H3GeM7+RlLFxjVt|67@E*L{HxU0 zl*WYXhxXytCc~en)FKyTQF3!u7+H^0`%18+cGMad1BCSQCK(AQ(|o$TW{aNoo$5|Tbl6*>b7^ls7b=g*~1@9Pouu3 zCe)(sFcg*xd+*JJIHk#QY;=r`o);`uzI&j|hLp8{iJz~?^?oI3TSYx77* zKT3l$xb#`A*J^e77RTLko+`$oPZ@uUvSqugS~uci_q)5Wlq_v?T628^cJ%a=^vvU= zm9;foyL$%!FgSD%>F-{Jv8NU2szZByHI9A$1wXBoh+^O$y#_P(=zX9YCDP%|Jp7)2 zf{g<1rIT?1rIj@i*+WO??2zw*k1^7ngB}7ocnx80y=`4?k&v+BSrPnFXj-nH%FiR~ zqJ4BilGv`4lYuNEOjom*7ezj0G^oR=vrpCK;JTNc~`$5Wb)gA*To1T*WvupMRLtsFa7 zT#e)wQJZkRXkw-d*92yon{eSs;b@h8ckf}_&D(HY1D0(=jZ`GS7&knKo#N}23B32} zi=p}<6N}=#S6{@-KY0g<)iuBsq3y|VLPyDZ&R9D)PQ-QFAHl>TWVl=$IOo4#7?|@> z&3S{t?h+%X`glegIhK_i(@HE!67GH>QatEw<(_td+#)2PeP{xmLt`+YKh8)t9PwTM z{7;ylDCRYZfS}q#08d`F&U=kS0vCxvrvzvJj%DK0gZnYlRQx!Sd^BHQhqK3z;)QqK z^A|Vsz1%#a7+7zMV=QEDq=$lh>AJsV!Za|tr3-_*2R2-HPOfDDrUAq8W}TU-3{9?vFFlNHk&;zZNX+dBtMZ7ql-Sdd3qFiZiK=b z_Ec(W!m|b2pJ96RW~_YWivRNiXc^EJb7xT=s{4iVl8xT#X)5Y{k&9n9!+;$Lr)SMC zEZ}dx{{z5v;r#BKz*oNlG!}Pq+d0`Pq@imXa7`gCf^`1a;j%=Uc@*TjE;89{;Cdty z!Lk40mk{}%{~QiItOQP66yc=9?XCD1_0n2uYVrN$|^)65x9;6JE!ZKriq9~ z*OkriF6>Ax?8Fur=4wE8%GgQhPUNOAnKq}i$k&Rvt{|Ic`IzGxipl=ZKQ;+md%D5l zPtL=Hi!1y0VxmKDq%ZekZo_qvSYO9WZ=Z(an#dr6H`=$cD6b~2FHYmT8 zfNyPm9W`+|3NdNL`3%@XKP^QL7Q(ZtCZb1oK}{v!y~4B+nJJ#zEbpa}OgLI~o>3Vx z4xltNX6YN(28cHj#vmgQab{Ih5?Ze5mn;^ddijcNwq7mT$HrmVHZJeq7wSlR({a!+ zGmE2V&a&2VhY6Jr0P&S|oP6&CWMZ*Ezu(=~k9&Q6{_pif0`I-JIYanxZx0;H#K5&d zL^2tOt)aZPxWgQlfvL9UPz$zobpH4eoOu5uBL@Lgo?9^UkQbzK9nOhg)!dWcMB%*}VrhhVJ3)AHRu}x6kAIbsjH| zN2B=C3ooKN#D=>t@12v_hz4-a7XV2niKtqnM+jFdxo-Jb!xM-M~#r}(*;{4IWem?0~te`(DA4RfR^b8GS+s)hlsW_x-$r_WWVMk>% zzS-Z#^fXV`e{=XPY^~dduH+WDFkzX60|<#85M}5%M;O_~WvMz-UFEy11%~Oba>?jN zft!o>4&he44U%JMj&bGD?JD`fzgE~=$8kDGBEq{YG;MDl2#*o`JM>P;Ge$wiCuDha z=zK{E%SNAMnIgNC9^-SA<$%HrxY8VuwH?QQmRpMDG_stMrDLgYAf8I0XK1*no|9;- z!J+@=AB4_Vt$Xl3w~eY#2GhEM-}&W9Sn6(TFS6iVmVsQBQ5|&rHi-JwcUZN&iq;1Y zHx!7i5SfmHuKS~iWb8nhL7B_jsahxWJVCW|gw??H@2C7c;~70h`q7Vo3m1SdeaZW) z54U;trwn}=yUEIkPUf`D|*b4({83Y3|V+>vksw%oa3ko;2cj!I zO#@C=rDP?LK!LYt)$xJ17fsK?-iudY8s70rc= z`ps&QyzB7&?xy*v|^jp4o?+}g1{ zlre3nuNNad-DsMc#^JN)VM8nww-7-V+1%1<9>Lp!gO%zkd~oXdlKKJw-h1g3o`3%X zR4sbZGDIv1zA#mWbu{*Z>_#2qDztzyy1?!Qck%;zRo;a>hg6csF99EJw32~^40LD_ zw@@Wqe?hgAi-M&dC`C+KKfgsex;WRizpF+)nyT;j+Kr^PFD^AhM9G#n~5*A{33x!}+bh4VRXY2^SHzwC(2h9k|z@pO=?= zGhjJsa&{Kqd-t8d_0K(b0^RK$IPlv)hkef1fryF8=ce)9E;@qruYd9u3;?ekKY{V7 zN!+-17XZ-R-ht0OcOsA{mnndY_~3^yKK?P5|M745?^T=zK}6ASxt@?k5XT5P?QvJJ zSWkYAYft<+0I(qzP|#usbv$yNKxk>g!Ljqob?m%)-Iq(E&Y4&gZ-4HUFs~ytRjsVx zg?HbF>*`{yde^olTk%hKv|}c{ivM)?T>!ve-2DlDw(k`*CK?s}je3I<*NjzdOim~3 zdijWJ;ecKi2lE#HtN7W-`%H1lhf~9oY$TB#!}@CiRmfV1j6;k(?UiE=8~#-pU+bJB zvX1YWV#qZ|H8uTv^ghL+2qT99S{_W|Q1$}OoH$;zf0`zzaOmuXf}2CBrru{J8pTgu ze|1BPIW|J~w`@Ts62-xD7Xg26^O)nbWp%8x3zzqA?mR<|E0F7LGq)%_orvL`&%M0q zHjQ<4A`^+?z*%v0p*-Jsv;`MV?i~|v-YW&Fo5j8GVsc=;yiRCq_&V`h4>w`Ng2*ea&8H){O~9K zy?0)H8LL&LohAbSTW{S#-<^9okCo7#xu1fr@on4Ghq6Bf06v|%1Q#X_wI0*VNOczT zymVAf`!2mLJywQtFB~Q=5BJ@egbw27U><}KL`fQl6B-}9AH*#3T1%mk47f-o;+W`a$E_XP!*%jwCT>YG z;9{|+2J7r(tb8;%JB!uzH2^?$WhI*G!YytS*j1DrhR$ERhQ+gYuXl9lnZVNU zT667Cwuh*BmzPxg2bcW8x~lb2?KZ-8?ft8rUqH{$aM>4aTegjz*KPndVEd<+$Wh!y zov4j+AL?vivel!Q+%0TL;iS%_XY?5$+W{`#0{-ILUUcnOUwvW=w%68x+1bxJ&gNQM zxVFfeef~5-J&a={KD!0U5{Yw#r8q`)(kg?tl@3fQ?`wt*~^w{I7YT2o2Y8ugWMtXzt2_9UAsW$qcMi(4q z#Ib3Mri{zU`s(GtwG)A^#pZ1BtOKqgh#)-P^ZYDouB(BStG3Q$Pk36iyhh9`Gq_n> z)zNtW@zYW0Q=T2kH`r{ zf#KW)D&Urt+F}YoA<~0t4v06Z5^#1$&{qc0e1LLDq1*RN=|z5kIIvs{Zd#H`K$rJ1 z)yH7<0_a`v*aluLEXM}mqW|_?ShigfC~lsd!k#NvwSD8lKqQ@oVS6oVdN_@j-g>7X zb06yK#ZX_b|9d@=z`HNM=(jh_@lPU}_k|;eVA>A0-@Jvk(Fp)vf7(FKInS4Qc;>G= z+qYu4zbAA=a1lLxy15DGjvv91Gw1xa(c7mfYr?^NLme(2KDeQyy==?EC&!QBz=ccR zG1C$|5X+FWa1qJ5Kxuh@81s@~a_X#5jXj0(;Q%n-%;&Yy8I*_(8_HawnJc2xQOpYh z9Tc(J116TwE;)qNb0!z+&KY^hH(#*rC~rV@V#^~y?q@zrgDKQBT$Fm>KR$H=OEt-| zEbdsXs>FLQp2ErZK7i>W*K@YtMqOX2Cd42&7T45+y}W08hK67m4sMsp2@#@oYz0UPHfoe+S{8U616RtYLaKq~st_!4X zz%XF`FFylx))apRz=x+!!f>hX>1gb!II6S|{qVyNFtb2TZ1?Ruz^!RC{?-@p^Pm4> zAbmwn*EFLM|2?!eH{n}fdjnb9#$UblBc%WJ_kgJtoc?E%u=lkhYunhir5h&>6put} z&P>CY7=v3;iEQt-f@vvUkw-LcT#dXFz*THd<2#i(KqgJqyKnn^UmypPiyQ=Vw}Eic z<#KgoJw;G#J&l*%dIuk!I$7|D%CJ;FH-|&#E&#UcJE=w8xz=PDCM?53Lp+IJ-u}6q zq1r?uQiapwXVG5Wj+M+RQjUWI&GgQA@2XTzd6!RPDtxVY`NcU^_%@V+mANrRtqVO% z+5qlA5x<3+r;3|(W+9PI#?6$s4tKZ^v4uq(C2wh~z{kW@)%Zzf&WI$Q@Mcu?>=Iu7 z;oAYdoR{YUFdWxkK%v&lg>X#Um}+mqwY|IP*~heCThL@{3(g-sghOX9zyuJ5foyK^ zua(c8sfcFLkk1|nw=(2SBXvKX0s5t9QRMII1K*G%8Z>@BnKWQ6Tsqs4V(pUKw( z*$7D(SH{d@doH1I83EFA0NEa(FHv?NaQWx8T}1lZxIM2J8G*9p`W1e&WR9jQhJQ`& z`*3sMFMsp{%>MSbfq&P84<9~2vZ@Mux0QE63uz8iZyS~ubswe6!WRx6#&dt{@wrHK zxTD9vkGukv=ya@c}ZvxLh5B%D%0sT);G*3b09?6CB z3+hoi9?h{wP;)J0>(`~1wO!fX$u)Z}2l$`ojE}EE{!jI2< zjiz zid5tw5dVuPz}|OH-dTP*0uKboq}b5RM=fbv>iBe6+blniWAC4VVaOO_yt4z>ckjyE zce}4#L+AZ5wn*DMD>jRW{YBy&SS^k0lfT`*GjHyDe}(we=p+G znN?JFHemmbjh%A489gMdZ>bpNw*l!&6e(ThIXNE>MF`#{u%*kaM#ARlfb6WIbiVPM z=21QkNYXD$;-ly*Ay=tyN#;6In*d1tD%vC4o}95<001BWNkl zwUJy}!cww4CzM*Yjhcl;*sfPsenPlfJ|AB?IbM8B6LCFFPHSk=J1og-lG1cW ziFl6mAyr#3AaH{~EskFUSyvJNbEIT|FZ!mmqL#uZB1>FZn@|ys?2*vV9aTq@qiWN2 zv1yuSi%zzxwh-0c&3lZlQ;!>Htn9*icFm8xt=3lcmMdcOF1c2QF z*GOUGpi~{8GH{TGx@_j)DmV2USM=zLTvu4r%jTuaF%%u3=!UvZ82Rbd<{N za=x`=J8a8B=kOS^FyKN&8yD_HidT@0MUdIRvCOt*VWzPW=Z+o0kx$O~EJWUO;bOX_ z2{(7|2(|b;AFU@6xUz3A2Cm&e!{jV1(4Js`#-<8oh~>%-S|F%Y6ARVf4@2A##bH*k zBptNn*JUP0Op&uP2V&R1fSeo_0o=?R+!^NhU_k{{{Ag!czy%j<8%jEQPL5ipa=xG- z<6@HfO^#Q#`|?#>I(%?LkvddzOcU!B37>1oW?fzfuxp~Wazq;yI`j1W9Y-@6#L}5f z*Ih0D9Ws4kC2`s~@Z9oxFQF*Z4gGk^Rh)-T+L`!8L*9CCM_uHMBc|J>BitYG^5 z2KZ<6jLJphTnUpCTC~x z?k8t}WE|%2ehy#yhhIZYZMa3-YZV*Q$sPxdO-|zM)hp69_xFB+*^!5^fAIhge*Go% zbaVha4ghNzM7J~`SrzUWQ_HlFtg3?Ry7=nLufYA2{ctljjE)+h+FOiV5l^5ZUR=L3 zrl$Zag6!erKnR_azj1OmaH#5~qO){ptk6>zH=-^JMSI2sZSINpA;z&j}XyAW~Rl7EWt@|($rk#%@l{jM)py{eb_ zh54H9sUXhP=c7K$^}A+t!cazMir;yfU#UuI}A~9oGlZGBF8ZWLr*F^cn_a?^W17fBBj6aA$9NV* zGcBABoX-grq{4Y}?rmtE;08$f8Tt;krGTSdF>ZyWNGv7d<$6z;%JLqOB0mnHlzLOX zY@}3=dghC`38{(MuCswrTd7|PMddC9L*0My07K(rc=7NNWU?82_w;Fe;rSO(S%Q5= zk2i${=+V(@$4|id)163mHR0~ftGG0H1GeMfK!JrA{4I;O!+X)pQ)kXs3y+S%6pKa? zt1rdACiGcLsx!qR56a2S_W5TAp=_KUJ_IgbcCl~YGu#i?r3KqBz6gBlTfo+>p>*=6 zm4a`z^iiE}hHq@s|QseO`N7lc;X2MZ63fWy?iE@6I2WS`fWiRZe+%m@Fm7 zs6qpBnQrg0(c((^7&)&PVQU`Ai>`?p39a7sw?=)d|d>DQ8 zd(m6JM|rPdWl0eKmPUo1D?M+WSE^Y0aN2)x;b9@{tjE#1>#}Fqv%kWN74k)HD#m?h)D6tt@%rb#Hz~+p|nLJ{ISk!uY7A95GeEeG3(AX&6{e!XWmGU%G6~`2!g9AIU_8(4T@c(`b?mu>c4J_IYOBIPYGA(s5 zYLkdY!s<7{meBde`t+QyhwY7x@B?)mbN&wm=N#c<0BjVCdEt$8!qoH}zvhi(`P?e` z=P@goKda7vqbrcj9>}9xq!kf#4!x z($&ar#&IUs4CVfn@5|SC^y))rFW}7c&ta}%<57PN*F`*)TkqmPvM~qO0PuIkEi2+A z557E&f<$^k8NF_FB8#EmUwet%&`q9~32nIO_jOqJs#;F{L=ou9v*S3)!8pZU#`F*rMw*$s6{Q}U?@T9Bt)R8(8gZACc z;%ku;=}oE>ma&b@^~G~8<4U^pyc`1#&L24(dM%Rs$7kW5xsRPca|#D{=HH+imQtBC zvRQUQq3vLOdJ%tp{(ZP}tAOJo-jIY7G2s5)ASxfO!uYR`BUx32H(q|#d*;>8ZMq)i zBExkNOQq>Iyc1YA5*W>JT~seG`r?J2N71qjpL~kY{zr0dFu>5+9J?r|Pn-k;&V2i5+q`0Wc zB7Zgr7J_ByVY~_?zhkaQ&*L^k?!E%u!slw1obro(8Y)8L&7mW|5 z*?Z;25Mg=?nu=u8OYpi3hWQK$XR^wlO3jBGSqV_{UtV3zocT!I_b}#A{kZ*4KEC(1|MSP-~Skhm@sxUqp7J8k*7Rb zwvH~`xQ^+Z6WcvMij}|p6jO7vKtm;>|MUgCeB>C+->3mnSzt#KntD4>U0Dfi!k%Op z2Ab;|fFq@4!r#7m=N8=66=c5r4Mk%Mnn}bJacq=4ZaGQ-L_}aJkw>u2XPWgK*WM{K zG}dGn2#rY*TZs%jvO~_5#-#zVth;()IXB)-^bg)a=g24<=ia8xYkPL*?Z1|XljyoX zifB3m5nJBP;TYRr221Cv&ZG1j@3!CEIjs<&E2XV$Y;3j8J?!twbH1x=Vg2s_G!7DWUdh-n)d;_ZR3cv1MdfRi70AS*{u^{*z_Cm$CpV9cIdM)Z%jw`O zCcee5dOacDw>qC)P1+#B%RgJVT}ieT>1G=r>#~iB41WUIcu1H|NurpOs@c#Rn{xcF zU@R`Gfrx?UfX^e{F^l<)!8D(!6d5OyM9kN3<)Fs8S|oA{+8oEl?7}=8M~@CA*$oGF zZXq$Z+m%YPRF-WA#i+if2H5RwvfHne|jM465> zW^~B7m<>6oUp>xtJS~*T0IRy7EI)0uvI6|&Ujl#lhu(tiU-$)J`}WWDg6(n>#}afc zOnM#3dFXA>q(=oUuP$V%A#(!ZZ!qBE@_~INM=9LDeFyrwwv_bD;~>Xz@Yb1+k+rjU z`0sy&UEer`_LrFrw0k?EhmWGMF6URNdwl+tQmAfz9y_nz0C!HRI(u=uFxO1E-p0p* z(80kfI6i2HIM$!J>D z_YD7k8E+t$r-++PvxUyF6{XV2J&r%}9f%nt7Htb`%ui{RqvG+}@H(1Oi{wB>PbL}@td9u_Q$V@ z(L=Vxd}M^0DW#E&qsfjWTc2d>sgM_@G^+V*p}fTTg7TJWK1cc7Q(G3a@p<^h0`WCf zv*9?K-{(?`TAII4iDL*dVL_y{`20110b=o zhL_)d2XDRp+NJ^~G|bH6*vDr;r~b*CyHs0@ItGKMhRgPVLR2nWP1rokUEZUp|KCSS zk4<6juii%Ikv`xz{u%HDgOEIV;u5CZIm=eV{P#sYkf$zOtIjv0gB(kI3a;nCLIl}T zn^9K!_|s1@ICPIL+?|E6@^a@V>`S0LCZxtfHwhhNOv3}@rP}TAZ zo`2^9UtXJV@adub81D?XmWWewX$hxJzlSuUzR%PPQ|q72E$J5G?Ly-DfY616ZqG^N zL0DI8`Xmc;&=VsxBRlsjFH2|V5hvXe#^JRV_48H&!he=FNx?7IfH+Od^=mF`S*kST zZ8d!#2$z$z+EeIqvg{1nuDLaU{3XFf-BfSd7A{EDyLoCpyY&>I1TuJ*!F5nsEkx@5 zjj_Sv3^b_B%AmJUUh=bIc#?~chJ>60r7>7q*$BnqIUhpu5^^KwoD*T-X}7a(NQ!~t zDU%j#xc)T*4kGJWG(DK{>!>qyd4tjfEu0`o<4t*wB}{a-W3HhdE6FO%KEYjAD^*ok ztf@g4M#1+r7;tfC$5y1{G0ZeIVs(>8H8`e;hi$E}_GYpD#w|qFJz-|RTev>9rF=() zEY{XwwWQuRhCaZfFe14j<1O^Bn{AU!X}wm7azY(Nmk zBRTqp!JadGcFt#=+*((8T4u^*^t2hc<_1%l=@KKB=WRY-B$rO#c^kMu32zuWbNN&3 z-ntFdm6fn|o;U0=iC@DL2cz|lQ> zHKiMY@4+&4BV1>oHKcb}3e{F8QF|b~!-yM$f)Yo}l%RkPj$V>R`RYt_{23U1Mt^@O z>}b~U){T{?@)22@^BDAm$_sRpH{>d*G3_}acOSpXV zX5jkBpS*+R>tg_bj%{18^XE=sCjeB%U>)p7UuP$buCB*h**tW2Yd`w!yNKUQ!^}3q z=rCY6HbWgvvcX^dCUhdM(aESl)%@vjX5#)_qZgar$Uz~*f~Vz(5ueW_U2A&2#dxl&U@k>0WKT7P}gD zVI`YFb7dRSb{ef!T`*wa!SX12>vrMJ+*Qo4&-yK^O*Bi9#$>%C|IDPfBV#GbL;p-6 zD!&0+ucOL(eGo6J7*R&Gy64qVsOsx7w+oiW$FYovc}|3Qs2qVTL?kgg_oS7>&}8=U zkghPDiFZqJ#mFTSw0p=4TP?P%)r5o5o-Pda_F|qPc=aS)4AC;SWMeU#BwmX$d z;dzyb3REUM{U;KM;Kjp7wNXifxGcz#WPBDJ-6XSlFYD@GIyKbR`p0}0BG>;@-@H2e z$O_44Oz_>g=ouPDHX6Z9V|jT**XSr(9!@gbioEeEs41&;m9^|JIKGhmYa{RFaZovI zc0ZLgHwV1=Ch-051J6AN{NgWq3$~x4sKhF%^5JQrpsh7nN3PH5W|K}11uc34uaLBn zC5gBE1#mIj&=Bg>%nvVJ#PaGYj5l_p;koUo33=+$qonbvN!%J91^^`DaU9>f551k8 za2yAHzxV~T@861=HfFzV1F-$c)U^~^k0&tQ+=%4dq9pre>j&}bpaWCISseN5^#_$Z za%()L6=MkSLiwn67Zn>*5ECrimEnCPQ$ z>w?dyRw%B&M9di4tG7V*VHk**aV(|hF|{&=;km0=NiQH~RbW@^i&9++Q7Q6DmsZC; z!ancjxgIvZ{OR?4xe#tHmY#cmWUCF=E5WYI7(rJzVHFZSv%)A`9*N=^3IpJsdLowk zQ_OnrkAfy~jg4>k2W~7(;O_DizS6lbFw<47dZYA%58ub+|N16ycGSCYd<)Ef@|^cQ zZNvE&-vL&=Q(uk$>L?EU$`@go`65Y|mtHz@6tUlN5sgK0c`e3}F2%pO-2TXASitFuRNR9ExeOUF;K@=je-krP-Mw7eV8&q0~E#E~@} z71QYOjw~rCPu?RWy}WxO;pBTCB9hJ^i)hY%OHnG- zb_8V;$I;xT>q_cF*fxxp`+%hRkl^YniK8VroF5KEt z9PD?Djbq^Y4Y;l$E!d__QiK=fQ?FFpDUAe@8$#~NxLk}Hug+XzbDW}L+K4pnNy@0$ zhV(3MNf+KYp?x`^%}r`B8nC==sFF&RaQZQ?)5r9B8jolW&_-(68UXfPwRp*Pd09Uc zt-tc{T|})4>}ov9`qWUK(PM;&YETiM`V4}V%a^g5XJN|syk6Ze6;P{rk?BQ#)(w;w zEQdc!Y2fE38*E(ZKF?oXe#$4B`1JO>dW@N(1Mzp@_`^#qmZg0IIue7B?=BE5z=DGa zY&_^_!*G8O7D70a9tQ~+A{P3JDfOVEt?Z8T@vctv-MNR@dfI0&OEt-|JGOL&4Z$wN zLK%WM`6&Fz=jDc(k2JsJ|HWMyK8q)yjA5!Hp9=uk*y9IUnf}u<99P+*3M=G#^AW?p z%gk5>xvD|bQ1aujrFaj@qE2>()D-HH$%2cv)%xq|RE%`b>I7gh zYHMopzt`8)V0Zu4g2#QTvW1U4eg)ER!5Qec?(fkN)rl(#`f|h6LmqeP9c~mVRHH}R z=4bSbo*vTk)1bD#A*O_fq5WZGbiTgd>AzDimjYM#8*KS0g z(kR=LvopB=-~pC~CUNtRe+&L*}0idBB0MK%L2ey3q$P=z{eu}44 zuAC-QHI#61Tr+W<>*9( zo56UjroXs?Oznh%%#4H1;ZZiegN}qOB5+{%yTx5_BQ)31f=5Hkt*5-};&rHrdj|E0 z6-Qs)b^r#pH||44v3Dquret?(HpmWa-V4j3d3-Gt<}*>U5}^Lqk|tSw>fDE83fy zODHcqj#*k+#?6l}BYtHH)<3s!a9}5lB1iVB`Rh*F2_k|=Prz|(>PNL$6nG3XR21aoq9wf>NY9hL55vq|_#?JZ6C~RdQPEj7dXqhIq_w?ks z%Vmaa)6{Eh!SA~JLJ}IF?d1G~h;mWi-Frx^uIG72T*ea7_*AVW6cx;Xi~8v~^cnX6 z7iHVr(K$MX?z~t6GB~J$^34b#%B{&9(5ekDE%j;r&$8)D-a6 zTfphlz#DG>$BzTu-JgL7+u>#9(?~&iU${N86^wIV+3KpsXAJ8^c3l^D?%zi$lZJ7i z14dhEk-0ZRS=+|N!5eU0s%vjY2hy1=9!yW=PVEC?(HIQFz_u+pT;J3C*y>nrvTPfP zwUi`-bf;9xm@WT^;j))(w;T)86S9`T|0jJ(LwB}!jzLuEVaE89_%Xo3r1YGoALn)2IR zRC|2sIvGpLGspDD zt(((SMVKVA@0dA^?f9N%VT&@@tm5`5Q9{~vv1Vs5mtMn(?+-cNvgvoL<+l*j*Ds*%ZNVQq5ZS=ccjkHv80*dZ8(fp|1rncQw90}X@!Z5J>}o@Hbwm@jd;tVFFXsM9guUPZ4Q7)I)h!;t|OAomK?Rza9l)E zS@2+m@`hrn7s*^Tnzg!(i>!!b9d~o@!6OGIqU#wPICl|_Y57k*>}bQ?{{Dh>?z}&W zt+(#NO53>w+oT`ZN;~98p*npGQX6$zl}h38a=vt*T|66&0-Feo{+Xim^$|GlUPdAr zMdGVRfD%tPdPb#FP%^rb%;VSf-$g#E<&V#5o<>Clj{j#zOni9!B-Sg!ox-sCdp}0@ z+JjJOKe>7tW0RA>>AP6_t531CyeuaenFG=`jGx~R^Jo`(cWuSN!~5ZW8NLYRCbFD)vTWf$hG970X4`Z{ee(j7?5rVR;FSwRLDMae;Rb)`@A){{&IJ!WtLUwBcYPpEo)n zOS#D78Q=`v_3v?qG)2}HqKE#8{-;Gl!M!ZO_fMdNemhWi$N(IS75^g!AJ&8z1_XtD zZ-94vau`zcq~1__N;Q}kGLP{5A@xhCRF|y5;a$7)-k)u3K=r~Bs^^!rBcB@wg7p%I zxf#lHUVUp87SK2|Q}&G)H4BSqoSE@QC>cj}R;wy;zq^Fvos)6IUf)@er#?=)H9U-rEg!WtF*S+1qob&t z%V2kNClHUo=-&#M1`Z7DMD^jPcagSAoma1+=FRUSmF!05#EY<7JpGvTaaB`Oc|U10 z@UN*lCdU@sp`dQ|%+H#aJQ6jI4Gi4|ATEgP001BWNklSZhQk^dY*VjxSHt{Di0UiIdm+Ry;7twla28pQQaK~Y%E6IL`TPC zTd=)8wTRo_ejmo?wqc;J4-u=dH-V$Hpm8`q-5DLh{U2OF?Bp@Df4TUg?TupZs(1oD zEgi^a!yU<}I<)oZL&Yef2^K4!hZxnL_zQ-*+q8LsT&q-`bkRwTw zY$#@|{*IcT}b5 z`NpXk%-7eIWzlx~_yqdy+(YHk3iwgZT+@YLG5~1|c)xY+;iIe^<0F{IX8A-ITlq8E zG)+zdZ@&$E@Bwh*gco7^GeYH*M1|z<=I!D-uEO*8((tl^vpASf(5|hP=fE*djBV*e zHX3f#g!|)Lz+wu$9UZ7kJ{o_;gXw9^%+E>JvbK$jH?CuQcMqbu%>s_&z;PVZ*VLfD zs{|bX2&iIh4J{A6h-d~}-0$83dlMVGtCyD1eQy{Y_s4T`NR9F+FL9Pf2_FfnmLea+ ztn(wtx>ax?tH7x|V3HiARrMPP=?%Ejb&9&pZ9PvQTm%2!Y-&buy92W!JGDPE@u8VvexHvQZKK3>3Lo!w^l_ka*%>(f~Unn7;mMio~ zY9Y{B)q?t1H8PHk`>XT#&!d+yv@(Z`W8+j~8)nieygxgQ^EaDe#^M;o-HrdT|+hu3W|7t^v%~)#YiOo+9ZilJkqwf@gI+ar=R+>2cdFZwpUD z+t4X57i25;q`Zv?Vk;^1-X22B#3T$jSV>mn=0JY`c+=E0x`#(#Wo%`EGyU1hZ{3_B zIV@}yf*0~g;hv??vtv-OMGFop7uQ&>4x;HSYG)Vx(ZcO^VvJQTuOhy>o(pi|^?f#n zsd?0GURV7>dO#leg=`1voG(od=i{Bc9GdOV=!w$#^DusN4o0jR_{Qrn8lSEO+f7a0 z;aRtCJ?Wa1Lg94CFuACIf(RQ0({udIbxlJ%^If=xfrZ*yI7Ln-aaoLbwF4CfRvA$I!DLQ_P|@D?kYXpFf$7?~60ioLosVCk?BxNI#T0wj@ zg#+nJFyNwgW&x(-_<56T7n^hpMP~73_m*-plPt4ji;M0WAX{-bVx}>{H8oi$lP&yU z`RM#0s=X+Pxn*sS2QD*M&4ip*H7=?nCt0i0VPx8ZEiZ%*o^YkNy>nfUS}6BDFHb!8 zV0jqvNEO;^wo7#@EO)(o5xD}Ya;|HvoN*x`Tpr_fer6a1$olKLbmE%)T4e>=P`<0c z!uzfQYVm}8S57TY61oRCuyT1hpuy;o39j(67hJ^XZXaI&1L!N*6}5k?HxGu#plsn-w>hBi@D^*oktE@!T{EAd&a5m=K(Ivlk2V$?7gQm%8 zq!RJ6FWPRJnnwHRMDD1te47D8-DLGyv`04<=(oq+#Wl6h_3!f;J)`o`(h{(^_}Lv* zdIerbLDO|G5B0jvq|Jc_G#r7u?mp94~ZKy(FUmHLJ4K%vZ&0fhS*(61p z(nw>88i}$rR@hcp6BnW3rCD+91hRe{-N>MF_IM_dn{X;;S4E_BrZ*{_YJ*a z>2B;x0VtrVQ2X-g-JAY#-?`_U%)DN?ov`v)qrnqiA0Jt(XhJ|Anf%mV$ z?3r&c|Ge>@Po3=@*!T3qczEx=hRVny?| zXybYif8}GTwsBI*f!f^5Z?tqbFv}eEHHyCD(|P4TM=c=tj5B**Ww~Pv7>_2M+?j_G_PXjqVB3TIlL^ll-)K+O+6UAPz%(xNk4wLIWF&4PgG&JHX@u_U+h-!M@t|_Igx_V_YJSuSBQEaeCq! zE(P=GY;VW zgZB9a^i51+v;ZQk^J0Ss;}-oVu2HEitOh0_!7;KB8eBMNBz2DmnR z0f~vRxqC;3Q4IoIog2lT-o5AqIZO%wvEpd5P>DmRwGj+>l(H7gE$k|`qo>%4O1yy2 z5A8vK1Uox=5x`(?XD1db%NSdl!({h5R5oqG&P|(CzxHIi%MbAoGdbnvMPn0?5Sr+{E zA^WZFN6z2wcULYF^0(W{{loQTDZ>u>D5b_*iD+Sr0@h7TVb{lJaBk-gL`jU&av7tW zHs=jKSKT)K>v$_mV2E4Dwl3nO1#5B$s$fTDFho7A$rj9sVCs4#;7>uybE?yxHZnUaXV`iuyQBTb_Xf{v^~TA4z*;fotN)Bxczs2@&ih`T${~+D8 z&5g+?pJ3IMsx8oOPvF;Q;O@dv-o|YnGIkuhELN#Cvo+ZOlli*!1!%sh%B*72=)xXE`;u600%RhsWZJX*RS|ypkIfo189Ev;FXJ#Xsp(+3o|oj-RT>eGxB(YX0DQHbNMzTPwOE)iD`zKfX}J2hrK8p&prn1YdyEz z1}DT&ZO>vP{5YM?OXeR~Z>535R~Ht(-161&!3THl@`lGzgo``2p?hKmQOv&BH0ZSJ zMRoI;EhrxMVd@Da&hl$nE~8^^9`kE-g~{eimoa?xdgf6K;ycN2#$+3tGQj1)QfJX>f4QZExz5JCw_ZJS3GaOORTK+R-GgDPr6fsk z^VTi+`tIzND>!lHG)l!Hdb@jog)+?l`~$4}FFpr!x8gGoJ){=5Kg|>vgPy5rJowi? zLdReJ72>Ts5bxNPb2!J9SKc@C{n5gmmV$gL5+%Tnvn&B;lu>+Z(f z!UC4dW#Hx<5F4PQ2yaJiL0lx zmoK6C?saTDKX)D*E?*Oy&Bz0amR>~em}04?>#C)reh#ti`~?Is zxUhX27TeuJ*7YcgW30P11!D+%v;L5Xy6Erj`?j*aMxWwx#Pgh^F^JA%?F^T5#T0+`**v7{7DM=EHjgKQq zY@|`2reXVXou|)Y{q-9eR%5T) z?nYx9^U7yHI!kf&y81*qg>=~A>heMMMj{r*v)VhctqoCZ&XaC>VU3EUaZtq>F80+J z2-a`e2fjsOiH!pl=Kj@r+TXw}o1X_ew_>1kTlU36Qg%eXT2F1GYNf-op}(=1o!acS}xE>FILZT&}4j9Ot3U}F9P0tD#q*n-8C zS=^jEhb_H_RQ>>PYw0Da?=m>B3^vrXIm6BFnkpHQ1HrCvOI?K+lP zTQSpfdpAZ5U%igj#pMj^Xx_j_PU=ZtE#>X`?W5J$xLi9G>o%?h$mZ}8e`?&#+&vKg zWZq#WOE@2&j+56;A6C@(#m2rGvuMd8%Vo4IEqT9^L4bjq`Pr zX8xNfec{@{NuK>CU+1#NXWl#cK0lv)YIK%;QZzPZ(B2-PxA&8-$sMBi-UGh#9Rw}C z2)_6f!iVmzT)t1u5z8>&Y%${hY;h%W(SW8fNwDSOC7j=}z2>HE09dJ1U`#ddcSdnz z=5KIgTOWF!c>p^$^UYEZ?y8Qbz5B3bco;+dYj@~vt!UupIC`e1vwkZrm$CVR-sC`X zfHqXye2cM~ycsyPV-gRi*kQJ5TW_(JjF7^cP5I<8X9W?5GexHDxW=x4nWDWgDj;axz59Fl&g7eKT4VDeixr? zg_B0N+n$9{SirjW4d`hd5;e`!!Cflo2rjsG6Z?gBpgPD8M8xW~H_@+xX6)jmD>Me)5w9uuRR&J&Lb^vt6E^PaIRv2o09`C34Xu%ApReVz?z$Z=PzkJ4yqW>qOA58VKMB@!xt2`^b{+&8BVp=o zTU^9KNBeDETS-)0S;6D4yoQP?qJq?b2T>0a=xP0Edy7=*^oB70POhRt8|&9!yMd@u z!HGi$up~UIHcPEbO9hK$-?Y>vKH^Q;UiG}Ej^*p3ALcQcrh?GfhazS;F3&dmCb+qNJwDvOx1sXz&Q+K{dJCNo zZN(FZ4mXyj1}&A#D9evqNw9Q%3g15QI?RnZATem)(1(@CAPPg2N+oo6c4DZnAD^Rx zX{RbaAnz&R^s+{#s%J^K>6ak-_#FdjpT?x6o=vW5kG+g9?D~%Y(A_V7lIarFx_Sode8aX*lb616^7A)a zcjq$d>9jUpPIJrC@@4tj+#~-lZ37a^*jU_GAFZ7duHdhoZj}sxss|s4C24u!le`jf znUp@n4{w~sP-_qN^$ejs4A2q+GnJ)m0XjmA{_19)#ib>bE0x?n{Hs@A#?zZ0z=^TT zxH>Zl^XI34`7*F)5awULkwz*-2>;Pf0j&jKVgcq~yb5z>0 zLJ$P#?&v@m+^*i{r_Vlm6!-(*{nPnmug|; zb+;Zag3k8@Mjr2MF6VBCr#Z-cpUtI`6WDsXtG7!`EK8NV)8@0XR;d#KLRhj-7+1=? z1Ms+^jsCcUa@WL0L^Ym1GYFS#wo{v7p@YU;xLHB#{;;g)}!H>_R ze5PkO@!53DS2`2!+r=xdLEGXY3<4Z^^B79Y zIo+GZWbwA@7h|Z#@z3cJIi-aac>WM-U+^SH)wDW*uVeNS@%`Z#02oY?*SJt z0!NPm&#jIp+$Tw^nK{h$41#P!Ywf&Uyug~itJya?CzlqN@SQ*THj<_K-bsxyn4O1TxM_Hed z%(N{7uB?<;m&-KPZ-W5kcp1hRlnU)|zkcI##kNrR%0;ZV`2Fgj7hAl1qL-SmMXK@ux>vJA#b`aR~8Xev09u| zuuz_X#>;6Q-L2~pCuMZB^r5qb>$r2^Q6#2 zxj7qiazpFBfkOyHm_8IrYdKUi*Lp>kCaKA5jhM$N`xTVdP1mw?H>jtp3nPbjqkLec zsdREa1qjhSJ&ScyQ%xUWw5e}$65G$7N8gPJR8UYnGUd|-8?Ib~L4e7DJ}h*!<5rWq z1_NU-eC;}-l~`@~)azww+w^>_Wew8tP|c|^KH zAo(;9i;*eugpJSr+m8aL9ojab`87mbTS~|`b{+JAZap)lO^w27y*(D?uslqyVtr#1 z+34FnJ>!f3sg=dqVdr$rY7g6yxT9SjG;-T*oc53nAze3Td!FtG7wJi#rzaLuViWG!I5TH0V-yST2KPcQQw z?(&U8?yJ1{@A7S#k3AoLT>uL=OQ<4`|+T?F+8-&W}a_bQxZ>I zwGKkhE(T<2q!Ba!b=RX=+i*vtMvAgLsS&yo#nvXI#z!lDoP(>+N$G2xa&7y*jo{gK zkyy2HZ@1FvWIx+-)F8n1+4ET6xfLyiPDq?2sTOtyfPx!=BjqJ-1a#L6_f@7g3-L2G zn|azp!+oE>*;>{?pTU$~lIX22lUpN)vsT1O-D86fDX(%Pc$x=+;Q+L;pnwRKOgWeS z@FXLkp++^SBr(DuL=eam3{-1k3o%}Q;_+2^28xpeNx1@4s_JtX0R2D$zW^n{1eYt^ zLB$YJQJh{kKqam;boH|fi)z#2(h|P){qG|wMJWB3UqrBXeM9Y8jgjH;gNN|=|8}T; zM5_$ngw>>3o@>Zzj`G-PbLrEx%oN#Bq)$O>&`m&%-t)PC88@9BHq)ls>N#q+zLtQs znX&y&Gg#Mc6-m2AVE|Ag{ zzz9QC1iq>&RiFCCZ{d+Q-^OcCerDC1<)b*p{^KVxbnSZex~)jnH}&?&bJaL~PmAlW zfkV%4m&4^NT0XL+U}L1m#oB@K)#Mcfz#5!sxKFo1J9Yp;5a7g#wFIY{*3#tTGb!o! z+5qV1EVao%tNlLHn9t}HIB{)QSeue0L7b$A`)n{qKKrkK4;Ka!^mKOJQvf|MMs3gr zfJ1M+hwiD=n{5Dt(JdSC;r@Ltdq}?Xmnd~5D1ZLThzEwM3*!0& zH1l`&HVBpj=`#@?m>(ht7*PZ9jw0TdtJ2>i@Je(|V#6=m{&ya9YX zf#6pj!GXW`bv&~FK>)zS)D&7vE%@0lJda|bK0em{v6fQR&N~#FOHvFU#qpXPKm~xo z@tb(~?ROAYb$I!u!i+2B>BscW#W}X_%zVZsJD&Z{Hf!oprQhnDG=@x^94U`%E~xih zA1Nnn1g&e!wQ=8Q8-!n@39a|c>FaSpk}NzoQ}j(XFtUdQ0B5Cv7<+7&W|85 z2$KZ8w{GFl*Wb##sqnSbDIX-S;WkG0%?0_Mxu3jeBVB-w5ei@AKw+tZXI}UbA|!bE z>8EmUf$5x^!;>$)j0EXb&SexupWBDB$W|Fx{VZ=dlXXwSY9H3fx1ag#Yj=((-lsc2 z%gew&`)9z^6!4920M9)0N!REnlJYRBjdZk~R%+ok*LBw){9G)Drk9ZX*0<8%Erk@f zT11$4Wn~3_`klW(&{BZ;@4gG18PAqycm3Tj;;H}jKLdW}?>1KMCqQA6AV~cE^7yN- zqje!Y+{TVbh|jXq3*w?NBJ4PI7CTR!5u90TQnm+JI)tP>ZPKQ#D3eY40JG03V(VI3 z4+|hifIUVuf+hXlMja;0OIq&T?WA(-nJjNWu9*cOZ`#^=%Qd#^sLQp-vd^AvKpxCV z7TeY#|AuWT`!xktJlA%9Zt`6$RTgky_;bpOw63fC#WT5COffk>iq>E~qOb`4y?tf6 zcy1+L#C-V{*0qh)DBB-CIe!T~?IYez+t;U0qQ7Hn&ZcdkROrC|k*|2)(fDdDcH_Xv zSDhMc=-HRmzoVrO4-7r4(h&`J?-nhUZ86w0__!*sw|xYC?Hj;0A=bWa|Y^3m}L(+EnSst$ZyH>G`g|D>)2H@pLK^$J{*j9X}=344D{r z5zbp=B+VF6UeN zy(bo~;>z@Cv=qBgDs(AX%<1epx>Vo@E^xLRm`6U)U7u<*jz*aimG3iS$oFZ9#)>bM zXFdFC4Lp~0K5RsiFq-}^RcP*eTC@tYF!td~Lo`(ed8o+E8vqY0IW7L*OK;=oz&7mc z98l(-ba}g?wmYnb-uU2socgE#4(883Nb9hB0KtFzCGNA|`8Le;SpY!zYmegaZ+;zZ zRnJ4?Q@8MMzW+V^{FnSj5+Y(x_KBEU)X~<4Z~pX817Gc{Yu>fc@zB@rKqmu%p zwvj81kpP+RPS-$Z$8N4}JZj;|nawyx#U&QS^UVgnym6aZuZDVI6;=k|QOxl)19$5! zg`aGTE70FR)u`AZMQed3>h1&B8bRO=I}b+wbA{p#!+Oam4ot8lv|31w8TM zt4Iu8o58@8d&m|F60lLd`5%ivRw3zV2=ORtV@*W zz^JxXDmcs;W2=7cGYfd?#h3A;&po@UIzRmOJLtbTAvW)EpKHa+1=Ke0*UF+RtSLl$ z_|$P4nb&uUf8A-?ycsxf;L}<6`*b_BI7yHa_UK1+k|Or5yUZ? z(JxM%J%cyieW#(gl5Wk+;NSl62P(|`4==#He+@~JAW0GgPj3UB*#Yz4e;=(q9r&fM zejUM=z6KbBsI`O*L9-gfou_qEQ#ktCn?go}Kmx=lWPQHj@->W%Ud42858n99<8|{K zym1qUkG%^sHxKje?_jR$018h%fTXM4TA1dm2vd2ejU*a0lN`|ciHt|FS+A0YReC2u zwY*=4#+weaQ*d2*!A|-q=6p;w9wQMTUBnJmT^VOcbAwMOs11sJo36V7v<=W& zf0ggY<}Tpuvg(>8K_^W>&~7T9^Loy_&=xXq;X$Cfy@5uB@^IbYpQx7D>U zJZby1R6}Fr?9?fIF!mY-+lTPkEnmS(QpTU3`TtN!VtjGymoV5i0G=Z$(RPbeCuQxI zH80yEpY~4t{Kmt8iSg$68N4-d4kxCsJN5nji)V3g;V7Oud<0J%dN`+5ReJuXfI^fW zV6I2ce-%iKbD$Xj7MGXsfBpHl@r^J4REC)wAv#!cCyDge?wQ%!(y85iT|b<85|!e* z+mC$tHd=nO^#wFe4%8bXLVeaBdo1fPxx6aJEVA-=TsO`u@^G+gz|6zTx&|7l2dZtF zS934P^tAblHsu$WR`9v+zknB?d$#GDGW13=dox>5-S`|Se8zQws=qW2Cy27IK%32_ zS2I(seF4%7e}LYJTX^iXH}L9HPvq8l^X1Ffd+I|ZCd3Mg)p`~njq<(?b#n7Fz2|Kw zLDv3Ae7{us$DnJbwcOJVA&$QK1`t5?2~ z+?aEgvOxZlrOO#$pe0KBmoYJ*B?GrcFM;#Ao?Hju8o|oRm3g%F%ZGin$2T7a)`y|x zKTZ>fXCT1ksZ*#V6&%_46%kk0x|Td_R92q8`7-wOeHrZ~-mL3OYll%C=9edNe&P)r z-u!b7l_%5hT<<^NQwU3Vc+1Z>(1OOWGnMDd&yJUum+k@9qA6b<`%v%FFpjTvAz3SJ zX|!|WGEys+#vAt6A0(3uoWNE$lmSYSqqtnx*BHGUg{|fU&uT(@2h#&hS(- zj#grH%*`VS!=@dYwJ$8-!4FPkPKgq+W|Zpb^8OrPrKN<6+qdDu_H9j-0{|unaO{yI zc;v0Ov2J_{L524P1lG5gSXAOn-&mzBvbOan@QjSr6W2h_h#(t_M#SOxwv>?LmO^AJ zDR%z+m9wtC9l(Ciz0B>Bz3O6UmKe2K4^eMhTS_r=8bjm0bPN-orn?zg_NPy_?nN?Q z&Ir9JOm2GC&pz$W^-9Su25sC)-;!;4WV1`9ews(5atCNXjPF}WKE!%aVzoU+jfEy-V==-upD>iD+CGPjOPcc-mD=0%Htbym1EIg#ucl0$#d#E{oF=hWPv2cO!to_g;Gy<5Rb? z`t91X6~q1gc5V*x_j`IryE=B)!(HtVN)m+fTq2axf5=!DgDk7Xp6pNTecC7 z;@2C|GCi}!+KRR$J01xh$&T%F&OF+rFk*Nufk0dxz4C;=Te>#NN|^3$BS8jGbg1kH zTL??g;zB9y$&pH^XLyrh#0IS_@T2PQuzHPqm?WznU_)bL*n8qsig05CzD8LCds#QF z1jsR>!}UKNhqP!-5H*Z?;T*E$r329V<$kP?a)IJ9<@j@1Ox zM9l4Ra5?_ z#>cY0wcgA8^3wUlLlA`6-v5}xTMYudbNO4?)^`Mb9h+6YGfQLmaO_1K z-TX6n<--4iM>qd8+KOE`dHsjDF?RvmdJke}|HCi{Ftm>ql=0{T47LKoHmW5Yh;Zj9$e9CqIHVNCM>DQF}$wQrX8BWVjvXQZ2id zJ3jC#45*kFUE%54SGbMdG$3Em&zzE ztz?_b;wmna_>8nL-Ci4C(E;UHeH+?bmfACNiW%X8n{*1zk^ao^mRI)KizIa;MT=ROftD!@DM0Dt(0Kx-@T z%fAd9K79Ymt=pt#Fmhv>u#{9b8S4#e+WI}|{&B{0nx;|#KYHhF6yE3Yv3Ym{jvhFO zpZ&t~fHA<^&!TI~`g?YhcE{X29)0sIC)^-Fp}Ycl21xc3@mGEOLK=&2t{~1Pc_?w! z&^s>JBdq4*a&wb>@AtInT1PaRQ#OYosV&c|L$V2z35CyEKN# z!}Bm|EqVO-wr^m0$^R}dOy;+)eIpLHH@9KC9yQKkYV%7M8~gLN@qy-Zjik53Svzwz zGg=|0@g--P>}vzo`RG0>fLC^Sj?jjauo_p^LyuXBzsOEz5LWejW3cL*bDE`dmoMX` zKmH30eD^Z&cm7tx>BuP<-^`O>XmkuCqobJZ>BbvRJO%)$G=S|3l?sl&{w7-Imogk8 zEegz0(-0E{_;~LgT-m&7)$Im=w;z23N8UJwz8jNB$3yxR$QDA}fOioPf{+-}sPUpl zS!0@nZBxs)LTQpE(|qB-v_Y0~^yMzGG|LD|qj9T$ZCpyH`gL_}1KI{*%Rqjo5x>ON z?6OR6B2VQM`PWX}pV8*#1hj>jTbMd^qZ^ZX>lk6rAd_2myQECX!>V-T zp;~$fa^NOy6Z9Nr?PXu$CM%t7dNh9hZIF4}-olM11zDSuY8{DB%8k&-`k&h5jz+F0 zt@r!%l)QdtJT58BYQ^6;%%15t`CpehpB#x9%**jKt7#yl@!QvktT8pVkxYa2Zx`2X$i!eb0?5=XZk| z5&4=)YDULUm3<6A*moVJgj^_qO@F$~Z@y{=u!ReO@7+YMx zN`+QbN;!z7V$)w3^ z1-Hp=JGWA9O6O%!_ENwinrmJ`0R>c$3i6b8o<0KvXxiI$SV_>juxxpIPKAu?g^SwA zKB@KcERQau>dt*cCV(IVd)0a*F*+w_@z~36fS~a4hYnyi2N<+2E#cv}-$8-^rKK|L z4cppF8hfzT^&!aa)>)nfXs~zhec*nd zZkHO>w4kfA6X?A=SD4nLLZyO7-h5kubn3B|w|o3`1LWSAr z6G>oS|IA(_wGrC}#*76dpr^9rGmQaSNReZe$E5axWP@qS!Ol~HW!B-OS={^GH!W2bu)cE}hP!uVWwjN%aA4?} z?3r}AZR_?S3L+Gv7L=kA$Osb!MLf6VD*z07T6?oP>17j>#i#kfK7H6@n8XwS>GW(? zYl%weh$0kF5q_~^v>-%;80Uk#dy1^QvVtGI{T7~o;wiM&@i=T_mg4dXqLoUG6wT3r z4~}E#+8Dx0oL!j&d^h+VjL4M%`L6V>}zoNc?l(q)ila}@dMl#a&s^YfK*U#Jz zUhuWQJnK)KS{|LExb~c>?E%IDD?D^S8kK$A^ ziH+-ruz6@0Kzh)v5Jik}?}1GUhu(QFyS7=9L4Yuh(K^56d6&MAExWXRa4pZn7T=mc zQk$`#v^d&&BQHF<8=ZU`pZH&>a<(^ZX-q8B$?`)LgVRcRrR&REO*NP2IFyTx5dm5^ zlUj<_v-HY^mfGA7%0+%VON z1FeM)&kW70`)bM7k!4x6adBgLyOhsk8l}c-Ve>$(fj2_7-pt`PcCc}{)G*!r+#KxL zAAt03d5lkvey&LXd-s&Y0zCHgYIMrCg6jH9*VHT?fBAL1^4Z4Mc|R$Vb1nT9p>t*q zpZnem2x0Iy&wUolHFT0frGlqlcnQUF87tye0@Bm92A{rt@6e%|2U44D0eRS@dvT-c z=6Tw<%Ok-)%E=>=$C}O?)t=F4mq(tCTYE-u3_0rLdpo^6lE4;BIlf`Nq5o@H!=?K0 zq`zz*x!Q}(hh-Sg8+&d`dE(j=fE2q$pkua#NogxDZ6yXs(j`^NNLDhv>6yy%^*Oc6 z#dofkY8%7ZI)Jtzuq35lWXmIch2%MH)#mZZKE$<$aIIC?-$mnBDm|Sa^oI19IBO$s zT&CWZEhJPP!$!aM)^*aN?BiLIqUv1r^<5(Ri?*|)`c>H?!K?awydkdk86WUA;F~xN z?3qLVuZ@#+4>uw$-En-ks9ybl5-7fK74!e~KS%d(|2FWs&jEyq?s2+$75LzTwbMjD z&E!f^zilk3u2Hypy=@nCe}5Wi%Y{qW_3>#CMgk0iig7ktr+=BB%J-7!o!{Q*?;{@< zmok#HPlbq zfPVW>*{}BJs|zl;O=FKv9Y+uZ80mS?nJ8L`)`o`Jr5iYX^R=uF4~;yJVw7G9dVca9 zv=_Uup=$>KU}k9om!?i&-}=XK?CSS%WW#ePMWt*|Uz$D*V`6My_dr%^VhnCB-h?p; zR+1Qc63Gv*r$IVY1S*|B#AkN$i5I)2fj86^nE-j{*2YrV2in-B+Zj{=p9IWI68?U1X2OU>TPSU!+N}*3AzJ5`vN>*#F;?u-?E|suU+KZk-Vnfx9QIh_-|oof zS#)~}bt9nqURK(dmw~y)Z#cY9_eqft5Y>*~NPhW-XxDgX!#iD8BdWZ&oQ@J^2TS;_ zSiF`rIWvv9kv5F%K8ypOISd?r3^+KPy&oA|k5aL?ijwaPjf`H!hHKXV2!3P?)=f^S z?v#L8%Lxrm8Q@0HrsY(}>zbO)Vkq29Bo^Y0fTWp`sbA__Qp2+~9Bpv$;S3qu)u32U z(%(uy%l;slt4p=@9ACJt$EI<{<}Tu+n{OZpc%y%P()yr3UGq41xiW{-H(tcP4PQnW z)b~DROoCI_{tDX%pF(S~TfJ*9^1gT2{^8FfK!A1aBUz7Z?|&FAQ7hW2bv6hPg(dX14a4rq z&gy|>jV}TOL4^MH;q1#M*%z1p9u+N5ObY4AMX4eILXz*C1G#*4?^ zMj{TcG(t4DHeDV?|Kubl`ulNd>y}m5<-y}8Fm&xYqH>HlJG2;q`YcKk^h{16LV^Py z9LIv%d%WIgSNRPv}3_j?=%&8qxN~K)`x$&eYQt1mg%zn+~Twx#`@$$ zfwy(@_aOa4ZtK=^)Yb)DU4jn-OTYgT)5|p4j={^#iFhX4N0haLmd9-gny4OeN!B^e zFt^+suRU*T-AvkJ0xOJr$_>{#6wOO}&V5q!NtgerrTKZ_wby`u@=t)TeGT~f*MS2E zfVR~g{<%-9CoN_CquIqP6u-7Me7n}B)|M7L^zZ?gKlxn%z~)1H&|O(TXL~!k+BUnR2VR?jhddEz7s_ zuzW@%e|hsu09374$pz8n)wL!CR&TIfJqX`P5CbxB!kcRVyg?l|(N^@r8Z zkI5gNCwFVtes$71pD()QGFH~VeQ5*rtT!b{&63MGvW;ajNmqWyGsDT7@%!_0Z;zuWxV;sV_3Pv_Q&AB1_Xy1Usu*#k=vBbC}R** zQf~IxE3X4V+R8J#cPWQU?ehyb`o^0mm6rj-$Aozmjkd}&S2X}CQG{fTt`(J5Nah~C zZ9TRWCzMd%9_5o8{I0oKB{3{LGvZ=w%=0G5-W&Cv^Q({3nPTR6-vi8d6=ElWJY7>5$FPUob_Vum7DMzl8BI8w_T{#xWonzkngAe2epJXxeG$FZdk5>xP)b>gN z)zh}vu(L7liL~al@!C|sevsKxh`*+XGD47sMD3EJisvkU1?ddW9oK9xgEQCGenWJl zdERM^efF$@F#&e1jgQ7pj*g#4_y^xY=e}OxKmCt^b?bm&ZNJ%_qM;!mNdmn8{!fNA zMaw`fku?ITrRC~(wk}V+B}O6B5fT_Y^7>nN|HvUsue&!Kc9qIyeCE~H03&UT0gB}c zf{K*eZ1a`!iuKdPW7{kTIywC2pkHE|O#&htqPO$bM#R)s^GAr&xw*ZBJq=3UjsFTDVqz zZ+hoqYyCZB9^3{w26cEC7V*sXUqoB6%bA;QfB4@MWt+BL(}Syg<~3TTw|~3ToZ#>q zV$u&XF?Sv}W>2HDWdNJ|j;Oj(*Nsjc$HmFFFwn6b=t# z+_f8>Eq#y!XgOZQ*z6e;!V>llJ&iEnJ?_(sH(*Sh^}}+!h@10Qus?VLgB_a@29f9^ zgN{-UVD$O@C@kTT;U@qXv=_U;my@LGuv`kN`W*wC%xJ3VXCC}=+8GSBc44HoO>8@f zQ9uO`cCAB%7~{hutM-t!8Va`dqV?x{v1w?yeq`_jB5=?*K8a#^Wlic*SgBy|haVz} zV@MS|6>I^zZ%t$Cg^RejZR>57v-QG7^h`~Og+)^3H6sQj;{YTxW|CjKHmz2{w!x*p zT)PG|f3$xOo|P^$HEKLdbCAxvB zJ{@boyrFG&5nIk*!b+)#&bc`hm&;j=Wg85Db+@L`H8U&VAwxvIhD~~?cDhlr5 zB)(7g=_ic{^45=+l9ZS}=v9x-k6yurtD|WySEjN2`!C^qTM@xGkKnO`51}Nk?A$ao z1nk~}p3W|etX~i8Yp!i~n)ZD7F^VfIS#R`AO`~UeI(tt&;#V9Djo+Ze$TS>Loac(%+ai=1UkV-$}4ehGM(MKBJMZFMMIraGn3pXDpE|*D|fG*oDpO z_MxS~-X`)etRL^D;TI;4p|5=tx?9&<@9W`ZrZ6a?r)>oJC&R7qAV7E92%^wk>})M| zqqW#wQ!;n93}Q?FqgYy*_P#d=(9<@8o;I$lJ1PV8cWhP9G!9Bp8wNYKTdf3o+cspe z-8`jssLe2ZZxo|hX`ta8pz`1ws`LVbI|@_nFmiaWiv?J(GuU$B5-PRsd zV(W$xyok3~l|Dg;j_G-HP0yfnHa-2;?8faVj;kMri&SI3mNK^jqg21Lg0y1lXnetxWdyV3U|KU(BJj8R>f zrHv7a9OYpnE{{eE0AX8^hiiEr^I>`Er8;XszkzPE5DjH3H$xYENF1C3M z9|lf)LM{P^)?co#Z67kC&a_FJ4z$o0{>tl>hfJ{nwkPGUIez@o*DAqqS;yC<(Gj!{6pa3hk;-Jbzsvb zAgaH4=sw*YYG#!CcoN%pO0rLiCBxJ^)KY@MB&5UiPam zzm)pgN4&N2_kr&>w{)#3k0E-7#0Hsc4Kw?ABtNghX1E7zJO z>w&aA*zH*=!^PY_8vyeq-rSgg@G)ucXXb^%A;JcbVrAH+h=O@Wg3pE!xG z*;xRZLO8XeHxUw`?k8)*4Z95tNX3Y(rG@m9amx1NwyNm1BoId&p_~8o(HWU$j<8K3l zgP(MbnxbOy-aD^-w?>4N1Jc$ipAwMm-7jIK-bZ_p(mY9Cq`v`!wuL2iqw(FQO_#4= zWb`VxJ27aRU97f4+ZoB$YHMe*2UxkoS>u!1UZC=D+h-$tekPg9W$LlwS_SM`$n{uUna6wAet;vJzFKt}rqk*=xnz&; z0wu6b5xxX@VU0roH~jMCF${F=L~Bu>^jIk0!masB*w}k0H?JrxVYxDorIi`AXLzPxAZjo6VAtRiD1=39RrN3!>fVLch$TyVu?O4w z9zqlpu)X(ys)GU0*EXb-8Ur8-BJAqj2ME?mi*#u%>ei2*GUqrFIf}{}Q+>YkFg9E^pi9fhSy>54gW< zSjUE}NX$x}gKaYl=%|Klx_HF_c2YSYub*+YX`2-q@>0hOySlwv;7Cv&WWbQFdgfyb zA$Thc19O1CE&*Qxk))p3-zv`L6)mpoE1~5=ukep5-m_9d$?uu;D5f`)$+|H~ zwK!uH}2DY`pG0I*J{U0$#1STB3@&< z^J=JAD4=v;1OxxcXR&SL2o{!>apuNV9NPaN9^A1Lg+ifzCZ7Ox&dy=z+L#L4eBm+* zl@-AUfl3CfrHr#yI02?Jc%vHgyFrdV8F!toQQVE)Z<;0s>?tXr@o ztrUwmzhgT#U$~sDnkQi6Q2Xoxww}L$Bn)w7^QO9Gw=FJWWb`V6IKh_lmyj4bU`d;c z7&T;QBQUtQeH+ei--dFH>!b5%s&^eO?A!*xVBp#~$ah=H_cdo_EW$iVl0;{cPuXO1 zN{LmQC5>Czkf@Dvl6wcBezf_&9Jd<1P+3}j`P%HSpKTztIelRL)#bZ++S^35tw81> zeSXp+FJC{*n>|Qs(_&Ur0{@0=eVd3KhvP{bAVeCSR(e=wS(1lDwPjQ1?Z%e2S0KpjoOz4MjEiB_K-#3K z2D%oS#}jFsp+{sM_V96Ut&d4GLC=J5Id{9id|INfw*GHs=PK<2`8ZhjvBoa8PA4gi zdv)eCI!e9hZXLAZ<;}U~Y|D+v*V~WN7=O4ER&gI+T{~_i$F$VaQ<9oekP}wR3L|6a z)H1|PCoMgs{{pl@8$k6it&dlvwMmcLN(v3IZgL6_ocKuH#%kA`LI!S(qf~XwRa{R0 z*4wx}vVJ`d?%soI<2P%@^AUTmHJM|x*`7{Z-o6EK6k&3}y@gCt97UKINN=S+d0;p7$Og-;4=iR{XM>DiLP zTsdSwPRID3EV;Rgv=_3^v-ZLJS$I5h57_n6o3t6J$7$OB%(g^^fb! zvoHc}gQObrCT{9st{?Y~blVkI9U;aDRK2B#Z7soh45WR^$E4F35n?L`=?P!*WmDxV zRBv0mpt#J}^XJFyqlj9VyE!~ArPO_Dh)$jaUU>y5g}|4;oZ{*Gv?kQ(XlzCrHkPMP zCI)Ke(rgdJ%qLxjxNMTujDDwocbq^*S`QOq)@YkC%4v$I*9 zQhlM`3!Oww}Ss4d0Dh_c<>C!y0P zF3NZFl6{~hL0%30`jB5QboDHq!l+mhjoa~Tv@ZKr+KwTf?YhBgpROs78N0uH$RF8n zx9@Zr5~~9h6JvZ~6p5h~4P7_3eP~Rt!}xc>0Ju4K5v|28bhh+6iQG!r#t5KXS-`~n z1#IZqUt?JM!^`m^5)(V&iK$>EUd*ir0IX}@gzZ6qnZ@hgdIm5U>fVDP>{0Jp3LV(i ze>97^MJ%98NZVdohuwouh?a6&hP!quRj9qxgKedUKwkZ13O%^>LL!xAPafWss1ZJWdFJ08%IZRdCO)juVTTqSsLi=#m>!}@$QGG8crkO0|}#%E29`+ zKd|ae+ii=B*nII4ww}8HdG#y_i6HBr1a0#R*m~h2MmKM)pRtFED=P>Rd6^$G0y$m+ z@pZH)<`~G**(RU7x#w36qykMwAV2fu+-(>D@y2DsdT~v*UYiAsO6963vK+3N9VT1L zWw`NNAscww?(dsGq~-If?0ta17mHdxsT6}iC7(k!q6CUBuVIt|SZ)@MvklL+JfUbP z?3!?h#}F6?7}io+fR@?G`*s>Ltn!&i^g`M?-?#B8Ty9-ME6jc;|H|z-^jG?AliT!U z|FThnLA+E8UDC>-G%-leXtF)7r!mY;wn?pBe?j&4K1mmKGL(>(_zd#x7&H zPxtAz>Gn)kwu#lHT5~;*HVq8}Km80Azw{_}Z{3FZ#YME7J%c0r_TNTb*PaG%+(hf* zBBu_!32-aV_33*JExA;n&;cCv>uHwUya#TzH=IezR7r=+l!e_>G!HF)5-R`>2(}U zK0K$NdA&=&3&bzks=!Jwb)LWqk?RpMKbhL7_*5fbjr~~DMb7eTxP7GU2Q~&~EyKpW z6n1^~JZ>$Hp;YLw%7%#Rr$*${YU23HTdge2vpeL+Y@B?^V6_rk^5#4Yt;22Js((vl zOR3XTG!9rpBAwffFFCfxCp3%Fd5uhmCGH{hRyqH}>^B{_l)7NbrJ;y`P`e)jr@`_ot;mujoq3Wor!*#wdC#@C zu^#76?@8wftemJ#KFz_#p=@npS7g%7mvon9TTvvQPWep)BXZ@QHcTSKmd7YcNGsJAl@SWS{a8 zNmH#mt>H@yP48_Dh{->P8mHQrx?a96zqn6+S~-0c!F!`9vcCX*I@}mq@2yKCwB_O@ zv@MdSY^~V^iNS`;*AOO}AH-E>mc+HV?OFzDj&Hm2@ZlkP$NfZcpyF#OsIi%itK4|D zhDDyxA!@ z%u;HMN;hrWz&}3|YSc=yj9Uv=Fx>N?w~#zC0Co&M<$c%LGKkKW!MX!Hz1Gv%gx_DMov?R0JUtRoT$4$I*svx zfxEJ4dv;+SH_l#xIWY!2*KBIuND8DIgW@p6LPrPYx|+KZt8;b^JI*=L@Jw7NDLF%Mi+qD zOFk5pjJFv>nGq=@nD&*fYv?x)`RnhtOhX%3CFa#t)|r3n_G&?^lnW0(pm1W$vSx|e z;dpLhfuA4Ni z@K@roVRGxI&tFT@<_dU!yP+B|`vGq)AlytGS#~4k)=IM$^^i0(1Dri;Fg$!8wBM(D zjqEY$8>3SBPk;M24b`VjLqpl`j07U4CCge{KDn}& zf3q)NmQ#V%R@rtxl-F9nMif5t54X~!SXyOjZo^+=^^UjtJksA z)_TXiZKDt&cz7dFbT{Gr9)CC`dst`7 zibUSBZ}qs(!^O=?KJNL|%kR~aI|hFuXlxAe_x}dvQx}29oA7y-y)(WJJ z(8lx}$L}#4$dj@BPGVY(mGpa~!l_RANQ%B-Ub&J3v-AL5d$RoP#<2kAKpDUB8EZCv zEG2(SjUVE--IKL=zLwGUk+U?l#w%_Pwp8Mt(RI+Zbl)1!Z{0t>ZLBhmt;yPBK$aI^ zeEtefjJ<^YL(ihGePhnIroVwm>ynG~8zZ|+U)t5m-P=dF`Q+0z*HTj3SV6zjxWbOF z@q|p{9tzc%+})68lPrTmbQo=E)E;eltwom2c^dHjI_@nrwsnj6j(bBvJxUUT%IGxk z!?Shc`bc{Bo$Kzz&Gmz;$_D_hZcO(j%y)GlFb3-;r>f|txw|D!U%ZIrm(C#A(u?7P zJJ7$bd5@Usm&rR&&FDq1F*iqz>)w8D>l?exQ2v~1gnKn!mgL}W{=S@T1QUobjXLSA zE7>K7m(Mi&TxlGMyMO69g6r|wrbLx)vUOXU{j?!F0lCg1B*%!8IS!*jSMuq*GVKk| z>{VNP-6q`XYsdJ&0OmS7(K$PZzKKb}v-BZu=@5o^7wxSf=KxyL>hB>jwCj3|!qWb~ zIXu|Z?R@h+omlK>L(9@K2Ck1IvEFlw`G`!)ONk?s+c;!lg%G>7$QeUOx^Ldw?gN1a_@{$!_)Us%X$ zWn;V4!W*eDz{N6vy(!smgn(Jzb2Z!|i++-*Z?jO0dy-{ey6FLps|M z^3l8<=97#zzO!u$wd7tubqkZsnc>!0IH5hmp~!Ahxsv5mtxwSV7g zn+yOrvwIf+VC3Re6qZ)9@uD|~>!mokDWAsF?JLsFq{*KHwZ=QAOHG+)d8`($lj^mXr3*pXY@^){~(w zZ?5ny&B_hl8vau|P4yeGmo92Yh!|w%;Wm&0$QMM*?QML{&+a=Z0Cjx>*hYT-LbTLR zn`pwUN9A|6H$HHQ6hm&UBlR!I;^ZmNTIr?q>>-YTFmX^B4zOoAKJ853mNo>rvI)?$ zL`oPr+O)c3%a_I^s4E?tr`7PA`}FCc#YJFY;okbXciIG08&Kk4*=vJ6O}0r!>MPt9CYiU}dv<(&;`sVm z;}`cUxZK|d=xu-R{W2Ki|Tk;`WN7nkO^h;D&uApmX z7Jxw#MwsvH$nC#Uxs2AOB>+GYhIR2N02HDKy(0s-^?P3cI#-9qS;nNl;wZvgS0_vm z;JqVhp7giz(fHSI@?!OKOar?uER(B_u}!F zUqg`n=aZcJtMk@T9xL{U@*5m)kL=M&W8bz3X&s$Y%JjN^I%h!62mOAvZIXP`4P(li z-_jmn^LS|~ppip(h~LwEVt-cTX*`#I&co-7~U# zJWJ2~vE5;hEsxxmWm%$VQ4}fefJg`=K@bbEqW~0uLKUj&z0CQM@8ntTy_xx56$nYJ zgDAZB@^0tey!V{*ox6qZuBx@JbJp?rH^99@S`)H1QHv8=U{CL_*}86;y&7`EwtSDQ z1*A4l#cyqCNbeHoZTp|pO}eGa7cI?|7VvNhUA+oC^9*JW9|s7|e2+m+rWE&GXlHexD1vuByl-bz%8lOV$2!~~{$d**awM^&mf8u~I*V132DL-118iYufsinTOZCOf^Z#EUVyQS&8 zDNl`qqg;c_1yB+j`*?AGbIBT|ThuOf5cBI=9Fg5FiZDknQtW{~%@Gy35+JqNozk?6XpToLUt1G8PUb_T0hX!zJ<9d9seqCGXeRN^v zN~BSQ&F>z=qVXH~qUb8V7XY|;ao55?!+d%c@+nM=}0G_{P&xBk$sI4Pe4?h0y z^2l-=-M$Ss7FE9u{?f<@E{%*}==u%R8ci%6)4N4!g^EPobk86_CxkPP+8ZV9C&uB{ znvvKWd3!;mu~-0k4xLI6x6Dwy1&poe{r55RmtRM%rwg^Gb}cN}zGD=^#BPsG;pz^J zYos5UMsZ|P(uk2*LXJy5Xomcm8Py;q7aywtEWJFAWtXpDa&Q1?WIb(~SK_`t+rZAl zZzD-F$v2BGZ|gAr(-@gP?VPYaWK!c~j&C`%xJqO1Vk`yq+zsP!AGWo8u>6%+lJf}3 zvDDOC*B|P)wuUrMa6VnWsgAaMNfL=mB*AsiJ)QEfEt!hY?0?#1#3gaKY%h&ld|FBJ zE%lS1ENXWxKxKn+bCzWc7yYpCW-J#}DNXOq1&u}2i4hE=D}Va@5YxVn5PzQ6D8ye+2s`f}w1 z09`Y)*l_$LHXb|Ca>Ulaa7Rwmu}kv8ijg@l*d}^!+g3!46dR76Y`vFMlt;ZK5pSGM zB#Oiny_bsn1h-ID52{W3q_2r6Jd2ukOvYe+XuOhM#UZ$7N-SEiN z)7?zL%XR5|ZSIYfn%zux(KA}_oB&tmy0Ux9LPnA{6683x3%SE5c2GVVbn#o021bM? zvZdJ>oaKI+!NbfY7Xi76!4l2(O4;UYW{@jDLV5zw)KVlZxs^Fbdo5VaOqNS0fOQsR zZ$z3x+)CWmGKMsKm@nk~aSzc(clIn2^`g-(`RQWB?PFE#UhLb83rD=Y>6~MZF^Rf4_ z_T&df@6?n`lAv5#H54XEUmLAB5PA84wI7%^O*s~(sy*716X^fSe?;2bhsj4jjmE~U zPJUbuxe#6IU;7)L^e(T~F#*qSjR=@h5!(fh+5(YKTUw4BlA72Izo|6$4Y2*CH6q(d zmR#*BziTIi@0tIdSO*N}C-VY;o?0KeYP}9muG5D3((!CMe;xJjcBx#aR@1uGO0J3s zipuoiTpv!b7{aELA-Y7nI4A`~Inqwjt{^U%?ROVl=(B&w5@UN>UyT~IE@_Qg_FIfq zr_W=}>9dHDU~;e@FFo`?u&vg9a5_Jw@m60iUU>B3QhC34Xb3;`*yH$vul}dPcs`Q& zm9CeKVqkpPV!ZOe{e@|1!f4>;O&oanRlM}*19Thmm=jiI5^JUbzY zUb2f|S!>dENLrR_E#^)%`drBNT*g%z?E-FJwehG&lDvzY+;t8Xl~<$i$aZBzx#S^v zDtYCxCoy4|o3J$2TaJr(;5L=FU?gJPk_86vl4H3@oBN#Jcq}!Iv?q80wA?~X;fzgr zOj>*|u_g7J7>vp7a%*lel23Blg>$r6x27hPQ}O3ch|94z+tr06=1G<~X`*X(HgAy> zF=~oOZZWw{J#NJzD>w$7M#Cc{8w>hWFrSXm77lL(;P++6+k9Z>>U1Y$(2oM8w`LH1 z=h6Ffp9b!qf4#9lE|p0SJ_J3?*+Rb5-v`sAKykCRr48%|25az zev&Dy&X8Dw?JYM?tz#_K)mWI(gr8I2yOQlJ+bx1@e+swH-L}*DOX{xmB8qF!Z&{Zu zsU1C86xZjwXg80H-0-w8v`VQmeX(6yg{tCdA4!{^f3s~b`x5sxKi+^!N$K>cu(I9S zRI)yD+**FJFy3HE3p;6B4j*BZS%O(?KE+w$cX>0bl)GeGw@rgRm>TKB;bX_JcI7HW zQT0AeHu1U9HS@Ayo9N<-6^NS&_Putf?f&w}J@?}B?)8{Fat3{;Craa=+OQs7)3ez8 z?)z<&Qj7`hIMvVEOY4iHb8)?KvcKBi94SuHg6B4GTdqG|n5w-;n)S75-9tDe&+@nR zY*xj15;^k8&#b|@eXcKBl-pY=fS&0Y^i56Xqq_#$w3dQrd+ER`iB@?fgS8|qzwS|8 z7CWbqxHLu+vpwCo+1G=K#e;b3?mfXa9~&9Q*vK#dplfy(2VQ;^X$tgDOd@X3ab$7^ zn_D~r&}cp5Lk%@fjUZ1f*H{|06gP&35F^D~d-q_fudhlsap=aPAspVj8~a~7gu&|* zd3UQBxlFugb{=VnRE2PVE7CC8v(B)x)k=4ss>q%nX-ZSz{CVJy{}_{F)9C%h&!e_` z_nqeIBS+f8nydGR(Fo;BINMryG@7;Ln5D>YHgBqfNXK?$oJ+xGE;TZV*EcbR{jVMj z+A5rHmftM8a$bBmgwv3$b@8sgxr*Dv=9`-5TGMMBZ#5{#(QWQp92x`jGp;kmf#Of+ zOD)dtD;A-Ai-ntx^$`H0t!*3F-?4e7+r_n@Tnfug-M@W(P7!=V9#>wS@nb`52$!D%;i}>uiL_kBFnFZJ|}VHYy?qy4%TgdIM~7(4-H*V@W$Hq+`IhXgkTT39ILP z+n$}ZC%HnjJ0){e5GS0L7Lw4L$ZA6_6XKuy7>!*GtC=oK%mwnletOZ)2 zc4*5MAdVv(KK$d~gS7j~LWQU`))OZT!89^Vf-NbnQmi<40kuX02M^ryp`0#eDM~Y2 zkEnZQ29H1cZ6MX4g+R3hiV}qSPrl}bN1{|EOC@Q5=~_U@d7%@n`ECQ&rX($S=})uu zJ8m>E@XTMKv3M9$k9-o1wHx!a@+4iKmJ2P^W*{G{c5%02X&J4pcxfAH3;~mdT{yC5 zNxnIZb-Z@fGSJkhArd8UYH5p68VZ+y-QJfH#+1Hx_Pu*n#`9I z`SwI^w&Y&B?><}}UY_SZdio6Z9y}yU;r^KBWl@{+CS`6Lev>qn#AlmHJRI8G<0pFi z<@&aqq>bjo+q#T$8M8nc&HVYx=sJ59@lQVu?A?2(+4+c)?$NF$sP#i+~zt0RW9$cJF`n4IH{}A1+k9p4mtJHz)D&zkSZBi^U0adNzl%)*)&lR@fJC zPXXh!7VEoPbyAbo#U(`;g~L-*hQyj2Gs$JC@1!puk))=wUCi%dVT<`w!;fwU*B7AQ zlE#+Y3X*GCN4>>Lr_u4ad`=FaWR$049U52&Z=`!J+4H#zGZb#VbWK`eUf@8 z$JYIypYs@S7aVB>tNSP)KE(bt-ke7V*`!K-@DVj~+aa9{8`d}WgzZ|hiSC&h%yf5q z7GtKXTjhD^z&=d&^C5a`KRAtT?;Hh^?4Y{@QGP}> zb4@mdJdld*4Z_vZ2VkuNsnPh}4qj|77i_0p5zcHJ&2KEPO0!*Ec=3^k008&A@&=ZT zT|wMzg0^x4*(w;4ZG6NI@j~*B-d?Keqx>2%FtKE)@DPV~XsW*-uRL@=9{$b?=$V{G zlyZyHKdJrg*yeW5LSxX)SUhHZJ+}yJfB3Y3u^mbh;ObS({@%Yw{rLM>@>{|4Op zbEEQJFMDDUR<4Gl<@gI(#4b+~e`LQInE!Sz%lYa^{9DN#jvIk|eikdsxE9xFZ7;E}#;dwbEpCE}<10@;*Ebz%()E!%aSXO_ znWu8{+X}WFH2!ySIB@`k+Cf?v7UxrVWYTD?!R_Gpy-M$oOkpueG1iaFQ`s&sHHGI_ zh-{y;`p{xyU)x#SZR7a;Hg5TFc=5%_($;+e?NB&vbqn+u-IVTwthXj>NUK1^xe|@L*!nkli=LwYW!f2 zUI=c%_q#i`29Y#Jbh%aP=_+Pl49eeC8P;*8ArV1R z4MjB&BDhBjwe_SR_%kpVr0G;ej3%7Z{9p@sadnI7jt;HqCWi0l(Wgwd% zrW3~iZc`}}Gv4`x9kh7Ur_u02d0MPZ*HdM2`GhepCsjNWU+hd^Cq^y*@eV$c`?NqIZnbeNYG@~ZKMGV; zLuxyXpSUnZju75{CE<>gLTLTpKrNRC34rBeS8)GJui$$RKRD+)woB_zoWk~Z-eGB- zMrfvbk*hx4SW8n8TpTU2M%U8ja?u!ywYZ>nYxd2a{Nn6Xt zl{h2&F0~44adOnyx2LT*A0Ha%((h1v>AFTv`^a{%WxR3b8@MoW0$YbahONT~RG;&u zae0*Ai(PBsdWNVxpK6-78a57L;&!xqHCKpjEA8@u2<6zaf6H$YU+7-w=1G>X?AJcz zEl;i>>rI>_i!`?gGfYOg@|jd81h&56SBPAKg6lJCW*p{?f2#!VKU zjRn3&m@Nu>A{Z}cwi<#t%tjxhU-!H*d3L^D?9A_mv~~h5V1TQu%MZarzvC!b|$ z>zMWMF73!T|IWIXI3QG<$&Y3W?Pro`7R}azbVAGWBrrLtEGP2mkDg5|8p0b7+@s#U zJn#Sj&aYm@Cz#F5;?d`x2U6s6RQFGkwpn{MTj)FU0%UK1{cZAn`0%cj+S1Ojr@M4Q zS|cpbJX5m?{MxUfd(|kSU;ZMneZKvvA59ARW^Y$nemx~MrqxbSYjT(u3DR5xQ?_`< zKHu~G!{}->aC+U^w)k9m{sQiL^Dxp>pW5oH4@pOU775McUg2yPYFj+W&!OVbjZ_-< zX6c9*IAJ{*l~T3>ME-6}`;M%x;@%(9MlPO}d}ti&_9u&7LnX;{k8S!Q>a|`^JNx+X zQ;}8br(*11t=v$VMWIC{+T7d2!d30)>h^YdJZ%G6d&gb4O=;}-W{d%qiwx&5E{SCW z!1ttZI%%J#qGYm+(VBOT!P}fu(23jfFrSbIM=qbtVyrxW0X?(R^R^(8C^dga?%IX3 zYpXAgu1XhItiWsc--idk`=VF=711Xjd7$u7QR>8M+e z>tNH!e&q`bwNWvz+2Z|uUm^HSI6}bd~7_o zJicr(UVE_m;RsczQLp2U)@F?d_QwG`xU?E`gjuI>ApUPbadzk|2_*Wbs^7oS7lT?;2{w?kF2GmW14DYMAWE91D|=*UegJ>|Hf zbt$#hx!JU`C&_Eew?5N`={TR`p!*Bxzf6 zej1PZagoHNA^wS1*Ed0=^Y@pb@p0y{<%1e+ZuYw$3+wWA8(0i3Q1)`Rla`N=V6eZH~;U4|^zO;b$nN$-|#S&AQ_$iCyY9RStdzO+8Rtfk~q z-4_tfP=3yj0-h@X*Lk_|=g&-Fz#M7;E0kH_^Ak=<`Dx=&1F9^p3znsL&}Jrb0iVI; zROCtV@<}e14xqu>yDkm>JQF|oaLfU78+gC4WJ0C$x>(nU5A6B- zvTO(6bSkCQ%lZ8Vb4X#hxpDc{Ot+3BUB2vjT&h*C)R(OAm*c2i85an@Of&)BfuxM(RmVbnLYB{xE8XO^i;?5^|SfV!;!;FCwY{on=gJBXo2RJr0&Vc zr)zw$gidDE;DV)KO-Mnj8F(>wgeV1~=KMGY%IMx#UPJ%HWL}%D*;z!5tTr@0X|h{e zT-xg7I_O2&sfnkx0aQGQ{3Yp=vt1A+%OQt>CB95hM-z24 z^7=Nq>v-{jhl8y>JT`_MN8ZViYt~D%MK0MXU@WajinKgb;FAuiUM}DEG`3oczgi1z zk1t<}x9;A9>7Je-j{wlD)$$u*X1cra!lPN8_8mNg{u`6|AqWvNw;GR>8mJac+-a&)VXVdG30I{EN5s7G@5ou|x8~;)cvZBRe?;9TSwL&b*(< z<7k_Y^al4-xBcS)R<80+)~;NMmCKix#^bVR_G!M6VVHd5BSc?$_FI^kyovPxd3vnKo&MHE$xH(%sp*J8}<*OVFuN1py=HIy$sQ|RqzeP9pb(xb$e7uh|` z9pfOvtszT;a*Gk6k;k!GSRTL?Aw?Yx#AxE^&h0q8Zf#rZ8Lls0gclxr7>|7CyZNFv zt+~_IZ6y+`NiQAaPOhJPCl+6m4}eYz&z>K?`!1YWJ6f6VB6@T0-PqCf4n|L%0Uc|I zyliO^Tg`4aW+#UC6w9t$#e*+=@3tJk<1SN7L9-pQ4R&(&#EV#GRw;I$KmwO)LBvGLYcW#-1)0P{_5ld za-D)N>nyTDlN~*N9#hfnd=9Y?IHuInpttQ{4JX~f-SfnnsO489kjcplJG0LO*~yP| zp+deCakhz`*=a{)>bhnfSDt85t$zSGauLb@{vzS&m zr{vl!L5+GHjd~r^y*)U1|2??xmDgI6VhRUd zzLqAVt_HnGTb>6-99qX9onB3o)DXN&5G^Os?TKPC&iC)xi(7r+6AWcv-FNU1dMBsA z&a4zP*)PwPNb_3gtHSi9HF5$A;QjSJ^PNWpk(T@I(p=?2=jl7+cYzkDGb*yvs^{Sc z($dvsZM9U4dLV5rWTE>4NVc(SH385!F^LCWcnJ|wyn6ouG`c!l)wbcpNvt`0Hs`~F z=fP_?5H~fi&DJ6z3*saIWOr(8>Okpq+qjz1Qsl{p^6;M|M(MKWJ|N0qT)v(9_!x%1 z^H=CS@&?BK?tg>EvgJtQIxLLjGPM&yYj18R|1(=RAFooob2+-FX&@+FuP&ybvRp?C zm*Uzt+;7?8!#!J;s(Ip?MmbNm4K4WqsqQvhuWcMP~?S-!)Pq}Tyqsi=*r#44vEnODx;+_5*8B>R;+bs(Qxyj+eO>@pM`Cd;7Z ze>65|O4%o?_&3>hNp3gCNL!~+&}GkT!vpe^ZcSDX6`cU7XrLR>Km7#u-Mbh46;Ilx zvdH$G?dif)UthKI3h3tG0N&oc6WiZ;7t1eRHcroCTE2J*wyzw;%kN(Smd~Qy6T^H& z(zhv|5c+Y^^z9?J|NDJWe$Bw)G7Ks{;FF%Z+>m?G$FIw4^|aDIrE{~EgFGo)N@@2F z4!QVQ-{M3TN4>SMSdLKZqoW(GQZYWc4W&IHrIM_(+`y5V+$Enb@Ad{Kxl#DW;vpQ} zu?x_w)=R)R915InPVWt@P5{u&m{#aWL^Ywqh7Z zcWlGWL3fc?5v5U-*Xgajd$8;95e$uAhqQXR*U&absd?!;Nq$)m7w_`>u%phWSu}E9 zz@2x1PM-$8^d+FL5BQZ|0e0*Fx~uzWe_UujaA@b$xtEAi+p$F#h)k4mXeHPAIRi&fL-F*rVfuEs0|uH7u;nf!~KH}mcuLqWW`HotFDS1z!XcPnr)IC?`{$ko0PGw6 z33S)`M0#6pnDcTR>mxT!^?ZusSq<-xQC5P_lT;qBz3?(Vid)1di=>3r3qagcw`Csg zSn-W@?$42lCsWv#qfLbDuVKHS+%!p>aV)y#9&Wjzc^s}gZT1`+S&p~w+Evhc8P(z% zYTfM}3f2i7{Ov!(@yq8C{lpH8EL)C8_TN*U2rOT!j*Z9ey${VK!K=4wI5>S1&7<$) z?rqx((~x~%+1H@>t7jWaIeSipP^I znc}$02p?PI(VQ-$2cS|uAjm5^?w|DKpnYC-%S|b5u2iDyf8p3xUeFO(yeiikZ zMsBBM_5~erpm}6TpfM@D{A-Jg7e!~X;H|xP;o|C*`DWp{(ri~3-rKen%~}oXj-Nud z&6p2R%q+W%)9g+1Vs-mo(mYP~4sI+O!r{B;cB@^8UO#Xz_8fc*gV%24d=TH+YMy59 zBaoJMn6&Km%Oh>c-)?`}0+rB}E5Kj<74W;i3;e5pg|44`8W`+^XA``O@j!dQw<%U6_w7g!H85PQO(b`^k7dKJ|0gLX!T9;&}Rd$R73i zEJC)Dj7zv(kBcmpZqpR0i0>nd)I)se_iQ}`MY=28H;S;b53d10Bbh~`ISu`OtCd+s zYGp`gKt0Te&buhIlTyl>VeWYmg%kk~PA#Mv8cXmjze(_HPkvz+k%YL`WU?l{1i2a> zM~Qa@Kp)5*6CR?4_d-3_loEmK&1(t4(z3gY2f75>hTTH1k{Pmn{aBw`i>{2 zo3$FoMuzdmefMC`p|=n>_;m7eqc@|s-aCqOfBF)}pZx)rKePk*m&J>=r~3LZ)!$!% zI|(?;T|M(NetkI?jkogW)-mHRfz_6EFY0tvj3GIO%F=`cy#3{xCG?DU!183XjVl*y z*TsTodZw?4CeE}>;dd;@be4uLu**hmM$&kTS}nq9^oi%%5u#6{rp*!Zq-}aGPvy=Q zp1Y>P)ul`E{+7)EfVi1p&!IOFCw$pfB&L&zYC!Ai1!j z7Jw(Yt){bawYJvJUErxt#g=*L_n`CB&oxgOuNveN7hPlL(EsZ5z{Oj*@-u%AGb`5t zv334RM?h@KwvGgA2}mBb-3`e0w4hm+tJ{ybN}V|F6Ro-RQ{Toqokr^uhR*!U)i~0@ zvXt&YYZy}H=(EA?~G7axRE=Lub4M5!$=JR}JW0ovi>&R0m?ep$vsl!3IGseyQcm%PK(a3B|3>~KOF<_@ zl8qNSl|uI1wpy^OhUnf=tQlR6?h2=qa+_uL?zz#`xUgzv_3}#S`r<`6wrvZVag5>f zW0h;t-`9s7kL*YPfB1)pd%F>pOukJH^y8gfJFxZ0d-=1-({e6Ov@uBA-hK-47OC$R z%W8j)mUOaysT0p?4p)b=^+IBO(pHA!&a5BB z_|nCNeQwLqW9XfnYT+zCD_frUm6c{M3MCxoj#9s7PZV!t712Qggf+*PEy1yETQD{< zT=-4^V7jLVmsX6ZXK(M>iS2K{i=La)>UmZ>zU76NL+Xvg{3kUhU9X)zzqoP*j&I$B zYl|0`@>oPymoCM-JGW!Y(PLP0c^rId54CSC=a;uL%Qofyr0o-T!%or3VHW>>I8^4J z`-su_IHq5G88^T3H7pyf0l)gI!0z2ZMPJJT5mm#iRY>DnH(zaiS>L1NNa9_Id?~J- zqO|x)N`AiUpou!jXGS&^`5?P)&0^WDD~OO5E<$7J%s1h=I5&iQxrP>J_%s(_7lCu0 zR$p37skNl9TsV2Sn8%-1TMl#%qpYzddvK7hhb$v8dHdVR-jWsK&sQJ643)l78^^@~ zZ2Q}OERn3mvoOD9EUSZb93Kw%=PTt6 zOxi%(rXdh|Q+_4m6C$1uW z?g+Xrr@)u0E!vh?WY-Ul;O$*IacxQ1{$93tF^=rP3BO0q_l;`@4%-u zWu2J^IcG~a`t4miadz#Rwij#@C2@>vOBUnMJ^Qfh%^#q5@>b3r9|}fi>JvVW#EKGb zm)Lm^ZX6qSb8v9ZH^o`H)z^#Z-X73)!Z_!aj%d)^3?=#c5`AyhYx(Bu`KB8~Lul5? zA4%hud6IuV`LE-aYpAk(7U&MpYp(%+@+ZLG`8&YpJ_jsY21E9&C+=^)ricHFk0F zuEqF-(=C?OZD#p{i5Idw^mopWty;+kx1*Z}^0Y2i({V$%P`69?na#tsg!~v)a-;Kb z!zg9geq=3T`!8|j`kZuXmk$@u_(z$)eM8Uu;clDBygwL!3ytP1HZ8v|5BK#ew+{Z_ zx(uKm9$cN!T=QxVe3zG8J$)Hj0W5*C?06JP|7+1IJCe;yr`E>1>^!tIQ$g(c_>Lg+-v(xrAA3KiT$tm^LAlj2T%@%HxGN#Mhv;^fV zuDGrB6;?44BwaPUvvUW|uUXaBHDP1J*~ELZR>Q{kj$`TNaVHK<&d{lEvQ61ZnIQE{ zJdx4N8iV(zcLJ`9p}~jalv|($`mm^)8%l#+7xEIZWyj+ZDwa&2ig-NYrOT4<2++J_ z))=2inB_NoaV+B?%}!tpjZ(SEW#qyobl;jmf(VWLt_8R566kV!pruc0B3x=_t^HiU zECC4eXL`SO2DlUIk*5<$MmNOldEltps#)J)N($H&G+2x103$RRBW5M zz?VKZFTW2%y~Cb-{pGboev7zsU0STELnUhR$-cR2_pm%|-=_9i)H1JPxg4pOI=!@= z=(p{O6eAM3kWHD9#K^P(59XoOG zowqB*=90-x8zI5?(#3OLjA`lW(xq6o=rTsmUur8||C(i3|I3fz?c>Kw8(^lp8|PN9 zb{1`ShUMmq{BO=L8(j&g`-cvf+Jb&p!N?(3au_SSi#tLjN2k<9k$57@4Qn}zmC0Wu zF{V5Ly4k|VjT~2=S+@o!H?7A+g~`yKThmApVcF%&SUPqUO=zh?8#3fZX2~B-IP;Ai z@*XR_ZB3sP4p@9V+22=b!FGtwuU>^(vxyDIPN4tBq<9~(;Fo<0X}&Pp^~dPG#klzT z;zhW+bZN&tN*Ws;MwF!3h!a?Rc^rJcPxe`BZNpAXTa%?s^3wVv=`C^nrPgq@)DHu; zt%BQsENOfk_{KL7fAz0XAKd`_>}P=e`|mVY^Fjjyz{ZWhi4(Uc|Ejh@aUNAq8nZpr z*JCYuup>)K7Cln6ttGKioZpU-*(+Zu!<_y6?f(S4(!} z@pQdi|A6J)KBe!G_|Ew;x7J$X7=Em3@rO)n^9zqSU*2JC9KxqXeMaV2uk~W>5_!_+ z+;MMp-$Bvus_EQvJH^KBVB#{FSp|QD^0>X0h{U#%+2?F?b6+T@z@#dN>0Y%P<2#3R5%FxG**bq$%26)HZth3}$+| zOKtZpkL<<7nK7LF@=L&~Rh9GSxIHL!2ggm5?!YgX5%Yb6SYYHLEbg{-H> zb`n!D#(Q_?cAQx|+VO&INn<0!Xm-`a1`LURnWwllL(7sWq@Gu6} z-Nfn-<UNUSnl{ZFq;yNou~>ASDu7GJC%C3d2+e55t2)VRKQJ{)W@pZ~d=URnZ0ILU`)UH;uL zsmWc;&FOVIYlTFhRhzn&VG3b3S&rKdVZVgL!_xk+I5PZ>C0|UkuWG#*vWV;x-N$UZ zRm)30FK^ut_U3Tc@}hWdd)Y7m80cPx!Jc6(?p;yZrXl}Fh`$sOyhmU7Djuo`Q)ob! z#V9J(mM}L^Tutzn#gU+wzq{SpUZ^HJwHDqo-xQJa8p(wz%XF6$$rG~4B%}S0`jl5d zE)bTNn5KEIEDWVeA%3*MM-x>5&@(-aHD}J2FWO!)h}y#&(bML2nbe*!5?oxhV$KV; zC7oWk78~C`fu38poH`cK=!z9M{qbFB)PPN&dZ6R-^+Z+nM1Qiu-j0zxzeaV~5$3vM zQxneVU6ny$zBD?29p7^2b5s?P1T$6*NmZf&lm67t~@+MMD~UaW0SvyQV9?-2tZ ztY3#)1y{MJQG^fHuWPXwq36~u3||<-(6xzHIm|N|ne57wZ;K?H2KW3Pbem5N^x@*@ z3N-6Ae6V3%kiRk-8yRjfaU9E9ivsw4CE#lrll;d^zHWFN_I2>GC1n)CnT76)5aJ zr0Ep8REtZsCu#9>%_(a;9cHzQ>r#fum)e2L@zqhg)2+i>=B3XY0qQreqyNy0=solT z#_s<#8oPJp@fk1{VHOR-!w!Sk^UT*)K7c0qaNAV3kag;4tq#*7+G^K2M8ad&Ar+aJ z{O;Kr@>`U}BhIzj*wV9oPQPn6jq7}{C~Wnjtp$0M>&xQ4Q7x{f>iM-xzR^>Sqj2fr zu+BO5TQt_{mJS`?)=BR9oW96qBm0K6vE=jxT_?zs&eW8@xr9F zi?mX-oc2j@TMs?Kn;1OV6brZc_NjBDt8skG=1M2*onE&#|9)ff5TZ22lFQf71fBbw zYjhR5e*NzO>pJ(f{IF4fKd^p%gcB#` z!)oiC{Ft|DS{>hybEOqyf4iehYayO0rm@Tx5XnpF!Qo z7j3)vjO#(T)304+I=AdBzI)!M#)v*F1e1pj5A$Nvg*CiIk5+OP^W!f|V_ph#+ebh1 zSu7#zMfP)F&Gc9Z-I8YK)$F_(*Io88IeRC|cH7vsfkLF~%;|k?;m51C4{+Gj>;x`P zp2eEQJ4{@gPgr7vd=#PZa6WUR(EF}hN;{ai?7c~wyq)sy6luIm&q95a#|Mo7{)YS; zA!A#TdwdQ+$JVfgWj#j{6G$m-tv|_STB(iWIL6e;F}(kc*D&yt)eZx*eR_Co3|EGi zl`h(DG#h9fy@d4oH1PAADwX9cuQGjX9Y%L-#OR6@ouzM;?)GIVo28Zyd1>a8Ts%wP zwYODrsyz>WkD-na)89Cr*3iCM`rnqeg}5ABHy1%`%T2bmeh(5yOAQ-)#t>sX`8%Dr z1=~bt)~&_*#wqmPyp>CZSZ%vyB3sYb+n99w>G#X;>UPle#fxxxcsWKtI3woeZU6Gw zy7bN0SE`MYn`f`!-9P>|@bu37+2*xtv3Rg-W4g7zWZ8aB{V1VbW)pFj8M1ux3q!qepL_UDfFb2&MB&yW(=}jD-9a<^QK9hMvQ;Bb{%t zv$lWsm*n5*&d2&Nq)%gqFpt)P9Olkr`@Yj}AFj4iGo+pD zGhbY5ZLqyd>8c&W7{A%UfCBvw2XsGi&B6sF=|r2SAlrp;B!r)j@bsn)!^cQ@O1~ z9g$r>eh@@m)CZX5pt7ADPJWrWo~28{=Yl2RMcinWL&BA>ij_bld!9hUZXZMIOln5~roL{p_EoPlBy0CgBMrUWyeQTzzbSs|RgB4Hi!KTr*<&ja{ z3Bfg=PxGRE^5xREH$Gw2sey&L&QI*Bt?3 zHZJt!i0cT5a=x?E(CTO+smD0GZY_>&-_q8})d2Fv+mizW*zo>I3|_l|v^9Mb0r^%C zdJpmhYoFQ0W+_je6R%T)y?Af?*0%Ty(b$S%AOhkv#gfb8An8p@3{%sNBv-9NKuUbQ zbKkE`eDB$sO@5Pb0iZ9?j}P6B-T>o39KW0fMqNgF0+HggZNw0RMmt{$id@Rdz0JI3 z2B2x}W}dU$a#vhisS%~dae-!};>)X@xsE!HOy_C{3-x(o+VbXF1G-&(mH>Z`Jo(!6 z8qn8nUdO<}7tnv?bhjh=qd3}A3&SK1?>ut+SM4S2Jh5(wazgs`Md|JB2i~0rQ z4cGnS#&Tgd^=TKQgmQ3y`T6oW1vC$SM~*L!-_k6~$K}EQJOrNG$HqkA_Y@ATlB?eq z4&@h)Uu09akL_Hijc!|si7ADYphbPowRhaIQWZ~j`yR~z03ZNKL_t)KCTZLAi4%MR z1tDMB-jdnTbR}sfvx!gX+>hmpmz2h5`!zyswt#oKVdnfeW)Gjki-!(k)4H{{ zWzn{kTN$~%&84|o6;dnFXX=Dot?6QDUp$DoR&!Wv?eYWDAKaRT-G$t*{jq#)tu>!J zCgNNhGj5g}oM{2~*vetNyK_6H`ufl=U0N}MB#N;mIfg}7uYs(p6wMq%W@DahvTVH8 z%s7?p?)PzM-V;nL8pMgs8*z4YP1}6?=*+rNEWUOPi>}`QkWICqRgYA)t+j2mMJL-l zMvC)mRuzuhPU+H$5%f(>Vd>?o;*Nog4{fRGekf)Chegt+`miZvdlu2e1aRzFiqX*@ zGCY6!G@1vGAbS2K#H&^T|KK0|SS{H8D3A{yg`W9Q3SlCe4n}MAlV6bUo1&#hY;Dog z%<9sXBFi_u1VbK?#z~;5SLG`-R34#iO~uP|amda+x0e zaXV^lE%CiiB3o@B>lfy!b2_AoWM{d^#==B*iAd;dJ530^PKXfz8_v`g%_iNtRkzCb_xbnAojsD0-J zbTt~lPyaM<&pmgVr3DI*4=-!dwwE1+oSrcUrPEI+B_F?r?S|0l4zazobtZvR0CsI0}_giW`T}DWgyEw~D%VBOE-Df_{rGLxR+M@7L zQGTxPz*;@N=QgbmKl*VdlMnBPp12s@^)^_n?OIsA`#Icvi#!;`z1H9NEQPSPd}h;z z<8Zt(tX-5(Jrt=LRX5iCR9<4WrY%p?Nt||Dgu9)Dz{LxQj@oS!klIT zoXbhYG?WAjnMsdabnE{)R-7CDK449`aGuo-!DWjVV_92QH_MhuaAnyt%$7`IcS1+E zZ^M!+SJ8cI#v{!9GkrpKifm~1v!v%oq6tdk&%?=Ilx$?2(qKHMA{ zz{H|K9NoUnQ!l2m;bDvo4`b-Y4b+l2`9aD5Uu)H`4^z_xpmKa(39c4Sngl;3@T9gyv19TFi+$JP3-)ofky77$uzgnmoK^4soQwxOZPY3}WSJ~_#P zb{|A71ICj44hQDKm(DtVv<0U7RWnU+apEL~2iBt&Yi!`>(*@9e=Zq^W%5`ZqOruFi!eCVh)^5JkdP*_?~TWE1imS2YOoLQZ`+J> zt5 zvbeMKV}Z*rTmb&+n`j;%Lv;URh(CT0uzvlW=IY0UI@ey>R%&nb_`;+I3+kJ+W(nP9 z@=1O5qV6O&QhXS-0RbzGCzwo=u>KQYY8$hzPy+}z?L1p zg4xa6*4^T8sJIg0Rkg)^Wm=0x^6YObKNb$RE1bM!Ev;Q5d2`WnQO#V-P2ywD&*tTh zqi}1ca9i8rVIMyBg}M0D*KR|-!`R*XxRYO5UUQ>%@~DQ1%c*_5=_|P$6PIIee~sqT zu5!Ico#Y_FDy))r50?NM%_c5hzKm5P z!?<+iDjLlO0ASI;Ach78(6@6nR{r{vn3$X_&40S52Z!&z3(GHDMwG}lD5q`fHz0cC zKD^W4hvB8wZmFXDtH>%z`*-Zbm21~ZH*R-Eq+4B?TZPB@!q*ZjXdWnBVri|F_Mv}aIB$AA;KBLwduKuyWws)G&p2g(zhtS=>3|)^u3fz0|o#tqPDiO(f z-yt=6^jSNMZ7}O|C4Hgq0HQey)+|z|=!0493?}EQZ8kv4x{#FM8oBeMJ`c4{D>0#L z7mY1l9PHD0{&+6l3Sq8dIaO2_YprNq?O&Sj=HcThgdbgvY5fcSPl{*Lm&s^}8_Iiv z{8eO6+nmBYa4UrIvJEY>K8niI{j#jB+UZY4XtAm%DZa0xlk2+hvK#q zKEFUaE79$=zHjc}=D`uEoKg{HkJ;B|bEMMJE*p8G7+qckkec8NR$Xx98~z!*;8QWO zzec@=>x&mvYN6Ri1J@>QRJxWq%Kx&KyX&pPm>3$wmF3Gy(_X$dj%KroMT3Lr?Jhr^ zTdRO_I(7aWJ~)3Kli&OSZoGFMYk%X@_{qmU-bN0V%KGAmX9)X5iFVyu(Ch*qt17~3 z#2OV6j<|fdeEQ>s#AoWnwW>!NRTPJLw8oB9sjdklfpoT*xQ-@f`nqv?<64~9w9&(5 zm~IRW;jO)UuNEFYSfPFi_rSQF=`HD>l%B4SpvOQp0XDd;0Dl_U>-Z7iRqD!m^l%KTiAEx|bQ zw3Y|WujD)Qoyv$YaO^OaeEZKavuYzQJ^gnvJG{C;60$QS4A690wheT&?xi2tuIbd-lX>Z|y5s^{Jrxh_^K>17EaJS?5% zTBBKaxRqFL`S!bQHD5d0a9KMZN79m_SbBSti-%>Ow^jnSs^Trv=a{j&9$E^Q${Q2`@y)H*Z4JOtAHx_geBt zU-2z14gKa*_~cDHy?yH9IBMNpz(6;eNrJwfYB$_P=98aW-=g35!t&qshf0jgUW|5Y zwm@^G=JlJ1|KC3aj!mHZ^G^eh?Y+}1-Bya@?CR#JsrJ%oo26X}d3xF_OX3NMhoxPW zJ=JJIZ|X!oDtX)zCMF~-HDUIQx0%S3wP}+xk6(Egm6Wqm*Vz#+u@=Y7ysTDZQoUq+ zpLOf=MB8URtY>+WX*mvScV9jDw@W^)8p4*cbk^X~-w~FT?2WMG!?tc-GR)UzC=B>T=6Ek%8xykE&OLo$&pzKo>&u$p>)@Y=z5-p2Kb2>`(4UmwDz zp<&>&^OCh8wq=PjTdDe3o(oyjET7wN{KVgjt<76jZo5?V-L{8rK01_+Pa^u-Gw7S` zNA2;)fn5tXS5={Qu(r>#sgkFbXrc1Td$!+Jw)T@gtcJ0iwAm;=9|;zT9Gc)c3wZ{1 zDiC-CM(;)bV~GJ}JvgpUGsw7BgZpucs{>sP&2{keq0{*IaKCHvVO@V7GCr5b??<bNGu_KjI3wu47WL{b{OK9yI z#B>=#mUHGLwNQml6ic98OR+fjg2ky1K*>d&>|jlBV`vdxzpvVEu&dXv72^x2nR!qrn3@YKg2#g=WGE2YVDk5F$k&^^Wr z>(*@E;Mzg&Es&Mh z?MbL2VD7WpBzz|Oip~a;8|C8sc_zV{c^-5#3T=Foy3-H#tVYvIxyj*CIr%Nh%-Dp)#w`Tye4GsT0WV8`&WjLACVZ^8BM>Zsc=&6_K^= z*iN^7ov^X)donySd0JV(j!uq2cOg)0TF_0U%Mnl3Dc8%6t0Kv)>DrAO`07{x2FXAA zPw4*NzR=c7Nb+sj<@EgPui@ms{VI}gy@&K4CcvW)R4=GqiX%ilb<}HhlvOA~iaHvV zCYpooUYG1#kq-AhA#3%FZn8=>9-k`oMdvOA~U^CQ) zj4^$6m9|d}3F0V0TAM$KGd41e*ALu_2cLftjL@tPA$3~BZBx>R{3}JI-cj|@-5F`? zLgGwonNT}Njx6x$=rVfoxBee2-M10Zr+47W_&6Sa@B!3n#p5z$iTe5|S;<5(njg}* zU!XbB>@3Fq=xbQ|{P)oPo4*b`^5eZ=8vq6efkz*W@QrWWo{?VFvtzMpyYb4)A)86h zHl!l0LYNC7xq#TM;e3rYk2c&tIm_wfd$+igtz|CVf4ZfMhl_ANmF4#_gyI+DG3&_*FI{u( zevN$HGAxFWets7pl%K>+J=Dix*+{j1j!?VUcd0oliW6?<_WEQoRYRv`Y32tTcVEZ+uw_$&KvY*+Vx%&%xaEdz zr4W7dKl^Pw^l$z?R)74i%4u|&ol$r;v_1OtLyzR&53XB}sp;u9c*wZ7J~N*t$a)U( zENz}v{50E~(WuwkuS5ye8x0_}Z=S7XpB^vo0oBmP{Ca^GsF2bWn3=)M|MxQLjdkez zi9Nuk;XBRM9ie(1XxL?6^Gt5o0+@ed_CcJZ&5n{*fw=2XyvC z8vjWiB1Icd!4YVnFalgz3g&?nOC7V209-l=tF&j5rbv5d? zaaJ|nTupc>SE-1r`)MrNNrNCBx2}5R zd?Tl>+DS#f=`=AQ!jav(aCYq)C%;Z8sYQsQ1aX?ZaUPZaKX$?~&)O`|b&*mh0)Qw2 z;`s-1X@qQXN0Lq6MyP|Jea17%Ds7;-b+k^M+e1`_>v~8AsIUGZl!!}a_I!l|D zbcgh-w#59v)RlZ;up>d42D9!nKOoVTp5!SB1rsW6E28g$EY zEJrl)r1J>bo5jG}brk3{_C45sIXQa`FP;1{p4#?bB93Z#`jAv`fqFY&JVgFDmWOf# z9m-w5=dw7(VRl57=N(FWyNUX)_*%bz1X zaTSe!nc~wAKT@8~!()|033TtQqK$4Z{%sG9d_-t^8u;Dc#fon~hv;AYb724eJI&EY zma2Jx7@vl0M2T6XwG_@@`bXtvI@SQ0l~n`JNRVHYkZ&eO`D`%caitHFOH9!W$`2o& zD7Pc%L~ff`7{ggCtmC=YIu~JS%eTcPJ`Ae))bXYE8dgkF@7Kj8CmUfx`T_ zHq2{Lof5%+abM(|?fa6P*%Z3(y1rQ-kD)w$aed@_|3#S8=R1*Ui{lmbud;fEk!CS< zjv_nJ=AB?;R}Q-2RS>=3#;?Xh71I5(vplWbm;N9-vZDN#do&ou(pbekI)WvTyrs42 zN$ZXsi-c^m4Tj`2;c5NG|=b3Fny{U#JSH|(ci!b53kCo%&cIlxPUPRxG zsn!Yt>L32m;_J03+|hzOuAC+DNoJW7(*iEO4Ky_ceCbP=?%s^r&p!!_F2Bmzv02 zYGQ2V2oBv-ypf?3y0l^iUj5hs9QfWVh+49U&erx#zi5c6osv|`+wF#Ooi_BG`fnzK znK(X6bbW^7?c%enHOkGh1^Ot_`t?Aq7U9sL&L$f=nWU(aUr2V9^WkbbcD}km!#(NC z)0SrejSp1XboL5KU%tNlH~z;zL9=%`#-8{oOs(GmxmezwE?Lx`Ma~16TDF09Ciua% zFHIOoOMC$J%&oobzt#cnZ)d3ov=w0WLwKCnXQ47fY(C>P_PpPsN1^ZmAk3#cT6%Dm(rW?{2?aeb?E!;e}ib#I$$18q+Fo6Qx)tjbwOEto_8SIM=x~MF$vp}&k@ka8qgKa z6cZr7B$dK>yLz*VOmVFT-(u?Qxr;6IZy&~?XLgfvkp_12b}gB(%nV_aVq8RR$d;?+ zr<`>A&}6wUT(-Rp_xl}EPkLD&i~lUf_4kBwtZbkAa?<)k`w(>Q?P`b4aj1{qYH@sd z`z`6BG&bK(s53oUgcaMz#vxo>o|g=-R_`MJ4hS?!WVNprQ=Wxm{3G+vhc zg=-`+CiTTcy#d`1lRz1gBi280{#4_9PU&(=Hx%o|+lffo1R)eYweWqe3}q~F5!DC!q!Yl{W(>GsT4ebW?C^Y*MT zef7Wr?0x=TE3LwJBkGW03ZNKL_t*HZzg^d#r;i7=(*Ve3*@0omyrI! zAK})as~Gt2A4a@->1{b2??-{6sB^bM75rOLI(#FcYQ7v# zPR#7PT)3TzZ+wQWy}*ZamFmKFs&-h56hJ7T#$HQ^wb4{Fxy zK%_@;EOyZm$MPy-mONVJ)0>D|CkILh7?Z?`A~bKqL>=Wz?Nmn-v-ud*eUN44{J_T_ z{QlSQ=8JD2`lWjS0DZl^`0V3P&O^?ADl)W+Q_W}3S)c_9Qyky^`S|&E|M*5o8CbUI zSQBteX=4H8SdDXO>2i=g}x*$d})fFN{peOyCa0-S-l&kDsVpJIPjP4>$iGz(Eqi#+taVh zIBSsAG_$o_cl^wi<|8gh%X#^0~^sf~U&o8zd>-k4cm>fvegdC-_!0E=RG%m;;w0Pf zSToP`*!AH=N$q1~pT^TzHv7#zD^hVF!WkD^JWTatOsW5DS$-|gqr>)2tD)VLk*cYl zV9tm}OR-~Bx0g>2w1bAm#;@YVLx<2^uj5k>JzP3bE8E^`-{LZ>jfr*;*}c1V z$LyA+c>DPKIC|<7){KnczTKT&O&#Vaq-om2kNv&90D6J)!~Q*G`C3r&R`rdSS?`^B z0Xp}MeMIT}dEl#mgEU%?-k*CA@tS2oePO|N6`F6)O{e*}=_D@VF=cHln_kWikhffV zJ2T=rhy?O}Jl?d-rAB$)+IP$)mlJbK_*ZMaA}kU5ty@6KuGAAQ%Y=HS^Y@=XR*Z#o zUcNYPJtHSh^*-a`U0H^tvUbvO0J%Y1^IODW2qzcg3XK|UUKZ2peqBs*ZqDV^|J;`E z4-3T$`3b^!w@RO?-Xq#YjO~@tJ|1iz8~f&=WITU9et(?X>P3FL>iCMkk*Cm>SuHPL zES9&fH^O2Odd6kSc`k`l^kP`K858+;!ZCEmpvE^6^RUe3zj|X9J-2R^)_LXf<#_bo z`|$b?4p(X;*(T&SWv|lw(5iFivE|)kkmoxCXq`@6Ud}*Yf14#TMvsuHMYcX4h0l8S zbER$f_Uvcf-y-vtIgTF}bGWZ}urEMk=0x;8y+K&U(fyhEV_p;0FOkQT-e^|`v5v`7 zQ~GRfl}AS+MhnHY_hIPM*~3yGRs79A9o@Md32In=VGJqU1>DvnVR@5pnk583<2Rdm z7Iq*00p8xd6PK6I?}@{!&z{59qsNTY@_F~H4@91@omtLJ#K<-t0=-kyxbNlHaPYqU z^EyYq{hfEwcXKM2A#`sy-``E+JtHf%T_26xmx{DX$PTGuOU$h=c518qh|%fOz?Z*_ z=(ShT{g3}U)Yh$Bz}9mh*SfjA`CDAgzqS3w#JD>WpA^RV>$NU&J2U4@nnTM{wrjFb zsr@M(X(Z0qN(s)@N)PwuXTOIxgiq4Ich0LE?}U7bE-o+DOCbs&OP#O3Yzp`LX;Q^| z5rXycQj80&mpj}}{`{(k`7yArjZE*GXW%gRTUmbL9_lZnoQn00zb&d@?D^oWbkTOX z$g_rjc`RFk4?I_mr@LfXn(|>V7b*hlo#bXu4zog8sthZ{BM~mI(1~&vslMh}0wrEP zM52hUwW>l@>fYVeh5nsu5Pk6;U`3lVL2XbJMR<7sJ^0pdox_cx2D~M` zocRr@##Ds!(+IX~T_=9(npQk^sIIbB)uf_!E@bHlYBh0W_byx-87a-F9kObg91~Oz z4XHzY$I1h!-@bCH(3NY~aPaLTcHD$l(Vf8R>?ASo zwRon3g^4)G?v=X#;@Y!^U25hwJR9? z^KDyK^%^d%2xI%9XXADf z_gZ;JACHJ4O%>&mGi;xR->SAVi}+ihHt6tS;LrXH7+j3#b5A2)Hw;v`0b+sLBfn>^ zNDh_d=kst@_iamlG-i|DQ^vrlh#}<>dA%416ZX}jm5GolchFxty}rb z#RmSge);43Zuuz+*S~GuB+u1;hcU3Pl#m=P($t*RZCii)h48-rxy98*+{$++@v?s$ z73Wrzz8#&>u70Un|8P8_FvcyzyhZUsR7HwZiBqNb>-golR<$kN5$P}6-=jl3h0|9j zpQR-83#ST=HknR``r1lMJwNUZEq9b*dQmrjPe3={lEk(fo2@1(qu%Zwj4WANAtsZ= zZ^Z4gu`Aec{3K3p+R#>BmR6rVhfT+hW8lV3%%YyxG+X#t!>0F-BdNu>JUl;(QrCWP z8Y|9Ube1X0lbh|^h5GH2=kilqD1KYM_)Yo8rJpOGx7lKBsqMpkP4-PX3EuVZP+VVm zjA5*I)Q7=2ex_6Gd!T%>vgCq(IX_68NDT*(pB!xo2;VgwU-o>_@TD;fOxy%{EV!P; z8-1gC(J#HAm@E`Nb^iZn?@ga9xvu=MU*>zYS9Nz)@B7{jpc^|tECdL0IOLGS;f%x? zQK7L%a*P~ughOHLlQe&T9g=0)AN;}LnXna#ut$opO*y2Q;mnX6fdmMEAV93m-uLe6 zy=&>(t6paML%y45x%Xz?d{u=8h(3ryzs$V%+;g{c&+pugZtUV^JUBUpu7$-F&qwdv z9Qvnckf6a@1Js=W(z`-3^Olq^;7;2|qBW8P!?(w9^uuE~`N%_9=w0671dSxY!^ciw z{mnZ-D?j`pVGI3D8S^&D%iM*bQG|1OJYCuC%g3v$$~#Kq#93qL3!MJX2d9x(d({8-&S$3>lNoJ>%%J z&ZXXPkD6{CZm+e^E3GYSzrNCAQD+#)Er(m5`uS+TiJyG=cBNtKWxL$`7|`bD$B-d7 zkj6&cT1gsLc$u2Zvb5#lT4z1E@SV&d}l<%`!D?vBb9ZHH7=Na%W?yBq}P{KC4N zPhFH(?n+K&)EROO@F7*o8>QW#GxnY9TkG4(#8#6B~DJ#k0TlC7d{aE{LxI`0^^|YPmLzjNql;{Th~9OV~Iv5}XHV z09U6oG%$d%dy}|3K902qs;`f&lAw%C&Bw^tWlGiImm@>Cy5d8phF}t8%aV3MB&r41 zb0nNQToS!&&8;3O7D+*^-v&VZ^wcuqy$mAXR1VWagIMgTe|laSX}B9IEzhg#yG|pN z&R@NP^H;B8)5r)m&3EC}zxr$7{|Q^PT}D(}e#4}W&N4K(V*>_vZ0JZPs%h!U0c1-H zid>hf@5kfW0_c|Z^7{!sO(rR^cNZu0TrKv(x32_d)zM!(&_*_}Sgn1>^`tr@B0 zqzAbMDIUbL25#I|p>)b+;o#PF>Xi;-(#fnm@%(dnA}egDb3aq^Sn+OONAjcp8(G}I z-LL!(7Du)qjhjMth`P1WN*HLe^UBLa{MmeyXw*{lb%G-oTM!z({+Pi?Obq; zJ9^A@r=ZjKlN-s|byHR+JgmDdl{^muztG57jt5*@+S-v%ubD|a`=lllKZQOoiK7+56fvSS#o-etapv$LY}>dA05I6^ zU$nV#coJ7(SU!-VY^YvSp@9)E{O`9s?hSJvS*Rk>To#JF4J;CmywSz-={K-f0 z%b`9zbL0rRyUMYT#8C1}PPX3E&oqLDp&{<|AWpsw&r-A4Xwl}w@gS`BBk`||hjqJy zCkz~NXspCb$0Y#PA}-~AdIz1@M=h5LC|*=^Em;qq`0 zkG10y=%1MZP`)91>jwHhvUY8y{D58dvi0!XWZ-Q-ZTC~^3wht&a_uJO`ucFEWPy1n zwBgomY`S){Eu&ttV{dMx)=6zmKG!3k#;8MOxchTSAASh@*`EQe7Vy6v-U_qn#_zh zWQ#>g8k&~#>FW^u>54BG9{DjcFEg2@otAIIvnw52CO>v}S?B(^Zo9?Cb#A`Z>FKi8 za`?+$`!6(=fA`~C9+$V7G7h|#$h6)3W$4bvi1Ie9Q}W02VdGHyD%2knDo@?-e$I7b zyY20=XVXR>^8ooP@{%tcWwrG3p_#_7IO(Sie%WO&-;FtlBwM=*h z?6+3kM8>^Ah5yG& z-GomIk4k=Un_0MRYaJ?uJS4Yw=+xy5`_G=kx&8Yw-`5*dPa!mXcMSbAvuL$9AaL&) z$;6kv^HSj}PoknNnfpr3_mt%Y0Je_az}m@s7+*iUBL1vRH*aCXtvkiyXY)t+n74a? zx7JL^3RZ^=m^)OXEXAg4H_>V~abf>n%nsDwlszyrgB_QzB1$uCxq2O078MK3<%#_+ zpN!q3a_M=imi-!n7d>}EonYtBE#4j<2Y&E_e8KjMF9NT;a=#_|)KH@VJoHe6vu86b z*50>aBb$|u@50^X;ma3pn{k5wtJBKV`aUVCc}IR(jb^k@*p1}1Pt{)zerveQYA(Z# zWoeXSPMwY)^VGrL^>B}kKP6%;FJmZ9nmR%V&3JS6tUOU3zY= z%Nsj<^;wP#t1)(+GOP}pe|O9ThBTzm7}Y?zj8Ao#P*;~<79X(wq|669ec2&-2OveB zzmee$+3$Vb-tJlw5ODxQ+$D_X?@|G`iLT$ijkSYA*syM0aiZ7!!UFD`zJmFG`*Xat zZ9Bej^ieb_u9Bg$s5cbv*t|J7?13|9F)%$V@)$C8bn)6KKKkBIFn4Vn_%9_DP0t@L4SW8;KI}Vv9(_}D*0+_= zXWCg&MMDDv*tT&ah6V=_#Y@1U&K5*V8Tc=4R7=^+x#p`01~c&M!CdZ4eu}PJKbBL7 z$>Z+359k4XRwxwwmW3<-R(-OVD-5@$=(}{_X~3NSKWdNdCS0x!a+jXjL`R&{_IV9_ z^nrLIr6~iW(pjpBeWUC&R>*M0E*qvGP{+{jTtEV1ZGK9M7UADg+#!njC`s68-ppFeq zu_&J$!Mbg9j#1<@O*Hd3@_Zh`0$LwOh%;c@=qt(LRa~E)F&u*j*_X66%{(d}q z;2@ff296#$h$!F`nN*Y{Z^3#DBdVvj$}EO*J{lMM!pPB5kI)hmYCLSWOWp?Q9YF2U z@9&cSpbQc8;s}kU45r}HyS6Qun?n4{wcWNsCZw&0EeCgQz@z`|ZwH6ho-J;%k(A}W zC0Q1vLAZv9*!$HW?I9uD=Sr9A$i(BPf(_ptZ%2!8XXEm*xuJFAlNh->F0OvhJQK~j zKg+g8`LN3&tlx&%5!F0D=k(!+!1uooEG+@Q^E<%fkKb>J?khDKz}~&U*|WIsi?%st zwMR4UAM?j8`z{eLdBtr{Xdc2~;*^Do)E}jR_A(~YZM1ZUOXu?Qxzg9qdgLu1ha^`U z2lIFoU#IW3q%(k#)sp93Um$32DMsek+uP%imv`$9dGQCxe4eg#<-s}9fz7KP| zJ!*D1H-(glTT9V9pMS`wy>;)kv4M?beK>`9@CDg1XwkNLj*D+;A(5VQ<{rur+&?)p zjWZvfK=aRkiC>;QgTs6Gp{rTF>6u2bxJa#cW*&RaT}0Z|K&#Qj)m=M~RLoNY!1k-7 zXfCy|ZS)!jC#KLs18H%hZv&CovJ_+F?ii-ltii85xJk=Npdu!)UN}XFc)avtv z+JL!TJ8jPn?8{gQiCTs|i%?+6(Z z#GupA={DuZH#K<~K25!(EoSw$+3zx9t(p6-L*y8d?_3N0) zPUV}bdZ3of+lTf@h4k~!4o3b=;CZuP`v*S&cJ2iJ{@=gf5`C&Dj)8sqfQuK=!J_SI zjJq1-PLul_-G{OQ60<~wj&zNg9Q7MMoJ; zU4uR7>F%yo=*F<$esvU!-QAcT8VrwIL0hifK==G2l493owGsz_W}|^-Z#NqK-9Zil zpk7BcF){~$TX~bjKNP#Z+rSx)wx;0(toFs@Hy98$HBJ-MH+dhIu_PEQr;WoS z*f^Y@Za+OVi=+R=*DK?2c}Gs2UYvKkA2jLIs0j(Ad4gx!N09UWpkGs+awh!d$Z$7ZD!)rj{2Fujrkeke@*(v_KJ(&<_&lAhLLt(%XeBPAMkYnVXd#U9YRjpa!~HFZMFV$rw=q{ z?qTf*Kf${9-@xMfJ(z#t8<;upIEyFKH+C}TW9;BEasy#knb{EBc2MYl-QnEdIE9SZ zl23W7(fvp+{@|f_7@JEy>(l3C33WDf8oqAWy0)6H6qe)u@$snYvA!PYbMN@WxcJ+a zOE~$QKIIxfQ?>U%f0Z(mmCq3rS&bT>#0nGhvw6tUbm17fwlu^UsHv;j#Ir{q#h?Dg zpJC_bE$HhhpLo-KHARf!JL8D53|SoE&W6qxW^TH53;WNU!{Fppdt!?8S#zm{gQrg8 z>aHE$McV+-*V~Jy9)6@Ut?tD|Y`J~|(zfQcL%HR+O6yp#aGdlA&3z_7{ZqswXW6FY zw3+n1m^59;h5yU_GI@BKGPMzqJC{(LV@F%nb`U_w+jyDM!iLG~Ic}F&24lnMlp~Q- zo|=>^99MQqJeQ=2C{5E}%X!Fn_8D!fzj>CI6^+@{I_McpPU@Et%%pRMkvn6#eu$zK zIq7eBd>ljfro^Pav76l(UCJ%(>Aw>6@yEbl`~|SE0DSw~ zz|&9PZ;3t^VlmS-9TX z7Op%+TUviQUb&^L?GD@i@WqqQoR{l+c@0rmf8PD}kGuW&bYm5A@aNm-GjPl7#=U;s zZQ}>oLiukOa*-Z>O+3CkeLF_@<;>;0!p0GQIr{4HlOLa!&)?6%-Fw~N?00rA^p%db zMzxLX3UABgN~5fF>^@5VoN6qudH8%e?$%$0A*9yRct=~sxdlikYsca}x0-3$r^M54 zjTuA(-AJF@itBgo;K1(P=qkHZyiI0_ETwFGurcDL1P}l61d>Jrt*$1KlwwW4Q&ZIYXr z8*0(E3~6I&+GcGqwdqeW<7@u%16?weOB$tY{AqG#78Q@&9Yf#T9PX`MgV~ZB-F(zY z5^TJ68yO-TJb4Dav-4O&6Dephv0OAvvVpy`{WRui8!At;sW=9ZplRu&zL{C9o0!1F zy3RH?jNBc=fiq{ZW_(h#4BbCvnNmHbg>S5Cc3!&DK3O|r3(LtPnOd^T_M^42w72ZhjehyoAeG_j)%AJ&s?y?{?;!gB z{v*0Jtq14)Yc z3Z)=Ztj;Gr)4HiTxWuIE#?EDye-%%PVIxDA=UZDOWpcV@aZzf9gvN@p(sGBfv9>RL9oOdp@TXr*VLsyOdMJNiH(mQ%)Au1Hu}-ME+tmZ!=37V+ zx%rlVuS4#J>2nN(^Q37e`&tF5{I#n~ns6>)tzjfL32iV$YK&jY!?|`XELsaB5AWIQ z&fNNb^nB;>po!c(P0DGC7~8Lm;?BkmE4pZ#8^#8lN#op2J2r0te*0z2%+2D^?md;^ z%UYVL)11gy{-n)f*>>!qRJJSK#-x)=Ls7SbhT>``j^;;X4+45P)&`0WYkE*awDzcg zW=3M;UkIE!w75OzlJ(P;Lz>Pp9MNNM^MYU!GUSq2>nZ59k5q zv}O&kb7zFBS37H6om-Ff%<(S>ekWOS0@7q@%2u`RenwpNuc zwz51^45>Gz9xb=3-Jnc6S`8oVkkw&a&u*ummcy120HU!mtoiUKSoiUdk@ogu;)!Q4 zb@*AqL-M5GwqsPfC3GAqtLE)X$8Uk_@H(uUkK{$q{(G5?y=YAQ+M3( zPlJR3SASVm^9wI14r)BMl;dOV%aVR;B z){$n%Cwc8Za}Gn3Qv$>2+^!V$&&=YX6DNxaEA54Fc{B7l;?kTE-*j1$4 z9v|iGex}=?u^P<3y3Ns|2Y1{|q$l%1WvTJCk=yS1nWzK8R{Xl>tSyo82l4BLxy58` zFr5b36pdC3BX`FzwmuB+)*-p=g6CR#Ik;>_dReNvO_~K5d07oi&!B&1wxcVNeKa^d zjsBTgmWOi9Wm>zL1g8b%@(St*F^2Ds;ZU03MC0LQo%FY6@*eh|Ifs#3ciUHIbFHbb zoR%IPAHK~=*O5)yrqg3V-9GHM^H!EV)wuigY2bU`1JV@u?cWBTdFFmg^qHqJe7X`m z{WcaSu9rFL_4DVkI6g4%a&+rL6p@G%F`jgfVOqrGmIXk-Fbf_VHgiJmgEebG%k9n;RFKXCK0GrQyT9b#Po{J%wOpAKnT@Bg@g@RuUHVcl5U_M-VUfs~EDbAOBWyl5O@%dJU< zt47Nvto_dDZi#8R6-PZ?<72Y6jkT$*L3B9#Bklj1AW~lN6{56yJ@W`>_7?_#? zoq8|-w2y!^SzO4P6}3Zkk)PL&qNY;T27m+^B5WSLfz6{giZIe=!^w$FPAsS=Vt;&C(w$1aP}5+y%UCpzN2y7uJ?%xo!yC)mM*ngU*U4Us+3Fk;frr z%%|JrzFPt;e5Yxq!jjo7uYTs8B@&YK&CcP_$y1dJB>Q`Nv1P+XOwZ2LDjx#8IapaU zaSxO0)^@amRMW;=x6y31ik#N%);l(Dt`1a?59s7zNDmbu{J49^{k?NXn{1O33b^_; zH}yGmkbe>^yS{1YAmJat`<&ZQv4Igl?UuJ@+L=aDa3E}?h>)?Xf6E4_^5;-GdLVqU zbDoZd`#isX&}Q;WdDXy_c=yaNVt8yE<0Hcz=Bhdm(p}26kCZ=U^^{Ma(Oi=hhW;pFD=av+rYW>ptB6^54P2#vLW;N-7_xc@5iqT)f>t+1BAQ-_=ftFeioY zeL2WAju|%>SG#b@#V#U>w)dnp(=b_jaOw4^Vh07jJB?-+*M_= zx>9!CSrbZiyc80Dl*vpz*Zj#zWWvI(32A-4jeR0Ay(dYl9b1OdEW^aTNu-y@foJP` zt20FH8>2D|P29tyAAW@QpLq(?gY`B!4^B@bO7fG15|(o?e1I&&;M6oG*R4ewce1H9 zr)H~#{+ZeKWEEXj%qPy|h+ggll&zplM}&KSq(8~Vrh1yog)}7^$iUmHeao5al52ed zu4~f($){5{a@nYgh{DNp@A8G(ruCEMLMORZO}^PViQ1U0Z)P5kzyASV{q9g2;?PhU;p1pO1 zd+Z2j(&6uA3mAiTrxd0h%8{Si=ly;89aRa1lHXhM}lTC zDXz~~v?s@P3yg%ky!Xf+C0jYz_tnLtD~Gc?k+azZ2I{TnsZTRAz?Cb&pZp2X-w*um z?*dOgxyp%t_GoA*pF~cQ>aZ(EZY<-&#D1(yd}J8HyzY62h{cj|rENnaTEs%9f@j2f zxs7Yx^5t*bH(7U6h5hy^(G{Win}e?~m(7 zBtG2hs?Rbj&9<$pv8yd(hcT}Nj=;`cZCnb#`=4t z;_*1z&eptK@%%L^WgyRAb@(dMc_pc(-j-oqI6`6uZY67L&R(!hR-S#@af&7qL~(}2 zo-Rk3=F&8hR#1CwHX7*bt!H;jOv!axz8Evl3ozf?i#W=P1)^7X?!eWZI~*K=C*OM? z8*bh~oFw4hj|{1}t;*bb6CuC(X8+l9_~?npf@P1>6h}Wi2Bbi%(FBA&l3De`XY``> zd>OyP+mr*h1hj>ad$p_U!o=p!9J6c0CCU9=V`qur?9KJ|Qd|=*h1=Id>mkfSZ!VGf z*Ua@1igou(*<14R$Ty@nn1p$M&&!pLbuni<8;!ty8N7B#0`k2y+DnI%wiL~!7Me>f zw7SA>0&gSjEX!e#Pc=RLbc8qG%rG`qKW-InkYU4He;Hr>ErY$Lix4!_I||1` za9nMpcCzMBeBr({K9<_H4%wV?L$=>iw)5-y?JG?kKFmtCxwxpju6^i`mx%Ug@X&Vs zm1AB%trYgED(?{g$8zMc)6+QIABH4x`F|*MD4&(1dUaYArk>A7rmv~gdRtxRw@t1} z=4Pr6=TiqRezIBnfVi7aIZEz8 zLuljh2%dZNG5pQjZv~f44x$n)q6icCVdJ z{L&=47|M4-9i1>{w>dbU4L>Pm1a2hx^aX#*Q#0k6Kj-If8_7&*$HhB0QD3loT8Oiw z6B?SDLUXBA)C|>-ZHl^Uj<-MhF12W0tLw%maQNgY{OrY*2O9*2^<=cvNG5D#eX~z8 zSTiw&M?OA|kDoXSAi}-1YidnOYwDR_z>dpTvG>e*w9v)ek1=x!*!@oe=qe-1U4Jg^ zFXP#Oyey3Ut&Bcd5S%2yy?gm-&kyKVo9Y1Oaz1h*nH!nhmY3%>R?oa|mxE!q^Ue)cT%g0JzwB|h_-Ve4AyZmYtFjjQpq&rD088CnUK=>dGIT920RWzP`(1R+Ef$kU z#=hl_%tn^txi{a&&tLokCf2R%XyJAvNwDSm4IKUOV=SRdEb!#hU0}aCR^hdmIl{X! zvdFb~(q0miiV0cWXIk_s+z$Sjmnr@#wKc>8B6D)7> zd5GNhh(YI0rNsoIv5m;`BJ69H>X~Uyj@is&hVI2hEOq(YX9zWt1eJ#r@NhnXxhj-pz|s=%+H1fc z{Solui@+cLA#n8Q>ZJD>r{|xK@cQc+CMQ>ie_cGxQLZnZ59i7_MsLf@nB^D4jmODU zSQI)lf2KFYE7zCg>5@F9gebyj+$%%K{Q590kLSKUu^dbI@kysvpAT1u`}=HO?l0B0 z5b>x=vmEcb`DhEfjK567#-3$y-F_gKBxP~I-pN?*wi-@Vu$3ye}E6~`s0+R!7&VlbcNT?Fx%KA9 z$+<~FyXb5k-{6%lRwq3i1otLh7zZ=@VX*0g@;!F7JH-B0gR+faUSA*w` zyit_l^_O18LT^tH&-b5t5|4fG5w?zA2eK4q2`aaIX+wB|7zswV@4&~8JsK=G0Hkq@ zH@=jY+cWRHiw!sLpoI(>njo}ABOxIdvz!z#ts`S$^S6Y3I?-{2p5zFw$)uv&7Y}dy zX3R3>GE~8NQd`ugymM4V=NY@Ttg#m&Ay*1Sw*JU5aRg+9#fy_v(_NT(gsB) z02)P|m|PnSZt%82rg;w2q7;&LIx+Hv+XqgaMKfvP^x;G0mDZ+Bw{GEyU%bysN-x;f zXX@umty|(dzv;w`;p7`In;D{Fk#hv9*#?q!D8BGHMuRP{&P(f=x8D`@CCiJ-EotW= zukHMItBqB8tI!@6*?P?JU?|Ghq}D2=B7cnuE&C$3i={Pf$}5+xX_d9@7X!4$h2ys& z<7FZr9{&RiSKi+{_YC{^-9KFYiBgsU|MZ_?WN;Ap2mj!~hUiZ{`E9ZKqod7>;%amu zaXH5@8h`UK*2IyzFmiB}H*|51CQtSIqz|{*?|dcZ$9Qi0z6x#2uNkWWy+GaklJ<{{ z9d#{GESG1*kXc(+hkRCkD86=wx8wNmb`{_7ayQ|tF}odB`+>?ae0>V@L39$Px*qCL zhLT0wRmBiirQz|bfTMn2mA*FI%Xx>TP2bA_h%3C0WE0ftMJondPHE)<*}!6VcQ8Mo zy8GA#mm@r;S$pJ1SJi)5_W2+sv(Jl zs8ubITAFrb>$vuS=yQfi$Chjx+~MV3dh1)f&38r1@F*aQ4eX`iVaimNqU=v5i~&$` z64?yQNgLeg^YYB#PjzRzv1muJfo$em_rf9?Nm6;GQyqHjgO4ycIgKTBApcDUGyK}GeNF)VrF3e--!pE4uK8_vdUPA*3?mYJ`Og#Py7T0ZZmN3WxVw2Pth~Gz$7&~Ik(xH3rqO&k6uLs zDSrC$OPE?SI~>CQ~NqcF6ffctMa zqH~ei9%f{tiEo3esVt3DX%U*vX3o$6Ep^LrE{dtld}0%Y)VWtEK@&~nr{zVU#m=U6 zn*X}zm++Mzy^2?V{VTQoIh=TVk`uBT*P4>f>wr(!)3*d<(*d$A(j;?+2#q%K+<5I4 zzHLXE=DP%C*OG=YsV(UCI-_!O`c3IlVBvc_~MU$iU=9r zeePLrU+!95!Ye=eF^~ai7Pn>O8j|{Ot{-TUnU528nR4C5TeNFbC~NH|j3KfCeSJB^ z=K7VTr6u6aH-SI+1K^+kbKpDQ0oK>o;}2-HsoLh|RyxPLWqe$CSmFbYHKgB-_v(y= z$=ZirfPLZPsYye6^9VOfn=aIja^X^XF2k`po_yyE<3detSu@CqTZ8>Mj-t3aWLVm^ zBoZTbVvV|e3{_aF9ACTg;4XI`A3v6L%ep+Q%tI}wEPcHF6ozg6@9U<&T=W`7VIBYz z*5_5Szx%C!KQ^}cYy9T2^W8jry|$hg!EKAU%Arix&~GU->2}+{<3dty^hKIWKBpqD z2CJAkWY>c2u?-{m;Hf7{OXSApEx5gLV`-R9$<%iPNn!st3JW_ytEY*de(9y!c;xtz zM{w%l!`ONG3J#t+)1EH^q5^|aIb7Pe2WJk|yH!`yhfh3?M~)rG=Fyul_X3&GH4=5i z7m(6v+dkh8ZwuwR!;JA6?B3vyt^Bh_6t|B<;o3~lZ=(6;+ z-}^n_;fL?HM4t=tV_;WUH=?7jVewq}S=wCwEm1r!$Jm^QjX*TECLGSw&BXsr9Jgg0 zT4siq&7(|T`1@y>eJ#hUYWduDE|#BCW$X?!K^<6qXk-1x^u%hU6nj1zUozviES{W7i>3_c?)C(hz0Dc zu6Y_EGJ4pWCchIQ0c-0u;F;eV3eE|nfpTV^q+i~o%qd}*9MOlU@ z%kl-=KYgoxy0+PcnRg2VcvHkkvKVoiF6-)No-TnLxm?+QEe{Pn_8wr{4H;4k+5mU8 zJ!c-&Z`lS@_SzG@ee-4M|cdQJGPgUbU4Ln%G#0!ocvTS4yxTQIAh3}nu&^9 zi9l|q28Jf4@umOt8nR}DSHJp|ju$}#dB50xbrg>rJB|d6c7NoPzC}n&i|ba#Ym8!n zwavV|;xt7TMZu@J#c3Y@z^Sv?dGU(4E=+1s`*c9=44~E+v)>V@=a#vo>(gq3*ARUZ z?!Z&LqkO^e1G>L7Je;2__TwMdZ;5pPvzzL}9e0{JA3io1NXtPiIX~?*vx1AeznUlh z$43V4W;B2LozdHN`o1!7kKvhmrx$3uL6{HF*?rftL$bCe%Q7HKfh>O&Wf`J0!Qkm% z0BM3OiqU`h6q-}xXiTSwrV_-9caTh6!sV$L+u8@pj{eqvg~>->Lee)FR0>*d;~3@7 zAv|2X3Ncec{~oXr4m=u5s*0ZgyzDoZ7C}z})Wys7svz+-gTd9mhlU*x13C z6`Z;WZ?swSYT0Cg_GuQ`DBK`^bD9&7>*E9sJoB@6kj17fh$e>D z;r*wc#OtrTjF(>fDUi|SwGq%hwHK*ADY(OOi|GpD;>R#N!i<`Gl_V2c^Zr{Hb8JHa}a*=$}mOX{Qc zhHG;Hx4EF2?tP&?9%VV#$KLx8SuDRB%FVn;lq+wkS~E(G>OMuE{`KiduBDkQB7B+V zr4T$kJn1b5wS1;%W(L_$eu{hl_`k=RfAv2j`qnpd(D#5=oa*3VX?s_Z@e!Bv)+3@E z|72R^3#8sbVa-AzI!%)}lJwFO%MrA;B=aRoJhaSvJzG52f!cXgjvss_r*(y$QW&{Y z*ClMm65cv@)vZ1d42DEq{I69fy>4#v+Y9C@}*h7F3QlOuO8fS zs@rni^jD5LZJ||I(}iixdtZx;SSf1s#Q&8z)g50xmsv5Pz8pJVwYK7Ekmit5>OAsz z()u;JNFy(emjSsDm`*U(C{8ZezO`i&PCool<$~z65hHB`P6mulBK_}v1bp+iYBx4M zFBv1n?9c!{dh#(W^n{(T&8gMZL<>z^-n9#99OKZ5)5y^g&7;T2aQ?u4T-mb|t!C-v z=asb7)rHd!9l}zh3tKN=1D(U1&!y&M&Nb$K4};GnW_DW?d<+L9z6-Zh%KCu6k8y-1 z`O&-Zz6)h!L*Q`qq7{n0enF|F9Boov|#3_85&DcG?P{lvdlk~ADY#G z@dNPQESI+P-w>FTYZDr2O`GJKj-@Yzjyp4NjSh)mj<@0UY+9`OExj+)%4s7pm4L?8 zdUH3&uQ?Zvsg3t6Wj$J+pHBXc43T={BJIU7Ct_2L>CNYI!Mw}kL_Fgn4c{nakCfU@ zFCTfzZRJll?cEFP+qXJ$XVddo`t$dIrETc?dtXPiZzr&fH4~pVdi?PS$Bt#VeS7uO z3LnWNo_6DBUvKeYZ;l7e{{bx#d8N5u)#xY)9vVg4R;2cNlKkPME#Yb&y1cmE8Cn0@ zK6ck{I}KURCWc0WG_p`>$kLPZ1XM5DyJ2i$m(?V7X?XdThpWcp#G@1cKo$1$jSW>P zajX+2M;Pu7iPH&HwdKy!53k>5Sz;?ec1Np2eqgM_lmlmfcv~(%xR+G!V6uU~elOLr z{9f(=GvWAdQ?2-nN-~p4(oEydgba=1QWtHuCc+G~uYR`kRF`IE=kV|T@-Oh+-}olF zYZ)-Ke7x0OWWD9u4K$Jj?>}9A-N@E!*Ky?IUm`^$7HrdLMgXbV2qSmL@r9rL96x*U z`Fa^tbmZ7CvF*w=25iV6=OBk)qUCqQx?S6$wLt?-h$6HHO+87>`<84Ud3=6m8bJtZ zm!=)Mrz8zrydkT3&3DJtJz8^J6h&Zj>$XeM)jgQ`3o z+O6$}%bn2|UwZ?6Gjr{;|C$BBPKpwi+ElwcT;?Ewbt!3DTnC+Vjaw+VhfX~tZRkva+7ly|0N)r+}Z%Z5zZ16oVFiPxjyBYT~8(cUkTAR?UB zuFV$C$b>Z8?cB8wu-3=H7SFTMx>c=Ush&_6ZXzOXkZeyS2r`PAVY%p2EMokp;W3B+spA%&5(~gN``zEZTZP9AWLpzDxPGs91&QU;y zh~Z#g+jDOM(Cv|KKg-)2f9CQ=MTv5JLS^Xcj~o|ANDKc6E!WF=kYO^JI&@oz6?A{>!Fu@XU}8T#mk76P+Tv}d#%0LnPW+<9jFJH)59a=zJj>0 z|Dtv|nC%QX<}|iqoMq^rn#J?4|E#D7S?9dmBOn91XBUACFbmB2Bss^Pyv6WM!&JWf zrY}=N`4lrv@8ou3T)fGUwigdXi*lno)g;>W&pm}4+e%EF6!P-PWp|lt8;0X(PF1!R z;2%-SN7efF#b=&w-$wLr|4$5l^Jzq1|5|>+_JiHht45*N)lbz}hL312oS?C<4-cDh z*JWdo7SC8XDV^jf`GWE0G5HupsaEAz`onydtzRdUTefAKL&=S$uX3&QA~x_aXZBBf)MQGxm{|%?hhKYee1~sX}S7ryHZ&w%FoJNGacFaw{dEKPQH`kKifc}g%M5SbUptOjHlcH&=5I)P-K|64UR>I;a1e?)*@3G!WM&rH{(Gr7cT&zIAxb&2|}u)RHuj zwfW3VXnlT_2`{I8>~pU8zhtVWs!X*JT0(nzW+`dfGL@~f|5si(VGVExR`-^IYpjNsE~wGg)wMC}PBUcv?}(1}Vh;w;6QiF-q25}K?IV4SbyDf9aRT+;+ zyOn9uKnqrSuF?Xix5%aA`9)H679T-hayjwyrzL1vfefb5T(r=dZ%jKIh;bnB$HQfyvB@4^bw2IW zcHAVLeO&f(;Na6IhNnMll(aB#?qh8F(f@_U{0#ap9>?U!K`iXtkNNHUaqrPDBJCZ( z{FXh)8ogNRYT{zrLK=4=>*@od3|Sl@Yc%sT;~41bX>YUQ_Kz)}mZu6FaVLk5>H^wo z&}>`pWdL1&tICtE->SB5_XoSjl%+$l+_)u#>VxaBIu3O@gvs#9jBlYh(H)-SJUHKL zzILz9tZ+IF7xs2(48P3Ae&la#**djULY+c9Z+1Cy6d?b66VDvG@QY&`NO1DV!^I@@ z%)o#(AsuBIe(}uHm6Nn_9Am?}VZ?F$_Ql7TD<&vfC&@m#=23r6)aPlnn zbYH~i&h5CdRi577XeD^!gAWj;=2nde15?xJnqMj~qMnF#V=?Wa;5ngX3>i532h4)! z#2Q!g?=hmhgt83%le2{f!Ekadi{;uyFDuA5H8<6j)Y^l>@gr$HzBrz&TC*uTkDZ_a za|X951yi@28}}gq@&q$^A{+PQxE6Nn)@OTcOdHbv3M%Vz@?q`jFrO1Tbqe^`{~Fl2 z6OBLoLtyi!2Me};MTq0#I(Qf$1ZFU(Ue?AjRR*&2=sU%wFeu_k-tc^lR2UsX%N<$2 zd7g-;Cc9*8FPui$_V+T1)Nd(c#{N%B-^=Y4S?&~1dLp!hGR1HT@gsy`tQ`0@1Wju9baP*|9H;d8p*p6^d04O0gVhN{LljNttKeJfrU zoW|CV;LPEJ=$)I#hMRXVa%-&U&8B=^f7C)Lw`M^zl~L{+p#{#of0`6{dCEoG9F0PoaH4nwV@}=K4Clf~7qO!lc<tv*u4zEi_^=di&H zH)!+sc~~;3}R#Fetb-7|rQH`LF!^ zuSSw$U}hGJNvjBV=I}u@lEmV*ZhR7lPn>K&(ZX%*mNBIjrzwUer|{fcZ{xjZo~ku5 z{pg1uW7CaWh+F2OA46294J2r>UAFw9AMM&U?U#TI2gmOAW7>(Y1xH1SZpV;4^w|R^ zmkq2$T|iVX$CYqU!amt%^WXdgC|j~frETYlB+1$>fS+td*EgZPjEpXVHvP&>-pT=* zYR~Y?!=}ZAb%Y2FbS<5^#!Y>*b9nsy579S0YfVn;-Y#7n@^@}X z0JOJRn@n_`8;U-sPe4ua_8gtVa zIQs$CzxC&6%uZqI;V&R^xUfrw+wT{4Ou&%o)xdcDW=SIqp`X<*=PZGIR)!m8JUixm>4%Fa4FJ`lF=8 zzp~ZY@7!rnZ_6wmHjcD;yXS!g|YqR#O3g%DBtrukrl^z*|-E&xX5}= z+ZJEa{%aMe;nc&2aee#N(yN}cD8ikM8@%5QEiNtL?T_*Ooz8;);=pb%y+E~d))A;Z(&K^F1eP_;L`0fM}n1z%mEZ+uFjE@Xssk^h|Q0Dsj zFxS_I$+c?{rz!TGJjZfk&`BifiRzW|t4C#O4VvtchJWMl{HU6~m%o$!ja&QxEVL%4 z-S}@C9nq9yic9-X&gKjec3i%S!HFs8 zD~st0VADr5GNZn4HZ3>WarGi%gXR0eo$#&` z-X%qN8l9DUr_?FJwzY}h6UM{1JzMr~?t_zQa%(Vuj#XHR9VtCq^SIwbg_4-X{p5eA zX9|oZPn=!e1TGi92b3(aa-8F`LS^}o^?GyL7F^u7r#ON5ev=$oa!Yk;-5OllyW83* zx*VGC?ZxFiyRqZqm16w8vuOjShr;H-L+ReSH5gw%jLoAr0Pysj7{ZBs z3%T(V%d+u#d5E{fp>kuf^t4F%si&l@>?0d8Z-C>+5&h2Z zpm}uH%JBW1(uNJdty}15(Kb-8Mft#?vv3)p-s=t$JMo59BsAW;-SqiX%O1LMVoZ4vvACr zJ_K@_NO1h@W@9ekb;+!F~jAO%d`>W(w^NxdE|6`+g9A(v=O^5UdHg< zapZ=$fd)}g2T^Ir5Nk@M(SD)@1Ln*(^UQNYHDn-o48FTK zK@$;Lh16a1i|C)84XP&q7#%Vq7nbY+e3McCZjkxL>Xkv9Ul zRL@x(U`I$XFfq+aKTn}&ei3WOC#+UzTG6`k33Sab!Yn~Z*y3k>T9!tklZo6=7U6%Jc6s^{35I;w$S!w^FD$zGo`a&Z!ea z?E!s$sL=q1SMLyt0I~rrP!BA)`EU!y4fNaq*`%&@CD{<}^vpN8;M_%_xw88zhp;Xy z+P1h|{CK%Gr^YaN`aP^U{xigj^O)Op7<1bXU}5`yWQ`_T18a~qyDh1;vq0x9QlWJi z{oMw{QdYNatgp+$fO0kHtx7vYw`-nNxzRj){i8fwBtpt}D*=>!`3!Rq_`lsh3Uh%} z$CJ3U9Jl(?kl2{4V-w!~E^)Wp{^xOB{oGG31Z(HBoQKxZQYu&eT#iBRuCpykmv2IE z8RXmZ8c2XfgtG?@;L7furKeZdp(IIg^1=mV>w0RR%tF{Tx1{F>dU4^vUR>KAe)^cE zyBpRcPE#Pdh~YcqF!(7#iYNlk@85^T9{*zXP+IKi#`SGmvH#>*F^Q?IY5q(jsvJRF zzqP+2RHM~##c7-iOJ<2yCCVZsz>xt*M&$Qs71upq+Pe!^_Uyu3#r>|0BtfIqLWB&r zH*X3$>2AZFJ6Jn0Dc+eAnGK3Eo0}7uD~)p$mbDl5nw*#kS+Ec}@-o=c)RozGo44b^ zi5U#GF(xOo$U7@iwQpmRr6zG3FL9|s%)e557z~`(omm8(A@|*w?cN60(Ns6s7k$bZ zK&N)mgt$CqTgr;!o!zpyytD_jq%BphV|Z?0g^->){*80c zcBY%kYQruM8};(kxqRezkfoHV80JY^$zc?Zwfww0)4yf>Z9lC$ZYWmnq?N6fk90X> zO+A@9MXY|R?~hwPX{_q%^!<-`>HP3?&;~qz8yOeMd5wHNZA2ht3`wk%rnQLF5i-t#ywuU)9Pewam!3;>#>=>X$#+ui{d-| z$t}7u65QOj88^1AyhrbnPY#q&To(s0RhNeC051IEmoxLt=Sct0;6 z^K3lF@fx3Nw&y)19;BPQxXk8$WP?+Ue1Ntib$Rf%mMP@PW9wW-mYnomA8!aih2sc0 zZkMX5HI07F&Cg^B>qYrg!n)7cGT86r#6hDI?$aG^Z(<{4e(Q;N0Q;9qqg}J9t}NP3(;>VEE2BVk9tUFmq5s>X}dM@gY96 z-|2Il^m{%~Rgo`E8(K(5fj!tt2$+X6aD-1vn*|YknXH6ewj?&d%Fya+;OyZ8Z8>E* ztiOF18*kn!xC1eoNQ$$U4df(vMVB@;5FufG*IXma2Y%DLP{@;?o@GvkHYQ9^T_huKc)_jctLdJwSwVE!o()*bs@Dr|S0k>(p zJ+t%JJUb`yV&WUQTIhmaq%9|^DXd;UHy`c%sDnwM`})CmD;4UJ8m z0yL4XWs*C#ad7rrNh(@Z5yti}N#(nwJZgj@OULk88}N=g!FQ0MOxlaqPH0eO|?vKiiH1 zpIq9x$?rM+UlL&)>eeZ-7fGCnhm+=Prz^F-C?c%5Y)- z-deX$Rgud_VgKoI)YW6Fp5;5!PU_-f?uX*sjaizQ+iBBn;1;R;D z9yz9N6#b1-)Z@HvEgBQ^4Z(c#uWo68t{Ef0Ik!4L$1G_}ZWd}ATuE|jFH2fTN(eL) z^3(64XNi`;y(b)#l6Io+XqPFS3T7~J*8V~#aP!oS40QUov{;EK7B5eG@}B2~FXWaJ z|Cy2^1lQ^wSJr1cx2MZ!W$epPnwtZzT?4i)cP-K7%UF8*J)}t!J>UK|@YGW)BH!nc zHf@S9JDXv8dUexTo*k-rRWICjr77dNa50bP$K4sUEyush)4zyg6}kGNwE9e1GFAlA zFt)FnbEdJ`#mO%t*It<_9U31ss*{{;?3?R$`HkajSsUDUkrlb7^!<{%$z?fL@$lo@ zdYI0{3GpX|_8VR{KsByeEege}F6man$GV(c*YWMtNm0jh*G&i?+v~vlJWr3??%LjT zzt=WB$JIW}F43`kn_2Iro^oLgsX2W;MB1HFQ`++T@*=Hdt{ZKfma4zi?OQ!v-Pp5j zdvJJJKN)Up-Hg%g)$ylhW-vKDh2HKSYzREjgpUQG<#2m^3=3y&A{(DWv~dvq`!``^ zZS~Dtl&058OT%%bm3pEG4wcL zevw6Id%JAgn-2WrwyCQ(XzP>n2`87G8D@iaMytUyn5L(JAN&C6d#8}R@>Mi{?`!u* zj$c6<9E>nHxcYdz6RN@_`n$%({JrdrK22?hq|o_yi354MIe*l--mqs0`qaT-} zOYOGlYG1x|?=OY;AnH+h_z*M@yz;h=Xnug|GFx1Lxy=2;jXJy2yHtl%9C)IrGJ5$1rX1AB#j^?0t_Cjd+k;Dcb|a1Jo%-da zu~}q)c@p^Mw}OJpc4emfXcBW~a3FZWHm9V~z~w!=(A8SP?(>(>Tx_+cb5Oh3+l{L`cUTh3ROxH0*}#=O?rUkLhK4Y`W)OWd zbJ%k2Mv)&`9%f1wFy|(i%cs)f7dJ(;tAOgwTs|yYSA?GFdF+_JTJ%dh7c#uOme`(< z<}L|ZkPf)Dfouu<`Ybw+5JfJzwuy`K%E4y?G}#-0OcLG#OnO}V=mqEcs%2gx+>wwK z>E*ClUf)gf5%5h#eUceQZ+Jg5u}%3=tFQyk|vXrDh1v|82SmqXl{MC2aLI2hLP{6N~~<%{cVqwRAj6MHN%he)001BWNkl<8D(!^ zVOAoLoVdeNzt3A<2-dAjHYeSO^f&n|+n`1O5@p!iLt~`K8WC=7-h>lJ9yK2| z8C<J6 zzPvvw_)`lde+B6;E-#naECl4IblYv6Mi0WsnI)IT%dXS6`IXL6)4Fjotlw3(l?f4Q z%XLci?aO*JJq?^an_=6wWyn4{isXks!Q#{s@a31#^TeT*6Yz6Ld-ed6ljvv?d3EgS zPVM{rm*zpZLWapUN9k({SGn?Whel*qn<(=kx_k*x@2d2W+sd!v5t^2M=W7AFCPHKh<-HOV zYLkZg0{pb{W8P}<_m#J8zj?rq#^*<^J z0&z=|Hit;8EHx7KSQ|%EKD5m8mtB4mY?qfzdeZm-R$S|uxpZ2L zZRXNx!LvDmyM3cuJEq2`=8NuE+QTQcb_6}o48Vz7Nptyiww*&t5dgSXL6(ATlTl4k zzGTZqyIkosb=p)eIcghT+UJtE#c1qKEd#eDX(ZwH{wJZ~KgBdZ54`<0@WUUX>&Ovw zJy@{4qO@xl&}v0Ee!Me#e6=vQi@&>%)myl2i1$eyCSuPrZxY|>*b>=up7lwms_kGK zTWi}gh1Sk4KJs6;BsMPRUJLq4$As8KsGA=rB3Cq#-62!qbw?V~#3*05%{jU1!mVTN zI=9EdFkZemIM9{;7^kb=`Bl_FP$#w^uSR0ML&g6&pM7e;q($Jv7i zf=VKoS}8C#8ys9ZhEd4aK#J)#gBV{Qw$s^1=ML;goTk`zc@*9AOU3&b85VkbaC6J% zW$`z3XX6G8PEBLv&fQ{S+LS(>@13bSBhy?@_mOEW&GY=5-f6WQwWs@;?Ld;izzyMa z`{QRT)6(Ni{hMNTupbj6>oC{fhjRz^FC!mBW9vsSwtfUdQ&VW92{zrh#mY=N1jzlw zrLh^i7zjK2z z^DiF_^5@>`=dt$vx6qhRFm?1r%VqwtXH@d7>U}+OyK8)5U2Qo$d|8~8bljHl@<|+?{>qel9WJ)LT*kMo zZ&4a93~O5(c3S&t}@p7NO z$<|v*cPgYcxpiq-eR7$>n&zkiBd_}$`kWUnr=Z?K3$~4Hdc1J?42h)m z7dd6j9CGPrC|Ug)xe5=LjoFds_j3JV{?t|z7cYxuW`KYH?~$CljjrGPCb}Oi*uL)+ zid*xr;VqW)4UZ>VFUP(*zU!OmiyRkMZk z$cl}k2;J=)ofemtkYyQ~%_bUZVfOsO0>1a7AK>?Y^II6`>#t6W$=FB|G?JuxBkWRw z?DY${@xQ-~zkcLL`0g+N*Wh&O&@0b8i|CIcoV|P*Nt#qg0O8{nnxe)+>}1{cR)Sny zTzcAm=k{$$oGts9#xgv9iU`d%hW_aB$1uKrq+Ui=kaX#~>;T$YYcGta)3s5Aix|cO z%<2Mj*0#An*{zf00%gMNyp(C~m9RFQ#O=nRnc!*bFKGjoTa~VnMz*ix)bm>QothjK-GjGdJiq;;pD$+RF#?=%?dpYxOx%P6MtnI?+GHv9c%Koc<4X6w1fMoQ50TqG8(Yh0 z^Rszy1tS%kluSFMGD|ko;khx%LAaa(BCgy_)X zT25Wt<~-qf(V0UBv2JVvJ@aD)L|W+W#+Y!t8xSqq+76&J`BgibmmQEqL5W>JfzFc>H zpchy6?8K!#yMraELsLUTIQhs!h_e*PfVFof&`3>-%YiIk{43=*Lzn?mQ9FDd*G%_j zMJT%PNx~-LqX%+Xy5^*9S84ecY`Z5>xh6me+z3fysS=Jo7OBio! zZT{XiF13v2_iB)Dgj^k3SOCVxfRX#>Q+q%j+OPq*aRXRdst(J^4_51t-)%$MSVJ)1 z?q+vf6!E!>%Y@=#<;evAAEWj7Y&bxDmCw=w)S$bZTw{Lb`R)S1+%D|7br~aXeIL<6 z1Cvj`g4sidl@^mJ__dM-n0EcqNvHsUUp{7{h!?>=k=sbY9USJHtS4Xia7)LHQhc>p z7N#5!`sz)l;_pkocIFRnT)5^+SZdHd<6$XY#M?0)sJTfaDw_<3L zSXw8x#c4a-WEyVS?Kj4`C1rEx!EV9iZZjtad42K?%^9YK zhVb6g;r^4AqNLftQcpJ;3kl1+Y z+4f?PJX$_(hjMi7vX@O7T%+2u(r5!EpFL99n;K=h+8!r++ke`ZY>OHhgpS-c-+J+F zeyfk6Eqd!M;6MBabbt4|z}H{+q*MQurS5K^tE)a9UKy&!!y(@|mNjqqd#(@6cNgBK ze$0C%6bIKS-ExAO=TDBVA*4rAz37o^dG1*w`%h~sm(G^_q}|BVcHwxwY|>Y{Trv}f zmn7*+j$@^E1p7|EjU6uKBK>LN*3oZvnfs^?ZglJ2a;k%u>*C~3fe)t&8q;OsyNRRqf#hjl(XQ=xZPV-Y>>grprET@_o|{?nxR5pBd2L^D zeN1PwnsBiwFRu4;o_v!bh2i23S`(J(v9NLKJ z8#MpCW?&G%`?aqF0KWhFPcVM(9$tF#X&l_WyOLih?LT)8UCC1QhV1X3MD}mq={TJ_ zdhLr(K83Dk6UWY;sli|V%hTnp+#atq>4ikAL#8M3{^F9xhw$ClLFZPF?e~{lc1iy1 zBd!%qF8IAwX5P~*>85u;e#^5-i#9y#vb6OFFSS%XbDYOHNM8uAQ$ptEn?|+zHg%p` ziC1l0s?j0c2uAHj+MoF%>jaIWq->4tN9E>#LtYXMmOr=cX%n|aqPE;7$MP^Ux}803 z$1^^ZJT%{`ZSrr*ncuo)q$1+uk*PbM#5(M9^n>5d>l|ZuLYFTCtyYF7pX?yb_umKp z$v**p<2QhR_z!_SdsbY&2L$Zi4K$k(KKP)s7FULg?XauU`nU}CI4m)?{3gHi_*oH7 zqE?=cPQz6SJbXCfc3H99u7(;p^x+jY4%hn9)~AN2TT1Seu)Q1R$;=*^BPeCfWI|fr z9<(1(AIc`z6Ue%8VQnf$j_b+RaUb}`(=d6JMD?xP8|UGV@7C>|;PNtZr@Pt~XP6xI zC@g-bIa|h}Z8vD7-~Mm%S--c_(12UVC-aqu$-nFCsw5A$9Io_y`67b`DxBXilO4o% zFt{f)+>QvBp-<}C1}ofPCDW9fg2pJ#e~%9jugcZW0MONJV*T26wc?Qa$xYa~fj*o& zxF6TIZCx?BW(WJR=H5Lt7IP=V_=e#XU9b%RH@9p?oTNDV{xJYlm$6vT>nC#dthPZb zRhS%vr4z?)hZ@*OpvBu8|CcY(jgerXuLl?R?OD+)zFjoi-;Z~neFjmM;i;d$hc#o9 zh!ehhIj7VEh2mIvRt4o%^Q1B zcUJJUwF8-XnMlu^T%CXa|Ji%f7|E_IJ?wk$MP%f@XI5tI`(DLbNETUSv&rsO&rEx| zTQj4vdn7Nw3ps8GdZJI9t zkO{!F$lBvF@`>7k(A6faa(8#Ebmi-`ICWXmx^BI60vjrV{r}|=OkLt*_WIqQ(9T4u}H(L6W9BI<6Ts1 zWo|b`wcl(1=Cbp7(#Yyl?vb~;NM2oFHeQmh%CQFp!? zxO;ybfAPZ~W9ffLP7U|}`CrFh|LyN$sIU1u@?2QC(UcnH*0uaTu2Dn#bIkUpmmB+D z1kYc6hb92r9vwkB2yo>6k3e@B$ucmWNdD=qymFy7-_->0 z0rP}2hkFT=q+2g_UVtn>lWAU5AiEGCL zOuK2@Ak9bhbDg*BUz&G$Dvq0HYpv|Qo;8X#BIfNC^jUlF^oXFt^E1Am!HpyByiM*Y zeF^d;Lha|1r{Kmg?U=NW%zgPiYF|e3+3lZj**h;yMd!eAU8Od$e-?(X^_z>c#?G+y zN;U3UtM{#>m9A%usjm)dhi!CxTmHCJox|2EE?lU8H`CAV!*0H7B1Wj^I-VWQ#l1~k z*xJZ`%l%QtkqgLmTGG;*r_5@eoa7LKQ0wQDmoPp*j-9<*@ZRkc`0nPHl~$gS&*b6^ z{`}h8Dt}Yg(bi7<_WE52;~4+q%6Z(He~5C}gTuS`V9WXqoYu@Ve*TLO@V%E`f#>=7 z>3i?u-rqa~v?NDrZX8{U=MFvv-{%_q)^o=ZMiJUdC79A$D&c!ye+6x=_1`q*MKS!S z_J-`efBRRl^*4_L0D_kM%PAV^JAv=x@a{d>yKOs)h1z*Z4-oSpiR$a~HP#<4kL~fC zoWf2?_7j)?N`I#~HqOx8G_Snz(TBJ-b{G4$?ZCe6O}=s55FZi39BTkbh*fHam9Q&~ zQ+RtV)rOBqr2^v{)wZ-s2|M?}=s@B?$|>Q59_a39lkf6-aLw!n!oOzTZLBdH_fd%( zIQ1l~xv^NzhtpE`I8Dz_we>+ql`-3<&zkd_$Bx;a1=GJH#nlJwd&}g3a5MuF0|?Z@ zZ5xNPpM~F;y$M4iPi`gIy+p@1nL&N0x;`3DmRsUDIc>Wk`J+DqjvfVm{nvpF8-N`C z+9y)KcwTba_G*cXJM$BF>(%_r9pB{r)%*b3+Ojn@wImB;a&eb<8GXDyd=e|2^_XK~ zX#Jd@LH(YEv*m%G5b?}9K>8~`msm*GUMR*nxlvj-FljNleocRcwC%EF8i~k}(8a~w z_S0s?<|p~y0rNeYIl~z)+jiSpthE2KTH1~B#Ff!Ef11l3>uMr@w<^oa)+DO*%$1jm zh`Zy{-$Pl3m(d)rXR+hN?&(3zJ2_K+~G~*9+m=}-@6-k*9-?8`tW6!3^UffqKX^2Wl_Xm6q*>2wMVtwrhJ+PEpS*vFG8# zV@GlP=WnBJW)8e0B%6S-BZTUiCrXnt@$@$DaFuo@p^u>gE*bj4-s$W*g<39um*Gt6 zNN-Alhh)N)_Z;(y)~I}^X;u$%nmKk%VpEDzf229m+vY{vvXz)uR%Nvs+UmfTleCjl z_FiQH4nt|L@-DK-G)c0ETmwG)Js|DT^4+j#_^F|({f_gA9;x&%E`q!qJ7C+Hyo7tD z!QB)2a!ECEYKKjvk=9e)?c~;jNs~#7+%77&6N&M(}VNLx1_lXutV6Zh!ypU~cO^;Z)2^n5m4Wp1QQUgqm2#kQ2o;x^n%pO)&|v zNkCau|F`!x=c~f_#y;}CXmX)YakL<9`bsX1D&CO}u z=~T0oW}h}OX|-qa<`KzvB`OKT70@u!Gj+>$7;y^BY-1yCcKJ9>*D0!!88JI@**M?Q zS=XyXcREG8BrDzeTT89@Ti^M0{IK-z@#k;6j&E=1#=7A(x#CK+oJUTaKZjHQ=Z~>v zp$%XE!{5)XV+^mdaJ9OO3=ZMff9HGnv);<&dRy&<;buPiyGvZ9~M#0lxF5?*j^`q?DcLpq`8 zAx2QCKff~ltnmts<<)UeQfI__QOTV)0c#8CD-9*TlW9>JW(y!bukoF9x^wxYMT(&( zY1uNH{L=N^sdMhz`1}JqOJV8zxncI!CM86#wI(eH>|R>qWU@DtQ<=<6j+N5VaQIk-aZ9aUYco)di?i^s{?22v?JY&>;gjjudfFV5M2_v| z$cEG&njSNHzdY*55yJKtun&WHG>=VOTd@eMYmMzN^LD*(n^Q5%DBm;1%dQW%pHinJ z!)B#ZkH|h@_K)m1rY`xyEms;VYc2o7mqV&?WEY3a!sxocavXR6H}i0z9NG7^%`nlB z+0(WCG|NQ%m3eHebR`?);;**Pig<&WF7=|H-*^`X26m&rwGRNW6fIz`JclSMV`ga< z`ZPqF4@Xgmsl{0Uz^|-3g3dxK=&&VPeAyOM=B+&szrJPz5SMZ4sRIZ%Z$^7-YnoPj zYb$=`_>1W6>IMM3bo6N~9^|Vl+FDEK>FiYH>uhgFmiV5B?#|Ad8=b=-zz5Ghg99f{ zp*XixmyId)ccRqaSu>mzIbyg+k8EizmC))~pl-_gFRo+D=U38}3Yaa|<{8?HyyBLFwbD4})<@9tG!KwR|5u0RGWGO0Hb` z?cW9t8~}1`ta&1h%itief4_&*ryE1FdB+qT$2Hnj=iZttx%zs23%8{`tHzpizm>n5 z{99Uy`szc5&%)8QFtfCm@-|eta>?Z8=Dd|#+}K)b1@L+-V%Hw%c#a6{$L5iQ$3oUX za$Wgd`zTp2ZD|3QeU)0Xz0WG2%Nt|caaSCdRI{79B(;12D<_X)Jh7!d9h$+r8yHn; zXX}E^)zUGEGX3sZ-9m!;Y|;%th0{P*$M>OutGRpGT^=@zTJ$wj`ZPm3HaWpaOZkaU zN?@N;gN(k3^;i9<&) zF_`b9t|*G&d0wuQ%98Z!>yA+zBMu`Vi~!GrSMYO{%Wkh`zR7?_)WVGC(tEjv!E`Q} z+IUtQlRC-P<|0{u%WWaaS|L3TE5xY-2XK3IWSJ#uTuh?orvq;CUIKV1tM|gCqu$M@ zN|jTWJ5QDRkTy(TMdx~x+BIle1U{o&QgtqY2fogjo^hIVE>Psn z+zs;?0LnZhpmU9iZg58(8AMiXNZUz!`TPKIc3l1aq?({j>iYou8e+ zwZHv8VPSNW!$NE9?)vQ3m&$8e8Wa8a;4(`(>>|RlZer*+B$-1sV(c0XICsuJ>pj?r ztx>UQ_3~_{tG(;rIbZo*K6?~W&7{;{AJxMzA1^O2PPU`0HV-wOV-!#FKlxXOHN!A| zk_ZuSpXz1ubC+)H;L_-y;_0&6<#k(NE~Q!Oq`yiFYw~|R3C(yLIDP*!EQa$qHnb~^ z@6xlH%>#f}-+c%7r;RHpKE8?gwa?)FcQ2{OuRQZChWh&P@%eMOcSpZV)>O6m+vCGPUNVa zu*~Fqzodrb!2#s=@+%yYM_seWvq;}aY=w3&TQ<3yd@jpqGEC|-U-Ma5HsT?6 ztXVcdIEYe~x$D*=pKHB+ODD;Z*<)bq$Ke38-J4ukT5r%5^#A}M07*naRC=xrPJ^|G zgvOjMU-m4Is?b>6M8Pg}o^Ro{EphHRdGVN=nKVacXMwlgigEn7m+v62r6u5B|7+Zv zE~5Jf{~21gZvq~%?f5Fn)~(5D+n;{gSbR6<%nF;2aW*QFo9bLyPpyM)@v->MW1!u0 zP5$ia)3yd$N0*pf*A>f4|B;0??<=tX0U8UN_*v@gRs5)?W>gNzaM|}rS2R;fGM^+A z`&MP{Zhr^I;oNOb$YUD4taPt0V*wi_S;kG_powWHnn#kK!l0@0gQeYY@6>FVgf3x|&6n(vK0 z4-@@;CQ!pbsMK9bFx6O^r4>sT92 zNRLu8rPg?&HE_qQ{strX>0tzUm%%wA?Q zJ~)6&Teo84rE7)-vVE~88h{8Xxg4`F`?Kq4oqqd!RBFmGOmgLf~IQDSn%%g5~*)2a$53<9!_&3GY9NZ4a zBeyx8xNMHz&XLatMt@D;Xcmt49G|s!maG@2X^&fG9$BL$i!bVk%cmK=4=y)ZO}O|RN^D%%z8t%c_mzEMe6}+x4iHMXJr``J9s6fb^v%8f21=E@Oc-h1d#5>6yDYWSX|F8bWJALmfU8 z##eU~sMs!tll_?tnbb}icM0!gx^6D%>MO-`IUi&Ou{e?a`hkKyebLH|GbKEC(z zE4lJ&MCx^%X=6;!nj_q|YHK0e9BIX*CQ`p;Z+ciA@hc0*W$y?Ori-vmp&^>;TAqoL z0DuA#+GwABO%{Q6C%cKXgaC;J3&jc0=081AEg_Jkm1a)zEl5C>?4PES8;HCo07p-* z%L}o9?1?DTuE9|T4##EEr*dCBY z>9!r#){g2~Ldra~kso9|ktd?%*f9?uei&nHtg-m@_Sx$0qUEOTUbt=A0!C(TmzMjP zba={J3p5V&M0_pzN^O=_j>{&IwsA2~oEpc_U;Ht`8?(6b_x=}zeFK%nJT`XD8lQCj z5>wL{!F55Yklp3_mY-s18_%&5o2MNVa{Se#R68%p392otMn)!P%5F_2H*k+1uDZ$V zB(WU=^-Hx;#8o!C1+R?cLynDTP&>}bpv!z*xE^tFGTS+p{BCpESjE+x*W`YTv~+yU zhct%a{LB+%rLNrmWWSGr41KFRs=U-T=NEGUpw+NhWqnvP;Nx_{NQD5IKB^U!}%u4H9pTL zf$w9mw-?`e>FYp@^hC8?M1AA0r+y2q1%P@pw$@#Sk{pw7=}MmR=48#SbsKVd0+{)eza>b&YhQ%RX1YXT zRbsZ1?@}ss<{HeqI|;+rHGpOqMTE z1U!70Gw{L!aN-2;&;A*@|M34sVfz-KRNpNJPb8nTv;ZwFjf_T(Np`DiOa~V~&|KE$ zy;=vEuO9Uz=87}=pyw!&i-WVcy`%QHAZ;2yciTJ}hZbWp7S`jkex~ugIc}My%;KtS z5dk{(gitlbl%>`DS)ZrHoKgCiIfm3nZ+KzOY1Y2|#!Zp$J9cX8mRg+HOo`&Gg#XgT z*X_32+&q>q)zfQ+Ra$9ZvCUoUkC%w-pC;~#ab@BZ9xhH}q-!&V+V$zVCeNif<8ya0 zvoL{ez1!4txzNxW2vPDo7dHMJFn^CSP4Db=H{^Fvr8c44S47opTbuE61+IZ zy`jNnrN91*>*$z$fS!pdwNx}xEyl&1h;x`NO0!Nmrn}gzX&=lM+APE^b!Y?w5$nk- zYhON)JM3U@9|oWA%N6!PM+fc?^kd_tYXGXVEtj^MkIIG6e0!3-uUM|9k(^Yvcv+`* z&(~f*IXf($0%Yst!F5pui`e$f|Jbi5OfB!k&`tTB# z{@{18^S}6J6SUW|ciVQ9|MPF*!b87SRmjkmr4y zR0!aK#~wrhZih^+AM{IO)w&%5}j8q-wsn;o}8u= zrns-l*=at8XKtGXHl|msoZTrzmKBAmOlHCMZJFwhj+a%8#>q)!niQa0C zn_P-Gvk$olbS*K*Y5qcF{}2m;{=iL&P&n$)d?{UYqNp zuyT}HuI+Y{@9M4UQP}t8m9u)>W|hazW%(T0#MiEOWAi=z+04U4geHcy5hLK@kS-J? zu~WADg?f|jWfJG;a%S_@SfoJ~U?E(@+qX~P_~e6939-P`jUz7AC%|OQEbJLfo(~+IK->BPGczw@#5entZ8jWa>GuD0zypn_MmOc zHUvTC+6e%IeSJ7~-~ig&+R)w6iT1WO4EOUXTE6dL-S8UtzK=ML(cRIB9h)}6_k8qr zby=nU+Q0a(FnV|wN-ZspI?+NUq8ohjO83?gbZ@QiMk8iE`TMEw`xqUp&FNYe7qRcu z83a*;G6HCf%lX-@##3Q+3nt0N%Vs*Jy*2Sbz2eH*ewLknZOyejJaHA{fB6CMztvu} zefPZ!xc28CV&DJxn|SAwj{yMB9XzD2FmIO7NUcXWyCpHNOJbS!iNjH7jzx9?@G6Wu ziNl2YWr|mvpfz2^uc#sRXNvp)C#Wx!ghv%!E8Q)3Et}(Mj+8U=VpW{}G z^QGmuGc&*+|1q$CKUy}geX?MCg=Kg+Sx|rZa%1u99ba6$HW9nUW^>tkbke+6@>c1e z$`dw!|Ky&Y9U_Ld4sP7)^5nU2E!%0071=iG&CDj2%=SqzDe zVB-t7M{nIi|K0J*;!b&vv1{Is#OBbhQLujG!0FW&*6qX6;fN*JjL{r{qz?7^D^^Qn z{mR})Q8 z)^|l~yG`j!E6Hdk`9#NxB^vU^aa!su(J5nJ){SdM)@x9isg^p*&sn|CtQT$%%);d+ z177w{yxL34gY=y+W|SiU&uG~5C8R-?)aKOME@XvogquH(65pT2(uqqbU%QR=?|vP4 z;f2RxLiCB$DfM#hBu;+bU2i@%PtRVsEq||`a(#MbrB%&#$((FnZ1Ze;(+l}olkoON zmn_Vkt(P7**{jGFkW!@)B@`*qZ*;(fi8u5}&A3-%nAnP;(_p?XH^ETsEdQp9g}b=6 z9S^y}<@c#J?i+RWqQ}kC+W0ut%u>jD&s?-!kE+?7*aT9sdhV&FX+NjWI-c#6lWAyU zVY3-V`Dmdu zKbX9aS7*j?^M37PG~=Ir4$LgT`|e)rw^yD$hEFb>$Ni}(?BB5io7d{y&(Ttd$qP3S z*I0ZV`92=Dw=2Et8ffo5z=O~4VB!93{y4}_^4dxz>_4;*L3b-ooIh7r4hd1<>q_Mt z)=$jm`NT_Gmvr1VN9uV83E8u+q>{s?q*!xpZ73J&+*i^>Ir-E<>^XG~ol~=Ql#{Fg zL5&FHo|j~o`Ztkl?Udt*W!-P9IUqD8m)6g{7g>T0**a_o0D~o6GG00zso!kdBb_V^ zP`G89wv)cGy(8NwttS6JHgscK?<+l7ZvY~mJ_XJFR;89^Ntw6hn(@kJ{>|0t|Y-ug7dH5!kf zX?&E;jU}Hpaa@cOW2dmYcPl!JZMZaj4Xr^D8#;znK2aRuy|J?he+jCcIrNCA*KCHimmab!j&0&3-%8wV^WRwhP^@z`CAX zVN3m8=-ayifgfO~FFDn{kmG&2#}3nunc+Ra;$`LuVZ0#P#V=*Lv5~g+8q#;UESgT# zBK8-H4YFJg=C>yAB|Xe5shM*^#Fre@T~Ca2q&4(JZ6v~4(j>D7I(5tRJ<5BY%n5Nl zY2vHDCcn=flQi?E)4*eRs+L$+-oh*q6~zkDGWdwo^CdOwcL}3H04jBtXl$1iX7whP zS1hl|N#OO@fiMLA{@(}s@}2(oL>iZl4q)@^Eo`*%v&=Ee5dB;#xQZq5?8N~cFE9>=xa*P~kuI^+Qh(W+h5sL?dNplR z6qhma@D|qh?yEd;@md{kuwxxYIyPXSeFU=SQGD+2JbN!L}`Wakkt@EI-TB zw@u+Tkk}%&Vw6u(tE_XJey4Vw;0$TsG|nNnzIFIns7?ut{3%q>fQET)| zD?tE^jskb?B)5<~&SEnycdIrzxXsCRk8$yO8B%|8_3&!`GRDzaegVx~<;cPL>2zER zwk1;J{IoySJds;kG`nnaEY%|cq)! zwc}-l@r-cNm8FTeHYTR=kYLMG&mn#{)0fYo(v`-N|F0ciwv*5{c6Jk_xSo-&?f&u* z8t7-HgDTtkLqnEb`fPdUlaKLmejfX`@4%XYftukz{Kx+m>%Mge zBggkt4L8->gL1L9iA<=gO?`>t5pjwtV1t*W@ikKHR?}h+%jU0S5lqmMd}oJ+-Xbs`Z2#XSy%j)Bp7t}Jo(**^}43=_4V51d3B{+1|}vR zwH8k#OS-y%Qfc+_%c3Aztu_xyu1=6`a%>_r6U|A>T8nzwh|$b3PrtRXrD@Aea!b~$ zICCF8Cw`8Oiyz_6-}rl2*tpAxtHax4M742RkLfX_MbmWEM6Md=B$PUvUUF(Wj{T;2 zd|@nYVj)k2lW$(qiuZ{u3Y~N0D%{w;3W$&CC2xKKJK?^F9l$W#JP(KZHlm0!0)(LH9Mbr4!b*U| z*o|haes*SYH z%xHiky9Rz4DW_z?K$BjATW1pe;d1&$w2W;dV6 zic3cauy(D7D_0uF$@PpSjkH`hkImM>t&{XjRZlM~tXU2US&!IU*BvGc3)|oA8wbo2 zXU#Fm<-=p$xKt)`_be^sRn3V7Wy{ZtwfVLPX$kckqs2aM9|nct6nPns=IN|)Ee`6A zqkpZBx7G^3+PwJDN&RJN77l)V>oa-#rJxOm*MCR#uxu`!^pd?p&suiF6TfSonC1Us zrsck=L@tgr({|%x(-+1zlS^#cDNYM%Snk1+t5UxY!KjZhoGWcAhpE45ZA_n~SFtTg z%m5x}-Xl4x$U}?`SFgj5V_e$4RUOE+T2d&NF?4qf2R=R}kT4&yrT3A5G>;pj5EVBi!%f5T}u`9fQb9?sy9x&C@gV@XNe|{99XKD&DJnTJv7Htpa zP_CT!D_fuD7krDeIcl1{L5kUOVZ>d&xcIR4`RLZ|7SdC*Pfxtxgy%&Fu>Im^c+lDY zNEU6k&dp=v)oa-F`Bf~T2+6$Ub_thta*eYRtH_1ULFL41*J5qGDTBvPZAIBaP}|`a z<$*Wr$`hUwZS~u*(Ta(&_!cPJ>!TM&Ydba5-EABg5Tj*j2_3T!(v-r=reJRWEQGB5 zR7lm-U};|K$68TL}xTrL??@r51d0^r_7D(K9)PeJ9VLYkH<)lV}#i zwDzvS9m>N~r`K zKJ4MuS7R(LHkO98OZnquwd&gAlV)n}bX**qb1-AszAnkfp+e{Bi?!-OV`J%$HJ>xC zq`xMf)P7yEk33FkBxBxM0FhR}eLyw$pX%-PB`j zt5uEcT%?fhWDFBEfVACF3|#o-9=lW03Sn^!2|3o>c{3M@Y(bYtZg5_j_%P)`85D; z@e7FIp}(aS&-D#r>&O~h-ns?tZEe`HZhe|o7=~E4W(4i6t!OK?V&ljt`g(fM+1`Pn zzJ6?7zh33Nb|`zNa;d))NB`H~MbK8?wVm}EfweCms4ILTNp0pm=@LjzOsjTk8p*); zIM!XinGQij=G{ci)=85%Q>3ZSPptC|5Vc5iT;(^HX#MQc*Oo8-ub*K3ZyrNyj@5%7 zpFfB5KYj;yOJ($QEMWccFgA{^twZ1XM3dg+yL~>KcKS=YWxrk1s+bF)%`25@sW?xg z%4upFkjU0(?|#-3?Mzn5aj7Aa1agwj6L9e@or!Mpa&uVUNmqN9w)|&Lpi6zt`j>Ss zb(UhoMqO&M6<#{k&JfiDoxGj=k~jjidliuM8Zcp;9vQR)q!!)KWZnL*!>$|tz_k+c0L~VnxH|P;^Nx~f- z+?_t(*1guUGXPNVfMY|u03?g3dxn=!tN;KY07*naREw>t4FO{Gx3r_be=FoUHrcks zup+IUDGq@ot)CsRxz;c;^&BbAJ;dm$3lZUxmxGuu>RT&Z2tU8 z<%(yXfOhd>&79oc8W)>1dtH`IYt+`&!YHQ4MlP9v(eA40T}uXg`!Lws{1bL#@y|Tp zNn17ZGfxtlS2o+%2uBVKqOZmz@tyT5+YHj*6PrQomrmDWMojjJZb~vY`D#09o>EO4 zTlAtAbJ4a&EK+A)*usoipND2z^Q67-LTRpPIWce6vtFd_BSZnAs^6?r%%t7`pOZ}! z#>t`_Keh1`KVk6tjK^4&gj$F6n&=*Fo=Ic(PrK(avv&2!`WN}R$0A%f97H)+ZK{d_e7dDhE0Am$0Z))vk@wfIBfse&q%y967``i zw5Q^_-?8mwWX20;c$?#zIma;Do7*1hwp5)DyYqnYyP0cVo9?pVkBcmiV>hcL%jNo6 zsM-#fPh%ZUBFp;3=EVHmMBLf7f*2@cRekGMFi{q1 z#32%m0eOP}V_dmt+g>oE?VLiFQf9tPZMnFi=`Gs zezk+FvZZHo3Wq-WINcb`Z!SUo9%A&3PvEJKKf#C390dT(x3*SYMD3E|(h@day@u@< zKdWqc_aTuuW8tI~bxzFSnRhFi`ZhK2~>BSLX;359ZbRd01J zE-qs0rAyd&`C4T$F)X&L{aV~-^;j3B|F}hksn^7Ou1~F&Hj3ZBnNNa9WB^8E(E9%Jc+afy6y3aGkW!pz7c{KYZD4) zWXv9J_EK^wy>u)zEhSr7+6cqH^Z06eH>pG#bLmp?Z}vR39Md(@)3xH}A~jOVF1+9+se9h1;A_s?TT_eQiA zO1L_61NRrEFw)kKbsfWLx=T?Rr|y52>ae|gJ?<||qqR`NNZSDJFHGa!{1kTdY_xz8 z>r!3hVm)0$9s)!t`MhM&1F*GwJ^EU@mBI6@{9>G+yoR;y{n*kuh>oCuk+wc;=~|N- z#Q*&I+j#gYBU5EDVJ1kvyY}%ZD9vvFO=n!88-QCe)h0l_Xwl*9( zbO8Hy?#dmfzFKWuWQ*yVp2gamH*s@q^A`7ZP0e6nY&<3L>=O1NhaNesnZ3a^+-sLs z?N--JV`pn(4*G85O_JAfXUd*EyRdoZE_7vFK`y0GC}8J*`U>)dp)4R{ zhhujb+Z-E=*iJC*jC0#W`c;F%^?C2%lL_NIh+)|x7P?*&t(_abV{zQ}v4gztUw6sPSZZ}8rwDv^okO;uD(z$-)drGUHM)AUYs6B?|XlNt~2jqe#;(A9{-NA|E{sg9G^5n zcS+=YBTR+aMglxuC03T)j#}7VjI=b`0V!EP?9|YHXELn0U|SOEe0EC`VOeIg7ED5{ z^{bxOSJo+-OX@4*N)zm6h}qxg%d;4py@KJ+Emk;}#Q=bUU&N8M-%$Nj^Ii^14zR<+ zM^e0G_HF&ooX`bac7Vbh8{CTIJ(bgxxqb4<1j#pv-B?GmK~SY(D@OK$dUF5|p_nvc z{3;jR&|*axsp)c_2%L2$4?N0l?6m zd+_5JpYGa$>7MRo=hHbmi!GNfW90hnisv91B?2T^e&_j%h&>NC)~~C3;dblXJl214 z9a}%WBo=JjBaa+K={MP$T%(p0m*;8uqMfXOjWM#vCR<$kbFc7FTv$Z!oYI0^NjFv8x1YcfuVz0E>4k{CR;=P3?O}$ z2+#c32Ri6_MUob{VKyeT#hcEvH-2H6)G+C!Xfded_z(#8Oc0X2Jc z=^2B!-VqWqts0|SH#^WJ;seA?i$^m+jP9})W=GJolaVO5yR|VVOXftRyaC`QCKRc3!`f-iuU3dK^Wr2*Wbi@&mY5VS7+S|sY$}Lgh5(zwuwGM#OR!!#VddH z8e({O?VGP)p|zAdKQE54?X%C*O~|xtHiVBd3eejec~R|bX9wPT>4lo<&$qSWwQs%x z0C?ezx6nO34KI!>Ehs>Q7$NxXS7KGf8{+i6`=Dj@Aqbt*$RNETbRuOe*i5CY;&*=L z!USe4_jsxMX%^C_mPoCgX5ehU0ez?O)~kHpd-@y-VTj9H6JJ}SZK)pFeeMF*eQ_i0 zUFJeE>G$CBnhUj}iXGA?Q}f8K=WOZJXU$6^z+)Rk=}0b*IQcaaxzighgJ)%V=9Xq{ z<(w+jJ$vmuHA`x8{8;n{y$Jg5nqizgaj2+5S3A`EO`n= zjnWolx<@Zc>sfjan2DNL(lrn6BSHa72oU0v!_Q!Ru=Wk$E_u+=fj3`zG0{H^5yjF6 zko0lZhpoOjp1H9a_n2B^{g;OOuB1c}@MnL9xz|pj^v##i`h#D6)EYgJiugY8(n}uR zcq7KtRO9KGJU3sQECgR)uc?QB(=*P=Jx*rzYm@Wq->QFid(dO!_t^Ms;$N~)dXu!= z&SoEBD#r?dZ)MaR!Cc3qw@#APBNR&3F$PkvGOasG#smN;RIpQ$j$EFepmx9$eA@%f zRI^3aUP*dOjDuY_9_TuEf79*4wDl&As>YqO#|aMSl6+jdmSp#$M=h&4?&YaR=c4Vr zRhMPl>NR?+DxxuKWN|)QKHk!`RU^oTg5Bknu9z6WNr! zdD79=hJ$r1*al1|?#jsE-Fs+zIF}9|ozpYPM6w^?&d8c&r{6OVUIb`9+=2%y8qb?SBCzx`frJ@;?l0sOwb5g}W+uTU9n zM}*t)D+wHxh#X!#^y|~bOc#Tz79`B@K<9QRDUxf3mI?E2;W&j6Oq`ik%lz1N#rl}Q z$|l#Y-|f0GU4!Ht<1p+#FfC^cUVu*5h}xjerJp_lgEp&}&Q$ZX2yOw=Hd4J3gp@8L zf^BqVwXaGm_q@^D3c-+0PMgS5lMb8@#4ox{n3_MXKh8tSjM#^!kC&QI5ZwtO@xm5gBKh9YwP+9cRhTF`gXQNh@W@im?9E8mN>xSCeW z)J@_GnC~b1?Xx~E(kwO2I?1k@G|KZp$dS=B zf2W*@U72OE>%!EVYhB_`!q4T(RjWXZ)`#;r@{5n~{&UY_rn_rZCjF%NQH0K!+4K$Z z$zjQa&fwj9D3r@M{nUOusAE&LDQ$Ce*m3bwthsroas{*WJjCgO`CaEOz>8zt9UjJF zsio%P?bi8u6c?8;a_bhheR`>)KTj_LW~-IYe8|>b+i&4=N!N#yX}qb09dvm1^%kKTzX>^XB5@4Rq4x8BW?!LfVTap59D6pUWW=LqW0B%Ub0?t|1~AwCmd z))URzZpm?##`6TRP|jR;NjPF{bOIn>?d;-c0CRqAo4DoCLKc&2vfjK{8fjX6I15XZU_?+Z{}s`CO3vEBe#NIdcM23 z2)y?mmOl6xbKn14=>4_l9<@flw9?uNJpHtXpZp|77}giJ+IUjGRA&mccyZo%8nJPh z8Q zPvl4`Gp5s6RHjElY06q<>&3X-7nV*ganZIes%*=RjOVs5fbwDNCl`csjAUtYkm^8; zrtjVaUVim8ge?WU@zU2aIdtE|1djaTqa^-PglFFU0Puiw`}W}0+EHg5myF!HjeRH2 z2-K^$cLTK1FhR%#l;Ht*{*AZcdofNvbr562LsjztfZb=#Vci!u1v>~*eybPVhUu>p z1O52u=#kuIA$kAUv+&~xyU(7-$c@|LL|z(mv^PVJcRV6-pP}|BzniwX9($3+wDV#e zy9b-2uN=>0$pBh_&oz-SkQg4y2(bCn%h-JB3dYt9;ncxKZso2|q_4)DB_`eF24c2E zNmv&j^+Z247iB3x< zYF#2S;@ynme4$&SYdQ5>WX&nprGK%ApS|)jJj6KsixcRYm`Uq^Fk^rad_)dCWzjwi zdz|;u($p3ck?ZeYVGjOp{tX_!eh$HRe+4byUVXpY6R9o7j(Pa#qZs$@HJ-+5bMGWn z?H=R`YyL(#n!i>HFVmEqS$=nMTicdPoE@upq`9xgD2m4z+Vub0eo8)$gAd1$*hZrS zwuJNxZ_1H#3yH<|(k(FTKQ?_Ci4POtjn>lUGPVGC&N@LJdely|lJiyc%ii$BU1C>{uyYoiFcvWpCPjFx9e?ov0ixV0!*G z20F5@36Y(CF`UPVo3CNGb3N8{tVc^wgfs{mwlnO#```w8i|yzvw5o8XGw%73L#eUY z)4K_KdpCh0b&^)#`}oG%LzO%eV>47rCO>0D7-{Rpnzlaha!4p0rTa0<=()^}Gyv39 z%mtQQCcPV)%KO~lwzNDXrg^4kv;&o7Jg9rYGKOxAsWXl2 zx9X`Dqv^Iux$W?_tnMj{G=%X0L1NN0J05_PP(5mq{Zm2|`OaLiD3rNiM3ZZ|a9b~s zGaYWlWHcw!o8eBpB%>LDCn!f%oD|=&RG(twMj8}A9xu7^mSUkNKcYwhETCc38H-R z?bOp}J&}$pUKU`hm8PAR9lts?c_P0I(%ugA^k7*#o%4#E#IPm1HJXInY{^-~SjUsj zV3W9LEzH!-d|ba}iFU%p&gb--8CKf3wl6NC^OJY6Ftiaf&;KgI{vqWWHWxLT_)?Ao zl)uEwW~tcXQ3?^X<)ww%CZ=JnB1miv@Ec)QuzoMn9%j|1oTz4WMPsFD`)tH)m(|Wg zGXmS5a+`9IVE~!W-KEMyj7h8d+u-WR@^ET1OA%+ZBDaRF7Eq5iCO6C<-qcAt(KPxq zaj0ew5}!(Z#1lSAzGfT~A!{wooRiSn;bvo9)9Isg(-uhDB08;=@vDsyZG3IkC2xF` z-UGs@<}`h<6yn7<-o#J8^$pCow$^-eQVQiVV$Vw_&gu~_iqSnijpJ{j8J1{}kIk{T!FKZNaBI zt8bFsa_KVGUcU)Maf+vj70IQsw$S@CSw^CR>_gQ?eB04kpAC^Iny%1%tXqfEBXOLT zpEf&0h?7kNk%!{a5|)bfzt2V`2tx$rFlDKcdQbemcr^7yy+-gVixqrPD# zNK7_sJE6x$`kXAb;E7GY!rN$p2Eg8~AnoCF5*?j1CpVf%L}KfsPXZ&psZQJWB9w~- zWivn9yItMh);lqYBkzBR!cquY!Y)rLlN-+xo|r5|@GIxR$g@8IlQ@G+w-2E&m6I?oOa3k$DRcMJays|thsduLBv>%mX%YDoA-N#6}{zY;jTr4+)t5)(7(YE zN4JkWeO!lGU7uMqB)W11`0@XT(*1Fi{>dLaYIUB-G9-(OR*zFZC#Jk=L;^vq(FeEt(-y47zQTV{6M# zztCs~F+TBhtX}9HSH=syNZa;du;oPh-Q>eAUx((a{9W2tx4*;nw$1cyFN!JEII-E% zSKf}V&KR-M?7Z1^)M#p1el8aMcBL(-ot}#q>+kf;=EWKZN<3w9SZO1YzoGihdbmp$ zSLPiV|0nmDx0sV2K>sR(}dsh zhIFp`(&7S69y*B0zI-(?#c~;Iuir$7#2Oa>ltIi@&QV1e8yUvAJ$oAB=oIJT z?wwdF6tVW|jS8}+OeK#{krOF*&nD3EU3# z=+211ue{SrJ1Jve({FW@DowP$UTxIfU3x4!lQfEY*L`>4|2fTShUEG=&Vp?45L zZcPISJ)-hi`vlnALH33gXUkjQ14OvBZWI@H?X0W5W6#54sRbV#dj$rh1pZerB=M0suI5=m2(}xq$w=6NrJdPsfnn zBC281N#7?%=uvWNMsoaK7(1GFKw~&tWIDCxqQ3+Z$H2*xz`y*LX#Fq$Yj`g|3$L}l zTLhoT>PSmVa_aVSB@Z9g;j4{uE?!eTziR2#@(b9%*Un#tswMfu=?#q1zS_8&#{kO1 zw5xj4k$KY%j` zm!E^aYyW|lrekw)cRg?@yESMJOg1~=Jfsab`G-t37GbK}{p^7yZ%?v;`4%ScjxEt&yG9?+7V|u z)^tZ_s4N|T+7ahA2J~E#V@Xpap$FuZFs^hYjEarYM4;W38a(PLP7RPXsrFQ!@;%8~ zOlpI!uo}2Kjvx$i?!aEmc6Q=XNnxps;X8M6;FD7*qksqjs2(ygk=a{AG(F}hMYNg;7g(X}2fprnaEJ@*l&r!VM9 z-%!~l4aT@#CM`Y5(NFa@Q==2PdEs;7VoWCe^<;%foMY${E^N1m&P~7BrIr?J0|+^` zVt8nKFo(iYxe}Y-1YfL;R9h+|oo60bYF@gd5?imG1e){$P$2;BMZ9dW8GTzymc#Ce zJdrF}vjzymWT*3^m+TgthakI1yMAV;Z<1x(wdHn8%eXG_lzou+*ueM~6GUCDm^%I)%x~G9T49ZO?TIHjF3HI!t%qGgjg5&UdseQ}6-{nKwy1z6%Cb&* zB&6k=dfbtdRsf@I>5|phB{tHw---T3;&vEMb(}2XsvVuIdv$RU?ApZG)=j4-Q_Sb^ zS)MF!>}s}V^$_TKM7P>(#|&v9aimViwgIN&OZG?k8$_DgPH?(}^Gr--qIDAqn>IkU zpahe0%qVr2!J%^u`>k?rk{?GY3gZ;$YCCPa21`=Co)pX@(* z8k2p!xUyw)-EsRSCvfbY_ta8XxwxFJNCtq8=~=w^#+&JN%Js<6_di6>#FSdFE$e}C zJ=eykJ9psnwk&*^jEcSmQC1>&u-mDFP#Ee|yjv&Pc2rBXUs zDHM+*E=Q!xR#w9oGH;Css9Nw znX>uv6>PuoDaw`URB8)cE~MH^1|!EdoA=6d?)X${If*O#s5}!-isWg;044J(BE}K` zI!h}^PbCaMr>F+IGV2vbcbn!w9ZupZ;uZWGEimMH5tDb4C6GF3+e*GJ8H4$(-Z-LpGejEF|CM}8(xJJF2vLg9 zl5jG8J@@0A#IKFIW<&l9HIH7=6DNb01sXqqjPFjyn`gAJ0ojweZ%_9_c-0% zUDtab9~{7^yLMp5g-_F^r-UqJUFfkO!pTDiF}7wn_nhQhdmAoo--^ihvHsfi%2RId zyr@6M?X@Ggw0$cccC^=37Aw!THY}7{K-+4mJ<(eSxNmZ4sddEZXYG$Pd#UuAa;SR5 zPSIY3~#!6@!W&%Xii#=`3>L86yAyAOJ~3K~&oauTrYjOSABh`*{}ra;Mv9+|`$f3E>kOEh8sH6J(O z!%JgH1muA?A||nj{mXd;J`7XyZ~ks>IZL#s5#IG~V&l1Id?IXMhHzml`lju#w$YN; zyLox_&HJ&DR-EyhEpF!Ms+HB?$15d`j(rWEv|Y`ZRr{^0)Q_h(d|#>SWvU;ewa|u_ zw)~cIb4fyN5^D{nXtIK*UTuJrh@4_4 zBg)2+fa&H-R}lL?F7B>x2c{{l^Yb|T;YVnlT@ZPZu}`jl4i?Ke{^r|w>uWDyv84rz zr4~drwsy77&jT^A@8oIpjZda;OzvSPm$4kWWLaek)GgN*FK4*CZngYVS=y{ps|55e zc-!#O#B?&yC8RsR{*$LsE*5ZmbR<{q&6L*pcyxaY;-NMRv>H)y6H?bTvr(8WswcbIXe( zl;#)Hl%vYKhoJ>6g631jLd4*c%E;DA=cQ{Qp}kl;7IhwCsig&RP)N&pYwak`@7bN% zF7};1gVF1^;Fm+tj=dP>_0L548KOnt{dqKzB7rLdY!iG*;H4dI{3ff58v;I&C(?Wg zf@HVz;$r=AYmrcQoW@A9iy*s5v8jtmM6@QZFy=(5lv-nRW8%WY01(YRz{rpOIil`9 zOuqDeENs}W!kUvYazT=|uks(DM9aVU zhLR+gLNP|yW3+1uB5&I=iLiVNrYk24hnsO(2i=xro>FZ3pB*-zm~pbwsMbzb&LO)} zuOW?o-306N+sHS%cWfKbg4l;8&J?`Z)H+dw`dOy0B*# zZm#2#bWM5g?RU}oa1Mo~5QAg)5QHH<-@Yy1s|C`H%uy^aS7wwOSL#ll92U%%@%2}K zh5!-Xf9}~_o3W3-^)@=EW(3lgJRD;AE}iBS;q3msxUqg+u5!@g(CZu4)brP@#;?j0Pj723=cY1ZbE72g^SpD`6}XA@?X=-#cxS^zNq)qXi;0nN5(Y-AYc_h)moUFR-f^v2CfON;>opu0MfUXh%6XHI(Rsaeg@%u=zw?uF0= zgeYPO69awt+p}t3PA!-mo^+#nE{K!Y zsIKc>s4XS-Je=RN8=vmnfzj(XvHkq#VDChfwqCi_m}*>)QS=rxO3Lc1E`Do1`=#K( zKlup;zxW*ScfSpM=hq&!HczC9(l}l;rFu^=`42zO$B*T6>C-YpWaUeFXK`!(U5_@D zkM@?k%c*U;-X!FyXA6#@amP-eB$ome+C&~57)>ir$O@D^TQYE9OFqF3}x7NuNM%eVthr~a2uI{w6@STf| zSL3m(!~L>ye>C|%x-vH=Sv4j59Q}>qIi9<|YnvePl*WA8*F|>0++fJh3B@+&CFys;?Kf){h$XNp>^ScYD?DCq3-=KrD*8CTdk=1pj?{f4)@)}du5Q@`09b$RdgXm2e2?0Qj|dMt+Us6? zo+V>zhS2`tAx3W8PFaqR5Ht%Y`7_eL(l5h@Bjv}@GL2e2wHBUn`$egzm^$&O$6hJg z2t{|VQQ3)wnhRg4^#)5J*4(^<(BrvY(x!WI8a-1}!V)C+9eIcmc^9!*D#6tk5yu$5 zbr*HE+;)Lh4+Qy(85#FcHE8|q8rLj$U1%-o{}hVrCff%fIXV4)W8*qp-Mk62UCTQ>aH78ti>)mw&Y&%Ga>2P-2AfN| zbyo*Zc)-2k!KN>?6?FHHz+t<+)$z~EZx3c3h$H|*+wK(#3)}lE*SmIzn zk4YL=m^hllNleXiG;%AG^jn&TV(@sUeTT`$H942E_47+;eK=RaK{4nk&ImqC3r*fe zUdLm5CnUB`(&67=y$|!&0`}1Yd=!VYzb;>k$;p{N%b41ClZCaI)0@25ObhCHUQX_M z=Hlaans(Y>CCTz(*CW=V?K}=Py8*b>(BZPlb1lgNdG4?p?8!K69BQ2;W;zC4Wu`{Y zrh*!20$;Tu(P`;gksU#H?jZZX=T1?LYgm&^?^9q&Dv-_eiY%w*WX02 zSQa(Qlix{gB}B_di09sT7rqza7ssB)y}`k%X+QtgJ18zJ0+FYNoJbgQQ|O%n9%$;$ z><2DmCk-}4xa9eA451rvNVs1ub$ieu63tV2vG@%7J&xhU%bQHBSAsCa3$MS0U@=TD zX9{6%8`0EAyZHdK?@NcC-Z7^CN}Hq?!$9PT^mz=gvg6sb2z*)#IS3QLlDH~j%hCYS z21*wK+fKdknLt*0b*QiH?$vFZ@c9nC2qg$ZeB;%h!V4pKQ3Q4$ktWmzRq!*DEbb^1x>sP`TJCfHaf@ zZl;q%3O}dxWG~Y_PJ*OrfGJP-C-OuZku__8qenfw^UmtIcB+%)`~=yRj%jbr-%P^9 z8rgYNbA)B-o=vc`u`R`xzxh!acYpFD3=FKp!pq;o(#S@@h$o$o<|1vqsVJ_DE#@gd zF0R03=hVp}(wVsAJg0?Iw!N2ch$o`iauQCiZu!`T@+ZCFl2Ev|#-?r5IdS{ZC&e&s zx81%noP49KCxw&Cob0w}6Xoi5UQ08G@#>8kD{WEoj(_e@wRv*h-*i6G;U)VthcWr3 zY;`g}?&lh(=|$QS?`ce^d8XXVM`syjISr{LbMC&#U*cn%vrFca^h9Zuyi`k?1m)AQ zJ)p9P*gTxD5kU%mn_it*Xb?aq2MB?v>bEH0*2limSuU!e`0^d0bGptP`nkDfh>xtyNuQwI*f zk0b0ndl9|k6X2F9u`TnMGY9tJ*4j~&3-z4|5C#FlAVBNfd|D3P!dpgMxt)p;cT)d6 zsxS(-TVj2-j>qeI?3>MTIR(uT?WsWdT=#m(Go!SZ72pBz<76Sek7z{=DiVhjP{y?_8*y{}IxH27Rc}?hxO*qAY~76ETX(VL zv&)sI$rLkfW9A-BpM24lO^ybm6jEC(au^v zkyL^JIDXv22Oq?kpI=^Dns4R_-xx2>$}5W>yGL8EN|@UD*DKZQ#TGX1PPiV8%Ybg;&fzUhDx@Pkt@|OFUY3zbO}Y#)-|3_ z(wLN=NPh@aI6@`T|1Ei}^m3S+;`QQe7@;A4H@R^&UTjJ=_V4;#OLmWOwXQ}+jMejs z)t1L`%riM_^|0BTTmNSEN%`IGuaZ;izcvn(n>&2*Pvcs>AzIJXN4_$`KTeqMb6fkn@7TRYYf{=A`I1=$TvI}I7q)$LEkSSC!h@wrOL{G_z!;s|#1QY=#%dSo_6IgrM2$%0|@TA&d_U zG_7pYJw2Eh=)>9@H`CFA@1X+B*-9zQRI|{7+b5YNdBT|(!9)wLRApT9CDQ^ao*yK3 z5s9{@bKv$z>BR8M5!PP4sq$f;N}!Me)zskad%`wo-C`h($J|*S*X3GvZT?HNuxE<;mHGPufg9Di9?rKs~99SH=eiFfcZbzOe~wY$6@A zJ+Z7md$`#8yQLZP1YbfK8v{Q15im0Y{O<1pd-fzJQazE!Ue>JfP%6ckngZ_LUH$y4 z_n5}`cdc~m^$)N%jj$5N4|*h)>1rI!;mvhLjEU)a0EwCHbw|luQ8K@CYuzXwwznzU zJm1=i>zjCkh3`cu%`ISX>>j!&rz_edvqik6IZDTWIw-@Q|KZsO=GN?|WUpotlDB3` zzTvBPWqUJi<}JsXSbeuWojl*BQLlhXw!h#1%OF2xs1d!a!=f4=I#%fu33B3=>b^U z5bTR8M#WdL$Yp0Qq)AQ_)B5Y0mrgf3RX;VQiL}fu;A^kFfj3`%v96uQ&%gZ+Ivza0 z$wLQmXU&@2@mNn!>=R8Er!qa@Q?xc-xr&X~uHoL$AU-~FsIELp3k&$#&)z_=6sGw^ z;A@$=7Gg!U-hKYLTsv0ZeCb61z~K*1VBp?(YWzIJpryPXytFjQJ7s4Ey<1HMrJL4w zgt3L7xjh(U#WS6y@|y=QBb-SEXb_=x6;<{&1uz#t$SJ+#{q8?`8ijHhUu@ivS*~VE zX<-2`{p@x4OLQuMNvK^GPEVU^qO7O3*_?CYK772I^MjoI#{JJTKsY@64Z4YX6C-X^WTi#u~z?d0{+_ePs;seGY& zm&rf*4Dhh$)H%cj50|%X!To-FBWhu(jDsJaRO6737&q6gt-3H`*ZB(=y?zUYg)-#n zV7&byuzHzZf=y*LeRNWL>PfsvgzQUz@c(D;O@rh}vNN&IBl4)qx=+-7pin^JzWPE> z_jJ!p4~Iie52+=G*OJo8jAoQ%MyIG4C}!Xl^NmTSGYfa z-+RxWW9r}_W`+i^ohp8G_)cvtc4}*pNhAOPjEvvS<48VI)eWGpOmv!b^ z0oAzRARCXD75Ur|!aI`sixbCi=!!}}o@EWW{6;*HOHnqKI@)mO z$Y`Xf`%y{i8@R5ETy(hhP6mvi{)q=R zu|^mtP5@=-H1_H7kPzE=X9JLhDCy}ajk2( zZh-ipZkbX4>N20BT~{|T(~8ICMmLxaD`BPhdrkPpQ*|h49v0Rs^0}*9c~rik zTZHua?+MBwj+mN$IB5YOKcCg;mh>gYuwOs<37(M82 zo=e8iu(pnd^-VOaZRAtY$um+W;}R9=1xW^vA&2FTR!ofyVmU&Po5hX}EOvCDX>|>z zWuyJ!BBZ?Paw;kJaehKJGZQuz4|GJ5_bZ`HB7wVyM$kVw4a1fjzjb%M(;<$4t zTHu9h5MOhIr~M3G=VaPwGQi%o4LoiVD+>_U-vX8{0l)Wqz}VQn!}c>o2M)N7+tbs) z!-wTd>V7O#EsA3O(=oHWPC0}>{(jqs6Y!m{hlTSF;-|74z7p!%VzNnbjIDnx z7{bPb-flp+8x)J3z%V`FZn)d3ufx#9WL_2)kg~8#MqVON<6Z}?45Y1;p<)P!!^@2} zknxrauMAqx`3k5bZ}mNd$!YYYVEHNh}1z*_!a3wx(c3UnxLVqE9caSuU}K636gL5ZblcqCoi-hbsNQXoNhGQe1&fvm(AHaZv%V*Dc zh9#Y9(rLW#;m5EcP`jOmVOuzM^#;tGRq(iIo%*L{Fmn42YoSz;ssPAgFTaGf=B7vyprrx(^V6pg zvvL@oxQCwUImkmAq;l4T<*88o3T9HILjMM|qZZ z^zg-rtLXSrPH@w0Uk)bBoP~q8?qXQocG;XM(yQq#%~@_ zdyuZ`b5RA;Wd5dOpe@8;;lr0-at+T=`JV%zd1Vc!u6z#Za4ors9??J^z9DNyn?Ojx z5L9PfG~rIrayG`012@~}VzEfh8Zyo0^Jj4K%2l*3EknRP#vLAjHX)LEz($pDb7o zAJNeOvd&`*fnq<97TPcU=|bscE&0`8Sf(oyiGQnnM*bgPUq<`8e-1N~#-lfW4OVLh zgrPbt5kMyS!XKTHyFA%mx)^c@Qf~8B&|Pxc6p*l0t|}5fOIg7IZCoRnfwxq6-yIKb zliQN&%*PGb^mYiGs&JU1c&n+vTEhF8%kTauG~r-ZA7f!-M3tWWc|>#E4yUKT7Ca8M zShRAVZo8vk=?Hx^5okxScP`3Fa8P&Y`<_jY5Yt;OG`j)SoqH(^>XCQ&s3yvEY8Th>+8 zGpsi?U}mr%R?Ni11K|pQpi2~{ zWubjx5z;YC&fi2jgSMqdUcbmX%6vN)77^Rc`Hpl}f9u?Uw~4n_M%h<4)T;7@y5ZS` z8zHPz!|hIOEoKM$ARGq=?@Z)-%z_0e5y-zX9<-DtT#QB=ZFO0Ta52aDyd6uO?YQ6H zTT*?4$UV+E34wJs=I#83cf+d}VNY^`^J^zmek=d(rfRBU%;&V+){2?Ie)LVvdNnZf zn_l$whEp+_U%sPin9|Cb_j`qG8(3Iy|KdkKf|$Dt@y6@GOD{d`s_jz%wYOKt=3kwW zFG)Af`OBh|>RPAg;D07qvJS#7JXf`CI&X+hTqCRM3Dvwg4^nMG`X(IO^v7*2(kj9E znI4~U{KzQM$s_=Q?zwriE-mM!SCXLs_e4!{7bFxbS7crDDP=JJUCO@{#)VumxwNC3 ze*H*OmuJGi@lg`=gic&L;>X35tDal1tQQRv^VaGzPEZY>HXg1vJ#L)a)C3$pEKo*V zrcmO%u6jIA$Gu#()3Gp5PqI@GUgolvYDMJE&knX5QkWSTC>lL_aB2!24;B&M&7y97 z6C|nHSZi&9ZMwF%`~7_d^O_nO1ORl;&Ew$s1Zp?7^DTB!gbD6EA~*H%6Jw|?Q$x`l zwmGdeH{tft!$?>eG(B1cg&0zCI_VzWI<2&|;O5v^QD>ZLkRt?^+uP8(_z1$HP3Q(3 zWRnT3wNy_w-cF@(^XM23%st2l>r!z=F}9EchL^L%CaO+c+O|1%QlEi0Y7Orh!E%JJ40=Y_ zvT@5Qmq55gVX$2NIuO}kI-lYjMJ5g%teWm=v!Nb4b+t%rWmuVR`EK-W@?+p~LYSmU z5{*nt^?%gfR#Gs7D5UqFE_bSODUB>O54D~_a#JC)(izOXdkx}v7o3Slz;+fb$NN#= z-%&#S{XMGMC%Cml-uDLu+b5#L`YLL!{RFAIKLLL8Tfm!dKJ6;)Q<+p#l|tvHG(jK6vLL1h=h;ZdG1M&%#|U6$c^Tb1SgI!UfemFc+6Ny?>;2`qQC;l{~h zB?XWL+zm&L5a^wmg_*Tbzq$pEmTh)&ENKsdBmsAolaAifVOp+&QuYuaS8!MU2(w89 zy-glSi0n#w&-&4=j(qug07yB(Pkwoeeyg&UA9Kq!QhhcIv#X^>_fvcpbheKhYgg>F ztqz@_?o=nRt~As05x(^9aCboajrsGc(BzMJpo_{R@apkuRV5t<hvADhN3cq1MZ%rMgZqL0%f`Tt>j7JgCY=0dADBmGUIgq~WZ2<@esNLLw z0SCuFzvdZ!btYukHtIJwy_N#5BX>NT4eZA-N@Oyq+1<^9TZ+*JI4sJPe1mR_VmS+0 z$HA?!BazBT*VN$F*b$ul^fLyc^@v2&$5uRsPo6u6wdSUhkH3+?J-zJPJFt{O=xoQebN(j2# zJGHg=;`mX-GgNveEtm9nxbvE2%}6Q zflT_o@16hvAOJ~3K~y4v-DDCDfMcKE@XD0`{B=|7C|5PU_W9?eDlqY@{$Iu0Q>}Ub zB+0gc%}v1B>(bgj0dS9mu0~*la=~UW6$i+Ad4)i?3XAkS)wLjM`O&FR9>mL&%MZ}} z@%Lcv?%>hazJqN00T_l0O;z4RT-P5lh^v$>-{wI1J4k+ab9C>JJjvG^;((GLaxhF$ zfQVzNTi1v$TC6SZd!uM(y5bn1cPne+mzVr<7R7+^8=ZO2`}+Xe6T#@m4}rss*}+C? zSvQ`mqooPw{o$j%5WJ5{dy#cN$#t+ePA(@;Zdg#u;5b;mR` z9zf|_lIi?vI(m}NL_^7+Z=7~dYq>Wv4BK!qLD$>^)NO2gE#pyIZ7*tqocF5vi=05+ zztaZ?k&DM5;9#+{BXAS4a2&*QISAW9@63H9w|ABMQi11|;Fd2pwaCv}b0elkhVY=f ztHd`PjdHOVW(N9U<}3`|orK8RklSfp3~6Dft`-max?#o4vQI5qYHx?I9Sn%KEDIg}4`?O(NBZ6~;fqo+(6yQ>pTV zU~2`ff&SU(UXwupC~6gLX66QV%WI2t^ES}5w1y_EvN{r3`P0hWT-!i*Rx~`igf@WPIX+8Y8XTb;%M5YOhj0nVH z0RH4pV7%}G@Y)5S>+!5H`&2m%3VXYu+6P#x_DlVV= zn2fJ0oZsos0XiS_>kDb^QRQJ;iwOVvKkLm+czB@GSI3#bes3e&Zfz0}K-=OY@H0Fm zg0&&H0FrdhTQ0FD*CN_%?S*H@kwlRs`MVO3(YN`AW!^_>EBw-uOiSN5$JQ+X^6lt2 zm1H-bmmjg~=^S=N_D&EcE*}p++eBKR$4@OSz`=vnb=WROBA|uAGEfjN(68z8h#aj! zdNLI^(@gYl29|+sWU!cYss?wDj9{Uwct=eQ4q|F>5FHDP7`uKGHQQ;}Fc3oyH%=YJ zR*9#g%=dJ|uxy;Ta+S5ifaE)}2lN0vvR&JCDdb}1xeIJI)Z_BmGkET!i>Te)hT+Km zGV)xA@nzx4j#ti}M!KfDj+$X)nI|JA3@2^H8A@4F7{kGva#&DVkPj|8>BNP8(+|> z!F8(svyfzulIxW_%G^y+T!*XHk_Rmjkecb>9&jM?7}<|!3$;jSzf9>H|jGkm9ClcmrbdIwO?W76smLd_Ne;0AlxrlI$gIX%i>sF zl>#^h5Au)7hmkdb)%F&A`rP@5_4dDZr)LDnvQE#a77Gu(``k%RgMea(rU4dUTb3)Ln3t zY_%rvCZJFpN#qV|HEN+Q*h}cFMjzv@)^Zw=tEJ4puu_q?!4KYe-5tQoMLKrc>^hH0 zB$-hC+NSS4tT#7e;-Gts)a3Ax?;Wm{cx>lF*8yzTrO>dpfx)|ztj_>xa#Y)CW3#Cq zx5kcOwWT>y8M#;ti=7>~a`rTiU%d_^Cu3OA|FV7Q+9YltKT@$VZabC2^w0nt2=q

7au=nq%G+Sw> zzF$ZQcIH+^v3=U7y+buM!0FQhpMUOD0dy=hU$=PFAivXg5SMam zB+DR4l}3N0ROT`SSWbYHR{7p+*%Ja3WsLWYE)`M!q!tf*m(;)XKUbrx z@LYZ8I=~Kg$cFMn5bq~Rims>%9VZ~4u>1ZN`tJqx$g{fUJSkw!sTw8v6=Y7}_3$!P ztSk{Fmyi5dRmaS_tET%mmyBb+tHUdo8$e_&Q(IeTSz3XNYT#%%R=~!3OCvTK8^Pa_ zZ5o&uJ?L#-%qHU)yf=-yjZH}BZ$bzh`Abx-8qq0=n2nj?e(coN7VLLN2=8cQD`uj9 zat1Y9X|I1AR*Kr!w8?R!x$&_%Y)i5Y0~3c1qHlTziEIX>lW=R7uB*k}(UFSFS?ug^ z$AyD@8so_BkP29`3h1|4t8HjqD-i~TqP~WxQ4g(HW zTU)ReQU4T$7P=3h<U2`ug0zySsSePTN43bT28IDJ%%< z7S6Zuvtcz+e+NnJL2G}|Z-=Gl{95PTemy65-c~m!Qb>>G&NifLlMryQ+SY=(p28=I zE_Jj601U@Q%hIw^X9qkAsESAVI;^jpToWp>Ge6^xpGqU6ajSfnB872HzN)!U*FbKb zRokH26I2|_+ok3aj#0xfsb60jrY8-;)j$38_;GGq8&F>lw6zIz7x$;D8kM3C3`;NN zq2SS=juMWAxt!$&(#m=KggcpV-I)mscFe@J(?UmH|Ct^BUm zRBi*H6-Kov3XmmEZdsBc1}Jy=S4F^T=sp$0hv99Vf}FE0=o&b9oI~Y2vOKAG66`m; z>pUk}uc(yG^V@SQ7v=>GUS-^TZT?Vkei(gFeM zr1w=&{{>0YG@62QeUcO`$31~^Eemyb$03&2Fn9h9m>15Wa*gReJ#A`j15G*Uu7lHa(9`?Vs&b6VX9!<%UJgLx>pT!Iw?9ie4c|Cu zz{Xm0GcG>=TuAFmCm9}vR({*ZdnjBi4=`pcK}-k%*m*oIy{~9mj28Szhg4T?%nW1V`; zPTOIxBpO%=W(H(j3i{3kM885#-NR@yvDr{WX!QtD-SL@=p8!0z!k;iSk-U)8ww!jd z1@cJ=L1ullkVnA^ zuhmN(?O5t;!%iwy)!m$%4fWV;s7KC>;o#kgeC^3}$r-#G>7o&nqr;wJG%8u9iMie$ zn3jb@x9%Xmn+2&902!Ulj@LxmB_D;h>g%x9(uDrWX$C3%U`1D02P+aB_FlPp*nNUi zxyCH6(&bUYgpx+EGS%oB+;k`1tpGqesk<}GgzL^_cz;PP?bacl&Z2jE7G^G|El@zm z!$qXFC<-6)W7LkBumnGfOs#YM#%BJ=N`Wk5a3J!r5x9%B>6_y!hoZL1t8yO76#Qw! zbAF>}`I%$_i=D-fM&e`}1|IZuA#P=S;p1(&T{ZfnJZ zyc0=ccNZgfCg4EAT03v~*b%Q(7jt8GZ&N{a8Gw?a~u+P9>T z=WT$OLY0~b#`1CGm#p|5K8A_o^Zev*)xhj8Hz=L%s9oG~Tg^{x?N8$x^EAM9bW-PW zA%$Cz{4bP`dS6%C^E`CfPClnQZj+-5k5ui>`%Fy&^L(V2PT6fUA;yU`u z_`w1;)>@j8NhUDg*Ig7}%?|WK02rE>L~3)J^`I-WN)99Yf;OAD5zh?RFbp@ccBx0} zO%4x1I1c)!W>B-W1L5Iu>S0~quw9?3$k<&fJ?dyj$NWPW8FHgFv@uXAJ?!j6a%UIK zk5)h!A{yDYjp+yT=sVDbScLxPn9Vkhcq~p_Iaw@aVL2cOWAfGBAJ4+& z*nC}~-*P>Zr%!OztLy<<$7Rd8-hlIauE{dIk^vRFy2N!)Y77)rm9EC%=WgRLHdaI-%QUgr)rr=Jk05Lpp^-`7@N{3r#xmX4$05Cq2i*s- z@I=B+Iw9ZHYr^-JsD5)3jce!QCF>NII@)0y28LpjFme`J zmR113TZOo;T}Ae8Dw6Wu4bL((1efA@xEG15`A%f^8#EiL%y!i#wEgOBj;>#vo4n$diBHx>>YK;7mR zF1+^vxZ8+|v7}ba284t6zx*ZaR4M8;MNqUnZYu58+YNR2_>~tbcGw1h<+U|@|HBXP ztKax0M8y33dXnO^>Dt{pxOn|q$@QybY&&n=hSUBbP{e6_uD1u-SRAJ>UMah*;xk6& z-%<5!L3~>;*G)%Ujax6(;2Z8*MjPkp)HfM43G6o@U?P{dEy}bK56V(aZ=O?a)E3LK z4YrO2>E{6Tgew)96GqlCvu?rk_pFMap_T3SiisF3-;+V~_D4U#{Nf_cA3K3lhl`(P z9c>JkrcZX@_LUj2&N{tx@)RHh#-}FnZ%c)#DDQJLyD3dI?Rc^riA@1`>kjGc9mL>3)p6_E zb?K`{)@RuhizzO`WGXT}_tVfF_ zhZBDkF-k+CvmQZ=E2-QZq+l+cPWf(Yq14AE%QP`HJO~E@y)&~&>}K;5-GK1o;_5;? zEgF7hVm=b00Za`K07779uwQZ7=9I`}U^p&Q8JL=Zk>!W#0n#lSK;DVm24F(u9c^9s zV`HtQ5mUoMq3^d++OA9Cet$2zXXYTCA!Q$U4%;n_m^wIAk+E!MpdY4XVesA*lH0qW z!-(CZ&F&BMRZ#Ny-eG0xODUg?^dya4d2oar zS1zL_XA8OSiOBTwkigp9wb6HPR%wG|_*UMLLIKn{2Ltz}At5`jyPT0Z#Mm4bu=2mv zs9|9->~)T%f@pQ_b0|(G@2!S<%=H$I(o%?K`uky6HU=i9QL~-S?|ydG`O-M8IzOv? zSFjHNUm8_e>9%XPrUv)>sxv26T3hj`a}BKzmqBL=Sdi||LA^{h<)VrtfBhd9WfBR@ z^!MY?t#JsZ?4drTx=1w=cM@=X-z7%~iyR|U@6$f*U2>1`1{?>NodweACtH4{2I?Si zUQ7j937`+km-7%RAzZeOZLT49`90+BUdQ^&Ka2I#U-pc_!TelxaOAt4^;cjU3{x#|s-a~5#VNC!!Q21lFY&b(FQE6iBZ$`*b_NiEV>n9Ps?V?V zJUKrHxEd4M6|OYp3SqkADBs;&`I$q~U7NHrWQvy2#e|oJ&Ys}pjssJvw;Zp**osRV z!WR`xStv!j|W9N|SX+=C9$4)wpmd0@B=^!jCl>2&m|9AJ@SYAHebMvs` zCa#@4QLwIa?_9;*nHiwF5xf8U2M~sV?_B+#qcqdkhGN%>{oV@{jLn}QZEpjA@CS&! z_UjNo_f4Rs?&;NKpGu;E0YC_W@o@*++r`s|QMp*Num&j_E>@oiUTcE!Y+*Z4F>)Xs zt%CT7UORn#2~N+`>Ka|S)=~sr%iFZL-B5>Iyu7$a%WbV#ZfiwqYa3@ST}J)drYDKZ zpfq|b2s6sxT&Cx%IYkEL`U9>fmFIHsTvgIF`)aSz`lv_u;<#9*Gr->o)tJ&yiM*6> z$8A3*rV>l#&Ee_yJ`R2wYfxjOtJ^CinmwLcMeF%6K2nVLs2Ewt;eLA#e~v#d$0c{@ zwhg0fXJkhRY}VJ~{V#tB*+ls#89740GELY9IjE{~xN2v~)FkoAh3Ap3sX@8Xy*b&2 zfe&7J8RtI!6sgUfyzSE^Ip52{Ox z z%}rqS@QYYKGzzCm>(D;!4XUpPUU@~}{r4+7`B_pWcHYAH8|?1WLK^lk5aKIW+B`TL@At-oz5v9PV$ zkH>@W^J`H?`s3sM!KLjzn{i7EaOR94r|qa!thNGOEjI`%sAUIPj z%jCcrgJiXQ3X?;+h4q%E{E^m=kGAUTFg-Yc-kDjiPL9VUU1jQOTMHJtE01n8IXncz zvC%g+8<^`l009SgjvPX^z%is;&NOWsy|edWW^zoL zm1H0WONlq;uc5k18J?Wrrk3vDZf-WnG@`C?T(!+Xv}&qT*F>3CH+bl33!yy04SDK# z;xdD3lnBZVT7GmTDm_g#(37TTalI;)FX&u`M+pqdv-sRs)6hv&GFmn90y}PEcCZiQ zhespVceSM%AAad2Br+Mi{NoRh+}XvIGpEanKsMXohuQu#d+XO5x#`{>5KlDz}a!zw-?=)YV~Pb{22G_IgOY{rRdfXP1E=c%6gV7Od%gGPKw6uCOh{mLCG&{VrnvxY_K;hG?i=X9*hzw5HCUIWhGbzLT1 zSAVOx7f??`lr{!wCqn*rrZ$NyXHR3jLfgl7T?!Xpcn)8A>xVELxo*3wEpHuJwrCY{ zuiH#Q=VwyNn#u^?rnj=nbwgd*xKAzDC8Z@ zg}`=Qb;^{qol3zmxRWdOZ{7Ab&Rx8O&(5DMXuICp*};!K{RD5k^fErU{27jojG&{X z6}KkuVSH)|2in>&+}j7IHjd5TItjb3bVqkJa$-0o6A9ENlW0FVjF-OlH5jAqFe5np zIm+mbKA&sa8&T69ea&$~zU$f`|9w9ZcC9}D37?nTGDfM9AEn5z*`%A5XGj%_nFh}~3*-ah&(l;4D#P& zlM41JeU79`I?aH1sKogyPw{IiqV^@vhtCjwB~)ueaWU9QXTsF<;>56KVV&x;Ke|$!XMV zr8Oap4wZ)24q4}%r?%UvslkmCrSC?$b@T`f$42-4dBk>e`B>Vr?3ltpr6GT#sS$Ta zNAR$-wBrHGp%q&D(J3H9g z*+FM(Ytgjnni{M&H=|+IJttEKeOy7L16FRZE5zu^F+hc}M$YCr$d-$QUMgQQbOW$d z#*$i`VsBD;1lYOjwBxxVtHx#(2utwJ|AwbmRd4)o4j!jZJtBku=3t+rnZGb)xaDH#ebSV-xY6tkNp!2pt6F!bL+avXJ6{f2v7gLLa{`9TNB`^$V$P zYq;ShstI^&XB&^!)_|=naPuKx2=smJG>k;yrP42Ss@IA5I_9tcvrJJTMmaobpPp@M zZ3T9AfZg5l^C)I;DUXUlj_|Vms@(8r-TPr>1RI@%mLlkRdClD3MAPLTq2;6RA=5p8 z%~yUte=sXIHc_7Pnt`zO$zd|FwvjPmV6nRs*H4Da#bI>w*cgQ4AhorP)W&vxo#O4~ zTqF$6yApxrDNo_8!Gkr|Lq*#XM43ba?|k)jy#Dq(Wj)X7QF|LMJ%0`_zW1RgsY)49h6VY z+g`+?Vr9tQjT$vf2*9jKK$sR_Jihr_ssSy!dR#}n`jLWR`H?!6($X)vC7-KblI|M1dlRTeDN7}lC!{rfvB(%<(MstKY1Q!>gy3VWBBmu6?C*LZ z%;Pvnt}I~iM}GqGd%x#~klLqbl7w)L$##Wmv`TPsG)y8>7O#i zrR=iwWg$lZnH7{0>s6Q}ZPmI3_at#6Xf3-Z`IePg)qc#}pMt9sU zWnGA-F{&;-tu;#s_mfNlU-^otAmDQKdMk|I`KuNrfvV~GDAh+tP(*){hUMR&fHS(W81nFv!Wtv!RX@L-OHaVUQ9Hc8OM4Q{&`1smY0It(#ZL$W}@7zH{ zeH{k6$lkrPyNjP(xeNd}v%QUaP+v}Lt>Mz@0$SrSe4WLz`SiwhtZi=k%FO1nxc~4W z-o5wTBkUG+XNB{l`R^GaXwd1|m{hhDlOV2-t4`P=f;?eq^_^J9fi&1xb z2kI|8hwhGOc5tq(3D(|JlgI+-cq5kXaUCUm*MqQ-6Yxx-J}P{V+?axNt$w|xx&}~s zN(V^IuI*uAvd_vlN)A(`!5~{FK=WE%rT7d9YGtr2!tomC9`tTV3JKPE2l26DW3!Yo z3;?Z7&A@5*#5-$q1GUKr(cHCGsibq*u;+u?&ZV%&F+X(epyY(SF2R~r($(ncNTXs{ z4o+UViZ6~It*WCT01Qq}p<`hYbfTHM&Crjtb;+D-VW6bbvAC+038$#ijOGNO>3?|Zgz^fURP4btc{Dm(S zFEL0;iL!o_i^YH1sjm+>cu;`H1}N`rw-PCM;s?JLKS)*$V!E2j53_V-oGJ$Dj@!~e z&5ypbk|yT+yD@&Gcoe7yU0rz4)rF?jHJrF|4XKSS*Z^Y4Vy8ZZTgS(+(h~h>rpe(U zI6`3P?mfhJvP#=cCTyuk+2;*WF#}r_DDl5Ib`%Z-x@YGQ%UE#o#x0?hBLHmIr*P}& z5j<*dE4#c>XsfOcS5BY8>uhjISHPkjrdDmn+xA%C6AXLg03RiP`7qb+}_ z%$YNInJ;JmvP2$bTkc|VRm#%Qz){MT^H<;5tdevu)A>T7KIG2Y@?$YDMA1ytSm*+3 z)Dpf(>p}{(n4tPxe{aPN&h- z&;ZAAu)Ma0=Elarhy;F>Msd|dQ2od?-k*0NT3T7frJFZ^*)`<;**jRhIfLJt|2L>< zD=V~!SGQsb4({JaMS!^+pzK$j22t_Z!TCwB5;eS> z;5tWDiE*WHa2@OJTt?^He~Rtl<5>Ke-$b^(J5ZKZRgr#PYiKK>JQiAR)U)HR!}hh4 zCwz5?N?#m53II4Xeh0mi_hIhlKqq0?o}3GSt(e>ijJ69=%_*KXyp{m8K9E|LEBZNN zfRe^f9O7~~?1!vs&b&2zbrtX%m1Qnr@)*A_+t16@pDQL4hTr$|_v)@6)uSf~@JlU8 zPhYO0uM!2CyvEH8!Ms3K;mfo(1WZsYT{Y+O>Bq0V0xRNipoK`lK@3)&a|H7=!#lgD zIy5yjh@2V2v8&hfGewOaTg{pB-M9V*TmSGc@Wwy;9rV3%ruYL&J)+Usv7<2Gx{FW$ z=+BY+?;L#N})uNPasmE_l|1kg{-cUUHoQm{?c8?UiHXG?dSi01=QQiy<>T^}i zNp4aGR7ZDyth3{#k}k%CtPO7iG9Vo-=*$Wov-#VluMLIUsv>6{QBr+KLj=XeEyy&e z_l~OTD2|sD+RDKGFaKZQ<*&J6D4rrkL93iDoIaCxf)Y41FaS}&BTDDi(aP0T?1b?B zrjzK@)!u<`g+v6`$qD%m==Co4)_Glv_c1pq{50Xz)Wb>iz5S<1rQ^Uq_y<6>97p%* ziBoScV44D#E{@+)7)jh;5BRQ?N!yeHRY)s~^!hxp3I&yg_LZ!2!#y{~+w z;K@>@QYMkW58n7HzVz;okw|BidmO#eRz!dw(d>9Aj^c{CX@=X37 zbqvc_bm}$Xl@b)?i>}hs9Q$%y8y@9L?HRv*w-6o< zvA>@~vb6!z^K+=Jse$7-s86M^u(X8!u5R3&nFauSe`6CZmXk;10t@MFtmo1gt3ROB zr@5g4@mLH~^K%eFC{Ex9+S>8i7dLS9)w4()90Z!{u+!6um4mHF^ta(aTN`>i58#8# zpGEEu{-#TzhPpa5l!QHWlxCo7egWxJEfzaEN-jT)npRfPJ3XsmHaeLw2v3A-nYf%D z%>o$3az|@}x)#vv<|j1MdZIo{A3A#xUM_YXS(Dz@l@4?rm<|3`R9!Kzvx-Gj-I^|O zfTah3Ad4*bQ~~(7D1?U9cMyc-*O%+9!P2VFI3WFq zoFBdS=a5MzvD{WX7+xtvj?di2pz1k-Nyo10J2e~|2j(B(_L0L?t?$6pH2NoJklNh# zHt*T2&eB%G>k=ec2hDN*&Q#5@PQ~P*$0aCKFJCjgiT11S;=o6LfyHybgrzgDAk)xP zwfy&K?~!2uJv~4!Cy>hlv$GD?*DK3Y*Qb`B&)(KjNh}s*+lXqH^5+O}Z6q`0Q{S0ml(IG=2w0E(cfV&bL%=;UZg(uP34_-e*+GRNvvN^poWo+e1vp=bS1 z6?=;+a)0*i(v{HgFi=}7(AEa%hq*m=r|r@dagOrKCBG3W+<>hs-zXoE)vLAkE3SbRP@9{jc%%sUP8&ul(U-D@P?= zU0uE9pDS+V|Ee-oWwS0xgR`s~U-D%x6f2$f2}x+}LR8eyBYN@rFVB>*)|gKIO4JBEZbiOMHvfU z6eVbOxlWLBvQ(OTxPYtUoT!wbmHnsijygw9Qmpz zSHs25${e;i-5EUu*uc>EWFDMylLEZjN+&lu(E^?uCO-v(oZ#dtM~ZqGdt07X!wuQG zx?4Bpsi=fx8IsBMoyfYJD+@vk^TWZT3dx_7&tk4 z7!Q_~@ZP0QQIkyI&DXwyOg4+`@4Nu#P_zxwoZCkw(=-wL@(B74*5XTNit7;66{Upo zgg~M>nt|IgO?>d`%Q*YdB_y{q$_OoFq%2Ul@@&}ssKk|>eBS8>=pcort|X;3hadSY zW5%1HIjp)#OSHykuz_&ip}s3MUDyf$uOwZQ=6)pJ(L*B0JS#C~6r#rZdVJ>>z6HGS z8dBY@c>ALdF*bY~eJ*GHdA@|&8k|EVV{zdU|}LhZvTbba*anE37A z$AOxff{ynukk;@i9+XoGR5F29dw5VKYBSN(io>>UN|5l^n~( zm$_IBPL=0fHXetxN9m;NoLy^>ln2P9&Ci|UwU@^+%YTAB$t4HXHJbvXsLnhxrH+B+ zb-yWBHQB08)Ko_V<`smkx%{F&SsV|OloYncguU0wu<+i)ti`FT%hlOcaeqP;DY_Qi zuRr6`0*$%Cyn=H_Te)k#iipzp@A?YvXuhJMQmppvJ6$DI9F&c5tk|5xY4HSI2Jy z01gcd1_ryTNhWaO&|x?uI}m0Jj^m)es~hu+idb zYTy9qtf|GRL^IAewIauQZKQtyfGg(q+)?cI?dxkjn_ zadj34OGwhXt6!Dv5Gg76S+TT(0U-+tMR6udD{nnL_#? zwKw@jFS^F(hLl;_7nbm-t*t6f+noy!(Xh78yl411qP+fUy>#7;>{}UqRobcfjOm@7 z#mwLUc4~_UD2PH`a}V+k+f--&3dF~$Uy}7xF=;x89H^0EDK9-|$JdWfmyB#04bwL; z_}Bj{HU^Jl>GX^H4%>f=XuuUKkVpvJyXRnStvdNuioq*E7?tDyQteE|pVK*L(6hQE zqHm-I94xoBVx_fs;M;{qOZfczAK~8r_7p3)$nGpd#Bf=J z^5ps)H7^}&^Ji2ZF0?f8{x97w9i1M(p7m+czkBVjKP2nAsj4pb>j20r^_ynliXD=9L_+cn~VjD22~j?t*+wjkA8w* z{l+(o9>?s}O)Iw~IAS|+YzL0x6g7769xsK2A>3oEW93JXa~%MpJ+H#d;%TGisWWOn z(Q@Nw*lMYvc3UWalXJG4Ql_EJVPFylcb--`Ga&No zgvt1?IwCkc=Eegx7b)oo2=EPRR5F2A9nO+0!j;347t>$$9TMrlJqS3L=C~b|N}CAZMJ5`)-dN#{IrtWD<#rYE@0L4FlVCDaM2S zye%qDoSL7*;_@<{JAMK?=`?=u@kaoF*PeSG^{JGXZen%@i??p$w1;wBwDPC3cd%n+ z@N=DA_~OQOd@z2iV0nxG)8An6%ZHJfSb|8HnEr)%q;Je&<$w7BjK&)L)&D54o5=v3 z^*~KD#iQh#3jSU_pOsX=Nj{5=>kgRR;w`t1DllbltzM&-H5!gK(~H6y~xpaZN7! zs^K~w7hOJo28Qj|3OW#I*x10aYd5^;v~mR{#~H`lH0b_s!O4f+(B*orOE07k=9+Uq zpOyKD{2Jqz9JqymBXSkf>L`^kFMM|>SFq;+(r<*};X=f*a4GuGaxwH?r=cOByIUZc zM5y7obSl5MbiP*p9Heoh<`KPa4*SM=h+enNoP|4^!C@Si*VnMRzK*)uS~NE_;{NO$ zoKI&l`18->+MU}teRwR;Y1?)jOwZ53wrzBGbmGqRG@2V56{l_6wz2T&5k?0Fv9h*? z^{p)>kDO&;2)(f3V0vd8cGkj3eG67HJ7|czcADkgG@SY-ShkIa%gX?Op`KnKz-c>G zQ;Q2PoCjVwuUsFWo&p@8t+^R(&2Dh7mrl9%>6Kfz@Ty4QKutZYybFQ}3l4IDZ(*pX z*LTe@3_O2a4Ia_o)rI~p+9Yk728Mh4V4Bg~9LS>X@>ClR>Nd78G%;Bfr|p__8oe|3 zad7;uhoh|ghFk{@>NdB~w7Q11=E@uho7UDaJaG@5^AElA#Z)^d5119E0S>pca~@f3 zyra)e!q@IEj<>`4w2r8S;=UwT9f?-?$rAuyzjXN`tUR4RQOSB8NdlqNQqrL7Tx+fB z3v^w+zf^s-cR$U`E7)wP$97#b-A*y;nty=yhl^gcXMMvq=Zrzp7PR|39x2xakT%~y z!}t9dUO@)yTYdb~yYcHhWF6hetEwys9K3T6 zju4m~=&#suyW`;^;+d@1$3Z>`sw||x2lcvaTNHVxa=n>9U8Q>ca-;wwlSaezb#%Y~ zX8;_`efigrOO-dC_UYNCzCK`m9aVGM1}ewkQC6ELPf>AiP#StxD8GqUsgeZ8<8Imq zT?g>+KzJYyNz)G=;NIJx!TG@*;7}XlzkUt_-93nzChk96z-}gk_U33CBEx9>@F)!1 zM$haV;^{2hz_xPhvwwA5s}@N;1RS)&Sx?*79{wA+-`|H@$Es&=xp{O9IWvZ#yZ1aX z)MEQMqKSFYXlrK&fBGN(8o%=OZy;XcZkSS)sLmgKh>N2W$o=lOaqj4`QmYz?hJWd0 z^nK$T3^SS&x>vWzy~>rJQgK`CxoFDEsAcy>!aS5)#mEVJbv{c&oXP6Gqq~e3Xwpyxc0Py#`C{UL$a{kpPaDFBM zL~zleiVWa4EEJ-Fu5R>nbRr&$;qU(Zn*e}hz+AuI*9*%qaqRMS0Dhx^&cppm zr66z$i!YHIKsKld#pB04Aqm!q#lR97H;gvkG+3NBI71u2pCX`h}X9Xlpqnhqu= zD$lDL0J-pN*jr{fpL*PJu=|JqH8vYsu<^#PA>DUK>koCk+ z%oXf1e_2~q{s0JwtFjSY^G6?(Us|M^++rnr2CC6@@nzXT`k!$I_;%3DwP6W zeO2Jycb+aE;Jhw~=jjq{F$J1@#{XNrr}Kl2#)gVEBR@`3m3~3@i@(F|ogLhsn#B6n z7IL{9<`y3Ua3h#~cJmALbaY~UYZF(;Z=-Hu0p`XgYzQQb7~bqYh%-%Xu9@y3m%DDWWK$O=g*yiIM|P+wN+RF z&OC*BLT_o5(OXxWLS00=lH|*t!OHlUXNH`9fAFaZ%cvLdgKozW! zQ2D37FI3}JSY+fvd`Oo)=r>J}sR-RfvOf zrKnmzeiwNJu1gdKxPh5tVMohVC917HQ&p8dy|d=!6_{4xjkuiJTZ%_xQOlq<$UB^K zN=IV?E4-*=G(;p4_XEQ1>YcB@#ee8(>+$*|P#yuR6%(%Fj<9yXDLn{zNrrLaBH?EN$s+ zazehVxLDrPwy)!@W1y#W87oNV>BqEWCn)sx%EiJ_HAGSMxKEQtM}dY0fyPFl0>6d=^mz4Y)zVa` z+Id16QJ#>rn# zPfg>%{DQZ^hs)lB=w4Z%;=Xrilb4Qx01h0ou`VXNyE!AByAVcpYg9l zw&E=1c=$<2N9wwypXI&biMv{Rx#7Si8{M;WFl`It zhexqhAMLa@PRFj^KyoJy3#K;*^*OyZ$=M-_o1GmB36`urV@z7l6RbV1HS< zG0C4!e0~kFbT(gi6XZn!Ups<6vgi4jlf>UwA)@(Q8Luv;TdOAV{89_|(DUPei^j>T z_~JkPr`Q-g0Y~_KbrK1n%)J5o^bApLtw1W}V0-&%*Thf3tLk1OxrT;gY&CTu`QI;z zM3KJ3h|9vCT)&3Jn#u$@x5kbD4&3!D=ZKkO?O-_#;H^>Z9oeFpsR})-wWnFps1{0f9$h>jay@fG27QyR{c0-6V=h8 zFLrj|^E0P#{PH!g?&_3vf7^xut6JwQ!abJQHVxK)s;Vwh9+ri_eD@u^@zMocynYRb z1_sf0-~a$%Vs;kuOY-O}2fLX}7U{ zY6$i}?^5OFyx?dX?sq3NUAbiLZsEXN|0mGgg0-)H2bu06EhI4KFtq;Z3h2UWKKe`@ z9KyYkA>^tkX9B>~@F3tg7`Zdy)khMoVGac7=s`!j18*ysqqU5pZ%dg%LQRrF0Fq@? z8H(czZdl^{lj@-U4-ns0`7W(yzYHTuGM+$3-hrk&zx_Q`Q-kJ)1|$;+)Y~bH4h*8b zwhn#cci_N)VYp5+M;lu5CLs$QEv*>o@AvZEPVbs3b7dIl+edNwv)Nb!6Z%{y>ZgU&M6ZgDh{wgO;)^<#E&M)Bh z;ln@`e757+EJkmSL)Z?(TRIXXZHSH()e#$&@07;pqOav#@yX4`e*P?Rv71&JE!8t2 zWE^f)KclWSh4C)ciX#;DEqWS_r$KoP}@7_c6@~SV=pME?z{Z;2TppStdvqNPRq*1Pn zs$WM*&Eub-apEc_-~2snA2X9`(@(obE>%bJ zFQ?RU?y2d*>aFW*IrsGIn`K@OGRXw)9X{xu23UYLx3_WW)6a0{|M@Y*ubhThxDRY4 zG1%Q*&}q96WfBP`+Uwz4w_xm&*4*97rJukdS1qXnm%4S?YTCf9YX>J21d@#pNnSXojd*5IlA;qT1c5DSg+})sC>~;a^qwP985VNGUovUcxt@&fs;d*ft7`33dm%^VYG06}Je{XRu43fy ztgiktoQVMw0~6B_wu3u|50!mVUNXIlW7lq=d1(bX#AwsL=foV0Mg5$YV?3(6)FsHU zZSt+S8ju(|=N4dE7OtH-f!%<}|2i4AjbwV)Ez1$iSz9`6^DTO^-~9R}DLol^{48fJ z#cQ{{=jB&4(oHWZ}X25 zNI@Byx_-=0stl*<*%0tI3hgDGznR`b+tqi_G=32`e*2$eeJI?AqOA=$d2;X6eV-l= z4G#mRDRA?qgG{D6d2)N*UZ%%UKcR35TDK(zRmm@v*f3yv+xbeAKsR^YPXMKAYS56X zLp&bG_|zm;H#hO>*>gx|GQN$EQRvpuBd`qvy_2&rvog{)aee_4w7Th9SWaPb7}xOA zlN@XFFk$j^7gQ)lD{cMF~@CH3ezR3%BV0Fe>N$Z%)4s9jrM=! zNNMe>t_Q{wA`UINvW=Tuz^?0%g^S6^i#fNC9>#oMPt_c*t3kO~3_G>8O#C+TaRnv# zD2=Jzo}5G`m&J)gqgY;F!{@hd;q~WV@TI#tJ`PMxVI==sz`qYtt2FW$z|>tm=r>pr*j{y5Ut?j!qOeG^}O;YGar>BUI( zcc3l>4urQmycoT7>NHZdHK&dmbOT;ynr3Y8)+p*~Qu`nWYL0!%`N8>I8ZV zM-uZxboFUfSuEQuf5{_;X$heNyyy)O93t4tp|J!_{+8$}HC|^*#T7_kV~dQ^9N3jU zChYuDF3XEb^{Esv=pJj;or*SR?%jLZH6aQzFcJmbd3>{rz)^4+@r`A)efaMXUth+ful@>l zyN7^S%yaPyk{nd%r?w%;RKwR>0SB369GM78(o!jtNML4Y0L$&c1{DXu;alTqT3LmF zsYKt9%3hIQ<87v_ck+;y)Y|~Z2YmOlu2xrj&HYQzRDUO=?58|rI$nkoGy>#u=)eK@h^lHt8;kZ9g64W*l}BlBsjxIaW1M2Q24Rki ztIJr<_?2SY=^cDNejBD~;`qoR+@6}m?hkKc@JlB!mtI0V7W168cXrdbH+vt)Mn;r8 zga8a7AcP#x0zw!NF$2O7ZUO-a;U3}aJ|pNk05L&xqx9H_F10l`=yD3Z|8;e+^M;%>pb z4co@R{5UMw$fU1srBbvROmm3RbJZv3uKcR3VUXPKs)4z#$H`xl z%3wFOT>oTVx*p75SK0s-t!H%1;>R?$XS^h2&NT)8I;h`+uw^wdW-OP>k0)1#2*YUz zDANJyE_98e?aebvZNWgp>N_wVnwMA6va}2t4a{!{hcc%ft^Z{k=r@fGN!(0O z>S|aGdXjQdYT+JgA5J0LQ13cy@6%5$4GscRQ`j?3+rZPBVTDPrlltAi;t1^tu3Zeu zgVGRp$|d5M8XPQIx9#)}Zr!^F7y{z|XYaj&?8uTVu@e#RrPjy<5(yxIgh*(u3RTrz zqSc7*9Zhm)IizunwzmA>56wv92hF%29FqG%(rC0@GcJwfd@N^&W8}<^*zI0+bysz1 z6i_H=nMeQ$Ady)yUzm) zziRk8od&w|Oa0EB#gAmJlwO4Hxg5R}A3c?pL7bwz7CjHy^?4B6wOIaUCsdX#9b?wa zdD;yEyz$W|@G^ehwnnEX5hgK6Wpen=`yb-Nci+Nd-RdF&17URXQs2(^Jbe7tn|Sks zk5E0g3`FZ6o6mR*32Vy_WF_-f?T0FgV?oPEBQXTFxLlS*W~%=6dDO9FoW+k5$R zx%{v0hXY9GvbcKmNX7HoF$SkDTtMUWEOJOEjAM;SJ3}$iTQy1Iq%wz z;h|%A6vw~(3g^$AEm`NLnHjwP@u%?NDu-=9ss~5ck7H7DewOm1vD&6(A#&{w^)vwT z&fNi0=)OOI?e`x=oF!9JjrYIzPQkjjjZfgz7Z+5WNvf04!b9CaA)B*{r0*ifjqF`} zj2D~BG`3BNbgu$ACcx&;{t|6BKgQ!9{4r*Fj=t0HY49pq|uBCYR zTGERur&3DRF_+dmI~Hduhs@vJg!zjr`S;nD1OPug$FkIwJGbFF4u;0Z@ag5t_=6w* zsG@R+?(N-!z;&_n&i#o0hh+nr(<0*BL1a^BlD=RBFfz{s3r9*wIdVwYjf;dj~Chw*nhN$J3{C0md6^vAcUaS{fS>1OYz$ z@*-Y8b{us@xBA=0L&+M8(}sK$vvP?A+>kjo%*xTsIY?PyV z*pOO}?l_pFnXq~$CmC(2@kTRALSEj>!*!v^mona1c(5}sPyj~_aib^Ux1iROu~C)| zYi!V+xBy^t3kJP5fYzW#k3YFAYT~>#5O-sFR7wrCbwCMSmIP>2i$aRTc&~5|)BgXY zF=!A*@7sU#7H%DgM_615RWB`}es(Ue5RjlVevDO8-}&I^Ve)n@rj=N&tW8ynd*P!4BD(xLZqY}tyPO6IjK>?HNs*I5`^r>`f~ z)d4$pIB0DJ=H?9U-d$aOwjpli`A{Cun+nx2e&23S)#L~ouYQF2B?oh_{{%~2y8zD> zuFRB=evcK|oUc^naomZ*?lk4ltq1)W{8wK97ajw>9ccS^&*1p}14Z9is;Ma&apJD) zpn7Q;or6QzI5d*y^Bh$|w=)metyND-C>)=gjoc7@qZQ{QZ8(q;gDuy{RbB&P4TPPj zH;qbd;8=ILEN+{Qcoql3fRv)7>}JmqeI1t-;*jox6aqHvp4L(1C+g)<@^F zAq;KqTyZ%qQ&ZS+{~M_&OjJXx;e5hGm!p^?_=onZT zK}h0bIihV-uB7DIAx&{BIema~(cIfcz428?rM3J{g{8CMP?`vJUZy||;zVm^ zycgqdQ2k|!I38xFZJjphmt0pRE@C5TxS=Y)w6%o`;c*8_TY*V+=Z<4WakWUAW7EGB(>$=k2=6 zb};@l`3N>LdJCUFMHn=_n8ltu_mK6{QEp=$?G^QX%j6UqX6K?lkjH29{EfFGNm7I8 zZ>xu5_mVJnxsrULIsPhOywA{UdO!F2@?>ZFScU@rf=CwVwXq{dS+PD$OWY)%U zn^uF>=M&P4nGq{T7I95@vdmlf+SYQ~+^KRp(%Xxc#_)8{zJUQau7lb6dEDy1kH^D9 zD{|WI-?bA?V6b)I391*D5#;~lt;$;4NaG-M*0aY%lF3!a8P)4eNUWJBUQ1X!fOOoJ zDA$&Cc$2klEGA;K%~#r#EF~$4g$tRN%jN5pq%D`8N1o+UQ&aelsHzIszyIZ~acjk& z*1kL^AuY>J@p&Q3_<9gW$E6TSL}44NmooV7FFwR)-#xeD$hyixen!aUiyBI(Z9hh~RwWAj4d+RGx$q zZJjAyInnxD5yz*0GkGfaoqn3mrkCD)wd8i#^8+) zKSABxLKMu*z=<|DP+7^5s*|Hv+v_&v;ez;t8;w*+0UXp#&Evc8{R*Ugu%(lTF9%_C zYH5#^8z-dmGh_F{77&WQZ-m@Jc5-%_lkyhLEkEiBdYW3!;qCX{S1SmQV896s{CwSs zUvQmeWNpfs|4K_j5*C&xK_{;z7pba3(F+DdOU=2t4?RyyimoHSopXUzPfc$<^>&T7c{okMUQ^}+m$ zOW4rdg5Uh!_Y>0{+`R|J1Q?l^Sc6if<`IIwn^+GxF!`;D@rdKLBxTD2v;l}M{Zf8o z87RIIa{fuS=eTWx>MC`w(y{=sEGWmeE!XLM?A5*)E?>F!r~G$c6b^4~1x}sP<*fE( z#1x>1%=4jgx>2g<3#sZ?Q(jyEm*R4z?e7~HKwV7@y2>!d^gSLxZFLQ{h_nk!OSo~r z52p?s#HCv|v9G5GkB5dZITISRH+OWPp{^d+Z{5Jq&{L#b58vz97InhK$q{tbRAWbN zEr!NM@!6FnG&MBf;I7>T>#^yQS!D(v)0CaEO4A*txI1V;6w;-KLp*f$&Tqc95 z=@}eqYK?&9-uh-7Z*D`C!%U~6wG|z$t!Qm(#@xa@x;J;JGW{UHmW`X#5d^Kx&6qvD z7h5-N!ra0Fj4^od^a)NMJcMHBvyn(jLN_szO+&+2s;j}srt%GA#c1230W?m}MgqKp z@Yt#LkLF679~-=&Z+CIu4xo>Ut+ z=olWsLVX=ZI@f0Gb`K1od1@NTQRtEkn^3>yD2b0T*$)oVnJl^<4I zbc~Lo^Vx93YoxK)o(E9Z+7NBv3&mgvuKh?2=)v;?bPf*T*1`R2;HdN?NtbU&&Ux;uls>tg0nM?#nF+HPTQquA}_Bl)z$!x!KP;;@DZv_J>+1J0z=Zm zt2LW^5kcROv_Zm#&w;qZIYK*(L^?pC`M2vjjzTk`h%C5H2L=C9fTYz;$to z=T(VZ`J#aGN@&|Qpr^-CM(u9~C5?#6zkz{+A9ZZTrJ5RySkIap8q|qRXAd6%{`>Ig zNn5IIsH?;4$BtKAez|qDK&Vjuv za@wYPlcOhKe^be!1lId!ue<9{aA} zf`258Ay#bOrL$QyPfx@3102454agg9lboNWks09ac5+h#>t6UsXT4P|d@6aPm&xJK z1SBZMY!AI7c{3GT;;G@kRG+T@AIM zGKu=@MXAMEbbk6*a8QqtlfQE7Uo#Qs}YR{BP z>n7LI^3vMrlaN}RqcG>GK(DZng}FTf$8oT^VBC0F-op&n`GH*fQ`G>BTGz0_4Pso)l%1OdP?g@p!zL{ z-j}kMmM(OTR90LHkr-O0)v^{;it=c!Fli+?_(fAwQ|O?*ZJUEFTV8f;UKL8Rckp+# zZAJ1~(svHWKTErG`p~OPa@I@E7s=(uL24<7GoO8d%O{Vm7|ZE09U&8PBwOA@81j)5 zUtGe~6Gt%Hv~uih46wAk3{z(K%uAtYg|aL zo7@jJjev~UkvIYoWdqIG<(FvUU@G}G{7Z=Z-DryU@ zUS7t@^A}M&w+Lep;X2#VnIk__oyZoddl#{`as*KW{>CByOyyBy=qw%m4g#c>{U~?) z>}!eD$^IL_K~^|F(?$$qwFBZ^U0<2EszV%c70x5BQ7uh7 z@Atz+fQLOhil#ewa6in^`}pc#T*B1cEZ+a(JbwMn@5a)lJP&|}jcpt7+L5F9%U}E) z0PurzucNUp9u%k;72;MD`P#NY$J?z}dqC^sSxZkAYhUCTMC(Mj7SWccLMS*~g$U2f z(s?@@`%~!@@!(&8mhZI9!x3qc?-wImMtqfR$4RtxYj}E<=K*US3%W?8?KrK3@lg88 zR4L`u1xSX(_Jq(TfTRz9VQKbQmvR5`01ocngB$nzkjv%JvvnJu4iBTHu~9i~I}YIGjW?d>0dU~D zZvJ<8KO=wVuOnDlId!=*lf)p@hf5rgQtS3HuVC_3qdK0Fl$RnVH4b zxh3pxY>Ny>A0(y z(RZ(C-2o|#k~4KUx?0C4G2PmU|)F|q=1nvZ;sa{5uERFN>TeeJ0VWwqr&78Ia z$AxipWUKg?vPB3USFE~$x+cYdpFhBgTI6PZYu2n?Or` z1A{h9Yw#Q&)rJL;2MJ+4<6#-jvdHWt$f>4azD~l|Iz3;isR@lqeSK>;%GL@XueHp|RNBO6uU6G#Ptkh) z3set{Vr2hmnC(55G{9*o2fGh6hlfbV_vJNlqp|jOOee^8Ha#31#N@}ffxdA#zquc+ z-`$Vh+q$uo$>7d|egMFMUAvG@t&HbRwzdL00mlFxL!&SV@-AM|4Gb|(N?e%~^bBk5 zzG3MFQ5q+TP^l#kZPo}^9T)Q38kH}iHy~0uMbb0Sl{HK{35^OhVNmv_BffV%kwEY#Pny3DFf2GvW; z&_~3w;aMx(oa2DvK_Z;7Z$Pa z=54f&O+?0aGQLxbb1?AWN2so9IfLrua9MIokFIk$#BH!6aO#oF z_u_g7i3qtxx?kv&EozfI>M^`0H`|8aHvGHy)*ZMez{sYJ$W&F8J)Y9pEV`Z!V*ia> z1&$?`$S@vVOGZcI^i*%!98A%`cyk0v4akqts)Yl{p=ikq>w{O)zL>>4-5bha@-ym2%~PV1+5h>E=7gPcphatYE~Dcq_t6M+U#`?>bfF6 zFggeG|6GOVy7=L_*HKj$mp8X;+=SPUrSQSUFYt@cKf^!x&7Y{_oXe%YJ-d<4WU=kR zKwcy5MO-t)yl%vCldy3T$@tZTbLqrOk`YJ`9#XjCxzRf=;;TRBDs{Fb?XZ+q7!yl8 zZ0poD>9=e=ujR4gl)MH!Kh4luQbR*%XFPb&!G>}V5Bf$^VQgHOH%cU-N0PCgQ$A#a zs9MV6#KlXva_lJl)T?tOM(yGv4qd$tC(xT?$;n(x_W|l>=W*!jb=*F%4^tJMSPTFS zvvb&Y>vky7=K{;&(*eoJB=0+LQ8%}MgV%20?*85=Xv6cSxrPP=DNn5@0g$(A8F(OG zWl+7ajGg!T(e-2yl9TwJhbzaAM!33WaS_$a8R&S)^0aItzCieFwz(0v4<_5`%b}&( z8a&w9gTQgo{cr$`F9~6hWz2yW^*^Q2Ts1x;R>J$rc_+^E<9J)^Lp3h9F*RdldRNxM zvGS0*-*Q$3yUu{Up4gfOh;+&6HI9~PjYwnbqS@9dZH*lLnfQ^!J^`FufclwvI8K0L z7r%$M5#&Ykh!szNS@S1<3j5$^@eO& z-#~m@?hWlwulrhJVcBC6S4%8jNOHC@`>RPUx9_0-=_Aba9KzJzv&hwzwqvc+x06z- z&~f|BnQ%N`yJoPsxOVx|Jb4iqd?m!(I{AL-_w_qEKOH_LiId25GDXeO5^BoWz5aA~ z7>}L}0=*pw{^)oV0JjjOQz>+|x8u~o@C3VyH?HGo?>;;o8Ad~09eTEur*n(15cYF` z(6T%kBPl)0FMMVetrC3FhQ!!xtKf4USpJDiJtj&k(`nnYNxWvMOy5hw(~f$lFs)9< z`fB0u0|y+?zSg=rU=8-TCQ?OC+b^05O#=O?v^Xm7ml_N-(I&E4h5#+e!Fl)I{Wv=@gIwO3kq%Hg*0M2woRW{du7{Skc3ke+S+u>C(4K}y>}+g_ z6mz!GZmpJ`>U0{X4jjboyi-phs>)=r`PnlC5U6GWTr|wgqjh2ulWnc5s?VmOVN@+I zD+f&E0Y%kv277MbgYS8G*0p)Xk$T%l#?Ub`8bu${LbrYVtu!naQ#%!ZX3rYQcH{R8 z<)9UzaRsV|y&ASMtg@qZgzve~3%w0R0>HCpKrXlXJPYyv%JT{7dCh=gb)+^_k3U1}<@Ztl>?vjsyo1ci zlZmN|t^Ud7Io2~ORdc1bi3!ZMG*%ojc0)@u_Vw(<)a(qtxPA>l7-{U;=qNU{w4lDW za_7m()>Z_2TsVQjhLLd?Aq~bA#5xv2hk^w@luw>M8 ztQ7W@=E)>oXs1A~uZG!4_-AzhIjM$}Z#g6H)gs3U*Oa|`9jwvGzt5fcn``4laTk6) z@(>$8arK!r7|{FWC}3U|HO$T7%;#U^jjN8Bk0cj{29(CB8JzgyOPqh>wN-7_^L!uO z4+pU8?tNsDjyB%%MnT$iYT)_-Jl|iFQ(ej-zsds^!zex>$79E8G9v{hz}ZjF*E3!Z>;^j~8+ZCFSAvhmR0=F7Ea2si+Oc zaS)_Ec-c_fp%0=Z=b#{RB=QwU29P)TF>Yb?BAGK8%TgQ5BYTz5#$KI^=H*0enAA#b zsruykr=@>cx~@OHLBI9NCi#WNevT-`Sm|xmy3R34FT_qC?A#oPcc@LYZc6M-d`x2F zkbDH#bNeoOZ{Nkh_HNwSzqcgL^n4#%A3wp~n|D-HKe^$6qisn&jIr9JRo7A%BS$42 zfK2!v2(d9Aza74D`m-<8cV|;>SY9rgQ!cXkX!dLvmyy6^lr6@XabqeWUsrsIu;d(& zciJFlZRGnR$j=~h&NJw~{|MXfKeWapr4OU8WlL718!qxc}Anf&c7pv6RUmZR!#ovNvtmfFGWF1MhwQDF9$O zlYxOjRVod)B4rnINLp_+3TATi5o7K5Lt^AeSHy?OvDyV~mot$ZMf{uft#m%7WA$Pj z>xOlrHB~-m$%&;mL~YaZ56gK*yvGt?+;Llyou54-*9JE~zx;??H`JvOz4n?@?BLq3 zEv=PqFC<%UBgc`JQ`rTS>mh9obX++h5zqJ0F+7Tc*Kgp?zP(tkS^4JG>g8qh-nk0^ zxVyJ^#T#K8X6LZy?me`QQh*#C9Ty-@NQg0%23sbku;qGm< zSYGy)PM*>p#r9n4;ikzM?7Z8L&bnuCVKCj&jK|&E$}YPqoyMETPei)Ma)_NUr31UR z2-4V_ZED2ChE_F`jpM)wUjMXvE2=XYY#1F^yinQ@SrQH~)z*Uk-8)xp3!Ja7$H0zm z7&zGWFx=2Xqmy(bj8<6NBdxSN;%ObxNK~TGWUN~`Y5pD8cQQXmR6kn-s_lbDrPFPQ zb9$LdV`$D;p?zKSb@oeavm$jpcr6I&XP5qnw!Ps%nY2C8Z@5h ziJY;EQ96}EcV~E7N-mefy+;r6@c;S{)txN}{@`uw+FDxP)Y|hx&!PIvvHFVTE_#Ck zfv^k^qHc2BrsuSkkT((0IwAG=Hvi{BcK0*f`&-l2zueYqIkV&**Y#jS<+(LRWlaDS=0y9S# z_HqFZUAYe5^)R}rqhcr3#+g~vE-YHcL;k)%@;8-Gg~@;n)k!Q?K4DX-%&|OT_$*7+ z06K})+KN(U>ijn6#|I=aFxIM68-B|r#;&hj=eR&27f4Am!WJ#DcEo4dFH(U>iWvDl z`Mq$F^rB^#a@jCCj+Dva&c0quuON~E5Jqp`fAbb<=9iE|DsTL?cRX{O=nF_=D9>-X zhnZB7dY>>s>;Qo42RLx`CVa=kNasdm)1@6^+Qui~`aY_bGcjX&l5v;ou8)NZ4G9qS zB6UP4*vR_I*7`_c_w7CejvF~6IxtwOttsi8SU)$19S+w^ih)i+_kcMkHhIowX z-$ZdSFfJy;dj3tNsw&{{;cssHzU@?94IDihe&4Y%vnIxAV6BZiFNfTvd9;1`b2Ro{ z!qk!PV(jFpgfPqs(j@DL;*Vbarx}Wk=*wz_>ZqN1b zbYujz)iqeoW|8tdG}TwOC3U*F8F%*Y#eV-LTE?f8%9<3U>^RAiGMSKVPK(%G2|gVG zf?2X*1v4N)vm~ijmezW^5o*Nz>=Q*my3>*OTPeEx-49bCW|wW*RZjU(=`6zn0uo!-58u(Ky#$r3c( z(u_~vd>wDS|0^)YBgDZbN?-JRSPzo-Wz7S10#K!MEQwzgT5Yw_SSn=cuC2CA&R4D` z+MKH~uS9B$JLOw+C9fHCQ2XNTh_8upe4_PhG!K%L(cv}KmbDga;56Wf)uHoC4sJeb zJLMmmNw*9Z^Q4eF(aQmCF>|1wOv5fSI$jxmJa8Tyyt*S`Lz9kA_+># zMe8@XFSL%w-mGjJ`1SG3+Td)r3sD`U)=TTglJIinRGb?mjrmH-TFq*{?Y;jKlY7r$ z==I;l%#OpW$Z4Iv&a`I_uxF2h!9n1wuhvFBjITT8<-2n8n5IJI>D8w4wkFpvZWAJ% zVVuLSE%|6|v9P#^AHMzuw&e}U=fUyAh&u-M$do~*l;jgk$& zmEg`|+LTwB+S-7#XGPmzJ*c*3R4HDTyn)A;txt*bkV0}VIlXFmheta-35`%%T|BHXuhxl4Y#19y?ZP5Do{dDOCu@6)l)d;Q z9Evo(VRRgU>!NLJ0yE8}Pd09uoI+3k1GEp@4%_ilZ**`lmTgCB5O{?#yfFp~OG^m;_6D%;1khI6X)kW&L-cjMeCV_%-CMC-Q;pG$9hhz@ zZfl;{&<59pvVZ&N7}#=2T#pgQR9g!k?b?CSjU6THSq{xLG~iKBHyjgS>!T-m3w9d3 zt$;0@wmy;3n#8W9B!KwymGV-lC)K29v0M}M`3}h?7v>pq)iG)`(tWKXFRevRswq|9aF0M9ybYcH?j-bk-X6f((Pg>3MV`Dpxyg8_^a!0=I4t+n@pd2BcS`?JhyS zHmtwNuLIWH3g7ah9Fz4hTsP*4VIAe^Rg9@U_01$!){>t+^JT4U4j3P!rR1nMJ}(|t zM9E$f7ru8xfu>+HnitAnViuEy@}?uu%#bL%$bd>>DmYLRZJ#nj9U`ky?(&N5E9 zD<)UCs%`pTQXcfgfeaQ(CtcB2AqV7{6<*T{BlV@UR`JRy(Lb%cQrfVww5%QFWqZ6O z**)Z{y;gSTa@U6Ejo*Dg+}t5dW-pY!CQjR>J_DIY_)wB!??`a^b)dN51;kmvT9;|F z&QK_%yS+E>05BNbx&@h4gsKaI0OQkBFs675=IiTm_1F=-^@|T8_Txtev~Yh(+vo)L z`?qlO-~kxdDLXQx6Bsnj&fvtCm*8goXjds2nSc;X_()0m3%J2Y8HA9wBMR=fY}i+pwC@Gmy;OX24P*N@?P6 zI8jP|?y7c#Ia0I}21V3Hj(fl*>4l&eRJN7U@po*1!3rd)#FF>qqNnrKK#4&Y8Kr4V zky3>A^|y{q;^6h0xO(ge<|;T>!7&DnGqX7M@3Xuehwa#s=ItatPmf|3kzhzOS< z7ve{h&R(&L^E*zLoTJ9Q@)z-OIU{YZPXDLBe)QEC8Vzk)osNY*8Q3pZ^lXl%Xt*eZ< zEJtXmR7WvG{^)1`d6#n@agLf-I-aV|)z&Q}J8C2S> z>ptZDSB=yh40721(|-=*Y{b)degg{|yYP+nzFViFM4!I16F70g!KF)UFJ-R#*Td1?UL4$A*(oJO%Mlt>TQ^|;w%0$lM$pC|auS1h#@cQp z(gI05ouvhm7qrx3Z#d?4l%!B8hj2QHYYU+tJKfsoKVJq0-m?ej?hfnidEfM+8#HFzV(P(EVrt-47o{ z@>=)90R*mxf$iN`s4wlf-8wmmp8f~<6HVQM4%>m4PmJuOGk1Uu!{gX6Jcg;Z7E~=~ z5_^pLseNn=8=s8`xsS{9l}u{~ACNA^yuGk)b{@NC?}r)*&%waJ(c`>tgw*h81k4;$VoS}LHHIz5GmB}cN>h^LuJaE6#!;wVWt`Zx zPw%&nDHPJ{Ytbt%xYmPxJ9h}{Ky?xMX??6Vgmilp; z-+&GUsC!;YNsQ4YW{XFpwm0x5;aZ4%WjW-_!H(NrlvcW((H+)oCG&cXt>g6yRC_5+ za!zuV*ceo{h4H=o)}%QwA`k7_9sk~l%4ElEs-q0}r$=vGf03lKk>wTEYuOl^>lYv4 z<>>3bWmGsFf|3t%)IQ{B$LK% zFG9nWJnQ3}Ld)y+`f5M3IauL*lc{Q88rA(%XsD~l_O7n7-m$57`wp0Y@IBPk)WUOJ zJQ*HBHkU=pOJUcxc+_p#3Y)LdYR13gt6>sR>mA7Ti-_&Xe0m1uOxjyn3QG+#&?b)) zY1;^qywo2jeQWs@?eex;qZ%Tp$@$|sp= z#0@b4!YDpG*zMu>u3vH>k>FR^>oVl*;Dd<#Nh!t5CHHoR$AH2@Q++<8Q4(`%V&C;;o3^i@|9o2uo>JVYLTovpj#3`PT58q#KafG zq~Gy$^f!47*q}rMI9*REcGzWd+cl62d5wgcbe|(ahwcaYS+U9fDG25GSZLQ9p-o7@{Q;XJ3cw} zr#9^JQCoc9135w`M?{l?49yO9H0SG3M4-(bZd6MymB(K=>f49L&@nU;eSNAsIR%>h z@0{f%#7anQV2>*+;>rvv#dh?LkJaeQBT3jP1cnRE-j##rZ?t7#on9iHIpg5M1%uI1 zAXvo-#gb^8mka(Rt;I->ms_YFdaZ4`dkI_r`k!Kc$3cv|`8%pca>GzkE`{o0E9;X; zZ-`kLZQtC5BfWczrm4=$s`HDB007T*QB%>$Eg`22o%g)N)j<;Refd6u}7~&5?YmHK&~0Q*~39PlSA+AyYPG;Pqvkg zKv0aTmNGbg=__12atKqctrfq&X=oUGZ{0y^Ig3DS{9^-!ZLrCo43qP5?vu}890ymA z9;wJ_+{^lKaslY*Spbo&NAj^R3{3$7csU=boR8M*1kQc@8I0@T!r9aC<*tGf^v>zC zsIM*8P%Kq^K|W$}C=t_vwki0ydi)3$>g!?#=)iTcRLke8Up#XPZV;gN)?KuWPsK`c zpr!O|Rh4>wC1e~23w3okf9@r=7NSq-u^@Xk$oQ!gFE7H}Ug&J9)&j55mi` zG~Fv~-bZ5HW&ddh9odh%-(|l_EbkESjvEILB3o7ZBw3rr+S@VK-j0U3IizzrG>y*yV5j~{w9~T- z^O%~MMRipg8_S9wuB}dbdp^ndGCj-vaebl2{Yhz(%CAH_medorPFLC$9qYcfTmn$P z0XfR!R!+Ky617g&x|M1Nr-$e}evi)s=G0nmz`@Ppy+N%fhi6yhPCf*z^P_cG_eY#K zh#6rxITPJT7iK$c$AgA(d$_;2_hi&+mKMUWDLPJQAnHuLn5^?>$LKf%eWJ@ z+EMRIiBSGuw#*(++MPWKrNjEI`K+cs-qIYJ z9$d%9FMf_(Lks2(9A0UR07e0ej<&d=7Gt(5rPN^p1* z$(5<_idtBoU49!Le0~G>KDvTU2X~;WW96IQ_U`D3etVva^H;B8ZgDZuX`9H1e<4ZN zX|_Gf6*4&=iMIi{3Q~S@Q&cEJQY3A_#_qCb>0}_1AVT8E-5iWeqFXHqNh~e@Z$#SU z-qCB?+UieVOy?6x|&z)LvbSozx?Yj5&U35Jf6po2rB>eJjjZi7^BKvKrrUoCp z`!?SG`TKCQL7oMAkwYbs0gzhG;jLeMfDeA~4zg(tvSt4?&d%bEk3K;LRl+bv20vnE z+RfBM0M{}2;_MmBHkB96+a|{`a2*2}a*+U1$mN~$$wfk&tMmd$qk!0`R6^4Id|4>2 z)Qr`wKpLq?w-s9&_-iL4o8j9gI(i)j+mVmwsuL1Jo0(0Pa8$zY^itAa;vo z8)e-!xRGzN(mGr=^;gj90PUn5!Z7~w)J_kzbBlQEy)cT{ufG3wQA0t)>>R%H;YZQt z0(P5V-VjE)NqhEt37tOe;NnGt;o1bCk0m~M{RXNRm(egin>V0)!uae(RXza&rV_$w14cz`+J2BZ- z+-d#xgMQ5X>8CjK<2SJ7dq<0=wbv8bGa+{MaqZ|~jBYCLlqkZuclY;V_uYGF9~sX( z5O^R?N)qqQLkCujiET2DgPG+(IXUI(IMk{al zR=BP@2m=?$b~};71JzLWD&t3KE|t-pDGIla!0m|lX|*QPErl!~(=M;jbSyG+*YKH) zw4${D$)ufUsJ`)|sbv~%7O}CUlmOUa-pTi{9jnU$$uHV0AoWp_82j3hz^KKxgSKn~ ztoqwg+E}v%buHTq*fZZI8z(2vJo}wwJY1-Z)snZofR=j~u;cIk7YzK`Kg44DW&{Oz zv*!U#O>16-b$Z3Au`$HPz7Jf!Y}Ra3^IETRr6>u9S5gOiX2vzMh1b`3J|wG2J#ifK zG|kN7!1bHBdFVjd^;`+H<|p>4Kl%~oa?5Dk)LGH{N&OgdeOlk`vkl@zPaMUI4R|f| zqji!E#rJEFKFXW#?C+z-cAm-#b1j( z7HHP9k4cD?LvEqH8o0)Mk87)I?<3qg<_nI+e?uw9jd~8Ezo_>5JngtkFy-w@2bt~Yy4sP8t$j6v^uJrt7P9-=ySvRfk zNuF$%5ubUq20RZFo%7CaI9K*!@7BJ+?Gmnm(YUD)2RdRoo;uojW`pFJ~}m;eqQ)OEOe zweSX!=jgOuURNgrY5w$u-z&`6jQAAxzS6je7Y^SeUtYz{qX#g&c~i+czbM)?G>pTS zuSJZ2fVCfqW6b;<7&K2#;oPU6;nO!>Ur~9dE?h+8)C`=Q+=nZ7b?E*K0QBCvgOr~` z|E`^@Y;E~O>OT6Cf%uNZb_@czCcvBTe*`!Z)Bz8BcA#$$D@+`iywJ?XH!l*~naPqm z#zlaS-ug~O$DG+T(A^E+^>Ej-S8wqe#^@$d*bnL^;P*7-7AA zu#>wS|Fp=Hvl=Ti9aUnIA~6?5DNH`@N%A^5BlPHy;Fe;xc`$kK8kQPF^O@cZh&QM) zCBZoH5qtBG9s@dJo367|Rv>Bz??w;%H0&8xc-U$+sYcR&ZN;KiRUzTMl~cJwO}T>A zN(7|EMc|jeGw=l2f7`Rzkxy>o2eejM7f2ag5^ zaqrP1%*@T;OJ4#>+9^W zT?h+T+FQ2dFAXGm{6LLATUM2_4k>v2yrXW-+#ab!{&Ae)ppRG)~W;X?hm*Gjj-p!?bk3B)Lkeo;*m! zRcQQeo|uLU123Dy#%IHdhswU$_-q7THkUU-r;rpejMZi&!2^=hMy4nOw2e$gH67ei z`Y69=W1|@R)m7{`(py$P+ho^vtfRdwhiysIEzRiPy$f(0v=5IV>?vR1K!djN35>UI zSd$aKh{oGDAX}A2EfyhBm@Sb5EI}LfOrzYS8I?3M)=GYMtU98=UyZ<^(z9EXL<)sw zugu#<`!c;o*_6Vu(uOGDa0g0~^&2?qx#i9R7jE7I92DipW?lw|6Izy`eWbQkY}q!H7OdpJU&b z@9JKo6dGZ38F9IZpBbx%OhUS3tSjp)Q@U1~!jz=LiLaU~o6|1>Db$WV#*V-Hrx-c? zV+^19339dNpZ>5;-wvv(3gz7(01h7x4ak|y%dS;nDvmO-bAd{W4(dc*O3xP5~h{U zicukiRT|H(jf_|>83T-rga+ep8x`Ugm45*(Eouq3aCt0G5I2#!oA55#N=Oz9;6*Z@ zo0n-x=d*Ee1e*qjmBb10HfyUG-}+*6vOc$jEF1B@(Q>ekZY@Gk3CzqhSL(C;d<#OU zn>APVya_CB!|l+njP^+^Oth^~YUDy|4LLTJs||4wp60h);Ubx2?_H@*v{1$TsuYls zJygM3_^W=HKfeI{p*@KV>tcNjUblXeiRsqPtwXEwj$jU<3vkLjemxL!IWH!3@slP2|q zjSg)t%$!obXaD6hC>^kbU?X>p)a~E)H{=jsOx&lu(ME2iCOjVMHp5!UlbX4e^j19m7OmrTJZxL+sI2&;UOI?Xt0(>g;tf2p@GCW{1c;lW2Pl`8*4(&b$EZ;h#~xf#Fy z=67L?!OuVc42#Q4_`!*jI5jqb_D4^!3=f`5n_+mpl;!;KL8s zPBUCdUe7(!b~(zqay}1-CS zefl{9xVU`s80H&R=GeRC=~L{vbq~lH71c}bV5C-&zz$>3Fg=UcKmHV-zy2D63OpE2 zpTB^Xi7CLR_&^?P@i-LYw0h0)4Yu8XjLlD;!GXbCQv)s^KUQ|Rbu~5ko$vhsfA_2R z%YMfOpwjIzWJ{rH0*=9@GbfNs=}6o1c&oX_2An^47NO$bUIC$j--v=K%Nc;F{PP)Fm^k-2EG28@`~QWYXq9HCeMAiw<69$s>dW@ssovI_H)hc@$9 z)_llT>M<5bswIo~BBX?^{n9fnT zrO0Nhl;l^9i@;J{#bb?YDbszOXeGi}O-*<#=-1gHZ=EV5@+aH9+kxj9+`G57`IjS? zz7#S6djI)<4&$XT^v>VM!uA7sPgENm$CbxrWiQ^40Ggh%nS=nRk9+%i%aVyR*&O`9 z2dY!p-Mb5C4jnG}PRjF;@;vlx*@~)E8bAH3pJMt?eulsN9}Rx<-FH@G@DA%waxq8Q zj<0x3EK7$y;DbPTsKO0ECr~i&XEm;N+_t423DarR(Gj{@`7fnBEq6!>gh4b*8d|Q> zRQSFPtdr?g0?>yJIoKcqGN)3ZGt1YJl6g>)>Vwl$3jIZszOai93w0% zCFHqygkF+IHAXP1U#0Y&LJmoh$_mnVcLF_aC6n3pC#l~>fFR|ef7cH9sg>=1n`~>v z1JeV8&~e*~cwyM?&Syh-ynS0qy~nkCcah0vv3pxLnj1?;=9Xy6s9p`CZ=@B$%uVAO zrs5i>)$ltl)yLNxZ4i@6?qq~e7&XwnK;&zzzq(#=DsF6Ztdv@@D{C)TA}N*Vn(Cai z_J$3(6ra$`r(zC8b4SLbN+MowC0<0t8~nV6kVljg`^UY;b!Epj-kL@0J-1v-1k8Qt zeT`=0b*G*pgDIhQdGZGzeob-GSb?7elC)f>jmOO!AoIT;-Su>&IpZI;|@n z^(7EILrXkVhFqaaQ+y?r9Koha^j$B4YDWjK>HOcoxE>z<#(#pPj%_f`I@n#OWO7|# z+cqGVb8!E@!P3%;DR(spAkOQ`$F4Ttv5B~ZBi=y4cUC_0%hDHAc|cQ5RMx`M5`tBR zL{GUM>T7FJosI*Y&Ci~pWpY}rV^Z26n@G|b2uW)wb8@{d5-K1$o19QX352Xda#fLN zmd~4^yaSMv7@tr@HIOTXyid{utqnFl*65}%6-%>Ptoy31EjCR}0V5-o*UL-L%JXrj*tR5Z<-$z1C=A%nyBpLIY`o6plrVU*8ztG z;*d^k50>qtvI1d4mfS#Zc6OpZ30p(kEy$js9mE|NYHINQ_uj!9zx)`f z$jPWOU9P$K7{NbzANchjR#bK&+)=QcifUCp*}Ocwm$V+mf7>Vx>OPG)8_nt8d;*e< zwK*@uzP+t;qr0rlE!AeNlZtB!h^G)2;Q6RaH|mbPrt6vQSkIGW0DDZ(bJ=4wBb_K` zLey@4!wR8K@?DTTl*;i{DmlXB+|xJ}s_v2_rt)W#+c;JBlM~%F(VM!J972Ud^-;|k z83V-klQjl9BpN_|D8#>Hc!@$|Sbk0VNA(Xt&iH}V&hQ(Mb3XOFtQQ3e19boJZ(Bc; zOlz@v+cMTl@|5q?jt-#nv%f<1)Cg|<@jqE*?U<&ffcM@raGdZ2&mxDOuhX}L+S`FM zXB>R;$*U~ozX*!sc_-ny#^%WyR(c{sAClC1?Z^=fZ7%P$Df3s?VgBqAoRcf}-z-Ls z+K#Ku3q32;opPAScf)6nxZ-=ZaAwqd+6*AYS-?jMKrS!rgiorLma((1 zAFc^7&|Uel&$SDSIC}XC>SyQS!^M%yS8?mmeoVErRFuz_$4}AI_W%$6jK1m z2&4hK69j0Sp2ey27h#;R_4oGf!DMUl@ynj?>DzP&;`{+ z059VsoyovOfa=9%oc{bm^v0EAN3m2>lUOzYEN3$~f9Vpk|LuD)N6&?4K$bzFASw@p zF?q9k7EATDxPJH$0E6k4mZHwpf$L(jwG|g%JB8z4eg!Yf$^aIc!(LddtHG^f2Qb&T zHc@bL=@f=LHvtAXaP@{@*HWk^^^jINkrD~wTBaz@wBmyL>QwTj$zG)OGYQ;mpq=!W zAdH;{P^vA3p4bbCG={UfPS#AmB_oY#*cPhuNNFb{iFqJ5ZrPG3N_>R0c}bg^n9aDoLsX?M0@eG1-{zA;=3WNs0hO^_JqB-a{Sdab5&b zHQeP04N~mW4oECs$k^JB_%3$K<(EvZJNJ>T0F_ZJs6B<80(2kHSV|iGnj<979;rYo zhivgWN!+fCo~MB1I6%XC;IVHdRaF5sHQ!_roGG<1gPs5KPheaZ!*BgNnBRT?CS9Gt ziwgBcVJ^Ysz+MBBxKjWZDTJJ2sk)}D$f>6f9YV0_6Fk8JYO1PGU%?r^Rp~UkHf_T3 zv&Zqte>jfUjvvP-m%qa4gNM;lL?-0*I@v&PJ8WyEaQq#c^HXnxedjBUN1D3mSrK~%HEpHDP)WE${FCS4<% zHLQ_IMn{yN#$2`u-|kI$Pxq|E-P8(dTU?)M5SOjO6gt*dG5Le?39NcZ1v$wRtev23 z-mI!NPJ6a?gV8&WFzH%FCEM$p zEx(jQD|u(Fsb*{h?Uz4B&Daw>`i*~t#f{rbzLUuSPo9KF_O8>nmwI}DAaL;Lk-@^k z%c#N15kje1S4xg3g!kg>n2qKTyVmQZ)<;)LjlEsy`J=bd|K2?Wfx(qKx6ylG4{BE7 z@zK)MgcD5%)V=$U2aw5TvGd6@G|kK_hfKL{$@scbE6LhcP1F}s)|HM%=Oj@o|H} z!OGuDr3^gJDH&}tl>)YG34d2AZI_qcmbVJaP+B^$wI+IuX=%=}?$BS>+5j$cK>k!u z+SV_(l9GEJqIBf$$Qm|@)3tp^%daxp9*uL3c#Wu3?hCSw>ip!)*FkV>H$okqkDRql z{&@D{PKWXvP}xDWQBq=OJG!?-0>o*wbGBpsEk)sJeJhzOT+6wp23$IQVg-2=roiP> ziVN}LLbUgfe}L`3brz|b@}m{VFO~e&2v6{pyeF|pQtoSutK;i3*Gp!6Cw+p<394RtD++~@@bi7j-ZT_q!q)G^N0$Do9zw@H3K~HgMAmAN zG$w8JR0ePBLG*@P$+)*D1#<|;x=ZOQo$G7CACmK^dv+f^fAc@1dU6d!0zeS*LFoInL@%b1f#b>U7UfQ(ajZNo%luT^>TR(`kuBuLpE( z9H;!?s6hbu23t06!rSLwFYlcSiB5lZje%nfd;|D~yFSFXWFxM7hkMKTl_ZI}kq$O_vNubwgvH?IJsdnLQIUIA#OmVRkc_9#v^ zs)|2a4sb!oKj$#t z)PTGDdoj^ozHvKnU5vH2cfooPn+3Dgynx5$>$H{$=)F--K zyv)d&%D7O;WWyV+#E65INVJIVG34ZBk$@_t37_$z$_pd|OCPjZAYsk|Rxi;`XARG_ z^EN5YG~CqJa!&J3X-7OK6+FRDc0`fAV=GGLi@#^!ObjV===XZ=5`!{Nmp6x9#G1JsEr!7 zd@SE*<#&9Y*7Yy94Nv~pUts!tA9nr0S?uX9Uv?&{PN&hcb34-i!H==EvlD?axY2hH znQRt&dwS5-u~DVh>U&v7;>WE1Ogg8*CfOULWM;st71opknE`l3(h67V{lF?mN&-|~ zQaWl6uRgZqmdu|WQJ-QY<-BB>FP<)`B`=El`wdbl9c}wnr{~d2Z2W;3qkI)tpYWWZ z_Zc6v%t}(H+_vX{w3L*B&CTRI=w$-zyLMa2ezp?{oeCojwvMPNIc~Efuq}h>O~tm! z#5Qgl(3WPBugR@cJFFKn`h+c(cO6xpl&{$UO*lP_)h{JyAkI(Am9LKN+mE5~v9i)m zw6&pnVF~G_TvX?d&|nB6fM@(Vy3kjjgzxc4*O~6e~~g@UhK9SUgobOYlZQW+Ot~8dk zGZ43uGzM&v=P(nzL5No-8jI`-KwF9I4KeYxj>m^x(?a*De@gLSTY@g!i)+KA_RU!D#AQIhAX8O^vG(>NbqlGsx&|BD+R$H}f_ri+y0>mY z+B)fTEof+L3=2z3SXf%d;PN7X6gE`XtCmT;OVJ*AUGnqyG-*kguG~B?r?t=nyK~wk zF|&y{xhwcLt;!npCIzP9zidF3sW?Z8ckMMn^KN^Dy?6|}S_)5{dw%+>B+BK&HK!C+ zSBFQ)S3+`5+h3#5e2){!A~xqazH11 z7IxH?8z1aVh`x~fq-;(#qIS_=EvZT=kMh^g0F$pDN4?f=rjBTNGC$Yl#~sB1EiY2O zZr=V$4xh}6WX|Q`z@clY*Mqk(%wQtiSbj$FP9(j)>b3z2<-&vc-z?S%iO zySlapgxUf-&`Y6FF5lF(EXD(DoLnw$u7tL|_owid7xDN<|1qX|Pa{Y_9}v8_$iMI2 zHF)%huj}i9qes79GUPg~oa*a=Q>Pq!`K5t*j$-)pL?-3Q)RmFVC%LR-9+$-PIelex z`SvZ`%TLO&sVQ8#brat?adHK%C{2g2UPH^|WVEW@o14V{@$ed&t7`G%t^;C?WiLt> zJ|;J`p>OYQ1g?w4y2A2gHl47w&P$~4h}6~@H=tykQN2y z@Fio0+}+2qdgQ+#5`Drz^|f;g*!tiJYUY=)TwR5SyLyVYrFnW9JNx>vVPrgV*e21f zb$k*%_a305aWvniB;h!0$EKkX)GjPW?`oh6ND-Bk1k`8LpY)te;tqh8@o6}iiZM`-P&+ zP|fH$t6}5o7>~j*lAIoENniJQh}P@0PG2vouMht%Ejb7RgTB6(T_a7aou%oSF|^$L z0^Y2Tp?Cg1W_KQi@lt|66kCb({X+Fik~@hsN9A`arDy47%y>D}FD_zkaRKcGPIoCr z=~Nm$Tfz{6+q=4u^K_ASiJ&BdIywIraSKd%E)qP3O7OvcKCl+z4Wr72pjeiXr% z0ke*dO{Sp=o`9&kl=Kn1$M=iTN`P{?@2pgTJ3bD~&tp|i z+nG%0{N3B@sHh3go&l4S@!ES{>{bF5Z@KL4wOZK=VQ4N-;%a@L#~{rVH@ZXP+l^HF zBtLRVG$Y7FK$5C0QBpnWuXK23+)8MjT_pj=?K%%zYU8*&B!9&tZF3(4aKREX>jkLJ zg(NX5S4xp_8Cyzv6s?ELmwboO%-Yl4eZ8oiUqr{V(Wq^+%`LcdVBeaRG1k!zHwbY2 z!X?2|1Kd1V-bqv)|K)Gs%;CdmX>2O9#3Xfaa+-40zDYBd_Z-20tB>iP>F$}HW9Q!43%gig zu>gn#xqu*u28n=Vq)db)qZw%wb(s#*NP(gm4T2<)AR$r!7Aq}QSnlrZ&dkot_8dJ& z-*;E_QPp+d=gUm}$mi+qk(ux1tFFFg%Ex-@y?l|89+43q{<(X2&?+xm&(3BOXL8Nl z3pz}hEPontYsaz~STEN?ev`cBv%GN-oJl}Pn}dl+Dzb*c6b;fQ>z?G<+=8Nmwk`PB zs3=##E2Q<*%`d|8JdyN)^9DMhEDy>$pbRl2`3XtO9?-guw(9E97)Sh;w{8nF^^@Xy zO=-5b%-j^3-+vu7W0x`Y=;N3={JE0&%jJOg-eZmq9I#-j+nLP6aVp6U-5CuH0V^vO zE?x2;ilA+#!m}!FHpS`9((W9mSy@UN$Z~u?$qdtaM>1}yt_Eiw(b=x!Xnt`K7e_~c zx(YbI`!ZgB{#le|w?An6*&|0$v$%xr)93J$(Q9z*EI!v(t6DC#)8Kp>mhZW;EEcM( zg&v}<`xPr|$gbx=8Z>XzwDNV6D=*t_q-~_|NYVBaZE4{#E-g%) zxsI$k(w`ChmVqDYQ}SddJAohV+tC^$1@6hS+obg>t`FksVjqwUgJjzmg=TW5*0`*; zan?fSF>Rsm zQ7jGdIc@}Mi;bKG@wgqat>#?EJQE9**Wt0|oDA;fG=t2UAKuMaFWNSVNp--s6Y&JQ zkXfpe0-kw{@OBeMql7j&9)zq9UWiJaP%|JsO5!+etpi;x0GZ7k9yxUyzE74pnZKX82(no_s(swov=xW@Tl_Y3@(o$I@%(0RXkt)u9i$5Y;X&qWk&{oIS8V)iW&L$AMF4&^9&!XVXOv z8SJZT!CWqf(bXk9UDpl^2vgniMk5z9ZOyp6XArX~2F_+Si`k|o*q(=zM-Jh@$ur1o z(q9JO30 z;qdLId-a^{qPr5boeYkX%ST;h(N`@MV^%q&fu0AFsoKjUTC@wv+Rj_Li8Q zB=mScw(JoJGPn=qv!g1hG{SLqZ_csHd;F*eqHi>jYzx+x_QI-8cifW{<_u6gEY;TF zc1L@+k{ZY58yn~u87&&Ly|l7|lNT?bvb;PMsMY{Rj*Yl+XBucq za~5r#w2_-Xn_!yC#x1!~kgXk<(SP&|S$|Zvn7nCIuP#A+MDLVxg%%)Mln83eKo_%K zX)cg^iaE?V09urTLG~d_FWPKD0W^h-adI^1VC?AJ>RwT5#*(2jVz zn=@-5eA{lGOFQJ59N26^hz8=xF(<$4Pg+HiGBJ6@diW@p1Fl>F`ugtdXrdi@xT&H7 z7#Iiwx368}qsz8JrRu2LSC=kVHaCHWbH`CRK8oo_zl4>6{!o_cI+LM~Im@+!Gafj{ z8EEgAp6r43od%4*aT+bhhS2xTJ3m8iaCZ+}&qHHv9mc1oaC>?R^|iIw*VK%j(NQJ2 zNj6honSn^s%?9XoRjz%s^5ydSF!F1X8}1;%Npa5jLF*mCW~L}` z)zBG{@>~a-*&e87e7TW&Wzk4Ay3s z2?a3f3|_L89KuPz(DOLNG_JR!EsScG93&px!MY$z14*{=ykfMnwu;>JGSIx4syq=R zlDk7>q%6g?0|Y@w6bO_RoV<}do*(m9Jh$;7*wGl_>G%5!VXY*=zF z?OO0MKt%>qf<-PAMz(y<63@OLJ&=moNJm9lhUNB-3`{?Lw4p2J>na)uHuTWm-v#QEO8Zo;Yw2-@|uG z#^mbE|V3$7%y}r=du~NnJlK-TXFhevTtJe z`~`I07=!J4$Zl-pSB9VuT#%KT0@rlNRDg9EOOO?pB!1BAWF_U*i1i1pJ89j6$Pb?- zk#U?oRF+SoLby5E@{+FZ9oil$MTSJ*h}0;gE};=Y)Rr#mY&9ov|OZT`k-KPes)yb*M4@5 z^hs)%J#lLO7MinVfbZh+(iED@%J5iS174fFg^y32L@vLhez1Et);2b9bK*7{>*}z# zuODTZ44yjlC{AQDK<(W>hGb)Y1(*NiP1s-T#N&@00#I1-+VXl>Ux}qU2e&3Biu#vp zmX^?e21Gp zwkgRq{ojM>n2PqKAC{Jg)C%Q_v<6#|7RZ^*9K`)249Y>o9%R;P!l2UkNl(}O5}&S; z53UHtw!~dIF#5Jdt9TukeIliU#Q#z%NZcx=q503p)q#GjSCobIFV@wDC!;v7i>$i| z9~OGAj-Y&XO>jkhPWlLWpFLqCC0m}foa(V8|3%+L&|{Nrt++POSJG+ixl9JPx^^Lx z%c1Y$Rb)2E*2dv`!P*jRn72UQis-nI`YpW?xjxa@iq6Jjx)UOA_ij_$JFlbe>KV*D z@;s&=eHppR`?ouJa}&6E6L1_KmId_nS*W@<@#8!638v_5O0O@Z(Up@|dOzV_c|D5A zWWAeycEJ?vD8)rtFa3Hjd^TrY+!D20p0C|V*$(8*U^3b23*I%r9D9g>?F!; z<}i5iQizFNWZ=RoT8NuF(Eyt4z@ z%}oqkx`OhR_57;HVb&6*@ajW0a<(SxBx5#M$6@PnblZ;UN09Ht&)aJmuS?`D$A=$N z^PN!1W8)J>cRACxX%s8A^qa5MG|R`oE-9e2iXs(a2Bf55yZP)~mM9a{;evLoW!E>c z=j_E$#gi?edpy|4ArtOrl=~PN4zq(eK1VV`iD(utI?RsTMD%Q1)F5{|(v)SD(-g22 zIxfMSb~i~iT81-nfQrtL#=$T$u)Ekq&15pz)6qLlWv7B#aXi@7jkEGAWxFjD_KAPVj2tSdQ|>JU6*F< zCJ>XqNP`>1d}WDAHR$kkezsX(eAX~&R@52NAj+66FySqmHVHP<(N9u>(e5zH++s&+ z(zWU^A?e6q1&jYBDWU}9$$`$fwTVx93vRv*v}c}2tEb+Be2elO@$*c@NB)vDr?;jY z@srK_9|Q$yV*@yM&WGa!JDJ$=6Ub zat1Sxy@cg~fdYC!{B;ZF>cHzroQd2tn(DQhWj5V4)zX6H>gse2`gjcf*aC2N0(kER z@Xd6$6{F$aJ^;YAn>R7HxQJ{fgUXdvbY8rS4;B}3psp3LZ16@#fHh~C`H~H(S`YC> z%Pl2!_3A8sRV$fW+OEfQE@o0p!Ggu$fCg*FG9V_wdjq&%w9#lu<0I0rAgdl)@XC?Ic{7!2j7=2JsG?oz1LEDx5PN|Nt2 zE{oWa#W)Kv^U+x`qtVR1t$853lU_L_nwBd@JO*Vl13Q9u;i!2+vV-kF?97#>WodPy z9L?Nzwtx};ju-*DAGj^r(&Y@`ZHr#S`V`Z@OZIt&%5wNK2mC_qO6mJN97%??3%GmTHP;&42sZ zX8-_4-#dZk+f%T^CfOi|w;zs@AlnOBSUC)dS0UZ^=7@~0jv70g>k4nJV?8O^iEy{| zAIr^Q;9LJQvWqjg_2RE$=8@;`+B4_pfw$iB@zP78uPoftET}v5U{f;Qym$3&jfdoW zNcPFKmgQl59VSu>uJPu&w7!KKV`KRKPu@sXmdN(Jf(~P|EC4+9_Hk4$uOf#GUTE#b z8`ER>y-Ozm038+8_z(JzfHxN9WxM6$+E5>^3=R~1&V{|hxUhE^-Pdp6;K!!`KX`5i zfR8L_<>$VZD+{e$ruA0iX^n0HUIA%DXp21CspU8MYn0+JZ}ggJ`QM=jn|Sq3!q3HJ zis|)`H4+ka!*6sCk5KjrupSs(^+ahij9Vg8X?2pkvmQ+~YmJ%pI7{7cq9KhCxP<9L zW;`XO9B*glkWq=a^k4a8{n^CNw!v2t?f}j$jN!fM5gcx4Lq~ZvCf8SRZgC2Wo9lRE zb_!LV2P+@6ePiM_#wI6mbK*97J9lAkUq3RL3=ZuX#>tBpBXw^#Ev>BJ;>;K_U*3=X z!^0@g7EVCsTNXxpd$4Qd7RuJwOL|tzb48!hHJPeJ+B)=>FM6^Wg~GNF+Jxq2ZH(;hg$*Cq2K%s{;1qNn2UiFBgPJW1 zz1K!ivAh;r)&_^idm$edC^eX#5x&t5`95fTxtQo|!+K>oCfnLD-BS7yk)CbiT7MsG z*F*QU>nK|zhZkvHc7EjW>CMqG!s9%;N>Iyqmh)SW&ceHmkqeRKxv0N%0@+I^F*Eo$ z<_|rCwWeM7g%?S#3tYV#eD*vaRaHU%)YsqHsh~Ub>7?zRUB&d_t>N~xrKI+dTu(Z^ zJ%NsN0ef12lVey|Uc#l(Q5+m9?kCA^Zldq z2hHVmXeuXp8LYV{<|gpw^f+!-R-twO5OQ}Q1g`h&hV6OSeRUL-%WLq(IT7ru3OsYP zO0pf*7Js>qX$9wXnb!ubq43+`U!&ML&Yr5TN!{h%tQ|=<-iMvSpzZjsyj#sqHkrp= zm*#w_x*{@+OjQaX=uAUW2HW`va){|2&-9z8R7+N?qkz=Q10qvR_61Pl{lq@xu1S+u zHxf>08FiYlf=rQtGHi#><6Rc!^pm9bmCB%TseZC!%LA$2o-oS!At2E2jn(iZswgYN z^G6@Y$k?rd@?`LY z0|%_|*ypM$AZ<+P4t+Anwt+*3f^q!joBl%?v|Y9^g{ITTQFrMKmUs7I_RtH7Ws_&O zZ+te_0u00e4c4eSHb!G_vJ7MU_ckVN1u=+>tlqtgUxALen_;*{KRG0ikgKqo};_XK9bl}>cC04 zlmcCg3|H(hBC{5NydEd9MYNBjh*N9$^0}nVI{DhUANU-Wt&sJ%o`>~R-7 zr043@FUplfG6=s1zZd7euzZU;oa67%qegSbBUaClXux)K^vh8X^*z32avbX(i3iZV zX8-^o07*naRQt?UH9}|_;RdpRgFgU5KD4^XxkYWT1xAcI*~#&2ZW5N(DDDF%zbT8_ zC4*e_J0V*cj|C5ws*8FjK+cq1i~A|s_Y$v5iz8*O4t_7gM#z;74<8&olIXy7axPx{ z@oR8gDR+aKxkrQRPF`BOutf=J8RcuHo+tY_a6bg@2+Iauf9VCRR#wLHmqZ^Oehddr zox!dfx8UV<8w(lG1{hb&U#YF}yNQleo0uDZ z@~%H`brtyj_qkV}eA3$T(Y`zM>7_f>@Z(q4JF^&RTU{ajIS$<o2_kzsPQi%9T|-_r_1)!hxN0v59Ob#g8?0H7@uojI z$%QxW1zMRMK8H8eIpIu^$PqEm*4`3{2zVZOs${bKl3}S3f1}~35^4BiPI6lj;Y>eC zlZmyY_Q`zdR%_jGdVL8^WmRY@t43dSJ+hXMcV=#4W@8P9>zmMY@DQwgpyt^tmr-6; zhJo(gXw54)uIplC>=s-%m)JksMH`!&Sj>7D`Y(PSPaQo1C&eb5i^F@+e0v(@>+9lO z6sOLXR@7EiV_|8jXxX*$3QV=Opm8$h2)S62yQ)m;X#` zp)Eva7G#Y_CAMY^CvhS1W1@G7u#hin&SEO=0^hN5{=nW;o5nJ34(+#Y!`XC=UxFvtc?+T!wnlnw*+L+3x%u9t zEYQieC`>N+>z3IV@9M<)1N(~dEor2`7q;)Aer_HWORK0}Sb?+#k<{bpA3ff5t9|1) z)9>J7rmY!Qh6k}&d*_*;uM7>KWpWY~YipqK=D{4x7RaB^(mX0zsJxcJ@>AiJ_I}v? z?VOA1+v8~Y@CUfrcNnV&pMhW3a8G$iL)WeW)MIUJ!1}s{vN9l__*Z6~M1yxPws zHy}f;y|>qvvAd!YXT2PzH`md+w1~C!4YY4DczdL;7mYKss9s*lKTGzO)?Vyz^#LTp z4pufg<&aXBu|}s65B;AluF?+>M{>0&tjn@zpm^CGGD&6HE_E4B0=w~L(>kyyT%R6Cf zP1qsTaCTE@7(vc4Y9X~bPAQH9*0QcRVZ<&pY4-5*y~VlC;@@Dp>=Ez*jLZTNFc42v zKWFy#FutoZ+)cS%6z42WL-jQ^c;@rZq2cR4Q}Q!eY|{5ARFHq80P^lo)QrRnuPzfE zbLNcEKn*eF&3oD0Bh6Rw4(EUq1|X(mkjv{Hl=C3?Y>WG4P6Pf&bB&&<9q*h0O&bUp zh{|ml(OCx|%pWMtDBLr0UXs(6=WOtQ82{%?Tx_h9<_F*S)ii3bG$2{(Ag9VXp|Qg> zQX*^vz#Blw(8-%jIEz2!KqOg6P}STU9NeP-`#=Q0GqXtm?SRiKkj4$-cfFzvo8?(C zyEMP7903)p>nPg@obWD!a~bS>?HRb(1cgI!o8&x@E0i|$m@t~gB`Z$mh?Q$)62+Ow z?+kF?d%!M99tGXg1N8PXFSZSAgMDO&KH+qCSIfebS)NDzhp(ab+Epy>dl}=;yntlK zOPt;YArGR);b;xPQS~M$jWbB<^*H@3pI=F$IC;ozA&8f&eEuCV*_0`ZesZC zd5k0AdTf0aj~w8DG1wh{rzq2%c}DYH({ zcc0=``>os`rwz!rE45pG8jnr7k1}bI9vfUEv?*)n!#7#~ma~D;w$`S#J{^xp3Bht5 zQU}#qzPwN8yCp}9>B2zBd5{s9d5t$7#@iYA7l~MOc&XOr%vpAAc?M_ZuH%)q0sQgk zM*w{MM$a&QIC%r_tSw@(z7Bi)22fjFh4)UM0uXHe{pyP^agBfY9^Sn$3-33+gnj*m zvn7)3Bl|-0%ruU^e*z~SKU(lUcO!?5g%xaU7I$<{H#g(MqlfY6iH{?)rx;nk`w}** zEO=h=Aoffy2g^65onD>d#@Keqxisx6qzxCtwE&<;tY?fc{ks|9OdDoR+%4@DW>0Wm z=`F$XURhSkEUKB;8{XEzpE-a<2M@~`N)|cEtISSKnWkk1=m4wDv^C*e-dP*>mWM7} zLdUH!ffw1%=Y)3!|CyV%*uc$BTP?NqyYa&|FeY{c&QzIB;o+TUp29|X8CEMQ;b!6k zj&qp|-hBR9JaPOzl&`Lb7Dy?H0?f&>jkFOS8^j&UIQh2O{@}tEyl$44;hkrm#A;<_ z(I7&T+>C<@`-b5;Ho8ZygJm!CsO_LMcY@w_#n|9%+^n%!NUy(`%(A9OIR`2A~V@JpRNm^yX@oS4V4FvJT3KDig_GxSJVVA+NGI-J|T56?`#T{3T_(4DNJ#oEr}FN&YzElPT%Nehj{#*8)PhG0M88AiaA7mwFWUl#QJVmwIf(J8@I9Hy_eg00&!-L@ zgys2Y8|T1nX|*quGzk@)DIw?8q^cGJWJFfrkyt`0bOko%#& z9&jG6{pLIL38&~RP11gRa|I)-P(s~-mljXGaXhk`QJMa|D91-U)qbdfA4u5 zd*ooM`-nIJqscwDLTU?gbqZ|2p1SgL9o<;2t;Qc)E^^H+n4X)%?83s9gSG)+xuzO( zO$~WI^IkjGN8S7ad;qz8f(*UME+|bgUV&ZR0jFeQUl^qn18CE=Z^&hhx}}vl4uRb% z*5-D~kyVJc=a~;Wm25TMx{)uwu0n1x2~JIejsDFNSNQ;B9)?mCq!-UQblB;{pp_lj z6a*6AX075gASI^{LJo3O|$F{!91l^kSuYs84{0!RtXNx;1 z&o<>Ej#5cu#P#6)!`I;d%ol;C(ss^ilR$CWSXe>Mb&;v5Kv}jhkk^1Py*QY-J&Cv8 zJdU4z@g-EY7jKUqmjTFhBR$I;u)@u5y7+pFbDYirmQ+giyBxjI?{NTIfA=Dv&E-)p zp;8HmZw0rVjmXl%mwEejiEW#JphZ03;hJk>M7jy4Bc z7PFCG17$7Sq`@K@ux$pLlf&AFm$h+acrbMqnmy+)qW9_u?3^2N5Crv+(?8(NQ~gHY zX+&}0IUwh>9-V{%{iq47} z1i@V*c*^#$SYL~`pM9q2GZyP=@ssDDgX6k*?)9G_yRrd0-*s%v zq8fr8A#&^hyn#6&#?SIj!n2emFF2>f)W5W=R`SPx^|ni2jApvebm&CuF*QEvqSIRo zgF0C^kA`~d+T;w9l297$H186*m^db=`_kfVyg6|J6^@PSjDs(<_v7E*I1A7B(E8j9 zINVeZ*Ktr&RfUX`!DkL13EqSVuzCLI<9PE|=g~R1yJ%)=v%i2KdvE2+YSDYFLmg=O zo1epTPaG>+HkZj@rK&0%bEW8#uYBzbc>Vo%Q(_zSRttlJh40y+2cP=;Ex4|a8#nGZCwEFo7}t-TKB|_M;lsuwADxDqaZt0ggz~lZe2chcGVO$3DXnnjCEhb|@iT3m z_`j?iMlPPmf%0r>-BD65lfhJL3qCsf7!IHK5R}@2Bs85O<%2@Y>^v_3pC?5`p{~I? z?1r{^sg1CVkGFH0_E7!S3*%Jw9KtB4aj*GXX~^!=i-EVF;w|3M-}%i-YY1IUvaplZ zp{*%_rV@N(D-LfVutfbd`Z>)H)#irUa$xP3=hQ@ziRQ_~B9@v(Nmx5>#!ww`XkBaG zQr2-mwV4!6%1YgaC`%-9d&O>$+4?}cR*%_B3x0O3uEfc(&tYUlrI zONP{4ICz)1GBa>HaN%by-0o@*H$9h1Cm%b6Ll)3>YXWwTa&;mv{n*2)`O;QoDf>)0 z7EQXP6LGm22jg8GTMpQkB=Iu!y#rU+1LABd=84&+2BynyH=Q|n0GZ7k+Ha2K``I?0 zC8c~}DJfUJ;`&P3a@$XKZUfb~E~4$7?_s&?S=@g5*Wf>75zh+?z*}!|&pr91g_@ec zN1eI*d$)IJhf2xSzu$H=jk@&oSFSX^FK&#kVkRDPa9ba8kOVB|upTwTReZy$#T z3)!_zSVj_@41gg04xJ{;+rKE4C)%glY|P=jfPOEl8Qf- z)^(W9Uv%DRV|pv(pS_KlZ~X80 zzgzzVzdrsiQ9N?cGTys1qVR4W)5uszP)5yCvi^7;3L87M(c2tTaR7`LUJ1P8S{pr{ z%Fc(Xnj_Ez?$H+0IOR}gn(f7Uh~-N3$y5Vx#*os1gQQI-wE0gO22@~K2mm>Inx4ZZ z_cB07x|q#8qqM7v`q>5_H_1|$-@P`Fnc2X(9{TI%4Nn}*ZG~<0U|HOoD^*o^?d2E4 zHazpz+o+qJhwoDxICnWq8yB<#o!*3<-_k(u#ZxW}=7GnXzHWzn2j5Q~I)t%ZoiV)} zPZ#&@ftzu#_w0FC2zI#9IAY@k&kH(B!3VEC@%aTy1JFAZC3zh5%P(7~-o8!lJG4Uu zDb0+m899y4SN{mhyZ2#cPieb>`8mZ*aR8smVwR2905q5`#f6Zs^}qcA{F7q{+Zc>SY`DlE z2hx}=c$jaf$MMfRRZ@Fg$H8kazlaxq^cpIcSHsXTGO$Z9uQL=`U@XFNo-^NOz~*T$ z;Ah;Pe_-Y)T}+k^($+4fSLDH zZdsO^A=mEYHMBTA7vejNF{{mWT7v|%lPeCVMh!VqLuLM1Yi1Lg49@WLd__Y^sTMy{ zf1&3_5eYd8%|34_uf{VieW-C9lvx&rs_XHKy9QC4$)L8q9qrAH>Yl2YQvj~rx`pMo z3N-e%qo%4V@_Q2bs(*`9`#=|-YO6KIQ&UG%4bOQttE=dx3mRGn^bU( zwvE$i5!^=<#1){(Xj^sr^+sB`(bf%*L>}u3PE%W|EgV$5TvLtZnrf_7R$!r_4wcKR z7`kvNf4pTNcLGe72_*pWz*Ym^B+OWuB&EQ&G5yWX+<^b}%5q$IWEj&erDa)}YYaC0 zU$pmN@Zx1OPR{1BZ_wjpd2nOKk`1ZwRxEjRiPLM=MoTSgEN7 z1^kdz)DQV$>1>BBp>e^piDY#AoJH#EQ9UE>ImK7=QXSUL+A^vxe}tM>{|#&>hg&ay z6N~+i!YxlPzwZ_;F9-itR(vch1lO`zoegY<9v-Tx0jjF*M@Yrpq4+hm7)6niT;-%q zPCm)hp}DT$-)v(8t_-Ez*>HIp{=fYQ73Jl4?(t*Dqz*0#q;k#NQph)D{{l=OlRkgK zgA=Y%tQ!O?@L*LH+J^_>R8-*B!~|T=L+=*!tz0I9iS{;peE3luICTb2j#nKHOy!Ki z4)}B`Q}>`iNST|MyjDz%4p@hmIF~K`Fn*7xVu&sJ`@@V+A9hNIueT=eq%@E^2iIgn z%MvqeneJh$jo#cBY)K%!hLNt+oc*w-XlqUBC-VSnolf4H)L$mDAibUBhHumeupNQU z*OHb4vO8FiGBfzU8RRVSg~l97oSL=(jbFB6oAkVVV5Vg$A9OL2oY{7>n{nw$wv?2fOQ((BR2pzpi`@))h+Hlu&$-$7yE0Y?a??D z813oCg#&xB|Sc&ouNLd^AhD{46=SAOc;y$9&$H?;^P2wk|7-?qmw>0y* zR4d{(lJB8rvlDtGw%vhAizjhSX^-=hLehPl$Pk}GJlKNiez>bycQfKA(OO~_Jo+{T3 zldj($$B*7Q4j+L|>ex2E_Ssj^R9{-6T1l&wmH6>zUjhI;^Tyk#URVl~j1liaLSHw} zlPyj$WSxo5;?_}Rr0FByPPT>17BUKBl*ISwUy7|aX%XG08Jpj=plx2}^(&2k)rAFv z1kKvPB+D_-Bvm^w80mw?SygmEE(0CVM;TFryn_s`O(8?XQ`OvsAr(M&k89->s#fNY zLAuVRBo%$+OL9PZ@Rw9L4eYsovwuzJU7Y&Lfhiu$UU+AE1n*8=4WHAPEyHj1?Z-d4 zataqV7Q*bhPaZsky?y<-I68uxw{PR6V^7BP=YvHA&`P@JKs)UJ>I=X>{b}lZI5^wP zi4?b-$@e9f2%Z~Ig(MqaE8BnGY zOWaAIjAS8)HdDB>gB*|#8E1)UW+U|SfdCp<>vzWn56;g|nZ{gP9qhx^K|aRaJZ|~D zV^6^Hee6AZ9$nXOhVqN^hfy|CA8Z&v{%Gi+Z6xU!B>ST8%wPu@upRXIi6@R?vaJ=R z(nwz~Jln>;)91o*X~D{yFgPrTWj~Dz3o$w?6mlSZmv@p0O3PSRBNRuF=tY zDVszwI&$IzoO<+N(M>JZ-~BwSzq<_o<1u`2?ksYrPo+Ads{hgzSgwbQ`-Tga+kfUP zx<_t=tEZdK!Rgo;{Pvz_P~l|3>y(F|Oy9yeFje)e-CwY3wcTI zA~3j{r}D^EpLG&jxY60z9+Z}d#5dLh)cGhFLuU7u@;a&qY1)3-p4RyL$)Yr^ zE@bYG|4nLSQBB-Zqa#|c95qogf0LWzq$XnL11=aDQb>l>MW@2J);4PQ}g zkYpK<_|(LyGPjaO9ITg9OV|;eWMGRo-bvGBF%un^Xez5jOIdk-`(zFo3piBQ1P3m9 zMn>Rf9W2zk`##!BjY3K7XeO+IK81BGl%TO)I1o7dyfd%SU4j#`-^i?EC~3KO>B-{k1m z0mVSvIF~MJ-{2+MKhj+5DNd}Ir*IBs&fK9_o#>Wy`B?^VQ<{SDt`1!5@54fU;dvry zxw;z5)zv6pUx(wn=)E`s#_gOTlxK)(QIWG9qKvkf$$PAjf3|P9SqI}CrDr%LnrUi+ zHRz+yx`xJy8Bpd@;>ymu_xa5*&r(9d_%27ldPO;=T3fcvqe*j(4Y=983!OK{gsdfp zzA5LKSjUN@ILsSeg&zd$nps^!!@0N6`NKcLbaNkWJ@rM*4;_V_2_^@baNY8n2Aw~*~?!{F|8 zC-+H`fthif(aPegm6A6dNgV<3acOu6ZGF9HC@aH_+hr)vmX*vCk?T0P)wK&5HwW8g zKTzB4NiwBLtfA{QRca&>A4`m)dnd^jdhh7diGkBle9uJR zR3WTvmJ4d|)irb6$j|y7iGnpBrvFOTEww0a73t4B_ZX+ssZ^%6OlMSC#xuDsQOqo7 z2Yu5075${^Ae$A{9hZw(+o8z!#n0omB?bJ#xGME%lVg+b-IIKOuo*ZX^lzLzva^>VN_XQ`I5PU2)=lw*rw)T*bg zgeG3yJ{s-qLC(ow|H(55-VARf=Cc+!$T>Rh;_Fik_x!lfaS3C4cB8|!QwJ1qR!14q>hIuG zLzCWn`UxC){{u8l&4fwDf=yMnvKZ^N%2GTh>Eh&TutfhPtrO{VzQdchmCr28!;S`tJZMbEAOJ~3 zK~(Qi4L_Z_f)8e{Va44*e|0^MG_>Q}w=UwJT|JH2jSbX~T*Lmad=<6r9k?)Z4S)KB ze~0yr4YV|DPb6KTytO91bMj+cK2n2yU->c~PZ3abWpDsKEc9NvhEfDfTU#rB@o)T9 zSiki1*!mW_VrFIeojx<232 z0v~+fLnb@w?6fdkI6icTc4*tlf{)=p{5zOA^diPz_+_ki^uf2CJD!Q8e@mGWN5K|E z=0)qHK}~Un#!M~;$JM8*#L+9CeE~oIr*B~lW5~HKa=CQC+i^W~kKRDr?FmDFV2S6# zM%mg1Jl8gy)xp0CC!-AOuTI{?yR+l)d>@l7O&C1)If^*D9qTO7Y`GL9D4kTE@kA5tY8Mpq$b0;C z>8MM>tV5#`(-E!vh}&k$8qISYaXT~)*Jb3pi8E80HjG`j#xT**UNmUif9*27+w-`7 zWEPu8_7u&8EuTTbGG*%<=ouNsXm7IPZfG=heM7)g>e9xKTpa_55KxXpS=Zn~9eR*Dywti3l_g5=BVY zAM(HItSJ!p_#ro(P(aQ#X@%jM0}AYMakxMFFPaVdc4s@T4)kNbzP^O_!L(jpj_WEA-7rU!R2%4t3a}PcYpZ7h7>Eg$F-TTIjk=+p=k6OiR-r zUB$?^j{^WU=2vj?AAcJM{>GQ#lxIt*CCKJw>de{-ZimS_c!hFf`5*1=32m_5?Ywbl zZgCOQ^K%&NE-kR!w=9hG_Nr?u)zz4oC`OPaP&8IsLw zSJZzclU+pLOcW{ceaYDPljhKU*h%6e`9@9Ll)gT|95ajrwcT7k)e@tUudbcKol{7cqny9`G;~ujVUz0h6xo=oMgt{hm+vqb*A4GJ; zpdOIAoYuRU{%rJpEa%qn*|tFp)-=M0g|kbGIKOZke`Ocr*B|`!Z5-M&jP~YcoW6Vs z=dWG`05sIq;pZH7SE}WE!fp zfZ>UH44HO5`=n} zv3xSxl6-2MBayN6cJrCP0UEUcVXjCtW=Zw6p}g|Gp3Z0Rs;Y3Pxw0l{L*I+Ae;ruN{PS=?bv63F|kGrMgGX ze_P0Rts%&=(WJTBt{L@6Npfr(PFXq1GFkk>E1yGMO$}as=Qw8n@egqHmp+SuU%azZ z1U9o-oO<*i_MJJ0*6~SjQp@OOBrDV|WKWnjkRWQnj7{3kVSg_$c$#NCNcQ7GWWnEB zrtP!p1>pc($$TWKM$`_SUwcyRsHGJk&Zi zn#(fy^`5<<9SC1c09pochQ>tlosJ9ng z?d_lBYFUvnGy>Q89GRRhzn>AoHH);K0S1g9k9StFvIRwn=Lh6}URskMYh9G|bFm@WK`3 zkOAiqm}FT;8N^<`SW{&?chC>KZXrRe|@sO`L3KKt(QxkKTP}%O|_6R8_&v1P%`e zE*#{9glGMnRvRn78n8t7)H+6JLawVaQ!Kj_Y0cByQVXpG6g<8alIx8AEKx(+EIK<5 z@iXx^P$@h<4$tt z0*v#`Hfqw^UKDlkHQ5*3dUh_!I}1r)wn6CHELA3%_c&*ewKgyRxp>nP;7G~$F#4l0I7`G8vX9F`&jFbH& z#{zTXi>I-JQioq_jyM@Wu&LJyxu8uSfS%P`~ELR5Ef_tk|6kZeJD6_hRnse`>;oa}S%a-Hn&;L!V zwD;W=?(QaCxdK?0kGi^`{WUefHcY`C+M%MPbzxxpX1;Iy)t}`|mvX;qWd$u$Q@hcE>`rvAKbTrKQw- z6{3muHcYg)p>cK=883&XsTq)0jd2ODrEO*nulA2Q-rj?=R zzHukd0~1l3nz!zgc;AJ2YEPVeiIb^O9hyB#nmet7S~%9+56|C3YejW<->U0kW@8=m zxg5TA>jv6A4+n?#gxLza+uKo>$CG8kxAW4mV{lz}%Zb9$jL>W*gXS$9b5H%@q;Uuo^j`S?n2hkZ}VxXvfJ35A?Z&_kz z=_gD&=}L0KGle(q%KH#r(>b$sY>Exet!;tM7DgCw<*Rixz|y9T&4)S5b;2zRq z26ykqo}S(k?oN7k)COy=3yiai)fR8hy<1c{F^bNg{0Y{a45ps{MfeTrPZ&%~dOqJj zeQ$=rS=wr&Z&I!o8iPYz-_H1^ ztz-K;;p1M;?MUQE+9q#x;`7UwK-e4>$qsCqFbJ>Gee!6TxIx6_I4C=S)~r@aXRZur zG+ThMl)Pf9mr|XN?^CS^X;+Y?K1-F7kGYag5eZm=*4yIw{FHbubV#f;tp#`4AqbEh z1I^`CXf3Y@!A=G_3{}^|$%ojCckjkZd9XvSp|%zcwYBQmStomFEiRoSUsGGWY{&&=4%1xw5eceSPm=O>-pEe!x4pa!Q+-`%YHz`CML85_=Q55^r*lQn}IC9aLu zob*n$b}4mE(-0I#Qqq|&7Kwn_j$q!!GEUza{}lZ+-9Fuhc)fCNV--uAOQ>-&=%}c| zrtjhU$~D=gaH{eeO{ITM|6&;yCTFp*yo83@x>TE}3t_jy_XV6L&8f+ff>_xJH$-G?>N6XF0=2&2x54R`|AMsqJ6D9NpS{Z=B7AZ#M zv}V&x)VR&;zu>yWYzvKb$Yr;bTSAd%+n8->LjCj{Y@cyFTLVprWXcKoS!Pu<@iBj& zZED1o!GSyGT@!EcGHoc5Pt)>AYe`bJva~aIWqcO1*T#W?CfK%(j+WK}lAcLsvI)MM zTY~gz#hl+i-JsN!ylj2~byq(|?FT=?dRYx_eEB!9(vj}{KZttJ<;wu|Ku1Tg(YZFg zTE9d0kd~IBHjM|7OdU75+;+|UsBA1wT7ovr&SBuvm7+o0)}c;VKf53PncF~Z1+3qB z7AP;ic4;dn#7bhvN_Dv&^WB#CMD-?b-fe4YMq5)ea;}Tp6O+K%+h~7gKQfi2+ir3@-*sZ7erWEV1cL8Y$=ga&^j-#9}u3P^-RC1c=;&XuIX;d(+5#jKj>7- zd`^-PN%%N+8uYbw#D{F8e#;ty=3`5_MJV4iq*9kM3hW(i;K99WwbojhR$amxnn*|6ndw= zF>_?3(V+{i&n6}{{e9Yg#9T<6E$c8hJ~N)yo1qH>u7gA%lpHL{ior5L_nn--+dYaIFDKb%*g96Y z9$#=5--ak2Poj}qx3H1h+;ZS^fK`hpKG{wkVAo5B(6p->Xst#=ZIM&=Vx*=iV`Y!U z*MY>}3O_qdiQ@GZ(xECRN73__{~XTR5*9!6b@&~9C30ChnR>d z?B8!;3!xM{^eLg}TABRYR-dpvYX@51P zTn#Pgtkpt%=51SmDObHjDM3188tQ0n!4p6CB9>NG&`?{8@u?|H&&}eIp*^YYkE6xf zTC7%8h0$rYz}Q;9XDr0m9AhPkr%x)r-ky1Lcj?Z(Au$vWx+M@UtaeK0h|U!jl#+nY z5AO^nlib^Hx`wzksee9#L*vbiI$GH;1W+}wmTtDVj8N%ZgA%4__Zzj5T}#{&nZY1v z5$~pm_PW_3&Th!9n+I)0v%jLP`UI2AXoG zw&{F#;9{x123Lj#Fy7e_;Vlh~cXYsUU1Zib(SB7#_xro^IqacebRgRaRiKwFUhbu7Glz`v%X{pZuR(GqmxMM_q7#F6-dR z@Zh!`6Sh`SfyuU344uEIMuwH}4@jd5vmzBQL5rKKcPN?G)_|Kg^)=h}v1iZDanL(- zXCzHlW%HBR_1Yh!a$*$YFa8P^_8fy-Ug{BV(lJ{aAG#LP#LVAd$R{eF-jx8Hym%3F z3k$$oOTf!xz}|f&@@t3sk0m5FamyU)Q(&mS%?(|PwKYI@H#+n6x3{$5ryqZ$o;lpx z7w&j2Ml&&)ZOhl!;bt7b_c3(-GHj2-kSMdZ1DWj-Lbot8k@(`T2Ch=ZllcSTcP^=& zCAtqy+WvJTow4@QNG2YZJr(_}lnu-XYhq26$Bw+l2pQ@-mj`I$GhJmvPf*f@bhm2# zkVjzr$THD^d76#H6*>=^E+N})B6RJG=;+vkm0S+r9lr*^$8Yuw;f6G?L9Ct+lBw3Z?l3mKcEPn2#+(>7wRzr4DctDVfRX>Lf>$2xn+m1VG*KPilU zmm{=dbq!8Vt~2pl(}SxVYDIW4uteB!5g=fM?r+|d#4>{eyfr>H=O`bAY{SE;M-O6g z8zM#5%ggcZlgIG#_g{sx8F1pj3(eXR=W6>()Yf7CCf~K5WyMF*>iRl--$zx-gavv` z&^1q-@Iib=(P7fePj5j3ZoYj6Z~XH=NA-XDS*&kt;G19hDy$->fsxi$3dtT#U;a*M z>pDz!c@Aywei!u@-^Fs*Fs7dTDppelY!jL9VSC!NJv2TJxUP>whjuXXgGg7e`nYl9 zeshuJ`*~0(y1J2NIanJ5q80RBkmuM~s;NfB(pt!)nDp!ouk{)C-=fa5N8Q7^)S<}BF7ZzZ5q$A4`P_8-;z*+ldDZ+Em%hu?Yc0i@*6sAz(g?`J%v2(ZPPsqn>5XL-Xe)Ez zz{9b+CX8ObimLUMF7&051@KX4FiMra_k@@0h&{SWK-Vzc~_{LxQrbixqHf=NfIlb&H zUM3ljFn`7FH!-usVdh2zz4_UP^eO9qKD?}rk^X*I@NvDj2kR+pE|vw%H8fzUws59T z-?7kpWdybJ3$XKn+iuvijFeca$W!fnm~x0(tk+YsKek`?#@Rn8KrET!ERnj7JEd$k zgQ>Y$T)IArq1}ZumoC=U;zoBjI&X|A9*Wz6XhbFBS}i3DQ{UH~PE}6U9sK3BDUFRU zsa^4Fj(KO=5yUHfVP2xTR>jl}?EcH&NBPVcCLjM9%g5BfJ#dycR<#Xq}i0Pqfni0?tU^j?=O&)jAWGmu5rgZs(Y0AQx233Uq#XudrK2X5XzOkQWL7qE9R&c>~YbgN=*E5(lzfB&Zghi`?p1$`6( z^$lYE+g;~<|O`?(PLzK_$FFTwRZ4DIeo zm31q;7lDARpPfhR#3Ux$T9XS~7RIM0F>&bvh8sFid_PY9wvyCupr)!Ck3R7z4(u5& zsebb*@x52d)ufVX05!vN4UVC%L;aT2M^OWi37iS=$s8kcS9Bccw(|id(R?H_=vvN6 z7&D2vmd1#{jmwL!8`c@f3WP?dAP}0u6-)^f1<Hqp(lE&xEy z;xg*y7L+`bvdrX38W>Fj8k^1_>N0yb-?nY?)#&F?khVNVQyVZiiyQr4x;3cIpuC%L zaIL>@dl(fYv!BuX^}r`L$Wazg)Q;jSCY2AU*j&CBrt*iMu3rxVxBL4o)TBRMXNPtu zmaY z!@oFH!kx+b4|B>Zr+H?AUSpGu2o?Z4zk%-T)hp=f?8L~}E%?5V=7!RbH3fn|u&V?8 zuzVkxoQvJpuEW`+>?pc_eNafOJi$k=$MRGjI;K=>CdH40j<%a!Wji4F{!yV-J4 zV;JAn8P?Iat1JHLzy3Im_4Q)7e{0!$i)o;xlI?lO1rb|p(cjR>wvC3;+Q!}t#5AXwQ#B)P)OEb}SJvgoh4=!9}-~!_G z2$Bb!Rg>qSmk;dL{UqloAB9}Vad2m3&hxnbN2E-gv%)OT^_lXl5S_Yo5o=2;c>2I0 zWNXvez2x{w|D^39=U6Xxcm4v7J#rA=d+W`DWlie`Q>kzE!PZ;sjWu+<`DbW6{RVD7 z^EKRl`fJ-#Zy|l*e$eD3@WBT@jveFYXS3Kj#`z(p?Uu23LuTIz`Dz^k;>DS(dADU2u|I;cTT+vo@)^np&${VPus=_aQ z^((+vzrxMP~$aTSua3{e`TvQqF{tUzAJ6nH9sd) z)b?p&i3g1ywE07n&LX}2{hEw(Bh(Hrjec{qBj+^1L7J0X`)t zjzb@|4-8(uj9cBiQUq;Z#M1E-Xgb`FMidX)Zk(D8gSM&PoScin3zv~|GPt?BYfGoe z5;-{+yKdeBTpu#HC(S7CZf{3-il8J(JdR9>8(b;;T(-d^=a$r^^_VMEt9dO6OGWVx z*RE|mF#bxPvc#FZxtYt+zs>Rt#&&n&((q8x_DZ_3J6#a{&8{xM2byMPP`$K_`k6T( zAGq%$6Uq;BcQxw{J;H^xGqqNIH!g@~l5jtAI&GA)}@S{LH9_&A8#TnqQf z_EOgm{{6*;>#L_H=VIs+N|~a(hzg^VB+CrHC{-lIwuPMs%AS1q}cIAOJ~3K~ybG`yOT7CnC}qI5N#=+uPW%qzjGK3tSd>Tk)~-6!`E2fj zX1F5_N4)bnx*OUPfIQk)92&*PIs-gQ<*br($^w)tTpmM-{9=vpn+?v)MMh}}ONkc~ zUg=%nvrP>c6G0nyPV!kCg02Iewe*QUyu>v5nedPeBDIT)u>I0@#}y(r&jrs6vZBS0 zt2o1?mYQ<>-JO{cRf<@3i(fxja&sG!%@}bC(00!A9R&**838QIM?*u<57pH`W8-~h zYKIbOd^|W(>_H=MX%6<4)2N!9#>7)UkLkmoy=!tO4e50*Dq&2g*p_H~F>qM#ZH3iS z`lONIS4((phWEmq(a5h0N&1p*M|oKpo;>tuzCK`o{{W7k`WW*cT*aXS`_cSZf5|+D z{8<(*?%e~&bFu5jEo9bn(2g^iX~~rLzWPmu*vjv`MoV2io(iuEg-zu<>p+xB?~URs zbD_5&5m>Yy#>jCx1HC^JFY`ATqfO?`CCp1T2HOl|85xMF@1Jp{ga=- z|0N$7O1s^dpHG`b(!8Iv)I2$j!|#2tC3#{04`0ETU-~TCTGQch3JlQty_pp`>asNH zUaZ1}9hWjYrio{GG?*tx=q%g(-G+w@a_aBL2Oq`wt`7J`qA5Q*@)#`N$DRupk=e}Q z>?8Y&wr$|@6%3ufl%E-tO&g%Iob2!yIkNq{B+;8A3K{Ox&x+D04*y4~@ERG%tFAwJ z16mxN`-6Xnjpf(z%D?*CsmgCRl`?<(ySmWV)dkzK@XMe7BJ3hrwhPTSZHdtOUUEHh z4GSo$VU%{M?QZ?b)_NGmVPg3b{6=-5BT{ny|j~g`_n+B zjxtjwMrrFSvDAF^voyMj<0YQ7op7t<|M)WefA%&o(1hB5^mY8om%dz7KGrNP;n_Fd z#HODG9n;K2T8+ipZU9GLypW>M5B-+eo@uSbajL-b&O_Z%} z01>@Yd-94C;b31$dv2$Ro9{oR<>P+ZhPIR9u~hN9;(AGA*fe!&tBU3$e#JCBofe{j z+q!Pak&P(QmgpqzGjrt|t>RKr4?@Csjh6iwKBKL*BHy^SWZx8DGXuOS5VqL()uX~h z=C;5>awE0uExu~!gJX(s4vui~3kQLL=xKR{$i(e{kG*Hl!?!Jr?dnXGec7b!<|f*1 zPvDW0r;$S@JYDc^o$gS!v4N(U*~om-R!6;t$T>ljjFh%ldYPl0uW384_U-AhOlz1!HTDBbMt!p-h3v`$Q7&-sg}onHh%>Az@BOLRoIlK*Oom!Vss z*@cB*Gx5d-hIaQP25m1_S7WiRR%N9RDEi#3uF2-SNLxo|ODj5C3MB9oWZEO;+>j$p z%W&Vgm+udJ6hW%DrkNRRmSyi~lSe#R;aG{cd$Ht<&J+mV=~Gl^Oq$y!_KuFTxN%p+ z@8IT8HF61U?|v8K&wLFthhDhv0o(DEP8-=y8W{n6-^akfPC~Iy1I3T9yM=0sS?IP} zM^xhtK1+!jx2E&@JlEKeO2?X}qSn^$*_!=GRb&e9OXgOEVfLW?{LdJ1>TI_Y^%c zM?FvcOG7JbYnZul8~){KIAvMvdihZ5XPJvevSU$?qab@&n)a8baLSTV7|%RL?}-BC zXj|fcmsz*vKPR7AjQ*M#yQ3}DFxNI@fTc>%J-jfJbfClH1F}QMvlF(~%gY%vFkFtB zsPVvrhucYPRHOfbK6Jw{6D>Omo7?~>o{9K_kA z+u{O9taZz9w1sU0#t|+LqRfRAPGT1KZHMuP>7-^NZs?3|$<-O;g@0@ebO%`#)wgLv= zTeWO5wN6iWO(kL}I+J(aUf#4VSSC%F9G<;Q@jPy zwop3CJ32ybhBbQ|q;V%G%z(IF zNlj^0bA$kgu3bmU%axAQEv;YZ|sI&!dVOmbt!>TxVLK;6oN$0JlN3(&vmiy#%)j>(6F}Q)?m7(XCXh| z$|RdaB6WYoDU;3O4}bW5%qh5Ap=;EiASM%j_*%BN_Y5`E@YxpZvrKDdAHXE60- zD)BQmDZ$jjsC=zBg3rN4nqBkYz=0}o_#~thtpTMR5_P$Jl`)MQ_SEuPbX7{CH7N(} zS4PVB(fb#_h4q(zfQLW*pJQtOD+pBeHpL{WLy>j1R>W1hAAAr--d@AVUpA@?IV9of zHq3EuamH@&v>Fm27;=-AiG2fEh+vC;aC*Zm+uJzx=)w_4Fc|$keeEC%3=Qa6`Bjg*s z(abN%q;e(GT;9pAQQD@V3N4N&vf4dQJ>v5&|HY?j^iXA^fp9XvPI=k*OB}Z`Pna^F z)Fqf@Qc631hRDGzSIW?2xsttM=Z5sZX@4>UDA`WCrN2?ToxQfaCY9JKw#ikqCya|ryf1m1|gRYQmGQ^;M~F)50QB*&N&I!pnF|tM}fUcc6j*gS}fzo(5x5 zOLH^6`RZ%p+T7v-GGjAnsBb{?=42ZXsaC7y($%6hjJ#SZ!)aRz#hQ{bA~T)*Ey1n6 zVx|jNO7p6MW(~GzuL0=T=P;F1080dEd8BR1*`_|@b&W3LCTlYDEKbrOW19Rp^W$JU zDyl_QdZolG3H{~MI#1I<_GD*o9vFn+Agx?<)i)v+0DnF)ifx_;&aP}u(~jfd>t|oV z@BLS^P}_<#=|Cx5eCZ@!{n7hqoR_<6s=XZ6FR!3}Ib-d~I2s-w!`uJiPvQJOpP+mD zCTxD|Fp`}gTB!m#`BU~8oc!5RrP++m^w&NfO@*#jBI%=^$uLch+}dyr01GWmfQs@U zJ{y$pW8M5hA+0H57X$~-N7KSmp)Fj!M0@*n%rG6zJN!+ttj#%N>qn^|tMUyEW~*IeOH z_??^s#IGebh4ANro`>bCiss(%EP|yhTAG^Bm|%Bw)8Zo1nQTE~kRKjnltX-}1lA-E ze@ad#4;+O0`wI652k~Hd2+fU+SYBB{>ng$-+&Z`)4a>{u9v;g(L`k)-lb0rRoz24( zHL}p^UsIlthCzO(68d}t=odu+Rt+kSk9j)z#<jY29E#uUfRW=`B}7fr?G ze3BRm&o6d zn@cBG1LjgG3~k*4Upd%!{kE9rdItIhsY9!`_2yv|Owd|SSE<%RQ#zHxS5BY7U;OGg z7TZ$z;L>L}edGxGHgB<}FQy#>!u}5(%j8qV$gcZKMs?{l4jkNvY=ZeuWrckkFgNkA z&Su%RS!tR_q>NQ9>KPfu-dlITwL1<1ZtBm=2A@e9Cw}8R?44Wqvt8D zFH%fy=)&zor5(A_>l)F})e7W%;OXjjlbiAkIc)=OK^7tY?L!p;bLdlV>X$QR%X$rY z{Jvw$R&;l+FZ*a_TPvb^Z->>MzZdgOe!em48YQ99=pl-G&C{f~bvXHRgo6p$ax|+` z=)08PK2(1!EHcx@&C);YO3_cf_B#If?H?vcDM`P79|}37M7<8&xP`!RFxa~l zDhQB^u?+!$>v?cJ58Y$qIDGk9A@r0EKcy{)y^jWw3OrmrmORi`F>-t#Zr00h>y@aI ztf&;RSH7R*7`hZGkaL#pUK~!2rsHHjClQStn}l$}`4hIDHavS!@GP5N(8raJr8b9>#}WndtQ%X^(DQe z4>vy_%rGZmddKsT%H@jAw{mF1_yi7LxrQv#Y?Nqe%7sn8#QT!!OWs3#6#7s|<#KR* zKhdW6VwBEiarDv^v`x(*hg6}z$(9g^vI%?h-%%Zb4gZ&Vf7B1kn%+j%G`^3z(MMSS zAO0C~JGW!_>wgQ`MqBWl7h495o0rw3!9iefFhEBKaOzZ8R@DQzuhHj*lH=;y5a$}j z+@0+*B5@={xK`!1y@A2U2(Dbl*U!CDG~M{dZsc4SCqKGqUAIc5!X z9t5Pxh$q=g)RZX|V!XDd7%$%pkI75*FJ_VoQ*<{p<8N#`2p1Xr{l2|89{{rn1lFaM zWdt)z2y&&Fi;V(=0)0B0MRrw6Mxvbq1K585VPTiDmmrps>$+$>+KZ0gK7^lsskqgE7`^W1sFxM+UvzkqSX8ifrFKC>4ZJ;vC@ot7l6B zxccQ~yz<_M`1qAGMaM?V+#F7S^f5fRNM*9ny6*7!XI_6g!ito2VI8$%JqnA=516BR zb*X>v9w;B^>wjQ*7rb6(yfBlB&w1O}h@+{wS$y|9-$nL+{4W0Xo!>&Lsr;kmc&*Ay zAC9VWj@9cpxDCH}>7SNaQna@MFHD8!i4~5 z&JajWvsr0{@{_Cl#`5-muuthmDD@})RrCbEA1LbjJlw#YuxJp{e*U}KjH(60D^%RFIV)9?s(_1{C&!a~7#1cdK%|MgqAeQ+P{AK&#a@Z&ui1-!HL7Ys9EDQb{su`Fav( zW3iucB9v@x345bv_eCZVG653c?t2tbftR=_9&xWr*FWusom6B?n zOX=z)mX?m&gemPf+eFHmD7|zvwV`c(jdc6mc`m%?v;1Uzd8x(vfv~bkQkM`XrBYgs zfw|3%I0%of9f)VlSgum~Lci-(t-@pR|0YCFgZ*rxx2PzFd5l5Q`hjHlYb?7sSy}YY3ousIsbst{d zL6uu|%^nEHIX_#;JRvPQV{6C5i{~8G@yPQVO*bubEI(_SYi+@YZ@hw6fAAhupx=zv z?S>)3^i@+*;JR{$t^ay9(kal@oh^O$A7Iz*d&nULJ{w7I9mRA&JRXV1f129_=za7U z>0B0LmnFUVij^Sv5l$FAe4n;b*?<%>w|>cfMd`v(Zz zI2@f+YIuJ1tnl{K6!87;2XI~BD_>EllDpFy)tIWizEqlDWzUtu>Llgaxk*R`8-%4E z{Mi7j+u)LnNHf6KOB)uKT5NrlEW18*=uSXy;n6&L*WG(?J#W>z)mKlvgw(IOW!s~5 zz2)yXvT09jux37%y>0F1k2dXs7$Zqg2~aTrTXKwhJ0K!K5y zbQV`47g<04+cX@Sk9>o>-jh$bw+a9v1KcEY)KXkO_LV<>8)v!(9SzxEApk+oKESENPbmHfJ>1Xi= z>l=Z(%66P-^_C=a)M>$x9B_)845~-mXs#n`*jBjGJt_HrT%G0Gmb8waKLLu1$(o*J zJ7#Br?|m6l8?mX2k%WV$iO4QnOH+o; z(EDta(H~yE1h0Pwj_)rGP~*(ErUYxsL}8!%?0U3kcHA34DwoBLBZm^#y|Bn|dYrJo5j~ zC&e3;is9ra>arU_mE}H}tU1;+@i09tP1`&_okp=VfsvEFe99+UXPY`t8n1a8$^YbC zlC&hJknVtFh~}o3=wH*oSByB%iEbaE@|+U+X#*Q?O)2W`to(@8fFUqIp>yI1T=+l$ z+}pD&(J_Pouz6@0+wVU_AsDd>;|Tn$c|J3>Y<-bY}3lG2uqrFBMuQkdx8fZgt0q+p)% z!F5+C)P?^=YN>meTTQR02y*<>@u~x8k;q zHTwJz$HT>Nvm}x&IRfU`(nP+x9Fmzx_UDqSl-ju*OBk8(clf{Q^Z}N){%*Eej@kHD z2cmqLj)Fi*S3VvknY%XW&H&uNhZA_{oP1(^O96mX)VMz(UBvW#d0&1G{!sr@{dc1TbnDjoQxZ!DH!bJFN}>@%;2gH3xneNUci1 zs`uez?74jxeu100(9!SpoH6wiQXj6W#bC57?3Qpi*@Acboa~>XVFCEavq*N}4 zSKj*o4GT+b^M%9e${n~lua(@n7^mjXAo6^1vT3PlHu7{*7Hb(9!}@C%kW0;B@GF0} zh{JY#xi)&T+hSx!^!Q@COJys3qYuRK7QMCf7^RRB^QT*#>2 z5{jFGc4bS5^FMzR*xOb1bGkeaE;=TsaO(Ugs{*`~ual3mtp)H}kqOUuKStkMdCJUc zE$0MU9FnL>4r{RIa!@uws90Fg?HY117|<@5KZ$-0JM`f z9c8B5B%^Hu^6iA*xr4@P=(AflalOAE0MOIbg|D40FPcj4>&Vp~ceEbEaC=lo8`1`;?;KUwwjL_kN&+)Ar@#$FTp}Eo>YbE19QPP)KrFG+&;O z92DCs`Fwd|F*93uU#c@gnLQBv-AqHzf4O-5=a=kwIsSTSisDg{dpItZX-#yl#}(gL z9F>=p$U&y$oF^*Tlx_nrhm>EOqGMe1C>i^O&wk0zIDRls@R3g264xdpiM(}dbpDbv zne8`os{M>6ErKo)06cV!Pr`Q`%(bq=Oh-E=Hf)GIyZ!zHq_a5$P}nd&f#&IXct{Du zk(=MT>O*16;1IHP=~YMDRzZL*kA|RfeqOeQcw?qaT^`T3XEtggr>hWOb4s08EXv{&b(IBmz`F70S;7?WyGjmcw zfSm&aNM~||9t@al5kF%&546o^uDQ@Ia}FBk7qNb9vMNs78^$NlH}C)*Po|j@G#?43 z-iZ2^YmvMH&krfwbP+z0TFGJCgGcaP2lsdGsOUJ)?y+&~7`Tu2CsXi{Dn#O!;Uwa< zKc*4tKO35u z2rxJIylWBX4pKQ4UrS}l5<{C(8EMz(iY=F@1X@m;f_qPZ_a7uqPqpEjkh$$8`kQJ> znrFN1fL71$k#TsAgQez1Jn8DfRA)!ob!@1w$HASu;N?7^|2mv>IctM`UA5zM+iyx8 z<>~U80;()EtkJWfWSH0-0h~v~^9!=xslxx|I&LeGK4AA{uDl&wyAwS{i?<=#7xDL_ zvp^ZCqBz*Z5vCKjxe=6OW(DM31wELK+niIy5!JxS_pM@5Czb6AC-Jzv%BT6oB?P~C z1lW~q(=#7WdQ9;4YU#T^lf%f?%^2KP+!1`+!$;UOG?K?O;kmu~WN*#Kb!1*QmqUGS z1$8ScIQ8)-xbX5z72&$Eo{gwmUcvTz55ZkY1GdiScP%wW`dt8YP68jtVLGt-6UK=4 zBY%^X*=#6hImU{Ogt!vS6_!??Y+br08=jxcOyh&kK7->r_{Of2-b>ty9N$8R zxDcmzOitmzwVSwk_&~+=-+uogw%vaSC*v_)7UymfqlRSTu%xr+Ge^5t>1}waOb$Ex z@5A*yJlN5fsE%#ZGdOVLCV~K{Us#40P^5et{`VvGmZQlgC)(}HakEGFL3BMb`=?~v z`Y)no;2xIRdNIBCCFGjyr=wLuar#zexmHW!TK8ILczqxE_~QU4PAD`rRXzJPdZDPY z5gR9$nVf-tkK*7;%Pu|Y^}6LlMa~pXOw&uia=5PbZQg=YhYy#0#PvMXudE=8a6Q(% zP|L@h51Q+M=JR^xBR;HuQ#c--PUU=T7#_#z*#%_k>u~9%;}tcvzO0CW(R!OmK&FkO zIPCrGDH%%qVv=rqQSZ5OUQ<#9n=M^b?V_(rfm8!z38rPrRCQs zm83YKh3Y}Z2AVcBQIzqdWSe|yanqKJ-bLau7ug&pD#wYQaYT$OfH}D}OX9n+E zZEByM#?jBN6ohZPs#r4K@GpM^oKO z7O%ehKF*&zgItx4G*&^7kIL@mH+g6w&g8?>~dd6JLYB$}sH3%{B4d*j!`Hb(PDLG9P|Ta@)^N zo=9Zi{j+!9!PM+*n8(i?f_imF$!D_ZGy?&W=(=u&2Yoc8-bz)ub4qh#BYxp) zVYKvhtI&qY_h4SvM_$@EdbRjh>AXzC${JNhwNhyW1`@TGr}1mlfNkRD;x#1$9F@kU zLEmadZq1cW$>jZP#To=zTPZ^h&niq#YDm zOMMWkFCAG-;rbOqw&-D|gf|~QYs3wOD zaiuj{gu7)*t+Art{N$e~@|I&;mO%N-UJu7vHkHD_o?S(2Su0wpugCpeJHn&C3(m^2 z&L)}!Xr^&qMNzlHdmdc4@UU@s6xr=*EH^Z)s;+uG?YeUhInT`-YRwr!xQxFU&Z`tl zPxHtxw1IEz_TivzIfI^&QH*ZtSylZvj8C9*@+ph56*bZl$u?0P17^ez@96ogx4bzy z54-N(!^6JqWjk$e7@xq-djn{DI$h`se*T}yFD1t%4W>DQH1YJdF-702g8_9Osf8Id zjr61A`g^FG9>dt#pT+e4vn8K@Q4I{WmicC8fd2jfj-#+?Q_YH5qh~}(MoO`jvbdhO zGAdr4O-|qvtS&!Uos-IE=zoIX{Re0~vK70xZ7Z3)VR;!nBcqHbMz;}4#2&4sANOxD;$xTcLIp5i%Cv=>djWyhdV z^u|$~mM(SNS&gTi$aX=piIpaeKf!X)wq<_$m2}$X?^U-rDD++#GR*c4pe32@DXOtU zp`E-BhI+T);m+-tD}l#zsT9UHcB5^227Lqf3%To4dB}1PsQmV4*YnXa`4q=LyM*h9 z4`C&--7KV~#zqWo?**W+{oaH8RTlv~=qSJ%g(>kixaNpU(xzpT%aEnVF_$@$$)C}= zS~`uy*>P#LgP4gzlFCqXQI4~ zpZLacsm9Sx-rYIW&ukc-z*0ja9`}_W@mbT(djr_|Xb|;F%OdJ?bSp@7t>>dmS|aGf zbpbkfOc-!1zm*`9!^Yt;1PZuysC>umzJUkW`tWi7Bq-u+vhI9~pQ&vm`?AC82zdDx z=Da^Y1l?>XR&J^Awci84(D9o@E z6931A%j4(dzouEMd4mkOmQ1bDP<8=iDkev+z5n?^>^ z`{=P)15Es5P1Wr74+Kvz!XN)=H~R_^XSb@G>9Ul4d^3 z2bAqeDwCi%fjj-b&P9O)s=!EVD)&raEZb_fON!kR+M8+Zzev0yC+z4kRZ?W*P&jOt z={6WwgHXiObtPt{b2e3j{16sNf$?lI1B&A~`1-k5@S{&YE}G7)xB07JH1mA4KMf;p zfA-RevYayyU%7_vk#V@$9CAp(gNslM2O1WaaP;C8Tse6(aek%9&3R~CSS-9fJz8i# zw?5WNDrduY?4lS;ND4)5GuoVGGQDk1>ZdsTG8IT>t>luRSgTzFj*M*Cgn>OfvDDO< zs7=+Nh3015IC2nsZ{9)s

`kbga3K?Wq+JI$9=J%ZgDs2F9j_1~er$UWYmBIcPIb z>r@cmrHX(nK21S|+&(G;esQ#JejbOfTmv5&R0p$;0btZiL5?VGK=mJ>}{(t@JnB9F6Bd>iMi<@fUJXL%o7w5d1-$)K^2g{smhW8el zn-j@S({r=PdHD@`>zjbKWNVaZMgnX`nrQ2ZZ_3SubS!kZCT|#*R8{$UAxh?E?E?7JyvLQr8L=0ceEp0R|kav zvoXf!yZiRS^?fwWFQR#FA#d#Bk}a9E0lv`BP zF#*RX-Arh>({8bR11(1ed{rSdt^Q*$jqh}m}D9RQTV zVDDBeH&*7joz7+p$6=bz#4=W(e3P8(@KZdrf*u72ZLS%U(YBlC7P0TW|QV>m%gqn=pRrr!jT#)x^&y zovY7UwzBcEYSP>saO+lpR7#=3VZTNRsl8ocb~eD`V)gT`&FF}?hse!M$!7&|KeLQD zZKthPHeOSH541Kn z6sFtT;Z=Bo(qdB+rq*|0=e+@FyQKqd@245!pkVrNM4vaUY^z&4p1yMv_ddOZ>|Z^HWBW>{560$^`~6Fp=<7po&n6^!lhOGb zFAM1w@{j=zdy7F~CWp^A%`alx!$(jmz@zP@H

yH}C*k9uA^@aRnYyj6=u>&{RLJ zwKKJAQ4OA-N7|h!e8<<^ zYGdw+3BYv&G&KR;-3nb@Rn2~lzLXR{6QUd>4mAhtqo3sxf{iFoQC75l%~(*!W|^wQ#=7QeMX%UuMy z(b)vlrl?j75O5(i>`^Xk2a$5(@+)`LD5bD@LpM@oI9HpdHVqs!IB|R*>nEPz@Re%_ z9EE$kcVT|rx}td=xOM{@N56V$(1!yj@Nwws zb=*9704ojUMKIvh`IHRR8cfUMs^j+;$`J$b_mX6O2Q0O1{FEM3#rgB+-8fMV1zjD{00`b?7_(E-^P6JK?Lc_c}Zz156E(|K`|vb z5S5`U&(w~%Qj|*?O8lkT>1W97;1qbf10F#JaFAZkV9VnnKmq-G%5&T{Y14)c7}?W> zxeb-AZ_=5KlQRAi)rxnm(X%G|Ds9KT@}B(8O=xz^9I$Wn1dqC{rG0*2G)Y!E_xQ0# z3OD*)s-?1Syp8g=Y=M4CO3!r7j67^gTDJJErh(cmMBnxp-iRkH3+w*W(WOZ#7v{U% zTn{hpT6iqA+lPbZ`FW(uII;G6e?OY)8*qGo@d!gvSyLZ&OvrYrr4e@z?ZtG0BSUT- z2%}2vxOX4D_aC8dIm62G3poQo7AXV>x0Jp<@G1{!BJY+Vi|c`~{dbG?}SrdvcB7;|=nElEQ2Q?vNX z-}#Tg&QARGZ~YZCHx}Rg?0Fu3c>W{2`SK}j-PlvqahuOiN37%;&FE7l%pTIS68U#Q z$4V;D5tO_0&KZxl_m&-T4gi`L7I65=H8I0YJjQFw`K9DOe2np#t+fF99my~V^@}Sw z`q^cCdg>IE3NY8wlGr(J-P}C(-MWpA$*1|~;4V|T>ptT;qiFm%sn63hgvO0RP{7(M zkB<+3cCEnA`uFa^M0b~UeCt*ox_TXr^Gm`Iu61%bR%cnasBSCD>675&(ld`VtI6lL zyS#voYwuvwkN-UuHtoXT*M0@d8)^gcqFQEoy>`ar+TrAd1>n-90H;nVw6y_hO`NR> z?cNP6EddW7KC2Q}k3;44)#Y1BJ#4z_a4q%3oLH`Jz(R9#vW(jsfK8Q$yEFSo&P|e2 z$T&GUcJRkl0_n={E2`4UGfITeM+^5r>AR_JGb-} zOT)1@$IaXhVPB)oQsOpu7VBNx6Y^TA*}^3rQ{u8YUz6?4lq|V~8A^-GO$`|B*%+C% zHmB`$CX1ApgAawxgTqK?as^pm=k=&>8y@WJE7BiCj_)I#%O$cm9oVr0HwNw{%2$&q zm2%hAku96>U}s+NWW1lgt@%EB;Kuw@_6l`J%ieE%vxCNw|^Q*0a_3tQp`vC)Eb zE}I_@!|?(k920oRmy+|b@5XH?1h~IzM@2?NAdF13^WFeDC!ZpRlmI``F{Iy}-9T%f zjig|*kGgO)#y?vfxT{B#`KHYK8W!kz%|GKk-I#oi;d-VzJFszGGuDqkiPVjpvFsd< zT1JNw0|agzD0DuV!sel23~wn%*ode0scEd6TR;ve&~d|x)leJCIk@J4j((G~fCSzA zx8wWh85+Uuefxk_`fRt%&0+h4hXwFl%pk4ns8vq1mhk@8hV38^vlS3H=pG(J&P^eg zPGNZK=7^Fp2{kS(GGn?;K;r#rQ(S0@3QH!~mT4vMj+?{fP%%L%sSp*%Wu7OQYg4sp zdOG~f%!F@Z&2jt1rfR5?Q%iH$^22`vC!4{@>%WBgZHM5e>l2T#)zyKoo$+bnfU~|E zSnf+sRYr||{|fMQp^PVht&a!MJ~dq^k!o#|Jfaf1RP1V3K2lg~RcYN)2E7j-BT(VS zy-I0Q*9IK_>DQ2QlSjRgYb;5{#onMQaC9?`5?7u#UtJ?R#pA`|Z>>1awC7`vtzvjv z{??<+h7ZVC$LpmcPbwn~)u}Z1D8;#CE@UpD*sP``MJ67Zj+>LX@im1ULOdH{1S_- z<^k6cdcr|FirZ}w&1{-ZoxeO=FuJaonk2%+#pWqrt)kMjem1og$0D14pjWb0GWbSX%^Q z(}tOA9oJIwRb1-cyoicKvzMi&rB_N$U43^bs73CBe(ueqpN} zJ#X49H7}7fk8rO}qr_8S-|VHybg*2p>4j|lYGP83*L7W$agSyfmu~qvGb9m8X-!%* z=G)g{si_eP0p?rRCDy5B>(aP+Fu&2*$vbW@XE5K=f`yi5%(b;7cGw0&Y9swZx0rmniAKQ(^6w2?(E--R4#`NqZ4p^a{Sc& zyx81~+XoYbaZW(<>(=4!zCB3ga_AbHgdb=tm;=di`M8#=4B40hm^06Yp-D^o{5hM{ z!NybT%q&`GW-;4V+zz<)8z-<8ClZ(6y0Zu8e&cT@POs;796z<$19e*3u;nnjwAP2q z92*vvvHNy^!P$AdyBlrOGpNt3M9NENvef`Wg%QpOdSDQzUj{}X30lK=LKkxk_((-Z`+5F2+cKKV%p-Cu;>&w?| ztFP~cdiPpcBynYETLv_i)?8PI*bOmtXqO0AgHXGwHQGK%#?Kn6zA}A#=aZ+XUs=Jrx%tA{Kx+rBD}lj(bd>_~E^;6amG%}cBpqN zvgveejZ&V6-iMD0!Y|JuWYBbMkL!8ZKJc)h5Pq&z@Rj89a>X}f216wPz<%$O^859@lF z^W9XI^95cRzd4Vf9o+%8J{m->E`_m;8?o42zEZ1Yb`IMI9$@3pXkOTG3w=lB*%kT( zngJMf498gLxXpp|rpLo@;bW$~EwR&f_xL!P=NAw_6^!Z8DES=h^U=apq%i7A-%X!m}Z+kgNsG%>kpM0k&=X;tP#m28uKJr55JU_1U{Fp&A6bE+f#I^dHSi&;4ZtO|q;MFraiq^T= zg0o*#nxOA0a!vAghke(^2ps{}M}YKl2HOW7!gE{z0S0?}kxQ2keYSLWCr&HZP+fNk zjP38-c1^A!`bw#%lknab!LagWrucCn@6mgYL$;daJt>Ww#x}|`Fh&lSF5=`4j>o0i zr#KZKb7Vr`rVD z01pma_<#dkJpEEhFC9-@-diu9hQcSw5-UI{Kn13>9%6W93w)fA9_;9Y=ejs} z^@hkF07<|qz}>xj@L)$@WrZ;M_}pon`tW0PJefks!L@81>Lk+0AzK(N4(Kplatwlrvxwk5o# zozA&|SrtsVS_%OIas`+3@=Z0(we!b zY(yB+$r}+|kls!e49H>JGKG+fX)}b%$F-L^`_SW=>k&YJro3 z0C?w}u(oHHU&ZWsagJb(M(~LX_ZXPp?S~L=a$l4lexjKSuCd=MkLQ z2jBPMB-ow6^{_HRCGpm%ZHd>82dSX-D3oU0d>X&7MiD30)&wds$TwF7!K$LWHZLsT zwI9Ei*NbY$BHqKMUQ}9?Y;S>wWEje*7x6r3N!+8po3cwhm|vr zb57e#q1j;07?~!jk>X=MSxoK#@jQXonsP5LBbak+^UyG|_36ZVn_5sHK5;Wulg6VV zUJBJYw9ZMrxWnEf$t3CJERI~f0tW#upE!mc1NYIUkC0_$`%w7+U>ZxtMX8QD76;8AudD!1p8~E6lzG76 z8kL}#8Q|8f8iMT?jLILGw%H;PnZClgY4}Z^{+E~@O##hyXxY|{*5-93lQ%9c6?}Mz zCrX`kwEhyS>%SUThqd+dE0%WF_CXp2T9LJ^N1D!Xh4bN~WAZ8XdAD)n@WHZACvBUV z!Ty`K&@w%n*K?N#N zNT{G9DfDvzOcufqHic2TZ87I}k^<@Iz~TxjsfLS+;ijk+-4QKCH!~Kkn>R_>0^uhG zM_d@Bev~E`9$`D0M{+R6N&Wm`sEwtWZXvxfmZ)#2{iB;VqJQ6>*eKfokk0C(yBu_n zjl<36piOSlIHeswLjbXT-~oK4@Ob;SvUgrTUEhhoQBZz>_Q~md8DXpFz=i1hBXL=N z*JEA79zE8$V%AjgmmMokLK@F8lb`nKY0S(fbF7`1dJ0E5SfAj? z?}x*~7#bhP;oYSp!SSWftS|i~U>d*EEv9jIt*cwmp1= zwyEg?H{=f6rWjUw8x9{)TzHa{L_o3u=Ol*fXF;X-z_Y5G$=|9?%gfYDk_e>2;w@ux00SMs2$Gfk;j`?-TF>I~q>d_*B~~SK$C~@(x0wdCkX-!v`_EwK^vU0VtTGwA-pG7{^>8)!DT- z#m8m*thCR*C_k>HS*JSGaj+ME^Y*_0*43lFj7Zf9!jLzwPt$Ay<)imlU*f&18TZvcU>kVU$H(`2M7=|F5^Gn;}N z;KyS+$RULka-g_onvZDgOq4hJ34>ye3NM{G3~Gp2am{(Yl&^jjT^x!ga*V4f5MALWwO~pN5w%A1B-B)`9(1$tNkP&L*HC zS)c}~lgL}T6p(3ZSk-10QHD~u@bXJI^X^Azo>@RRPE5!8>XV9mq8dsX4>k=?V40bv zF?KmrUT#{070wHeaBNy{vJY~+hr%p)UgY>bnwFL#GJs7UkQfKhT5mR5;V^rsm*48H zKV0t6y>Rfe>re>oxe`~%^X<$~2y~4$Mf)PH#D}{4khlg<>a;ZmR0TV>j!5sp+yYP5 zX&JLSu;fpUY$i74*NW=^OuK|H)*HD+IouvW77ePYFKW+8*F)Nc6}v7&HcGrrYm(Fl zaEu%mOiaELvrbY5D=l+{4%<($;gj#8?+^Yr-2FShiTU0GMW3k+*=9DE2}+YKRkip< zwej}oXc$1Or3E;BTA>OtCD&+`RP8mrSbp|<$;z)zJ)^pKbJeP5Zv_APQ=q2_2Y&H& z9NAO)RIJTI!`Rh-FTW9q>!|?r%DeH@pI|s;I(RpuLt* zShIaNXq}qDvCl5!)6*{l2sho8k~1GPx5-`U*Zj&fZ_sr|`+qRpN(nM=2 zowvh@r^K`LoV=c-PofYx5ceE*O^UQqiO8pkj2>q0f|iG;gwEUMo;)dFGN+4j~#v_ex!qHFKKNBh(1noKYg+G@B`Xtx7A=~|ELM-P`g zdODj<1~=mY2$`)ZAd`b=fUe0Wc(S3iW0Q@hIyx}0dnaC={1n}L{wHJ@(t;bk$!NxYTP4F9XgVw289GSX` zg_fp@6y}{zo?`#?TWDC&i?%Cftj_?b2}B{TkvdX>)1Z)-`JO0RSJ={)**VO#w-wze zp{aFt7IiBbY#tg$&)|p=7ct890yZ+DU{nKbAGBLrN0o8%;5r3`EclM|tq&e!JA906 z-h{zkIs&;alfltTSMsgm?@q^EaKV8;cM6d2ISRTdPm`A^_San3WLi@=ikrVLy0M{l z;!Rw6wTZetI}2RD9zZDtrGU=PwWFZFD3n^9MeD#NwBJ3C>BC1ccJ^lhR3D6UvgK_X zwPrdKENkh&RO?AD#Ennk@9B>AymNDL8kw9xCYuFzbYd)6!j_p?bhMVsO`XJ~%H|`>I{G+~mw0&DuowlXYm-B26l)3b8Dz~|jK`Yzs zZ{JpSrACx$^2Iobu$uXsRGum}IR$05rX0hQiJ6Ptr|%}B)mJ&<4e!Wzs#_AjsZ-A~ zO3iUFS2CORlw{&U%H7tsAo5I{WCUAlY`;Qs&mr#SZNNnn3*<3}!)%AYKtDdafW`ZPW{ zdkTxqO{=P>?>O*MDY$uAn~-tXw_eJH?^aLvxpM3%4qm&C_2W-qZhbA6XnfOLs2%4h zm+Y85IxE6Y!^$#VefNEwKX<06oj%sI|Qd!vQU|@4jz=n$jqIdO^0nhCdhG^E9P};$oQ=t z=je!PBI4iSb^{kGrzI7w!%%f2*4w> z#UV_yEUq&&qnGjVVAGRE>#Xl{V?eRmP=6PrIF6B8n8BtW{9ANh{W0$SwSSDc?T6u~ zR~J<=IYn2`a;RJ_b+SCGYfJ`02jjzs6*g|HT9#jW%H;sxFP+Y$T4Gllm6CJqR0)dU zXseiUJNn&67#&e_pe=(#P%0?tWEgz+HiF*|b%lNqAd|@^s3%{4xK&8kC?3aY2W^de z11Ppign7Bp&S(Lg0$-&qG2Ep}mzB!pu>aak?7MXvkGJ>YL0?~jb`Z5sPvhukSCGpG z-q4b^ssAJ%PSUw1`Sz5!Zo6huIisZ#-c}3UVeP5XxnBFWmV=dT&%$`#5xpB z)Q+3wjFh-p+I7Kx@jQKzb21%HapL;As02mdQAi=BDbw~$5+O;I9=O#74si9@5lnP% zD6_6F2C4u0P2hO)O~llDAy3WL*WpJ$@mAIArMF=g+Zb6bieE{IJM#@P`d;bht4*Zg zDpq1LzCk0LdYD_(xxV!I@O2dgXq}nGEAM}hUpFb>7PmHYyH)fr3M)GD`fze81CV!6 zGlLjNZF*EDBs?jdh4pDwGB@e)%#pv;bw_nB8uM!IOxw?N3$=HIOrxV&^AV%@Scv^e z2WE40HaBj|vj+Hm^S9o99kx!Rc{g8@K6lP3{GySj?H0Nn+6TZG72+LpOwDx_rk&ib z`6RmtA1^3;i;g8;hp3*{e2?@FIi(h7(e>$fap3>{2e|xezl*0w-h@{l^^-AItY=Gd z}4wV45NvangUsgaY{<+UVb#*b#Lf2<0n z90b2}5#GK7@J}2`bi$P;g>YjcIdJnj$~BAZ(wg__-qbzhbb`FQQ!_uyoGBdCYzkEDZUNd2*?ALdBK zhA04fyCx4T#=qpf=gsRszh$k`X*(I2!nFjAh02@cf;AFMhksLtvXjxp>1my&{arhvnI*L2{79%g^VyU?i z4GYWA5r9L%UhmMzm!%1=7y~p7FVzw>%Td1Tw7MNOFmCdPN~yV_0jUJhPXVCu z>I8;Hhj6|*Ku=c}x{g=&9;HH%h!!@AW=PJ%E^>vGxx$--53HM;$9zlaXnl_Fqj`P- z0C4=`CAcfO0_f+_#H8b}1fkL>YO4PT@Hq%$hf#aAGEf_+$F*iRC_18||=(pd(uHMqer`qS7sW^|O(NI@!x(Q_^l5RYN>fJEP z1@ThaQpAs_B62ex8kd%^RE4kv4NJ>NXS2py78*n3TFlqkq!gdF+DgA_(6g>hEz2u~ zNt02s)vOd|2IBce)Cg^^b^L!>GntdVE{)KVYuH8{-%@JF>SlUrFp@KZ3e`Yn;{wsz)sJS zm&O~dLTwIh^VB$pVmm26K=a%@RPZbnl9C(*c}){Pq&Z6Ftkn1s(2gzS`m7zd{eqHQ z&T@DG8s?S_zCi}g0IHyfH=UYk1G98=4(nkHbs+04-FEal(Z?Wj%t^+HFm+x(1szp| z^gW!n^ZwCFcwJZ8)Jz&LshpRJdfm4w-@n{|Oh-;rJIR<3*1-|AiGQy_{#`|l-loiB zI-uLRHP?{J8pzeahK>1HOGl&;Ifk`9k51l;&YQYS1`W&0r8A#h2Bww(039tY zc=Pm`3hJZ`{>Rf1KMmIq#h%gYCmqa8x=+W*O=D!P-R0cWLETaYE_`escnIYOxW98p z$#!fU8Ab2I$4F&8)GsW+sX1n7yVPDrNV7}#vDGM?o4BVcLbu|_=cXX0hBB-R3XO>>i| z)kkh+)Xv+VoH>o@j%uDn_u`V|mZrY7x@2lQ%hd*!SC+ZiAn9|2n+YG3_5v(6=HsZi zHQP*Q&b+v^6ySsGe!7MffbDtdPS;O9!SRcikV7hRQc)DonYdKi3^fJ^Xfv?`9Y>rT zhbeEZ7o&~voOE5hJPs#JXP#6QwK2lWZ3L?-p7?S`hsveejK6 zHq2u7Vbp$XT0rDUP+T_i^IPJ0ohi<@Zi617K-v0we;fXn`%Xgowkz-(_z~3fI+eJ(!|EWR3Pq4 zAWsGe2^;9hPa60pxTUm+{S~dFSwG&cxM!pH__T=bli=njQ|!{>rJlB4y<0GS-8^~_ z6C0B4kiK!~AOK*;z5Cd8_a2;_2hVYlOQ+$x4nBJATxln4Mi)-SA7QJ>bsT*C+^hJ` zcm5nfF4^uIK3;ggzzHzZ*^W=ol<%;u>FUuV@RftjgTrt=9|0)pcIcw%;gfTxkf|>n zg|ZY)x3}ZssgpSS!AEd1J~SBRFjK!{7k>WuA`YOrdWky-Ct;E%C7b2pLgbZ9XHu~_ z&Phh8DvyrsOMdLy@&EQ0a6DmJ6VP#zSBMX2u12s9oy!Ym7 z0Dw$g9a6a*97`yj=7j~E`QW37(Ut>E=?qO`lQfE&V3x-|)9t4bXL24AIKn#S0QB8` zfE{=5M^f_s)P2Kuhe<_$G{TtN9R^E%Xf}kPSt}~Yu{_*g?iUW-R&Wi|0=-wWzNXVQ zk9MXF>O87jRIy?gjPzWL%BrYnoQ zTbIcIL4X6-ZlZJSi7;G8Pl=$m5$p%}+RWQ5$?_+f*KbBTjFfjNS8`rNd{!D%?)B5fpzdraZMe(PRe~xss+S!Spq5$ZPLbPgW zx9(74(@{6Iel?`}#T9IQIEVlW4|et;oz3FlwHu-qnkP5SFQ8>+4gvVaA{l%`Zr;)Q zU%57O=P9#|Nst1s8F%7(HuNGGjGspx%rZ&xE+>biSec$lenOT09p*^VoS9bEgVNY= zHAkg(J{7NTvFW^`cS>EgA@_LQA4ybPnvzzEsPq*|xVcmc{^wMQ{jJwu#}Cebw5mL6 zDfLmGCogAkY!v6e^CL9=;VpdY&;F+}N(;-;>rN?KE3K8%c{Eu`$qIy@0lpny&dW8s>+SymmLf-GD{y3B*bi8NnE(~ak zEDutp$rWh+Xr5$8_XRYPla z38T88Xz4zy(|Es}D9)db|>Up-8tQ^H<1DO43Bg85wJ zF;j2>j!YL)pd+DLvEO{}1Wi|@0=)B;H{q}1OpN=xcEC?LIC%92X4=|u{?%lWBPt=! z^YD9r@#k3nN52pJ?jE2g`PrEyJO@Z2hsmxkTs&RcQM?pgKXM4Z>tOr9!vfQavajmU z{JM2`=dCyJ*7x3q3ix>7M69ydY}I2!kDMgTtvvNwGSZ8HIp?G4YSE*$p@4meOaMcR zpEiwZubCZ-001BWNkl_olRbsTJWkc-`WU)AAAtt>{*4buBvDK zrKMaBc>C=Dxm@YAtEKgqe~9)wA7f_MNsPxhY}bakfvHqFIV)7;u9=4f&GOkm{H+y9 zWo|SIhMAVjKD^eNZ)%k;9W|(9Zc`3gp-(Dh&4t6#yT&K+^2eXz!&lE$)TXl^e1yjN zMQDexuw=cViOUaMjSHBPzFZHY{brI)by5vVvW~1#aVlqZs}>gL`B3>Lwhphw;pgzK zR9MH$5+=W>j%*RHKj8I}?uyYkGcp#9mvS+>xn~vi`+SlD(73#e-FN%Zzh`$9^EIXL zJVo>V+@ za{zbHmZv#M94w_HY2cKHNoxehQKaNw(l|~zXjCfkB_}<$qZ^c?4$!tJrd*yneYPy=OJeb;S8hlx%j9_z|l) zlbqRv5M^HB6OtoD5f>1hr-^BL33w8odbpg);NkEv&K)bwOU&}hDc{7w+)AXcajp#G zw;9qX)RFSdDgo*iRu#|$t+tS z`Tc76)f)bNwiJ(*lWBcz&+B(+>he_~b@aN-htfpHl6?*4>!gXHWxZ@|Dpp3Zls4Wf zC2uaD`cRQGM5RO*{`Qr^)#Jyp*xVFbj~9Wi-o1mN@iFxFY{H>k65qDBv?ApuKUCc0 z9(EmSl;#%~@!p5$;s4Y3;QZ=ooPP5xI@{VxlvNpL$z-#5TJNFdtJ}+bGAbXN_vNaZ zjDMEm$(7{5^-{{X!hf0164o)XoQb38w+9Dq#zW8G2%Nyj&4bTI*S}$W0(csh`TpgiWzhS-c8=!F>Cq3!4n(&+re{zkwY5Sz|cvMl!UuqI{ zUK)>TzDfvFo_Ph9ldd^$3&)pogD{svqMOV)7Y(4JgzNTb9RQ%1PA008^jU39tBq}C z;r%V;yQs4r;bWUFfT#08^IA&4x?HmtWu4^6u;D?4j%)9t>(lQc)3F6(=e~tZdpD9$ zH8okK@+x00jF(QLWmgAlhox2r8(+Ei>6%LE zArSZFieg88^Xr-u1&5uPpF?(N3RuWs@Af_%+_|gdGt>gkJN0$W>x(@XlHT;jIjjB^ zw$&B6nQhjatdKvsAx!5KR!My>v?}CBe8ERl$7%*1G4=7bfS3G@*n(=n_^#U+*EiIY z)VH!f?O17zij#i#$&n1o2h~!TvgId_e3ofVKwSz*ljzFxQ^u2eCyoF6hET3b}%s%!dP1A&S`G)~y)r>8be+Yu9!0 zOF#Kd{896tSM)rOLs-oSk$3m*LDo&>BL@fyiR&|Fd1;kIIR`w0Xrfi3g~$I^mqPF^vEM~^Z(D@n+D01BxhpZdzo4H zi8_G7QMixB)#yfdqwk&>&Tu#fIXg@4l1nWqlU9`e$Rv}rwk!RRY)xjmS0=5Qeyqu~ zqKR6WY_&^KLvl$DIWwH2yQj|q8fW7upbA&rK;1_k@9D=&Pj`=q_wr>{7J%-Cw^bwa zWgH&yBHaD+i145p$7jjBa`dyPojeDn4CazisVn-`yz-eNZ|nO8c!}A)xjBkw~4)GMg7m+N}QSkTw6c~GmFTZpKdv^_2P5_-41$Wd+55x7|x|8@NBav}gNHEUm1hPH#$x z=Jj<9kKL}iX?y9;3~v7U2gv-=AspSeA6^w-f*ybA=f;iOw=wn4{|eo$?Ws0xSCd!q z+E`NUBcLAi>y}2m;V6DS^6&PDrpVMj!ZLCU;K2_=>>eG%?LEVF-x5&^buKQVe|iQ@ zYwOrCcGrrm$p>oPo-S%9IhyI%a!@`Z%(#r*+Ki;4|5H3r)88WzoIWUPM$y(Awrxi> zprs0Zry2>-10MJaOpapBtph@o$~;Rs%3cFgg3C7eR(njWNr!)_ZDxDO^7AWJPXNB_ zE8>r~mg{ZPbmgc0=FC2q-YboPT~XQSVrje2&42lwO8-41Dw#$gC}6 z>ddb?H*9Z~rf)3fPUrut*NdmiXsoYbX$cq~2Zn|kR^(IqLQ%5qVM`TWlabzKz->d$ zcXwfGFvX@5s(M=|+Q0e?4)5KYlKVK1ql?@=L9%K|0+zrLw53!IASEHVl`A-leICxuI znsNG>V|f3jezm8%N;#xO!xBBW`bjINwtx5{~sMYv;NadmKmYr$f*#tZIgMFiW-lFg)gH%eMT5jtxZLc#Ynzl62HVU_nuAuZ?9 z@@4i$d_K3QyLM_6-kzO}{vEEqJol7hXm%DD9j)(;)?*8A4w;7%O(TU!!u2h_wwh!qJ>H9TtsU}9jK}DL=Y|T{4=*`CubG8Ay|23mw1MWrpIDER)T?xE9vlat#;EvRuyr9`-16W1DC4;yJms zalN$}AHQ_EAsekrnM|tFE{&kp<`!iB)2{&g(p@tx1qR9@X=>Xbt{!b1&?;uLC}lI^ zU1$i>X!5K-bL`M}sT5sKYkQXZFfS3>7@6}*0_Ws>403edD8Cs&OoODyLx(@TiXC_F zS2kp6g{S$1dQ;kYN6I~{z)sG`TdEnJ2Z*9>lY>FZN&1(zosse_RvhDT*HY?}#IX1# zt|G2E@)@-%GE-;)nA`$hy;?dsTV@d#9DhKK}y-+Qqa!0V992i_S)uU&<`I~7}O2bp~Z9CQC$oxHw zdH!g~WhFd%Y7|%ofI@zRn;d8Ge$hBaj zFe6>vZf(c%NRm9gplLq35 z9013)AYdF;a?9wFR10mg3gHC-Iu@4j`cL03Yl;x(pFN3%Znra_Wo->Fe()h$S5^>& z?hV`Sh+-O0n~r!`&&+<&znQj%s~=J6!*mNQjiX0ty={J7o9%$pnAo1@w(Tvy^PA;& zZd(~`vA&3L$_7ptwUb+jQJbj(Y3iR#^lqB3KZWVP zzJ$)-IF09yq}wo<*4O54sf^#~t1VG1V|J6N}Q`TlI{bjwAK1GL~RF>Oo zS08CqurUe^eqD84U6{m!^#u&Kw&PGo4?KieFBS35!wDcr7sTP>jq6y?=dpL^PHgGw z#^mfQE?mEcTlek)05ZOh7mgi64q4o|J%)=nu48s?4*k8o*fBVWm9;gTzjhU$j^098 z-n1RQJBnS$_G9ZSM=JF+H#GqO+FM&uER~SS_}IODJ389hFwonJY$k)&mS)`tKez_8 zZ3TAhtlAFKw?b=d)u^?(8K+O408X9&0CcvuSIrZO|5JTwsI$Ethuin2N=p>C8CCz8 zHmRFvd`f;z`(381om@UCO{6>MD6~CaqS_gI@Jt9Q>wvs@)ryPsJn%XLflCNYh>P23h&8{b()*qCCKvd>=n3#b^@y&cwnrzRUyA zHZHYo8@3dw3{=KogrB3fu&07Tu!SO>3ya11uRQgy#LG$VM%!AZFGgZ^*)OtQ;>k76 zY_Ds_*kyEo`aX(nU6?!aGFG-9tUC7_gCdiung%uP+1g4@*S?Kt@kZk9d-p=Lw0P+0 zX-IKjD9UDmvgxsDRIm4Wb17K|CqGT{!kOB-b_)OeQ-qVz8q2-uN%T#OV|ZJ&2mq$c zmzqO+1vJ-W=ZBDT5eO@qNc!>F`k>q_iOEYG?M`AJIQ#!8*0zm!U3}5M?%NCXek!>y z%;oRa_8=V3W!>)2Y01_j@j9k{+B~%XIOb}7$7h}7Hkqj7H4rilmUJ7psT^Cd=`?W; zY!jrr2AmswyGqk!ax6_#?iW9Rmo*EyELPeYdySW8e0GbjM%5KMKc~r;?3SsGha_RibFW&BwQxjlkX;xh z_+_9IfuQa8#!+m_VRY}Flw~%KnpfA6$(PE2+P!EhU58RV>xD&MY#{U0+>M^_rf15@ z;~SM{Qc25*-`Y_wL7O|~V5r)ndFAhVftMDe=~`>r&~2)CZ48kq!hJ+!NB@?NGAZTk zt3O=)bM!DWgM5?#WW=I68(9+a^T~65BTOu%?Gw$+BReum@Qrr4z_oT_*yfq}E|M20 z(#^JH$z{8|9v6ggwPy1H@@CQMDscUJh#>H=YuDrE=8H+TZRw`=yH~O6ul{#Tyzpz7 zJNYt-?VD*&Rp-aWv;9oln;|HkG(F*T($;Q>&F~+-0sK!t!bg`c!9TqdJGa&rQr?T@ zL_d|zUW#z(SM-pnb)$o76pe$O*S^sgbclxZj)zQ8LhHh6rM#mTE}@jO?a~l{UkcH- zup)FZ$^Q(B$ckGd^rE%fsZE?yOSSbWtpM9Hl_Mz>&*B^qjix72>TVvTl_gPHm*z^= zRvHuA`AuA{zniu<;bU2|UB4bHWP956nPW;ntEQvV$UB=Go8p!^^wI{USuPf^TwFzO zN4m|d`9c9Ra}Q&G?`Um9S4Rid^Lfn9&mmtZ;IBXY0E1ilFwonJ<<(W3y>c11C&r@; z3u_2(&%tZT0EY%D<@ERTV!e>Zp6%Pw-r9!wrA1sFy`}2fwQU=+nG9y<=ddy|iSF$l za0FE;UanT5o!#($=X9#1aW-oj8tCms?(cmG?FaX!tV{nZAr~n%i0=pg+ik5 zsC{`EEvsv2TUrq~Q%BDCO)@RsvS%^`MZA`%&ow_a+Sh#+e*jE>m-YhnT(k^M$FOM= zgYMT*e3!i^dsdU4Bj(08fTTy%AF11^dD!qEIYkk3DE zF5;;cJ9#6u$Qci4>o(1BlG4egQ>syaK8LOAIZW4(hsc&!tT9{~g8ix?q#WeKLmp@= zQBc`NWe3pUnxcRpfzrYpwjn^G^` zxPjiTE({MvWfx0Dv@|v0nZ5g>e(-%{{AdI0dZB>9-YppH-GXiX{n)>27|W|GC>D!2 zvWM|tI8wsC-TSfQnWI*HCl7IeuCDeD>>lF7HQgN=$L#6qM`u$yJY>oZy~-X>EzQk% z-oa-wNgNZ3&y6P?aZ%$MZJ$fIs&$aWs=92`Cs`|R>12eNj(C=vVI|LY@F~JPq|*oo z@v++yLSza7_Fo@CF`Gp(ldaV0k|6-F@5W7J^F??F(Y~~dj($F@Z`#TsJPh3%N7sXS z6p;l*sFs_yLqlJ>v7N~k1+L=oVC4DcDAl}?jQkJ0#ap5|yXyfnK5(qDCh_Gs2-c4BH)btrWO!_!UMbx?OVuzkCSd-rO8lbdOeZx(7XM|NC2ao%#% zCmU8IzPn74Y+6=T;qm)dfyqSx!2PKy^iE8q*tAVN*}*H_YY43Kq+dbWN?ygbAnoG| zT}#?7(iOaKitap=sNbvj_1);$)ebH5%{@~5jCGiOSjmei&-6ueFW5RHz0R&d0_!~t!cDsJ&l4s@NiI=LKR z6!XsopWJ4e{43=$c(^6`gy-jlLiJffkj4`&Px5H2{*ISdSMcG7XA%Ch5AfPQ`FGLO zQ~lI6QBwJ?-(12gosro19wVU44hRWeJfX&<1D1Hv&RYIAMC-~bIu@%(t!p&xzcGUD zhx5WQtpS|wdskanfzz-0JS@XLsR|=ELa9=!mSddKTrj6+Hm|0`Mgltquc(xP%9c1O zO=*Fe7N+_1a|j><>2{);S@zpN+6Md@nCcT@dQ*TI>74qFds*^lyEe$x!*5QG#`t+= zI#9^zBHQA+a@%Df+T&i2e_1cRbCV}~{->YU^#Z|KjG;z=O)80MPa+d6)Ju&5%0x>` zz|vAWkpGk(1BD^l?_bA(fAL>oWpEGXkDfuH>q)eyTvEUU&Kh26m#Ln=S{p}F_42W! zSZzz*;8-XY@$R{^SbzHlu(XbuKX?br$BqEssBP0W^I0to!G4z7QhP)YqexWO) zWgkRWPBDn(+ekbm!Mo-bWAs5(13BAEBI0PEu7)-@ZR@w;avH!&qyJ>TxoqKD93QUU zPtrM0DWcjiZS7KDmLI42Odj~V9vKq5=(6k*WjXd(bBz^OIW}pTqjRqomr*ROgXV0L zpFu~i4Ix4-tj|UBFxLuS+#t1H%44m#0v`b~UWhGC8e=UM*HI|tkwph~`&vz#G+in|jxjgw@|uE|W!XS66iPa*7>vX4z@w&TG#-pDG;yw63lq zTXbEBOY)8*Danz>oX}_w0GN@p>bIZcNzOk{%qp5&(f3FzaU?s^MT|{6^-OB%lENIU z6Zc)e2`>n7Yu{evo86&dT31$(34%(0ZNGO9J#+K8ax6YV=>F>?7`n$dPVuc0gc;=l zTYcD8zbkGRN2cN}WAeTx@*{AsO4P-YN2ZFywbknnlkxsOjApJO~{A&72eeqfLy*WQk z|ALA0xlQIfg8FQeZToOPGL>7lzKY&YevH1eKR}_g4^yxH4J_<`&RK38H9|7Dba|2$ zVe0qVYB6gv%YHI2^6Dz^;fEo<_BHS6rtKQ&;>8dTWUbd)R zK1mlgu1;6~k00W~|NO`BUP^cWc(zbP%j%jXA4%r368UVg|f=ZF?C;e3_*EBdjg{|WgqNlhI zNXG@`pdP%Ysc++T9VB-9k0q9h`i4CsQElWWr(?yGgIW>7SA0^R$}vLiHSxQ-;TZLT4=%wy7SAo-SUS!Vk;Ggw`zKir+4>}o>XT=mMJ&BhEf``0k+$mr-JT3Z001BW zNkl2<`DqsEF)76DTyZ6*xmNtIVPlem#_c8vHi@^LkdcJ-fhsCMx__}N% zUyauD1zf*-8(}z)Gl)*ArzI&6&3ZlYf1QV(r|k=#PxTss3`Y2yIcHsEYh^$xiWdt_ zMM9^fJLeX#Zl*QcVgn~q=(6oX-Bnj3 z45Mmg)GmLLHLR|?F+iDX-k8}nI}2R75~8EyX~gX(iM&z~?c*cZ|F8Z#l$u*H{^oCD zW!t{QJRvqaikM6Hn-G$mouT7*na*^An=WUqxyFZvP{`#Hxhn+$ZrmP2@$H+y;yN(U z4zyRdbVm2=!JZqVXkA*hT5Ib#vo)qBA=flrrx-%s3}I?CQv#C=_RCtAwqS*oJ`F(| zx+R&BvMIW@)=&DNRJ`Ne)-9ah1jx32NH3EfujBNyNL~YHxm#-`Yp9LYZsSvlE8K{e zEi^fmOv{_g&_5DGi>XVYW2vM^cUYhPQmsk=}t z;!l7269hqkZ@&H}`o#itDF`rj|2}^F(Ff@5>cX#o^_LUdw6(7fzwx!NThFZx$zKET z_x~+t8Lp^hE_(g>)4=biU&NL+vDN{}G_YlhvrQ&>L4a(rSgC{M7?3HI;0Hm&7PwEI zJCB~(xyr#9c7(DFH5bWP^GUpB%1-`V8-AvIHcqGhCQPJfVYEqGqh(4h9ijj&Jkt$L zBq_qmrrO92?3GjThA9ubM@HcV0Y(nln#%(eU^$x&NTt==Y z_d84T2r+x2R{AdxC3&h;t>Zb3>_dqwHGZ@gndx6fs8KySo+|xCoXf*)91mVbfG2K= zOkU+XFyFuC(L6xz&gZgkv;`;o3C6QZj#2?Vm*2sG|MMT=?$`ewCf@wp$oJTb%O-7x z#guH_Cd+7P>8Gb;yqvb~#`5H*LLs_>`02*&&7($R)}-<_10PH57Lf}lN6$T{WY`4C zWq{`N%V}FDCvoEZ1r(7jOI{yr*O)#{>GQMwixJVbYO*GzcA!$AJ_Qx8F53|vLX?ai zvyrMK$)^tdp#z3Q_DP_gX`Cx>AhcJ#%zm)zx3RJ5?=*YDP1Q!r=K6ddEv20oX<96; zZ8LpieP!{O*{sKw6gDQ3dBd=XrS%8sZ0>{S>9JHOt)f_3M_W^O<@x#he~IUId;`60 z+X16AnV0D1gR^LF>c+wTmn{25ewtjog@v^lZ0*=nNt5xjIJ5JY@!p;9!-I#OmVO-E zat!-=4#7i+`Sk}lH~Bt>+PCBN9j}$!r#E^Gv~*)|=oAP$eRb#rqToPLy2G7)$aZ!k zgA#ss_z-+Az%Q0pG1n9yMY>oj;TKmfp|zz2*=z$Z?|w`as=r9SDa z+(cR`PJWrVj9ckfYT*O6)JA#0nXr&&e3plw&EIU@D(i;O>V))oW43FHewz0N)pwlJ z-XO+UTi>Q(;z9mD<7Yl}#(}kXWViTvPBwYs@|*^1=|gxhZV>>Hml3+54D% z{%hq8+etFw@l%}SveS_)s>e!l=ZUvm9vzL10b^q!cJ2gDoq96g(HE8CBv*Z9x$~Lm zsh%>--|cif(#XJ*#G< zZPL!sEzoqEBq4DQRKgOP^`uL)5w3RGZni&I+Y3=%&-g9QHq_Xe-<#HnX0Pc((`Fgk zihJDp;SlQ?Gv2WP@&fu9A&<*R@r4y=-9FU_gEkRT^DlI*M}f=wS325pe~0NfNKc=R-a?^JsC*yn>%-P9eVAWb!tL?MAN~ljq^+zWumxHmP0%Of|irMnxR@8iau+c>a`H<};by$9{BZK?Qm zP4P72_x|)W&R@L>%&%eicu%TL+w};OmgZ)hIDQm3eiXTm+OOpTxQ*uMkSXZ@aicGE zj`qd?_dp206R8&st~3v(V)4YR(8?kLK)k^@%GbWIj6EZx2t98@W4#)AVTfI~?_lr9 zEo9dVD3wn{%SCDe<0d$D0VQevYiU5PGIA2ItAQK{8vfW$Mi+$D5vmzLyRM|Pr3qk~ zRZ)6W42z(`i+o!Ylf~=_ip{Onx+%%HPt9>aKwdAno9U=Oq9ycFWy83P)@HU;I|D+< zGx@H$qKy}AteBhl%(mHv5!AmLM4P|4Wq@f+*}p%2fS88Jw5^TO%d#f{C=<=iMSmR~ zAw18+&Yh2&qo)J_xs`eB{o{Xvw(%Rd`fvU>nBV_Af|S>3ZVtI-GZ1Iv#?1uNmZoPO zv?gNdvjO|y<=wz=^?TRu?c9OE@hP+{ty*$a$~)$pTcg`TPH}?FWL0<->%oTGQfJ8; zd{tMZx5Bb)@|AWpfh}t~`)Vq7y34Dnw38kdXC@jj(L<6=SU;ta!H*kQKT48gCyr{x z&F&eN?84I6)Xp#GwfruhnRUoKW(wCgdpydNp_RrY55V;D9bBD$4{z@MTk5wD?)?xG zi(>$QeZ5C;YU`QGGEUCV;kyTa9UektJm6<{e}>zOcK`r~diLOV4}Gh=Rn(3`@GIL6 z;v3ucA%_C8bRv$;B(lRwE0+oxT-5h<_|E49|mn0pmL{h72 z-<2#w^6ORFX5JIT$c6ARZNbfemT5y!e9c{>cd>Kqo>OLcK~ULX%{-F+46WHjeI~DP z)={;2Gkx5FTgD?A+XSKqXd&H42_7;+i~2%mM>(}an0qfCr$O-~aa)`YmX2&~3(!(3 zbH&$TqTDWsG*nv#a-7A@MpNF(Nb)9zq<10hr$Dva16|u}-|R(wM!mps-=%efDqNeg z#l*HjrN_*%5RY|bnWm#(e@~KW9{ge+-B;ej@&EDP#*M%Gk1+Y_cTni+PssClDb8aj zM>tfPG%|hje1AZ_7+zDM0Q~TWA-??OC<@q9+8i?N#W-@m&5fcCo!?WR>nqzOjUF|5 z-#G^F*7LxHiH4S&&YofH%lbdE`4|_Y@;luN0m!J?9BVYvHqrJqKw2L3ol?5_q#UL4 zCT)5yF|U4RZ`ii|pz(fElb3qvNyWAGaOK8xjpf6(eXCPru(ISRzN})9M-UX@`&nfD zCabJMX$=`ai;Sml-B~NH;Nv@ggxB}|E^-<2|3&poE#1P*(iooI@r^PEA##}(cwWZA ztGjoyeiJfYuIhL@(EkDs_MdjxUcf86ep$^Dn%~{cz4-F5dB|8Ie94#XLo_9D2oDHD zy!hS+c=wIhu+Z%e%h{C6;X7acrNs7pmWXc%&;gnPcxcM!k#BB7xPen;&FkxU^=I!I zSc}s<+_?`3HPNbQz~I_athC${iL!%h~=-j*_JUy^nbn&m`Tc7uj&|1mqwG8 z5%ySR+eKmkM&2?nqgmD?j3fi4n?|IM)7R-q2x{8zy-(e z_PcQLX!eih9MOjDg<0(S*Z&l)%bghc?mxuxw(S2!BFJ92?n@l&p{E@E`vexIP2#-+v9q zfA3dt>hO`e$^l5<`;~9{U!z{@H?o~LFlQj%g+#vO+m{=;1EJMPmufFB)vEP_sS{i_ zf$Q*;JQybRUtrW~;Q^)77HY&fm zOO%RS*K4FQ&DpT?k<+;8%iBeF+{WdLe zD=U~=T*S_;TM-nBxcP_g;=}9=*1TxBW^l_Ebhfu+erXYxM@De*#&vYHcT_ewkKMnI zk1t=s{L*4n;MhZSHML^!%;8EM8Q(_`hL~Giz{=V>w)OX8ptlzXhIeE8zySJsdN6kX zzT&H=t7}6iwbQ(}{+?bO{N@<|Kwo!vmDILlGHpF=EiHKYSgIBMkl*wRnoBQfDNx6Ih1JhF#z9zSB zMKNKFWlAM%9iPCVE7#x`OBFs!pev#M$}_!bz;rU(>XuGGbChbj97DPoq|4e9CAoox z>^J%@fxiUN=4boQ1f-D(LGO{bevoM)uila;qUETS<(Z?_HcPnmU6eSM&gzRR-D;t0)5G^r`jX=)y@o;1Hkn?zFu=qh0b(t-rZoFQ#4kR zq$g9~rz0C)$CvNU@wjMd3AlAD#Lk^hP0`0q+2wiko%!d;n;m>XX`C>}GBN~{RM)T^rl7ku~+s;fE@nUrb z9BYI0D8Xhap;2C}mfPXTksU2%)7fVUU)d>ZlZ?{IGTz*v9T#akDe|_d7pcwikNe8y zfTiblzqy{p>xCzg8s*?^1l5Y0Yr)KM`Qa#|P|D-yxBdWU_WTx_vmF)QP)TpwVegOq zAr1|`ir&^CgaB?oJdfr4Lp-zfEu)Tjx3)Q6-W&Z_II{J1^t5hM{nFpQ1Klm(s+2&v zo*#M(!L}kiglO_}$aooHmjS-#S7y-5Loec`t%^&>)KY#sI6q+{XtqsmB=6UOX4($69i!))iF0+jYPdKZ7N&Gf^V8Vz=l>ga z{n`JD>%aS7V)~_Tq1e#}h}OE=Q47^-i_}t&=lE=omb8nw_8f85SFhMk&qq830r1W{ zAzpgPdwO+q3VPuM59iK>n4W&zoFvneVy{aHX+I~QChNV_%X*Blf5{?ebc>(Dob@3wun#B8X-2peWtk-%3*1tCP)&H9509#L_e^;)N z`y?aeN5Pv}M_T`CW3jSZTZQm&ee$QcJNF58^qj!aA^WzZb9cXoUA?C;)OAQbZ_Rb# ztpmRY&!dBO%)$2VquAcXn?gc(cy;e@S0Zx9;d1%p=+-Zlzq(qLu3u~%;Vwxdb`PP| zUwU3eb2C%6v-MHRFA_-^MD}|TS>#Z}t3P`e@4fyq=2NU4$Cs}IHxQQMZ$8?VR`AA8 zeuf`^H+9x>+uDrRLA<_rTGH zcuXzJhbmvc1w9{gb5q#$um35!KYb4u{^Q@rdha&HuZaa8rTuT#6=$=?=Qq>Z<%G_Z zu3YYPY3-#rY6RAvm;j2!5NFPOvGn^>(v&=k&BID2+9K`j!>`=Y#2U?>i?&Zo%6W;w zA1{$jAnk*QSYPsUXOy#%u z+az2*2J_9q$_I;wwD>z-SAUTxt&X&IFV+gGYb7=ndAXwYSL7bTY`nSBQ+@I3GK6R4 zO*4Sji_6Ft7t!4^P^oQZ1wj~KYGoW-+Xj#|PVO!h zR!|7?=x^>oAt+*EZ5F%QdT@1N605~Lf*_A)I=c}BMg0816jr9z@$HTdOl;}Ji;lK7bhJfLvBN7%7|wL##EUOkeRJjnZ(JVe-GW2A_f)?3_vmY(NAKN3 zXInd3n`^s%$^;EbbYOTG2Zo2MCsgITjONWDbCZu&0d9A*$!nZ&m1*4N*zGdst9))= z5Tt*jny6g4#HoP+DKfeSIZ|0ZfQ;2@4h(zor^jiW565`mrR+9T8 z9>$yYuuEPg>x+0wEB_w--1ux!HJoavk5XTq_yPJm_MyLHuduOz)%-lp-TPy#+q_Mk!0FB zF^R*UUIoB*ZX~NRm0sR`YYd_9VQkOty6W(Q055#-5xO4EBMb<~n9(7$E$-UTEz?Bk zDnMvNJT{5twEKBAa{JLF`r`=NgpExs#CHXGl}%Q3^)p36qq^w1U#Z!2*J``kg*O16 zXQmCV7d54BlQTCinkMT%h&uTl=_t@tpNtG@S^%v1T^79yrzPP_mL_gY29aOBS$?09 zu9i;sD1}7j+7BYz6Nf-`q%Sylb3KRgT)$c75%3(jqz~BIreFFN3SIpOeLLD3bH4dht)6N!#$_eA z%1kaN9xHDIBR2vcudM-R&xSaD+(TdAhKl;!Q*$#==bo-7lH5oow9-he&d*>-7d;ZC zSJFgPk!(kr%abrqY>B4vG4rW0rKtz? zCM_yMYGY660zU5SRWz`+6!?Y@t^+Xjth^zS{m=R{%lWv2VJ`cG>XQG)_pj#BO=+;~ z7mv(2msX~yN#(YUlhP-Z>&DFc2VckT{+E#TIa0AK=j4uWmm_f7Hh|~(B9HWvc|avH zcUkUu`i3_7+1W-fIZ#&;kwuxbsU@y&ZU346Y;T8^bM%Yj%X#+fC+M4;h4$A)h%tbN zOc>(yhacnovnNvpNHeKxegUUH{0IOYOl53DKFi8z%LjP#$3Mk;ufB}cI<6iG0R*9k zB61b1RxIBdtk;%_7mW=iGSK$7ty!tQdWq*5jmK&>GNskNYpF9LOePTtqi%{pNj~7P z{EcISN?)>EOSJhmeXY@~NuK2)yvoLT?r$4Un|N9KjgzoY)P6n^~pT}*zq@#^u?JxvpXMy+L3-R*HUqmbS zDb+`=QI|Z5DSZGP5G(pkf7ZKbHit-)Mw^(crPcZDU8dXum!73y9nxkY{XjN{-ecuM z9{SR_-_duFu$|NKzB!RlMbu_K#As31XY_u;eqmauX zXh1YJKM2siv>fZa)P^?!EHkZbTmx?P>LPPKm~%2|jwY2y@Yjc@o`=?Rv%T^f335hr zRISW<38&xt2qb4*ik`r2v^gwt$shaVlF_Sj3`HBYBgclmrb_>L>Ro9N?RGjdRHay+ zQJdtcVL*dt^KvWdH}iC^3Cfr+25{zvZBq$zT4{LDrUJPMnt0=s(&1;`iJ&2+nYGHWJiP^g)BD!Ifrd0fDNi)e3x_E zZm+99Hy=3HOST+|OPB1(a8o=$HhI_xSWeGRJS{H+AAJ!bPwCN7ejP10 zE}-+hzr^(OU&s9~{dPj)_|fu(eQmx64EF$I4}sD~PDgu?Zcp3!8>OL{=ZSRm3+YAE zrAmJsWsIz+NI#U2f!-dcHF}c7bphQ{CHkn=$9e%M&c-uAwCoSoi{?lq8!OF7Yy^DV zY==st=~2wjdcb)-xOr>WGic3qTIJ-jt=QlHG5{c#X>;;pj$jWVI$H)sDG(95%^H$P zmfY1ckSb4la`g#4vu9?sG{+lUJ#lcNd2Jofo;`>2r=H!=6~|999s2Ydw%@&v+ zzf8_UKlE_&lk>QA;#gf+dFcK)_T3mk>(UBJ;u`75W)CYUr+IY^yKjxb4+GrVySJt~ zn%CEH;`{~l&OSsC$|%k=`wYBU|=| zMos3DV4N3^Q&DR)#xkR7g^o0`U+5W^N%fLnf_p#u%m=QhBy%x9evac& z`+ua(Ay|lbFf_}UIC5JcW*xO^^6K?gr^Q9!%9Rj@ z4|^CG*icbVsZOfLK7G{0l0xcU&0{nc1K844YkU)ht+utKw~rpI08>k7ZfZhrSGp*y za-L^UGB!hpMp~_(UG@vfLi(gF4C(_aU1}uq2lG?*PusSEDTA3?+m{)6kxlGtZcfu1 zB+a*>b%jg6n03Y@u_tHb)=$-NrfH9EMx9CWeKSy1bxo!D%Vk=T%e0ET+Hz~kwmZv9 zkK?OrVA)4nrze+G51IW#H`em(r+F?hgSmOqWv6}Cygl{Psk7(MKQ#ld7?jrxdHu$N zj}o#75g@Zx#NkUCo^REdNwiXz*?;LwBFL| z`u4i5sT0k2X4lEMln-S|k3__g`yi|PnZ{^(!?XO|#GxkdeDqvPXL@I3vrsrQwhYW( zcX>J7JAvpojql?RNSkwo$C8$}_9zZjs?bVr=a&@c8_=ycv9rmeiLd2vX1QiMT~0)~ zg;@-I@MjqM(f@^;fBPR`eajF+j{^vp`5(3RaMhP=tJG%K#Nq5}d8zb9BdU#J?H~Xi zK8!YQzxbl}xjF#+lr+^k7pr-WYTsOKN)uDFvDJ~9$N%6B;2(b<;U8W=c>Dx#YQ=fW^(;5?GyG(5YgH*TT)RvTCegdxwW3wHQ23*$~M=~%|l0Wty=qAZG3Ip7-pSu zR*@@hJog(%KTk43*$mzq7E-Dnb)*e(or`{_e+#7* zuH)u|U!bpThicpFyT60C$G(T9{5+bok@Mg{?-86BIF0F*3A}&*ZG3IdH}UO#-$n!! z^rn|X-Mip-?*tH_yQvkwwdWN?7ve_Te0|$NrwV`hI5KMe29-M zrs5+rhvqp$QNP?nK^b6sMy_~AzLdBwg>8dnZkv2==H)j`{L0T%FTF|H7{mYim0zf5 zx>sb9NJzjfO{ zGRt?Ti+lDYP_?na>1qL}E{nph_i>wh`8@E`pN9C_*E}>eRZstv8bf}mgv{+5Xd1bI z;_>Hj|4aWy<+n!85|_~)4}a1d`PD{r9QaK;f12`ny^7y4qP|V~Mc{k4bx5Vgk?cthxhM zlWljq$edI5at=vXJ@fREBt_t$&s4i#NkIsiqqIqV%DRoVT?H2Z8du2{O3#99znov> z4>4~)GH;cz|6qOQJ~2@s#8_aVOxTfc>>Mf~mq>$%B`OCJ-GNol|C$2 zTVE%g@p!hn zzcbDgQ{P*6)8o=3kD7;#_?GG=6ARXsmvv~h@?1DRUhh`N&vE%T`ktf(EbG?o^2C!+ z%_n=VF?OcS+#aF>nFp@iK#=osclS=r^w%C?+NAwAM$kFGQ0eQ%?kx+a z=fVO!gqR)Z$DQF_HRaEgN;rPuBKjw%;TOXS-ZTR+kY6zb(7LpOz1MGH=-xOU_Vrf1 zO=@6j8V9c5K>NZHBvwYHMAQD|chWV#fNZhoDmIqpdU`P1--jK`_aJZe&6Fj(DPbiq zI*zb=rZbMw8dy>q8&KBZnxm-nj=b+j+QgE3Gf9-7OyRjJn zynS2XwKV|;`r#c&Z$OvLFlz&3V^W6!-oEkscxlgX zqNBO5l5gz6IV|TN;KcT?n>p~_=)c4>+rEUp_F-kz*(OspHLM5L%e((3q{+Ld_ayf8 z9v9mlncmp_Z8eN(*>s?75MSN%4FJ&s312828ho(!e9S^z7jyICeYwmcBnZe-g$QAhNSXbW+p>gj#(5HG#=fvQ7-HSJ8H_iSDP&7js+i4n!k zwLrE8*X=`uPOy9@XV4Y_GM?rqwA?gGa4#%)?OHPgvHpmFZrtWD#^ zw|FJ!9f;ICUNj)*R`J`@7XzjF7|sv<(cj++d#8!JkOxGmwXmgTZ;mz)pai_h9h zvF!zl`C{q~H&9OMuTZ6{Pd1tLJe6>pNA+qZ6E9YCq{ZQR`*}Kz7&_9`I!-K{FTN9B zvL2pegcqV($<0MQqW>aGRn9>#2(kbA2yX4$i(+o$=hmCn^VmH$R{4H=co^#~%{7

eBt~oZwXqgnk!{GfXl>97K+S=eD#9VJTW)i}h4&5Ke zo|~iSoLe;Tk?ePX?@x-Tb$JzolT$Tq+Aij@7&)*XyKjz_O?NHXAl^QIj~jt5k4f!P zjr~ZP3po>c{K}DQM-7AePNi$RJ*XV$jr5efFCqY6^-Ov#I*jC((KC(sjHCU!KGR0G zb)Jb+_@FNz_?6Mt%{iF#M}0_rqGMLc-{`Zve=pf_ZjKTgH}W%mE0v9rtB)7AJYy-w zcCNXNf)`rEq0wRkRbxOol5b60(57ABDl^%?TJ5b9&vCMD zBO7lv?l0Xus!xKu%h`C}nKoxyO4d@8V&mo6K9D%g>cY>mbdyJo1KgP0g(;GJ0aQBK zdopGpTbn#TG&Yeo79k0a&>Q*HdS)IXha#E^d3ZsH>A{U%f6@EkA^N6fK(}Ib&o3bG zeB9c#j`->Be>!HH?KuCBsEfcE8O0H|r>wikvNn3#rN44?yaMSY`v61-Z~ zHNSvjQwGcJ?N#eoZ)wK(_8~m%>Ba6_qwwJ)0~x?cqD#VW(W>ys!TnfiYfIf809fkm zz+!h7GPpynESD}LJytv-mdvNfk7nQ{8aH~bH`zJf} zsNEW)x$a0bQL1acdP1j}_PU)`em3=(eDfMl$Kz^KAIkS+`pQsA4Iq}!>R3->GqcCy z{027mmLrN}o(#aoh)-i_J^Hv^_Nb89p4+7HDff!DtxUXWT1S$5* zVo71A(q*{QxHNoxnKo~Y!`mCh+F=MxOaMoY)Lq2qo>o?X2M=n`_hjRO>J)Et+bQj~ zR?k^G;qcxXn@FU+E9JaRN%J_erua#ur%emV71TriMPweLW?SA}x2e0#&!)`R z9uIRZi0lrH2i)K7cjflJxO>d?{L%ULJ{xl}j>o8<5?3taKxI-@@!cP z;lSV<*wJ%Bm9<`6!q0F10Scv6E8p;z=MaX0GTNxFm-hUvas=+E9mBn+5Qg%4I2W({ zWLwuE40h~uq;j<*+GrXlu*~NYil-ws1kFh%Ay=9=<$Vq|Yy+sYT{{Rp^vyiLi|>Dk z56`@~q4JMiyo8}UhX;LI>Z)Vg!~~9iai&eN zNAfLC@JA)-UU5b4)UFy6020i!H@j0S$S6ViO;VI}=Gz3SIufgPV#x0Qp8ICDW)y-Y3Ry;UdMIiVc{Y#@2C``318=yKvgwOzmN!!!WyQ5i3;deQ)5POHhS zVbcKCcxmPtscNB(f@L5A%s=@_h*w_mP(#qmr&K4kU%iax+jlXy`xqV^Ify6W5L-2k zY)U_w&LtV$Ek zW85E+%pAHq4j%#Ld%CdPk-YevD-^KM)rBzh&^f;VS1)S>M$c=vH4C{MZXVo+-J_$( z1e~8XD@Wsky&v2qLA@iRgUQ}wKB+JHi7rQ5 zLZPQ1$6-bjPip&w$D73CsBo&KtvgS3G^gzl zH-B*a3!_c;Ri4^6A?u5%b>bF!Zrp%hC}8%~SFpJEWbC|^ZQMB3E>Yay%wq^{xsxQ1 zT=T%}t@u8v-x7(VM&RS86i*Wq(PHwGPI0#9qo;TtBA+x<&%-(NJe-IsH zUZuZ4l_6~dje)g3bNgqj$(S%j8p-wNiRy2Uz1feS$LWd9@4IBrQ0}F z%E!JbjMr@c7L4xOo2nlcy1KB?)rHp8Rb+w^c8%RJB1QCnCnkrsVsLy46oERzi}D^P+QJmIZvt$<(4$nZA14viqpIsDYIUBinX88_}ZF&%IIrzfeLEx$>sqXn~#nH8-ZqaY4~BG$=BK za76J!7zy8*BtWqv5!-W`fjh$~il9yW68|zDC2eV@xRViVlg?(kgot8ea?49r`vBQ* z8b(WqX{QH(0&6*Uk;s@6rJCRln&vXe@JE-A0wkcRYyJ ze7FrFPG`OYyL=Ono8_DJ+lHcSg?_d<6gQu0$(tsh{4TDf6PUO& zqukm$S4N*S|1{vXZ5g)(6VD|*HywLVx|6RSpe=D=W2hGV+o))PL~(B6_&V)Hg4+1A z)5N=p(vsP}wEZM)cfFBB9u;I8o2}+(qc&TEVdW4f5N$9y_~~`P^KgIXcC0to78$#3 zc?BIyOXyr!#J+1cQ7F4oG6=Bm#!ZBthr7c&og25kFhu|K47`wAwCnaA3`|ZVgopOU zWgNNuDW`_Q0SGJ0`|`aIg7py~-_lflec_A}Fl)3P!&eoLMO_MGIg$>h;mQ*)^EBObszD2mzj`R2E@d8nbtjp9TdPbOJBjwPjH#E|jnBIkH&G+Okn}2T~yNr%c z&jMiy^M_Akaqo%PJ~c~x^b}vG_M61x+G=<=4kuIIc)Ksz5{WBwGihlFSXcm3Ui$Ne zqLGmh3k$X9Yn*Ltmit*D&ml|n#;a}P6IgF;u5P;w_re?MM7X$)w&Odot-tyvzEJ(S z{Cje?F<DT{kMchtObeYLd}*AE{=u28_>#1#BM-b?FM>Irfl zriQlR+L1#Dd_S?wIGXF}!N|e=$dpRxo00jibQw8~D&;TjMqp^sNhgWqCql7lb2kPvgkgx;`FRxo=sa+02>YHnfb9c=Rr76~m_+~7OnEJc zcUx7%n06cVCu)%l9cicaj2`1)lD4#v=-I5>-QT9nw=uWWZ|>i@OjCcu;?A~9Wc^U( zBt7RRPdYBHl|S2BX#@|cb|oi)Rd@PofLfQ;*3@g{7N0yHoh^fofoq$W@%6blw99gp zmj=uy*R360NuXbwc4Sa#04^sco%!|4%b1yB32jTuHFNo>X!qzCirEP4)90kVOa&*-{DJv-3Fp{>ShT;?l`usiU49yKo6x$0v~~lu$qprE>IfS6M)%Kc}<5VK~C+^lSkJTj)476%t&IK zUn)O+LfXX{@y9b>s&feg$&n)A9&hoMWoyvxQrIrXfNsB*h4DPQD0-SP-l(14Ed}jy zV1ITwDKsD@?&;b+8fVgt5elB9J4ypHQ{|d-$u+j*b>XIiLh~-oF&>d_=ZDMXQr$3e zr+t)$k*lsGnN$rp>$L7s=vCg|qXoW$W!#vVvcQyo*MsgsF3NGfGA zID7gzoc`!zY?*lgzgSZ8B9dNm!*+m`&Nf^&St( z29-B!w>F{BoWtxuAFdrfR8t)Q5codMJ%0+%eS8*u)3fl49OX>PKR$*NjWn|RmGf4X!(*DA!=B=b(H|`tOBBd4(I|=~N7jbWFkv}&R1;|qsl!}6yYY** zpEa+XPh%4qgO0JK9W~Sa-Q{zTk)P%Nlh7&mHJ4@bEpeJ>JlFYb942|=ejxt?`!k47 z_Eqq<7fG&mC#BJ2(#D7;-}bwerLuLDgn76<)yUOXREFfkjc?;{D~xpR{%DyP#g6a) zKIR9GV*2G@L1AczRhHy5Ej7Z9F#AK>>v1-iZ3(c?2iEiC`nbe2<>}P%)<`WqlOB`1 z>Hd8n2tqvbjEDB*%OIXo3VKxbapUVrF3+XsIj4z(>htqB%l`gVgzt>P`}$#Q{deBN znGTN-<0h4x20O>4=RBG( zjUUqc!5BR-W-;vx)Aph*t5JkM!XENQQct0{2wO!Va7xGm<;~1pv-3DHI}b(x$^F4N zfp4s(jWYmmwnY&*dhU|4_KMavg%F+x%=h#Feu!(&9L9W4cdA};KL7wA07*naRDmQOZ7vjMj@sHh;;eC! z=be`RfV3BORvdZmlhwVi}N2#eUOB`&3<#~mn3Seo_Nx5do_Pm^6znS zyuMJy3FsaYVVb z0*+s}h)c(hHRPJ8uK9WFzI8j|$@g&i_|dvf{tl1c#;(yj2z?J;7}k6mx@~0zN3MK| zEz`3ol_7K}`T*eGF9Gm_09&SK;UmP+i=t!*N*u_iOc7Gh%LP?ykW-;b+ zu!iu^v9N^JmDQTsv)tZ}x!xXhEHIGP@q_hW6q%a8$ITwsOi6ZK)lW85=W$F?!lYw~ z`%St4_*sUof&b) zhBk^M-{gFhP65-cV7E{^UUaL>-|c4sTw_VrXc|;rY#Z(N$@gUTUp#HhFxsf(FlAA) z-j7S`{$1v`^VSQNH{xE|C;*?E1Fl^Q5r!THYQMbUb5HB*z~##!g1B(ZF*I=Yudwxl zKgImPSMl)Z85BCVYz~7Bp^a*6Eh*)9E?<79rzXTprcw~%?&JhYr2yWk?eMmwI~W%? zFHPCUys$i%Wtbe=PV1;2<)V~d=@0YTO>*N??fe|jZ^V?rallu~bkm}f`q+%DVt&^o z0kru!z7I9eNyzL;1HK!ljkc+_W$1`pxHMfps?*I$l3b8>b{s}9%eCD>=`nF!o_Ji~ z!uH8n+_pw(Ec0DMQCzI3TwlZwB%DlhCOW|3i(Ei}3=Uqo1|K0t_wB~$-o5Cbp25lU z=bdepbCwpJX-SuRBWmlO8>85J<0jnm7?q9Xg{CaRjE6hBcVXnferLUD>EjnpnRu7{NG)gUi#UDd)^+q*Zs688P{_GK zi{=oeu@4~R2-RoTyOi&M zzngh!EU;cMkGApHwK1kyS`sDoxo+ke_?l`RM!pL#uFc0-uB8{hsiHM&UUZ`J2Kc(6z8KrGT zeJ)Q}HGa(Jrfvug>A`6lMa{h(XzFT1p@uxHKja3iq=QbJ%eJ6H$QYv$1y(P*bQQ^d z#>BQQ;8iqUGP!l9YXcg@?-Iktr;~MCgnH-=8GKdIf-eWpp}>zKT0 zsa~v1oNR_hNKu8$Hz-@`9ndLD&b4vnHuPCbj0=gvnFu#4mmjG}APrtNd5 zpTl~~#&@)Zo`;WLIE`0+_AWZ-7c1`s0D?>g>#dEu0dl3i4IjUF8gKpJ$MAvx85GN{ zv8{DEDj7q%N1a9$Oyq0O8hW{9bVHo~n!-8QOmIlxO79>LgEL)@5)!pjp>7C6c+1$zE zQbn>h*7js>O#Kk`PNb7INNyS!p`s}J#5H!~wnoQRA#=X@t3BSb!`c_^|b=Vil- z%ggKOADv{AGbVu_@0oiXl~Nn~wVmCzcB{+2>&ou-b{>zhF{drNyykMbeUF|<4$_mV zwtKwIY^?0Bm#>Xs{p&kjjF*|efn@O}l2=~9`t@6}_^HRSICs<|hbhTlkK2vb%20Gw zpP(Gl2d;~=?H*CZqpV!RZxFAjUU^|!T?M*bAX&53fxn7YJzSogM5fBu7;3GtxV((4--Q4*$oMW2cT0U~tZ%Nv&3)QDhPNfR+2)>%bV{!a z#eHr^BoShdSQ=%ex9ywsCs3rZae&0^cKQ51#C<=m4Bt@R+G=?a zU|kM;%T1E6ybwRvc>0aAdp~Su>jCQi%`5?C8qoRDQ~NH-Ee9H@I#v8jI}yj-3_H$V zKpMw5dFbF!pmz594eUSlAvRyUl9w6*X%ge)!Gq{D>+#)p>O(Z!9c;OD1rv+QP|(=> z;b~~4`r2{3(e7aDh06>+$3hv};YsfHZ@qL0AMM{)xoCT7dI}#LJb>M2&SPR}xi?(^ zi$HY0YIZEs#UF=GW}mfwX>n#6r}yoJ(i%I?e9R`p35;eeT;&36AK2!tYK%LFdEA&A3BaC^gy8@HuY-c!OY8uF8;q zjp56IC~0c0#c66g6K#}RWvPw)c*lO?vwl9iB!lioUi$+u{#&+}^!TJi^1hwsPJqY5 zg5ujlJ{boOehz|}tEn0{mz7_TC}_{_Uc78Do;>tuJ}%9yr=}*-hl!9PQW;L%f3&YtnyTpK zhmPae%dcbWh0B1>v7`KK|yvWlm^{r%plRCzrk zrJ>a5`u-~qK7dcX{2I1?d)(71TYvBzR=4cO`7i%%tZv!k$l@bkdk=2q z`=hWXD$@}rmE;oAT_N1d$CjPGOb3ptb;`@BCav?o5$r|s3%bq3ltx~l%zIo(-`a6in8hH8nm-~>W9?96DxhG?0`EL}XKGz?l&wctczlw`Cu~8(A zRlb`qJtJPW?U5Vk*!EPW_1Rh&9UU~TV$cv)Z!C)ZHTZ6 z$1VoLgI$}LP=4*3n>PKQw*??A5#PMSuM=EdXSZUNE)C-%j-TC4!fb5n$9()u5Ekd_e+Re@6Yy0?Dy%)4l9lPm*Z!u zpG{#o%e>Q2I``fCak%|%%Gx68bg=sy{{)@s!?^O;ucNhjqm#Z)jHy12!XLBoa`;n2 z{=VEcmt&jsrvIbHJco<5C1M{8`}+G&oqU61?N?vbICe~7&z@gk?N6S{dw~0vwe`%# z&Du!=06J?!qubL85t68hP_!zn6{Uuu^mO0evV+T}q0nwN@V(D{wi0)D(-i;u+uy?K z;$msKekc@|q+c5H<7n<#n6#9JT3jyN)S6fOgdUh-i?>>rmR9qb-je*pTHZZywtT zq-CnKJCm7oro*hvuL$NiV6%@?lx5ia!AD5r7^nB`MXS%VE;i54WBS$tX0PAGmW!8R zcC(JN40}H~jc%0S%)Ytei{shrH?ZOQbx{XXr~RisLZjU&o+xN2o&WVit+6qjo!f(* zXK2NiQ7g2BmX1%3kwGbqvvYf(V};ckUoL;NZyx|4O%m+=@H8eDmwTKEteZC*^}fKq zykjd?C&qAVc3off0rG|07k2Kzt~2Lh79W^a$$9}4qarB`t65Lwt|SMGU@19qs8rvn z^!HckuqsP31FU&I+83L1pnbKCS)c=;38F^DrwtNJb0@?du@oS(r8iG~t-}GXZD{49 zZ8B_pw=o$Kkw6-~Iuoe2VYUqh%3NPRy#PjXD?=IoL#=>%vm&BZOg85 zIqNTU4F$%^^=6)ie<;QQHy^n)IUvjQ^Y+^)4clJ1_icOZ*Wc2fxOqZB2lLEl%SHtw z%jwP<4-?GZ%_hijkr_mf-uJeFE*qa0|9=l1M1STld|I3%hrWv<#^+`J{4{ zT<*PLM)e^6o$1Md`8bH9b+Oa6kt8S20;>5f@E}k?J zWS-w4+{BTXxoZ}TOIvK?dB4~F_1+p zi}r@??48-t_>l83G^qCQm+ZEl{P4o96TQW7nsEO9^`Gp^gYy{<8(+Bsyzqj?Bahr3 zzx5Y1YU;1YWV(}U0VSuYe3r_mfx;TyJqJ;q-kATLJaiX6x@&)Jc}Gvm`ZIUs#IXYH z*iBkIWwkWEl8mJqYn}h*_?P?Jrd%154%sETmOFrP-E7+?&C<(wfJ_4q5BKeI8DySe z=}yG4T&B?I8kM%>K3JLE`6S}ZehbCP?Zk*QY6?fT2z%HYjuC$Kd&0^}<3m~zdrq+#zHo|5C!33sFDjvTj@04jz|H%4sH7NGZ_q&g7(PmBAeL!%I`hk9|Jy z{s-trF_tGM1MZqnUWMIf&tc>IRnR`txmrzo&-b1D5NQ-)d1?xP#`cSsu;ao7Q34soK*@keWVoe(Ar>@gz48^c&i-RlaT96U zLxNEkthqo-8dHe0(omWHZ-eDXlx!at&A}>nN2Kh$9bKs4zxGc*N&_k(6}5-YQ2U$= z$(y&GyWrj?-Y@Jl<^9i=S=LLj7Ls!FbarVz8R%%}28*su=yMSaxlD_`J^iv>tPxFV^Nb zjI;_rDJU;9Mwb?BKYSe5Hf=-}l^+E-2z8SLSrjoDdeSOA^bXrLwZ_KqBez9=-PM~~Z*o{nSq{y;%@0v71rdxo{ zXAvOMXT_wnVtJr502vzbG$tEc15y}GR!zPhlly~Yoiap-k>lRsj-OgTmqYnZK5%yY8R^3*|}Z{+H2 zUwqW{3nI^R;>oXV-0Naul7r{@r191~bZj|L4Cg#a`4EoNhv21;dW&81V zIh^CLTf5OZm(|Nw;gJx4oR@7V-OO-XtmCxCc-iRvS7xzyIVY_;c zv>A$xvCKwXSGI1(JNF$~v&Gtm(l|yI%MC0#V-5WH(Z|s4a|5(0>Lv+v#5bT?JF3F8 zc0Zu|WL-$kQEN3*3ZXqCvn_=W6KZzP7eSJ|hzOhWQfQo+5dwy{iJ$q%fqOY_WWrpz z2v#}ieE68(v(Ijm9+Mjrb~T3d^Q-VE5XPjg&2@3JjZkEi&3?bK^=Q$W{me$zvW@F$ z_;Q?S#|M0)(~rJ*Kc-YZ{53c-b$ui|oh;Axm%{1Cu3f^`AN&y}&M)H3Z~RTPHf)7f zk;AcE`mnU4AfKJ|mE}qtj&=CbxLDiu2Y8y0e(et<`*rIeIJ@5%CZ{yb|9(L^ee@A< z@}$Rp=v8R%2Baynj4!m#DbsCe%^Ow&x(lcVv|bHpnFvae&m%{645jjqz0$0OG+RV7 z*@PrsSB!SjXn;b5NHt)Od<6}q@-*Fa5uNlFE8nTLbM4m+QcDBm0a7{{F&xyZc=4?_ zk$t!yhxhL*m(e z=IX{`r7f_13;PZFZHUj-@H=76bvv=~;MBk79UU(>PoFz&4{ipA0n>J;w)vXep*+5P zRpo@r3e_PD@X3j@0SMDEnFlFiyN&|J!gOyPsSD&VvyCI{BXQvUm{3egeTmx;3I`9Cp8oP_G4TuQ!oHC6-;LfMT+eSwR{Y=*Y|C$-FPxv4$z{B-ED=2+-Q@S6l+Q6UcBmb56x!)jdpWhC;!3DoQ3juL@ zHd=ddCuzoNS*q$@&o=c(zP{97{<3l0pLO!dB5n2XpVqWBN* zzkoXd4R(i*2*QpOE#i8dBQ=?hd%S)N%f}O!AauqA$1Cy#BpD31uU(w%+RHF;yv*eZ z=dy8?4?o)FYR_}q_S$INyj`iwl;9xcF;`rF5x1}w5BnW9($?NO%LoYdLAnlokmlm% za&qy!`#Xf``L$io#;vQ^{FA@Hwjccw&OQ70aOL4&Mt5p`?;}|Ll+Y#m4pHkuIevFv1gYf2Qe`S2PwDd`~iH?YF&I)&{ga z8?VJqUil<)ocAW(&97P7f>Z*Ih>Cxeg4P<{?sYU9bc#r%nm{D2n<}2oLRyl%tZupp zAVa3xh*i~el|)BmFZ`C-Mwn*ANrY8R%PT8bX|<{oijv6+aIES_b1sTAc-H(sE0$66 z)|Csb(VNHN?~s=b04ZxT>4|VnADud?#}Sl-?!Nv4pxkT@6| zYtKK^qHME}GV0wWEv8U)LLb)y?i`xYH3}JGD8%R%r5g;LHu4R~ZWnRvoGJ`G*IQLi zKR)(_`73z!ThC+s8z=GfKl`uxC@t>^W+6Q7h+fqveO73cq{Y9XmhfqKZpUqODfzo7 zl&li-MSA^^?n~Kxvb&#U6aJQ7iH(Q3*8`EpmC|QZmBmZ?JuZ&0z4Z{DK*fE({g(1m z9r$xu2RDWR_LRpyeE6TI?nkTp;(7F2%I(Td#3Lns&F)88ZvXa4?Urx1tuMD5!|*+G z?ZWuwGuZOtw=s3Cg|lD%b*ygL2_40O62r1rwZf<=%-gk#CcTVrg?g2Zr9<%%&MAby z`|-Z~<@AfQho!S;HIhVO-@e;e=m@FX?V{7^dY`r1Eo7PWS+XocI}o#8S?MB*x@fgD zOW#5qPa)hNGAK1B`;=-Ris-{Ht-DCmcJBAY>kz9kK-su0_qhzo@fZP00XjvhmH>2- zB(pFlmq>)9p_JhzwVbepJzU>E`Ff`r4-o*fBe>-5TDcn3PNDz7cY*mOsK0p}%ZJuu zwY6HAO)+`2C5g6Dn5Ea|D!1z$D>ncDAOJ~3K~z7ywek-ZGtjCwL-~9JolfIxo4EG@ zq_)ZkBkpkfgzF+(H5_X#!`L?ODrs&froO!~+j``esk+t5I8uxDxoA5tS_9~7fE5MT z0n_Dt2L#TjP@Ci zdy?uTLThS#B;}piJBKrS=dk14$GG>^w|Yy7^LnmKPa=y)vqRd-fpeMn&6)+FkhkDy1;NU5*X(ogXz&IWCM(8qu;vV%Xiu4 zJAQB{!-gHcNqIlm@zvRHylt1ph5R&j`DYO()C53CZ(-J_tI$1mSLpDPrq(#C&-&}`)G|9l*fP*RN8rizq4T9R_3$SpRWjjjw zxPxZW*hh(0=a=%i_sZZzX?L))(B=CQn&ieL$IWDdXXmJA5nED=SRxHn6%1 zjE}~g{X0WZdlge>-^Ye`p2r7Y`!8|xt_P7NjnXk;Xf$uW4%xEko-L$4?;rIVK8+OS zP1cBO9MY%qnO4BU^i1XMuW6Ry#=@H z?&p7|-^-C{{Ai^DD4u@=c06pqv5?K zt4uQb4&;`&z^$1rzg=VdH?OyCbA1@q#wApu^jG}xi17Yle)8LOzkFOeJMb>sQkG5; z8X1vrQ~LcPSHAqd^hE7+Qf_|F_NS)Kyn_v|e-{&%PGkNv&*Ji9UqfelHpt!I^0w5W z2+-{!yRDV?nT-X^Qx{*#c#VsP{W#f_%r!uDOeLIut*PAxUVBaBzWWr`*o3YLb-P`3 zyM6%FYRRLEf&5gXZr7cBzIah%b+rSnbI(TicCl8f0j2!-P3zufAc{Af5<7Wy(;JB6 z87MX0OE=z|$OYu+j)l%BdWKTax{Gdl4N1JN_e_g2?TDySvByg2d{R4Gf&EFA-Q(Pz z$?ai&O?P}~Ny^m^>F=Bb6retLSFQA0FJH#o>9b5?j`^g8G1imjTyn3KpZubM-ZD$` znV{iiZ?nNCmyJD;W1ZV$t_SMqMt_VpWRs-lB3s@co3?F&?>BL{opdK)>MF!ioyO1A zXLPvW*HFeuWZJd z**HwYe8iD+;mf#HaZS?tycfHLGjXl~$4LMk7|(O%+HQW!W}KZH-ARd6M79W!Em%(7 zG{y6;zlJQ!aP01TFk54xw_<-9z|6t|?tb?@ym!yt!93Fwlh{1B9Vhpmt0fmNtsL7* z{ajaXl=*-Cj9^~69kVw7x+p@TO#7K>TX*{{`#1kHbMU^_a`C4b$I_b0*faSbcHCIv zVC_7EkPITN&sN$Vnbab3OqSzSABEz~E>8BZ%u z96d~Y+{L?Y3j3KI`;yP3Oxp9r7xOcDeDYLdY+K$ik2+MZ96v2B0gH?E^+H|BvJ9P0 z$NQ|?^<&+Ym6d$Kv9iX1&d_fAc_|ekir6^N8fluM-EL!IVgj)hJWxs@N&KgHY~4DB zEJN{;wALxIYz0v?2BpT}JE0=S)v?reDiUe6?m%Z9C>0@z*Y|e8F88^8ac+$+luGhN z;i}2fg`#oQd zn>Q*_-Dxz8%^AGReu-opV9~Z=VGLY<6|Ob`)n>^La{Zjjcu>0PI+OuxyHpLAC)Jx& zDJcc|zZt?3hEN`()XZ11GRT(o7QIF+zk85gS@7N*Mr9xSOn}53mZe}zn5(}GN@YkJ zNv_aFYww|z!t+l&ipPHRW6a!GK%%>aED0SLgSfg~v>^|{2xpD!#zFaP@o8UYlP6lKXCy3nP z8u&sjzWTY&hOfRH{7cYfx4F;G_~i`AZIeAheLy<&PNWkB=Xaelef@gy(LJmqBYT0l z=kLSjX`K&D_{UE+p!L5$`%T|2z+As9Kb<`bq^ZWSV+s{(VShnAin?vAfA4kd`0l^K zl}~>GXTJRRN66i_Fs8q`8bbpxM@RehjMP#Z8M15@O6AvyYCx-`L^D#!zTGsrR>`f7 zLJSBi?d8Dvg-0L8BR_l| zGdJAr@@yN0q9!!<4a_zA+ukeE^~x!iW`F)b1c%;64sPYDVQHC8=iV|vOY^u5wB^AGf!5 z@S3ir)g+`+)(+C6%(ZEbh)CP+17nj9!skIP#V{ zg!JnNhxS%}6f+9Cw0#>UmR7Lw$~9=@yI&uC|0GTxI#`B7DzZ_hL7t{XB4nZ;lf`r8 zFdWTw-nVV(=<&vCToNZ%hAYZV(>7{QVSzf^W zgI~hpzWdQ$x2eeEzP)g*TvHPZHIQ+O4H0cncQlv0`N~Jhj#e_AkwF4ij|dBOixc$rnR0xsV2nu) zwxtw4-eu)U8s6$FOU^RV@6SWOegWH#AH<=(dn?mVFDzoi_3ORUNx8+(OE&h-U|q9V zk}xlw25GQr){C6maW3+Z{c}pjN9HYSd&A@>`1C)2gP~apA3n7s7AAk_-w^gK(;;_; z_ZOm10$bPBxMXp{GM3q=JBdPG3sHZVS@I6+skqO(*`~8(2Iy4|RMu zc06_jyS8nsowuJ}owYi6?|=O>q+hrT2j}K$E!wtee03GuE?z2Kv^_I5g(DB#i^=U9 zYV&p9g%524{l*aO2y7YEP2-lp(T?mRu2qAm6^{U$9>`Iw5|LPb;+oIuxc;vldy-Pq zn4Q20woC<7mI-mUh{2s^7~)9-wRE{rAD{OEhhl;$mJIXDrj~VVmUQ z=5iz!@?C81w(sRi(XYj?P9JJp{*3Edx2_6}g=^UK%3opj?H^(Op|9Zj-A6>p{=Q$= z7hj874@z!LBo4LTmQ6ma9mdr@j4N~6{OZ@DpBCx|Yir#R+^=6(IC~b@x>b7@T6ept zvtu=_>L1aF=vjeGD?Ov=I5nw5Tl{QPE~e$m_Mns%t2Z5iIFfy7YVv(O^o4tPk%P& zHH4uqqvs!g6c0WBB4)4N=t+fQsrg!vDpYXZj!%B?2YBwOC$O+?bVp{9Y0!v~_Vx~^ zZ{UsFEysteYU}s>{)qQ=7pS{qz!(BMjqN0x@9Rwt-P_Zg7H^}M&a@AWo78J=_%0;U z(3HVMUwRwL^DqFV2`$)m!L*c%w<7&tI`doylu?=CCGO^0PU&;Q%v~;{lWbQ&iQgnA z$!$XwBbje0fldCPg#W#`j)V=kZ`x62ugQms>Dx>bw?$*Y|oJ8g|y1t5tg0B9^_ zijwtvb(ohZfUufY^JMCdOF#{uCd7{ z%QYn$n?+bJWpZFl`XfoluG_MGf>Rj~YafnS?G360f%nN@8=9QW)| z_~;{z)#_8&DoPxF$L(q_We`i%pKMiWxuM4-f3G)xJJD_sy4a?X5FV z`!{0!qlZd&m$-+RwJ>-3Oy#2O#WVAG^$-3Hl4lO#$bovhN7_`! z-#Ik57x>$IhvaKVAxt`+$L8U3l^){YnoCOJ_Bm6AjU*MzBWq-TZsd#3gg!tBy#?7y zJ}gC%6dFCehBQ)mjR2~VT}!{sM~pFYe9}D35A65qpTCZ zTTXs#YuCf(Wy?)%r>*qTMz|=-_8mgKDLh{4#v}M|o@eshd)V~iH;}9@;_3rmz>RyK z2)3Img-;uV(uR1B)_3ypv->u;jDAbR`2pIS)}NlsQKh2?!L9vx9sTjo3XBB+Sq6Og zp~CLnfKpv#nT@fs;BM9c(CKuLrm3^rmezjhwbstFEX%OCxQK~~2_&AcszbbzBoULz zS(f3}ty|czVLciRT7+#VpL}-tA2^_K=1c>v7TGSXJ4ljE-f|69MiN!NgLeL}eN=Nj z%FixI@*%?Ay7kzkEzOQ+mYEr@^He z2)n9cmWMpo-1jx-C2-G~_QO>myKZ~oCUu^J+JTeL&vNB2e*=b(^dG`FxJ*+I8dLiu zC~TWPNg4W2E4_h`ebU&q3pjHI2yCcWn?`|^>(gL*2i510PskFn$L{1P@le5kLy{pguUMYw0v4(NURF*QC>odLj=En6_Q+``1d zO0T?n^JLSLleqV;axBluk0Jqx*6y!QO8*@NpFw)I-&V`Wk9^LNBT3-mYkuN5$IbGC z=ZHNwJnaapi~>=7mG^18UHMjFWT)wb$eheQiCW4qD3`{@@LV@Q+#yULqgFodVRUH9 z_WhQ1@Y``4drK=qcEpv(-VlOHlQM*`c(@L>?DRYwGssJF<+1ggB0V_4rXAbGP`he-mGqn;&bJ z_puPhmF1V=VB)Wl0h&Jh5UH&BM3dKGX16b8#fD3gPa8@_J$?#TuQt$X0V^vSlan0> z=b8_hqrfI4H*em8QVQea<4BUYNZV+H7DvZLI=h^1H^t=SBqk>4=;<(~?Eo62ZAoOc~O@w({O|E9P-;^%~ z>yOj&=jHZ)Sh^kf_)d!!^y4LS8}W(m-&pNZ^#>w+Kse-#4oYP*+YUkarTCmp?powT zyJ}PDE@DcAAb@f9vm&hty_p5pW)Mn8GVCno1C>J^Q!fL0RBw@VzPL6++q6$zH7|d^pto-ahe&cW z0!<&3!J|AFVVfQVBv*`^ER8$P`G2;-mZsFClR=|Mj8VJJ{EIJXw4~vtYkO}qJG7;W zdQgkmZ_W<30rr@cGFBNQ5E@teMoNG+0dTye6pMR z(Z>S*9986&4Y*EPbr8Up-mRnAVITYzsq$#_aUnCa4OUDcN&28Q@@I@tX6|6QObAlAaMCIhF-KiDyoN{ zP0D`w+DNos9^WKIJ@R7(&7QbkDgR*F_}|>4GdMZw-J>NgJe)>eqlTHR1Ax`EjgObF z8<$mJim5^31_-u)ZSn4f(41m6AqZ(#QEL%8?;ddC6wOA|W6U3vzMxxIMg{$s&_ zyiJ73G;4*?(5CsT7++ZxdfSJ=s=ZFrt4OQ6Z;NU)2r0pl+kQe=T%*grNYY2J7i?$6 zk}LNdG)fD>+YQz7RxrP%Ct=R{A`C8bMZK|N_iAp}-Dgy`l*)cfgeAGO<(MMu`;=iy zi7!oh8xfY{2<|WNYpzFmdD`M)OAzjJq24T?bKgPAUyi`EBZ2+i%BX6r`>?yb@787V z!Uvf6$v2QK-NMy}zJwb`A9u>=2 z4);FlTj8)LSzU(2&Gj%aq0dkqX)Mx~L$XG^J3_VK`dM zZPF2U?rA8zc=a^y-?$gk&Gmu0Qd*A0mb)!nTDextDd+Ra{M_dh^Vgd=bK&F47S%Ua zfeW{wj%)=0?Ap2wJO1A1u(-5@1ILf_^g#MzP*@SSjMh} z^Q@IeuQ9R$HRcP3T^;P6XvE(-rOTi28E{)?4?=_xst}ySwz38s6LSnLu{3?eZ=ZK) zpI@GdGWfF)vZoKO@)(pnsY(^2jm|(v?^@yza|X3*?_^BbjSsu6=4(qAkMd`sTz39& zz7XaM<;_!S@HUlgT`o@@FE2zc=I0WH<@Wh;HV=-(EL2llzOqqK9n36ZZdAG$~=B~ojKEJ)pTkMC*dt11UKD(-+iv90>IYYHHsUFsRrVB z1`7+o>C?dd_a_(|8xtwV#>S8&2^tOmQo=0DFg`wxb?esE#=}19c2g`YEFei@M~1qj zl)~6pbEqA^*NS{GkG@FdHa*k*Iorcy9~xsko=qN}Z4qp3rP;sz;gW*BdIak3&9#zB zER*|{W_F0`V>|(#hvtmw+!@2gc-}m(Vkcjj7@V{LdCthf5 z<$~l;+HyWL(M9RaAT^w`9=PV;U~-6HLhl*l7qNxgs`twT?~K~81EN*LfujU%xl~cH zr+3#$rK1R~0gYZ6!*OOt|+^VZZ0n3uYU480N~jt zpThWv+Qhd5rTvEMtH6F#Wj{uh2a@D2cdm3AaGpzJPo_|UY_R*1pIw3$Dfte4c4*%i zL3vDvYvAl1_UsYH!vj=HRY+n30m(yNg<4IL57I~g=Yl)C<+#gLK#1ZVgD8&Fq<3vY zRiA7l=W|GWpj7q-E;pCJ=H&(h{I)>{uQ*>9%-f~8a`+}A?EdH@d$hY$?HsJNlT-z; z^E=9VS8h)GZF8V(r;tFJ2Yg(f_FD}*r*1hu9&1V0uLCc?ta1GKo#@(D)9UJ~vlAMS zPkOi8?u>J*)%G5_mG4N_LaW7eqwYef1T$Bbpl@Eo#|Mw1yLA^j@iNd|hSnNUG%k8g z6paCDQt(LAn@~__BwG+i(LM^KY3Bda5|q=b7$3(%tO z{)qQi*E*3bQvdYrzh7EF_CNevAk$F)-4}pezDXLFKJ&thm|j@w*-!e!F!znkanU(Z z$eI?A(b7xu%gOSX`s8`|v6SW>?d8jDx;s(A+eM?ieYlNBFBkFU>10TQ?z_)?_vF7} zx;B}R1N*Tfm zc|63+MF;eoKHD&(D91|%C!3|Hw9K2Iyu-Ef)pi@-zIXz2GocAy8iz8c#-){;=w=-# zWJr1+Ge^A%=uX9(y)z!+i() z+cB&zZ8$oI&;P^!tnYkgA+OP;lS?a@Tw2ER2zE3%`2I<(zkai5O&*uv7LE5UTRK~h z%e=#rwBe=%i9jUAm6C8PBo}PcbUV*)w?f1wtZj6mde5mugL7$TPCmBG=MTnW(ue_j zsz4hHWMaV>FN6QKgUCMo>}yvz=_J)fIORBv$GK#BpJsBA23<)nEY!cMv7V1yKZBPX z!lO2Rk+`PZYwXWX`LM42%!lLo{qZa3u<505;@Z+JTz%|o(1#xIO5x+;`sa2YUx_|x z`lk@?^>YpT-eh}Sxk7#2M#e?@-mY0DE$2j^FtL2vUOu8(n!tpz?gGsEit@Ak$YrfN zy`z95Xr$hqzH)ix5zV|DAVZd|6uU`ZxdLq7tS~v5I199+NMUSj+~Lw{wGc%S#>dC7 zd2_wVz7So#dJT<6g7NX&6Z5X3e0Oi!wQ&$qsyS5tfy=G9w#oELZcqK_h+7=RG!VZh z=P{P1r?66Er_|Tqe-|HLzFe8EjQGT{SxQ0+>$pc@d|0x@5wp4E*+xZc5F(bXWm=DH zzP5O9oQ&Qx^tht`vBZ_gWV>Zsn%bRV^AdX@zbe54Qg_)#*i>tTr$7f#=ZLzsI zfo7EJyrpgj=dWME^@W>QKTW3_UthR|G)*x*If?ORZiDsPm!QA(9-`lS3IMQW!$v%E z|1sS9m5We&2DA60(>5+mE-$0eZZq^2A<8snZY^M8W@hNY8mB2{ZY@A-H?~MfQKC@5 zhckS>yTp7p8D!~8S02N3eR%)ak!X_ev$W?l8*5``gR5bsGkecxB0aSR$4Rsm7f0x- zw+uTULrPOB*k}L%AOJ~3K~%IuR-_<_O+9SeZOXE-WEqZ@dc$tX&=u!VuhY4nR+*i5 z(TrlxDVKJB@n?0gen|T22yrNWVLx+amr)c-Uq5D1Mt-?M_jE~G!>e)a3bs7=Cs^6G z59h!9cd@#8SLq1lZ$ky|%jm2x&7fr0#Md{%&)s)q+ftrSMx(WOUW`$lB10EiXVALs z@G!X8;BV2Nbf@UaT6dw5LZJaDAj{glxkD+xLej&}p1Mb4fL6%#3INqRu{S~^9uqu@ zo~aV=CR8L}hA0|Cl57D0G@HQGl)}tRFpHP!Zun6}i9U?<4rVH&8BUn z5%Md3?sWc(KCUttJubWkgO_QQo2e;%?jIcyxwAJRc`%NClWtrxN|qv4h6^>O2AA!%vbk3wBS4DoQTWgjyhwK z2{`i-$t-E7hIZhY!+1ORLHxK>G8j$3K(;8?DE*m?P=K4B`GVv2?+_HT<#hF)zhs+d zRSrK$_CGVf?O>2=8hrsEZMC^i8o<{VY)-yhwtOmS65revJ~sqt#i^hoBpq%qbS1I*ep(+qE_#A=h1lo zUEtD9baw1RckkWMV`Jh78KrV3mpDe^O6v}EFHn-i>x#gLB!2*lOBt&OS+-OxB&T%R zlc(QtsS{E^RK%Z81W*=80NkfdF7i#H^_2!;Hp zD(TOWcc55JjqZ;`YF(t^pZ##}fiw*VqWmNVX{(8=s{?#*mgggW^qhMy+I!!Y!T#6J z*Oux|rnLduRb>uBQfuFPZ+`XWn;IW|G@LyCiHbq^5LMT)KO9|McHN0+j(y9qI8SYC zI*o_?7fmFa$u4szf;oFi!%Rfe(@bkDc9yWAIR%58?I3*8i_qB(=Y&GsT@8k1P= zw$RP^PA3XUlwcwm$3kZr8=DgV6ux!wZCqNpS)`kY6HF%!C;+L>F#q10IK6K_rf1d_ zLG6{+Dq8I}nvDh~$0vaEH)fk|#t-W(K zNk~hrD%oFoo^OB?9ZX&c{0KFBen`Wi? zaJ2v3NMFasMQ(j)$C5f!4|B+g_#_|3V_LF_uz?FV*yXbq5+=KN! zwS73-9{GJd7vs8eXk+K!k+RPU&;!CF{+ z+TANFQX02jk$wrfXr=AJ#91jg009v}H-6vndU6hge86pb3kt}VZQcn^Y2 z-Lcka0C5bY^-nJ^CD(5mh8KFg>Ja&`GPjR!zjNUsZ0z3WaVQOqH0vPCI*3(-M%*lP zg}qyTnx)W4(Tp0EhGv}P3$>7;86_}hRGE=a`p4+ttdPUp`^%4C z#bS3AkxKC9jk5qWHjb^sx6Z$Wv6vPVeQocP*f6#ZuU$KZnPd#dHyuEvVoWAY@h*O2 z*FnrpOd>{#=dWMJAFVE8a_csH@v+B?G=KiR@8ZV70v^8ae%!TZF2DJC0ROqCng8$& z=qFR)_wf{OvzmvHN(#QldGI)%Rc*a3yC!)!ju>y+}5N&h>x#@ z%ie04Mze9W#G{gP$RfE|-`C!L{cHD=D(%bT>;7lucvbp3QueC2u8p~?<*dGE%jZu= zK3B4`jICe)f3dXrE?j%`%V?D>*!InJ$@>ydSI5FeLsflM+DyJKiQc`99VB0S;Wk)4 zpqnkD)x83()80l;QZkBV$Gy{diF2H+hgs;EWlPAiRVX!vIGzR&A&P7aQT@&{-Gc4{ zO2tSL|6JUldV663_{mQ+zVLu>I)6vgM$Z<#S!j$_ax$O3T62@gunA>RvtyC?NHELc%C6b z42sU1b!B`rPxIL$#Uyf{oqH^HjWsL9J^K)hOU@%=UIN*26M2@~v2dHkpHR6PT<6t! z7j^W>osN-n8U;@~^5o~)zx?!$0U$YaNa5XgHE!N4%~g~2XpXTe?*`QX;y@k0pxMvY z7s?B#bwP4SM#VZj&rbuvmXtfpu1hWls|lNF@clFRLGW_I*{B6Ggxx&_O$~T`BKDg? zgLZ0K>cqhe|8w`o?U!EtpZ^tZ?w`iNr;lUT)~yw(`8#r_5<+zA2k+v{4_?5gUw;rs z4%{`6oK?!IktEo&efvPXiN8BJ<9mZjq&D|BpbVEnsjEp&h?P6)E`TQKmFPe6H<>*C z6||ckf-kR&Ewc+hc+Zu)c9Q$Rffdig+n-OD(>>y28)s<@ePElkMSpL`=N8#-#y9d^ z$3X^B{MsUaZbLb@5B5VYu=jygTW-qZYEd_zKX4HW3x%|{D~r7E2g>}JZw%W(kC5zT zlDK2gPyN{FwQ-P$yCEB7`$mAT-nL!mZ`BT-gaSft*=s{S8A6m#rqfKv@-pzo8wz*d zo$nN8&o`%O8eBBpZnx3xc6+-{N5w)hrBv`sX#2S7TqccfH^t)O5;kt!DDs9DS_43m zB(NW8eG{vzt60C@U9@d42sac(3ahIz;+QHwcJWPYJo!_sY&nX>U5B71Hh5dOsvk$u zIMQs%^MyN5U#s=d*~YHvYSA-%Gk(-2eI;IC1m{I(0ub`=>8q+h?Dt zeVT|HD9f!$46~!Q8IxJD$0*t7{8Po;Gsy2`MP2y>H4n=hqMdbpQW=|UemV7I%j(=` z{I}1pm)T@#4{RSIoW@uB@U*r%-;{A@QCY9>A&WQ$q6qLD2rv+h0z2n?>U;Atb-3(7 zWpnfKG3Hy`sGxNhS=L3Q@&(a=Mkno{5hsPL3L2@-0G%OL3aRd*5#>u?I$0NuC_*>u zB3Ah{n1V*5ck02-&LX~k`bYTd2fvI&(Xr6nqdl{972iDnGB!46(A5fmeENC(%HAjN z+@&}1@v_`DZr9`%JhJs(eEsZm`1kL62ANW5L$@BaW@By8fDFDM$0l5Q8VHacH^A|Cp47kNt*T7@rs6v|hI zi+yQHLI^48IY*r?Ha36eqh_->JGMS>cCC(-%xw=seQA%o>OD^p!&qDM8AP7jY#qSQ zhclyzg2Kk4@{c$CB$2ld2ixJ$vdB+0P7C8RUwR6MyXiP)cKNvRkt!J_pOEKQCNob% zeIOHWMPeksjMZbftj$7lIcc;;WAP^T{KX$2OPaX&%x|GRyUmix&&iHPxcA+0S!UBl z<)4K3xVWCjGF=?2#B;)|A*`%*if(!ntDOsIL>yx=iByB_wng`oWJ7VCW-X-I0+dRS z#It~k5jhKjtKV~)EhE-lB*_NPgtSS2d%VJC?=;4CyHkCm_DB^w zvu9Zch{E{NjhI!D^cLhcHGR-(7wG13np5Y_B75}}v8d2T=l1MI8ppWrwKox`#%3qN zW-6Fn@B#BVma(z z-$&84q#F%h&UxijJ?@p~cYiXtw%iwIs_%ciH~%u;zxpzE&g{p-yT4NSr{o{xyxzU` z7M9vK@$k;4aI1X_-~Q+?@T-S@8{hoso4D1!iKlixf$Oas$aEKvY&%})2csouA3>u{ z%!isZr}At2K9}cF3VUaE0sv0kI)|+j8}KW8KUc^csa&$hx7}Z0m$|7;_)iag4hk9K z-g!z*mG3~Rq43y-P1v{dUcCOmr$qg~`b(efm08_Z>OXl5YU`F-?P~j|%~l7`{N-Qa zuRi|_S|dJHBkQ5K{I`iXy5V8jNY~MsBPJJ zk5Pd%{gaJ{c|Wu4+Ki9{ifIq%%KXYw$I6v1RHm>&RNE>Gp&ob%D zVg%KGg)i=|t@c%(mhY$k4?0%L+Ez+KY47=e{uw&z20s4W*RZtrUN1*qeR!;@EWIqX zT>8Q7csS<3x973@H;*fEoNe=wBa8Pj@@o?{j-)Y*IGPBwmXy=?e!5yiD~(7s5l54O zcUa#`xszyYY#i-&8=X$4z}>%~JD)~jwcYrqYe#+Y?^@LABKy5R0j~GI*!}drz33zj z-1pj>!bgsJJ7|-qz}HzuZ2X(`UQzMOMB&Xs?WlK8u{mQ?OY>nCc`80^El<26?L!_w z2C0qdi6Oa%IAH^BWi@*$v3Qk^^wC;i?$Kf7oYqE0U{E>h+DSvn)~!I6DJ(7m^YgEfVRIkYbXSa-M-?&ENV5M zT>Q5`JZS?o<&`WH>ToFxl;u4?APS8QUtq&uf^8G(Lr!0*#N8Lr2;~n4SzL+a+xDk% zpZl&Q4X(d!i|p?a=D9l&?UTWkh5$1G@bJ5r{g}$LIqE88ophnfjEwx1>IU}v|4SfuC8L;x*5cABGSik{oM{*tv0eO!$ifdRAsdB z#E+n^oIDfz40V)=|&Jm3oFx0yjB5o_V2IQe~-kWKM5S|tyE$@+0 zmSOkVb9nEbyUQ2$&5lF;)-mXR^#-tg258jV4aOc@Q89*8&-S_@a(QkH3a=ps>5)v- zitjo`zP9UMo09o`K5ZVByW9tq`d>Tu%zb&!w#lIYIOn<+bf<*{>(@A|xXJAZWj1m3#zLu{Jdi6{2{d+27X_{Pb9 zfzKcKO-whYi*nw*`X-h;i`X@@2XD{6iZAW^Dzpav$c7 z89uY^(@@ZuX|Bg_9()#&GM|3rWlKL%Vaxa|es$kxp;Uz5IrwG7O5uyUAA?-{lIw|v z()gXbK98tZq2HW)5D`*D$Pgn#1Nkmz8VVa44gB|q@5gsO|1>oF$mOAX@5O^hj@DYV zrGD)`sDp=UwKK&7VrXP&uI7`^-}(I0Xpbm}uAzF1d}+L7#S)_7waKH;J&&n{C3K4k zXA@B6h*0h`9Ujrr0+z|=J_{qYGE2bms;%*Dl*sSV{vLAYZCb3I7SH{Y(;TbYt)Y7T zH!C>sHqkw+N=viN{+-53yB|F87N@&3#=z239L(2xE`IXwSuMGgkq__6`!1d@PeZ@V zB510q51aYQ4M|?VPu9cvBn4q6x1_pbbrDzPX6&zm;AVw_ZL_x=>K_s7cp|Y%rUKu14JrDBc8=Xb0V3F2tdl8wu7yS&B>S+;VU%DO!iMG?lw$FaP;jLFH#p%!lctWwB#w0h%E zCD``XEvx@AuK(eWpuhJ)-}x@?*p4)g@!*RuAz#SVhQYaJ5g#oj*FAd+ra1^XlZ7`6 zw(}=>4BPPGwjk@-EXrqg??z7o8D}&9PkZI%oaI~vX%6C}QGCd5=_ej_cJTRI!|@{;l?G0A z7teq2&(Y0VIJWDn*f6=&Nqj#iy^ohEww|V#DN4Jh1Co z*mm}*6C{w*X?Z1K%&p#Z#b`6Vc59NYE?0EL<6dVJ-;uOf~Te17kjp>>9_ zxQQLpyP=?wGT+`{+zhmwn8v8_M0zdPJJFCMojudLv3+tol!}Xc8GslmXsfNBv`Y1s zxtLE)cwHjzMj}ep->eIfLao)^y|$AvNFdXrx62Q`@DgUP-YCj22v0#H?soCicfXGa z8m~O~0B+3A_QiYW`HykrtrO5%714+kNe?+18xw;zXv=XlAsj$rWobE$o*u?KHhg%A z{^v4&?Tg?lmR^D8kNMe9v9%bR_R%D4?Taq>kd*18nN_l4oQ!H$d_GF^XHjni z@{ge9T$$PHlj{N>Dz&e}vAJ?AYEu>d3?sD=ZnSZ?ZA*N8PDvo zK7M=HuWVH^x%@(HoKv#0fFr;EUto3994A{=20jvhmEscpF+MTEz=3!A?XL#GA z_h8$j_w>b^CckM~bm#exai%ecl_3_M86x*LDxf2|%r;cD-BQ~XwVil5?d3D4g8>P< zxB6fW2iuvbi3G+JT9!vsxqGJZub@eCEovzP4knd3c#<1C^Od{3cL41+VvH(ZxJ~0( zI`PtNA<1NGW%Je>r{CcShCsy<$kPRbzUgMoGsiT^9} zhIX@%cESodg5F6TyATRf6K|h<+LI>41Hq>u5FL`zC+TqZxhl+I2U}dA>jTK{J8?lK zw}3QmC`|^fQs0^~$g%`y&Hy`hG%z{Ya01wI93e^k3vCw{7t!f-Ff%iasi~RRsCtI$F;OfvP_LE zR`_UcAG%fVc4i#vmybaI>o=gjat|_C7%!dN)fN{U|HDMIz zz5@2|2X^mPxOx?M?X}^94ff>3@cbkV^R9I1=RZJ#hcy#CEXhaEiPVa(Z!83&zk&2Ll zpRq�vfxfwqx_eCO|dvP@+=#l4~|WZ0eckNfE0UCX5%U7%_kt`G+MGyz6N?6(Npe z@K1yy73Jo>4#iRa*C!dYrnqt)l4fo#;K3Jv3XY>ROdvAGjx!%)+r^8xwP8J8vvx_V zqA1Jo#1DUjiN$4PI^XR%?JeAvi<)S8vqXyYhB%@$JC2Ql{1aMSyOW`E0DyuT~COFu%-PZj#BxQ*LU*YfuF5 zdpBk6nOwVysh>WNG-=}Ful~pAPOSq}D8|71GxcKPYB}dSm5QO%n8WpzS2T_tQ`ol6 zpYLad?9;P;wkbjsjUi2!5l0gP_n|>av2kyYPh%Y;aUF@icjT=TNYXCO&h05LD9wN@ z=YMd|93DIVU@iHyQnhA&dmWzDZKN}U~T>G#ea*<(}%EWdcQ}${&}9d z@&imYH(~qwqs}v4uMg*+M>CnkuGwQAE`BR#WKt@|eLKGbjSSPxO+3=dvgO55D+Qy#By3EcQ;w8ko1%c<{xaV#C$zK&pGVHbx4w)r3Nwlg}ROQs>D2ST#B&S~pVKh{44w zya!6$n_tV1nR9X%X7h#HJffh*b2}juw{){BrSUzxW*aR{ZYwiIRL$J1r$%J`AaGP1c|K{b9KhFrAB$&Va)PQOe%Hae=f zZWv4ZNC9XpT*uZQ{UKVj+i>COzmDY{2cWI_LK`WD;#Gd)Ok}?ZRFaha6E&@ zXtI$7pHL*jyFmb0iIlH(Z7k_8^6aFJynGEB3au=|nZ-*uFtZb<7cZfcnQ7!a$NJ_pCX#X7XfI%H zY7oW{xG|3_k-{9?!TS8=OIU5SuzAA9AZ=Sv5 z=v=}803ZNKL_t&v{n{C*BkK@F3is^m1!8uu2d4Yq0jvy|3`-NsE7*AT8Y?G<)%#C< zfUBD~4ZUbP>2$IE;w6~(>>2_JZc2CBeh#=j2c_2`@`a&HsYDc-b)|4?AVa?r6q|7o zv1=u+HM^FeJ0u%#56;Cb;xJ>4#uxP=6J+9G+ui?z@8fCO$QN3mJU%cdTasVfEp2{P z_w%qxP%MqzMs|4;VAud(i?qIyU2st?tFQk`nSH-aT3hS60Lb^jOh^_V)e9Q8u>B5Di%CAuMnl_A^?Rr zURN9|-EJ#v-VF3}7{&7Po#h@!QB>>z-VbnAS&H$i=du4!|932JKY&{Y??roh60y$e zZ=!NXQ?IwG7+M?K77h;B)}$<~Cqwqg7Ei-Rszo49-FCX?i0yVGvv|GCKY)Q++!!tgztf9Pd0N4Zsd|kz!ze+iE^3xgow8a zw_%@T7av8y*`+e;KWcvc%5Qp&KN!_$l8T2qlL`@`7vlvYgB1|@Bisy$m9YZ5( zKu>1Kbc!fSFdj`6V{fuC1qCx1ObG1GxX*lO~EW9yJS8;1p4?ZxG4}R-X@v)1}@R=80#4E=i!1C1OP&}h7!`Mm--QEsfW;!x& z=L}I-qtR_+OZy5w^~!6t7jBQOws8EVmod4JFW4r&{LdwyZ!htSZvxckyVlnhesA9I ztLIO+1><-5G30cQkg1$#wlQ$t%hF=f*&O>!{gmvWk+l6-9%onwrkE+bk+PX+* za%RN>F#gFC_t;(3C~+D+wXvEHSGn;A-h%Eun?f-n7YA11Z0aFCE#PYJ^702ES3lYE zh3?C~$jOJChOzoK_V&@_$0xDjmG3~S7?+;@9dxHR2r2z<*@vQit!=*(JH6|T)pCSbsIY1OVua0 zj8+Ti`VL9D4KzMJhHkfuZZ}1ejOIh2pCu}rCoykdYurX`?&@vYtvam9?EXB~ZlTfj zoq!gmMkB#QA6w9+ag3Eo^8a3X_#voFVEy$Q$oK4u!9Og{DJ$@y=lnNK9IK)%($;1*e?cEf0pnp?7|m zsJyQdxi#^{3Cbp&>rNDN{)+VqJL*v;_1GA&dv~6)&cf~0&Mka!<@-3i<5@&1#?tCM z)=%sL0L(9*!gA{><~BVnn66Bdul4d?8FX`ea_#@ zSTc?A#4HZBM}WdqbJqKArSGaS*;vQ?2xF(^HU$O+%dx6i|M2@U_B*fY1HL%{cOHtP zov8RkC24msHAJxG*xh$yyjf2_+j8c+Qv*{s7jgK_6G$5g&du${l`UKR3`(fkZsXoJ z-ootsb?8hLi?#VV!KMWaR=l`#`#=lD4W`U(MGPL5FfE*y6c_zYMl^Y3lzM?gapmPx z9M|<7Lw>aH+E^(RS7xtE{s-$?{t@D}7imjO9T$6%Q$(5YIT7tiZ{pUfkc^~_0Cd?0 zSKQXpUff)((ir5Hn&UB!8b(apwQe-kZi+l4R#$Uu53p?ORp7 zdR6sa?Q2(W)%)~1`)Fp!8PcM;jZAv@!;~xvumlJ)1Q>=Pz&{Af5)7NB0UDMC%OFS$ zS6LFNVbAo!?&**E#Z@-Li;XVdFISC{axc=2&!^*aOEMVJ@ zsks~=@?&Z@4gc#)(+%afqA*g}m^TZh^0ai%wvR~qxiZYJ`-;g)DPuqoh|R~~ZkYl= zAj$yr<{{bC3g3TTsaC5aj=S|AsJUk;WpjS@ZxRIvLvsCZB;b(rWqyyeO6@vVdUdBFqg!9drmYh1Pb^zM=_t{;N{YDQwBCl<1uzN!9CC++CF(21HJ!o@aJ~Lb2PMw9tvv@GeFoL!R1_XwNWLJ~WZWX;-T~_P^ zxen>9MrfZm+o<$AG_vYiZ7d>AY8a`Gs{t)z%&y$P#(~WUg?3HRij}o!6>HHlMk*ti zUA+xJVsc;;?yt>axH5>oumU;+UITA4jKns?E-l@`sfBCUH!_X2IKheg*RXwf8(zKn z5vpMom9U(?+pgg)*wi(%r8aDmNO~eDf9#e|X%QX0;D!;sTzp@B!dFSNF0+29Ze9 zNtVVox$QnJSZY6!8sbWYKsOg&HqbVA4AU(_M_f@FyL?-Oa_5yE9lBKFUXNNjMpCb@ zqOll&yUclMW;=0nJ`YISDSdkzxF9#rg!kV!A(MSiT5sel({#?-KqXHF@tS2$I-7?q zknDqjCa<;&(Pw_N;?d=)SpKYZ`QJ6a{rqkY6D0C$`?)Vq>w5Ay$|G+Gb56OoGgy~m zI&J(W5x>)PlF0@d(JYc=4W)3%>IKboqLcErPrm=#SRL&LWP6jVy(F*uL;(DVVRg5?F%^n3q>LeDk}3H4I4^D=Q(o>mZgO6{ zj9LWw$?dj9#fb+WfRGZKZ`?vykJF$p3BA8(Xvp)V8Gema>l3GB@91f0dMh3FZCeTY ztQrk^$vNj93QeT-z2Exhh{LqM$WBODZeit?pl@kAgE<(tsrBSXw`A*;-j=r>l*MD` z?bBLHkB$NlJRor5M6o(*(Gt$y`VkIo{T3EiZz4|WxwUKFm)340N@|&D15v_`4NpQs zqEgD9;7eqT`IW2q=-Qv-;MCXASGMs|zVofWGKK+UAJr=%uy67?43tNW!0vKb#dsQU z?mCZj&4B5E;-n|4DV=Gl5(lOgWXd*Oa=`9@rS_9=KR`?CLxK*u)$&Lqm~?_v0wePa z2$J?4(1-WzMWc-fHIkAFH)`ZQcz+oWex!EqS{NB=n~#lm?qcTB6@-mA4cOMxoPhKQ~?esg=g?G`or zrcJz^&GgjwOuvko&qep{Gv6-S`gfQHYxBuw|L$Nm`liqT{Y&|j)DCTwLhpQ+q`jGT z=j35!Zs@h?4(3-JH~2*cKoj)0$}#Ymrw)+nK_O+L3 zBf8h74AZiZ_imr|%l9g^;@?O9@|q|cFnIc#K|v58N&aR{0E?gk$XNXopUr7nS=27h z{j^9tw-e%P`@1UR{^%$GHE~?2)gb|Fx_uYZm#?N?al)8{Db1}+%#o(70D$x?SxDT% zP$ikxg8tWPn+wy{Ha8)%C69i>(J!|N1k1^1vfBOTuFmTXtq;xyT)%aGowl#rOl#Y_ z@TP^4GVi_IGR?e#rSgx^<7dwzN@6^+{{V(Y@8kTPW7xgvd7QuVI<}5Ig1)kgLBgPn z(f)1e*Potv97BC-A#$}e)b+O=?cbXDjF&w%`T)Y9ch1%^tOfNkIMz-?YHjaQq${PCeBfLW?WZhCR3w$4nHBM_i}c@=xloWYrVjL)BN}tu5O>k^yMq*SD{@Uh1J5`Bg#>sPR;E~y6=|_zL7~1**9;R zO>W<#-a)vU__S?*8!ywGvH+SMk;K8xVe?!sKGW_y)rb3_sh{el`uem-6|7Bfqff8m z-fGh18i$)`*+u|>jkN81KL459x}8bUVpu&Ji`v(IY-;wCEV6y)t*MwsY+XWo^$``} zv`7ub-nj4XH4L9Tif~~Ca}U3Sm2F#_#rrX}zUF^hV`|gR5U|H=Yrg$&T>Pu@x8ZzB z_Lryid+}`j=z9;J?d8+4!g%JZO+qwJkP2a+>Re>}niL?*vdF6Y)1WAdx(>FkR4UCt z>+XZLJE7aRf$P`T&-RzHj_!RU0zw3kG6IBYuV&kvo!8Zx-z+rH9W|l`E?vKlB#{v3 z?qNLaM}J@O#nO2+w_yV3_wL5v)G`3|hW)Fn*na+UQ#S`G?pCuAKc4Pqdvsiz@Xxs%tf4&8-IT0zltt4MR&ys8=eeSK8aPt`tSseDf9_ zI`&bz(wYuH4#3y-a>%HzIc()5;1fqOBTctNeaq#@ea3;cI}shQdvpMH;ykCFxD!@a z!g!MGmuWbg0r4s*n;-nl0W~-Gb-lFHh;}jQHB~+b8o9~cL*a_KOY_|2HrcSt_spHT z^yQ_xvs9KX6K!{buMU^8`=D=%HLFY?bku2t=M7xtoef|*0XA8@@fz*4ZhQJmG(j^r z1>N-7aX1y^41o|sm5d{62V=<0N*4oI(3{!D0g7Ue(v0cL*qukhh-{cos` zYy`0U+3=D$yu9exZ+LOY0Ey!$3L4exVyy9R(zlrTQH9RdQoCtpN=IXeKFf7e}`p2c9s z5z7D&h!C5G^B24d0OhbB2ey1o@zTa*be;^epG^!*r%&{Av)|j(P#iP!e0l_sTomky zZ6)YyTExLiAhgWoBey~PA*6cDQ|)@6Ta8RY=rB1ga}wiPPsHiT=L8a+jE1?z1uVRB z5(6XSKtWv1<-3+wfSP>Xcj^qz?c0;?G|`H-UcZj9dvh3CTE_UjIm8GMqm+gWONiz) zGzAbZj*Z~_zTLRDF}v^D6o(;hZka+Uim>n0X_RX!P@US4hs4_p*Ih|%Yt?oqE%-!E zk-WnC%gZqlJZS|RF9+;5VPMls5H_#%)PLaY5XSMc>Ad7RMjrvLoyU|~hsNuL%L4j% zNFMx7CAuh>+sj2<{nXw*jNF+qo#mR%!sJ7%yhoq?k^{g=b~Sv6>-m0b{qPFF>I|! zPla_&|MRq2+MAC}GvGu0RZ|2~M#k99mVvFXaXz&xmo;6vB2lfX6R3(%sT3kf5;PhS z%H_{jU~*A9bxJyOG*ZS$k_N&8JIH2{+TFQ?ixXayi1E`7}=}N#G(1le%}knHrzZGvw9HrL7Oww8LjB z&vX`2$;w}(o&05*)|+b!nYx2h5D0`a!16M1^{PP7Jatfr5F+CZ%V9sZjUP#`Cr1vX zzlZxa189GquoIdX+|f}!vk%y^t+ijr#LTweoO`fLi`%YG!X4LSgX&Xucq%?71$)MA zDPQli$$n#!LmCIuxzZe=D|yB-Gn%rlvev-%3zrdxAujFQfh4d`!OW&BH*X@^vL$`5hMw=UcKJrBTmsWkfgmr@4PLV8bx1mOSP3O8pbr&eB&B0Ltuo_%+&p#Rt_ zh;Lm&{qe72W!hb+8L58GI}TTIbs z>6~%rUw(b5Q;!aLwp*pMwQ4?9%N0EGz#+(g_+7|Gg6cp&F5S3+dZU5KiQ;n%S#)>P zM%>**j-;`ShX_*=D71k-cxdhxj(pr0k6^Db$&DlxP_l|>SYY_!%$ zSugsw(Kq+xn^M!2gmzCTj{14M#VGrY>~j24lk=uqDf>;@=OO!9Yi#6iw^lk)y{F@? z+`1Lmx>aC)9(e05iAIN;7)D7AfheWmyp?I$iW>16N&O-3!w%LObj9 zfp}V!=zFH|L9V(zqua4(bUR|0Fzj19UIJhqxk?TyomL`2n1;35Um<}2q}n~Y@hNNr zYQnZ=ACo|-5h3boyD6=3(%9DppT~^KfQ91yArbueaOACJ#|)MR`J*PdfAa+^x&&)#d5lqy?!9q}_Wo z`Rv&J+`Mm3ssKO`RFEVq zO%T-{wF|gAouCGQqems4ep;aTi9pRU*aa>Of&l&feOOsp{qzI38x7#Y4^jIUzk_4{ z)xXC4{wE=W5Quscv~BJW_0vEZ4j}f_*34Pdtt0c>FTRAqHg{`1{?LQz@0rV2aNy)A z$OH(Z2%>5KaL`Y|j<#$SAcwcw(M0Fdj&TCO`s@snCCZNGJBBJtmh1*w>hfT0l1-+j z$SI6o%-lR3IhLXiys}tm?-C zrLYfM#~uLyOpPAS;m`agn@0|1rY%DHElNQJGi);4rR=^y6Gp8uN9#W2)4=94UtM~{ z@R7o$w`@uQdpg^di2NBm&+Phaw?3f9vuSY=AEu+uT;Q?&;uS=d5^hdSVQIM7?qB6n z3E{ap$o}^16K!koiRT0XHr~36I0&#fGVHX5O%lN5tveW*zuycG4x7QggxXYH^mJid zO&s6eJlPh%03e0HmF+VMho8TM>grmGk~yZJ-Jb>G^lNCJ2mcyAEDYE^ss&eR-P!gY zcZ%9b-L$tkUNt9$RXW1Lbc8caH0ufGI8A4U0`Q(E5r-iz?A~R(@#L*r7+F|sE_sxx z4%HeJ;8XbIUe?!yruEk#e-p>!ehfhxQD6Hsq93gk(=n~_Sv#c_rFlggZY z?^2Y<>^2y@auP%5K0#a_!Q$Qru(GYyVj~yh*>%}o2HQ8~^Fr7YufAT_-525I3#&D` zv=!DJQ^%0*u}dbtNjKBN6`Qy`^xIgSI=7y}Q5j3?_y~aQ*F5xcl7D#^UfW`d3#GCNZWjUV$)1y4J>e5wpIcAUqu&MjBg(>=Ay}7@1r5rd6Uy z=OC*_OIea{2}siEYehDCuw|Ymj-Rvi54Wq_G;SbpzWgfcZ8r1x>(9%|RG-xE^OB%@3A^O|%USQIp-FvXK1YEo*ar4?Rc5YOgMeS<-?VNgV zF%>VbJ)M}3twe5rGKsgmi)Xm+NU$$w-r=@3??YzTNbCA}?SRQUy%FvAPZkYFYJ5&p zm#>%o3XmT~LLjKe*njdgqEZPrwruIiTyHC~v9soT{O%k?B2j8IAfV=q51c$@oT9~N zD`Nx2(J5T?HJi(3%K`38P9i|k)||3UOG86Ab6_9BIL747+iDY;G(=p#2lryCFQ#!F z?@2!5Hn!WxIwP|u`0LWwT+Slp!t}7(I9Rta$I-su97oS?7)PzIn)XgjjZztB5A8!) zMkv)A7@M6(-)gOCfoab4+_K&lM8fP9s>QXJ+vMN0`?*gnPg2=9!zh8CuPj@kdha?WK6n}O>KWYJ_XKe8DMS9Myk<}0mL0dT ziehS?eIau0cS`&{TuaZDL8iw^|FSVQN5%QxK?%_ewib}m#ararvMt+U8$S4b1m;_= zKdScAnKQuV%_tPKT`rdqw6U=2r-_6pAxUcJ&Nm_uh|lK8>|%2??Ud&mU&VPTN`2KT zo;vat5(1lV-bN6UKb}sV z)L1(KdFr(t%OlrxtLT^(g_iZ6+5p*Px?Q+sMizo1ZLz!75|K!2H1G0XT&lZEL47H+ zbTKbG>-+otlKg3VlFe6-iQZyugos)Y+i^ z@X8M`J^r|{I$BlQzMzmY!JFrP50CHo6%1D0l@z+PdbEt!&-^Z4-2eAc4*NYNxq^iA zb7;#~acJr*;9Fz*_i)sBfoaTV%>1|(b{-z*oy0Qa9 zB`Z_&sDs?}N?Pt@%Ww6pi8bE<(q(A@LMw$OM&}ps?CWpfl`p-NQ(JFHuzyLDpAC2J z;ikI<+oj!w|=P#zvEk+1{gKYiw!0t2W5yS~j9XimWR3Zss1#AbV&&(-+-4xRxg$4`c?_gJ zP7=@uR`DY#XmljaL!q_e)TPoywa(O0G%vEjIFlA2|85mH-EX!sdT_FtKq!PS{*Ox&Br zQ$KkdF$g%)*bP!i5F$YWTArwEGI|>V$9yV6yX*C78C?FG7L2M*K&DWdrpHNsXm0eX zX>!Mt%tBg^gl!`bartCQH?lr@-9tVbcVByy9aL?m;^c2*{$=e;Q_MR603ZNKL_t*C zrY?XdT^=9Po2Rg0WC|BAN}M~#?oT|{lJhL;l_RbFZ`>v>FH{FdtO9mR+xJbI%(M$k zHxds{vo$}x3Fk4(wdGm{=6#!j)H2~55hftiqIWPvQ}XahUxAqmmk}aC-|8AJ?%G)> zaC_(0ZMgl+K}4&ymT7&YWj%oA1Trvr;|@08xMkRyb|2(&G)WiL@X%mY7JsrZK8#Dd zcjDHTsg8KnbaB^Ch(u!hrOT+S)ImE?XpBcTqK!HA9u+oaeLemDWVz<|a3AV%pJmG( zQ#Q%8?d|t4gRo8fY)&}q>ljNTLs%FaP0Ni-AP{~-a5s9Q zo%)NW_48xv;(=>t(Rb=SG%Dj*IdBBE&6_iIp6$1y-+U^A>?Hl0^P|U?@40Z&*|oMy zd6tB(pK8?OLR!z-4SV4}B>@R3l%mk;|2`$`R1gG(Q1D`&hFm}k?2WbwScZtt6Nq; z0*Rz~Y6e+ydZvP`3a!fpxb)=K3t1REjkLx;S=Ah=>-j4}?z&7{x|zYF=6qY8w8^v7 zO&pN-)rBuMK^FW)(nNUt%E*l%uc%)e_U!I~pT{!Q-f0JCI5LWGV zQTnWurd4-?B*Ebik0TKQRtNgAJT!<}fhe;3OG{W>UdHg?U~W1-YFsp?c~;9>`g2^fcs^d5Ha+Fu7p^!Y&pLtPBp| z*pWveq(tf6_fcv@kPsMHUO{!Omc~Dl6`_|uo4@IlDgiwQOYWft)Pw)&F!`m3{{)H^(=c<8P?o?94yZ4XN^Zg{D=OH>C2 zfG>SX;MG?p;ui57wZn}dv(XQVQe0&01u3kqZOGa3*T2~Vr!NUO(T-dt{=XdXJlV{o7 zHB7&OqJ)Wg0({zyp<6#m@5AW9Znay8(!@;bJy;@q>*#=VUwFb4OV|72!RvP5JL`E$;3ucC!Q*P^;g04)|<E@zB+HQ%xUKJm5Tb-QSw$H18NJaoP}>K(+2Gb+R%@fSNZJ2C zrS!@NkUw}G;;UZ;{`Ri{?@)UMK_B9H?Nix_>+?=}?Qbt9w0v~y-d+61*Ir4l|K#N# z;+x<3TbLLf?W{ndM)2IkINtig(|G#Lx0pti2*3d`Ef7?H&B^4Tso}|b(3Vn?j#k=l zMWi+GrCa*1w!?J!w2HdPbThZwi;(OL`wRFrCYNERd?Hy*GO-gKnpJ=I8?D~l++&OoIGNIx zcQ#LAt-lWoElw>EPj3gJV)~Ac6>eME)3kuV>c9Y&ht*`Z{T=ny(83b>R%_tMN0&fY zO-adHTQ=inmjT?m_}sj~vsxA& zLLZ||9wpj03~Ae&{F{6D+3#-a$M$UCPj8~RNN*@oW~cnR^=G5ryi&5TOLnQnQuyl^ z)-#^B@75(u9{myK`X{is|3S#jn{&A{$BM1fv&LOMCN{6_-srnmoLt8|zhnBQ+Ng^jt-%eW@nngPm`?)r70 zzh7c(?57J)3n35$0cy2ca{~CY=U;^tb#99aAs~V>l6awY;vSICz60y`+-6hhi_VM` zqaELQ8o^ULaN@jLxq0cvb(Dh;^26(R^XO50@q6FK!0wr@>Zn&LIQ}r5P?elKg~7!o z3@)yqx}tV`qsd_{XY|Ce>BpvL9AlDan|tWBwE^h)1l#is(4u7WyK{@nl*TT0pi%GI z^RRvw(RgM)TSxeR7pLB0U!Sfi%2yUAuCC0l&sT!3!NlcRGXwctUB3MJ3)o&yjBMs^ z7g=y?z`e`MBy??JW@)4{%cMQ`>_uAn3!wpbWZ8WANwRrk@@;V(3YZ}&+GnSwcVe|) zf)ElC4<7p%0TO)l$V0d~Gu@Jt<7dyH6oz=}!H06w)hlJxD;0!wGw{LOp*cZZ4smmO z3r-$7m|NbqtJkpS%vmKzCC~u;Km)(GvI^~s)VptMZ)FmOsP*@?e3y2pQ7+@{XP&}~ zfAtE=s}XEFnB=xR0Km!0yGheLd+yVJS8{CR$97k6cq>?d1_=TXq8VbdFbg2~r@fV*G#S=@f%7c4IP zWz%nI)JM*4%gUYceB)H=-eK9LmSwkMZU=F$|OFPeV=(?{p}5BT@? zy{$cl?R2gTE=EF#X5!BAw<@O$Dc71OPP@8jZ4HQHpo>EwJ~Ik}08+}X;?zE0q}bCg!^nhEAGaR7acguNoNFDn0jez`NMG`4+HIo4&)P9$-r{liK-8 zrX=e9pz9SLr1Cl|lWRS9yz#~Bl%ps={I|CUpS^qu?;QUazw*s*V_*Py?m2;X-jR6k z+`q%r=wXZx?r`#yO9Oal`sWY^%D_Fe^_yvs_2!X-NOFRy_e{Qka*KfMYAJgcD*aNG zZ~#y3{&kds0_Qd`Y9Caac@+;f%;74Z*C9MZLcup~xVyjHbrw{Awvj~>1b#8Rjeg7-EpZtd@@$u>NDLA*b5;Ox3&B+OpJ zdzJrRh$L-ednL3$!UDJ5UA8qT#TP<5kbxMYInk{D>Amw*NW2aK&`S{P_N5lqKp$)s z6+G#P6B_^kzHdRmp?&4(zi*e~uhVyJrnI4ina}QPt@z64(XO{Owb!fd)UCKIQhM)< zhkQr74+skomLyG>& ze`63h03Zx1s7H%Xfm6LbK1-kI(J94Ag4MOP^!mlepTx*e>s?}7@)ZP_A0NXTFFb3E zhl3|R!Pvd~h#^6MSHo7l?=81F$Sx*e9Hh_PJ!bT>Nxm9ef=;aA0hwgOo6`Wg<^Xz0 zCq3t>%(Q^t*~r1O>0H#$;oQ?{{gR|NojX}gLgT(;MK09yXX456Tj``b@OEL zTdS$b=+9HYc5w~$Y0FEpq)jI~=g5zlZO6GD?_?K{J~z>?=`Q5=IUYABE%M($m!QX= zek(fFCxG6YST7S%(w3wSjr~&kp4%>8!_4I?xIVoNA3oZf9kz&D?uIjieM2Nz8|Xt+ zF5$+uEx53IS8iE*&Yr{6jhiUf8>p_<*zwhTs!?KXpbzyT=V!J-=lASJd98uz3s=&% zCJaX3l6HFr%wAwpwtd)HIuq~myJVmHm;VaoWCD2fG03UxAe%hB?P6nopL(jW($l5@ww7pJ zM-d+V%Hu;>Thr9O`BJ40Hm9_tPhs1)zq%8 z1>L<}QxFJagPKlA2!U#kb!As11Z2|i?$YifGt@!fOaQ5NeU>tU-q};7Pr%1%S}i0X z`64Ai$~qEBJCIwor1!YLOTs)k%0J4uMyA}{LTi_1rlv46r535JtgYcMUU>y~|H%)K ztkf~TeJ{%8GKMC{&|mFMK;Ef?>Qv7|$3MaL3zs2M+mqTs<52acgm0C-N*;9W`KB+a z?OAPM(J{_Q1HcJm+g^RYcY$MRSB`LdIvXW)B00Jkn>{YiSAI9RuZYJp%Xgerp3akJ zHER+J>_-{*xs4UAm$o953wo1?*Z-}VHVb5N#l)R!7Ydg6*p3q9{ldCd3p z+nB^D=S%k$jYJbR>joyjv}a7?Y6=%GY~ z^p{Jrz)WG@H)kqLKb89q?X`P*b5o|T!W{%SQLolA_x1ImUaupLBa{oqYz2Wp5XcVf z*sQVYv&rr8k-lz(eKG3G-u9{lBOfcz&C;g1j0B*)M0S-zVCez`@Z)@+?}7ppH~HvfAA;x z^S&}LSizT{{Q`DvpFtox-*ubQnf?2a1OfJ(IR{9AFi}=qlPsfMR&?}Coc=l%m~oQnIs9x8^d*uExB#V)+3xc^;_prtNG*h zsW;_uA1z=?wHA1cFfcy1Ao9eocUJ@OFN`idJ5^NUNk zd+G{Sk37&a?WuzYvG0>J7@fV(-c`FE0U*ZE!V(@l_Ax#=d5MLWlhOj(FDBx~)0b4iQ5;Q_MOP&5w=Y`nIh& zbo>(op6mB=#|d|J$+T?kQWDJ`z!jovnA2PN%$YoA2epY;o$yPy$Ga*!2?E@=cI-a&z(MRic?KKq%%-cD_4KmZ4^Dw#<*wqp zXcGV?ccg;4+JYkYcmN5SwAPSVUy~Hp?hr-7xb}f!k~_Af5U?l7xqP&BsV)EE+$$on zgjKG4?JJkpN#$fob6fk1v`t(d){i*CvB}q#e#*1LE?>s~X9Bicxo=#Z>@S6*T7Hkp z@?#gD9blqbI3<$SbeAB*$VdI2*OB!O8lllX6~4)4+D(BZm6kUo+a*fP)0X0b_D1`p zYSgDX31hM{s+4g0(Eh?ZVxQZ)2j}+g!M1DHaOn6a2y|3C!bAMuQ@$N@6KJq+`i{T&$82W zhSxN48^8MzXZr_DZnL$d%?qbqIlKL3nDWo$-F)K9$Ma;@VWtyFjEQ4E!lt+WEl&OY z{|SpbcCs@3@0vZate^6*1DShI^XXzdX_f1LA3I-rWCpTn9iuU>&AB^r_{4J7eSMX` zQHQNx&HKb%5xm@*ENm{Skcc2<3?Vw-@hFe3URCuz`e-lxPuWzhR?%ogh@uGP4o-CJ zhWh$ckh(pQETvEW@H@?Z;_c3oeVf=i!OA}dq^zrNYTQkb#LGyMRW#zcbSbM!-++WF z*Y2k>sipM@pgG|zQ3;1RhnaHQFS)n}jmD2(!_rtRH6oN6QQMob0Kh9v=DiZ{Xme{Qy)DVP6k|_2W{AdS4~QzK{~7TEw(7dD8WsqBKPu zGJH&JqJ8Cbz9)S@k{2|8B*C{GB3Vmw7JzL%1!-BjR6U!eC1YlfOUvWWdW|c4rGtsq zgFo(HFfC2HPM;6iEtAOB&V-GGm6|VNb-&p0;}Tb{6nUf8)a^H34~$%tr)&$b*!;4K zih1p%_f7lR>v7sb^ksSzROBP&3y2Z0 zGoE#=TmveOOkbu>m(>&9y1KO?Nh|5E?%MDiWBZV~U%T^Nw#`k!Bo;HgJw&+Jp4#$x<}`{1Rj)STCzSo z>eE;*Z(02G%4Tq-sL7Lb_{`SNHm^nWwkk?ux9Ms3qpP!P0e zU51s??VDMc8rFU3DJNyrsHf9!V0tmAM3OsPrYOf8uz*BbcJU;PNLz4Ss`af3E(7#+j+zW1L3KmT+1 z!`ENN@<07Ey!vx@(D?q(;NY%Z9hYm%}TpCZn$}`iN^}EF3qCKHbkU^KrSH|c` zXnp*%Y+gYo7{4=%L&rbC>4W>RJZSHbnL}US5Aks8N#yzQG1U61>AR8O)9ygkqNDfb zvH#?0)T$K-03!6vpSF9Z2$?QG*Fd$wv#pX{rzhRxpqaNc-?yE+ znF(Oq!P^q25AH*)T6Nw|A2lAALO`k=NrG6bKpMe1&_ai8>5vLq{m*+mH~(pT@sVc2 z08^y5d4y$J@Pw8>Xh|$WxgU1l*a&dC3OhTsOPG*>#wh-zeKD=H3?~ zQ~*rM?uKLzUAZDrtqN?~v_9qgs9LR}UT+`_O9+C_UQ7r9Aq0}dznfQl>@vhh*AedA zgYb#Hz?Ln*Y&TqgIwTOPUX?U}aD8`AGe?pAj9UuD%F=dIE9$FMuzlBdVApm4Kx1hY zZ^w7=&hd{h)IWe-+qPk5s&@f<_eV!@Zr>irAi$agqaDQPFOT%9 z*|ViJ1~?v-Fv~J0tmxYPf@ED#9uxDEm8YxjicKbfk^QFk;iav(}tW9{B&*GHZ)3QJbv_DNXgxe%{MOC?a}}YfJ0(}XYCiOHpNtdEKds$NtgQQE00|)^-hccEW;b-c3Bvuc zQT*h&XYj(yuR@(c6*gOpe`7lCQTKd}oyijgAief&86d5;wb4N9Z&Vzq7Q;H7j=ii2 zNp)pwZCj`NabJEN?eJssLDyNj)y7C>ANKd>ta?*xt5L(DfBAQD<~M&EE87n+dFp?I ztn!F^&Ie6_m{^dH9osMEwmX&4UNBG|DgRPpabeeX&X6PVxfMm^9|3CVlIO z<0T~VVtTrllrf}SbJ7DqAgby_FsqJ4){I@UbuSLX0R*C)-l1mVjp7Ak9G%GSpuO+-pZzTL0F2e=9PjF?rI-gU4-gMOn7Ija_|Y`t^!=L3&B+ zIXP_JHy4|7?Z)+@U5;M|o4!zUj#64>+dd1Oj_l=Q$0Tmv?9EQw>x+|tcE5i&7}>2k zD{$M!r22chnAy%x^Mbr@*tzMexqfsL<(k;p|DH6aUFmAp!h5K_2n4Bo(hGFevltQy zTV_Hf6rp#He~b&)uHxXX-G$QIL>|QipBz4fYt!30S|BThK%-K|o6mj$j~x8~152x^ zd~JvB&d=e;@4Ss52=MI}UP84}Dew-q1kOv#InrOozCbIF09U)-* zLw)!^tG~DAv5B#h2KN2#Kf;|C{xR;pK20prd=ZpNCVx%GG?D zJ~qOsgzJcLwr=7O}*^Eo$(Jva|lbn-ASt7;nRF)uXtH$SzckA($55OO^y|@URJ124DMn3zWHWh2|&Of>deDmug zCGG>-W;)YUqmN4<*f&vZ4<`MKz#YHuy8F$6YnqBKnMRgrT4=|b7Bt!osP|w(y1qo` z*B+V@CU4wE9E4cwuj2OR&6pqe@6>Ma^57IO-8vm7Za$iWMYYRXUlpqZ0{|pe1_z9t z#du3^zi?@M} zGy4_4?sfvi=YYvhYyY)PWvz}R%#bKkjq{*xeV_I{Paw+zXZP%bfW(#U+tH|Gue`fD zGYugnN^ykUXU?Nkj}RFxt5uZhx3mKQ?P#v~;#2;7j}UEut1I8`VA&GI|9!F)T{mi{ zQ`wlUK=LUoU8_D+tdH5H+4;;i%~!P9l+8;X;4Vs8`Aonrt$QXQ*3VpEP4dI+?ff3y z?}l%3{o2lnBD&Ot2kywyztmm*CR|h50LA_~T<5x_>olci8h-oTFY7n`6qNacVUzX2QBdM8}&K#)wM(|uh=)7=7^0`UE_ z<%eAkhpf`GqB%>KardB4*80ikMB(N5skm)dq|Q#u$u6%|S*}#K^V@o^UB`fZ9M^{* zO5C~y#KlgJ&!uji6rI{G{<89Ho%YCq#0<>EoT>dFDynFM!9h=38Ej z$kiOG2kE54Vs#Y*uf2?G zf9p3e|HzAo2ZmePBz}L0=7U>Trq#-Iy`4_;Xr|`@-@f-K(!TDv%;sPHCh1Qy$2Vaj zQr*G><^=m^<6o}nsC`VoGxuH5U7K%xEkp&7bv3Ch{0mWw;^K8ciycw9Tt>ZK$J$yA zeO>J6)G0L@4bn)awmIQ3K1%D+q!BYinzWnSrU&xIxy-%M$fEkR)|Txt8wi z6~}W>nAZPpfl#}1*;Fb`KqfT^5h4r*5r%rRl`x%Pw#kn!6U501qUatfr40}waK1f_ zLq0Z5ye&itLIj9B0p`3`|0FU;XEq*FwZ+X-L$x-In|^oA!}O)A2;v0CA3B^-e{p*L zcm5up6#yzB&i%pbc=MnB0RPv2eII?5Dt_T>U+*e#o73X(F#h_*=kUTSuOV)tPCC;` zpHda1qh2)aLD~EjGL5gpC+U<*wLOny7Ku8!N~Hy~Egpd;2)8LeRX&dTev)pJ+kQ;*)N(y zVZ4#*Um^H{RNbHGJgXvpEti&8S5fQeXiC%0Jn`UR+}t{aMwh#NE)Naj_#+SEz==~B zo?Bq!s2D{T?qT*H{}F<62>F-K00n}!^GKf{{L@AL-c7y;-#_w&@cRK0B;^pR1N}YW z?B0eA_~e0u*ni@5S|5?F-}E@-jaAc*U!Qp>%>$K1b!VqTZo2%s?DTF6_+(06UG3ph zs>PSzd}jL)%^bcbrr%S4H$ShoRpavkxV5T#<)wMd{K5Z#mF)*H`{dVA+cX1&C8ss* zGVN!ArLp}}wgk6*8Fqd!3(&5^_df2sT3Eo#xzE31wj$Z{0<_btS(fRY2F$tz>~AI^ z6{ZoPnlrR?CdcJmkNVzNz--UmyQY9Y?mTE)Q(OwMG(41Ee{kecgmH}BXU}8&-YoN*Yor|jh|@*UfX3Lg zO{qwK102OE3{E}^J^uAMrxYb)dONkG3_xGqALNZ@c?oRYtI5=2MJOM8s(amH@?thh zJCxnjwr-7fhC zM!=3dy1s1-F6`Nbl>)ncO90hc9UJf5MgP(YD0o^K3Hms%tJ`OC1BKhAI1F)a?;gxt zyo_=b!xp*bZ~FS=+Vs0|Xu#)FEA`uo$nezl(zP&tlL`@l@oupG(#~QrI|e#IR4w7^ zj%l3VTRa#{3W1Beb|Q>pY`=IJrL_k5niUBkF?NgN2b|l}W@cNH+B0EgUH|}nlXfIq zH&U>B8Elr-dx`9meno1@21CTB|LxmPEE0#%uWkXprm+fHSqfG7G95i>DvZ?rYR!0d*wtBX6+4y;~SxTi6k|aSK zf6m>qAAErL|9KU`&MAl^J9`$e?e-v>bkKGLhzk6UpPce#3?OOlNERazjda&Dz1x^! zn>EvOD=oFYWQ0VnseF<=FXtm zZhg@#nZT{-W;d-fz_bwTP+v4t*o!^Mx&XKXt;n~??+v}cU1n{)2F1N7&u{tKxXG?B zuWk4f+Vzhpihz#h{up)hZCbZcdu11y{OE*ind_6mS=iW~oOV$)=abt4RDwN;&GRQL zE$1-%O?)+(*kA3PEkK9D>&a$7p$m?T(Y$L1zOFBo5J3ouqs@TrPId~@lmr3hCdP5} z=_l~yTkkY?L~GU)MF^K8}6&5yXG*TR3v?P{;gm($X4?r}dni(B-$6 zPWK<1D=xcj*Q@Odpb6)wT<+?7YFg{-!yC^(iznZF2SJ>qNLXvn07=@z1(Xjc&e)ZM z-l6yHpFOpppBKZDKD^Zpk&ZX(uuIQ#Txavro?g$=uy#G>RI2MYwE4|)KHK-o^S80_ z&3})iv=cXe_BRoYZpyR)ZJDm?w2>sow)VK7H;|rmzI!~czwNWy+vl-$dC_U@b|%Y| zMuo|bZIheUt$polQ}s@2aQ z$Uypg@6SAqVBbc(e)K5h|M5QXm9GI|Z*-#+0!u?fcosl&HvT0 z&H5ZkMI?pvk}S1+i(3HPTd(q{mek9~6!rzkpRVrdQ~{**1tt3xuzo^ciHI;k>waWf z{(e2y3Guh@1!dU*GUqu!GTAK2?)ChuQrUJX>b`9QNaISUq3_PqkhBgUas0U2^ec)o zm@i1Z_FVA~pg%uLVymZ(UdnyIsTC_T;czSuo9fJEF(uNRMK zUz^^iKWT27gj6!wXEA0^H}B`xV&3Z9($S?T4W@8pk|b$5 z+jru_uXNu(PV+GKdiyZbdPEt(nwk%_NXj|@i3=ALN8`;Y+9XN5!PW~4i&$A%P1}i6 zt)|K{>lOy~<>lyL?TV#;OC^6SRuGg>sZ@+0Y!z^wV03gibHR4WbJD`%V!-&42!ehj z$&xxbDi}h(T+Wkgu?of(6^Nh$;rLQr3Dk*Q+-W|W6B-qg;Y4%8TWO3G{fo4dOp&Kv ztgA!Jl|?r?dtb%yB?->$+k?9sH+IGM^Ds^h{sb$dgLviWI{<(u zAAAS{JzBs&H=zba5(Ma9S;dAscQJMS7L*U2Y*)VPwLU#sG*4vJi>uYV5v3t%OI9P7 zO+Kki^33+*s5+<&nt8J$2W?c~-ZhEaIC=W3GxDL7?y;iJ7HDNnnJCBgtI}_7lLGcT z*kzD4!TlxD4ccB_24-h_>5%BItYROw^E$Hla}Bfn5X^jIG=Bn_>X0mlxf_dXyxVn~ zkUJ|(*LRnOG>1Q$0>k+xn!tt=NvNxW;(l{#8e zm!#Sa`^=&JSSu)uFEj&zcU-)L?H4a$U}+U-9?zv)K|td4f&HjwtkUX+YygV%S_jMP zi2>WNcl%Ucd;5B9rv{-dgiOK5L4fT9B=@iV&N|>;q~B5nZ8!SLxHhv5XZG)Fn@<2Z zw|5VOl-PFp8Y-(~FiHq(cQI4Qn$u*qS;B)$+ND-wyHoNxKf0Cc{7dJ9Z$GsMmfN8s zrUTvanIFCqY-fdkbhOv5CIrjYKhpV~4Wi9HX*w)qp|a?CJ}-G>8ZRm**F~mIMR5$A zItBdx??aC6hJ5}dh?#9hl1fGGDt`Mm-BT;w$+_bray-~+C^%mQTi1~!_2y^v^dc!i zM_^fFMye3tM6Mx8Rv=^v8ivug<6|#@23!QCWXhA2bwF|_hrb7MbKWGs3rS0agoR#l zEi94*Tdv>0t*On3GlCHEXz#DQguMW++`Nf_p#iMEa}jU;qgO8Loo(q_A4;VICbQ1`&>)$^S(2axxPhd3WVETt zP1GQuLpQbLm(aU?Q!XywO!D<`Dmz~~wJ(SKGO%;<>CWEZOy1@`m%86koGs&p(fX#F z{lp20+1Z}3-8S_K3-`LOv}6BpH=cRlkGWx__2FjQy<|H)eCWt;z2@7H_EZXmDCjHN zv(ZE~8X1e`csKVOw2@D5iDbJX#c_hAp`o4x_{L#~*$opo`qUFR{NBe1+nhXp;wSL4d{KVL$)@)Tv*lFGBltTz=8yRcp8IrwNLZ-5-27$K}<>duy_7 ze7DRjr06fr#b++|ba~6_os#`(oko@9|4RA%`usU|&c4~3*z&`Fjf>y=XK0LVgv_!1 zTpmnWZl=rnj^-Y)T)LW;uFXGhZyz2uWsdII{JD>J_Z_(}Nm?B6$rI9DdL+?!b3Ia~ zrqdg01PDYKdii4ZgfcHFe?mErI`tp6RfkaT7e(_Zl>%b{K$0{dWrQdK=H>+E<`iVB z)z+MH*4AoRURHkQ+1WYgd8t(LE-ny47!$ft6d{gdl*?uGXUN~Nu~GQiQcq4NNrIJ? z6#x>OHf=-@ga|`dPYEHK_c@;uL4c-@AcB-N08#TuWnZ@`_uhthX*VAF=ChcYnrdB821y~(Q$Rm@m}$Cw3j!1Cmp(DOE+`pZ0@lXX~|iX?Xv|4 z$8~3c_@rca7LCade|tM!t8$2!teHi@p2G9nB)?~z&+3@pkNhEYl9~E~pLM`?Yb{i~ zY`_1YGivvpd=|8O&y;!kw|-*lea=M|ZZ_=;^9^i#lGT>BuU_BdmI?*1>P5|ZZrPnJ zuxm-uMI!4%+|JZx7aXvZX;{AYg$A`DO( zEXI>ezq9Lq$>tAMA8CJ|#a2A|YREFn!p&j9yp zneXUtXWO@6e|xg|xxb0VgxOQgIULgx_19wBQ8u~$0@|32_{e^{A~?I~c$PAPM5O*E z4Ip5PLuA8QIIK3AimW%#WvwBO7XSp!AZ?d!-UJ2)T91x6juD1>p4Oy_XXDEt2)sel z)oKNmN(DnhLq^cHI{i6&1I-{XF?$dMSYBSn;NTzz1_m&P;XMjp$7^+b@Y{ccVERM!RjUxs>;QI-V{*d=Y@gcFRb8_iCV&mV((n+L zhKJCu@G?yeKH&`M2Wa_{)S6JB79on&{xu*5b3V71NdUjw^E84MTE3V(U-8x~D$el?40wfTD#N5O< zK790HL>>d66*J(90xvFg-B8=AJ=D#_H%~58%I@&Yte65~cLKa{xk~g1+R?aye4?eh& z58m3<8O7Sub^Vhpb<47qsL%NDfwwHa^WMkgzqJFz1kE-W=H{BtOOhL`9NTcP>#_N; zTfqOE=XC)u^?!T%n?@3iAf2C#HB;MBy)rGu<&>w@zO%y_i5|Si) zA=Ao=#L9|58~F1xCv~)#KpZECYjxn-Rp9r24~Qa&|Kh8VJEqWRGz_3$sQ~-;12=D) zvq9=u=#YVE<0+D)#&#TIJx|7vGJ=2#icgXi#K{u){;0eh<>Y9j&v-8sqO1bQlNux% z5D-XYy}25{(o9En2SEt|TY#177XgH#j6~K^Yuszuj?x%6aC$Y^cp_Vpw3%e-Bm}}p z;*s}{;pMM>xuc+MO*2zdnEB6s7WaO39f1d z4-R6e!;V|4R`J1Oj{;D;iB)QKNC*rrFQc+nYg&TZdZ4h$#2CBUiY3cK-}9y8R*Jc6 z7%gn%RysZB--)CU?Ep@crPb*B=~Vpdxs)|Q<4alWUUBMPxBJM}V_bWgjtG5^Y-XD; z|D=hH+av_|zBu#qK*mXYg{k{?$fDNe=G9$PqxFV=7t>O|x2=>&`}N&(3qPPByjYhvJ$?%YCx7Ray5oZ0Jf~`|Ee{gGoNE<)W=tE#tFX zI1lc9+peekrpBf+;Q5`0P4mg8p{!(`h+hCUPldspJm#lWOx>Avd|vB`NVBP6gF1~=b1Sy4Vs2|y@W zC1nB$-|1L@lnqFkSnn1gj#rx4(R^>6R)`Yf7^v0Mvp7yrtyYa7>_#I(sZ>U_TE*Dd zh*NhMW(94lXPQc-5*8O1F)%QIVRk$&C*K4#rzA;`Bnc{&3i|u|Gk5IvQ4mOUad^=> zQgc`9LW|AGhU0ybdLwDNEKigGSTDCruzgQjBIxmE;yT*@OO4t}t${69Z=h6bq&ZJK z@IcomZT3|v*u8HTO276q>Aj=-PGa$o-$G-hhI3Et!M4qtv2Xj1uIk~Zn>H$CKmc2= z-ALbDwHx{21b7gx-V-b^b_G*UNV4iFXwyfYx-9$6CSMO!{ex?CB|G$@85%9NRc~7`#klPa zk!Fy%xN9eBebttE+AH7eR|6|6*na79%b@LG(-8W9^$E4HOSL^bpO5Rzbe&_OZpdG+ z-?VAdO|3i?`Su9s#q`yiINJ7Un)oxn zkL%~<`P=9}a}4p^Ebe{b+gLdKjFZ3h+u6QX?xCc=whzi(7!CHD=d;TsPF&qu#3#Vp zhI%zGo74J5F$j9)Bp)c(auJ*gti3& zRgR3nEkhb#rex#9B?YAvO%y5FUp1b%1{MfZzqR-potwvWKo(+LD&hLJt(`PbN)w}_ zm>3-e07R>G)HhEfUaDbjsfHUDFX8@&AK~z>z1aTCy|D%EkB#E~*eC{8Rsf;eW!u&3 z2;&4AUuln}LcxTAn_Isb@qoJJcwT*W4WD-g^ftPxRl{aE=FF%m$&1+2KAlUvxoNXB zJLSmIdBmaXUw2E+o&(b5@G=rBRV!=C=F!CV!fF*8bqlN2?eg;c?%YC5C2Xw*oIfvd z@nR0oZBVzsy>r9LS5|)dcA$oD0-2iAztY*4pSqB_Q<%AnifQ85W~}KxF`Xz`=AN!k z8mSWY4l12%6m#bd8AWMX*wHkMDE001BWNklc-34rG zs`ph9mrDp5S$k}9gO&q))uZE_pmxf7;-9&E5;rgzN& ze?KbHBCTYdFNZ19-0x&MwX=9_&0o=US>K++Pwp-^!wT)XvhLaGIbVUnK^DKJ$)5F` zYZYmvH8rL-ITKGAI=zOrGSz}KQh06VU8;>6J+||Ne}6tXZ99W(L$Mf>G4ug6dA`@NeS<2YV|BJR(i*Agg8#Hys(J!y?ekP{vmMY z4Dc`hB`~o8SX@G*(QtMKUt5!iA~R|-itZx_YRci^InE0}bLTO)eblj3B`CmKX{H@$ z9w+VwdJ7RC5Xx!qa{?yG3gUPXLX=T1jk7Ufr#Jhn03X8=p{S^!a%4GZ@^(k$V?#8p zBHB~icB^U7r$BQEfdm7~D=0?|toHYJ6%4jvYz$xi_E+#16#@C*`~`x)+rVr8?f;28 zdj=tPZ@?4JK7k`oKH72lnso3s0PH(`22B5Xvc)Ec0PX#Ms9xJ1xxz*mCniF>^t zxxTN%v$g9%<=5-PsSF;h4WrHV%4jWbB+ElzjDvPguA?)XirSCsv0qWIWuC1q6p_yG zX(z5t%(k#~qFJI_zAEY5Ikm948|oGp`>A!AdG%&}tM%Zuc$p^h%qD*z0@yuUPTPHf z*XZi&41JcSraq#NvEw!S@?^hBF`C}I88`0S!P(1~|6lgrGgy)=I}iJAW|`+*d+*J3 z_m~}TcXwtMSUbSNa2Z^YK`jJ86oQnf2q_>1AVn}hN@6I23Lzv2iU1e^i2?;m1V}6Z zVi#CHJKpy6boX>md*A)~^?R?MsaI8*S3k0Do^$TKnU!VU%mCEssD4$M*PQFlIp4Vs zd$$+A&Q~Kj8T-oCEp5YgLq11VJ34jYJZA6S#g_FOuw{L*leQ_p{C-i)p6%qF%(q+1 zt|(gZ#pAB^)XLNv`%az0nZ0{+Z~tm6)bRE{`2*l*j^OaUhcI05WbW7RT*v0YNvs`k z7dIAh$>tM35jCG&Ti$-pInkc+ZtKo`^p#IOO`$z+ZHKO%mmin4^QHKC@ndh>%RrdQ zMr$%0PtDbz*>;F|H+1z3#*h67SHJozXiltU@R8^7^GtHnhaO+Noz5 zKF&!yi)@6;>&E_O$KsYgVN!EjAh&7wXg4<+8ap$w6KMqU_EYR*p2fN$G-6sST00YT zNth#yX*u4nE)>&>gQ zZgLXSv+k`Ld6ex#YEL(A-^R$$P+OceJ28Rb`9)Ng>*;7LQr7v!1-$t7TL^*xJ2!9X zXtS41zJBDAkp-(ezPoGXJY;Cz%Xw!$N7QMVmRDAAbLKX}Ai$RO8*&#OHsT2HFU;dl zu3y0B!4a$}PY8-CNt?r)?Xi@H|6QMCu&{u^v!_wIc@r~xAA~w|e-{!`r6rPbPU2v~$bS2Q zhYzfH-0qP1X!zQQrwmp%?TF@6Y;Npvpusl<67IIieabDNv=(%XST_*GOG&;uW+gKt zB}S~9Q0zqJRL-|>bQ~`u)+=a4b1(-!0i_fgr!}Elr(-L3en_cGi@SuUK$p{afvS3B zQ~(tiL1g3X7)lL5sSu@7_9@3>V+!lmWxfUg%+AiCTrQ)UG1M z)Ca0)l*^c2w-&k&JJw5s6+HPr{Zjh-z0;>~{GWdt^QW%h)}0xwo1E%74?{~sLwNt* zBT!nS+-xFjMi`%+LwTi+);9On9K5L!Q#XOYh{I+cd*MH;FyZO49IFY=#{n<^+pR=of{f9yN>ogity6iP zt_>;?881odWju9C-fm`mdYtM~z z-;x?q;+KN$1gvnA^KJ}OtKb!k*>(+K6bD-+x z;myD+OZNVK}6h1pN z2dxBmxwJB;v(U)mpqu9=;WOzruJ@#gV~@k^h1)hs_i;8U`1+irKn+62bs&gg4mFZtY;9#F40&}hh0(Be48%E}7n=H^kW)r2FU*=#!D4J|L%M80tx zp|)H@d}|u&y?24vUIYH&f1bR&lQ`C^)e1@_>D^4Ox{^9q>l%V!7^Tws)`YX4a{IS# zB8nGLDor5_hCEhGF&U{;DLHZ5bEQ}wAhtQR^D{kL_D${z^UDz$Z7y`ssl{X#2`BFY zM0n)o*AODcI}bg88yhy{Zcb}QW5dJv8()0^`05J)fa9nD`G!^-`K zl3n_JTJ&&w|2~}FzYkk4UB-dqCjkwVnoUFq(}mmIK298W1}2+pq3P->l`h<-CEvUb zW40t-!ZDh#HuBF*flF)0gd!Qq&nR;(_I$EsNKqT1JLMXohnd+~T)1|%?V@cTwkk?d9OLAvk{m9>DIC#6cPhFiSp2Aa*J-b$r$xHlpt)Mx;A?kH@{IQwH@U;vFqy@NTETU->#1$mBVyO^>-FWYpUL8KK!jHunJ*$*Es)7>K&sc=b9;wFVTMIH#M%X!A0_wUNO| zQWEotOOm=l>d&LOE`F+*nPAS+&uHb%+nKm=L;CFiisQ3d+S%zeF1TM*^5^43a>#Rb z^@!wyOLaRXuDzv>w_C*ZAxqoAwh-iq((F0+X^_@ME02$B2CyAE%~&?^6$A@1cFUVbAQ_gKBLBTP|E- zGO~Sc<*AQjit{q-Pbag$Jya%t~j~YjBC>rl(-~vV5N}TW#A$0VplpLFM@S zP&0Q?-}eZ@{d=7953P(>JycO>&<>lC|AbZJSWR#V7PyXh^* zTI<56YWt{Csi0o3quGp5?eAq51@i}nhk?cHORu{oWxP9DdjyXUqa;)WKX(%+TQ}Jx zy{|?h+W1^bfMjcQ-12zE>1ZPqM909=a%GJO0Tjx$2JV0J9lZ7ELx@Tt7Kew??Bj;{ zd-v@}@QVRXUpSAG=guW%Y{tOFJHU=fAPg`*GE!(xB#X3Cc=uEH0{{-ae;gAtv(Nx4 z^#-cTE3Jj=fVsb_6)Uw5m8jiheP`IRugS+@A+9TFMGn$5cqrFK zP*w=@onlMhE>AVjBW#n;A03NdcDnX27lUY4x5oFHKN@^^ng8ZG(WIxG8kZ>&S0;9n zQeTgT=+!LF79^deo5e>zphi~Or1D(>E5Rx64E%pTkJ3!#-HVKE*PJljrM>e=#+GKh z22C3T;_!VVb_4KbDIW)MQ!qq~5D~&Yo)7{U(H5t5@^O;9lskC>kiexD>XwR`0X~PI z3#ZI?X|Vf+l}tmo&a*b>dXUSfe?6O5^HWy^6-4Jn(Npkgw&m~jGQ+bdy-eK?fAP` zHxTO;1ggr?aE;pDWNr5p$2D+=X1%UbFd4@&mY0{EI5RVMpp?RrbzH308jFjrBfC*N z>lR$yvKbS1X7Sj|uL1x{NT9z)fUu?8&2kxXEf`xjxlAfftzVKb{DiTj?u=`Jq_T7l zg2CiOc9QwhT zcVY890w{d&L2nDTd!al@&^~TwSh!Ox*FE<0w?WoB(~qSi$*0lzGaH{!SZ+VrdHQ*h zwuBwh*SCFj+=!bvvv30kN7o>11-Q7hfQ9A~0>rp=yM!~BE&%{aVTc`@-D?16=H@Vc z;v)2&MW6$b=}wwtQ+<93XTSL>UVi&c;2U4To_)J9P{}_jg=Az>>tl0wF*ZMs`7z&O z--I@;U5j!l#N=4E-H=6ooJ0ScZ|;cxBvH1UH+_aUIU? zJDackn(Rf-%h4ink*r(kU3Be?k+bh%=+Xz6{>;xg?bD8T?z{BYBu~$`D9txCD=DMfF#blG+ z)~){0QYwW|N}<{G-^}z^lUm~@RscSMcc7%B2ZcWfkaDi3Bt7o zjlm%Gpc`x_HApNi4J6Da@3Uqx6hW6S#W80ca3!qU(XP8_;NJc~*pHeI}mO0AAW z{*Yh6EPChHHS-1V$#XiT+-%&Vo2imIr|l>zeP*Pv^0a}k$4O6Mw(Xvvc^6+wshO>3 z{C0wWQrO1D{H-eu$qxfSY|{2|X{T@JZ9++3rTO3W1N$YnT`MLAjV97#CMEJR(Bl5p zl{z*qf3WKw zG*N1;PDr+Z5pRS(Y~rJ&eF=Gde~oaxlZAovaI~_*W~J})=IUiTZ%!>D((U^}bLlDv35 zx_DUX5ss?5jmzIKUfm@iD!tu2~_yUmQbd$boHRf?s}Pfra| z3ICS%B9KHVr_`{vPL>-@ztd>XMiBkIB+1lMXS{^ zwAQHC8$F-4{c+N!P068QufOiInR_9HAQ*&>SD=F-p&N=2_0=LCw)~T{sWf@zk`jy- zSo3(vc;VqWe+CnhFDqGz#gFzwYjJWC&tSxstchYg^73m4pz+Rw4`60ZavF9NhJ9JU zeR$7a9Nx1R7q4H#w_kb@dS(fW|L_kH{QBpBEo1o1V~=6?)@>;DaJz}2OSK<(Dwj* z-;2rHbUAY^UI5N>c1?2!UcZUdM#AUJ+9@3U)O~%;uRxWNb%Iwh*%~8?YtXt5ts98qDwJv_ z@pRLB3Ud_KyeVs4M-wSE*D`DwQxgI*JNE zu|z3s-|pKgt(=>y<5**0U=Tr|ux8DaxDqNV^zUTyPss|u(7|^B?euGQ`rfG3|+^V(Y9d{0z z^i7K7G}KV7&4t{dVRG>4Ci>rm$&=ka>Q2A;`1%n?K)n6nX-nJ2bmQ4m$8KJd z7uTM%r;oT@VZz*8p2k#l4Ame^LoGCGXhb!vtB#-^M>slr75hdeakI97IBwv?-DynM z7NDRptDCr7PU2Q874M?$n=>=G{?>h=s~Cns`mPpIEn!0F%l3v2*z z?$hV6dE4f;i?)f9THk!-D(ck=<_~2r+P-i9fsXjMCzkA7`7hay5-D|(SAR*SX?kY9 zQMu2;<*^s?*NdzBeEoqCgUeMB4zuu~ zo45UpqZa-|TRoKX<;tRLebr6Rv~?=CFL^%1O%_J9Tiftzcq%QPX-H^8{Q zA-in|(VA4v$vYf%r?ys5!9ZyOK`_)xo3|cE%x-@*;X>5}l!j6PLTj;hFH{UmyRnoC z`nE9nlR{c+L1Zbo4^Q&|{MI+0omz}%V^e0^v$Agf^wMki z)YMKK7~7aWySzM)-#`BriwXSF_T5-{@=09TzAcxJXC8VOrT;3x`)ALf@$TFB?8A?? z;kq;TUm`hUQOMFT4acjZv!=z`n9{>Q>zW7HNJb4zgk35gYBae5i zYq=~o#OGbX-bx+e_F4s<-d$?K8B1B-F>23Eb8_pQ?qbOcNA{6UfAL%rYs6llt({sn ztC^CVxrM`XRxC&JH&h`)l^g?94hDtxG`14iOm=GScVBdZwV! zM1aF@9fMNI+eQ^2>0yX z)3>|;;OdsmXqHQO=(RUMCy}eP%!!5xTK~r_os;~g+oHJ*7ci+v7@Xs5(+cKrRKG1n zK9=OK#IHOo?@8v)EEi*ND*h}>-*sZO@vs3aeRke{jPHAIT8VTHSsS)*I-h@8!`$ap zdiPz8>(_x#=7AI41LV#cu|H~!I(j=*S=u(d+(_Zh z%Pfb0%V)lf&8nNM6gYsk9k5*S+aTI?-Mc{BS1ubc`t(NDBngG*`hk~ALUvhZ?lQ1P z8)+H7GmuOC^t}oYs1jmbPoI&NV%+E^V%>B~r~$;f4y`qs(cJ{bHv>Q^=(qvdA_>L1 zo*@Mkl&T<#<^TlHO$~Dev_hCJwB{6sBcdjGEd;?Z;&>V5@+MC{N%*^Wf%$o)JDz>l z=bEdaM@B}R9nVFt+l}KmJuN#30&&uINA&vZ!1uooeD<@zXFh|X_gxJR0#7`l@Y-t{ z5v%$HI5&F$&Z@P;y}vq!WRPuL0o-m{o3oVKT90DvxcmiAf#-pph*9D74G zV(d750h=#fg+h$G<59g28vpH3F4v=T%ekzJK__Y(=RIj6azCKOi*G|F&(HprtxNs=$){zqv4YPznDva4 z?Duxq?08wv=p8MNx6`6N?cTs3?HEem-Izq9GKs5tKAool_p3*?C2HD{AL- zL((?V;(1p7Hg1+~czfX;w}WIpw!P=CCvEi`7vFOF?&TNplUtv{y1~ix{pH2mxV1cu zXEz?kaH)!)+x`&BXy6C8&S9>;j4y56iLY+lhB6wsx^**-K9IlZ_~5Qx2*2?KOy9Ya z8x8>Kl?qm>Rg_km&`>DX8+h!MSMi8;yu=;8 zi7;1&`D)2uQ~i{cGFMYu(gySCYZrUjJ=@pLCP+ppG`f}#0}vqo?BLn`}~h% z$6rC^&JD~y_*`c1%#sxL1SfBK+n(Wi-914&wtgpR@Y~b^D?C6>e6BC#hHd4UkmLNBS;1nX56R6NyxJ{Q2$50rXna3k9zlO#@1+PBw7?y^HpnJFy+|cCM zIG+FFbNI80g8ub?2dp&l+VB8SYhdg4tx&^>Emta)dfMm=03ROM3#Bv~uVkt7*sjF0<8aC7_PeY(1IcNT@@Z>)pPf68Yl~O$naz)h=bHV0 z|Kv76Z^A&J@DKJq-r6n_BS3`7lEw!GWbBJ?y@@lIF5=McJ$U$Vd;g_oA6IYW(^o$G zEVPbMtrYWX%aN}zyts&`fAAt+dgjU8&D8)3FW5Hus~nXOCE_?OyKj;(lg$EvzhaeS{#WbcRM?9AFnacL%Tl6Fjx2-z4A)3!i^Kxcy=$6>jM-m(O=h+f_ zm5-xj17V!zlHhIC3N26E=H3Uo@tG_$7xPo-B0etSGdqm!>*^he7s*Sh3IGkQ^Kaw( z|EU;#GjtYxX`H+mHWNSvUl8SD@;9E9g z(5NLOV?1XO!W4fioyd~Sm#-p>BOJT$-u~5!QWzc_#Mi&_0`z;I!?)gh9k>6-Z{f91 zT|(oRzufV`Gwo=4?OJ^A`R7n>H1On$FX4?R9>t;ek7IQ9E~2!=LAt2h*fEODL~EEk z4@@Xoe*i%9)g;wJfz>^A(fZ%j9e(R6=@HUbS(GF`%|gDe{`YZg+XDWyvM8Tt`w%i- z6RyRUkF!h|Th5z$)KDm0zYesyCABSeD~$5hTK_Yla$v%ZG%zflWh!36E@Gd z^O^R(ynQ@Mb48l@iCf5Cq-J+5|G+Iuj~=-fuN^yDIK1J^h=xu~n&~@taQfl}JaPX6 z9p%SO&^(H@#;rRu0Dxw**b?7v`(1b;>Vl=s{I88l}v zU&85&7qD(}3J>0sz3b}Y_U(B8_B2kMJ&8bt*gZUse{=N%e0lR>Rvu1nn{zPjk~Gzd zi~|CL^0FSq-c#6YFlsy4ijv)SE`X9b$#$g>e(=vz%E~vtAGqndy;$<5yu90v3&s@i<1j-7MCutbS_x^aqYd-nkXUiUP_t7|!lG-Jkz5~Lb;2uMX)VBZ z7YZv?N;xfsV}LSOF$Ni@QHK^!O1z8XWpQnmO;MD5s@3e?Rw|XCwMGyGg%@eB21P%3 z8_~C41SZCSM;-x&hYQCI0$|*_v_h#0lrk=r?upJ){^U@s8;Es;K!uhLmQqeGR5f~s zq?>{{En1Fzv)k58w*f!{rF2rn#3kVwba1m>7Ch{Ug z)VgJZPb?E$lFNMfMiR1c`0i!0OnKYTgaOIB0;p4$AN&CRu`Vkk|`6?1AyEI5fTq zwto8h_WO{W*B=3Bc*cD;?c2Ts`?l|B8}8zc?TA!}dyXDwrRuep`N{TN^cU3;`4N|m zg=Bbn-a|1Lx|qZexqLK4J(MJoZTWM_7B(X&t$WtT1GO5S{^5)1b-B*?@EGpyVIcr@$vimlW?TF@+o~9=4{%mry zv8TktzQtqyI#y8=BOknpfotb*>$$H9SzBcE$b97+JH9+Q+mCJOdkl9nITq6!+&1vH zgG)Y1;=fkZ-<^`umQK$X#qYA6Ro%x9?~ z+mt*drgeRq&L&$vuBL31HuNWllv2=IqnEYTK@ebY(09{SdkRB9DfE=TpQtDGzt(LZ zPLVuRX8TJ$N!K-ljS-SS$ta`418wd8zeW%8a0e5D6oiTbs<}Xu@N;*1%Ig zco9E*_A_Xf6aP>g1Z@}K<h&pM(p@Giy zxh+3}I8OYneOBzQZS1BWB7$yh&Pm9Xo&KfR{jnA(m3*tRXgD};X;he{|E7PhnV!Ls zqsMUUzTOTc;rZIzN9ATEuxH3=70x}KTAD{BjpY%0TGSUurncEfO-n@yA;c*fNPa0RteqdnyjeaZ-n$fw>CUk97h$QO4CnxHTt~O(X|+;n z{rzZcxsQ?t2M5q-G!aFsb?o9Nhisn^J@@xIAx9PW94f2l+VUlNN{h5@scTDd6P}iI z8{BTTpPI$PiM}JbLo>AI3E}Uc8DssmTX_8L%V<{0c;k_WJFGE3DWxzxGz1I{;n|TV z@Z(=x!L@(+66*i%I4+Kk;q8+rFg84lXFIsbGK(O%(fjYiJ@22u z)btDtLN>BCPS=hY?48V2CoN-U@y!8byseDg5wqvMEw^@W;Ybr8spv{=pT32KfBP=U?qX`SA(7^}qfxZk6g#|AoTi_uXGG zCN0d_cj`1w9oUbB(GhRBN~wfTKlCtOIr?tlw7Vf&oED|5utg_G{7|b16>Ft91-G5i z_~A=uqpg!#B^&}=;qRv+HR6`X#Be86-M;OU z8$Lzi%c(ObWBzaZiMG<$BBTWWeqMBDSUX(%{?6;OeGjtXiQid~&8y!DP;6ZIK_8_c zoh7!bhu(Adk2DPA>0-9~$Y&_EP`BP}L+{OD?$KlPhE0np6nFCgNxTN(~?g zs)Z#b0j*X_DgajPT>p=lzV$7r7hgwd%Vva+e+rErPlZazEW}?;a-DOAY$sh_I~UiP z3PHNi-EP`*=Fd+UPh8`;zSlae-Z z{i0bq-B73Tdcnn=;2^)PSll)=?~2-0#VDJ9-fwLOhhkx6I6pq-mH;gkaq|Lz#l|B3 z&6z(20DNWFmoQ!(PgCOIIX6GG`->Yk7=r7x{Tqv!dCHC`IG9_3g}>TUAv?*R)< zOn>SHtZdzrK6h;oKWWB;EQ38d?K-yQyFIaNCU*F;LF&!iJ_yn!YQ^|9XWzK*c$vt0 zV*=(ZuF)stS!5S~s9nXV}iwfh6Um-qY4InFhtQ z-^on{ykARQPAEdLxP-Du?lnvR%Xvowq>F&kZCh7gmGO#nfx@#Ob^oTmHU z1NY(DCi}Lu?&&9L= zo@{JcG_Sloi&K7nc6*y=O7sDUzF~NB?P(du|5w_EckA<*sE%Os(E8Laa_tMMfq~Kh zhEQQWD51&fcxyv5EuQPeMj0O|e$%nx(2N3e!@_EjyU4K^Ew8NLrFY)OGY>w5N&z2i zR=?{8s|PSX(fpX^#zLa@D7grZHmP%8AlL1@chf@5ptX>bbd*j@qEMo$XMHRs(= zS$;25A``~GCr(;vl!xE@V~;56>GE`LO50yQKHg*;yL5&qH-OKtm~ofbS;ntrmNl9s zqDIS@+A>e2)i3MQ^g^z0Il?LGL$rM>#p3zHku}Dj^b^~ETvVx4P^;AtMZIC|APAs! z{E^*i)gNl#iV6yWsvy>NPgshdg~M$hn+a>nVChxl+L!l9vuHSG(#LF;mK&szh9}P! zVHXoi2`!3r+!_y=!QVjGh%t8OE}}5R{ck2~?*ha)w`Uh-Cnj?1un0|!kK@swd>TvJ zc41;_0;TaWY*{Mf*l+$ZzW-|qpMLP+z8s3Dl}h-r4-MpbMlV^ZaGOlveL+V&#{rr zGfOIyPl{WcQtKtXoLhi?tR}hO+$5u`+q>jNlAXoLqxR_)1>IR;J9*zPRp+Wz-if7& zZX1&}h&Exo#+~(BrfVCllH8KYN#~Vl1s}|uzyoU!B2?6g&)vO_YM`)Vcnb548s3|| zf`PEqI)#CD=T(%(_~0N^n;p(WgM%oq8NtQ5X-wX{fi3GdYU+=D)HiYl7ORqJ1*Y&lBg>1=dCMLH1JuR}yS1_Lt}CtH&(huQHz@ z4c`q(#V^y6N}m48kGm6Eo)634<@IE{{I;VZzrPZ2=4aK?UrJTNdSjB4q2ynAi;IgL zgWl%JD~OI?L%3xtN$4;EOa2|`x%Q&xVxb>a)fN#Hsi9_2Fd_&>juH9YdVd&1}WV(QRcxn+V)hbGj zCU%@X&#V^RsvV@06h_X{@*m?yFp~wQ7UQ(0ZF`2=f=@8muD^u1yi9%*V5boF^6D(d zt}D~IWcB5mtrvV_#fK)O-nHGs*-qJPl5Qe-qIt~Ta(pDQm(8yW=98B1e8WsP*f^Uy z!?8v2u%E|#M@II$UdU$$a>ohp8~(rkaFi}Btdlr7&z1&a#5%?cyFQPx$}spM2r#N-GtqzfUEs;&DlLwb@#p(6;k6~zF0EY`~(r(WKo%NCY2Fz&`re_6+ z5n1-1k2v3`^M+y@ZcM7wa&1k zs~9=|yf^X7hxvOs!pOddQzNDxG>h*;nyx;y@vyB|_?Y(LV%LWz-)9kzAuTR?W8(`W zGh!&%vc|`^tE*gGoW-X<7Sb(fCKY2v*b}Kq)gG!P3kp za}ucRQ@n3*TY~3r-bj5PGJDlVnt|uJ8I8U+^4loco9yh^=7uMe3%3ht0bC-hj1=SN zYwPrxY#(YN8xQ+O9QE1!7Rj=cxSiDr`LvrWA^S&*i@=Y5r1A9A3O!yvkV_xu+;0$I zRmW}%r$$H)YO<_sE4BwWa3 zN^*0GnXC>XO8elklh}Xa6fSSyiZgqA+jI;7VGsfX$rg_zd-oyykG_nz-hLO~dg(=c z{>i6%PM?!j3d=)-_`!3ZNyq;E@4SognYq>mFRE?D&Qvr@`@&Sl0n#5w`kge1Pv_fS zO0pPiN^XNy)-xZjEl$)wcyB_A28H8SWj?qbvpPR>rhGn|~2Ru)f1`cTn4Tq;@*Zol^1wn>_*zJpx3T-oSxnx()4H)LNHH}>7}6(fTkI0Y zWurc>C#3F__>KOjTI5UWC^wQ7KHTZUtFXe#-&vgd$<_ayUs)0vLh|Ov|Gx4`TPy^` z@aqHW&Bpen4Uc?Vm$4pVC!K6PO7HU8#^=qIAG%2=`5mQYHz)aOhN>mPC8SH3glg06 z3CR;F@%UnIQ{xJDKT;|LREStN9q(+nc>ANGTepCb5nxO9S)6^LFbtu!MjU^9fO~Wl z*s}*XbEbc3Dg~&Zf;d`)zhC)@_es<9lnR}>XW4g)rOUWW)A#pnfY7?_FSJLnIrNIJ z=`h<1%t$n|%^W3~14}f^6QKD`lXEiGjR#Ffz}joc0_PABR1{-*co4VOuEos_>kHS1 zk2b7X13bMZ{eAG>gBbX!Wnf|wufBH_@&EHK)HA!V|IvG~wxIpjj%Ft&aBj~oOs`#w zvAKCn&fLM3EnBeb^x3q=jMSy2?}W+$Q^Ts&5@y><(h|w-S$vUw5<|*8^VIGqK9YJ| z%JFW;u#u&)lY7xV?#Id3YUFXf;P$>)%JiY^Qsf;Kp zw%Cn;SMkZ{i6c93G0Hv}B#(~l-Pb-)nuBzQaJVLcOFo%?)jp&vko!&C z5tvQc;8i<4yFWBFGlPjcvuxoNiAVx9S#G6lZhR2Y7us$ga%S=OQo-1O)W@0Yh?C*- z+9J#OA^Q`77K+2)DyLjF??riSPqJLL!Ao`O8$BG5*(1T{tgxSDJ1N|H%qo-Q*!;3X zyQ9N)IZ>Fv`pu1nBrUU_E??isGTSDFk8A@!7By$MgD3^RhRR%(W1bnqo-f3)&!*)Q zd>VZcc;Z^luJh!SsVH+o)YnG+qE9+VFPF<`Hk%zS+HRb>g65lNfE@=AKC}ne zu^yP6TSYEiDx$j+z}tPxDuhrbBgb_RC1IqDqF-_>0Cs;i7N+@au2M?i ztp+U&F_YWoce40UrQGOr^4kUdR@L0FuSq0LF$#aARr>ZvXH&uDyQ| z@BH4k5q{%~*tcUxU-AKf#o=L`*|!JfdIMn;Ve6&KxW0K4)=u9>xz<30pym8CvMWZ^ zS_~Mcqn6HYOeQz!d&{lTYL_Ie8RsUx4fqW4#oFdKeb4W&+4jF3kM|(I)#KAlMaGNI z5!oA&gmf(je%iJP;aZWdm1gS;z_^T7o3e9g*S1;hlpn5>e2U@jZrW2>zoad~tp*d? z#k-WhoDkq2a+pv$(lT+=1BOcj_|neLVX8XTvIA^9%Ezp<{)kuNhMz&m7ZNEzgkN1M zZn-oTmhtB={08)Y`V^jd{uxY;jjakt2X^jE79e#&w2|5-8wC*QRjchR%iVU!1yGiK zU`u76TMv*v4h6GF#w__(ICShdP98pp>9uP+=6=oX+c~8xOq#dHH_p)BiGhpoatB9+ESUmiQCk#YbKXDHOw_RO?Mx0Y`%g4U*1h6E$ z+rv#*zVy(}m)B@}Je>TMS2f2lc4MLo3^%6k1BQANe#}-N+WJh`Ss`F~Np#VUThk|O z3)7TW1tmZ$XzgChDKT}s(X(2J*-vo{EHC@tmCI!WL4aDV_L1_m+LUbc4Wadl*l@nu zRMan?70%WIJUm+CCDL`2P)++MVO&^!m*j_r@h8y*=zNrOjb?mN$>>XB(IRh>n&wHO zd-*Dc*ne;zHg4U7QYl2OUdOk8 z{37E2;k$VDfB6-R@7vsS9$G0Z4bknD$L>9XgU3%|&8_LQp7_aMeESXATxJ0`-!em6 z$c9L8od5tJ07*naR5etZ23UL>f!daVUmv@8E-ziFgY(E2*Ul|@&ri_ia`h5LO^J*YYZKa78nA^IrpNOQMl!wrQnyxnF$|mCE=6p_?tL2F z#mmCWCQaM!wQZ*4yU(s8>1f+T(stI~GH)B%*m`UGCg^vTWtdk^du*C#MSbPxuU^62 zOQ*1Y-8yXg%#lKIB!>#yE?vUK9oyS3+CF{Z0%rgGDAxV_7qITBP8aQH)GHNS-nkWV zn-d!=1KaaW$VH`bZ5+za>@>KN(12OI zNtSlG*1-027okIi3p;lpDpz8&PwGCd zXE+9x=zza<)39ZP`wrmp#BMW*Rg0qnIm^N2j6W5!IPAPQZ(!fEWS@^4o-Y5N*E;n& z!+%z3IV!X5T^q*&KxuIfLnq&XK7Ja_ho8jqJr6-w2R*Xh=F?Xmc?g)XRf!*4(n*~F z!Jk}sW^4%ibZvXlHqDIW=^#7*eB!B@g^HAmvD*Wf!*+}mONcOlvEL2i<|C0~W2EV} zYE!lBA>D*hB_@A(y-WMgCgbH$D0bLWKF-dUie7bPis$+Kf~S+swX#mMvMO>Xl3 zZf~5HSX=5%su$n5C)!I~26w{0Bp zyllhMC+J{>^O^P(#)PXyE4aRR9SREDN4FtRb|}MP%YY2Z*fF-fTY3C z-Z1N(WC^4T&Sze8(_6xwcHBv^QY3WI+Ld8_u*fY1SHQ_T`x>dCrDaUc+`*lx{_I@Z zaP0=x-MEP+%HZHRQT8Rk%AZ3Qz&JaCF8Tq1P-WGVt>z@iF`;Zw%%7W>F5sr{McUB^ z_Of~bcju5>z|GHgF}vmBWys>+t^HZh+h0m{DM#@VR;QKR*7pGo>7MjU5j(6Iy>z~?k%8tqDw1f%L1g-IoWfjl z{d&OCAZNY#L}J-;+;T~qk&(c_k@*E|x_S-Eg9DiD(=OvZ+qPlPFKol*FFy?Z$3MjN zKYR^uRsRBee)Sh{;o4QiZ(PEbr;lJ@O=nl2`lwMUK-s6;ZD$oNKPXC_;N$#y$xp}5r>L#x;)ncr#cZ%*Wb?zV zF(tm|mrb!Y_2FW1xa@{2D)F&vNtmbRu#d9~#$Z#%kl{Temm{seR)RcLXu(i-<2J&N~_9L}A5)?t8KPproi2lrxVp!iKuMmJp9x*1ot zwLgAkY}kKOm6s>0C-}x~5&nv}`MR<9Y#Z4{;#{T^Rv|pdHMr?pK})l63`#xN=_4|KuqI`{IsH6Iplj7WSV05JPttVNTfQCvE#thdYY$dNS!hj=p#s%FVMpp0tVV zT68g{{O$V7eEQJm0poeN<#B&=-=AqeveG!7=cTh{kE}%*$B&DB`vtg@8M9=vt9M-6SC+{C#6Dff#=i87FAL%>oi5scGS(8RbTjQ(efOW}X@ep`j7!Mw*7%G)+CSoiBp* zA5F`~v%{_~#_boWmcRSsJhf|eNI@wDt>eC(z};R`nsA*TXu{)>tdg6Up+YECN_;Y& zJV=9P$v9VoNJ}pvy1Lm+9@9zNT+{L8ALcG98{^26`V`EC#R?i>EyAXY*Dx}FH+fSE z@!oy+LigBUgVibqtI0zBD2j0J{{6t;AI3ZX^k1X?{BEdSQ`oz0J9hTzNW6v75u84- z50|!Y!}=RHvE}j=&^6a|vqO|Fey5sBYQ&%`X_144Au@7YBDQSZY}<+EudRbzT$x4w z{!P8khnutP(`<{-&M}`qu3HibZ~8X%U4GJ~Tq>WPCZ%DcsN{b-ZJW=5_}VR-x{(#x zl%19z0~Za~53J0o*D|~Q3T^}0?_?O;X7k&~)JOO`*TQ#gY0jTpQjUqFm9DH1l#Y+M z&!7`pSX#mdZym?=$q58UHYKMet`hCoycuf;u3!}9!f{CFY1FG_oZjF5u&-*Rf=Alm ze@-_xZotMX*Adn`SwLqj%_8+}OMs%*Ll$NE&5fO4LQ!udd_cWbda?uX6N(>|^QVGZ#5107`|3bpxU5d^uf~ z-=zpH|0pQI{1Jfe4%GmFQmKSSqlsp-_uGd*iKKOeB6eN3__#mBtuI%8Ihfni_xLE_ zPoxgv+QYn)^3a@cZ$3ea6wOSi@u2}U`Uue&$#2r(8%9hy$YL?5h*F-oeFwWVP-?W+ zcPNGHn>O~0zk%e?*@q7wLGwS0aB$adynW(0KD=}hxH5-zrD23W_iUkcjqPZDYz*_Q zLv&6ZJb-f4M9_>eb$bStS{!mJ?y7T8oki#eL=)?`}2}1?~ z7i?rS_~2mD>!zk>usb}9H>V!zx?F}v78X#gt$6s6AR7)(^l|Hl!uo0iqGWQc=`sxPd~`EshvFa$t-E&$!{*`wq>BLta+Jyd_#omMkdRC0L?%$zb8in)x36k zx-?CE{Q8^{{&p!oe*LC0m4Ul$q`Sw~4O!uAz|D6)`^sc<$orIeVw03U9L^KuO{Q}+ z=$dDKeU&^pjCkUUx@BG2CuS=|dIg~hS)Sa~m(s~6Cj(W2R-J*=Jb5X@b=RAV(98^Q z`n1NHHGV#VK%rib&}=pU6kmkZHN`P-`7)ya`;SmvHv#p;6pm{SepY~4#I3CGw%f^o0?k4jDPiP`y`aSakK~ED4%&d?4Og#Y z)77h(S-S=w?%SK>5h%<~PGnbLLE5@uBf_sfi#GHUPcI0$g`f%^a;ojf^o>^O!OFTu!bl68vJA792v5?X<8RskZ=m3(w{9~iji za^HoJ+|4M-xK7}_%hILU^1MCe0c?Nh{Cu*;MUe5FWH~Rl5;}+LKxz@Xt;olL1lz?I zZTHV9SG=CG9r=s@;KSGMYY81#>N?%wF0+)cne5hnBCvG4DsPS zd;I(LVZJPoZ(J;A_Xh3@Xz$OH&n2(2EIyn|-17b`!}?LXP25{!%Su3F@X~4Ma)9RK zq(>gN(>?Ci2GZ+;3hak4wHoJGl~v++N96>Kixa79`z zvE6CWXwXVsT2#FL0d9+O>}_f%P$e|um5jD;uYubm+K-M>ZL7-Ax(=;%-xel++@zF3 zrBXq?-ar_J>7w!?w0*lmy{<7c(^;N*IJBRXwAEl&ZAH?<_+xCTV8Tfm$7Qb^ovvgt zF}dH4Z-yWYY(_1~2U@bqPXIF)(8uZ7`T-&lzp`A%`sG_th@ry(&7g!+2lt~{?$4B5 z7>3xjWh<~{E8?X(-imJF&hP&ai@Uc#|BcULba)uor>8r*1=L4#6XTeh7{~JPAm%2< zFtoUY9p^59&Kx%jvqL6fO}`67JI3HQ4fy0QKSed4xTXYbJV2yajue-_cb{|oD0OT* z&a!eLUhE;#uB0~N@%4AtN{bzxWv59uf5|o?4-rj!YtU)6{1opz>PGHli;wKId>Elv zI6F;$9_?{>I}F|(*><4m!>+yMjwAUF8P+?=DgfdcjUjh5Drn5C%%c*NFj^jDHNd@< zN#DA&vVb56F>T5Smz z@66!FK>otoz1y~9{%cR-!nLcoHhrt(Mcc(J!h{~X_dejizptaT0ghjaQ4~eEF>@OL zux@gyElxji_#TYT-No3tN4GHtKXS zl3ebUgo-@6A=WVty>}e3Qdk-q7JR#W0tb(u#PHpP7J?wGEN`sxAD?8SRNsafh`#_I zgWLz<<4|fT8w)6wx{X7LBNN`n*LJ(aK7mHA_d}`m}NP5ilezSgpHX4A%@Qt-(9R}YR-LZ$LQ^48IB=01zqJTU9U1uP= zH#ux~ahad{*9OWwyadzSSfa4xVC4M!239Euv2l1keq#G)nV7XpZ5yFQOD(VQT}@Kf zuONyrxU`Jrq5SKs>Wv1LYBhvmfYBBp%g=`l(oX3wUVaHnwHm(o^fPUD*}V18gLwQ$ zuV7?uq2qjj_Rz=&b$TH?CF7KF`;0IL84vbzBk+wF3tJBGC{aF9jKSsQw%3#8(ctoO za;@Xd+v)XHW}m3g9$5Dna_owS^d}$oWdl}Y=CLY5Eo$k-@DK0cUDi3 zZzOysh{t7xOxp*#@&U8!qzCdBO>sxHOpBY4CM{a9o1KK^xJk; zD8`YL_qP1^fo3ux_~bMhyh$$pYY+XkL%d4^OqPmzx=u?amy6SNwd58s8ZU%A|2u&d zK`K+^_6Op}80le9Vf9P@lcOZNgr9Uc%}*llhRWp%n$3^simE6Au3ra!`?s-tcNl|z z_XUL8dcUF<0F(koMu59_lXc+r(g`5EBvB)`A-^r!J>{}_0G`6kNOrm!v;0z!rA)F=i!I3czj)vFaOj|?JgLP`N<$5Y@O&b`ez1eZg_tP4g6hbrSqC5|Rlm8TLTYK1~z29wY&<$}r#{4RlCLcT5 zRw}QpBBawgw|9N>O+T~{E3kOTayU?rSID*)K7Q&16RV7V!QXdN(kx8WE-l_8xV`1t zih!IPa4|8r%3ZsNa5Z04AT50RFJRXZE$cDzHgPvDHCJ$I?h@`@vp+4#+4+l@uO}xd zt{)i3&XIMv+gQfQxl1X3k4|pHnT1=}HZX{d)haX;ZqLo*?UN?}0F7o7$IpC-BYXGZ z%;ig1uGO$qTgJ*t9oOe(Fu86D`*-YUQ_HgU{3Y{K7zDUy_wGXJ17-{wo30q0y?hC? zKRgMXox!??_hQ=@@;BuA@Jl|Keqg7w`c?zkoHj-#+{^i)IEq=i^j$gw*~#fl=bPm? zV>9y@pP5AfjpgA%lp4)6Eb)-gn(5n^n3+X0#lm3=Ere|HnNNlVut%P+W$b76xXzL` zHsb{+H>S^D51_@=xOTO4-sdJFg;q6vGeMaoXE7 z+4=O#tKhS|4L=<9aeK{g!%3^2&l?+C&bFtMJ|)M(soArbs*d5{#17b~nfOvTcKZZ| z%ftB8y2C77La*I?A5U#Kf`NfCd@z3mw zy#4Mhu75a;yIP}MDq+YoKltSRpTgk40FLb4hkN(!@3fi`A#5E`)?XT^)lh1f+faOX z#ZS#B!p)nv@TdRpp8^1W_HX?R)~x-g4@Du_-g_#xf6?$ z@#J63a*A3W_CrUHr#$%90MN+c8=U!eP=hu|5*uj@>$i)l>@t&$!)waMfPB2U=#ams z|9!aG#>!d#Q;DTrybbo;r)%Xe?nB~pA~ss({etuD@+QZW?G1CsTfllk7A|thpl8DT zhC{;pwmmBA)bKxa@g#;nd>7MS_}i%MIFR-Z=?CyH9`p0%jv|$EMOL%BaNFL%Om%7U zm);@Mlc~3t(s}1t*dm=s49=CwgR~a6QKT0@i4rO1HB07Q_-Wg;rNgAaB^#G1vJc3z z@E$5rh=#2T^ZJroeqW8*&&mJV4;!omrHa|P%_dN*0ezfqTUAmjK%>z>v)M$s!$rD5 z01OQQOG`iy479Ls_mnJ*P8N_uYoJx<20K}y!Pn}U5lm^-p>-3nUI9=7prLiMb!#|} z)%q6Kth50jMieih884y~kDwF|f#fj67z2AEr6t!ifY~TP7@RMnC5b3Cg>9Getya9} z^V9Nq{#=V{m<7pFe#8i(7!SVoCIV<2ec(Ra*th}B0*BNTp-&yW2cJ544^Hjafp-SJ zgO%TU5q~o9BEo<4d3@#I!x-2&0hE)u_iDA$^MPX@+;ae0DQvoaEvd0)jB2gUq_R1T zOs}=FLxV$aWCe z2AYH((m3VLDcb-iS~oC>&u@QLgfk^1Kp=OqNy>L-a6{4j4WkG_9Oo|BX*8SAwFbg+ z31PLpGUX6QLt*On9X$BvTln!aPvyotfAtD}@an5rGc<;u{mK{H=3^*Cgs8Q^saXo4 zgZ90qQZAzzMNq1L3)yKWGzU0_c;BNdQElQ7pj$Fx&Nc`nxJnG;1Oju{4H?#^1<9Rg zoV&>dO z2@dIOX+dEm7&qjaH?Gik6;Pg>@sVF0O9iQ6m(2yNHelvF!+K}CE86u=l2taqmJpO1 zlJ;~buXA78yj5Mp!hIS7hFENS7Ropj`5nw;grCmQNv+svwSQ z2!f$Lq_@fx$H28~z;FI0aPlNZe&=_RnPrQVN2}%LwQg1t`Kisz$AMV?Wt(Pxj?X78?+r0~qzWf?gGg+))+?HlP zH|=Il0GqL4k~U2o4dzNeWA8|^tte{g_I8`?g!iRu-q`&zOR|~EtT|pNep(;53k;ds z>K0p)ET-uc<2>fO^7-Z@ZmA`4d3xqAoiO%EIb)(IUiH+hHnqk=vw?bCO}VH?5$-N7rs*HpxeE^+I*e+if`z3e06?`|LHzhZ3=a+Az|LKT z>zec2EAHbIMiI7LzJeguX{{HX+&+ErA}+l07I6Fq4vm%CF531{w%wlmO2}?gvME=O zY{|mqs!H{D@|O2p^PWzgH2Q@?1ZiB-D@FaUx!x$lq1_5(dvmgNoLoxGYt6qI+#Ua}oF^`+=H2(43&|VLOV%QlS&L_s6QMVw z{aoyuEr;m6#Aw-k+E$?tnM(9(Qa9YvB14mttT&SnUv{jZF?jhjYTNdrxprfU7kOD- z-6QcBVD}Lhf!j+msV=Bq!3qFAo zq>DRDtp}---<;EC?x3RlXaOCUW73xZ_O3X!$F#mU#U_-YLL@gb+Sh>g2PJ=8R4Rqg zS|g6*zMP!28k8)8cAf&z-goBouqG4&Wj4awY4M)cgsqo=7;#)rpKHtio%9cWsuS1N z3AR)KV%=y>Y?H)RRxdZbh-4O*fM)!WY@rEYzCDVc5JqFmAPKa_Ct+-wyCKgt$sUfA z&B&IV8T6c_wf)S+))6HMUpF_dhgSW$p=#fboxm^b1OQyQc@x*?PvY*e%Xss5{|w%{(($El29oUaBicpRk&>C2O{T52~=Ksgun+DmHTxVim-uvFGS1Ss8 zVJQHGr2%xKf!@*GWH-rSlaeTrmO|1eNgOxQDyki-5l zig1i)vBMgMMl-S`awxG$Hre~W0gY~SV{hz0p|)4=y?fI?@|}Cm$;|tfssg%v1*ZT2 zAOJ~3K~yPHIvv%hx;Jm`dCvJxo;=y<1J^?i^`!+T1fX<`GQ7fkD00Ifo{5{&a+oO{k35*J4&dJ`E$g_y80Wfb86i)j+N!%x42&I z=(Ago6m`-(SI@0Vk{~tGeS~)WfUoU-s?d9mZ`zM1H_a4?SMpJsg*fgU@&9tn%OUpyz?$LUAc}n-0h(K(v91< z@y$Q_7Sg}_4FG`o{4>A`oVJMvmj_z&(S`}0!Al`!_2A@Yiqx%XhQ-#L)cgT*&f+;m z64`)ai;~=N@A-yAmq!Ai)xp9k+J!u4WE3J;-`d1CR57=e0m2xSP))j{SlKfYRqCDy zWdi9mGM$g>^k|h~(-<1_YaG@hY=LhTkYmhzO=D2`g_e(OM>ndzGOeqhe*h)qiDff2 z9B+T$P@;O~jk0d>-F)Bn&}mVgVdUH?jGR4zOMm0PD{|(bTe1iIK9!|}5=A;(`Z|)v z*nTd09!UFy)_dhq1sxJEb~xInEKQ3EL3*&i=b*>Jz~t8X6@mAXb#zkF@;PJ}>F07r z%aQfbLpVF)GGAL?BpzSAtdR96!_3B1VPHB=yYkz+i?J_X2HI_l#~)uCnb@6H-;#QL z2x;1TXUE#Gtg$iR$tQt7`!m~l@Behk&znis=E(CUgzX@2kPeb;Z+?%gjez~43p(5`>dw+l@{_2---+%s<(sc2f3>M+rzH=G&n=b+bIBf$YJaWAF#1ojCnCO}Q z7oYhuEP!MHkROiX+7r#G{>zX8IV6TKJ`mHVv|`YS#BzqT5a1L6luU$9I0K`z^LXO9 z=keSZo*uZ(k3at+hUXU1Le+y2%u4y%2x_wrTaBn6MQG9epnEI^Kn--?%U;n6lF!g( z-r>6#n6~Ph*zZ2cdeQF*G-%MZ&<21oovs_ZM3M3ZmA)TdF2A5MwE;Tp71_TU?E9m` zyi`VK?AKV~wH{P6My98SMmBI58>LD&4YJg5Bl6A zk0Sl81S9o2hJSDY|NOuC=Scq6(-Q@p^TI~}T4uSYbO1*KzA`G|zPTAJ58Wl;C>v7tNx2f@BB{;z5!8FppnW?CKJG`ah^GsUbpE?AuUJ{-xOs5f zK&Wqpd1;*|Oc!EgxtS~tBocG`&inFSk8X%dZZgOm4S=!g5I!??6r|}}Slqv1pVGO2 z9Fw(Cd};gr#pZL03{P&{*>P}o>ul?Wjd=QjBSHBO9lp2teRggRZ$JM!nwM_?$D`dC z?N=jsk%h(jn>VpsA40RXx`R%&W)t_l^B%I!Mkn=AKeT!Mdf->w0qYIhw)IRuH$IN} zu~F3L8-iEnaK>2X3*AbW8uZ;DUt^>h$NH$$Yl)0V!yKL+JLOh1&1H=b7%`AdhGLB6 zV25uXy;9!}PqW7}arEJSt4uCII!u$HXDGp?B0@zHAHaVSrxyn)gdw z74kWa=6!r%y{|(Hh)fNyU!dwH9iYQH`n;)|JdkqDM|PoAf%HF(>SG+Av7=w7+O>2IKOQYGy7Or;$Ht5&sK>**-4uX>9;qohfVw8C4TM0 z_snlB*5A5~YAaJ)*`~w0oy+iqt_65F}HIrq{7c^>NIt(Hrl=L^X5 zB^WdBIb)MkwO@V?L?VS*+l0-RUDPg9_eMH&+6DlFii?6?ytBw{6UJ1KBvtobaut&x zNh;!d{+FB&0B1vKXLmq{|9S4})yL(Q^Ik3W6EPPhAN0R*5yDMT0!wt}DLL3e>aTj< zqNYfoB-az4U9Q`aNXD#){Tw#$SqD;nif|!=amx}o?n86!RW#QMiv&~VxCD?ci$Pi z3|Hi;ceM=BBu7HZ2uZPTyXD!7V&6%vjnhHQrx2%e8+2NopPp%SM+89j9!gIKko3(G zRF*toDbW$7bTgJ>)w(aVi)X6jRjA@+9De{iP&!exriZ>s609PY{NLE7fqVz#%%Z3g3>;KWO z0Kfc;0D$UP|6xw!qu*_2gz~lf?Da85|80v)aQ!|^!Khp61&$->AX$tA$Rh5X<((~- z=REN`KG;>}w5|DYyEy#pV``0^W2hzUdv>$+@iNOm-EV#^IS#3Gj00qUX>H!BGRv?i zje>5Oa=`MWvEff_V^gS%m%=J%O72*kblRynfxMb4|7r0R|zr6yrupk zvEAqgucLbX5^g{FGsVn_je~4wtbcuUNV^VxPf0vY@x}Q`*kZB+=sU`7$NAC6(-b_6 z(#S~LvQ3Vjf9gpz1`OAH;M9lM^YIzbev3g~M9Bv@lD6sSEqSM=E|3n*F?la4f2)t$ zlYAnSpzU1#d>I5=C#HhLRFD;sk9%>!zj#!y*O6rzTCLatFi47Nq@}jD8TocaYg@>ZWiN&GQn3sPtx58k`@-duigm^|VE?c*AEf3xe`w{A z8+TzJC@kZ=lbS#V9h0_m3gwg+>9}sL?)SWR3irJK0TSf6HnjzBJ#Z{CZY!hB>o?%9 zeZ?J;#xp;IKYZ~y-1z%{2>a%zuzxoJ*1&07()G=o@a!{RKyA5+&wb~+faN3Pn!7NE z<6u`Iu^e`Ypc|#g1j?jRR*wJtKtK{d`_H((#!D-ok?%ri%PiAVVs+>KkX9t=SLkM1 zEO>}7-*vvaY{DOF69Ya%<>IE>fcXkYS>C-2FTKHhH}Ks(@4+Zks6x<7<(DbKarNGP z;{)lql1=%C?K0j%VB;D6?WUqprH0_BufDJrCUSB~(ia{(j_m(Eig(YP#@nYpz|ngS z_LcXbw0Fl&Z2xcnQzZXIe+q!Va1AW1N%}f%y%HmW9BW$op7~z*xb#e|D6& zjC+!LR$kaDIk0v};;2L{6XZF5PS38={G1e*_`C}HHl}z{O`LkdMk99!gKJ7^c?NO{ zmGOVc5rq`+92O}^xn}U79SnRELyVXMNfSyJEycEA?O=S{&ofPiVIpPp1Lk|xuZ(Wq z1YUZ{;`s5q3-}iomyqX?&G#EOfNy-m{rv9lx_hM7FrxBmsa$5QMc%YFDgdg;>@rf* z?{!B~7L<>?HYJg6rlo6`L;Pwg>pjmq1}owz7OC2hA*jodx4G=Jvz{}tj$O%QEEF}& z4eovOJ>;q543~Cp$A<^Y5AqE{Ns{3Bv12gCz|8DN^28o||C`^%?f>f=_}Bld#V>sE zOQ`g5!oC|xoo{hu1kZl)3$QRa{=!SBFE%>;#4hV(Hh0_9G8zj-Vqv#<8rw4P$xzny*7}I=>FF9OXOrJPF>jWS26Wq-S3ArHmRSx5#3L zldSlH4NYrJ@%6o0tZAda`}y{ZgJZZc%)9(qoceF0L|oyGR51oGQBK5e~A=kN%dn2-ypoBzBJ1&;35}`m@M~N0Ci#4ES9POUFy1yk))l zFYEmc(1vXH@%QBeM+0-er^q{ZuC-wdFgG!VcON{0<@)NbDvi;xH{ZghE7y^5Y5GHHx;?tw)k# zKqZ|-VnRLI=LsPW;klOOt(r)A_~~E!In4hDe+A$A z&i7#d^cB4SCucDG#a(D`a^rpQ!Ta#glMiETWOcW@ow)aK@%!|-^Vs*{Y1EdQMQ@R_ z4ZuMkVi*{po0;T&B5~5v$&G+?R0aqGWbiE}GVc&m`_J89G=_fA5K0@Xub+1e&zD7{ zB$6>MrM8uIbVC4zj3ZlbiVS(0U~z0TD3`{hw%o)}quIF^fosZJ{gRi^3{O~ zy&K=@{(W!!8q)*I%kNcYcYN1xUxjm0=Am_0sr$$}@VbiWMmnI2bS{YLQK5bp)=AHO zxxy@fYC@VK-L^*S)X&>*uR%4b!9Yi$Op^q)YWLgp-aL5%X`15x1NU@IS55||odFSN zu9eV(uf2iwH*OYMX&JwX*2EapYBgZML)UEGlKdksdHZRloP8_N3uD?O>-jQYmdX5O zSPx(7l5}O9OEQNv6qyg{<$AVuoA2b7%4JDs?L_ft+LhxKrVmHwUhOH+31c6>f22My zbsyF#G}@NO$~0;RLX7F_KfJDa9))Q*ukMx=DR+3Jt@vA`K(-UG6v|Z_-7`5O<;?(+ z6Zt$-&Ou%8uocqzInDu{G>kbxvxM~PLVu5a@EV40T*8g7{f$DOko;HHDAwM?98F11}4sqXX-t|h*q3$~yQ!XCzkVIH+7NEuyjhCZYqeU`F5v72 zH89q9KS?qI6T!Ido2|mp+MhFSjF%c8p;q0Z@pf$dP589nfVLyQOagbanLb1*`8$*R zUCIz6o~cs2=lXjoTPVL!>S%ecC4rP>xyS<`zYq=&!U$eU2;0FwCa3|~(cCxWpQ3{N zWPC@)rpwpy+3$QG&3X+lKmHh2OU4-1QL9ya`7@tI`(GTzYp=hB6U{p~^Q~_J0M?C- z<4aFGx$5$)F=$sR$kG(geeNkd`ob%yFE>~XvLsHy@DrKSERgr!2(i6wAJjAxU zo#)PD_s3^D66-EGZ4U~x-8a4ALGLu704=ZAV0Bro=nNIZ5Kz;za$u~Z1+mJgH=aqs zl4bZI-)}T-I!ePshwsI%sqPWQ$cb`LV({c@+kMvd zdM{JzZM3jd$>8XzhTN17Lk4E?e6G=|8BHxRLgl6-28jiR7MAho3oj!#DqP7ts5_* zbFGGkXcMDa#oojFU}`D8H`~Ci|MK_n?9Nn|(vaB&!8g}d9^+z7U z(YM~lr`xt+?9LpvUb=!X+KP_6jiUE;%-;~Z@aX$`Mo=fg&E-?h$B&N0seSW}{<{3R z*60vPA;0XdLw3(ER)T9)E`Dcifb}G2NY0Rmlv-!z?~NEU(?>l9(bwY~edXWB=Suf{ z%XB?0+v9n5Z)9`*`kmCrxEFi`qxoA{fB#vmJw9n9DeI_F5EE$}a{VM~ zT>Sp@`Eb&1p*b~;d}2dkJ>k4VIUAQt;TY>LH1Z`xPji9SR>%>wYXot@th2Gq4%>~< zI$rwB<7;vyYK-1`;27?I>m5v8x{Nf-3r&RFI7uIOQEI3k*ddgyaMVu5*>c8FZhAdpmUNWsMV^NpI<;oE*BBJdFj>v3dj4)sCiqZUTksNB00q5E5otZ19O*-B$*_tqA*=YC=I zGI{+r9)Ioy00wz#@ch%CL6)Xy)vBxJQ)43|_=T_hH1L(51^|5X=l=mN{GTtQo#i%?VflI5wWSsYNjnFuMV6+hG->as0$XT^WNXP_(*&(* z4Rh?Gl;*qp%vtRH=wsL%s5IN4Sd;)j2huYopQw+@wf?n31Z8?p@BCwFNOs23 zmCMgCKNEST|1K+gB@}Zs;4+N&T zypa(J@4(4CSJHQjjRq<`f;@GjHd0hzap2TPfHAnbb#>9UhZmQSwDSU2Ij$c=YHLHs z-gpaRa|=aJ$7ThU%@L~UU5tn)me2aKZ+wz^YcCt2#@1Y-MtPK0hj!w*3{Z$5)+5Q~ zi$j`dt742J_;v@0IKrsfgz@Ef?*G!=2b~s{^`q2pc)ydentUGOPMu3xi+FZ~dyZ0v zk@khyO!DiEBE95cTtA6)r2a;u7T4gk?N8T_4{T|iAM#9}t4bsckwS*df%=geZ&LJ1 ztp0wzEk-|h1C^yYEFL%tJ36N7>T>{mn6JsgAz3>wb^hFy&g}e%Ia< z(#zt#qxYgQGK~4Lu{Avq-5jc+Im8E7vI_Yf@qDD(F?V&chi-h4(YDDF$Nnq4ngB)$ ztp8i&c@s#6i@w#|iu#M|!W3VDKd$5s6)&r2%gYTcFE69nY^npuM07Ygme=yK&g=U1 z8>mz&SYBR6wHnItJkL?BR+Y20wHB311w+CSa&d7H)oK;P!y~BIhoU+`nkLcu0zkW+ zB26ufsUgc|k)~rvk};HxrF7;lwcDB0-7qDhYnMsNZqGt(R;H3O*O#YZsgxJTs%Ckm zR|kTx<2YQ_LUS1^iN7@kchY>1Lwd@H(UM0wxlTBpgXz$n?ku4-`qx%^3)8k3o?pc9 z;u0Qx=@q>B&;w}oI2bqxjgO83dq?re=25)yPyZMne(Ob;pSu_HpIpTs{i8pF`LCbC z=O2F@BLm((;FC25^J8Op^Wg`O<_@{-K64IRE?)%)YjeFN53>1lm3JCM-o+T{5qAHw z-XFsZoUdO0-L%JkIi~OPO8J%@43~V_e{KPs**k;lTXcXUoY905lpNZ5-D*Oh`d>OZ!cf|LmC}-cq z4vbVB1KV1kz~h_tBSDT@k|47={_Vy0@v~FAFj+})|HOLi9UjJa6X3m@H?d{I20VD^ zFnk&t8Ntl>36=>$5DFkdS5mkzHEl+S^%+1b zNdhH3?lOH$;OTWwUr4YT0@1LJ@;m>Dd`hs+chd7O6b1B_2A3bNx8DZY))0ttj(+{S z0U=h%+(oC-O-H8p`=Ok_ayxt=8{bN+r>^4 zGYdK&DOa}qm#@KcJRmXEj(Tpy55JG`JEPVKr8UB}K{{@;+Y<2&38k6G_=Y+6FG*(x z#Zp!=WTraFBU%Iv$!J?$Zlkt*2g8d?c&PCjY?|P$2ac_YE7cYUL zBbwqGVb*}$|E1Fo8A*K}>jUBLJk5#`VVMw0^_7wj();$83^xD(AOJ~3K~&cy%kztE zf|JY%pZk45e{-}iK55UIoRodOPDJ^#_Cb=j`{w*0_&848zt_54_p zV!Y1%&M&DQ>*qYnwSHs0-}(C(Z;Cl=>sZ0Qo)qeJfIq)OO^beWIgwe@mBu(+BUIYh zUJX5P@DQrMnd0(|8-0J{Yp|p@9ee#vy!*iYxUh5Q!1dUC^%@>}^|b;!Ni!&Eooh|^ zd~gcWpPWYv)kywwGyxwqg~)<24Sj8cJeVY(;b$>2UEj*>V8`zn2a@FW9k)q#XN4qp zI!OkD9M$6DSC-8vMw(k2=cDwL+*e6=XWUHb7z=YRgd2Yl{b@RFki8+bb4th0a<9f# zrC|i&%Qro`zR@|BCbsTlyifKP*I)LhJQyrv%5bS+iy_(~XB^8x!dhXvZhT(rg|c;Y z3{P@N`i5fHaQ!$+t}a(Q$WwrU;WO{UR;nP&if%n=pr~ck$h>`Z;aOQz0W^gTD!HPcaGf;n;7gocfs90sMc%RX>$^^fo2EwNCF$& zlSsWIdD_bLGT)9eIIRSK_a@g9?e=vf$(VOlFko#PdCn)7uU#`RhORs2dAPW^ghr!* z`T63chN7Fp05CE#0%J^P!`C9ubBv6PU~)2U;~gHZ2M*Xo?RFd1T5R6D8DnFk z1K-Yg^e9lT11C=|0_bvT`-em{6O(iV?e-1yYn7KepeBi&jrYVamu)}(w??cqc5`A5 zBaaGkP2?5I?x~EuM^Y;m;gNYCadF={g!4~CEzz-5W`aj0ut>5DpMCcGNRi>CCywLR zhV`qCx-IFa{@}Opr!T&MGnXzR|N7g=|HW&tpM6{^?WK+k{nEvqJ8*I54y?O9i{n3d zv9Ld;))Y?Ke$XKzvM=)Aakn;d#UY)AqATvLXc^hTx&I{^lr508;9i%`>(WNy2MCit5>IPR7Q<57ZWYJQgbg9` zf%wMtbI6l9wYI4FJtO;FS`6|cSB+2QERFxp+y_O;F}pjL%fHEf*7gYZj2+VDtz)GB zaVeVj0uygN2a~t4@X*uIddff$^u4y5m+{7Mj!12ndVvGVuM?=Y@xn?kz;ORXifs#Uym?0y`2{{)g2@3fHCEmvd?*2B3i^q-F-sLgsECaA#L zOw8Qw6!Oa-4q4lRMPx6-T3B%)o7#|NcaY}`uyz?qGU9#G4EB-d=Yb0sOn`Bl%_ipO z=TWIt+|3XkrD+<)#l{#6dp=-GOAXZPL)frkJ<>ET7t=HiFp4n-Y07hNetsT9LqixJ zA4k1DG%()IGT^}nfp_0+V{wt3t=E2TuigUF4WAHxjlEA`OchzaP*j4`#btA-A9D)# zj7!Pkb9K4*%(e5qi!}bGk{FE;r)4|3zG;EbAPVlsJF?o^NM(2KFv=|^uieI>cTONr zn1@`O+JehdQ&=rcj!)p|Gsm&x{(Zo~&6vM-8?U}`9{3;sEuQ~77LPvpDAtXQt-73B z8`c-UXO#-BY~6}=w{AOIWHA@GFMZudOMH43$LTD&^k3b4h?Jqh%T1<~y2b3|B+l;M z9kf;IC%SGL+xPqY)`m$ej*bTTd4;0B*uchX*Rl1|Rq-N0igsahzA(K5=Vo?cZlbr3 z%+km(&hK{kV&?S6y`8q#4j}acnDlplb?65e_XE1Sm0MPJ+^E={4~I88Al1i*HCt><_p5THNrGM5wqyD~{#jtTja|nM59Em6{hhD+`G9UU=B?iK^Vdb3akF^T zXJ+{?-+03p9_3;d%MCxdO(&z2u;I|JmlW4}>rOgyOZV1r#rb1GzY~xmgNy9bFg8c5 zuc(Kpbuxty7GgZZs&pY(4NU-Xv8(HDyf+MB00z~rjryz`Ag_;-x%l;p^TIfw4)ZeJ z)6kh$=3pU>9?~(uZ>3)sStl7~!k-;b-$La`Wym$)s~;Lv$JK0hnD^&{RE7vZr_h_! ze*AcyJ~X&4jE&-xy)#}5y34*K%W>%ald#sG=T0>yQ$PZXc4uRXj2N`GrMrrY4oRC2 z@V2=h*Fo1At6lfJL4!p`FdbZGp}Y5Y1E7;$y9dzP4_)3#+;OA*H8jAsBV`JP`N$!}yk z<$(&~o_tJ7mZmSvqsS3t-lNMKA^M5F=e(TTIJcUPVcDWBDGZWkjty6C!X&`G@4OFV zEKcv=hs9N1&pcGCVb`8%z)_r4FjcLlS@4*>tkmvQgD z)j4k8TJJ#da(xJA_U^&Wjq5RfXAZm1oa=1+$|Gw@AxAmBDDl9U1G6vv3)$pE>z!TOrJ zn2=rRBsNJzoeap?(P3&numNnl^eHNN8*e`JzzTY{KVnYr96Jubdje@Y!`VHd;j4^x zT)2qC@0|d-J_6(F^_qAQ)IxsJ3t zSi3i(?vlTR+K;wA$zEgqM6O&~YrZz`uYCm1fV86*Y910|w_bdgw=N8f>TStMNyBk- zkYmHpIQm%L^>&JKhi8dFxh_71D2Mx-)~U-WDaM~hT03t0_5q()%4pj4GaumQFZ>3Y zGY13y3dHpf-Ifq38&#SWb>`o5$Y{%QHZoSHwMIYEdO_Ue&iZwD{n3Yl-n?6M^6(*? zy5}D3xNrdnPn?1U&_WfoY3w3x%i0ogfBExQ<6WoWr%4ShaeGjVd>+<|r^zy+78=`D zQMqNB+%5y{S=d}-G>hEbMie1yTOI61f9GhoXJJgOAbq=*`0TJo}p5yVq#(fwOY0Gn_hX1jErDuX$d1E!*>s-M~M0Q zN~qu2(yOd+mTN0b?74gABV1bVIu5&gBacD(C9-UhPTGKU^dR(_fMp@AL4ACQ4(if> zjDcCIyKmXKmh5&JB=2(aBNKIUwSM5$H((Or)WLfOb{gzPPe1$!KJ(y1cxU%MynE^t z&izmS6!v$X1J;iq{l{O!FMjFEs1LYD6QeupCh(nSzEJ%A#PctpzR)Q8NXkGd(fw5v zbE@N!VR`6V_BpMdlkeYmFD`B0zUuaMBb%%QImPMR?p-j}B2N;${N!Ue{`>&;KncG~ zNW^g-+THkM-waM47|gzLbK?fQ{KR8;?1h&)Iq|$DJVU=RwpwZM1g1f?^ia1be-}P0 z!@6PFWmq}I&ZK8wblc*Wy;qk zl#0VQFv)!hSzrIK^~$Udz~$@L@X5ssnAy?&pz`hYlen~FJGNfDQnVy5cEVGP-5-0*$w3?W@`01MMVW(M!y&rvyw4Fij6zS0p zk%vZ8al50xl2&K6VjFV&y?e`2U+yfsClb+7L|xXR2{Cgh4TsKhF*nKH&3K71V^}xe zBBl|N4iRBhK2%>?MN+4hn1)femWNPnwZ$7F>KrG^E7Zs2VGfDn{aN7S=U6(qLc8H= zuD8~3*tL)C0KNt%V^@c~&abC$CrA_@ly&qGk>78;TS68cSrR{^__ThGa-O@o4WD@* z>B20U)BDicydBa(n`)qMMCdMibp8F~^wggTcm!D*aE+7VFTWqd-*q^=6gk?p6zBHs z#l`6zckT8npRzQ?h3TEBwA+|D{RyfK7to1DoZ8N|0u${|dKStVG0Mht4h_dJg1%*L4D!1UbQJVr)_F*&&|(u)3x zf|n(USrOJwQ()&#;KYf+%U&JcURj>~l&P?lF)$`Y-U(PH=N@rnDa&LYP-!L4q*}0) zV{a}>CvBsEzyA!CKj*`Ce_tk1t$YoK?c~}5Np%b(avNA|zI09Kqd7(w7Xe^R9JeAAy7wI=nVeCuyV%KAbv32979y#?#w4Xvt{c(x^G@z-adt)rDaUqx>NLUrP;=|H3Yn5W+l^LzwAulHN6~;ubZH!a3SP_QoJ+ttGbhu4mg^TgeV2Ik42=~sZ(VPK!y4X6 z0L@!I(k)ZFxAE6Cs&lT&=akaEq*_qfB^A&3b&eC9{$6va^Bql*_+r_ux%n8X~mmv+p_3s850F};Z z=+!x}t|hhGEi{`c@^?M~zWWN2jT?cV`zrF$F|_CBBk9{gq_ep>cLKZ7SVFTIzgD_? z9c*Fr003(%T{g|j)LmzQfVD8FA~AKC#2FqEq(LM%msjkHBnyM2<1k=QN!JxuOKZJT z^I}&{$UPHNM~)`=n)J}P5}K@I^2KoxmM+o^tW7lRJS-(1=fh6gT$ZMOgp2yNo z_q!ekKQBhhPLrVcx)OU(3AEkBF8?~Vq~^J#Kl}CN{@_04mBVkO{0{4DL~9uhv00o` zQ;v=jB+&iCW_Dle(f#J@J(3qto%LZ2A7^rlHL8tC9{nt$se$pD%PB9mY5_jPOilse zMzP%1FL#L1ZIC^wBZTRh$6xW4z`3dy>1DYnB`F+-Il8l~E9L5bpQ~*_vpxZ&s(l2SX__}e-hTzKrsV&&VpjBJDYfpPoyHWuvz=i3ZuqMGh z@1H7G4!ipMt^hhJm=!%m>pLoOEw>*q$ZQL_^&{ZBIg#Z}@vJizHbbj@3z=<#H-X)^ znOzQgpAIG@9mi=|r!1R?P4Y-&DuXnQ>-WZ_pqq+Zo!c;`f@*a$j2VgIv%=ZH0PnvK zJpQ;ry`HEGwDLSdmSq?l8^!SO${nSRan~rX?ohOI09frUSZhTlsljGT$ZZ?4MT1yE z`a>If29r$brdLbO$1~rb|7<&BJZe-9zTU}vRUfg@2ap}*1%ER|T3WkoE99LOmgT14 z#LOS_;v3d5i1WJCu8z5ou0YyyXnfD9GuV0NJg#ruj1Ld4{(xMqbN%!EM-F4({uyAg zgb9kI{v@^#UdH6u`D76t-TxqIeMDTcVML zMeI6r4()2C;4c8M_3{$ zYc{d-`~~d&=wn!`Z%>MaeSCwD%Xo{NU#g_(T?a|mWh6mZ&&Hcp(5?l@0uH;*>a>%}xw+hi((S1p6(e34(P8wIg z$5<1h0~1p7&{#9%7mU(1M)mQjk6F8uL^51Q-hq``mTx)J+9~N#ejUSE?jKL*?;VVLU zCVQ1eSYrtO$!r_#ya9^@nbrIJl2_)IZ*1YQ$dKDMvV0kN-b6dOQUi+z5#Z<%WdD5=C*MAa4cE3Jy?Pbb-~0raZD92A zz1XvTF#ntw&5w`all?PT9v;Fc`)5$iS~#*ch)R^U6HPcNnw zdmjVb9s-!xpi^rN^P$S^ZjvC?!0$1wtoTqn1jZq_ zmVd`Vo#Y3)PW-O~EUd)P|8<-LIZtICdJ9?CsT_Rz5C`J-Zakh-QjfX%NKOin>Zl`( zIU)c~ImKeo$#(bvmg}XJM_oI=zSKJ!zC+cWR)N2=;xd79WDp&5>dt@!xUkD{*H8A% zpfOx8>D9p~PZFHoucNsvjSgei$7eBqd#>}uMK)mbC#?i>8i=)zA`y^dsGJqy9FgP$ z@N(+4a(h!)Rt2y*;&Gq)%+n<9)N9_tAUL(vY6XA0YnXE^c20;&a__=?@;pbD>F7BN z3k$e$;}%A4T!(%217K_%$%79A+qS{Z&Z5<7b*_!p`P1e$)hEj`EG;!)j8P8VM3qYX z>MQ`LR%@tKfFx>G&dNKW--H&D_WqHKQ*Wh+CLqoonN9?&X)<7#+n&2lk`dY9Y;>(Qf<2OQ^Kk9Wx?vXn9Q^f>D)HT$1m!t<#hK5RWV^ zWrqLEr!wy7KPRjp^Ooii**489!@sg5!NuvF>bh#(USMc>8CyTSf&>O_RJ;|Sx5rxb z8m>-l3G|HfyQbC2=kYspNb?L^KfQwJm4YjvZrC(T+g;x&AFp1RSihI=!nvT=eZZd- zKZ#Q}xh(6%m_W}ae;tH+Zs;7yTW1<8>sv)wC*lKaI*)iwHLhVtWok!KaB5d()^Tah ziaPM7hObll{o19+UO5l@#z(;M$9txglp^b#_fLx+N|B+m+(vD=346Ku- zX%-AGE~3_G7QMz~KvxbsKJN}t@3`Qc!9O^3aG<(M8eUw&=$(0x3%ta0;mkFvUQ*I( z{Vc}O0lFI^GYUBbT|}QXXr);Mnn?dg@`t^ zG|{?qsr+agVcl3O_s!y3H*w#xbFfwAn@&sg*y#vpy1#jpG`{pB0cswhFdX!ee47T3ri`)^j!yWKz}-TXcDTvyjg$D`@XC49 zYN%DKVQFMoS)BYa);c(#ts9Osj}tT3=4j^)%rAe6;@F43*(yq*&09HA#-vD+I;;hf zbXb%Eq?iDVt{vAf5&3tX+YCuEgfv};M3jY2ZZUF)aK-iWw(X*bnJSW`hS)~5q@^Vw zO-+EE*T&fzsMV@yw==ZcZPb2J#p5zpvR{O-G}ab`AM7hNa^eO7aZpw9UUG@^3kX z_5>Oy&XJs;`S7ztf3|aDZ&`gEui*Vg{jcU*abE1tMxN<3Q)F+T=x>hK%JtQDA*$cd z)pMv`yM~1apG0fNp1?+^gHq^VVr;L_)*Ri2(8l9>mxD37-eiZwc!cn>`N1{<9Ux_O zy1;7b<9&N!ti_IV7g1eoik7n+llQ*HP%MqG&sT~W(81VAR_(Mrhn~-!e=VZ#9Cf1l z+ZJH?UXMlGS6)% zqW0=<)>#Wm(*${*qupMe({{C5RkwHjc_F?>aWGBRecR!kCWW<4_?`$pcGi+o&UQcF zm^}3lTC*&YrJ$2mr{m`_*&p%@`j(|2^B%6b%Sj%ThCt7fZ@ILRzq+SvW0yP)umy); zS;`(MZ_Gy!Ch8>N5ywRaxfim#dWu2FsH1@b9c3^-`!I@(Q6D zvv*D*&!ZptXrtqoIqd zQEk=gh8z!RN?`Ls*h{G`wY8j;nFG=MMZ0_xN1hm)+^nss*y#!qO%E2=7 zVK&2h?s2Q0@oWtHQ1`WzZSn&73NqM=!PRYBaq_-H${Fr%(Wl$DVQg+5lecHpb9VmZ z*cI$VK&#V;R-@<*UO~(cH8hAB93aw4eiR|QHV1Qzslg(HwYi80W?gjX=ofhqZ7a7; zSnIBV&hrIb&B)bNtrl?mwn4kCBX%~MO)M-dAW4#FbTZ#DyC^@;1BdD?%dqs(B_tHYPC=Z_(9q{3Mz;ApN`|jC`dSosSO08-Y?;p7r0AP$ot>HG=YfH|+LflTvb*3Dw z9}tCl81q9Z8GI)oqA;RxIr;OmF-Pe@z@$`S5llj(p^rC&Ck1UEwJ&* zb#?HB&AO>f6X2ltoeMKm`tjt>tWKqYHq)9pLaG=pHmwUn~u<(A=D{hsr2 z&-4aDn2*#IL%iAxgU9O=%2tgS=sQ^l$%9N#?~qT)`L5$ykpp$P)3($@WlQ9Ci7Cwe z6cw4GSP{n2`BNRzpgb$m_PHLnPXJ3Rcb1VxSicWjLsfjbT}LF8<7EMCxN!^HFI-Z# z0_N^U^tMH{(Zu!(7h#RTse>zvxa}hZf2PTHPz*PT&GeVHc*@_(gS0YVXHnn-o!lES z{m|#fRCkU4Lfq&hJ&h@elAg4*z z?}6BljCRO%mdG&1U;QznI?Kazv`N9a@b;ygv;3RChUjPbqqku;ZG;&e2^?->qa4Z= z6eU^k5kD(tG=I$&Aa>T~1FX>jGn20X9mQ# zQ27+~P3q3sy5n>W&Z!HR`twamlEPYd82U#^Q&YggLW;9z)6T72{ZmYCm8TtCpY?N& z;TDNI>F;9pTkEa~2hS&?(#eBR%%8Pv^>MJ2vM9dP^^)?H>%-EBUA!0vYxxnAImEf7 zK0^OW%M)!RCq=##;nC$rdL!VRw>LCypnbav)6QWGaN@qhtBTS}RI668bLV#0o!jx* z^P7?7n}L0saN%D)hY#OA4;&92)>?tWv5?tTB3GW@b5BpA>Ms=wPUt11!MSgy_s8`+pU%d<{zK6Ve$_2X>LVlHT9d4%Mtzk+Tg4U+{a1I4K{t zCEl2IzJ$o194+Z^oyO_C4=%>&5F)VE&6fuRk+uk`gvKpKO(lG~L^aNT(f>yFRO z;r=(?#`v9ikmgEJpgG!hiZ&QE9De70q{#8sL&tDw`}QEuUX-ONZcnVk=$!?x?v8w& zo^ck3)Uwd{i+X}`kO)raEuFx8tAnQa8y^V`LZBf zvQPZAs&`@KS8j)a`3MED;#;hkU+~z5Jc@FRN3E9FA0S>BC#fC!eln)01J?~jO8(oe zX}QJ#i}m0611wJ+!t(UJ0Z$FbA#U4%7@x4_oLbg1SN%zN+wJE|%~r|^?g#1Uuk~01 zAgfd`KfXE#wY8wr`}bjJX&F1tUJzrU`53Jlwp3|^LhbW$Eo|9yoz26-qE_8fJP&bo$Yp}(risk@DSmX6BnH;nHNnT#YPIwxigf+sZD+6PZ?DqF-0?ca>Kd0oTJ}qcsL6o(Noz-QIsv)@DitGGL@-kQ^)usZ#N=}-)o0d1Xcc^>6}+?0IZ3s{%cwSSWJ@S&_$SHmA) zAqthbvdxLKP^|s*u^MXlCQBulBm0O?FZ#~oamDd&6Dy?&+5l3U;l8)tMT#6J?mLW2 zJGP@)>+QHberFDqb{o6ToW<5lm(fNA87f8lEi5uraPa*PFgHGq<;|;i=rPt}^44u2 zr*>%dF`N-HorFh5jicEmAU*m))R?d4I$Y~EiW2Q!K!m! zr1RGi)m5)(y~-HcNwLjvjn8FE*dkSf*fle3ppbnc$1FyEq&=(p!;E)_`YX z*e8;=`u!^bGdnu?qg}=abo<0pasN_mMQ8kM)a!Wn*pZTY-5qL- z)X^BNV`zb|3uMEt?*J;tNpm&HCFr@9@XkD^;l&`7cXG%a&_q_`ZLNVc75ZCpyN%`LCWeM; zs72&pyi8Rsg0DrVJ0M_}(4K@UOeV8qul&52ZTM|hx z*C5w}TzlBG#WI-Nz!6MX3c4A~(%pe*ZR}-WpA>b>J2E8^@_qBAYuI|}N}*#m>qB_s z;Ri80xo%AkpKM;g0be}+1Qr`h__JC9`;VT*OE0|!T$#s)nQd6NeIrKdYZIyK{rjBr z_JLC$V&}OF$V`eXNl|UKFgHF1r(bKQ{~Ydm)p}#OYu>(OSRSfjX><%uYw4|<>-nRf z$>-NMZ^B0hdOJYhZJHk&!y6Ajh&0Ra;45!n-ObxbbB@B4qK$UFg3Hs}`f}JNS{NI} zyGM`Up?BT`ZtHi0;G6i&?1nK{f{nxcLhj+`E6v8f&J)MX-Egcfvs?d^I|xax8tOV_ z^$+z$K1`eyntd2SEceoBJRLhYQH~*)`_sWQBg&Cw%FXEWyLMt}WLVXGaisUbBeP>2 zOugMR9oJjW2JQ1V6{dITQ6T( zvD3EWUGiuPV+oc_@+w+wz3|<-*s38NX&E_(crDZiDA(>OdhrUa?aKObzVt2+zLQ33 zA9wgx9Ig@PfXEyF5Gt3(IZMB@#7a_oqg-ek zgmf`FBA{EZoq7^jw3kz4W0Nq|if0q_o#ev^VLU&%9<;8seTM#~Jm{cI+=ij&03iF= zh;=kSHj0}YHw5GS!=$C*VO-s^1$#dH1hj1qP;7mD5QEm0RewtaL4Cog5>r8~G7i%@ zP$Z=rAf;<$qnUc!R9(a^n9fZ`z6McFKA&6-N$kH`N>dkMyVYvrCm{gu#00QmLxQts zlg?r8A11{uEgB7KSrB4gomZhzb#5Aiz(d-;Q|`D;<>)$vdbM0nDDvSp`IZ-Hzh()n z@vr+@Z!Xh;XXZn+ONnnt)a!g&gj06^~w2Hjq%DcR63bX50 z=M-%K?3+t5q}5TLB)GV92P*A0D(&{F zBYR2ubo(~!I(-(krDZYSb0L}aY8wP6yYwrk{;{(DJ1jHQCBkns?$)|?m`{0G-TKI{ zM~LWIo7Q!e{6$J~Sx+6kHPr2-9umjSE?q_3BIUP7>l1V<5bYz#DA^JV>N}zy-Ii$UU+CzF8@jzblmBu{AUj8;(yZ57! z-;WI2f_llr<7wn21wBG%tE6jkcp3oq@7jg^f9pTQ)h9o|H-6zC;@{-oz{v0X63plj zo_yc|Y~8pK)k+oBH7f5fX_aJvX5H~Xo2;IfmyYTnV0+MNgo<*%<%S?Q%tM3dc=`}n zhk!n$?n+UtCMNpEX9lbs_=+afJ5rp()5h|ow2UH_K{F~}L5bI&wnV8FRI+22E{)s- zX9ZI`igTaE`=pFU>h*z7i%6wAFW5ATi9_$51T1iIdIwsaywfa0z0nBry7!&;umI6~vHmti4zaQ5 zr6gMMJ(UqEpe(EY36bDayfNG-!(~(WoQyIwo z!u==LmF&T|Y-Y;xWp{uaoZruVNe%L_zvNoGd z7?YqZrwuu)_bT7H!o~#KwVM#ti8`o0H(mb8>AcHq)0DQzp zYAiCY2s+N)(m9B0;apj&jTRn$=~cY^aq95FRoC^;J7sB#S08@_$6t5}>u$}$>O*KJfiGOb+jcX;{eeyXTI9Gh`MboF7Da^Bo=4)?7`yb4^JPX zo=;Sra?Ea6hckQk;L22gvi#1(1U}g}gCx%}b?MX2)2xsQxG7 zm1VL9KrNT$$DVR+xpo=_X)Qr>5^}0%oF;GFvZ}RY#gW*D>n?G7h%I#=F~10->PzgV z?MN~Hqen|S2}!zi9FJy5G6#&c;zE1j!feOw=#b-XH>b92O5vcGVIFu4iN^GDAsJ)dKi zp58RKuz<6lUQ*BY@7j&a*RNr|vvap;ay_OtZ5k+F>az^muHaj-Vwiy`v>X|@2w=I* zkQ(lhza$_@$Z7jWe@(J6E{fRF(o%5K){hUxC8xD*XE!kYsCm|A* zHY6$S_)GU(Y7r7iGiT>RL^^zhJWwIOi62Sg=aP?0u1vQTCLX_+hX7?8=}3n>-XX7a zw%B>*LLu{pmKr!avu91CS?~V2M}dcSVAHj$xIH(Aw@-b5c9tPcQXHC@`EwN&?=Kpi z-Lw0yUDhknZE)6`0R7v$Jp$A z=O*X0vk#IedqFDtdNsrcg6Q}tA95y3ZrZ`{ELG*4AaZ?>K}M|AwOb8NMrp1wGOCUe zK}f5&kBcP+lsMWy-0!asS*LKtaZ2VDt~@^ghp&$iN0Atkj%`Y;%ZP>?=Ou!bD>?%@ z`UGnsK7!6cj%~6=@x#yZxsRPWt>gi*1JOSDTvhfm@mPB1kSICF(a4ccfV{biaVqtO z-2InzE^Kna`1*B~nx5Yif>HE!1B`5Ls$lb_LV*89IK%l+nKb$Um-A=^czZxOeFt;x~`C^5HOm+V=_ zwpY@Av>iGTe4BTf={d`3ZKrj2q-gImmj1TG^$){KV?A7}UO!HIhh2mQPn+H(9L ze*V<|fvGVODI&RP04pLpd3?3%E)I-ejPcD|Bh8~4G3hNDZNxWd2>#xjq%gZ3_P^r zEjLkOZOX-OGB>J~V`YH9=_{F;cD!@|zibTR^yrcM(Ozo8wpJc3gjHu|{D2w{AjPNLJj&sqBZ@j};mnap0FLXV&+n3P zJn0BZz;vJ+wM;vi`E$(mUn=@gD>GX04waMGMaGn?hF5H!r|)?j+;?nV56hG42gk$K ziU|MC;K(;D_=X4#hxLk%lUDdhxuW#)j2iW}j3UOAi*K37NuCz2GHo2t^$dY@Tp8r+ z%q39e_&9PF#Pa5r`L_wsI~f5%@>=>{9}$o>=6ORUS;43HC<3Kq)ij8*3}zwdnuJAm(o&Iy0XaM2o#5qSw|(M$P%1`dn03F=0!dD z6f!$C%FS@?2;_J#OAyD^lfr0Q0OWR#&wTIu_`%bk#nK3`jg{(RK7Hl0PvcMifx*3d z_u=x5Yxw#<{NK_3*Kc9hS02GL|IgoElhe#HTJ_~^Q(e=Z-oFp0_wQSEnLo+&(i6w= z*o!Y?^2Ti#Yw_{SZhU-T?fR@A40AW~EyuDtO{g!0`kvIU_?=b1$Nw$E(eZN1rCeP5 zWR$G+d0qE7M%MZ)X3|X-MePJhS?1p1aE`L1sI>5!|1|dQQKV9C56;Q zhSJhorUEZ7LGOvE*yLryNneWwmRW)We_DuBD%gpQZ<~`>- z=iGDKD%*UuTvLPFdv<$kxU|qbISq?N4O9KjCSw@u>Dtn|r5sSYM#s>1e;8FuYnr5} z`sEa`6`@Po@XP0snlmOZEoV%N;pXCaiqfgS!EeZvfe9<XR=8V##XsNbw zw`XNwCg&NoiB(}Q6#5{c&sDF^nj3E;_u>nX)itbNx}jOX(*;6nO^|5ovlcX|JzlE_o zBLIM&_6`iHNRCx8*vEIEx1)1I2gWeRoL~;l)640BfF+`EWe%3$hVF9nmq%)arRz#` ziJPcT*dIeQ=?{;D5QxX)SXx@zlGAoF3DnmEb90sFHSuZbw8dtR{^o^<6b%32<#PTT zhHF(Csg=Mvu6a&ISS$FtC<4#C6-IAU&;^3SBDusYK4r_@rD+`(2Qjmb-MQ3A4vqY;?!e81 zgPAg_Sqp7z-1{P9#nPaAd?Z~L3p3_rtJ3s03ZNKL_t*RC%I=xDP2%Faf#OKy|Rpx9)MC&`%U8W zgll$6qx<5tKDB_ap8Wgxg?IiX-uSiO$L#4=ocxu~Vs~$!m*D0U-2d$jWFYXTiNC-r zKlo>;-PKWXJz=D@A;n1NxgRg-IO)T~*a8xk6@`>>?G))BC(2|pNNy36R8=KmZG)Y0 zb5v>ul>ZGXOdQnJN;vMiRwm~{Chj($nwVSHChE3tYJrzh-3jswzQruaqfA-bTZhR( zTj6rjQ0pExyr-@q&yp93+U%rz6A4xattj3W#P)|1Xc?b^1sB<59A}??s>s`@jH**9 zeDTGX{7o#+ojirJmoDJ)zx*0*tp7Q7{5LP+*%K$XrLLdQ$3xfd-Nn+%3i@~Kz`1Kz z!=1J(5z@n#hVcBA3jbm0!-T(LV7quZIuPMPW~qF|mO(R}4n9mL+hPg?sXa5nwlbLL zLNXUP2}qke2}z*S^Q+yTL2ym#MKe;V#oEgaNCYt5f?#Y4!sXKsKRAcGzxy>DIdTv< za(Kh^N{n|v(MctQe{3^XmU7q1*`_AE`od=dhQ4tp= zgx?0KJ>|L0^2qQ?;MH@QCljxJFfIr2#l;wUMozV1-!F$EWHRJx1HL7KyJ_>4gKPA1yWeO;D}7^hqd%gEB~)N*Udd z?)Ynwu0Y{1l7nYHD#g}u9q^NR!)p&e#7#wdRmzI6^_WWG;5n>~=I=0tL2wNWuJY2z z<@$4ro6^l)_dEw(>!YE5ky7sCg`ZQctvGk`I8MIvzOgEJq|^wy5|2iy81e7Kanq1? z4FrIgT>~Mw`<5EN2rMh%=XA9fq1v*o5^o&^HT~m4M?c zY`Ls0(d;bn`@avo`6g<9=VjP+p9~|M5OH{Kq4Hhf#6>q%Gs4!-N=oBgoB(O~TsOHj zr6rRG=Y#-7_EPt##gx{RG{{AU$1)_IOX_0YX5wgIEg?mq+IAuQI?OfID_ikAE|n6W zpp{PD7s$cFsW;#C^I4F%H@FM;w#iZVvrjz@Aq2YH+Y$NiY<%$IZj4zLzV+4*@w3l< zdRyxF32iT(J9Pp_&R;~!+6+7OnXOL?X&6qLV8;cd=o z%O@QZm_0Dt&SfnV6P5Z$1`ma_R1~BL9AuI)q^lBGXl%gkJ-dsxwRd;~?T;rA$>dPA zvhJ^FsvjzzEUjB)^cEJd&{(%+!*gR@9jYrhF-6xU5KdpMP2tX-LCmyN78zF2TB-^c zjva;Ny7=^Wzo#AbY{5k~5%(Onw`naN+tG!1I)lNb+w3d`innCS;sDJJlT*>NAWzh# zY)TtUMqo$B8gZ>R|>Q8yA~@) zcev&wU~1SD>fuOA$pAbhnMHN!hW@XA-+UblTLbiQ4n|b7K)SJw#!E%nve~#;ey_L_ zu_$a__htw=O6a3m%n9F=mw2SZu=z!$s&VIr_~SOBn3KxgaM2OT@R@5Wg(*TF1M()-{N$^}K2gD=w{aJgZWK zX{@*rS!(Ny_mppoHuZF>9*UDq@`zo);p(32_k)~(C`O_K9w?>LyA z_de9thDO-7XTMrpS%GB<)KsNH^G(msqqe#l@q(d#b$uPVd>+X}97`*!XsWBj)Z8pu z8k_L`)vGwRZy)Mv@>ol!QI$xduDTl8Tn-D%%V?^v$Iamf7=QZ)PW|*#*tK^6$#@(i zF+#=H)5>*r z#qhKKJPhxe@{f0qrzwq>d75xr#>RaSMSd&kiKAwvUo-QYYZIYvzR8ix(Mnc!G`y^S zlYHmN&>x&QicBIAXuGK;IC$X-607S_h)IzH+h6NQ&L!Kjv<1>3xS3idP`}~ueH$$0t9M=!-$H0v{Xr7oUygM!pOI$c{6f@1uaBO?S@`{lZ z-q@W#bsPsSUSX$Ixo|-djdiP(x>nelhu;bd2TmCh-k(wKz`N{L)*RDVM z8|z8nkF%~_;a)f-UD6p=WHF~1MRj$2^Y<|GtN%6fZCz~b4c0<>pD?F$;!Soz0|~z_ zYQMQ1kj|r$(6^ZL;5xuU6t#w$SY4%{tvxCYci!flRhM^&JL)`8 z_w?dkB}(SzSli|6c3vWu&%uI&ST=_z-g*b;PaWTq><9ps5ZY$wL_Cg@LkDr-A9mrv zpPj{xuY4Wye~@_Y#HlUS^Aifv;>t4KzH||ved-K^5cuH-=df!>4?0_efeanT!MD%8 ziBBCnftpk}u2=M}SAHAmU)m4RU5|r7dhgC1KZ>I^!Y0)4cZ3?6o!UR;l3s}ErheW>N3ok9S zmcQ`01%Zx_npzrdA54?8HW`ESAVEKDyi1eoO5pPcfPI@gPC(V=Mfs+kiZ_P#VXV8$ zPbY;4Ra9O+dI&>TuAy~e3QDQq3G7Z`T)fgHgm+Rm`9)1MN@#?9B)>2h?`{^g~ z#G7xkX{1b*WW*xY$DN=!Ls1NkvtR=M9JrZ^XJS|I%YboDjYBa2%2^})>tG~qY6WNA zr3H&p&$-c+w>{WH6VmI-bp5_L?}>d2NFUtrFNjnX=4@9`TD?miB}zRrNnbOBmOBh6 z^X(P-u5tC7qC@kw3R)iht_k!=#izSSkcpLxNaT9V+rs|_6(?NLp*x=kjeMpWmTDoR zI6oXkeI+hjKZ+~W@YOPW-J{+*Y@Jo@p}FNiDKPSdIF6=x zs@@nEy7?$6b;49z3$7m;3TewnM^Xq#OF1~v=#xNgDtgTCRcLvGoZ3Rnu0|qK2LT(d z@375hmzvXjJuvsF{VNLSpmum*`3AYHgxL^(Z;$)9yO)8zG>|LfeCN>;0!E){xY z8F@%m%mKDwCDMr)R7a4r(lL$vE6szPyQR+`JZV<(4L^d0t6U|$vit8pfbBXZoiEEJ zwUb^5frESYVE4{`jD7ba-u%-4h5y*~HCVs>A^_m!XP(^_MB^K6I{HQ!&gMj*BI94#;I_AWV|w3VNOf{_o;4I8Q~Azus1T^CGoH1bzqqaqdq2 z(+wWBZ-C~w)r*4txVy8gs97U@y%_21Mcc$A_Fuh@SUOWMINMBBXR&$l_66leGF4!LS8 zHv)A>Axq_2tjvlW?<(9C#Ao~;$IfH`4H`-}TD!TNBn$mgk;c_Mmln z$~4N_$Q!yl-rkMg5#OxrwUJ9~dLE0_0sk%XI1kDNc?sO;)Q*vpZFA(FOK5s+7w>+v;Pr){e$o0-OHD~ z1YbUaCk`FL!qO6M{^6^TU%QIDlSjHCj@nf9wzZ=?Du$gmBL{J9UD*B7j^05MkZvBZ z@_^ycTN+1ya!Fy>eE!2dBDq|$Z6FrgI9(Vi3Ct2Pcq_#A^hp}OgStF!2-Y30!^+`^ zmFFQ{a}Xnw##vpFE=fOYk?XIiUQZ7P<6f{{a*^VJGE_@=56G!XZ9E}e7(cNJg(nW< z9{@mlS+&x8ZPZ(%_&Ew&iyXM9on6Gqx8H|=3mLKS_ES${rMeo@+FpHCO)7=8zr2q3 zAI?JzwqWS!5RRTaiim9^lg)nO9k_G(Jl4|du!N;y`_=U|BX1u;?rmFjeq)GTu)v=ZCfLH+B*=B#ZZ-q zqott{Eyo)H0H1s2IRM_Af3d9_c|-zR+o~gRywZIP*FTJx;g4+4ei8O8>^hu+m^GM> zOUdClT$i1KvcGOs;qBkJjiz3Y>i~5`S|q2m$0^-|wJNSmJ1$pmf=?S+8E zOiN37j>WceEF@A=rRpo$tn(P}?!t6i%a$Fs0Wb3WXzSvd|@V*mha$*OH> z(`qV(Y&_=6v9cgHyAcbQ4jsmHx#L;}E!EcI#?U_OzIg|=^NapF2lyQ0dLQDErM1^2 zz0(F!{kd08@h>u{qbmOW>fa65`S7-KyCT;K(Y#mbO@9fFY<0g2m+@CVZXDAp*&_J; z@X^vG0o7WYwNQ`j5U%$v+>*>yvgEP0;2647& zpALJEK}UBrlDeC?LascAX)jmUmfn?QZ8Pyc*A19{GU0j|ef&k?D^O27S3M7>lKtE9 z$Jh)e0H|%!b|#J5cfX6=j&9`JI)PZ6&DZeF<)*%eHq$7F^f3JnA7`!&;9NmD$t$lP zMY@-XN!x+fl8FR{4)4bs|KK^y{Hxb->epYv@bV0%=H{?cNYhkz7<>D7;_Q3pAphVj z_WqZj#m%J&bROP`*2bm^YLkKSA=*gxtxPr!!?PUYgdw4@8Y;!uLPQ{7L&_|GPex#^ zPa0X4wQZZ|o0|o4Ie}c|F~hcrnDi$EgcXO(uWKpHnMRm6OlMX|ElfT^&vm>G6r0E7 z@*PC(DzD-}q!HEIqDn9=*Jkfb&AifQ>M1z)bhUfZzempm%xx|tqbkibop!}}h)PY` zOtq@pu7kSyMI5|v8L$NI4er8XT^+WIYEmiG45pC$(sO8iVh=Koh3|a+cfEH1+LJi- zc~;kX}dBOTnP)`9MBGe&#?Nqkgs3s!hA4I5Tu*NrttcLZ8OvH#V70+ zClgF?V~#E=hW`tTzO9VY{8%e4s0Le1EvIEssS!zRb_&kQDq=3xLB9n6VM)Ay>Li?q zt@XNWkXs#xNR_8~)<=VYwE%qM{PhF-G2Yo(){)eicpNwP?Zv%;UFaGeL(lL-e=cxi zBHv$W!Np`-8%Fwj%j+K_*Rrr&TZ4C>egend`v7(}U+9-&9v1kVAVm$ubyEM-6Z)-$ zbd#k4#pk0Ayel!L1jSHYX%zhKh+z}63<7X7ViO19n{(PG#%)F=;7GR(N(_m$AfX?ePS2;eiULV}T?6dqF zDpolED%8vjTc_wL(-glpT##J3jt=m+QC$HMZGf8D>M z8;1rfcZ^iMkHA6BSZm5768H6T3vXQ5@Zz-5+Y7qz=vC!Gj zd>rtGU9*xv>PZ5y8n6bR$t3@%dWl2nMr=wcv{F@jXl1ANDW@p@~!`(ayRo;HjDk%3I)Tnzup50`D(z8wo4tqU+%p8mDKmT3d}PhYl8dT@_I*8bvG` zMgKF0A^yW};@s^Uc>eSg0D!ZXE+U;tkgNDR8%mI z8_bQy(h_hhJmzq+y$$(j1jpYy58F|aq|IbmhPwqY-%yYDpV+>m>K=aQ1HAq(Uc)Qj z`KJ}<6_Aj&wQWaDOH1IbGf(5`AH0dga@t>syT-;~33uDpUjTU6(}TQa? zjVqBQNTJLX#%lg-O&;X3KYc6Q;A`r5^tFL&H0Zu*ursfNhEx|ETbYtCNdP*R=9^?q zSw;P&xFR}Nw_&=^3L~G_BEp9NxtV(sfrm1cTQp%H`l>yg1?bYez7FXBblhfQHy!7N z>Bu*n+}s`bk<-YfN?^gEJ;kySHA_-#}MTIx0Y zU*22fG94dVKPsb>Me@#N)hrQ*gxc_1E~45x<@11) zFrs38G&FtL?RJL*M;MfR@4##k%BTvr2~M7ZNsuGIIauFA%{^R1fr3Mmo}XP zTnWT%!1nq+{Ad(EIQuqgtE=$~FaM06@6~tS!PML=P9Hpkz5P1@0Hco|@PBN~a|?!ys$_USVK zfM5FQ&*DFQ=iB)7sZ(gKZ@|d-IAYPLAI)3!ThUA3{3qHNt3DN@O8Mt@Q7QS}d={40 z#Kfk}C`>*!u_stw5%_E3)Szr1EI(MT*=nw(3)^~1t4Y`x1m%7GUvZlf-w4TV%gYTl znCNOpE*8aPdt0DArRd(kE)3kci>l={)_#Q>gtnP_yt@k{{k>SO-5w{C*@Xqn$Ma}v zY}r(Pg||j~c3{4#VO!b+0F#~Vh_7eRG&KwFO}dc6#$;P7+--8$Ry5z#h)gmLF|XU) z)GVpt1Jdyk31}kkhX@kOW#cFrMKDp*89zMlJIjBzR*H% zC^EI@xb1)>E%&k>EU2ZKf@PRHqjV z$4kRC1KwQXZ?N>2&gJ8BC?1Vr*UmmTf9DmvpZiO6zH|&tNgGS6D}I{lWEI+5njwzw z0QMflz!yJ-n)M~r)znnvfM|ZV#ZstWF3i=Zc&_mK<>(O$+*?=>u;I#VVbknpsnAPV z{Is|qRfDUePkARw{OP>=Dh&Jtr^KGpQMp{BnL>FGr{pFRWtIKME9_rCI{ zs5;Syoo5cAqh)h)@K)&Y%rqX1j%xQ#3?0CY2luhM=3#;zZSCmk@J_j3OQ&)1<_!SA zv3>iIDEKf9kB?z|YAUpjyTA8Mq#w^C^Yf?RzH$b!`-`~v?X!4zs0Oxe!?tal7#hOe zk%zec@4k)2DxmB6LvUOdSMS`xfx$sYDe>^}I9%63Q(ZkeTRfZo#PmJf``$%}{Z)wU zZ%0RKD}*J`+0u$z!w)b#HioX&HuQFO`cB$M_Uy&!gNIO+NT8{{9`RVL=t)}LKXbh3 z*mbqG1tV>jOPhu2X1?M;+XR{>1;I9@r82^vZcqECr?WHgkTAeoCtarMvv%r`Y|n^CwF z>5H=08>1a+to!$T-|7KEKtR4DK$q z*?kjmsdCK7#-&=Oe?#VaLBv}tw3gAaz3Qu>5i&uxs)ff-p}kqUt2lpa9{kr;{^8@v z`w#|HIS{nLorv0R? zt=<|%1gAN{#kA6G4Mt}(cWw)9js{7AVehM^J>b%>TPZ8}4s#b^*TFLRH^3Fg#pii3 znt1a%F8#^t5TD%x`Tu+X@f%O$nUg0mzqEwu`8mjM-2^T@##$DDY@lstKP+KdozP@oai@$TT&ai7L zU$2WR$T?8v{5@DUpd<(r_zIRzJ#hoi_&oyRr0nO;;e74XIf$xNvQk}trRIw6;HD!F z_>x1FE+cVJ?x`m2jDzaTDiW(19LZetIltr!`{lj)w#w-y!+&7JoV;T)@s+UM~%yLTQe>lJyLP`rAVCY zhWP37%H(fNZ47_+$;ANXVQ&A^@ za=3rFvYtvCY^V8*|25Gf)uc!GB8;Ttl41_N3Xc%JvWpt^bZ+a_?PzVGwDh$pB%)eq z6>8xdzIh##m*Yu}hRFe!M#N$zkaC^BbrTos2v*l2@YWPJ;_4$}z8}(9P%JLx^sL^T zl4>YFkGQ4EBPS3Z-OzhRn3A{G3Y`xgspy3qt8-^<-QiFI1;=dC2YAlf`b_ZJ&e62$ zlUi%DyY@jQssh;9W@E3~`_7Y3Vy(Kkjx3hR;<@jAAFia8TlGf({#UHr_q{nyvB9{* zgImyI@@uN+&8v(%+Y{*C*weKH=$mtK4cUw!qvSp9Fm201bh>+d`PJnK0vyKfJ}{omifVn;3hSdbHp za{NAb?JCaS@Zw6#4@Tks^VfmKD%ijO3x3+y-+c#tU0rzU@KG8|9-ACws zzH*2_Ufm|c@0snPG~pcDTq6eT>MA_!+njFe zac2i?*Fn|F8tUg3P&>C+sGXb})uz#zmga49*!F2>6GTr(*~vNoPw)p4}=HhwOwb=vOgiIQJ+VpG6AQFVPX^fP^H}#S><(j965CT_g zh-X(MxyjTq@O2>=D9pspHu4&dE*&h8ub@hM&oyUckML4kAjf0R4lhI6Zw9O~{R{Ms z(Bvnh&y%2BN!#r#EuFgd+NRn>vswMM*bK08SybITkNGeC3S^=x&~Coo@U@rz()@HI zHXiit^heShWA(FKdlz)PiIjZ_9Q9PF-!V~H~@0$x(=Gkm5Ri2Kqsg}Yx3mcGm zU`tNhpFFZ{8&c+x&pU`jHg7MsZJXJhf4oSDC?Fj`(@zH}9CH_!xpi5wIOf*zw=N|I z@no<*QzPZ2l3H3-2mi8yE#&ug&2KOlrQ+pNdzJK|xC6C}dtuQkr%p=HIgrA|Ub%dG z6v-6I?@857fn+>6$%W$DTj>(}!*aCivSRaLMpTibZdNhG2`A_6-Wfn`~kUt7j}dKE|Z zP|zd+0Xt%&zrPn~PN8FPH&V$eOwJW#aLdBMfkEUQ2Yp>#sH^tm{gxM8)YR8NoZN-z zlMxIJ4ERy|a)R_LrA!Dgo)9ELZR#PcoInn*#5tKtUfjt*v-CY>&@54&X){jBGwQmmwZr(wB zJp(}PK6m~3@9lYX{Wq$hjt<0BT8fy>=c7J1byi&t=?WOkp2dhI70jLQD`|=Pk_DS;06-i*sIS4iVRa6 z0;(BqI@ar|0yVbOHkDG9phlk0Dc-hVL<-%x+}7^V{5N-*t8piB&ua(0DK#r-^eDED zzWIl~>0)0nxloo%<5N?(@aFp%{oX}bg9*4_Jqs~23A^_kmL?}5vl+sUp|i02M_s2k8Br}w?dV>iiN`-tv(?jB;XxM8{IHZame(^qDaI>KJOrx z%Oe`yK>VAT@tn24_dVeG=Ye1RMgNg)+i)Cb%Tcnoi{f!08pWoZwmDf=3{vLcg=H%@ z*T!!@Z1$L(m#fG4y`W^sqh@n>OCXu6e<>f88P+zzS{V-URf#%0CqA#s#R?bD!?FMe|-M#4zc8cP$n1A#V0Ccvt z;?#kISY4~ey>Gvd%PX(q@e7C1R9A=ny9TyY*H4J(&chKTVli~LcVK3I9^=zfIJ7(5 zG4#&E5yYc0f7f;~y8Z{>z-$eG{cY%IX+gxYF)=fZz5V?dotyyT<>OeO91i2rMr8_P zZkNu#(Q_|NuuQsV%I^G{mlu?s!{ta*wQsgWN!65^BMM!OSF9hwcIfG-FFICMvfZ_V zLm2Ps+*D*iDFl{lYjF0=Q=Zd{bYL^ZoZ37rg@9{suS^6>cu@g2Y9oTW2n!OfWpDeY zYW^++yz$wNh>c;S^c(z*D{SnMt}v!H5-!~?3eGt~fWhZMQ@5!Awh%mVO+C|jqK-p! zy^lHpO>Kw`H#l={%cTj9tFIr}kLlJHzjuwZb2xbEYC%85w}cbWPaZ|FwG{wbCa1CI+D&cc7FzqrwVXEJaTCA3 zL0GlTUs0rloU)KVu@^FtVB_gw;Rx~t1HKDb0&kyr5-Zgy$P(*8I+?%^KK(2J;Mn^g zAho>ekC2)JsvUVm*i2FVQ(uPp&S-?mRY9O@bPP5eTp!wBv`w6Z5Pr1Ma?(aBh>{r8 zjL|Ps*Q0)KB$1dS5tQ-G7KG0zA#4Z{4Sd@lC%NuA%0=By5gYGz9g+M=A|ZgV)KdIi=$@|=v9 z{{ElConOQE<9`L`i-(Xu)#atTIF5<$e;yMEhw9oIyv*{2(x)8YSAQ9> z1<+EBM9g!%IdkkdqLGLn0UQ7<^_%J7e7+I^4({8F-2*!jv01(n$H`ej00yt&yvMdI zfbrc*c@rlU^OI|~OQY0}lY-ha{aPCLxwNEXO8wgn$G_%1RTh^@NbU=+1;O^3Ei*9< zm#58*SH;>L_J+bSl9HNu^y`({6c!rlL&_+hMt69}f)CujgNC^|DB0NoMKS!Okdm8q zN6in16fO;yVvDp-N<0`Fh2y&DY-vR*x$&ktVa!cd8hg(5KI&QJJ=b|s^hp*@<&aH*pFHH_rK4!0$~JE5-1UHHVH?SVw%dsB z0PPyB43`J_8xy{LR``D@rP|=F_!yn(WuiaccK+^Edr3b+?;8S`>}Z2)nVZMG+N0SV znx|$8BQ2q}1UpP7Q~6}!JxHjy+sZOsNS9edeDp35x3E5R9I`6q>o81R1>t|wx5q^~ z8OMB61M;ybZtpGs#N!>~qlo14{>;~%-&OcECAo5BN(hp4AePU2_!kw+WYIP;SRpcE9^73O~ehqm0A<$F>@n4(cs8~|W-Wfh$*tr%Osfz{DPq-Pef zu(aeAw3f!8?ct5|>N@fTWnOoCJG$H3L;ERy-NMT1D)#jCqobt-j}Kee-&2P}yLBG9 zuYV`-clA@H8VivfEFo}oUr;aHdTKXXPlfZ^f$koF`P$c{QaChNK3^_}G%dh~!A|%> zQGWTQ#CtBJ>2-wPU`r{DN>Q9nDCtXJQ!i)OMmB@8nQpUK zV3)UBL5^UXX%`nc0TW~;mup?MXR7W@xT*}#6sJmk#T4yIm8lE);Xv91q%>|p&}?pO zD5iL%HqZ<*V@P{I&l^>)7ErNIDYqV_fYvG3c&9<9Z7*_|KAK$6fzfKdw_Ox~BYap7 ze^pS9+tLSWW_0kNqkGUY{U}HhWk)@d55_IU9;wFN%FbENg zQ6*q88i^n=&<1g!1M&C9vG*T;5tnY=#J#mype6z!g8na_K_-{Qpw;l?Qvml>9$>z?;ajYyb`%$Jy9v`+MI5 zzVQuU?_S_bUjjacqjbupNF)N=_JF1kn^y`5L;wa>O{xqmS2|DB>?&`za-eM1r^DS~ z8V@Mewv@YrOP&y9jN$I5&Wu{!qK`y@s2!8`1wM*5nHqt5OuHq>Kki9Y; zSZEucMBcWMNyIVT){2Gttr?&=^>lOsKi7%scoNeqiYwYQ0Ja&{JvCLg1=sv5id`T}VIps%wF&Gp`KvvW&}n4X(MZ$~Gt z-n&DEf9EzZ)Q*SeZX#Bn!sN3>Fpaa1Q$ z*xTO^$8~Y()=doU8bCZ2L!!ABsVYDulZZ!Ss7a-;w|^(%(U_-59~4Ahegphx zIA-|eC+Bri7 zXV`b`29%>-1dbMuJ5m@Q2kP7s_~T55OhP^UpOw#|`utyD{ulpGSjj|T9CZV;4F|b+ z3>Quu#Y#=}h6V^Jguj{Y^3g-E^A2|2y^qGJ*}_S09ykAYDEWOjo=m`MWaGVuLxPWxnvEAOPC}p-t zZ4y%Ey_3ph4zA228fnzpr!c3UpLE*%IY*(iu5+2d)EVn~@-VE-adz;oDVZxhylE4n zS_!jqX_$Bg*-M=5zXe&@n{_NbMsiM zPT|U-gQ0J!QtI8+hlciM0Kj@WjaT1%3rqj#>v-+I&tmAwBiOf7H=<&H7I^weV5j%) z@rV6DuJDa?)ByE`iGC~t{QMfw*PvzhjL8ky-PeceWD?aO#}ZdpRpI#;KaHG|M_qL_ zlJNupVAsG-G_`x1cxzJ|1m#HqXbhfQQxH zWzf-cA0WB17T`=UewRy?;ACAkF7+%7E1P-3%F?lII1Ub`GqEOLN4N~hM~Jr}h+(8( zD%aw1otAMZxhWe{9kinHesTGjFoc)Klj)|~S~1$Q1KUCAswCE`Q%J0=!-B(b zGX?DVxG5aNZA>!@^T^zr1`-ie_qOBm^W@YHDy}XkXEuwN6f<@4>J)?_Hp7ZV?JY@_Kl$)R)U`(tLA=I*;3eiu>$c z%RbLzisYu|u6SQkvSZJ!p)k6p16mcp|t*m0my;f+IMD4;7B6($Nve~BQc=kU7;t96ik^Vs+Q_=~jf7xUV<2_xtJ6L%@n1zOVwB)8? z<(xt*m6JB0oY8HDM#Cgz&b>I_Q6ryPS;gKPH!E`5{xFHp3+`ra`Mu%%+SDVcGSq#A zg#|1T38W=ny%B|5*tSkm`_?x@0s>OH4A1>|k?Xo}-K}%7SS*U39v8sooVI~dcw0is zV((E8SOox5x^Uezq|ADo+S%zqg3SqDn=7->bxVbBUFP9R2Wm@?dJ@FkLA*_OgUDR( zo%u_!|Lguw#iV$_ewp80SUWi>@0y@4o(CZlApNr{&jMd7)c-An=^Rv`5n5#^3bzEw zxul+}o>2vyNPv@$PKAzY=q+NHkw4mc-@?WtX2lev{06f0yY;v=- zBHvP3E)XeB!4G1iGQ)v(vFGs14}$6NvV?XW2Dmwx2J|JSczGrupu1+Y1sTXiD!Z^n znuG-s$9daazwJR21Q)9H-FdUE%^2R*UygXQ`f zJlxr{WoKR%0M-fwAr#+ZNp{olIb|vmMRjGmr(LTsgz9R&V|o z_Anal*@3o+NmQ+_LB*gll|&|y;8|J#RO~gJeQqo~21WGJX@j7eJ6DAnr3kdBYaLk2 z!u-~cing?Gzz}5Em#Sixn~HD_00D9aQ@_cCs*IR=xxAMo;!qECwyZ|Ng<8dwA(sQ` zFvXfacHz;q!=gZkMIbYGQS;xtAJT6V%|rnnlZza;y>=_$s(KRU1g*EnblT?NG|ah= zzgv9^g(niJ(Iz-r09c@%T-0Fyri`Gv0J;zoZ`26#%Ih(9;=cJnrK<%T=ewz%EuUH%8*%tEr{P$@!nZEt*#GoJI9IR0Wl@y}x_gkxX3+Th zB{ZcY==|c7sCo3TXvEV}M6J_7!$!H(|G8S*5)rrokSSSOF2Zx=I0@<>4v5|Y3C|f_ z%KS%GrF-Qb@a{!eJ9YqH_yW-O$xyr$BipuNSq{8i;gt);rsA)13Rh+Ga>Kc_Sg%T!wV|;b>VEMUy5Tu2 z-=|F4OT=sj4dU zc61`|IJiAL3_xP%j&3C4aiGwr*@gMgIzIS=zeaXt9homYi=iiuAe+nL%AMPIFgA+1 z>KfR#g}%-%+#VUmg@66m$R21#&)$A?w-a_)SX#oRTQ`x-<&eqJT7K`}eFy2E-2<%W z&>D{-lg%NSNT9jC0T*uEfMr?O)7R%m9%`;{Kxaz}V$m2J*Fh$mLp(|jCD~lopWQou z`AncM^@Zba4-W1IhRa_YHp@MVnp2G8!RKO+IFd1D>qsxd&h7WrdhQ*0W zkD$q;xfDbt2W3F|Yw87b8BE8@7F=9ExE~W8?OWc|3jk6GEHpMiT49^8i@)3R*RNqm zTRRq)m+^4oF*;jX(ALz93pa0Q=}sR!gqjrL%)Eg+3mvhd|lPUk361lFA z(&rAP=U9(pBi#YnyLSA@Ve?H5xU*+)L)}j%9>+pM10(>)j$om&^hTy!G>XagHV7$k z;PO@fewYIQeWA+0>@qCvMWptyxk7B-Mp_TaQ3NP8KCV`_C^B~XH_v}7Lo;o*%@;6R z!GIgFap}+@l-hh+wX%xcx4aESo~c$jpsUE^v_g`h86b%%teq64+Gd#2Dqu<*4(6L1 zacB2nSwRA_u^1kAbs&?7!*X04ynF?gs|-C#Mix*;@*u|6xAb#ei=9g&Hg+GVO9H7X zz~ZseNjJEjs=|$-eVA{k+-Yp7wiWZe;e&T8Rdcv-H@YGrY4s1PJm zx$YVq0ItkHh$wW^YGIuTISyPvLRd)v7F;(2xXb<%LY-koWY#aOF5XJh(MLk>0ncs9 zp}c%rCHepLe&`zWQqqW9*qEZ$TUD=G=Xh`r+P=a!I+N3*s+(e0Dv4UHpO()9x#ml0 zdL@8pCXZNV5!K79IGno#OSrgl=-`$%IaVbSz9VzqaqyX^o`U>edLRz8qrJTY$pX&w zsR=+2zitjMxCuai_#)vSwewb8V>A^2G>mr?{4S1FisIAsFS|k$*UyoG@1xIvadiU~W zjQy|Q1UhSR@Yi0#lZTH~SZA5_xf1e^KS1@mi^%iO0~Ly~JI9V z!ntqozOEYz>V1@RECqLizlw!9ac8O$ke0x`Jp-8N2#@T@=}~VF9`*KYm<|A@+FJcn z$z$0po_PBm#8xt}ikx7|?S@M7AuFTT6J_OAB`EtQ1+?O)unMR}#DgIK3fp^Wm9|EA z$`3l|^M2Uyd_@)->v8T>Y2DLmbqeo2amv3w`oRS>PtCx}(;3rheYFc4P?RjCqHU{o zTdo5uvw~=B7?wN@Ai~yS7hK;XSX)(pa=_V(cZz|Qc-Za|lg9>$Ri7tuWFwO<7X zB)O7*H^R_gc*Hd-YAYbOySNaLF8rwTYgJVr+NpaRQ7#@uE*6EI^=$LDzd?w&Ea&CK zNj*=2?a%=hFQXWG*?esh5^%S;8C^sR(VsILr~MHlAq2A79P;_i+td|Smr}xYh8prM z001BWNkluA{Wy2u(_03_`c-Qfm_V(FLOXZkK)2{mf<){h11a( zPLq!2L!jxAtQdr^6C}J07iq>7l+dN)o=Up6m_kz!} zZtmZUvF@!0p#=(#+XdSB>t6zXJtWbmo-JO$OD}A>4PkVmf*`#=DwIg4ar&Ki0RZPt zp1^E#)0P~!BS2+fq&RCST}ClOayy0@d%HJIXyz*jxVdNyHx3lv;aVxJR9EBPz%I0oPcj3S zi;=$GZH?4Oq|bAjBVltuJq@aigUqX30Wp|P7=McqS6T({ab*_GcYQ~xKA&k*0?j#Z zx2$?bfB9HZPq<(}?Xkdjw(8%$xr^BpG&m?$W1>o+7~I|ywKG_?5(A}!#1t4$^k$b+f^$T>uZrtCfJD3o916L z08}q5Bfg%2+7RLt1Z1ZGhbamgKhPy;Uh>|ZrzTM2qknnjQFDC*PJZSo+}zcUh;0{D zIQD$G)Bk-epUux^e~b zuYL$LcK|Q`GH|3aWplYCgaykIaEhH>T_L4XKqdpMtZYkhMX6F1i_W1d$txh>0W>dy zxTQTaL9%YXG2t}*rj=u(mYCqUSPzIF=!#&v=NX&3~Z2(9mtI$|ikCnAGJbmP-e?RiMC$W5>3E0(yUESS& znF~ux{&CMw9X<-nvM@70kLs!_?CK`tNk=oiQ`@rf#GwyoT??np<71OYhUW=lS1L!x zlcg|mn9)|>XlE+CbX*eF7v2k1j07)}ppL1?R#ju8v>C=+7L&$m4N8&55A{xPJd0cK7z7q2S0^TV0LTMPT}GZUE0d zw_*D?L#`_^JU-_0=YgIcY_uvCo2wg9&&hr0I<^~a6+}bOXR7%O(BC}eQM55u-Wuui zGYmD-b3LEJi*#z3?p(o*%Hg=gDmeJwAJ|#eX8pBPm4CWgxs;1WG2Yb)+w}}!{dXTA zkxmD`a>;t+%@0d^>KSJhR&=4_gSo!ZmY+4I-k{R0>3Rgt|8-+Cjf)5wF98?n>Lf<` zdLS(e6CE8T#iMv811A~*Twu@5Td-ZV-5Q0~=%*zq?4~Ww(26O)1^iumvq?G4^ZCIsCZ#4PM{jgv>sjo0I0`AmrlOW@2j!wsOt-XP zAFgZTuI4X~NUxi)!d5xTzY!5$_-II2QNUGb;Kzfa(I{Nk-4c$KQX-qpBA?GAlgVmW zPaQ97QZAQ;3~}yRSy{#W{32qpan#oXGcyvDEPS@mGp$vH|GT>Jw?MWCZaDQyu(Z>z z9I*t;u7YJ%L5LVz{~4Dqlpm0Tg%`HO5$kYehNa+$w3rc@`XP;(ZgLWntMJ}?_e)7N zB=zvJ)HR{oV4L}Kj+co~P)QyUUr{<);X8WsHG}tu%MzqJw6vB|KjD|5G>^AjpfgSYM=v7W(>hmVkpMK`r^N|EKd zXq}jXD+RM61YLfC@_9)yoEV--xziOAvqS_{NC} zq~w36(x4-@h1fs;S-kMn(`c+MZ!Iom6Y{u?+9(@7BUBkY$M%tK`z%lY#qXJ?Dsha+ zv0}JGGIx-b5rK;*j%?dW+NCHPi{XuDpTV=Q{Q&Xxa7Rh{61`DTTbl_BD~?U^QN3pr z21Q?=pq0pLp|MkX1~X6^<=_t6Y7C_Xz!Dhm>BP-_rBC`A>FdQvUoV=bXL0o01z7%C z;pqUl&xI)Tm||J05LOD?=}!5)A9~<77eaU^rElc09Yz<99mSCg7t!)~3YP0Y*&4Wf zM)Q$u8xj&$dKK|UcQN;K{{>_uT7(~&I*mf#Ea1W5PK@;TR@`Pz7mpsn!An=rG4>b{ z*L$})_EkCX<_(`Kyl0B%&}@;~D7&x`ThHRm_uqsK2WQVbg~htM4Nu$pFzC+iK{&#~ zz^%Jb9vuK5XU{pC>i`LRhY`u`pBP(nfjnp37^F;p+)debQd6hMo)(|Na51NNJOS$WLz*Vfhnpl~{tL}#bxBz^a8-rHmx$df6uSzW?)*WtQrkW#|7<_JHF2!sgV zWM)}0STJ$94co4VghV9LsBMO}gbmBs99>-YMB$Vxr!eTHct63u4Tb?oGopl{t10}B&3ApIKDsE@%PW;gA>Ov z)z-QxJ}9INeDRy4?O<9P3FXCsGtXZPH1m7GbW}b!LWkuGwySiHbQL4NqbnM8I8Mur zDHQ0Y2z|lej)a~QN-eG**pHR!4UTmyLNhJRm}zN7!`wVho%MDKIN&=?+`!m;9K;ny z^bS9qHra5I2Y+Yf(agdE^7%aKYUt>_Qlu+TOoNSQ&~rCv!PZ6N^1!&RwBmV#;7~ma z2acpH)}4*@9ldHNZ!mInxO1;-Sy-sAhXhcwxZ)|C;9|WhflMMEo(BT8i_5T`e1Y+j z5k(y_Nnf(Mqw*3=)O&6f0Hy`25M7KLF!;AlW1;|(4wTJxAUI|Wm_j*hD+l9ZjyOaF z)s*8p2@=#AWjItKh*cO172TR(z1jZYZfLI$>Ii6xg63eUuC@>{Uw==&nZb2Yv#<;T z^DemZg0Bf4%d?>K0eveCAAf!KGtEWipv@h&RiBpYsv&I)cLxVB(^4cVj6sJkUPfy4 zF(?8Z0OTPNg)*=JlJ$r0k0&z^DY$t29WPBZn?ud=GL~z~Q$RJ;)>a%HqFj=p|IDw@ zT=zVo*i_?{;;krhS65PzxWCX;lA4g86jSuX-N*vQ%1r0s=Ri3n&L~#VbtrO%>O{Wwmgb znR6)Nb146QbrVSEfd_M5#|E1Lep<}rGBCG}?md0zJUoDRuUv*@S!gXp zz-_K?Kr9-?qsa-3O-*8;y9d>&6t3R&qJp+JHvqc{#XI=ZPor#`$yD+rQIq(?Cx! z>da4_egZiCMCe$xH8r8F>B+$T(_i`9q3P>uYw?*U^z_*;kaP{sT%+E~0U0=t6+9ou|ykk!z z!h&Uayw0S7o?g_~)S|Jj4s!oKjK)SF>gv!~N5W&hgHsCZk+x-9!ZM;A{+&A%krLbgm==*Ws${auKzjvUrR1mecpCe@ilO zKd1xJv9JvnbIpwy-qnwp=JN2zX34Q_4EOc&q;-SglFn;m%%+c9(bTdnO*oNMA2R!5O;u{xIyE z19iN!*GducuBcz7bbEA7+JwdWI?OgVmG@!{axDuZy}hvVE_OV4glIYs$q=I6KEj!R zlE@7Hkx3(Z|0eQ#4gise!6&>nuU4nLNQ&D)G#2!xg=R=0voY67>T82Kkwu-h1*pR& zBk4T4A3XGB!;!w;ZHZ{JnSLq>mFBX#hTn6gM=~)$I06o%@^pJDt$+mx+6-P^UxMur z!Ujb6Cag~~xvq-rT>u?+gi9!TnDP_?pUXJ4wb?{zaPh)9m3F&lNOE0C| z&`FNk4|2pfN)MaTB~kOd%MTh$O&FcP*UqA=%B*o?C5 z1z1+KSB|ia^x?W1on*)_m6~fHi$&ZnoleK*q_5=YSdRgwKjqRXAhbT2XjpF#A=GeE z>2xO`!pTA1JLx%7E@Zh_8+9Fh|L`=L?_Iru*REW|Ku@o>p+1amJh+c@*RGsl!LH zy1tIDzyA(eC%p}MRsTPGZyIFDm7Rxu_h#l>>(#zjb$3M8_NI#U}nf6Ipk0x zZBr)gplLh83R~d_|Ii4qGyVLCGPRrcH{}%m4!nFxY|K_pQ3C zs;jzdc~$k+%)I`Q@8&)CX69R}s?h+AgJ{&t%$s-1yPWTwbI-AD{3m;lw^#6aq^^@?~FMaDZ2qEzEzx9uBqx=~A{-a;Qx#K5-USdo$*am=)FI~jN zKll?&vjXr^RL0a^|7?#;Fq*GE`r0jrbB@3Mo$tZ!(0gCfY%_ni9zAgy#7@gi&N*5N zl`g1#5zysPCXS|ZBrBYYrf2Oyr)R^1#XbD=)mKse5~Cr?x&{W)>ROkpFmTl2!6rL1 zC$323ArT8wcPRg({X;#JS`F@iVnB1PqFfZ!i^dsjTkvr4*ip=njdtW+d1hDKpXQ9Q=DUHiGjf;&oi@(1qj2aLBrX@%yuo-nJ!4 zLoH=+uK$x19jmI&O1^{8uIKX6Bbc33&a$>bmyaHXZ*lCnJ7d(-blVoEA*a4?)$wTn zaA5;ruplvzzzgqxh)>QuziAo9R!Qz*68p>Fau-!LHHtqE-iznnH%IN^ZaU|`Aw}tQ z8l_Sh^?I_-xKgP$JwRP5mEik6ip3&owcy~h=Xt0m$S$kZY6QzO#*l673(LzZNT*Y% z)oLgfIXusbjT~iJJrVq?NHii_3D{N-7*~ec$)kWJJQr}i$KWgt&NEtiidfqxX8hIh zZ4`I2rfK5%8+}crQeK)PZLgdkQqoHCJH0a3Eu~MADb#^VJ+0!Yeb9qZCKi`kDtUZ} zh5yn0hK2j9fQ%-s)^^{rGQwL zWeT!rI{BN$-qRI6rXXCeYeXC!S<<4yKD{Kmfa*YlmO^4WyevBvAbFop}0G7*O!(Axk^AV7*=NmVE+M}QT z`CEAM_z7P7&a2peuyy<@ld*4~6cdWZ_fes6o0ZqOXh&CvndPhBYU44%bUcuuLShpP znjWd>3E+A<1<$r3{Z>h5@Xagm8 zAk2q=ZImI%%m}t#>dQn5&4boalVgk@`ty&lCm)L{Gh$r|+53@9MsfYA%iQ&z-;q z31#07)zT^Wjs;#Vj1k8{|gjHr;+{Mw~^bwD=}>* zlflNu##0aH{AH2=0~iN{i{w2`zZ*UB-AF4$nTl5B*q84_$|bE*0GW|@&6Je0lI5v+s%po`eR_)7*K$%TfXrF$ka~Z64Kten zw$k_wayRCrefr8r`D3}(c%AbxTSt7lhG?B?j{>Ov-+!4F=0T`TLkLx(kk>K!9SSkG_k>Ax5q!?j;Nj9uds zID3o;v480oV%xHNGTAfQtIv1twd83~x>AMhxu~U5Uz$K;GZ?wmJErPP=hsYpNauiv zDI+Q}i}I56P#+@C^lSQ@)=$;26f-XXnqU@Cy$y}!+LEUDQ?3PK8m%Cux_3R=Jd7VBdpen z=uf2q2&}txTrWPxa;+MyP(q+oDZ@@M#sUD}^YQ8b{QsbKd>A|S>_m6I3!E_=n3@I< z9BezXcQ5L$i?xjnoGA3bPUmp0e;lKk9OOa7h3;+~nvRAtJvcob{vLbnD8^ok4-a>E zPt*f!;m`zj4ty)I?v(W1Ecikr^9yiO4l0@WL&TP4;rYWy+RC2^f$`Z{*mXCQ2y7O? zwxU9D4Si3RA)vg;(GeIGEz2uYx?;{EMAF1joTSDqN#>-hf1+gOq|2cwF45;X#nB3* zc;N7`JkW>dV063a-c&Nbn66e~`Rd5&z`_$a)mq~lsvZk4rBb8Oqo}&_8Bn~1 zEFwMPJsy8q(VjY> zzpPZd=@n`x9}QAgv=%rJCJ ztlpDex|AHu1~Tr^$m4SPQ8xt2ea6F?IwJ|8_HsV!TCiD&p*QQKtFuO+cuoaR4SOb{}59*?`T>D zpP2Mgi8$qKo(9G5i{|entekvLz8B4pa{CnfnmnbRcf7ua?(agYZ_*m5uQRk3YIQ*4 zda1ICpFjEpzqso=5MX%g!8_RBcL1aLK=yNg?ExOH&EUk~A-w(YJ^WzTYxv6t@8jIi zevD>&@X3?gxU_N~3<9H>F8un$A^1Yzf4z4RWv`Ck7@NS!6DQC$K8lpnd_VZ&`ZZj* zejT-X9j@ykpUL9aUVlSNlgnh``#xS40tYT%4UABkjhtoU-`lkx{WizBqld6KIT`AM zM+XP-!#Capz>spBaQ{2~cm53=_dTQr3Qcv#$M@}r_;7Ic|bICDCt*mOZ>IaFHe8{6(N@pue zp{u)!QLJOr;F$&GaLa;+^Cyqv(dbCW9zX?S@GKr;ARhu=XkxF-=aj!vrHP=r3zPSg z^_M#FyL+cFKRE{1wnG{JX2`QF+&Higb=$#?+cS-t#2?nCyCbiZk(#-M%Kqc9EE^#G ztj4H*Jc=Q38t7ZRBSZLB^}o4qFY1 zn1fc<>n_&T)?rx|ip4e5YEgNF?+c_-POOs@03ptn7+nYf$8nI$#YY-+94B&MnlXgY zusG+)WHRXPE?{E9#?TPMl`GMFSj)re46eHZgeYq(q)Uk@QOq5;o5ypl23JvF0?lV6emsPkSYa5*NPVw+I-OGhSKty^Tjvrn};q1I9btHSUTmR3S}FKLK9|MCxzNymqx*edyd@DBX*cYuGi8)(C58&D%(0-^T8X3>p085o-)iBdj?pMC3P0Km82eh2At70mM?gdPw}LTY)UTdq-5*+BbB*4KhA z9*TND^T1gUTKU~qUug;aE13-5dHq!Yz$@>(i+ph%5K)<^m8YbY z>O>b-nDtd{kz>+#INpEdMbuL5DYz(IJ#-L0=a{;67u;8Us0%1q7%s(wQj{w(3l);d znhMaJO$Y|N0gRqiNEN{tgw4U+IDs0ixlbZHut<9)nQIxqn#va20lJ*o!I$-`uz1GE zfAjf1Yf{sl)KmzdRzvNdzK7IW6$5|$yTG1Z&!T!AQ@|#WHIfN%E|6?Xp8SP`5a2wG zdVL+1aDhh1W+Cbk)&$YKD%ICvOtTGi3_>)^I- zRM#9No4&3U^wrB0+IupsDO6YY^j}m!8ioH#EMWdpr;U|hg6@L~04qQ)h0;NdbPtts zRgeNhYVb{WD|(Vy?p*3k)~Jm#^WvVsxu3otuJspA9>b&25%_#-0`FuM9smF!07*na zR8!75e*KN_003S;a~Alcgab7H?r+84|Ap^wy6k3j;=n`y82Md?5vugyqx`wpXV|HU6#o7j*R97*PAI0&3gQ$2_ENnc&K&BTD z)@HD`dk5y$AE4}3(3|Q;!O3H?FoB(gF-V^C)$ud1;D&rI;A1#bz`?=*4t5U#@UY?5 zu~;qPuZ>SPyeYXjb?^{YdYgC&^aaGnGZ=kwKh7LIhJl`54EOg(4lOvgjc+~oJl#)(uW24J|BUa^^v(%wtBo;{Hi8B{_7~B&mDbp;nR{x;vWkEgcg_@0*HLs(3Y{ zPjUE|*|pu3vFCy0Tf9otfA| z8n~Cca;W4oSnJ+gG&)Jw4jupmF#cc`R@Do+76BO>$RT`>T7TnkFtmCGk(+Mq-HpYO z;Vsos(rRBXGNlTfstaYzEIl_X`Ad|;Y&@%$VK2-AVDKk)fLRPI44oZ}!R3MeFpTGR z(ER8q(v>QDmRB2h8uFho@>2ZVQ#%-M^sMCc01>{e%01h*@!S^`2vLUTtv8gRQNR}{WR((lZH++)<+&ONyl$) zW=dpQKVg)utFdW1I@_YHG$p*I+*hqvYR{w2K6GqMbCi-;xi)f=M(&GBkt}yr9_A%t z>ZM{tPz*ja_ZXvdkHFw#qq_^9ZDDB>kyE~*%~PgQL7}*YOu2#sm##G&mT*Y#m!csz z?t8L~ef|x2mKE`i-n+5_r>5jw0zmib8g^g54Hq_iSa3CoH`UNcuIA}ro%X5OzS$m! zPx;2E9!rq1ucHga$E$ax@!`9(A7H({ffEAwLI@W_=`_ljEP4ygvD{}@ zui)yP+ZY`j#Npk0ka8Sw&J*A3&v#)Yoq-$pH--Q(m`cM!VC-Ea`>1VMvH9f2`Vnt( zrBgPO!O>GkQBTU~x2c=Po8@9%`emIilP=9lUfUJoGHJaVAnS z(Q2G@$*iA}sJ8AOC4E-%>ZI11_f4&~K40~DXucEG=b5$?!Rl5^JGk)N@n@nVE9Ki8 zH(#7Ofg=|$p=)&wl&9gL0hm0Z%ENmK<*6NB^^z_hRQl++5u&i3at;<;pFepV3nRmu z?z?g>hYuT$rH*}e9!|ARw4I!k%?OVZC&$#CyIG+gT%eXtZ#n|KN!4^3wUndjz9qj! zNgKDq2d~wDbOs2qbKD*Rtvy!`AKG?L)zx$wwRDQqFJ6j9Nq};}N-`7Z*ro0$kg`}% z=xpDWAPlZ4pQ_es_|XSH#~Ux4ZOaDdt>66vY3yptDR;W+Ow%iUX#K# zj4@cuf#=s?@iZukkg40NVB-rsBg1xIR3i6;sKWOvaNXsYXEm6(yHWvWX9I87v>D}c z3AI`sD=Vw$>WX)0XIU0_jE*Kx9N*N)?$udgo_M*{)=PQuTeTVM>>*w{cen?-+r zU*n*3ynd)zUI5@YHXO$Z|79`&W1IPg(z!!t6py!Cy`!U1#N-htH*W`X)2Gp#ReB}K zjg}X@B{8omN3A*(RRc=5p(FKZt<3VwK9DGw@(|Lbnrf37lyec4s}G6K6-HJPFr^Ep z*nyF^m26VQm{fb2u_k*0nT;w015SPP8NdTM^lGn)()tZO8ycIP!=4+rkS^C6Zd2tK z4%REDQiok@4}*+9oWg=SELJ~LHk`m^XeCUb7qFHZSoD!xoe z#L2ZxPhm>*zDaTQq3R>5rcv-jEeIxaM<+GC4m=Lp@QwTC(kf819sKOgSGL`|oa{3T zKK{3vYq(!t#}7xwF>|AiKfZP;OxKmq<2S#nJoNp=d+*`VlgF`ncI9&T&F}rXXmVzpxY; zhZ0OHH7Etlfsg=D!V=v;TLEhYssnSEN;ZRcUi((Zr=Z_^=_Q=~-~;q5twQeRD-ia4mNE`Fx0pxMu|EpFPuJ8yJeUrIOk?S*Gq*mw0tSPvC)QV*O$1r=%psoE){ zZfQQx;DMuiX%(;ktDJT0RUL-?ZNvmy@;27`ZMwkOkp@>VB24_H~^cc z;ED&I7TP_^&+0Ii3io_a zAgWd?$sL$u*K~fVdvhCexVC%?llfun?b(S>7S4xd4edCK z6qkx8fxMl}(*skm;Xw+PM>9G6U~D(g2qfDMmSZ-@;D7$Bcy;ZEW zbxPH0$ZwQ1{tyigwsUcBl(_GsyI6z}X8yp)`~qy>!{sA~+g3(4qfDiObfu~pjhL~7 zqSBsrzO^YuNltI_qV32X^nJ)I(Zue08dG_e963p#oX>@L_^V9id=7=Rb?~}Uy9Uvm z6fU+J;c5lJ1C*oCr6bYx3@{}qGz4~_Y<{?N0(W;$ZA+W39XbFoVC?=JcrDIzHK317 zNzw01O`>jZqro-+TswRKnNk^p^N(ZKd`eMl4A={E$bIk@Hs1UdfGH`5ntAQ5dK=|3 z%GC-osdU>0F3k9+KchUT8X?qZL2;qMmD~wTx!KV#F5v=WST7X9`%AMA@cEU?m=^;1 zYz}|pmwq|1p6OFNG4wazfOxcq&;H>bWBl94!1#7~=Zb4RwB8R>G6tJFD0^jX&L{<; z(7t}S+6d~)4)BHBFto124-IG4?1E6<;7b$@?97y~ky?4}}Xl}cr# z(`oeeH8}v*264_&t=5pqWFp?ZwnE2_1+#c|7O2OcKi*cN5;HmPnx~H{kwNl^lfBb- zRBB^_Hipt;gI-50BJ3>5GrteXin5>6S%8%nhWG|^Y%YVw) zTAStJDiGYW$a{J&jMR>YvPGZB@q@hb#SI+$`~p5b{T$Z13;2efE@dheq^dOxEi7XH zwd)P(zB1VM$oeWrO!smThc8?T57Ei-dicU+^sKIG`+@R5o5Xoi?F=2U&1pNNvaR^; zcC~dn{}YcIbp9>ME9r)fiYJ#kkEy~KK3=$hvRlI4;tX8hMcQ((SXlzs+7Wonez>uK zsjg8>~TmaFE}oqOJvYx7#oZ^F|xi0&AOJdgiI?doe}4*KsX4vFsdt@4D?0y=}@?g>5~?X`tye4t-!J&S1e)r`W=itoD17? zcX|q*?_+jx0q=hHDQwHa(Y^aH*ktdR`r(VHPxav8;v;yzkDX&@clA8uL#Z! z=TX7~V^*jq1pv+g#{n3#kWQ;e7#kZYl*<)lGHLWCI7zWA9_x+Tw(Ss;S1KuZo(IQq zP$+b52_xIK-8gK$wY}AGf;!21_4fmN_X0O>ZYkTRPA0b1F}tL8Ft>bL&r=vF%=E%| zS3WhzH=|>l)P$y>d%a9;%A@4nXzk55sKd(&xg)e9l5a|`Tu0>kS})f?ANqdfhkKGb zOsx(i$u!a?Ou0Iv`=3_4{vDMLrY z)lyN#VnnUO+9K`ce!}ea>-z zY8QNqM0hFMe4<%E2!moS?ej_lQYk6 z$^hE8I6i&;IUM`q0{Rw~AMsMuIW; zmJHq+Ft8SUC_m_7%E-IQS8ua9ANMRCl6+k#P(Wwk`z3Im#pc^0fqmoh$rIoo|Kq>~ z*YEuvFgAuwX{`+4ut3=VZwDwWVX8ztBEP_0JYgr(Cd zaL%!@v4MKsMYUQ*xtxaQ2?&9Rpuw`bkQ~}9ShHMr364Do&gHx?IWI~v#{w7w^VZ?> z3@mOM`bEXr=E&56u`Vo+1IZFpM!|7%8hynx`B@!0=;fMx0fpWis!XAkC0n3?uh8y; zyv0Dda=G5>!eeT5B7t$R$NFIzsx3iU9}Y7`>xyfFfsE0 zOM?TrH?<3gFJ8vaUpj|x=&MD~fBXshA1?)C!3QR09>VfHTs*cpJh7eB3?nlLJYK(p zYmeSWcV-x;cm6dbarX~bub^0Ygi{l7hh9xVfWT6D9=De+;FX=72$6a)wd?jIez8UZ?~P^RB^~2VV)1CR!2Rxy$7k=p^^DVIDF}HgYVT< zT~57@bhWyrFtO=s6)(Q~e#jB~1c?B^z`_$8b1&et)2B8Sg+`K7uVdf!8yLSo3)cwK z?i=k=q>pH`{fbWxC{8^Sr)HB+mHa1eXH|JbbB`A(>%VnhSf+?u&Z6Kje;o`yE*?Mn zwGh~zKXDw#*aeI{oCo)G94tp64TWs-3elM!m5u4V14ZP)o1SCCx3>47_qBru01ueF zGXp7dR}?SJVdPo-NZo#7#y|a;;HPI;xOnjj zb`Ol;l^4z+-QV2E&z!aG$(kicr{cOONsE%m=oE~U!=GQ)zQfB9IGoDj?=v6SOmob< zV{{ZdWYo96@#}5WGa$Mnx1vA|u2u)h<13;oj}KpX;h6Lr*M7sG!yJ9SSA$RT3!(>Y zz!Mb$9*Oi$)F2SWZ2}Ay&ysxV@ceZ!mIh~OP2mdw7SDrO@%WZ83%p^3EdW$1SCCFm zYlhj)sIQNq$8bVauh)=DrI5?D7mhlK0_C)T5Mt9FvKeE@W;2N%zqU%pjxo5dz{7`~ zzS-bm+L~{QBu8fP41`|?c=NF0adXg!723M#py?@^9f;#e51R#;ch$2WE#9WyJlY-$WnfANOgSU()Cdc;KU0WY5} zRdMe9pW~fZUx6TFc`H2TSD7r=gY9+Zxp%v0?~R+7yf*_MoEUt{qiGz{>4#jIl+41f#=(q&V?eDNyQDhue%O<=fdH_G)QW|qGI z1H+!dGqAW5c@F@p?gs8JU%=kMGvG|kL&fJrcifvx7ckbf1BFx%Nke-_%AS1fzS8)p zG*g9f_@a*fQ~_1L2G8f{N#$|8Z(7rFF$f&$nZQ`K8zb3%Oyv3?n9@|ooJ7A%7Km!4q_CY88hpgu^MmVv$LpX(pc_q&-i;gsdsq= z;}2({YkfEX7ky8bF~#o!BI-4^6WVq69@3R63M)m!#S&oo9!4L|!Lu#g-m@F!E%GP; zu>00+WJ(n>N_DFU6LsjL9gTa@@nDXiR-A&;Rz>-W)}yUiP4slM)@t^s8qg6gTUp6w zaCgsi%UXOD=<(nnxbLH@xQ?FXRSZ0O+!#G9

BKN`02;JV`)if9N=xuJme#5;-9U zW+%qCb&tQZXE&y9-a)!t(?+FU7iD}d+o7)}X#7?0Y&R_p^kaT(6vK0ii1rs9cL1-H zVHHDmjplqp(o%io+ z_a5w+#6}aRO}lU1hFz}%VCaAR1YN6ZP!3wDUQD`V<;WFFC=}Pp_m1u^@`*>V{T7Y3 zn=b@$%7Eza<_tR(D(DR|1ziD4z$0bEDMIvT`d>Xwl!2mKW>mNr{HB0MPWj;8!;Lw7 zvTy-isV=-a@d_A#AI-dl=Y~(CC*2JO;Og=X+*-K>27$p$FHR2b$B!O-008*a9jEc$ z!WAr4*T5j~T;DiO_Kx7r#wvcia2KBNu}s&Dom43rI5>H@xA9y<6PAZ2j6fyi{W$%c@E^Jb^?3%hMvfB*(|<&`V8#G zMwn}O^gR6^{u++dYsilGxAa=ZUf%<3f*Dic;9AqjzyN;j^*3aRNVTC*S0fJVcRDsU2vmath2Mqcct4ZdiwH(kWiVlQhria|#fHttfz)riW;10?nA%79mC_ zygp_HS5?;t zqldN>vb~y4PoScBq zI1XI83PyTT-wSotQ}w!n-E_5(M}r_wY6&1+s^avAALENtC$=qASSJ+Szd^1k(KRG0 zWQt?WO-4HY{jIKfUnZGfd~4)+9?CNhfIs^);O)18|K{%jy}dxKhHAA2&(lpAeBVc{ zRt>MK)f!e-R#C6l!8wQPnx+o|zAqwSnk8A51lCHKZ6XQWL zP;fJ>t*xP4t{|7oBAd;lw->l@0nm+Rg6m|Zx`6Lj8mGsd#;No6$sAd6BRMFgH6WL1 zICJ2O8hlX)Hv}pa^iqJzv@}5qy7~rB1j!{19INzZ-XgLp(L0Q!(^~|RO78>3PpMzh z#72T>6?9K=)%3Ys!_@&7K&qXkdNJB|y7tJnN{?j0T?;h!1?qrPcQG*c1YOH(C~U0b z?0X;JQX1M#KxhOm04^tO9`1t{oWb+7UjdJhzFn&BK3zzZAuDs<~r^PNj#S0lG@iQ|4+7 zP@JRWi2a5!UBCq^F9T|wpl#PZg3^BR8y@tj*^3VzdL9z0dfP@Orx>h00)q>W@!UtB z;DeXH`~w~WEaX^~IFLcW!m&@!!-j|JhxX&vo;{l`BTzF~8cGZ92c`8bE#vI_AK;zW zzP0Hxj$XKkk=c28jZp2%SXBc`yvxaWX_xPdrlqCHaojE??foVSQTuRoH#H>! zI*xe?)KETk)X)}m;rKE5oMXq`nV<+T$k5n6iWC56<~DNg{slxji`xDpjoI#o zd3B1V#GhZq&42QTsQ$up_@zJp{f^#kD}MxrXaUj)6qzz4GK1gX52&|L6;d0pHG?bx zALAp#_&3iyzwPy;^$k`jFEpx=@;;MSZ&&&*0F>QTRQ-xJt2nb8m?DbAgM-1uODp5B zcm^D4IL?4pPLP)}z>ceh*bW-UY`VggN4#((3ipDV0h=2!UFyj`TKq#r!H! zJGiwq>GGTQ%59I7{w4W2#d><$C{~u~C~qvZH$>z;ik0;_tM(m)vry$>woxz7C;7`z z&6Lkq3SZrCzCyymZxP<1xL0{hq`ttFWLk00($$3^Yot;us~8yqqR#NjkKPUUU=D#x z$By9suAK>A=j%&TckW={wHsQWO47%iE`y=EN;P(c!9P>H6~#{iQlU#--LMEBE**bR zY!@dJq2rsz!&G0K#wyV@H0^K@$<*F%=KC&OzXsnAzkKZco(7 ze2J3}>-F&bdc$Z*=i8``Bgy0yk$b?t?n&br(4U$FYhdf3odWy1hXKgQDl`^|(kx3C zIBIrF^F<*zrsBf_JMPV3c4B->`cBL9F!A6a zcHg`WUiU)BMS5f^`K{HOo-8Gj&x5yg)SA2o=u&Hif+$6`G_Aq*U(CAsh_^Z}?HOqM0wZ8QyKiDFfVgLXj07*naREM)v#j)?dh~XFZ zxAjg^pTx~OibaEchni&vJgdC2;5P2a|I79WWHu_8x_Ji-0tYMyHzy}hv@8_5T1Pbm z(6NVYy2t6`!C*r_n#lmz4KLKu z`K2&CK@E%nK7(cTMBWLEtXu1m2pocKXH+Wy z$Yz0^I~i`@-uyb#Dc)B5CIe$~3?<8uTjztoXj{19IHmQ8ub*BH#l+E3q3_6Me)1g? zo9cC?9Bo`FbXQZnzv6dfE|eoN@xPL6(%*W2(lqi3wTrSqu{rIV=s&rl3c}6HXR-z& zOvNCh2L@bf|H3i`7M_4ZV55+S<+|`K3lAnIw^e@M2@TIbLbg)DN?$KlP0tA((8R-s zuggN<}3oyBW|gg#NRM@IOASag>Vax#4Ru&oU z6qZqHRp+Gsixb_%1L<#2b;Gz8lmc$8r znhRrn6nnaH^YGp+*OyW)mBL0>UMn{cVZx|OP+y(Z6XDm8_Za9bQj8z~6js;3y{KWp z{FBFcFh3tgPiRK-Kf8kSfAnMIfA2-Sd~$QfZE@g4wxAt=Nm=Qy5(S38E)e5AI*Ej+ zL;6Q=!ob z@rqchRpEIaQYi=dd2kVY~W{0m4fxmvZr@ zA|bdJ#lE^CM}+f3rjL5rq1;FCo)k~$<i3^h27`KAm# zlrkqEKjxdYOV54$DFzoF!zZJQhG#eVV4ZU|J#oijV)MSvWm97(s%Vk>Vf-vLv2j#z z9^GM8>1IArgs*ayf7|WhKYRD5IKKY?CWc2^rv1zJ-^2WW^`~I_27x#CVbA0aym;bd znnZ|>Bpx$n z%+W{xwnP8wxBffK@6F-V@BSi=?Abadja#<`7`)*zY)o%G|IJ1G{5$%tACHqI52D&d4;SgiWP-fKBKewVnrrVe2!k7; z`=NY4;E>E?kt{s0qR_Y6Yl5AMnuE$C%sgz5YPm$|EZp5V;rvt&$OD-BuUv=adAPHC z8eb-z{P=V9EU!YxDf-xn8`p7TO!4*V`&*t1zYQ6s%0u-XfJlCn7?eCCE+3t@4Sp+w zOvUvmAJ_p$A`N*d8l!Dg94FTz^iVI`x*@kJ-+GFB+0cByM^9bLtBqIEQJWPoc279WHA9z1S!Y*;?Dun4Q}L3-n(?v|*JWCo7D zC(B6HYFH~2P|9~^@N3syj68aT!xt~Z7c8bt>iC8l$)@`!wJrc^d{9!e2hh=)+F7Gg z;w0~yt@sQoQ8r6N%ym>6P4`o}0=K(*)#`Q3E-r-EV}nC2z5afF?JB0mCos_4i{3&v zdbe>*mvdPZ`?}G!ybg1n(N_!gJ!t={ua|@{KQ@ZGv;7eXbtyNX z&-7r_BynLX4|+|sS3*EAAUHTr^ia$Wy;sY3IZHz@+8YfymhUzWK69iTDVJkf8uPcx z*Syc*`5WLY1#?AvI#RDMholbJi?Lbws*!C2BO}1V0#tCa4rw!Zn<2pNfn9)4JfXLb zx06yu@pBvw*UORb#O2A1cg*}0vTnVbN3WuoThBvs4{`lM5v;01{80|3)m&P2sWmS6 zzwRzZ>ZWxI9VL-d?uuwBI-Za#bMVV*IHeGTgU+pO;Lyb@@EjX;+XfiJ(m?;VudjvT z8givl;`2S%ZlZf_4YQNucr@Bt=OD@aX8W&PN4lb%2euxI(L4a9i;~|}=Uovx_K-Ar z?*ZbxVFz;MfHRReS&!+dV`D1ek6^ygwTBSm1UTukmFg<)uFYa3+lSHYuFy!63giTU zp>zR`l>&p0;cOqy3?IXIegtwscz*aKx*P?>dec4VOLsRWq6-Fr>B4wpXn2^+4M3fB z_W*b(*eUcC`XD{(&a>7_eKwuO%O{`1)Wl>MGOQVyj6*QsT79|AQGW-gF({yvU*4{} zIC|kCt{gtJEgle4)f)PrEQf|5QaQBi&ONxcjn%&1Eter_&y8E?TH6T0G!+LWpX*l? z2n6+SMQ2E-Gdenw+S&Y@rJ+ltWbhS$)%)$39fj9b!24f(jAl)g^il4Fhbhg`E;2FxUndI2RCtwxOZIBO$K>gK36TDuq`fzh`9{Wxc^ER}yQmqoc;MlP2_cX#&|zPAX& zW@Wa~;5C;64jf>(c5QQLd8>kr&;UgEiNh@pWSFDVtVa~YGc9Et=%uOR1Wr*=RP$M< z=d4mlFhW<&xTcGkw^WVf8xnTXoK%QM1+;yV6XhMKA0p)gOzug3qb$n3O5-ZIPs?3b zooH6?TBIZ{0#CXJFJHxt1N)kWQTm3S4yCJA9JqQ7L-UIe0wJGHjkX0CQX4fKyl@rt z&=?S%bJ{?-M+ObBGE6?nqd zFq5aByaUF`GzgbSaba ztgTBO8psg>e&g`4&bf3plb+VB+ZPtC5t&Q4Yvd%uyU`)|ASF^=HC( zKi+s-%9dpf)xN6sKYAb~;8eZF4#2hi6dxxb4;)D+9ma719>qu8&=}?qdAG zES3iQ@nFX!j(>JO_S+@xeXX9+gHf`jxl$S2rGBp3+o6(-sjY@X1vPGH^oHbds3hGA zlhQnBFH+)Qk+iaXzHtzfqB30yqDGl+605gRp}n9)$=gS-qZ)^(N;{sSJ(|R!C+8%e z<N}~3eWuWY5BNMxgJ>G7et8ipxh20}Lp3cPHXo%k@xLUjqbi{Im10 z>n_}eS3Zho<#&@@@!o4Uz#(w$@PUpGz2wRz9Q*u2?Ajm=PN)NV7N+tyUBR`L0@tKoGapKpnc`?`BD^JpG3kLGb` zdiS;(Z7&WFf%!g8e*8Jq0W4DzLf1&SLdfTF(lt60)&8W+`Gb45=b~qIwdvU3EHP4N z4qr2Ru7;$cMg8B=yh!7G>>@ z<3I=j*WJ3e-KR~N4Dj4@3?F?Yu)GX-QNL;$1v>Yw>mr)(nDKHiJq2Ay%i90ZQg~n7(xfV{>zn zG-{0tELKM!%wz1qtiglDmrEl>Q8Epx+a)R=h?g-Xw_O?6NAq+Wcvz-VIDsB|l+S1+ zZ)uiK?GxhV4itlI!R1ABww?i)FJ8lX^)dQ$lNiYF#71oibE{Wj^Ax5Bo{xPG09GrH zuwGrlWX}QZ<0`nSH)*}LipLudu&3`(ST7yk3esdM$}r(rkbW#XfWA}?He<-!4pN-s zg`q=8apgCPL10(c0MdLv1~NU^-8BqmgtC$~p2!bCg5KU#9zCf%{7{$$?CqIq)M{%B zw(J$|``CNqChqK>ZhE33Dza(^X`4vRkyJi=q3}o zlEfV0aiXR6Nf$869O6^9LviXHz4j&y(1n(Y=eRYY7vDNocqb*9l?*hz)WV1ct z!xwZkHrOWNg?k1q&lfeg-a34EjS!hhqIF{fcPA0LjX870F&6Z)C&MZJINkb*_#N_3>@Wr%QwB-PCX z$Z>VkA*Nm@VU!qG3$ukR>{SI+738J0mx>Eo7TsUacuRg(r3{d(pyJVj{FL%INKf}j zbs}3pDx+B_fRvoB+Bc}TuHZcvHil;xP`7MUvRN<)EcN$cY4GVB==rNi1CO7ee`zVa zuBB4AHuR>`U}o-ffH>-$P+-ZBy-0<4?_1 z-Y`w@!nIzejmn~;qcCZ=R=b4CL-!OybEawZcg(WdBXef7CMDpM#zd{?#DRl2`uo2N zll;B1sPde{t?saN~mN{8)Lvt4DVTHLqh8`{A z_~++w{^a%yH@tFYv%pr*+)z1j`|l*}xJlSkmBqq01HLdWpCqgv zt!osansVUFJ#iZZ_u4+N*r^-izK*#@kY+X)2Vd0k~W#)LVWdwc>L; zZFSLcH&urRM(Mi5j)%2SMx!zUpjGu@SIZc#E}(094f*2wrdI(I!RS&6Djy6K#-`#m ziut1N>O7vhPg9$c5lL~%DR~IKkB&ptK0rO?>O4NZPa}y1^|T^$Mjs|gE<$XI79VT6c_tOFPVAJ5eHHyx`u#o zBIdUMM59c%f#;+Nkea*d>&txAh*0B+IwX+MIjLc{?Rs$P^(}krbLw?iu7{}6u&RqR zLLYrN2itRT@%Yg#>2h09s#e2+E7veGH{Xa%rE`I@uBK$PYh?}R-hCg!=J?Tf-%NBA zR#;oZOFw%r%-1vWRwIa-a|A27>+nrEAoCeVC7nUKS_x-1J-TkLXO!r=Z$6R#r%{2; z-IWN?C700UO2ny^4cMa2)Oob&Gjoz z8xS`JbUq*sUo!~gN+rDT^AGXk@4V4;j0z!8s#JiLGO~l+;Lg*Cy3;v!PNKvA!S`|F z-aUMA?FwFf{!H8N$?^k9q)|J;0Kp+_2dd}wW8S93L;g$E>aaYofpF6Gg#*soN681^Wis%tlKFCdyN}26Lgm&(a3zV)p2|h z;TzjOrra2GbuR`w^qbm#bfUHGH6-)1zBA{Wq5D4}bTirU3|?9opZxr%u^V<@+&}?{Ac< z7Fy-jUTyq7l;KzKpGPd}IZ4k!mk2@fGM6_hV4>_d_kHZXaT_x`c5JH~d|g1G%Itfx zgpIEJGcnp8Tzni8#tLAtU<-liTX!Hh!~I=5H>Du&UM*tRoqHI4IM*-&kziZ(!tne; z(DMvf?%SNir za~4-`A#G_XpU2GCz-Su?JUy><7f>j!VduSj4Z$&8hm=_f712{56FtAC);0h}|G?<8 zBtga2XtlQo^JAkJnVlzXXs2AYd8+g<-rIhPgK0X0A&kG#_w{Sl&)ISrV{>zuYoR26 za^*h0_-Ai{pM4H{{PpuifkC)N+cnKT=gZTpH z2m4{$cA~*HrA#V?69?K0kydvc%aT9MD|@cj}j zs~eo>5Z^DPCLBnmm~KD6ybSxDpMrhz3EU%xfgk*!t+KxkWHp3XG;EgR0DJc`+_@t< zG}@NN{yMm9hmt^UBX=aNF=jb&`RHkwkyZzW@^|ySRxcqcT35T0;y%s1)!X{2VzyR3 z)!#E=d!Pi6N=g;PNC91t+5})od3T6{>*!9Z>Ji6PNuR2m{HCX4(fA##vm8np7p%CW zGxK3y-NOUu+Soujo5kYrP{KEOy41Z|MBmCX%9-qz`17&ZIXHFYB{&X5o8v4FEGwZ( zbe0UyFJNeKF}$v&Q}CG*V3_&#KUu=)>^uT|#ZiYtlz%D~k$guP;>&}#)c9V{U*;K@ ziMCdhHRrHty6xj};sh@GPN?HxU9@5HnIO;gV89abNz-4-N9q2VlySUSFO$EMIm=R6 zLpiK+4suX|*X0UBM->&T(Ya0qFqFHL-lYNq4r#c&^X`4Pj*X>(esoG*YwI|0?Hc+Y zKM6xT%eBVRRI-i!@PL7ZCtwgbc(L#Xc&0ySsk!Xrg*sl-N~cvOIrJq%TO!Bj{7sHr<|4t zg~whwjKZ#A^c~(#xdWBinDQFc60d{rI@H&X=MEh~%5l(J=x$lQDaRABV@=g1ed8jW zg$G#s;lCAr4T`1czWKBcI!O+U%EV-Q5IcYLo@UTx!P0C-2DG%`K|h?N?{7fhEpc>i z9)dGmIeZANy*0ywp4CU}Bz@vMkGU`$72l*@e1x8=U-<;WSMIBM~OMHLDQ?R>7 z@0l3Flux%$ou&^$0M{EB`m1+v_*oHS44iX#39h}y#~CUWf!W#E$4{X?Dfs?6kQj9; z85aZbSRn}?2f4+`hsB_H0Uz)r!u@wepM2LAh$mMeFpzR?GkZAOJ~3K~(0Vit~t*7X;V5fr(AoD~AtW z^-!p;HF)vX6z6fP)!L;vLdlbJP|T;VRmtmE9DddBs}|}QXY*^4E-jHGBw9!Mb<90n z_nI9Te(DjH)Uo&II5iQY!cQjhqaMWqO!X|*;&ymHJ$-a;AnXr4PukNu*91DI4Q*ZY z&=fae)aA70x|EVM> zyYAdW%B|tTiDNDMycr$5aupNz9};iYLFlcFBaNRGcPC2^c+^YBj&92N(t4o_@4faC-uPEP2KR%q zBo>y^Q)y13#x>n5Oiq#RAyi%(-2-)LgSpr0(pez7#%+e;kz!oB?eT2-RU`cftGwqY z>_>WUNf%;It6$d3CH&E!{we%_|DWME-uinOIJx_&lmkR}1hL66wr|%i?Ax`gtrDg2 zTwK}mAFo-ktNmEtd)P>2B2D?OqLZI|h6|^TV|HS^qc*fxbA>Z$437AnRk^y-`8%~z za$+rGhqBP1B#V?rTP(ow{70YQv(u;WXmn)T+PDAeb?mq|(}-#i?DBe~0o8UiT1ERN zZtSSFj=^RrxLySo%YZuDYK@UwkHxL6iCbS!zoF)o&1O(4mEgKhCyHh>T-*G;Bx;Vg zX_+#gq&+pcZgS_3!=LJ19b2hXI>wE@V`A=T9q62;JdJuzTS#p-qqWyLB!zHwOhECx zA8N4`MpPWO%tOAT@-v+zQ5!Lxiwd|dnNxte{BUhkd>KV*EJOzCck30Rm2M&F8&sN3wnLD?W{5 zZXr$f9tT2Qq(IuvW3u-s_7A@tNlQDUFE@_<+!%Ql4=rT_d(wUAP4|-LaRPevZq)3U zb_sn?396!JucD$fQ)sSWi*DLTmk=t9SHAsJo^it@+6xkXc}7dOoAlnHy_GGM(Yw5Y zmAi#!VEK*5HO9JLne=R(Q4N#w`fOFtcL^D%ti8w+qEJOx?MQu?MqZ z2rG4hLY`y|1RBHh3t&Rv=DxjH?d|EfEw=08@WspUg$iLsML{&Am3c-6Kx8}w6gPIL zD9T(SD0r4R#0xAtBYjM>nEOdgL{t>n9^pC_b4-cWgVXUDG{Nxx??1_A?Z}-i5U#(}R7+D=)*?!`r-e%os8+ArV z*4Iqm{^(k{GK1wO%g7y?z{o&zPo}2uBALvYU@{}|)U~#bJvVQ)G}`W}GW6WrzyiD8 zvC($BB)_^2FO~RKil{s&53)fINv4FFcKaAeW$|m1JGb5YIRJRv!qPxLh95j?oKQ9Q z$7I1pl<1npU@-?(zXUF%YDolPp_v`#D@Eg+r?eR<^YVQ+G|o;rBStyRls(b=+)aV8 z6gW#qYToJ03=E1}lji~R^T5bRV89Ik`0O*_Fa81;90b1eU0`yu!_vRHWZQx9yBRj? z|0C~BgX~C>^sp~7->Z6cpbnsbLRH}?+;^i7^f}!#J?Ab*(yopbS4&c)=?_gtnf{0} zlSw9-mZm=vWuo{~W}@_iCYgz{<&rY3Y?ph?bkFoPJ$<2Z-**8h9CcT{D>L*XU!=Q7 zMCLo{6@XoOTQ#aOxP0&o)Y$`VN*matH^#=uZsHh1_=YIU_{1FUTvkZgKM4U3;% zPBuTyhIG*QJK?Ng?&QlNNJe5;z=>-lPo)Abo65Va)#=aIt9s^#W0v%>j28+kmBX>}80j~-)T zWVq$cf}w>)?7em!TOT}X;6sY)9*A)ugB$;f+wVU_fEYcs8kViAS1Y}}xVdK<0I)XD zhp^r}x()!W_V=SutYc{2T(QYlT%3*)Z(p*x5@BKU2yX1#(~`coGB|+S)4NdV?M0zh z$DV7~p%I{#)=CFj0%)ua^x?+7Jsod08NONW>w|{E=%YE1`HReA^sVX3o6Dv-KbPx6 z$|8w?k^W`g5>A7azP-&DB3oVufN%nktJG~BocGV0?mm2g`;Q)B^YAeC?cCLJzIOC1 zz#eC*1K96uY_a*tQ#=~q+H}58{pjVk+GN^ge=q78eNTz(&5;6DnMu?f^BcBKY?GC~_3op70<`9)0Jo5B4qZZ40^&12%; z1J=g82-~jpL>^rs>l)odV8Sv)4cQmr{?r6kHVwkJqP0@%z6yL~ejasBxKdf};9ETUeoBaY+r zAab{9WCR!)QJ9%oA4+W*7pnp^lH10z?U+&q`s#9@QBHqa&zgmeRoq=1(h4L7mTgVm zxVTonCk*UM<#YI!ngH4J>{jyj+26rDNpwBC{pQ%QNoRtF7;I~vkzS<1Z-Z0~t(-gk z8Gg(;u{p}j~YVwCqb0!T1jMdV3{tj=dBQLldZ)y&+GQY#-Vn4sX=hfi?@R$tljIt z8Y!yV#>{*N&y+=XdinZEYbKew291;T-dLj&GIs%+Zxli|bP5_BDpQV_)cfT3rqR;a zHZzO&AN?Gwg9G^dtv8x|5{FKHa~fOk8=WU?a2S5Gm$V-k8k$?g`+xp(AXND1-FH!E zk$U%DyN>A_H?46?*8CT*pTgpB{z1mKKK%@v=9a`UKD!0d=0QITn@8~Nt1m%A<>K_k z;UWC&M?Xks((Awa90N-$h?tE@YSyF?wu_B8)rv)Y@Pqg9_D7$hSgxklFdA!>e&v|i zT@82d%yjPBpExJt$eByy_34pZSGHxc&3EnAO3e16(D`fEFu$~jcV2#_P0) zUs(Y@_(0>m_Y^h=zW$}8x8GLy@=FbNk?eD(e7v0`2@r;TsMqJ=!;ze_a9KXy&T4_J zH`sF9#rHPP=c`)QE-^l@hjSmf?v?Z2wls3Y&5^v(+mW_ITIo#5JOE50(*WbCO84K8 zzGieZgXCjNVwiM1!ZmsKnBVC(SWaAT;P$7!cJ$ydTM$mbArgi2S8c*E7 zVOj0r?K0AkqZx@2&DY=(*JqI;93CNPz8jrwDzno`W!ML_hx@i;q;H(1a<^7|;xE5_ z66m`1+QTWIxv`A1w*Bo>>e+)ES~ZzPEaAJ^<^Yfy!MK}>ORfolOkvvjyL)PBp`L64 z+nWgH&@uOH8%8v%t4H{Zl#F29sFu1VPaNG#kPqIamOmYCw*mwCF zG!&kUZ9%!OgtfkG1!U9G5(>3CcHO**-EP5%vzJ$!^(p@?r^Y46(9Fp4ld zzaX}fczt~9pA3%h{%b3gE+dno1)h}2_(|raGG|n4^UQ69FF(yL9|LZOFU&10;>?vR z0FolSSt*)f$l~S18x~*$Y+iQJ&`1a&W`2L^$494IM*v3LKquHhgyVt(2N3eVeOwJMsmz4?1n6H{#nE%;@r(DHUkTnWl`3VN{Q5Mi z=waZPOzRN+kQ*FY%q~9&=m`fJF~z?p8=zzz<0k347G1C+enI{2wJ1-o9{sY zyz+{|S6^w&&L-p131xxO_9+`Iy8stZK@o^Gz^=^71IQ8_6W7X;r*cMfle!H(WgB@J z@T8Pw%W_Rhx!wU=7f9YH>y61r<4Ay+_(j0lMkU0o1TH5{iRP(^8AG5LX(V(H>maY;Op03@r+`7#B&d;(YN!+t6aOXz$4wYX9=deaATI@SUf{-R zL;QUDv!r(MZ(e$mlu`;N?+BIpaWbusfQ_*2_*M|ccNujoYp(IH!H zzP`CXgIu}!cjLMa$Ef^ZWb!XXgw{~l{OBpRK6-@t%_AtSl~L{O$&G3?ys&`XH*Tey z0mjizAx>kt1khL*9mc}QkY{bk^%7bqiUM{u#LemH%y!sxdw1d>TkY+^ro|;}nqR`E zxh0Uf2mnIx2(t-+bjSgWBJ)i8DY9)dU->Es(Fqq{oT zk2}*lyK+O)ld&xro?pP&qbD%OXNc29plFIg+T-M{w8r=;3#ag}Wk(QGEQO4~Nt7@1 zxm1+KUb|I1kI$N=u>Jl6R7$;A85qdv=f+bU$EZaSqE@dsX;41ym!@(VX*fuwgek}7 zcyzRc|8!a56lHRo2}NPCC7gNBZG(o>#?aV0`xt8j{avxEP2IVNJy&m_cde2hc=9=0 z@!xyy-$C%vpQ2o?A^y$}K?fs}F^>?W8v+Jf4lXQV&$XM-L4XGn`L>r04)7Nie z>w{U=ZX4Ih@ilAGmQChg;@b8hmgMgT6XUqKZ_kF=Gl%ErvHSW>Y`y;|y`_O<33t4+ zoznq0^Tzy+^f{d0?J|fqVjX0XGO{;HsE=Jwl~gZ2PE)+ z>sEkWY~zqhBgQ@7>zXMHm2>j&-9;4_gUyU$4>sW^(Y&y+4`V#12*3{W|G2{m^34}9O2Gm@?XMO z{9kS}ar@u71vQ&G=asFr#fOV&lx;uxns{{lfhM&HUR z5Sg1~=%6z{ATAx?8{-ix6v}nPp?!-0Ff%oYCmBI}RtB5np>xNNA&6q^zkC&AvyTuX zPHzH8#wl5Y_JQXRF%Y1oo1Ehy5b3^o^%WdHa~4BS7gIY2;aU3XXJ0ywM_W4&_@I?S zxm3azZ=Ax3Z@$IA;!4BPV&Fhks zMvQtjE+@@VSrJ?w4xnAksjm!Ww38iEIp zG56iSg}BgT@p^kq6W(hqMC;Lu@+hoFNl*yEakw3VEHCCZ0Micp@RA{pqvf3i6x(`s zVjHgS^G8}=9q8{$-%fmU23sCJhK_7J&5uv<1JWFC0}%hxc*s@bVr^S*eCDJAC{;wP z%Lo+7n`}hXj9Sa3HBhN^RKYW+o}M05Dpk~KHT3pwtZ|^XmjzGjkXn&}Zl1hZ*lad5 z)`RAUiz%nCeI{4dyR7#D zW78%D4cpF7N1bVGjG*PhIM0lck>?Om(1+~iiBnAJ;>#SNbA4jGhVKQl6e zq+vT4+!yw!bKYw78M`EDJC%Rg(!ke7v!iB8}#5n=xMVE>gKuu zIYY<+#W)U_&8p6*R4(J_+4E3Zv+?A;BBeQtjJQGiHRQ_irM0((ZP0Aqkl6FD-z+FW zK#QJaGrjI!Rkdqk0=t?-KjyS;^A`Np``_hVY8Qwe`j38u!jBK({-fEJ%5DyLmGzU|7b7u( z)cn11#FZW1ehKrlIRh!HS?gBD?+-v5FsZpNPWbI=e|JDM00dEt(ps6BW$k`)!+J@>@4d4`yV2R3c&CD4zO=O8sW{? zOE=e#x_CrWBS zqeO*7vyal6lAky&r@?D0F<$@V*RbzOX@`8#AEJgH&PU6PA(;h|h$O!H$bnXi`~aMC zx%nfN5!PJHi^7s+^zlEZ(p^JOmY?cQ<)K^)`hmdzM>GB3s{ zK#cj#!>E>e@L*!1D^82;(%qfOEgItw9%9ec8yK8lPVWKWZWhM=@o@V%9yB@Fnnkr@ z5$BH`MG(cCR z`GxdG1Cs47CZt(HGQqSg>y`+PeT{4j5##Z;F3eunD2z#+r3=u*qpNSG_$=Ce{ylJzf50RyS$`ky99}axbEO$WuC+S%WYM*rXch1 zk_~4y`mbN2@bNME%oC1~?4AZfZ%XtE+ScV91x|T{l@ooPYb8kwj5crnHgB@VrycU~ zI9DdvxV8Cwkk9$yu!LH}uPzTIy^ZHGBHX3d={s2OjLsqN%rJOay15&@BMUE6>*Ex^ z8vBO1TbVFy;?9`Zgv?Hb(U_#=z*yW&$S{s6029y!FuEN%i0eizi7kKl=>lH<@*A9c z=@=@#?roBsh87nQR-;toGCCR^Q%h#n*_V!^nsdrZD>tHbxm0S&aXO2PZhiI8e#D`| z_}Zct{ghhQJu@1266GoVeGqn4Wp0d!1wt9pnwSHP8`F-?c=Bw ziyimP(9+N*TsVFd2QFU5(9^}n>?r_Fs5#Cxxkl+q%7n-=ldUL};WNq1`tr4^>*ybs`f4LZ1 zVhlc8@}z1v$d*Z5GWuqs(P2VnNtB$scddfnweEPA?!0{myKme=X|;?f4cS1Po!X_a ziczc;Coxc3v*sbk&)mA1>@4uVcVEASI1F085wIDN{fLernN@Cww6ygD8-dzx-||+g z1nJ(H-i5ibQLOd%VQ~Y4N4<3VTWopw7(p#g9qMGL3f^ZMJ0opnbd+c}0Q@d%i#Nhnvxb|B4JC~}`PNSf~=bo{g@IISzp3}Y0%_mFq zso*z|_)OYdso*h8%)g{?*pAz7q-}e`*{6ZcUorS(F(MS{@-(sR>IlIdxB0Y|Oo_^~ zPm5AqDFWRJ0Zx7T1-^XyH7pDdBMyVMukut{WBkEGoc#K9YHBbWNk!CQn~7os7+hG! zo1gp&zx>{N0DveAz{6(-aoo73-KAFASgh6X&M!YfSc~9ZhfZHifp5?gtBQiKsT2F@ zmrvsO>9ZKW{{V;q6`Rc*g$TyL0jB;X#uyaQf_gH0lJbpv zzJ0wjp9MxR5NI|c1Mo8%DS+hfnw5a`jbyh#-U{{!#CG0i6B&A59IDmpC>ENt(S{10 zx{72|>*h+`nB(>d=uYU`o!j{ApZpQVzkZ6J{_#I(JAa5MClV(qF?M_TeDVSCEZVnY zC-&{=JaQi?gjsdEQY2F<>Ev)rE7#Yz)HbaV#4(db(rlJxsPMO%Ut1-kLr6f)IVe&8 z>Kfkp7r68x)5&0e|Q3AUbpim|y5p=?axf1@(GAip9?Q7X%?n8@Zb<>Pl3R zPBD6`fSEFA#PJ%!z;^s-E(3X8eEs_XNm8O89Lwj~25%P#Ndu__weonF%x8mR!}+-m zqMTJoItK^FK6uQv8>55sbIH7yWCBenX898hi(>=gwkBGu+>kb9^Q&mhnQBvZ#Ck5H z4l5W((g1vP@`=mTtZ!|9XIrLH6mX=iY6euZo^b<;`KH~xhLcCf=8=tjl!fx*hLf+1 zAS#U<49_nxJ%>s*7bTlk(6%z1GHu6gpH0B-ca~YH+}DRnUoR9iRyO53>&=dD!|eDr zY9ul4q|R}G`EarK@Yc&qfo8k==^yY*Lb8OoUDV@fqqmHgbhxkhC|thFr;R ztbCe{bo=^z9!=l4fw9>~jqA>N+iebHtT&v~noU}|`N;6LsXO-&=or@y?CZ#pSZR%s zxp}Bqr~H<4>6o>XbJuYGDZ=>$6!srQbo3=uMK2^jbw^U6r&7Vx-FxeD+TL~RHnu&O z6-IGsBlXvAqeFM=Sw`3n5g||-3nRlgbMiz}2c-27k8*f&b?u_uyNs3sDMhj$rvSuyS#K(#DKWw|XUp~YvozynC?&_=A zkX>%_w~PX&ES(}-HnhqoI?>8pY1nREd71^s%X}nkeL`Yj8y5#wI(`sZt~XAk4+rUv zHQBDH<;G=$-vZ40LK-Jv=BCm7+*F3QlO>Gij2I!6+kRU|m>$eslzD{e9R1etJqF4g*{`d;~L7lU*H)xy_@fmU@N1LjW81 z5;x03U|crQe6+2*J~_!Hp1ixjC(rzH*2d+wyyjL)&IgI3#-IaBXspIUt&S~^GfuKS z2O1t6#PHx?OKFKWQy--b)R2@zQkoHWQ)~=f&d0f5fFRO1a{dA?A3B(O;G$j1vh&*g zAUR7jnlLrezfH)kEsvjI>drmf+d0*7+l<3@|I!NL^f->~yhYNZ@BUSUGv`qG$xo1_ zx!H4_^IHvtO$$qyzIFpj>vac&*m37BHa~un+5)8WwsP9f<%C&TCLAT_CGs$Ivgcet zgxk}*aA$gFOE({^m!59kjFHFl2y0a_TMWmMmS9)Uf%VRi1|N@XUd7iS<+aOZIaC0p z3W#+Te_1IEfpwUATB0CG#w&_qbm1J+Gow9w6zX-2`T6WLN)?fK14cl`zFKSc<`B?v zBcNJ7%4kNM*YkSwWi++b{*Ax0aWH>t<7IzJiH;@KB3W;fA6v>A4Cj*w)z)Tg9&Y5O zZC!IU6^@7j^5NroIkzBJX8Iw2GJ8*(c(gn;P0!pmHY1mJaruyiBW+wQaf>fk^VyxX z27DOawJ^vsT-4~!a~mVdCmf~waJdri?Ahb$&Du&q^=NE>({{F~^AEH;7&5;UtI~i3 z_P5+>;KS%sqX;YmQpvD~Sq3ad!|M2 zAzBx(XUXZjS3my>0b-m#el(4~)hg|{a~DU>UO)|nh9iWzfXk;w6ZNcB@%=yh8A8PP z<#*o`SDoy+egpfjTuuKrxdUi?^xb!JH>65yWqj|04}nMvb=2)(vsOhF5US=%v~}E$rhAIBLNaYzfOcd2Y=i!Z-@Uh62quB-GAafvU-z%>B2 z$FUOd6j%V-udveJdGvfZ*V6y-GZc61LHO7IZQ$TRpo@{f`ua);yL3?DSj?MubAj?-Xl=)I(xW4DCc4Hy|!Z-*erCpKJ!> zp~kUAHS&|I7{x!5oJ)foptHVZtIw0Np{<21%O7Szl3jJIf3PMM#SwV8NLLVuS?P0YNaAB zA34~ys6Caw5=yIO1W__iCT3=!RE%$5IoXx+ZOWSSwk9d%AeS-RIwOs0eC3!jxD+L$ zu8)gkw^&MXBiY>6)3NM??}lu~n?nx9?LtAJjsg^beV4Bxh-2K{IfbZD*l_35^%AW} zew4txskNqPpMo+P^SyWrAvg3eZ| zok18yxODhXa?N^QYfkw=9Aj{48E<~}E7apK<$9bW%2h+$efXn4K~$Q+>f5IfO>KeC zz1!xoMpo#8!jr9I`1;jX)-|rx-X5$D^dqRnC{%0AUQ4vD0jJ3?IFFr}*WUt4S8QMm~@n|`Y_56!hCMF_d7DJ?|=0}Rq7tgA#{Xr%00 zbjYFI=F{%DNpholH773H=!v$TbyBALj7uOQdk*ByDgS)&Th?vlrbJ(D^pku8#Zqdk zBwwp|+1zD-5R~iS)%m#kD6gb;Z5h7wa-_1z?ir1`eIu1T;7qy@-+c%mgNK=SccynC zD!BGW1&v~@hMl+WFsr>pCrL0V0HEmGrf+nRBH_RMjxql@nLgV{#Nd0v{q^1=Zcp#R z?de@j18!-haA)UE1W}CX>o-waEvNOB2THiTXE$z7@5(LXS<(FH2yS8;&>CCsKZ0=q z1;{~he)A~qOm`kQh|}Y(V;ERo#>kU-n0vJ2Ai(WiyAX#Pql?y&g_hpdsm=QzhmCu7%*p%By}?7ey&3L1BJ?s(xbGyn`QEMWWn zhp;0Ex2xGnsqBs$8td#Ak!|bvk%*9&sX@%Kw%g{Db@5K@n2;c9|z)C;rexr zxw))V1!x^Z>o|AsISczXqx>1|!!NDZ+ez8k<+-wl>lJQ2S>^Nh<~QxFm+K8G{hPmU zrH7=G+b#0tPWY0PT{bp0`Qr3Fw`nG}Ve>B`TW%ALS>2lTk<$6dwds+3^P^b*bFy5L z&BKp$TPN)qU%w?ZzYLzsJhSJ9{oS(cMmCbPbq|v+fU*a@EJq0Am}xegjpAv9waL#H6*s{t zXjZZ**Np;K2WJC8l$;7abm0=hD8j84t|>lv=`yz8dw`%GBaUfn8{pBU`IxxhCyeAb zFm!wOuFPwv*P29zs+4;1%kRAh4d9Jm{Tii}HQ}H^7la}Gemu(Tg=0t3jgn?$(%hQf zjVKIp==>#6Yzgz#NIAW+e=n}@-Mg;Mo+u3Q>3817tDk>~{-sp}FmabOkZ$Gx=E@7h zxNKvRV$V5~CB{mS+^}`dqNK3m09b)o6lYfQxsO_f;e0hl>6KkFrpJpy8cC$>fAO4-8FLWfOby?hFoIxQr;~*Fn?q6WftMDv61D z>o*e^Qh-t@1idKNmr`!n3g^k*ZgJJZ7l{XDQCL~Su0Q=J7@k-~_&0wCnBENp0gA;U zlu9CG|LaC!m|Wczh8p+oWv2^*Qse5Zc0i`2)-N^52g*8Q{`vu+3qtI7{`Y=>EPmt+8k;|MqCL4A)1hs{p58J&F0v`O&9-^_{oy_Q#)MXnqmUiF=|c(HulI zTTd~}=Cir%na3TbRc|9^t^;$ONCS<-Y>jR3Ktpw);>>Lx#joFZ9q)Yn2^4_O-+AN3 zi*OtO2o+RBPJzbJ{@ar$@MLTEB4K~|#%p-(voA36I0@a^n)U_6)jFbT9YG;LSZZy< zFGBmgQ9zJdd1#s&WmySt`lY70Weu@XidrOg|5}6V; z(oA2yfxTC+;r@gk+OPT#m?!@sH2 zm~D#vj#e$|ofFpvTh%(-ZIf!_=EzSz(RlAYh2dfOJPZryeSsWulmg1-^135`w?h0{ z=r9B#$A+cZzs)U)A{>a05$iPo3URas9aj*?Ye}lO*0{QvNCAlA)r^8`jl=UX;#lUh z=a!3&vh|NFOq`9u@^LcNWozF4_W9dD@(fn_8m_Z9t$mKYZJcdyKFdBDt0;YAiQ>&~ z0mIG#E6YTLGq~8^gEKr=?utpNF2|&M2ZN=)V1FI^%ei0DpU#hq-L$^N?EvVQZ^?k>VclHcax$Hy+ov66FI&Tn}j*vxm* zLhU_eb3;|Vr-0dQ+n}Iv?a)5dGD1i8Rw^jgYuI*w7C~&U7xT@HMV(tXC{&n1Lgp>$ zLsEBw(=T!~C(In7UMk|=&M90w(B47kThqIfgM^Dq7+hRNA&PK!_l}nKrk^FvkB;E_ z{(T4lHbKe0B8}16r|AqansYbj?(Ft$*tE2S(I<044r~-j^u)<%pIr9K_ax;AGiUKs zj*88!Lz;slXNjNld+(E>QpcATE}HLj_}TP>&>%nfU#LacfAMN^m{TW?+b^75$D-l6 zc}(7$LBxCm0Ev~k7H4xoZcFBANv9x5ZoD62!CR6s9DnctGdrfb;^;p9;30~YnuDKh z$8>3Fl7S70yBQZ^dONVVg1uL+AqvB`0~c(aeT3e%as%y#;8MVMmqPFPub`Hfu>AIq zJoB87Hrb@i7vk20h0Vjbxpx|mwr%ZbOgY`3oB%Yi`^GH{%&&lM1GTLZ{D;=9z0b_` zJqqZN{C#uJ^fPnVHuQLW487F~de*7{n+IeuGkY^MTewZZ5ZMTAypdqGASfV;R?uC2 zru#CW{niCgD&LX36-u18fm-dwxQ(it6ov(8tr52n@Ni-R02HoW%a6F-3MF$f0<_Oo z5JT%Kw60j~($G4}m{~D+Xh7%~u`VZdu$hyMkGXc>Z?8X(ABWqRir4Gc6XZ@1FH?&Y zzWOLH*Cx0e^&>pD$5bEZ?$T0c(kbvTVA?5Bj+v1R#FI66Y;Cd+8cVK*L1glvG~quk z^=(At`&z9NNirkZ0@1g2OP8r7-j&Z=EjJGta^BwzE81;wQ5CmoXz_;hE4O@GJ4niY zrcT@0BFG&e>T+IQIV854CRI6~QbC}ajQ8AqEK$d#n&`jAN*YZJbdDgEIE`d`n_Qri zNo-VKu0(KHWz?g@oxP16v=GW+{ zR?)w@lB$V@xFd9k7?%zo#M3QXau?rPU!VB9RxD;3CYq5}3akA|gqN>hdj%&>pTXe5 zQe))nkOo9*XNV-ycqdnG)rv*j+c5+mOv_qyd(gHboQz>~$qU51f?JyvG&YJVBi$tVsYt{7A?m z{~mohj}zaX5fS^I7nOQ?@LTWy001!1-`^y)R618MmhO`M z&1~*!rnK*bb2ZSxOP4Wudj^GC#9$-m`*aRV5aq0)>%zjHo*?&LA73=UwmzaQ1!?wye5wDa~I z?7ey&J(VizEV?%D6OV*$8(jRR0qU{fhKj4{tx+>g<9SnZ<#7r1`doVDQ5F@K=dk0` zKfvD6ITU~I_kii$F!xBAjc&eS`&WUAjsDeYwcK>Qy+CsnfExf^%9dx@ly8RTZ~Q>m zS6fz@KG5oW?*e40O_=w7T|nlcIthsQ+n_`$?Rm$cN(=(KJU6dT!@yPPct?DY_f4iZ zk+qf87h964G?(F60GI<9xtns1Ll=i&o-qaN8VF4$<{D$#F zKbq(Uxn`^8^v(bH&+*NF{|DIpTW{ir|L1?+Vm-;XvuzYn8@jm9#$;B8iCLFClX|v| zhs~QjSGz2puf?qO@zCTq&7K)v$X#RtW?3?Aw0UM8ZF@M2li!?9Fisfa7vKNhhR^4N z7cXPS&AS%X;bv!=O}=mmlBasGfRM%uK& zx?Rsa;hF)*c_xjqPXaLpmR9iYFFwMD-~V1_d$vD#fD@49mdBq(T9s<(6d<-@iv zw(#f6!pX8cpVeLFa_e$&GRM7sylj`Rt$zs*^EX_RF!|-7Wog|oc_jw6?E*>4sKM_! zrs5LJXh5_%YpkP*$-o#n@agmNxb0LEWlZfv+n0yBuMA4UlfcgFD$r z)&AWh7QB+ z?5{|F%N-M=<557E05O&~4dU{l?0w`sy0Lc;0AT9wJrt`o+}u0eQ8^n;i^D^>c5olw znw@2sEAM`|^^oMHt(LE2jRzl{LtL$6%gcLF8XIaUUvrG^@<_64!Wsiv4wt7iM|m#W z9&1uco3qK8*NcSbCp+bK8)&ZkEr9$v-x=rqI&kRgZdvWB$UN$XDxo5%ZkzJ@(s_78-lKXl;|7Dh%ocG@n~>lm4zhlax8GZzq6 zB1Da&z&wB;*?eLBE%82J_GpcJT-ZpTc-{0ZmvQ9m1=I@#C}_-$j%FT)4&oT2Pv@Wk z96Emq{mZM38-qi*xSzg9u<#V&%na(KVXPfI$=b;exJgR|50FTq31i&Zy|XJ0+lKB> zO`xYz#ewf4#f>ee^n@G1Zjxl_1S%TdWwjmSVR#|oVfkvj*Z2r z)if#V(VMlsMD74)t-o+BoQ}8n=d1IdKE4yEDc(fOFYg zPwLRx$>77>3YH-Rkw4JiU?p(RaeTRQr&u1vQlMzYX^KvGyPfU{QhS_+b61bVfEUTpbK?7DNi_s6H%u?ly%ZvbDwEP2`bOy-B znBP2t2NT;-Ddj8Ew|DQtqpe%9<=URY>smeerOo^`zDRO*5BVX+V_zZNJVsk!`w?gIlAQ=ObYBoQGS{(z6 zD@|*B78C>l#?&ce|Z%>l`7j#=3Jj@9soQti%t#bg-fC{Fl;6ZQ$`JYFo{wy)sy$`d z<-Rzi8k?E<0JC@QA;y38|6uIer|A1f{{^sbZ!2EP&y9jWp{J(@%gf8_E(cgY0B@CS zeXO-S3AJNhNdR{PJbUW&srqicS>W1!Zi6JdM5%kr-?)COtv7DV2)=OLUgmV6uM22p z+c*^Rt>45*%F`zfKpbKbh~?aYn}AKkF>`BRKYN$qB93DT+L?z%ou)ilapZFr5@dMZ~&Yd`l`%{x0N7~g&y^zk@hO|nY zaQRn>5Vq{3_(#9^0IO?>(f+lg$FOf__ph+lKRST=w}%jwyK`tWx2}{^%YzEZyW}rh z(#bg6S$vJ(d)B^gAZz(t$uPkcJ>@5?%fAs ze)EKpBgWB-44YhL_@x2FI+r|*I~PanC&tWK%g~xS1Wk$=f4m-ilG<*R6RyqPcUzka&mbGovq<$1kka@(4YR_ zD4qEVbN|Ngp|WEylMhlx0Ne;oZuc`&lelzreHh-RnW;%Y1BcFCOq`xlCmL=xceO*Q z1<841Mt)&r7^h!rEh2rliQiRaXTM-6>?70UQDvteRiE&)^zVQ*+ z_pgc9AFWvPY>nuwV)J}T9x zVDA3VEG?`$xUL?iec-q{`8!6|NHr&0^4nh|TR&@7ldbppZ3xXuwZF0Qyvb_~?TE;H z(vh2^9WDX6EtE?{*Lh!g5r8{>`DIHat=c*?*)3`vC)>E+&1>sA{5kKfYn_&Xm1LA^ zj+Z0EMTLix<1IOC8;ZgZU%vhtPJR9bN~>$=Emu*f*J0*`f=+K`;X7%hA<);8GuPHi z$<{^q+4L#tPrX=h0&;ai_jXLJyNqW+HkaZ0Zyv3#t)W`4p|{wBz9xIbl9y^ItueT= zjOD?>T-$_>B7FW|{!={q@+yAvhyN9J{q$63TDMN)&(I3_WE9E0I=-T9hi!wkA$sEby6$)MY29?(i?oi;skdCg zu`}mTT3JJk0Cj<%sWp;wQ6F^UyBhQi@s3MRvaA%#Rh;_l*9f5TWDwOY4 zfPxzGa_GQYmd0B7qQB#53O{ac1#@NRwfDLuzLI!c;(H(F)>i(kmbH$#r6ftL?~+Is zl5|RNwrqtdNgkT!(wLC53`>#lBC`i=DDgLyw+PrM&2J0!jfvlCU_bTCd_OLyv2$%9 zvW`ymh-~a`<9psZ`JCEk>$7=njMKWggp{~heou1zx7!cMaWN^nD*f|@xOGr%6IUFl zEcdhcz_?ElqOA(QYU`?B=86yV_nqmTSlQ$=U}_ZV5e{9r#5Qh7bQ&m3QMQw^P2^S+ zk-)?kq#nAA%?9CaU-`Me7!RkmET$dkE-`pqN##CWuAYgZy*S9^Q#WNZr#;!=YpCbbPOEaLID zF_gPtz~E%Qsf?-Xhbf#fXRSgxceHpS#g8=RDVBzWOMc6>^Bc94o5T!bxrI*Qz*r<~*Q)OGgeplWUyUL#1*V2QOYuxrqVHl98h^dt2e6a_kb07Nzg)aV%DA z*z)*E*ZU=5nSsGB+~WdF!JL?i({F0NZw!T=auri|?x9$#Ar1muJaV{gu(#*>4QyIi zN;j#cxluZ3yYP}5&m^#uJXgw!I1KQ3Yz(nCN>J;x*58Nap+RhF+#tZ)ARPjv%47cJ zYJ$m6axF@49?+q}g(F9Be`?~Hte@qb|4dhEt?qS=Pe}dr~-{AiDei!414Gs(@I#(aG|SzH()!5Kp_#wmy)Y_qFo?viqD%eoB`QkO}0-R++q#d?r{~ zV>3;I*A=reY#vE(2;dt2!vPfMNl88l_me{tv`s-^*=S5LBo8x2z95y?1ipPe@-c6lIB)cWeBX?5LAwiHeTD|t)ZjBY8@OE*}91pz0dMdJV<$B2Ins z>$G)4i;E414{DFOMaZ>n1r@-)30PWK zYg~>Tccd}T>cv7=u5!L`>?jVNzl4#;3+b#$khzO(4F4jV0AO^OgxksQNz&19y%^9y zX{8K)s7RtJq;BdopLnc9`_6<$o*0<>)BhI(@BJ8+iQUk}9@sYwatniemi%5Xgk2d^ zPPJkYl~OP3iF?f7&MTWg(e;^yVyRH;<3y1ELjHF|nv zaEc%Z97k&a=gRqi(z-HSBAOA!A!JGdX(BcheoLX6J zsh$jonZxZ(yhNIP*%BxaX}Au#J`Q5aG?>`9Xq$u26f#3vlgz#(VI{dwyZ_Qv>~BQf zc5Nx#`X+BEFRs<_?gt++M_id6N@0F<1fRY0R>ytbee)KkuidbmhRxAWBD1FRXRsFk zCq7``P9IzE8heX{psm0SHmwW};FIsXgYSOu3xu@@p^h6?cYY*Z${a46Oprl(M<_8) z-$jJAKxxa=DDv z)m4a=C)XkDs8ow+Bz3K24u16`;T0Z&NB13J8K86bgVb z!zMR|4MC|A!f?>S%Bt}`o49O=;#Jh^Pf!Sl(%Y``^RA!raI+s-$h>YIH?>@kw#{8? z96T2<)rWan#oRs&X3%bI=`tJzQ%wdR`;jcS0Mh-z{0>c5okh*DBcd zU=}y_?ZNHcyPn&LIUhY98v|lsS^*=E=Nk-+wx_yH9Hc5FR|-Fv7{|iMNZ0F1%)-ZYZ9wK&a5+8GynUj#0vrTTu()T2Yq+qW4G7+s4b46IKW6!l4 zxVd+FU4R+@hUXVBe*b}&V{(XTD>i&C$R88`EO8hJD-ot{-GvSVTt0NLEq=56<}K{L zaSMgDx^n_r1EQTgCL1?FDQo0OHI&=jru15G5x4g3#_iqfk3hIMG=v*__CRZeZFe8S z97Hj()`Eu7L8=1)%_1%f<>hGH;VKS8+}^!w-E*NGTH3S;PquEsj@x&^rFPhGYcPtY z1lZKaghLP~@u_&-rUVq$oy|tSLgjy#TrV79BTqf|J-&mnum22#x6fhr)!)GUYrpC6 z`;DM_y^c7J(B<=g8%mou16n7uryGvj&^2iL+v*4!5#o3iQDol?QHR$4<2hOzeUSn1 zXbEB99uo9J75AC9&7K)74d{mCDzoLdtj`9=l-~x^HqiD1qAV~;tDj2YTUA=L$E*Vm ztZjZG*QTvSad^dbbfn*1K98AEkRUkcYXsZxJ`;n{2);N8dG+6&H9X`~Rwm)myGCYE@ z*$8L;=YNTzo!fwamhZIfqgLn3cV2k~pZw$@rcWKg)cAM{<;peP%4!(w@5j+o$FY{< zGQh{$Q+pEg7(A33|nu5mC&?a0uvc5>lH}>wq%;Y4-??1%0nOP+0 z#vF3eLWbIFoZ~c!8L0KrPR7xmac+q*vtu&7MQy#bG_(n|o*uy?TtNFrGa3rgMN(BR-e~9{yX{^2SE}~7N8FSd>r8;e0 z9y*eAbLJja*Vb@!U+a<1%_wDQO@t1qor<*=kmKd*0o|de3k$e>>n7fMskI2+evQp9 zuU);R9Sxux)V#hdd~R%1<{)am6a7#tJMaMO{iL} zIT5$wIN2cX?R9O9wOS2pYilSL3#lWv*-Y-uIJ^)9f#W#6wpKX_Eua zt}QGKLlM!dUXP%Zg4P-%Bg0-t?<{)xW#HU7jg=I#7NAtrwzIWs?`@CrW>>5$2viU3 zHQuZ}fXg%dh(hM`BU6r${njX3NATAp@syGOeuVDkHxh(%GHL1O5|m>wY2Q>Lx9kPj z*h%XEm7`gHskOKkU*fmf7Anc{?B4siiu=yhW2jB*LuuLV^V?(msc1B9d%3@KTf?+< zS3c@e8?swtzj0TbtGkmEqeO}(o%uV2`%SwcnX<-YJ>})C`K|{!?xXv>q8QC@cy_rSFOMO&x5`=e-;<6Uk3n8 zjBUkleCOS!d6egywbOt7&(A>bUICgoZQtB8japd5;jU>8MdU`ypFUwv6H$w@$Gu$JTT+IiGo^1-z_$`O9b1^qtO9^*`}d(*=)uABmtkzu zrdD%s*tV7=BO`f3mK{)u_jV*`6Tdh?njgLME|xc~&r!72Q^W^9d>`NW@FVoDR+uH1 zyI-3->Jv;s?)V&2bIV0?Sij!bhY!<0XK{m*7a*gQ`t><`pIhEsMfPTMV7mX~Kf&^f%>eojOE7DnOum5yh*GJwJDx+mQ)Q@mP<>wDDA}W;;i(t*s%7 zBCM{iqEe}#TrQ)pug`n?R8m&eITUTEudjqSjv^jlG{H+BW(TXWi9!7e^-UXMMm zo39>QU$AR(Q`+cEN@jY`*BQ4bN*%?;nkE(J@k*qSsGAV5wpw9qoPe|!gXNPti)OzY z8EtAz{tiU1?9s>~(xZ4^?QfHXdbuQ_vCigU?LG&%#kn1>+bk{l9!lBaD~Eo!Q<3E6 zPUJ40@awZ~UC-ImMot6YXLOsMmCiM4`^*-$@rVO!n&{lsFGPeO)VQ}}3fB+rZ5oj) z3PW5ucmP1+(A!%nv-X)ED#L8IX=|~OsZFvQS2?nc1r!#AJ2^3RjAi7aqm7ffIU}kpjfG)?zy&# zkH0?_8y{sF;Q-v=YF~mCqgpEB#@;<0jj4~8hBjelY625?XJBHq@{_^*chd$sW3bT9qdaZ z{pEw@Ht|z$0$Ujb?uys!M7ou5%pk0SC>*1$^L_%xp4;YzNn4 zq(imadaBQ)C$h{TVL#zN6NOdc)r$bZ*s*0d23M>jM=_DD1#1w{p;V>ijyRV&LV zee)RxzW5MxKlxqMC#Qje!7g%b@OtFm?ddV|A794hZ!cp0ca||wD&gdz!%fGRes4}m zo5+dE<#|3`B%7X|y@d<^>%T(p$N*0LgTI-ZcJ1aPT>8gUOM?^U^WYXPtg zWz#~Ro$cAui|yKT~CQ*JZcEr2s>20L+VY_t{t zsUE`LgXQ7&fGjMS{YCTmjjP+ba>tmF}PE3bxGW z5gx}t z9KVyq3DUJ<_DIp#KQqT=ljqbT+F3I-_~bnw5gCPDD8}mXH&EVx z9C1(-^OTdcanL+T_JJ^Q+fGmwDtDoJX z55M>|rYEPcd$RRI_qH8~$k$Fv+pHIEO#AHmo8e`C;IdtNic8%Z{}^%XMxah>(RFBD zMYRe%eoW6Rm1=s6^78Tu%H=ZRI6@ePSX*Nq*a8mac2^@NpxlFY%r&x9zd!NQ&p= z=$#NYN6Ln8xZ$Z186LA7ilyh+-?nWh>0-oU6qsj~)owm+?)+`8C+5F1Wv=JDbMl3| zlRVX32exkLwj`@elSf(z{AE#@K0iMjW%KYna%@~V%FA81({?8eqP0A>$)UBfq*0$M zKM=!63a9;h%v=#8=t6)86Wej_#IZJdn9$soQLOcqFto6Q-n9y7p_$DYY3{Hc@xack z(=)(0XTwU*oePbd;@p?MoLZsZ7#a zQp=I1=L&i&%$EQ(TH*G$&&XdoveBn-UGkRoHj=8e$b-Y13d!?b&zfDh8L9 z5kTYN#CX$4TMHw@xsDxq)KjTq%i||(Me^eWHW%VBG20}7G=+Aa(L4T}^OVkM)AAB_ z-MEFm<+aA9vMZGA8eO9<2hzM(wpklcag0OfE+IgSLamOK!2wVDWQ-4=xtPwM#9`aL zGr{KgTq?*&C$53R{xMYR?ZMmzTvt`=?ZN!mC^kJ_0zbmwGaU0sZUD(S8Y!74Duj5v zZG8?Gozmj)5N_<vGyI7JD*JMYlqUQ+3pc)*Yi>ucsU5aU3CzUBiko z0N51AF;-Sq5k++@EG(wwS1J{+5ujeLBM2gljRkn}gemvBf;cwOJ|idXrPf9iOg3|N1V}Zya=9-F|Q% zK@gzS(~BGT?j{e*HR!uH(R1k{F3-+jwJeS1+b6a_{q!(YhmPd!9BXcM^G8xL+5=0= zn7DTz_opU0D8r?Zxp|B|e3arTTFFYxQvR=kJr`Ul#CgBu5U$~kaCEYv<}1&S)m-B& z|DEhYipdpzp)uhn*%y<8BBbebTakLFSPfKf^1JJ_O$R@@p0KiM0JG!U&@GzVJc`HL zwqkU4E*)(f7299fbx$+=fUj(w{-5MG9b|p7bqtHcLtX0!K>UT<^33Jjge!>`Yw+(L zG&G3h+XX2fHd+YM|C^bwjGoyj^YYRY^cRYl>Kg{x8pwr?V`1)Yq@fVbJ;A1*{Yxyp z{bQ^hdKq!CmyI_kpUjjJw^bV7wiVUgt57+cby?)Ei)%SPNx42*9uz{x0{Z)#Uq`%=6a)%k7-k+=Zbp-n zKpZPvzpnA*N%Qp0h~`HG;}X?g{>Cg&%8EY5sU6D>wadl5`B*uRzsdJLu9@e!E%RvW znQa9lL_?Yi=|V{JxL8iJ-(`EXQ-jF|7~G`TdnuE%Fjn%M9H!)^Hbfmh%Ksu+n!L>u zWlg*V@{LZPy6DLF<+H5}vMt*B+pXVjSMs-Se)?pZjm~&^u4ZcYgwIMhKd;x;Xl;9e z(J?lXn(G)eN}YX0iI+JprrW2G{>!n263<8jGtY1C+k-pPJJ-D@Yv|6dod}``J8#@& zPK{D`&L6ET%M5Qj^)Y}(tys)$|JN5UU}iSiQ=Qzp6|WpQ+HwD~D5})(=YRcwK>a^_ z1#kTDZEPLgj7v9f;Ogz$z@73?e$?g7e~9CosY2+z0|1mmvH9g6Ik9f*wx#6Prq^! zN54IXzNIqEtyM<9AYAPdSqTgRrvqZDu|F8V=pqyp$0yZfxk$@2H)q==s7MU}03ZNK zL_t)}+vb^h-uLy#iPQGM6L2*IdxbTl*3vHjZ=c}TU){j@zCP^y=_#E2`~ObMHMrLG zyf$QwQ@fUcg#P?@{~^kc7jWwL{|2_dm+y16^uPQPpC2AY{da$eeLL5G%XOCh!q#ux zwWAQKB4S-dd*71tO|8Y6OM(YH9Zf3oA=6Uzg)|*Y!@Z+G6*fpmPuWMa*{=uYc@9j zGLg0UcaoL^8)J4p>!{USx1^p(49@W;Sr~XJTq66id^56pZfi5y#BCmae}XJLV9N@L zn|V*|FKw6Y!|utuu6iWpnOD|Be&B5@+j2+(_FRH^smQvneg8juZyIY?cAbfR`%~vLz3)Wjk)W?KFapgBS>s01?n}rbdD!KnH0A35?E< zMh9*n>2%xfZg;0G+mhvyRFaCts^VOn`8e~<^SkpoJ3r3dcdfn8KKGtGum*K6;_=>l z&K}mD*SGfCYjfW-K5|`ITsrZ5OMG8DdISJ4bL$Q!?>|JcP=@l3L!v*w#6=Bm4hZxv z=VyiH}Z55JD<+i;+ew5R&Nik9X--A zuOXVo z)Kys$8~wetdA^gh(btEMjvmD;Kln+l9&BxHlDXWQVyu9VLZ%BBPsY2l`B_m|!L2Jy zV7!l~Y7d^eP70o128X(~u=T)jJM^s54HUnmGPn)&Ut(jU8d@ZgNCdskb$hD@+3KCE{WeJh zKhlHeZ^836;JWeTujn2Vzb`cc$5AP97-vgMPg93kCb$mgrO(x7&MJhRcajCvb8|K} z$2LJ>JKPEbW;&#!D+0_|4wOF@UE1_(sgg=pm)rS8ja+@usAX-SEpC4>>q!TpJWLd9 zHc3ZZ;q)nw`ee&bJrP<6noI3+g$)$z2#S!B)KZUHRl>a5PM?1q)SB8`#pNU;K1q_H zniHWuV%8>?ptpN_@L+HI3Ufu(H9z_50dPpvS!20d{l}YMA1};fJDz93HcnIAa+sJO^Lwpc#WUQb_wV}erfeyq2YV|=!*hzaMp*$+8(qG+JMn!sf zc{qWw>;UT@oD;&r>bWbWK<7`AU_9H;+_Zz6HydJKbYQ`4)cu@qp_@u?X^^$kb3D0$oP zWN;9b&yiA+1grR{)vhFY)t43cegS|3j~P^(D4X9%RGVS7gR5$G3kV zSq{kp0zw1^+m*@^5{VsfoW^?F?rwoz!>N9yQb8(}La|t^dGY!rDUnFP^St_pzdi=q zy&C`oDivUTy%QmEpryFG$Yo9^P`7H`F+i-F?z70Wz-*f!K zXFr_}GsW;PjyF}xY9yLEt1xEb&-u4N)-Xw#X{&U6%X%BGUvnPgzr%U}js|RL+Hwn< zu$t>|BQmkBnZA7{w&kHCUH+Uu3zx!_Uc+e!p#L}3X>_t>ivXkX%T9VkBe;M zIDR$v?x1gVLo+hf=TgE7`pRT4H6d)XEF5*AW{}NCq1w|`DcMZBDQ})O zSRDRT*GnoM6o1MrT-jOB9p~z3qO9&ksy9I>t|?aExg!C9_Bd5Od_EVo5Pa`8m=iih zg-ixpy}ckOPvq!HpNphcGhrz~uT`Nvv$+|Q@LUJ0L(v{@Tcy>(L3o-Gq^))BG8oAq z0>Lc-3S0A*;a*r(eNivEwy}ttn}O@#fm9ZsADL#Y$M5Z9p0#USImlf23B0aely*(S z>+Y|!HrmV3Dn0+rH?aM3fUElsw61sKw;L0Md29YCrk!Sf{dJuE;6vp58XM7`{EaW+ z!{rCq%;lQS$5y{#iP|o=sWGI>osQ)u-r#_-Uz2`yO_b-Cq1-R1RD8dLinjp>2cF0Q zg81;Oj-zaR3E^n`NLhyOZvjZa5t&eUFwAXI;AD!@^1Lko>qsPqfe4eqK)>N4l>++v zDQ+U+)^r~V)AscApsOp}^dWskrBVrrL>b9sXN;{oLCIvIdMkJH^La7}oIELT^{PaR z=d7OzY1l!QAd#|+^3Gsxl|m!TZI34`?{tZThlxhTR2Ex!j=d}TOiMj3#fe%NX!43#SJ5pQg{f72M6Fd(J;IdT>h&NhNfcM%a`5N+K92re zk45!vwt$Jt?Ro|J9sVALDD}39Dvw$6$XT-$kwF*qY{f7|_Na91z#vS#Dku-3eNucb zxKapR_~iarrR$)WY5zp@odYv)Jr7g2XKR}*+#8R}paYpRO4g)QqVPtPz8S@zm9lBb zCa!DvG|}Y`FXQT^k1&038n1r-6?8RWG;3E`*~xJn^vDD@|BrWo-~BD1Nu%v%)EV9X z(d$T!x9gS8rgAcW=@$~%1ynvNRc}+*4yorhVY5D%);ZA?uI3WxLtXN$0KBL|Y6YJG zGV^t`QaAuAwFON1j`FneVB;mo$E}SerA`pF8lcnBUN(U%&mXH@<38XD+p?v6cb$WXCL>nR%_-w$CtD)7^iJn={i^+>c_d4Uu?M?iXQHngzzPfT=@vW zX=S&{HO-&uVh(=Ilq!+pn2xLf{KP%qrdHyIO&!cZldaUs%ph#AZ5nk)sV{6ISXfyR zcbzO(DkxVfP0wQ-Gz*~0F?sck8h?CkQ*e&2ZJj31^N=qV(G%0l6o zOvSC=5+oNHsm5N{W z=9Y%z#80P@T-!LlUG6qvUo-p!F*$hUY1+e6zIK2d1#3(|Ylle+t;Om4HUMoZK6oFqwY-fFzIt#8kgMnwx18fRWV?>*lcwmorhXel%`tiij-_=O zm6Sp8X=8f}>-QIc)jU#%M=?4azU5O#LTv?mL+Y5K# z3W4eFJ{;}o#p8u}4DTGl(%LH0$yCT_+YthvJ9!E?c?$1cxs1n;9^&x6X$%hxU~_vL z&mTO5&D=JAbpAulu=@0o=P@6Enm+&Xvw z!}EdbOx3b|YwOtR?MAU(Z%+~!US7tLtJjdqmrzC$>TUr6iA1T4!IjmvH}-nAw$Q!3 zZISbJZ3x&Lp!%&-8~3Jv}I%IiY8?VyHLLc%qkwVkk@$ z-~wfgOo1#p`-~qSoZ|vo7P?WoVo1AJ&mk zc#b>b(Ure=7x!<>;^522apH{^G1wRFo%_MwJ?PrXVRGxCHSc<)+BJ|f0Oi*)=(}`% zw`v{_p$ob-(Z{1VTCr=<=FT~ zE&XRlGE}osD^oM8RQ#~L-Q9TQ`FMw(yR%umcJfrLu=VSW#wC|ixnv*KN6@V0iX@7a z)xfj0aG}pDZgm4!Z$AkEArf%dt#-ahK!^mAi2*IV`V>fL-jGeLJOFqi3*XPdak6k- zeJsW8H_x(vwMxG4hYlJyOX+k9<#MI%bUH!1cLRljgIl*ecwYFRNi!rw%6dyxGgMC- zWaJhRD=OVEPBvpkIN@wzxkN&G_-D0pDT$6BwxhgB@>?%$;>y}1xWdKB9Y=9x z(@5*HeA<*C3iwoDUe2Au{<`*iu&)5CCOA zLrcpTeL7#mvueE^nOnfU=_zcZGe+Ax78jAp7c@sl`ky&>2B}unV<17!`+5ajkwitdJRR-d0ZDk9MGyC{9Yaz z#=_WWL>jG;(DE};5!Wcxn}_T;n(uKg zOzy9}SGns%Ylx1`Pe$NPK-#1@F<;*S&#kjqC z_gg37KOIFT-T1IA*Io(#@HPPmrs0!i01{GG;JV%5tstwVQnv`36ySH>o-U*;!gU)vYj7MO zo3+mYhBbey+OwcUA^|BSJg|yM;(;MMKb7< zQr1bf^O)OAmB+KkHE}^Wwk^I*f{4QC^>KF?zY)&WaTmw)O79!aTS+?RToC5khuH$$ zzKolt^Z2$BhxH!jb5pk=t)cldJ$`dN#f(8b1aI`VqPn#4$J63`nLR-166~wA&bNKd zGwa3F6_AA^=cnFkNza>@Ia>ppQNm%PDJ4op6pl|}^bH??nlTENkT+U>Zcf055I&Z6 z?7;aKUx;1Sh6Qo};d7B*nSjuDAEtsXJh|0VMXA&rczE~K&m&*Q2sv1=0>dmfk?7T6ALD4|b}x}t^ZNyVncM^~!3)w$r^mtMqH zZ);bNbK2_Z!B1X)6>og!?dsT6fSSzIx#6=aLjV?dee1A|^In^`KnG6%Knj7i;Q@T` z(&@I#Q6mAs5paBo1j^dEZr&^T?5z~!e$`Z889LA@ciNuzsv&5OG&l3@VAAv;<|DYm zihC5GaE?}6jnpq@@m2f8RTj@ac!=9~XYrL+Uju{yQf_SEV)9@Y6KIyODQ2R+*CXlq z@Cv0GzxCFL#pPxE;N7$MmAAfvL|6QIRPn-%(PMCij)Ia{X}6cBFN+W|4F}B}3X<%9 zQN5Z<1{>bKkL2C!SeibCl~bR`_KqEZp9@ZQ`vnLAEG-56=JR>YFnfDDhhnjad_E7? zb*)C#>2%84KZOvr>z|c@wGaZ`-Q7r~qE9_%vso*s^*j$78=I(9JWNjRZW;KtLw$X~ zYp)5s{kDX~PQ5A8*STgT1bZ(NA_ZTT;mZ;nkv2ldbAECl(V#(r+b|>uZH7QfKfl$I!6-8dhi z?_pWhuH5`AQ)rGco|XIxHcOjG2w)@~eGn^7UwXQ@h%5i?9v0QS4#Ne=pjs2jkXsGtGK)Q1bchO@TFZZ15nrZ z20Wb^-iMcm_rQUVds~aRwlR;Lyb2c+NI?54h+2<|N3b)x2esq{WosIfyBc-lPJa5{D>k)`Z)E$c{pVs zo_0twm?e8Qws7p?6r?a$t#2OFniG8E^Op+4Q=?5wpKU|BwNL`Grb*&{pmh9XAG5sP zbi@Sq7k}+2EUsgFZ4=4y0rd66xh>5$FNe7_r6gSuU7tT;)I}WXIX91?AI@UAlEVFi zyXqQk6PL|m1+{*WZ$uw%tsOmZui8pRB5jHKJTp9vGsDx>_@)+=WP)1D7V=14zl8Ml zi^v^0f{jep9ckO5x*SB|_IyBSh_tW^vWq(PrCdYcieUb^AE7M^Fl zyzCg;wnl|{GGz}Qf_@Qd<#EGl^8EC9QOPretMvoZCJ#0=OX*N*LQ69&D-iDHJ6ob| zX-Mjb(@!}5v|&$sZ);}85AUBetJ#T@hmM8gjS=3)y5!_*^+KW4H&ewU_G zv748Dnx`n;RA=)rM-Y*&`{FV-Ur{N9{(pUXIQJCm=k7wd4hBw7W7lZdu=C!N$Joy2 zF*-Diy#Q891>7%e;7H%jT9|7a^BBntp*Kac_eME~k5*@KcwiqSfQs+cM*O4gWjx$o z#O|&^RD2&r-@}iW9@OF6!O@xh=+0(w=ivhsOC{{69+d9RW^v-s;TSd4K0Wk&pcFs6F5?8U)6n8F)(84K zVzfQ9yn?B__b|M$QpL6;R|`mtJ)J`-ox*l^dxqP)A3Z{*P=x8Uh+|w6A(_&#{qR8; zv+6#xC17A^^`63+MpY(-SAIS|ZRnO`626;lB0xf2w3Ervw_1Jm@oisKxGYVztNUOU z@Uc2Hh{cf+OB(GFKg?^FgLP=_BVt1N|{$AZ{<~v>abQJ)N&s!kQ~!@V~UArQ>5+dm^;Ae7@(iD@jc{ z&d{B$>N5>JqnVtrxv5{M-$r4arxSCr`_i2cq)S^LggST^bL{&J0+aiiWF{sWEk7)(*4<=Euiy8UZW-FEV+5nsve;o&= z_u=&yoAVH?Z(}v4u1p5M_4QvsGNut_;L+J-c{~eYTJ=bW{i&WxUcGdnr8u(nCwj}L zbeQWlo=+-^`XG7^04m1hYPw;h?`T_Qw^vYP#I|l&&c#Z-{|Gni1Q_% zeg$JpKY?lHt&GBB(U0%p(eM5N{;~THfc`9;Klo+*#?O8YnRNY)Fc)5|Je*p8?VJES z_v35$_SgO{(4B(w2fu<}``Xvg9dWgzyt#z6-}t}q{|^2!{>Ghu2siU=t}Rlk%rNkvcUJg*O@D-f>G#KJ)^f0H;z=%95|*}(s&o0 zUp@IfoMw2soQFT17MOw%oEHc9jO^eR%I0> zFQ}VCbhRCUWP;*!TSBMEgM;Y#DJ;QJn}n6gN`h!aHty?{$W%Osc?f<<))G-^OBT=E{0Ow`1faC3&o^sbsN*6 zseL%~clOl{bNc9WIDIsbQ^%gn;hWP(;lYJh&EwbhJkJi`1vK3|fvMifs!XRypHo!p zP4^7rK+hmtcu1fO2Oa>4;}PM=xW0$GGt;QF z-~mNQiBz#v+xXNKeoj@E2Qu3Qy!_*L@y;8chZF*(R0=XeE-)!sF5~Fck1#T~z&5oV z=$mDHBU;z#@L3{yJp+_Rg^;O2IOJz5K%fe7(iXOkJEL_vrb1M`1yEf{_zDx2a|zv% zzlH!G^9@>+la37md--|IIE(`Tj0*|Z^N^@i8upWNrGk(C>GyH|-~14J{@Y*1&%7F* zLq0AF)^SloQ4*r&WiAeV?tlN?7W1{QCpP6QtyOf;K}izI%M+nx-D{g_Iel#mw;+I8 zxqS%0m*~2B9z8$#4oYK_*m#W$wn_OPmKFKNfLH6WffgqCEiv|F4zBOx!!sRndI4bk z$x|GhPii<={iLjcNtHA!JIkeBSGnoEh{)Gaq_eA0K~`R4M_!A9w>Zsa<31R4O>+{Auuz zO(YY1#xmitRZvEvChO~aVT2-;+^HxE&8WBPsah{wnD~_+IaIisaxo31?FiYHzrLdJ z1J)FaOUi_w9W9j7$pT=t!1rtkCEI34j^oH++eBgX8IRU)KE}$G2gr={Vf^#)_i|N@ z=(qDW4j+dvU5bf6<0pK9snr09uP?2lSS&R(+79b@qw)^FS2eAUxYO|fbzDF%vozWZ z2n@F;x&o&Tp2iE;jF4_fLI9N_`v1TG8-=|GQSKem4i^XUO(~OWV!4)zK0UY?TvAbd(gF+2Mmt6?SlSi z`f;Us(d_>MKtd$Zl^lX2QkK+EONIKQuDbvPd|5)-+k_Af9FYQ;oslV{|JzEg8#n-s zy4m@&Op}ud6pJM+Ew#4~Ekp`HrE0is!=BBNsZ(pbM#S%}^>K4_UQs%Pdg(=D?l9+3 z5(mfJws2wG9ZtcPx{mwxLsX_WXg(X6CgFVb;2Jruw^b`3&t2!H5nic}*KKv9uV;Fw zcw}pj)^T}s?z{|UF7@*Z?>O19a(FbEeJae8de_7bU3{gNNv$jB>cwfi0mr+%8Ya}K z_4IYqJ|A!Z-|d{&N8fSaI}Xd+EQ>iU+Q17R3Zxt(^AcT*Y(!E5<*fqz-~ThnAHELk z>B2kbKg8pO`KHS^Gr0%jJ9glm^B-!@w|?(5{N6NvbpAt}y?hD9QVHcs1voSe{N5|r z*xJM&|K(pIUnuB`b5{Uv0wR^D8JjgjW^Fd2xCYxn+60FrfP>d=!0~-N+OxYU9_x|m z``r`(`EObTqP7Taixh1DsW%QwPmNf=`pz6n_Ws3}1+dU+=`an&)hC^XRZ!Q32f7rP zHpcy0s)|qDTRkmg<^<12lD@14p(|P)hJ8x5Pqev7=gaBpov?yJ7ZPYu=3zLzqFSMO zObWnnVf@r1=?HBuGv_m>YJANvKSS*s8Fn}zrI0dt6SXp^IJ&Au(MKB#cza|7*dd_yYx%}) zr4n4f+}+)cuC8p$o4VO-7WsT0fM|PT_|rgqnv}8#p!Hqqz<9nrWAw1pXU!>AC_P;} zh>rrujg_UQj2{Lkx*WjMF;}!8v^2^UUj57%9E^rfMDx@n_=R*~PANUQ6~k6$S~r3e z)#eDL1}66DvH$FsL_yZq>X ziYG49sVAI#xNvF*?da~R@R3Nt(*HEIMDw(;vW$QA_Fv=IzxuPW!t+s~Fs2WQ>05W< zdLFJFJ<>D}nL+_?{?%WjgrsInZEl`QIB?4qyz$-dLqOsuufK}*fq0wUFTDRD2A5a0 zn{$-$wr{kpnzzH(I1_RX*9&1No({(p3V*8OrK%RyHM^7tK&Ini($_4tJw!F-faWT- zrtp5Mys*(>#q{}J2UU8*?UM;O1N~Q{`I>Tu3y82@gk=G?l;#`0P4z>Tf1_8V1&ptLjAuAEk@wDJ%ZrJw4wXD}Hmhk)`?repbV z*+p%iGkHMyz=9B@q;gZp`$#GNnqzr{ki9P$mKe6C-J9-T-QN1o5A*W4&B{dZQ=8= zF@eEB;Of;5GKeUA(N21edVACui4Jc^V2wvtRN2DVTSuUh&0psBCPzgkuGYCyIp}%W zL+X5R6iqy-HAjHfA+@@Nxl+9AGcJ!C#dB-K^?C6rI((-!|Lx!;Ld3+CU56V_7of`v zs-5ET7LBRZ_h#j*#(MW>O}(40qqX>>m-)txleF2k9AygoJ<(riiqNBSqLXwZWM(B-D^tCPpz zRPRnoz=K5j6K=8gsVkGk-th^{OinfxkIS91T2rG>=i#|7E}yjD!WD<6Z{Nl6;xfaw zYEP7$wt0})d-pydfhW5rP);V1>yGDS&GkGCuB_tJ2j?NBI=C6!HmvZve$O}^h&1nB zw(BqfSmyzu{Z{usk({oOuBd632)~*dy|Bhp*UIt{OxjifWg`*b6}6wNZu})jWrWH& z3i4QNDnHHWW-SmdQhV6#)9m*z;_UzON0@l|2!5e~(RMkR#8z()vYQc(fI7fWZ~(f+ zJ)@od_{yLBeh0WP_ld*&P!A%VykKucwFi(kkUXyIZEMHXTvp@G!QgpFF3ux!`!)(+ zJP1FP*2349LUp|p^~j(fAGmP~`K~OU?3!r0#_G||`2|efy@yJ5ZqRFr_zdf0b$!42 z=fj07J@l_{U~O;!UWaWF;?ko%lSmcIn7MIBN*@sIY50Y3 z;Q2*3P7gk7+p4|~tgi>R7u$H3Qhv$~Hh;P(l}cf3YzwaIVPyr#cTg?SNxU6jyVRT< zY~xW!wc+r3Zf0EDUZOd>bN##81+eEAon}2=bV-Kxr}<8RDeahZ2%+n+CXgfSAg+Xd znL#{1dv)53(dj$vg?nS;(KsuGep{Xf6U0lSut5>vmUw-+OkjK?*CWCY`g)g2lyka-+ z1gu6k|MB-AFI)jy@+2l8rGppWJBJG|oJ6hzUc|e$b9nyz#VYW0q5500Si#KgJ8*pu z_ow!@ozL-$m(jnv0cBw7v*FD*sQK0(2f8*v6UGx+O^uYS+>n9$*fzuQ6m-&;JC!rf zm6j`LWsu+ozO-ct(1tjNS+e>p*oHREGU^crT0!dkv~9Jvg~aRXJ306 zr_Nn~DD&+_fU6&DWiZ7a9+z*E^7qZEvS%MZ!sT1HFg!4T&z(FKD~@1%hu;CVrH)#T zjHc8%d)2N&+nDD4n}m*>C$Un>BkiWN&2T<8=>7ryI|s$;IXC#Xts}vh5O8AGs7}e= zERwy=_a`b7ai!J@T|kH@95=IpkjSPmc5E8IxH~W^&Ss)dcL!nj;pZlY;MiPQG4fpp z`D~W0+FYd~B6tki#uS0*e`Qz}ysP*{Y!;sa!a=Ry7*|oLzUfzMG%(C2g@u3v*U3PL z6cTP1_{fs7D>%(6OeI7xYx0)xWic?oc6yL-bt5GSRCx@Oy3nsyPS1z?;4aENqnLmF z*O4DP2)G$*YYG9luCM}UAp#?7$8p-)%vI_9w27;icMrnhe@qYb8#9Hp=4 z#G|OCV8+zT4vllOynHR>@9HTm>}2v0CVLvf;2B0e>UADYljm-R;WK==uEJ82jbC1e zrfQbANj=q!ndY;n8w>9s<)*Q3xVf8!OlqW@BlV83)-V9<>Kev3_r8j7FD8rt*xR68 zB2=K{wEEs!2>H-&K3ZVy6KW%*Jq7zGNqfg9@H4NzhW9RCiWOc!)^2W5o0-8aE`iDK z#Qi52dpw7=p#hvf9S;NaZEWDhv*&6X!Ln*h9c(}=j3uhS$m5d(i5K4c0GCcZkL3o} zOTYNzbLd{%MhQu%4Q7vFW51d@$8-VNHfHEX1ie?Qes21w4oD$3LZjrl%7?ER4O3p` zs8Mg|8OJTO{)iA7*0Bu{9gS6Jo!^e-*K*)n@~X69>YO6?_vGM@{ zM`Yl8Ik-+1Hn}Y>e%0T`)0c0-wZau-7;M(rf=Jp%o?SvFG^Cc_SL{uP8X z_fz=qM8!k0Tt+$hSvSD1H^o`jBuuADMgs(h(>& zxH;9Nbg>BG`Bglt-yX$VuZ$!-IM_Y=5PN6uV{vo@m!Ch5Qo6q5AII}CxUz~fXWy^w zcllMhnH!1o!_R;zcj}l1&^>Si=32-5j(+Tv&_B89qT{GaBM_qriB;VX5cmEwzQj-z<9&neB^P^T#Myi%29~B;2_5KsBpso1F4Q zt)jY~g{P%!=YpP7ktH}tu`qm|ibD<@(cBvH@lj(5E1w50T#$JEb%C(zPr&m$6beOj zcd#FPT1ZOS_KjVNrl$o42L*22kSLcMhmT9G$-DK^i?eDphd1iu=5UJf<3>3aGr1xu zMh_j<7w|cp#}DUcj~zS@??mu$lwK96TxFWVtqH(W1VK+!skPH|*Q z&#oVjL#lOT=(jCR6Ng9Rcdjo1Ywt!Bx!QdkAp2QR{VI&t6>JJ78{K+vANT(BEadzq zcKp_>c;U!VYq+a-ZlgP!#XbP{a+|oeoyQkP_SW8i`{{M$DiypmasWFr0|0uVFmcoxdJk|LfiQq zzjPTp=N90Ued8KveFKtDAT9&8(NhFhsH!Ew^y5TORo_Sqdrh({VD*KLtM6zLGC@`V zMBJLNAEd0d_k&Go1@d{>oSJ%rmJKQm=ZVLnvXLJ+uBuQqvOdt?(Nm$)5m*}-6R;2RZTUb#|;YS;wr&x-8I z)2Pv>fA>LGl0i@h6B-|`q zCj)hl2H*g~G1`;rQ)pMF3wTZu@LV`f8m>c^OxD5(7v!^7y$hEO67c;Lgh*;0yPKip z_8NxI|2dX3Yk2a--$ZWW5d36o;69OX;W!RTr4q6ozGm&SOhN#IgTT?FF0Nh`C>A@D zZap9wKMh@iZ8XPHta!Xp%&=;z9zYI<=VLlbO)QPDVPIn^ubztj9_FiR{v$dXAUm;=UXIC89c(XkVw>CJX2>O%;hvrV3N*V82<~Gk6kCn}=Z30W|szOUnqYcX4&K+K_UDgOr3Gx7Kd4&1l}B@u+jfTQJ2ElF~cUaopFRIq`0_@nD^q>s7rv9|et@$5NVd+rFf zdV1PUs}apDE#d5+z76?D7lE(-T+{J`ItYxmC4vp!gjdG!;xb-%|3iFu=7q?(V^8NW zbNdcNMM4xM%1EGs1f*tAt;^wpaKaXQL5m`7$V%HDl^1G$%7+K*1$@-M2a<2?(RXWOe)CtYiw%Lc?>A4FdrUNo`Qdo&_AaQ9o z#HQ!uL(S~@yq?3{iO^dU@5Gr8lZixAx0lfx>q8nw_~8|((afXw3&peAil;ff^Yi+l zYu7RH_-U;r!16Zd9?qLC-vwMM-A5oha19XkOFmwr)@t>hxBS5O-$kNO!PX0}ps?p) zNY6y(;p#6eKk2=Z?hf;-7~b(c^e?U9h4((dhcC5mxP9Q}E$p0MfLpAfQZ>@{SRZMO zkIh=)by*!*jzFo!o3EnC_k9$a1Q9~}<8xI!DTI#1>vFj3rcthJ1)GY(F4=w7$Z;}| zvV`y*F?LF&f`hpxecBElXEJG2Diu^J9ukR9#xtEst}BpE1IZ-txz7olJ=@;(%_iBf zWSF=XsFT!Ons(e1psaL!Z-i?G=}$6@unCSs0-S zWdmxJGBJjpe{`Ktx?w#)>%`@Wc$$=Y6n|E3hT`jPY-Gp%!f4BIZgJDJOOL`5#+FX} z{GPpLom2Gqw@Kb6mIi<~$B$R{u)_DI>Z|y(Ayxkl{3;H!>uHD&KA$KJ8P~Jfa6oVv zZ_n(5Shwwbs!0OoO_@<-N|b6ZK_ROhPnWRs={yQOS-kVc>p_?XGKHw-edfLQ(Y3w} z<@MTQ2GxLaOC_pu9nHYQ^Gi7S!Fil}^`*M`>{tp8PL_~@a!}+mR7`teL@wK(pHdlU4D?9uWjKuz&2;|bt%Z#shNNCvFCvBv{QRVvZDm| zz)gpr`Ftd5rKpFa!|Q2#baZ+KN2h0+io-E)Slby#r%7{y&uTOZH+OGs;d9@A2XDXi zW@o)AOWm)r06)YXE{DB`C=9Ja1b=iBUl4;*Eho=2^AtO=jbEEKB!u2jlg~)oXBl53|$z8qPCuX#cI-*n9Ur^T02va}YmBLNkJn zE%_5uBC3vfSKtS4d>)k!AM*LD_uj?9y;C@_XK$?VynWT53r{oLH#Nzst-0|$rKOMX zgp+|OWeLPH#0x0?denKjvpz}b!}s%Wochi$ySsrm-mvqQOeTFLx!@`;FLOE)~0%sd-m?l4Y|O4E+HIabwYJsvKab9;U| zmN&7KUPt6$%;bRAMj-d-{3!k_;5SXw(;dX4R(g#MAM&>8{Nd@&&5vCE2!2P0(|?=q z%)W2-=y)35wvTFk+yFazkcQvcI_Oey3s+X|Amb+Rg`NBH{e@e2WoQEZi9~JTjwjRt zece6S_1r#SvWV`1fyi)!eSJtJQ$V4F-b50+GkTp(cJ-s+OJv<-joV#aBj`^LV4`aW zd^p(KI}Qao&J6Fzc(w-v$#ihCt=q%TjURvmA6du2;od<=c-TEUhI}f8okNXJXzm`R z4ePE9d4%oCW-+yESHt+vf+kNLL^-Brm@6Crb+$G*_cwFv4sIXX-|{KHfweWv+`5CI zrIp%7ZIGt|!NITLrDg1X_y~_CcQ>7f>v=eQ?K;LDKZWp=Hz6)w(g|$+L^R*9rP?ri zudbv~#sg6G~?AvGn@wi^sldDYW5!P?VGC0 z)5MV}eC~I?4l$HPI>w3adK6Woq}mUZB1&mQ|LCf3YEMA*R<0K6O?IO<8H{Hi)VEdp zn%BLVAehFK2ysYri8-Q7$S2UVxs93IcW`Hab4ry))U&mPncH_DS+BP#%Q*#QSJzd; z^7-tP#;uU4BvI-_9YmAzEnFJGK6P?M5(y`Rq}v5lmDqfS0H{rAJ~!Ijmk^=|z^Qua zrcql9)3Mr!rqucphAw{}*|}NFz4i)9qtg&>>jnlw1Rl0MuQS*8eOf4ya3O?1xm-az z4j+bw1STecxjA&qa2x2XtlS8+(%a_pv+-CjFFs!41LWvDr4}B>FRnDx!L*$ZHO~1Q z5e2_>vm||m*1Lj$gWrYe$b@t&UEh6I3jhu+b&a_w)9{;!(uMmdB3u1tj29d<-qE;PiVR zz#NGxR3=|U_vSW~*K5@#UQLQ~YH}PAwVi6Ap4>JbOzpwq&XGudk6pTgWT9M3BfyHX zh7i>gz8!7KmW2N5VbmZLzs5P(tO@R8Q+}%j0^}&5d|T_PSY1-5{7ea6mp2u+KJ+

;=qXf^nOdFbTiD^TOP^{K>+53>I{{RUIvmf#!15YSy?-8;PCeiBhW>$@x3KHM zW26ej>RgjBHj@d*`x<}hPrs9jv`_jt>f6}B@k^I+`T6?S+%KHHi4Xq!e}c@8KD_yd z|2Y8QN9RAp;eFG1yfBa6?jG!8`qHgj4u5s_UA+0y%drk*)f-)^wt1g+;KQr_uD^Pd z_JyYx)q6f0iNRU%4Cy7#ILfpBA`yQKAsjPl@BC;QJngs6Yt& zwv&nNIzjPpvKb=Y+8BkCZ7J4^r=C+hQ<9Iu)i$K4zmuU^L1^`?*SU^{DLq0CeC`a_ zt%+rIzCXe)73jBX4)k z6bks<4}Sy?4&0KD3X%*nlMK$~Y6tv=)u6}qt!>~7-~B!uCiwz7MiaiQ8Gy$tn`a;g z!kJutj#}GzEQQR~I0$-MfT*47K9#8TFH=v)Qw!%r{{yNQQ~5~?V7k))M6JDSM`?BZ zted!-J4m$mZgR#;!41Pr9Q*9Z)O_e`ZmkFU_Sqdp32(QRPSShihy?Z-bs_xg6k z{ATJWxXu^QH7?|1ndUsD?FnLfMn3{e3AOb2n=mp@EIvj5cmD)3k;2k1{4JDvhajuY zpah#!b%{&V4C84oHhX1o9H@dMBm|~z&0_D}dswP^+;5eRUA}^`M{}CK!o<*g#E11T zymoYs$yL^;2W4{2fSOP1kHoMn&SxoGxK_%M001BWNklb zthRT-6Ykd1MC+zp!X>qO)cJM2^LQ~@B5fzlur8|EJSe;_(b{CHxG76?z-as9By$5W zy4ht!XB5~h7jS2D4yT9r0RXaYvQ~+@5ZJgHM~8BnFVUht9u`}@YLCtZWLJJLNEOJ}Ov86IR65PjCE;&~`l zTDu!URt>fV9E?AC3h4;U&g{cxZ*Sws26b<3V`P4jZAdF&R&SrKjcx3ieSmbnh;llK z2YdI#&cpRQOx}M8Uy9n5uk=To;N%%ND5c(Wsq|4mR~N!f7%HJoUaPaU1c>Q6Xda7G zczkkB)FMGAN6lr5&NeGWn7&mgp{}*2RP^)EVZg5wU5{07nv5&RRD2H~Ej|VS9Icem z>V+@i{OmwE&axqmdhgoKVRUZ3q0#ox@hJ=)uOB8VuljFk@l%S;p!X={4XJpjSNgSf zCN+$Hd7qh!`s4>He3qK7a^V~3Cf6p%;dOy7RT4<&ix_=6-*KbuOum4zCv))N82spp zG0r1bq}bjo-V-Gc(|7K6?4))pR8A&wZ~qh~?>vBz#AQIbS|AwZf#OksOcO~0pm|E~ z8S%z3-@N*?QF?72!xz7Y{#zg5>1*FWad;P!g2cZls#JhmwPJG0h%4N<2k3soKmWB?i&H01#=7gT|jV`tNaHS@fc(}>{+Vk+n zL-Sq&~n77FAbZq&3S}49uXz!D1 z6{XDtHAYPZz1nzlYN#qW^5`H@^f3N7z*jd8A8NTQlMf$aU}X(mn>o$Pi+(GL-mWC^ z+hj8t@f)Dc3Dy2U_ht_J?#@C;iO0L+A5!kw+`_>dH?d=3xn=;}zp{=4*Kgs@ff=j} z$G>@`73v?`ffwI87Avg2`9d?JP1{jPBrrEVYVBJRz|isvdN#M9khZT~<*KKvTET?} z0UwF#=iLJ{D0F48Iyi{!o@n%R?YSd3aN`!bwsPP%n<&#z)nmhk%H~WECH3p2qf{K| zbBl!9#-(dj)u;dq9i;Ds^3q4Fu1F>BXtP^Mxym0C#WIg@^P>%-R)Vn6Hs>jPe->&v zm?8OC8eCb!zPq!So!(cc9^+GXJBRMgt*TLr&`Kb+zbO5j0QER&l$hfqel@m4_r^B% z-Jb1;m;FQ6Zy;GLqjzni)+*%LPTvHjzkp2jK6wN;^*c)L;8LVb@&I%_kNPdpbN+`& zKAJ;rYA^EpkD$^!q}7p1S!z706@uze;c?|00o8i-wcM(G)$=htzl5Wgt^$t0-I?jS z<6RLMY?m}W7_U?A#6TL~IVl4hUO$|Y!o zE-e4aIowVAc+lSuEN&zJ`XtH=8@Trm-^CCA8-Z6&o zQVH(ah|@bsbJ(eEJ=7WbHj0Ot?N~FMXLx*?I9JyRgv(!_AA3GrW)WIw6Gw6VmzwE0 zE{IcOT;?O(q+{Kvbo8~Rd5Wr;sQIn+Ue#$H8>LrYS5$vxh_iA;Q_tT1( z>yu3rwbQOwU$=XbZiXbZ^XMz zHcFl}`;3qh$zmA}Bu58sKnZ9oEUu>w&w{8l;+uJ2IBlXj|N1789{;KLWAZ?PF% zS;dj7*Q&X@jN3qyqwpc$ZA+lS=5m!IM+lATituBQDxn4+ezklq$P2e$%b$-N6T#>; zV2(T9cR3oTm5Fo*x>lB>G``cWN?{sp^W8)}weY;D<`0EUsFdxkc~La9yn^R0Uj@g^ zVST7Mf9v`OT_OOB&*wf}4-)qt$z~~0EJOG{JZ4mEVnANUQ9VW->*x4cm7e25g>s3a z$DpnoscOQU9#n=-VEL^w$~}XS!i8k@Z|Y%54@W(Uj|9KA|G-D83%BCIsd(7=bOFcZ zWn4bdyy5n-OII-ZbRNQ!hG%W_I0LOMT#pf6Eo~YIa-bH6{`^PpAosui6<+yIei;*Q zK98IC?_qO$8+*pbaq-3ty!FbfTKEq>x{9l}Z(-l=Nt`%XU;q4Q&u$1QvG3+=-EgYZ zokJh?JmS?!JLAfS@5ek<+mJqsGF@XzCX=XCDkzmoNVRd(+OsmFa9v>M&ft*r2Oo64 zN5;Y0j>tgzCBX537ze=WqdiW|Yp!hk#>Ms~&W=tq%oo?h^0}cg<_>db<|niXqG-%;Ln*6wVA!1Mu+D@Dvj85GWM&ZvQNZ17;H>N5=`< z=9?QWfk5T4v;@YVJi(*MNtDu^z4r6tqH?8zQaPT{wtzW_RfT8-V0HY_Q}~X9`%`e3O=<{94=Pdl{o}#d}ayy9t9i}h|xa<$g5KHSPHAGTBk%$21ozSF9QJ5BYm;r@N0(^=^W{>M}0O@ zo>MPS9^&}B&M%zO@<(}@`RQPqD+bh7FIUn8wd81_eWSj3+F)txJ_q#8Toc%nS22DC zm(Cl_tz^u>4VMH2+>(ch$4^@F(rBaZ?QM)KEE*frq*me{!p*YqI~LY0xp8NDc&{C ziqfld7{2^A`ft6DjhRzeIr17%x*sd9=K(iw0(mHl~-Cn@vGLhygd*P&qD0Gs#|~_0x&smEMQrcNY6J)6?y7 zNnwHNH=B$^WP;_es$5?M8u8aW|6$zO3N<@V=y3x+%#!nZ{wcgj9*ViE2h(U zFtxW~y?MTetz52QIG#5Df>FUy2FKy{?JeR~p=+?di&{!twkMqyz0tjc z@eOA30;hZ8Rvefv0o0s9*IJ8O%CtQz(6ybz@X~TejJ9{qFJPG6V5X0K{Z=t^?$&XT z!f#XtQR7*a)Mcp!G5XflvG49I0JLSeJ^FMWneBW{H^ke|Ca36guG!|~{hs*c8XUgm z$E6Yz12UbF=b`JP_mRGR6@{ro$n8IhO5c#ipN`!*4(CVXxo641ID$roim#00gZBX7 zNMQ8we9$63Q0U59$A-!S5ZL|T5fa5pwb$xL5=c*`_kL;c&+DQiw5uQDtA|keiyOG{ zkG>O>?bt8k=DmAZ`tc2{-k-;U0OV>O;{8cvGZ`HI+-Y2V@BpWe9dBr~U0)Au_8Y+L zV{!3mSOy4FdssP|L{)~6Xbum5+R1etR4M|V=i{fvX4`dLIF4hzm1}$)@O^^G((Q=+XKSjw2=BBPKzWGjszR`+eh6}GSHUwiw;=voqVwl*B z-sz?2w34Uw^jg8y?WHg3ywz*otS7xS!#ZDEKK0gx#=W}!dPLvN_2}cJ&de30Mb=Ft zbo4B1PxzhzrNQN9zTe}+K{{8&)SY_}zHG{=QxvJg)8yz$Kj3K7mr+@0Z%&n4@k}=r zqk6}X!pgFmkAze4v14HoC(d8Qy9mH0jetTNi);11ZyHS&&6%JGVi0?pg9LJ?z z7e3a81~5A_1>beC-rpa|cOjEOzAFp2?BThKSF1OZ1f<+zQOSaKaMdk2p%Ko@Y-%>m z5kvb{it}JEo(!jh{uE#Yhox=9?ZPT6()>mo1+C+-R8-sfMtST9p9yKGFakQRj>7dE zPxEo+vziP_;=+fIiN{Y+PBrJ;tq~>4Wpr(A*KVq_^-#_|Z+*qL>VbUjFykpb51$tt zPvYc<7jWhIV<@)ic{Wk0;Q5P}kStcJJwAMERTu}EGL_CZ9Zb;smg*OTq#Yv_)IuxL zZ*>YnCFdWZ|A*g3_eYoT=x=`uej;u3WR;@gNzHuR!33(d7vUXzvnSYjDe+VX&=ZYJOZn)eY^N^U_39GxEUl|NLjzdiw^>KH5On#2_}F z8^Xvp&Y*OA5fA^zKgD1EK8>-J^>yU``2}oTnZwAhy#aiyzR`9uokl*Jjm1ZOj!pTk zo{ZGWIws-E652uD!EMS(G`r{AE)@#E`STJdP6)KH4G^0ul?pts{jv!mAcTPLcOGYU ziV}(7ko2ij!R=Ol%wh|X0^mVPuXtEAr+5tnSprar~jIPq~6-eHZ-vmQ=}O4EkP zqP4C(*XX++c{*X7&sT7BK$k36v4F+IFVvpGg3BAW%UtsFH;;j$XbB2NIs+ zpkmSDO8~u_n>cXeHas|}AW;*V{aTyq3K$aY^=W~_2PJZc^CK_Bif`XYkv38|h@j11 z64d#ptz`N#LZLYb;QdwyS>~chX@&DtVQnKT%vpUUq&=3MQpqG#jDcsE30@ZDUW*T@_uIHiT8UO zz^D12=2%(fGf-rDRmG+<`bp(WIDF+ADsHeDxx8Z-l{PG8`&ZYoXZC?M&)BZdqw)*w zo4zUpZ+I;f(kWa!dZcCkY_zepiT6Lc8rx`_^D9HG#78}#uYR0@nF6&m>W}Z{q=z6z zP;=o8%VtQ3Bp`i2#!n};zJTFNe~tdz?_+b{2|Rl9x0{Opaggh}@O{4k*+3@0dX@7} zCrwNM6B7at9stYB&6P7y2qYn8u?m{`e8YiS`_vpjZXX=0*irdJmCqc1rmCNZGr@Qm zw$i&OuEYH6fSRwS;k3;#R3`g8LMs>t?0OmXm8Blp@@S{G*vi{3sO~%{=VL@EAnNtB zsJ*C>_NtBzgTG~0kfbOkaZIjQh9$w{n*dmPc0C%r%p=W&) zg=`i=nv$08QNMp}17nZpt44*SM^IjU1{YQ^ys*qTG223=8-BLg*Bi@ddn=d2wYzt4 z{J_CjbuFMgxH{T~qzezZzAikN-V@8y_(p#p?(UyPIhlmx`Ivb4n8{xXtE!szY9^L& zfQNe~YjNX}IuM!b>B7|Ad+1+XuZ{yUDiuK0n|HYNsb~AF4hT~OpDKnz!el&4Gq&<8 zuG)?IW*C2>mLexRveEml2pL`we&;>h?iWcvVy+u>Q>kox1*1XVuv6_yw^T`_a|Mh) zd5WhK+V1Ox>Bqz{j1ym&1bJrk{7ceI%PrWX%vGFq?2e^R81JITE9f=Z(Ir6Cb%YV}8Fj zqo{R4H@)EfwjP-?avWKvZ~qu(e*25K{r$TTZw9w($qP?V-aiFjO32Gkfqg>|$Hvet z6F7SGFphugo2Xp5jARU*0B?VDo@kz^&1`SNn4tka7S(y_r_4jP;|L@Y?oXA6Y#{_( zHz-p(KuX!x z;qH2f!cKM#R5;z{47cNuo@O*3JX|cod_^+jNVMXK^pem3tbK+U9LSZU1qgYSkGiWZ{bqY?mYm2mJK$iX78bEYa6|5ThMRg4exd6vLS!Z zin6MxV~Zb6wm#d=RA=-YTbW-wke1$(L%#L?AE%AALGs z+eew5*@s+L7sj5>VR(r=X4vLZ)kdqsLv3M_xTI>3OQhv=0(TDXhpN$q(VZw{^!@Af zKoMTT1*E{i>o?(6xCx{_R#l7W2cCVb?HIt_nQ1JI>}bemF`dTz=qOU95**<}NLiDg zf#6PV)X;1okGpKIS4XEDrShIc?z}jba3E?jdZ24j#$SRV1^S4w?idwar%p`&)<_?pVOC%qY1DqUMS^lof6Y{R%Tw7i1J2MtMpYU2g3I-Jim;?A6>`ogZr`F-P+yLnL+^vZ`{Pl+yXqA zsO^JtpV&HYy57k)zp1#Y%}ms+KQpB$`+BO61Yo@cY!n2hhX+xZn9=&DDNWc$7wK2j z?_h=ra5H_miugPbO<{RW)q7*9 zzIi!FK)?|xcz(X=xZ#xAG1P61DivU10f^cX_I3mwLT&{!;NhcD) zA!*MOkP^6iS7Lj+QA%!gZ$2JwRn+DPu9HXH5fKk-Q@YXP*e)xExv=TN^=CRF3!`H* zJ$sxm2G+45N2uo79G;1SHynS3->VQN_KnsJwnyz@KRZ92!IPw^u%#Q_)@E38K_q4s@lyO)yOsOX%6!!d6dDL~6~^uE&qD z`{5(D(ZH1)HW;LXAmTZE&5o>+?3$m8)i-vn`gUQi6IAz5z{sp-3aq-j%ER61K+HgCY&m&zZBAd&j!i*S9m6lztWs+WVTsfh8 zP>7~dxs282RX7jVvE$5s2)0YMvAqS?ana3AE_Q?!i8`W@V!o5F%^&8QXV58{v~!?{2o>hzk)|!{+*7dPp6C9JE@#br{H;> z)eF~WnHlx~IzENLVW-lKGb(K0q+XgfZ(#NFX`~F$)3gI)S{1@8 z2gT#-C5092na%@WZ@F~B0k(?EK`)|ygatG%s#KTM!K@KwRCN&iB9%h zv%GeA8#fKEzP6_lC)H^6HxKiyRv=qmQAQ!rh8?!@6ILb(h~%6oY1+i6+)xj2{(th` zGuE;!I}iKzIXAqV>Q%0Km1F0eyJyH5W{MIu6le2mI2F#09$|!!+>o6 z5k%O4O#KjSQKTq}oKC||(>>L>s=F)as`p;KeDm4cKlWW`t-a4aH@tVNx`(qG)$iVW z_SreCZ>6mh96$RtT5*g56CyZkO{g$sanU$&(C>1;Lax>6LJJ^GKiMun_=U`pkf8`UZs2*9Uj5% z?b}hQ_9oz`c2FBl8pAe0Wqbrz4jt&pV4G-dd>mgsd>W-j1EppIvv(H|>jV;&x@c1) zDHQPKL#H<#N$vLTT`)@F@cD}vTV7AmHjMx&xTREt%1;V07PfCszY{T{1x*5k3A2Q5zmk0_%~d0BR?>G_FG4Qavz$*n zT8Glnn`4XvBkL8MIQJEjIL6(bJNh2SnZ5<3lrNpb$a`<2IlUdLkH3-{Y||U={)jXVGV?J$ zCPuo4^4w(UjvOOWH!H~4*tAd6NVw$g^C}>Fi-a+VZ;Zh6!tamJIqu3}y3_Q;B%XQx zDd_*~8>oNyyv^f}KEzW8j^XC7)NpHf40w7U)N4mDGdYPTPMrn-yztoLJ>{P_XW{&% zw4KQ3Z{6SNQ$PHhLIkB^81pwvSxPrO)$0uu3I#{b@$*W2dsU-t;2ds~F(wzkYpqeQ zH_&J_pp-(bX5}D$`k5JEW5b|U)2LPh!9q*|tv6syt^J+mkA~LGKoqcWeT+$54$;s@Us6Ygv7a=&@PpS@3JX7 zjY=Nh?ElXBxzfbE8cF`g{cgYc*s|Xll!qftrr+~-=3cO<-`;MNmt$x=LVemxy}nE2 zW9UxnGRwI$pX5uU4Z@gHr~D7vhTJhm*EVqA(iP|^!u1X}8ii>8m1{U~=?aD_HM9`7 zqv}edy3YKs$)uw;a9h~WRkp+8XMl`-+dQDQ0kN8eV%rf{t`v8#F#z^ozJ^l0DQ-|9 zz7vQNgS}U7+V_k?b$AFn?#^R+X~`L@PJ73LFxqA_N6XXJM}~0q&|KHsx$5OIt{yl5 z04TPaIB@9-3iYPgm#8IenTjy0jG=LFb{ba>AMD9sTT&9oxOC(Y0ASCxn<&*9?b6tx zl4q+cuaGk%6804mOLAVsx3dvy0(R0Ot*(7y^|n@jC~wNj&ejm|9JWT<^cJ}lC=VM@ zOW2s(l})&MX8um0+9ZC?#vpd<<*p@*r)3`zHXK`7!;x<;pfOa!wf(&ZJo0H~@g5Fb zyo_yk>DDTeqsh^9F+up;q28x7)VF@n2I>h7d81VVVE2t%&~b!IhYn(Wy!Ttp0bpdK zf`gYXW6!mlLiQ)67kT(Ti>J9=)JA~9gSn@fyGw=nhA?)dbcKam7`k*Gm64rTeCD~# zKJ4elzuPrIcN=Jds3F#oyTh6GTV%#e zd~{pdFFpJZeifhn`8iY$Zv*yD0C9xnfAtQQ@2mkE4Vb_B2I@CX0mTSM_s`*x-}@eF zdq$ykZ#qcHmHKCiJAeEhm$Sp=19=?%k~Yx~NZuCHmwwd~0hyXRq zeK*87bYkx1aOiY0EAfxN8$_6$Uqt!S&++k-k9Sl&_ud9()_p*qAPPLowo5Y8$mFBi z-m^>;^XA0aub_;*j;o*OR)tmzyKmmYL!W(-s#}U^;r$n$!}9dh12Nq0m3#(^g(dE_ zt<pV)fM-I zMXtt6Z9%n+>}^*v0T2>aD3BqxR7hv9vtq%4A5qP%lPhwT9#6h#zx1~$h_ z%?4il>vzyX0ZkOs9x|c^fIF(xI=`oR?~-0t{)o`{8ceLL;qjk+jJLk`>XzG4Y&KD7 zG#$Z%jOFIL6v%!B>`WrImYxwz^=GSW5v!2%#CCF?@hp|=SEjL_DJRM3xW_l`AvBvv z&76oiY+Vj`wLW_0Q+)cwqqwtcCz2k(MY&!_lxQ3|e*ychUT-^!6agdu<9`PL`0d~QO>Eyj+tqNJdOGjy?(|+qhDWt?GzL(-%D(FqwHlZ_|1<3P z@IRnAHjRbHetFg<+kS0k3VfYt#ag4*VHs_ z8|URIZ{#(pQcl3puC2m}l~#oOTPT1Hex))hfe~tU-`HBtFKJ9D-gM`r{r_yXDYl>g}8R_VjH$K-4IeaOSBe@YGK~!o=b# zqJ*Pq*>c*dvN*!(RM>HJy;8w?wE_Sr6^fYYaOLxzT{}@|weZl#pM%}h?Wh;fL=26} z=m;9+VmgZfdsXzuPj)t*oLXAO$+PDGZ7{xUCE^-!8@Cu|bZNdZ`pVAG5H_ak#(95n z6_UKdNF^>~E}`A0CN0yAqD`0GhT;@UDTaN2V{{aavXxCxE#oA?_{thsSr?`2P|8-y zl^P!T^fUa`5BuX$Cs$T*`tvU_y0#&dgxQ$j#`_#{8xeAd9AblIMd$ zRIg&_(pikZ^A}j3IE=O5{d+JmU7PJisQnmomqr@ALF^0=QQCfu#l-~8 zCLCq5Qe_xZht@SHRe&)9wWZg1%l41Km42tKMv|1F^X4EliifQ#>2&0oSR<<7h7>VvaNCRFkV_em8^+dcD}qIgoDC)g?rlVt4?{@ z-=e_p_iw-1%w8Fqm7VfYVqCh{p}Rc6m9al43dsoE-)L56=aRpkSvMq!FtRUOV%*FI zs?1Z#8(oM?Qf}_006l3qT8z@)mDYt3T+2NY|N_0>g9>TqC+tWVq$p9FsR55jLIb9!G z%p8)=*iW=(>`l%F((xJMa~AXXl3Th9T4F(3Q*!=OKs6cfn{m5~BG}m(={QTxKhj)7 z=M&Q02@`3jF6_uLzPyI1ba#WvY853>>ZFBLiFVAzIB9p?U(0K=x&Y#1!58puT$YWSM@swCKHdj}}&1Z+4tuh!R$$)t8 zc7vj&#@b@u%3J0nvUgkJ2f>goA%1jiHz$_|%EOY`{!zwY&&`{-wP$x%`=iH>pFrzJ zuVU@Q6x88uFh9Evyn6+hn*sjd08osf{@@v)6ywq3CotVdAiD9@HO$;w^46!E_r5GS z%VlOyp7wX85UCj2B(OT?o~!i>Lvb9TP$>M33-SfnTcK9zeMqyUV2nYd(Lgm2 zjD@iJ)D$o@1S~JJgvht_*LuB;txdo&8qhj>19V6#rcDhn5scAWy4^~a0Q9m%I_<-G zdFLB$hjQ&DKl@Hz4q41CpQy|`zG1e@&qxZDNfZ zDSX<7Wf?Xdx7)>?lDgHilT5~!A@rWMTblgY8GC`+|8E zRJqVg9@<*4pBgqw^Z30rJpKNMc=zQOdNRHXQKU7LF)$jb5}K4c5;piC+6TJ)i*2*Z zfOEt%D3b+Pn)u$2-+*dyT-^jR_B4rB z$eh}Zm@8Rps$odoNALKtxvZKkhHLJ_hTF7WT)4-nLV_-;H39NGz{rYeax;)BI$u5K zs&2E;RA<^wdH8*Sv;>(_0Y>5Fw||1SUV9bm<6DokuZ%&IXkq9p!KU(BBR^+y5`D>0 zSF(WIjfw!+y(dnRP48oX-OCPNxQN5&FQSEl6KPwvMfSeW%D8}<90dHiOM4v8F^1OJ zikq-+YBv51GQducYe@P%ob2Lujvm0>?XrcgyqXv(h`3&kYgWG#{b?w*3&wPyO zg?o@D7t)vC^?nWuP-vWeld2GnZfxM?w||1a{NWEeM?Ac+i0FTM6OCE}|Idm4GX437 z|L-3{|GSUy>Dpa<_P5V-`aA20{+s`ZR+8Y)3I+W3kA4%|r)N6WB}U>1WP7FTF2tk& z6jd3CZlDkiIj84$ohB}Qilcx0KVW0;30(S}{~DE@hcaolXp{UmmWst9;y6aVet(S7 zXJ>(Do>6$`o%WtOVA(?$AZ|5JmpZS4tXMohUl&aET3)9%hVu-G&a%W3?WB%ObCw*g5K#88Dv^gL0*oP9Do!yL$8>lKoyfXc{7-+g@Y%X1jn zsEFRmVn{~&?i!Ouxiki{KRGhAjAjM#ZUKBjIPG0zN@L%Pn+cwM_XE-UE>XTM6wne* zB_!9Aqv5to?jI7rxcjV}Bi!4xcS{_cMZ+nl(x_wT!WWqQ>pz7q6tVJqe?OS7i=kMy z=*DwpObpOGq}v40mN~{Ci4{q4kggYYs!v4SrF7OOowhSH%d_*rpDWZ?>{7u7RQ`&w z?idl228JsYR5vlFw@Q)L7_L^Gd7;H9$TmewXUw)T~`-EOtgntL{iqEum93>Y~WW74SC zl3J}+s?<#qjg5_sv@VTCvmHgtr6`IqG!%}aRVrCL9YqnMC`vz1<~UUC-d#YkSj4@1 zz?m}!Qs=C76|L4i#PI~;xWDL&BA0d)vi0;#95jU#iCOZw*=~7;F|WVBcX~fhzMefL zIOhq70% zZ>N+S_u3!fe)rRSHz~A^vJ~d3qy&d~R6-sc_=u1-I|ouq>2MjRE2dOw;E_*0gMvX4 zMQG*(cLIPY(Rk?7FQ5{-2`6&+p(N#rLJpA3Q~2k){LU_T9PbtBFDh*tVSYA0l{&)k z-s~HYO9M=_`_M)C%+34b=#B~*EcQW5Rn$JbjN9=J?0V@`$E2-70r$4eU~+LKEth6N zZDa`7=l0{`k;DCzp3*nRj{yMYE?vd`%hyoesHOc$Z6^e=J~0*yv}26H?S%y-Z60HK zV#2ur)u#)`j$nLk4Ld4#KsQlasR+-QmFY>Cg52{BmZqoE`sUHLg+&~`aM8{q157V2 z0VV;jK8vEQ<3gOy9s@a384*cIkFAGjx7fevZTZ=qhdP}#F1O5O_?THn*S2#^XI7K1 zrCpmCN3DIMd8yvO`09EpH!xshY93ju{~W5;aQcfc)0@P4rOA~Q9R21zrstP3K@Z$o z$^ZxMDq}skbeV|2ka zI_+wqUzPz9Wc%D115tk$o}s zE|r6?F>ZF9%mF%M=rkdz5v@@fuq!NYq`I(GOvn-1m0Zb{;hu^v@4)y}%46)mNNb$_ z>nlCcjyrd;@7nb=Ae!7|{5G%@DI@^`Twc39W~u~j zTH;g+(f#8)d&S{$#L7DZNkfQq=+yd~^I5 zt{${^OmqTAUp{;qI*u`S`D!`}1=x!tqBavlW(NhdoE}=9nZk$9KHXP6o24RN|H1e1 z>KkvNSZlVyY=l<(>NB1pd2j`AS#$flGz74$ebi?8IexH7VL{UFF;aU0WVkI=Lz10$ zN0w{h9yu(6uq!$N0RzCaO~nbk6F4yK(v8<%S2^yArC5{&XQeUuVgaP7XieES{HXO? zp|SOKJpb44wQCxu`TJKVGszLPuZgRy{gIKNEh`X|b(FJ5#&V>Ta<(9CIlu>47);516ymd6C+<%&(|Bv{$&-`QO_cwm}0ra)2FmIfP`S-l%PafTk-@f`U@yGx1&+vDC)v zqG%XOeRpoU_(h?K3E+o6RL~mu@sAC1f|PBEeBN0_CBRgnO=A=84V$6<#5z7ub)R(y z$f0-LJhPxPySC(x;eV2V+D#|>nm#kXh0I?Gs9EGowdA_G5LP)k`Ssl#4Q{8~%s$mU z&)&*Y&e$N(Q!Hqf>HU1Nq;k@zOqtziQ2o<8CI&VmS_SfiMERl}-#AnXoNb@Sf;VG> zY$Mc9T8ti>B9p;h_H?&=ma8;yxpyUa9LevH!a<@DZZ|nzQw>NN$!)W>C8I;a*=V;+ z^41!Ji^5~zq8~QR)oo=9$6aGAC5^Os1PH0yH~KZ)o_+c#e(lfyyT0DB<+l4LQaE?| z6mIPu(3R4W0u&G#jtEz#6I*3YNbs^x#-}d)F?s;sTy}|3lbF*mg#lIKroo zJ=*v6(LOcGCA|5)*YMiwZ=zhS114!pQdBxe2mukQCOLo`rOe0ZF3)Q~F_vgG*;&W( z6Q28oG-wZVO;%mgXNfE$rLi_Kf%jj2uBW!whKKOZYcJuoAHRuW-9~FI0O@Lqpb@DA z>yzVn_oWy5?%VfYcn;6L_dX_Ta#cYo*S_d}jQdHZ~Hc0FWeFP(ahczOPo_a2V~;XJpc%&#yPt5VlM z`=09S1;abaxiwQ!Te1p@3GVysmU%5i9@O>p1h{EBN()|KD~@ zx-mA2kDquPul?nlX)P2C8s#Fc96Hcv{g6RJp18yUjaCyxiC zY#U?nm+!xeTD=Ycc;(5baPm-RBl7xC8Ld(QQG;g*-QZjq8^#xpKZMF?|IUkxv)iyZ zYj0PJlLXJb`#wfiD^S`9{N!qsNne(A*=1BjM0Iu1HA%S05Yy(*QVvVBS_seN#can!U;RA{Km4RK zFJ1X7f95lU(KBo7d3>Z}IXfe}xIY5h0Z11jSyQ%W;J%h)&khAFhhXgO%AmMaoS)m@ zSs9nXx2vlx*Xt-Y8loK%L%VH|^9kwiq386pH_GRW+_^GXvM0D7%B`1@m`{w`Hzd^o zY}Vm+FvJ+$-YO-Xp+k<*ls+%7X0wTAv)Oin=5+OXBlw=yI(S2MrBcD_>M9C_f^&0~ zF+jb2F8dV65z6JP?4wqzqf{zqWC%(D6BFa0`9hbN-o9;c^=b^QOQ=*heWOuA6b&Pe zCpPWSZcXH-V9bJT4|<>P{ZMafDa)sK&o>V@cP=l>*>`*9uBc8pI*WywM<(7TuXYl1 z^Lb>P_vjb;CXvf#sDF8&@8I*@q|Nq6{+yw|{mVE^?v9*&?^}tqokyV!fhTfr0=f{e zx4$t!paYkUoylKN{$?3ZZ4}CtI$nGIO}zWk3utukg!bvlpZ*Nn78aor<6V{NGoU`R z=|<;auRWw~V2^0}&1cvxYh)ENDNqVt3lS!*HCjn`%cyGy=3o%v=(+Q0SutAef429}oj!#d z`}d+%=sxXr9OL})qtJ1LgBLD=nPYC3RpT;LBDU8kwW)~4twI6sz4$zy`sqg)S*w7B zCM@O%8EpeR14!u~Qid@+q4mVfJ$c7kvSS>j*X@uXDhrLII8kmpG?$T<<%1_%UuNjZ z*g~geN!6UYDtIN4w|~|P+7|~|ioB;J_@T9LncNbJXyVBaeg+j8oIQOCcX#gSdprSq zb=4zhJ_TA3hAMOcx(_&6D8*wa;iMZ`o8BkEpxo;uSTeARs8X$tSKfRJ@4ff}>H%i4 z6Fv0V7ubE{me>=rq77c*G#f*P-9DftcEc4Q8u&9tiGImvqTB;h&QhL}R0k_^pt3p2 zJI`HykAxI7Pwi9dN$JUb4xw{GrV*)RRU10J(M(I9hFs@z_OP3Jmbxo5`z_dmt__5)aX_P0>oaR5fS z!td-Z`!|D>QWzc{MzvbS$jC6lS0jHnNGa>#3;?gbs_@=>#sSJc8KaRT6@+G!F-;hg z6#!`M3J|QPbgO-B^wy|%K~q*-**)*h0J&4So%VK>TWb?cm&Fkbj%7I^aGb>%Qh@9G zn!C|CTy7&TGFiAKooG-1nEEAT0Ntrvzdw8-#8&F)zsEf$F%N(01rUeQm=4c7)m#c^ zJ5hMf<-aM@_lj-v$(^HIhAX~d9+DIb-iDrMs5IZigAH#XcR)m?%@S{tdJU}-^^B=4?Mg)}+& zG51Y1pb_vnI$!<4W7nPT-dn_9e|!eN`^!JyUp)MkDtK9M{N|ZUid~L%enLYW$!-s0+y$zHd%X@j8b^})mQN1U%!LV zwT*O6+j0%;%{wZM2Sprw?C|`II?{Xt^Pkq22CJ1@D74$hQh=;uYe-r|G3*n>XklgB z6h3^WKPU1ej`7y_U&YIB{RBgmTB`a1tXucJ*%^HFbiNUOH~Q$Ar=g6&i7&sx?yEN; zu^^#v`fT?#a`Bd@ycA&bUIB1yDw~RFzqzJgBc&_p3Pc2t%eKPks!T%6s% ztPkTxU&0skrBg0PGN~MZMqXDfoCOwDs;o)Hn4Gkd< z$c3XQ!tgK~XD=))qSb0)a&pr7T~fC*ve|5*TCGAUwP}NGz((6Hl}cSBh5Ix%2E6u~ z!t1Yx4dn+#p}D#>URvhu=i7~3PP=>lS$x$EpZjYy^gN4~^RSb zTsV&tV^n(2@;^yC6`3~1Vx34wK?-9o*kvxm}1ySt0|2&mMmSOEc5C@0E(h^o)+9?(*}qr%%BEIB@X_ z_oXsumT~2yQ~&@V07*naREl{2rRRH!h}(^lIL13Kzlaxq@(xB;HV~x~jtvQ=>8h*c zB3-uRa@{@AT^DkWux6X(SR6?_0j*8f(OGiYE|zY~X=1bkUK!k*-G(zyJ<+lK^E9$RFZAYAE$OpIAAwd8_FTJ(NK2Vph$1w$hd%olbmxXx3f^VzlUY7xVG_ zAgrEsV3GQO&^eTq_dD;R1;#&l8+hzxR33gxv{3HxZl6Ltam{H->cM@h(><5W zp6Lbz1CldR?sSIuPSe@`&KfMsneWS0<#<4xQGUPh*+}|kjnw`C28C7&%9y?)$q$0! zB*F1>Ut`a;n__q2^V;^KJ3jJUl4rYYv(!_#zlXomN$KWwANxW@P^t{AtB9i!r>tH% zuKqdY_C9Qo!F^h@V>I6^)nT3nfMdO0N2`^fTCJg0t7CnA14^m3BXw30+iJCfM%Fg3 z1~xV}&}=qw_wKyoAnjv&qBxF&hSsB_qfknrR4QR=%9TIo<&{TCl3;9X46|+Lr*3rk zu>H5Z47~SVD3I77`D^Cx?gvSpyi*mqcb_c&lc)pU zTPFC)Z_@+WYr0UV_wxJue$`>~?GMRl!ufSB!+*z@pY&44@08It;2xa)ZVY@NN><5b z;20VJF%qzmHXD#~lxhndU=j>(RPodYA3;YE&YeDqm8tL*fkaPz_z|WTmH=U}?Lrb_ zG!6V~U|fcR`-4r_iNPYaTMM8A4u~ob%kGih>%eO+Ovm5K)PL$G>E15 zT(+9s1~|5Wj3}1CT{-yxQRW`C*N$smYjZ4B>xhxyy&CZ zCi5f&th0IDf0AdoN5#I0avfutDvnBwz%2Cw2&n0h~qkp$zErzRE&^; zdK{0!+0%3b+EgLMdt0Smz-l%{?*Q5VB+KnoUI-u?Z_Ve`OY)rIa`J>$F4qz+FZ)UE zsVei1ztZ#1ET6KwT6fA9O1S%@vDtJX?&^N;rM>6xB92Zu@;Ltdkk37Y1wEur zWz>i?wG_OOQkGE+K+&!^E%O}!D^6K~OZY^!P5tC)?w-W5zLGDKX0FmvttA{Cv$2=t z+*WBjjq{mS21kG;Re1}_DUDtD*uy;Um^kAs#}*)02p_AF9ocVg^tvHdt|NL`^jK--i&SKl$MF7B^-8*sip;Md6GwoM;Hv$Uc<}KNW{M|i) zTqGyaqEw0jdu|xudGTJvIGnF>=KYL~Z{;d<_b}N?9|uXy z@1I%jX|UtZ{|Li3E@SnPm$3TC3rLDXX`X)lCI8~L&iy}QV_B+cpBZ!pP@hNx2$DkJof`GKH%?^D zO8hfWo*A}}6yz9jzwqpa_g?R0VA{7m^&W{aT{ET*V|4p(6FRBDL>hpG(X~unv}tCp z{Y{_gDw1RgtyURPR7UE8rXt5NnrLZBVQQ+BF<_447!wl{7#|1Y;068JUoQS$*kj06otMgU?#Yvk`Iah3QjHZNOITOsTZ}HQM5E(q*nNGUwvsvKkMnv;sXBU%{O{-cm{YDgm~6Lkjt6+ z!Rqq+G>Rhp-5>l4$Vx8i5tm8i5y7A~JcPGjdu2(Cz=*z-kdlLq{g!I81?xBB&dWDM1j zVZ8PISMkd0Z>5IYRLfiYcH`Vbr?%9;XCFF+q!457!d1|IM75)UWNaN`cN(%P=pbM?D2_9Pzk4z7_$J)d-m#E0}iVXCIUB3h+a=NdxW>?$c1hafJh6*}aLK zIxSuJF-=l<|qxAns-?4Mn&TW#s zQy>ip_iDR-s7;;amM&hF`g^zkU4w0!HSAE&CAq7~{g)udv+sR?kDhrdjl}<;=+RF; z#g1Ed({_-7zbius)jc~0Lb3{prTw&F8A}&328pgBkNffEF#Xc~l5rT5z?d46M4?gv z~2-P9u>?BE0tA!&}mr6x68V%Izb=fX- z^b(+}-zhq%k^V)%{r-F1zV|}ks%4N|B)tJ{7ovrPX!5{y87K)1;eF?*Fk~1>P@x5t zvP@&k>rgN_@#Q%*$|b?%8Bvb?WoG^!kT4u!b5m*L$O8Eg^B@^4x1=nSOH0$%*LpnK zG*abfmp`knv-J-v6I~c3W8O%0jt{CRZ&JP$(CTkgbo>fB+}M0ozOSJGbM)u_IU;4__g2=G<8 z*_&JD>cj++VnLKafYwHp)`bY4Kl(7B+_}F#K8E!!29sZ%K7n$r4g-bl^Yhqy^*U5L z$~J>9TA38Rj>IgX86t(Xt|^ZMO_V|kx=1J_4Y%od^5I+LtRO8+T(wYA6GY{@rE^;; zeER64ND5W}cIeV&Ox{}-bKH)qj9x|c9bMnRP%Ue8*NJxCxq~C$T)^nsdV9UQ2HPgn zi?*gdD9sABY+WN5(Z4Quwf#r?R-EQTqht3mTZ<#fdF;J@Bh6ioUAmVo+(X<=C;Wh5(aVbN|VADYBBFFawq3;$z$#0p6;s=WS`1@%c>(>wn_?G*@K)SHL`Hl zw4d>ADS@t=yYJuD4MctA`NwpBM5xxNHi8aB?b;k=&%UU(f$=~6BSh5-R$u-RHV!|IWN36i z<=uaZqR8`{9vn5BEhNGFl}!-P*J?E^FRwU;)?8#FK@CDUs4N56QQItkU zGsdLe)I>XW0HdS8#f!k|s^`t#2Fpsth~p_JKKd0D1?>okYCh z^gf7`<#hwd{(Je)+#Ou*75O^_za#f&6G+Kr$-T%uU1Uv|_vI3L-J|l#@9kZA9^~cK z?-+(?Yx8h3rFSaPZ)dM(L+|x?fReXNxl%mtQg&9U;GAd9gJ-GbTsX!N#Qf*^%`sl2 z!dBk>Ls656?*S-YjC-d|h@=pmKKn`oi9?w;$WsnbI~mJR6jfGD5O>@bY_?m-_$F*v z2vH^=M?3lpjwy}YyKKy7)(TqEhg;7>Yt#i;kJT7b#xe?JoXqA3|6Kl+mWyaOV#0F z0KnHLkE0bAu;a!Zund4ymyGbF`{n%3SzJDHC{u3(g;QUg#rVo94BRy$qutSJVu=*5 z&#VM1yMh+B&*H1oCpO>q5!?22r%&Q&d>%;@;o|WlsO2a@`lU;U4nZaM1~|$2vqGQ# zu`=3-?@YGkak@8=Q#h&d$vFjW%%Rdfigq|VF1#ysIw53DDdIEjA~Ncs#Km%?T%4+$ z_gw>J?iHFhe!CS6hOd8vsrUaJrF(a<_R#ZKJN*ojVJiy?Iaq~IwaY(A9*ReR=AL$1 z;GQ7bX%#D)$w+TbxT$G$~uqCV@6hB&H5+ znrJ3#h;+jmUpqOq=Z#4m+??{nssKPCN!9@*7E|dBJ2zA@Q%|Leh@$Xb6Sbp<#qlVj zXsnIbsSeq5VB0o@si`Ofqnb@?6duPh#>Pf72GqSq$to0zC=?2a<9tK!2S+N6K$dqs z^nI^^ve*~^PM=oz{BvM^eM>naib`z<=+13o3^w?-cf+qtE-vk!Z+@Ng5M<|fvS>F{ zC*%DVddo-CzHHXb!^h}(=g(lNKaTdn=l3AW4)<%ezopEgQ@ZYSzhqKdb-a)q37_}& zNhn|0BN3E{JFb$P_>=e+M(TrK%e z;-_uhxvvP()BiOzOgmPvX}6c91uV%A&qT(~lE)<;nK|YtO)2$!Qc@5j8$7Dt*XCGnjjvY9>ulESx3c%{r1kOD9#J~-<0qdZv z6jFmyiR+puLb_+Np4XNB0KN>_MT>;QLN*Ju+Spjy#VCxY{jgoGh7%Ds-9ODz5%0b7 z0-k#RLkw@!V4!gI&>SuuJ+$RM*HMIvM-HPI7jgLOi|Ov4V$ zHo(^Hk)i;IfHl}=D*}=*at;&wUwz{bO157ert~d!mI&FO+Hmg2Zr9d4U zrEr^`ks-Hbmzceoytm@8i4w|7Ai+_>n9=0;N3KU9gKs`KT&6(^4M-tP3=*->bO9G# zw9Bj@`JnQZHOy#9%6c(If@x#Lm+@N5z*+VT*PJ3o%l_(0+efkUwTE!}m3|f1Dy=zS z6_=Ya*p^f;m$5jz4JU98Y%arwxhjuF^zFD&5to!i(xoqx?0(bWTUC^TD` zSXxczeuM z6PIgnegD3`y+f-*!&o01!^ARO6HcS(ZsINw@OKm+hyv^?K)aaS6X+T%&L;xL{-Yg} zW11O^t*m2wWzE}Zc>Jhmn9o$a=NO99E-S?XR5KZ2gJKHEol%NI?3=zJznp=-tAs1qkYZ_@w=`Aq z&p^9lMJ z&6`MyOG(T=2y)9QR8}$b@n2zR{t|A#@*}JseF{l=ctB<4Qyj;Lq9`}YbT8CsG+>Oq zeoAYNdcEE@-cC{_xTI#YnHot;(%PU_t6_C@HBCq0*^fXbDfD}*)oMpG%K~ue{VYiu zWlP%F*ue1cFviBlP%JW=tdz<`6rY>~hK7J@HOBnB!ks(zcO#<2+34Au6$|95xY-rtk&d*Yc)&LL2qeMiPxV!kA=X3ELMeK*Uihw1*wF0=K` z0`~k7eh?tN*D~@23wil`mj-OA3wB*^o0a$X}oNj`^DFH2-}MqHZvgyW0zRm%#DkeNGV1&9*)^I!Y6 z+b3ME8y_e^+?EKiG{8DCUpaIDOVd-CS*GK`8z66XjxGG}uVenm2wF)CiPkv0Z(m1F$7msf#?`|IusSsXz#2X0 z$pp@wK8aGjjy*SSVf&r=%<}?TXthOjB)Or|B$AYJ2;YhP;<3ZIPUQX2`q&s6LnXB0 z0yahm=Tul39YJ+u*l7b}B^L=u3QHns4U)vmVlVfbjJeM{i`~CCz=48vd$kn8A=KNh z#6V(THXLwqoWIYx7!dGrjk}Y|9cbvr1?>6b{{^*O2XOD%U&F?shtL}1HQ}zk@VQ1j z4NGchZzUAO%2^^dcBbDW(MsufZ_%jj&)92W_DllYU6lJi>yj^VF!il+>K`E%>xR%g z)q-o-er62D@2%mXPriUIC|o{#2+LF1sL5NU{a3Hyz@;k~+NgR4+kB?E&ijBnul#>f z`r!6v%KNAYwbn9#Rd1D1I*mw`ATc@8Jlj~rhdINLjg%Usj|PVm0RF0RVIp zgMu+F6bh42if%|OWY#p{9-pWjtt*J4VMNhL#@W@Up&^Bk9lpeLaUAz`mGS+ca=DCp zy&iNv{&}VGabWLW;O0#raEo=1#B;D$x}SJCE0fHl@M)EwZ&**#sXU**%D(I8nXMCZ z{cg?OPy8O2DR-XxA(iNj9t2M7l?KrVvNiqW*GoTauCF@3lZW&MNxk4?<|;a^JD1l9 ztp!(}@1`W)g7hoICy}gQr+kkz>82Y|Wh86}ZpL(M8|ihl=OifkN#97DKfC;+&o`*F zE-s%-xR^1%jQlJSFuTb?w8QOLuCt5jsV=4+%0`-W!)t{!Gvsvi+s-?8&@2`4^@-!T z{kRo!@yK9j`ptcN5w|oBT(}b8?z+=kAAN{R|NKvI>#_Z4{pUZx@dF2YdT()d8@@hu zJay2$A9U{YNfeqb?7ey&yKmfX&kJ^|<*}9bdrOX&=h@lQr?5IX0Rv#ytvi^zd?lS7 z2@0^|LU-uWn~Y5W8L=2*4!NsHa^>HgJcheFI^Rg#jVdD}`1Fa#aO(3fF}b{oR;iHQ z4!%`tluBrpiXiMoD=%&vvRg92dCRMhF@a4bbziQ{iN(q?sDnwzl5}Q1I&o2~OYUC4 zI&5j6?S?k+^`fk?&0-@dwuHOO(~@{6YaqU?%qu8Cs~C*`z01OPRXt@v&~1^9=P@h zvUHXNkTyETiL+nf8yv&@_U*y`9W*`s+2@#CT15**v6|VEBC#s4c7K$ITL+UjQ|A%u zA2o&QosmQJ_+I!~_-&ca#n67qu2eQ8_YRTj&}$Ok+jlUzw33cMZFmTmj~vAHxqO9rKeRSJZX;c3gI(8e z!QT!j{Sf8+pCEsvcLF4*?eQ1@6xV?K9)+YK>e6LPU;PT;vP{v@_joSiz zai7u!*!kjf{vHN_k+TaBRQAWhn&6`?aN~W9fSw!;AJ!-BDC}7QAjfvg-^+Xhn=Fj? zfpyj^TV9dJ&;8!Y`_7*wXqIWSzp-!vpcyXv)b~GUF@=Oev}5Z`4MO#I&kxzZk?3P3 zW<34o3J^_NbGa(zIJIH6HrRLNI?f+E`oN90%e6Xo-?$aHaiY^aar??0H+Q!HfJntK zNC0ER@Vfg>|J0k(q8BQz-NW>`cQJnb9F|`CO{|=F4!Y2N9F!`xy`DRjW>RC}M#BZB zNzy`+Xw+&oY;0^`eSHIf$u;0k5}gz6+S1zE8sa#HF$TqA5n9{yzF~8#)e0)aDM~j9 z2*{uu01AaT{oU;YvNj$yDnV*_5?$ncZoq#xQ$yW!vuOR zoL{$nIm8e2Q;*G3=XH@U&grI@W~>{U%OM;b!raUYx;0`%sZ#{U+(ra49_33WBS^8b zisjJ&Emzs^?eLKUBTS$-Cfh)Z-HHYso9w*?;Tp1nZ%u4JG$jaXL|B8B&i;y#tA_vG-L(T(4j&k(!RhT?yI}kfLIa@C zD!0G$^DwdOPAZ(G+8U4&G6izF<)8-KhlDlV-6|}*l6#JTw%%b*Cp1!O=8pww*vwR1lWco}>WHQ~S*7G{E=fk$U3-*4rmd3@ShX?8y zvhV73%w4*Qk+ls^iY1NyrP+up^$Ou*>NgrYo)I<%>y5RbGCrHcUEH6hazWkx%yLz@<&Xatcei*&tGn;%!Dwh`~39IL;5isKks z>-%zh)we~ZQW3+$8gp|RacswKb=Bb7wFg&+?tJxT^X)|y*&C8^Q-tdq-YI*1mvL;U zPT6xJBq3GKGb(E{*zDV&`?IR@PqRVL*7F^Q$HD=7m&(sReSMqoCTym+zHB0?5McsCF zfX2yL^0jUXS3lwQp5&6<*t)hCHR342mk*sr(!S9`mQo!Wyz#LuHxas@-e>uRKYklm zuU*HEzx^~GI(jTOU3GXE8)KW711u~pq5jPs9DL#=W~X}NR}~DJxcQFFN~D!~M2LUf z)ABd^&Jy~3&MK;|WAyTu82kKv+#5cGwU>V#jpL_bhDV%y{9S?iLP{9j-`OypouZ?( z&tzB(xtrQIfvn6zB3>%bm2Pq>z@IU0g!8OC1L;}dnuYskj9tZaPLS+HVQh6BN54Lg zDA7I1$Tma8W)r7B{}KiY+vXP#HB4JN=Q}pZRUhgPIDI8?wfnu@yDCDW>!`I>prV4C z))*wF1&DG0a^i|pJPrWHBuI1(tz@N*jb&ZhZ>y|M(&G0aP^f2Pn$V_&IG#itjX8Bq zXSz~Q2_iboZ3BKiH*Z$=IQIW#IU?L`z)-Z4!12& z8twinx#&DnUYY*WLDRR11w*viS=p%-o$~C|{>}DHN2BfDKiEdz`M7wY@FJnphvHUWrpyh{vJdiMp`7g!9*~;K=^& z*FCx70bBOPBZtw*5Ur1o;li;ah_uG`n|HnPC5({1``LI>Sy3;IJVmiWdq$WPlJNYa`DJG< z+Sjl70vy-FUJEun!Q#$YTsnFPE0g(=&O>x>W(HbCh>XFuyNhCnFt~Pb4(sD%efKHR z>cj*t9JPHrdy9?2sc&Rt0=K?t@s@T-_y(hvBOD`MHeJ$a^b|9z$b) zpYU72yOw(f!0BVR-`#XnQdaayLJte^6U1OM|1fiUziFgW!Hzq3g$On;Vmq8Z2?<1e z&}_VCdAqZ5K5d?<+#J)T5pOJF?9v&GUikz|$DY8#!!O(Xbm-b&!`D;+0GddWRYcJc zl!`idZ7rpcBS-bWaZWDx~F?+sLkC|~J5Xv)@cYh~PD zfG_)fEBW|m#O7#lZQY7M%RjBccv+IleN*Pa-`qPy6xb2a@(nsoLC6^(p*$;cs5B|s z_UpxSFoNWad>rgX9L+}8k$eu)zocB?&%~)w%_yQTap7Dm!nQ6So}B}3ovFP=rC=h3 z7zPCZr3ff0jparKU#u?Rm6`3SDc<$DeYkx1ASyYxKy;(!wKbf-dbO{2&1`+8@q`{d=DH!wClg4rH!zXFiXI`^h6zDoJlzCEan z_BWnOGt*d_nZ}+QH?jBn4N$8Rkdjl0nM)+m8Jv|7!C+}-YTyyb$;kYEP)Hu-N(rQ# zj@GMGelovr`-3l`CoIKlog6hZNIJ$Ma~Ff>V>Vgq?EdA)0`#%5`w#HG!1uu86?`9=f`FJ6V zuO&~Pm!8wPIK305e-QK_B%GU*1NM^dplGo53)O3Deb9L=beiKlk9%KFw#2a9DLh|Y zzJg8s-1{^EzL%Dy{t_J$cdF9&w3iccUSYHzc38_AH)i?E@IQ#ZHh;z#R15nb^WhpU zigs~{&rQ00?mwZj?^Ks?VeJ;i3MD)}v)|D*ez9@~+lmDo8W~N0Yn2MPc=RxC?%$L0 zW}BkhYcQ{01%Bn%dP<(vEcHgiyQa`szJpr}3muKN^GG}VUOqj1^cX7t=1JuDTEpS<7qRQcZ5Xfv0OMyDSHr2R3bt9wU|bo4J4e&MivB0o zk%|zf2H3nZ?HY^oWGdh#_yZgy~PdTaS{mwmezi{hTXz(+o zADLw6?a*1el{~lJ=L6Y+2Pp_MV!DO$m5YXi@sjmq=F)|c%n*{|flN|m>>Ue4ISLo2 z*6ABEqH35Jiu;jMh&k{L@xq?dKEvP|4*F5V0gk2Xww%pmCFAa}6oE0wLK$ncO=f>2 zitt;=>MF?^$x#@tRx!1_d|$2|rE;hagU=hHclxKVUjGOfF56hsUx5K=*LS-eunXnSdP8egA0zUgbAm#3$2{=`wlNrI`xB>)QdcFdqP z0ON%9@iCk`brKJ^KF7rT3K-~y;3WOV0zLztb1dSZoeGc+C`$CDjKNPP$gHfCMk}4? zvaF>WoB(S3Bk~SwTYR^JT z0@~Emq513A&_A2x4Cn7rASd5{UYZ+lEmfM9W`RkS(W*TcX6F}hd)F?sdUPb&3XN1M z*nj034qmv7CJJKyaK!C=p^Q6^vceL72D<{7umHo)Lxb&;X?`Yv(QU=BI}5Ydr^~;p z4RqQ<7hQn?P^he;c>O$Z=PNAD9m3s5o&%EA_KOMpnp%NlJCcDhFs1=xYS4NeKGQGT z7RP1K4P-Jl$v4n}UB0l^%Mhe;O!jYK0I5(x`OPD$KqS3Do8JN1+SQuDiKXOE;D@Q!jB4^K=Z zg2wIYDo%_|*>pW$D8|!)t*6QRWR;DH~zP#qlmlzs%ckjeE z$By-Fv`thQ8NuTAZJ3$A2fmR>nwd(D9>}gxmrL%2?kp~%SSa+Y%-_00*Q$O;FV4QSvPnTyR z$!l1akTnXhIMbCovb0C`XQ+Su6C^7&AkL*8R zrXu^v?N1<51t>9JfxP)LI0~LIDuObwnD_p(mJfsq1#7hZU5U0e2%?*=?nj%($ARO= z6_Ui@_U(aZpG)@}ClmFCm%G=&Uq8L#6_ zpI2By*c){!{kz<^K2G-WH1h{E|6Q4n%kM~z$zL~?zaUF>nhF%RwHj=X&)e@B$O=6r1hA1<87 zj-hcpGqcapF@C+afI}n0I66{B1dZlU3D*wn-;yqLVQC3B?%V;40UG(YNOq!r=Kh}7 z9)UW&3#%LJ_qD9!2M+=V5B8P!^3)XW?%dITr8Y_TW@a$9x{le~^X*w_`=2=87#jCx zXK?l4TwnRthswBg zL&nxwyBO)Ll822X&hh1iT)y1@eIBQ9;|j*lyn)dxpQ5_!5EftjE!20;rSHlflWmgy zF3%eNjZ>2yk~Q@efQTI*=1k6qa*pF1Y4g?|?u>$0T` z+5Vllw}R<=OIRNtLlQ-}y-CNB+4%*Gt*@tjK2)t@-<4}AcFr1VlU&Bm&P069-ekr7 z;mT$5DN;ogqftar**l{nMD6IbH^&Ejm#I)FqF!%c+ctx-F<@y)VQ9#p(Li60(l)Alt3!ae&gApngQnhR zc7Kwtyn6RiUZ*y@&%$*I$zrp(JHIVHqL*cV7wADq0|wJpMtxh)b1;4Xt-H;1S^$!v z;{UtPm<=?ddl^d7Mb1Vj3fOB+x0y|qey6CU5rCv!0>>MstDsypjZ2c@w9$oK#!^Dk z?pIm40(iQ#M?!0c`Z{f~Rh39)+x5}TDySsW;4-~grka2|U-;_AhM^YSs%~Ix$2J>* z1W4KLVzY@|w{G7Tqiwggy^(ITu<-Fk;Lr?aW~Nc-5IKj+kY!1b(T&WXoyDzk1GA^* zdN$f_luMgd1oukyp)x*w@=<*MKm8agv2CKb*aVsApHwHUO^m}te7Ibj+mCB=HY)n~ z>KY#T^fPEEOsuTIm^`6koX%Cgve;KWx$X{W`IF=L?6F5s9p2iNXe*PGICuIaUVQr< z7zKR#_@e^@>(!BAeDe5Xc=bQM313JMT6IkRcLo4_p_0wTfFhOK-+6B!Pyx_V@NZ?1}X%@C5-t1z7ZiNUBeeyYsQn1G{eB#=#4h(Ly0rS~IZs1qTu!t4te0;voNbV>A-egwejRJA1Vk03@a%=A@-W zSD{TEExiV#WyEVhr(oEPPM_AtG}2$Rt|4Au!05$qP*_~X-26qu5Brb%1&MY z5UJQ+0o~43>k0skIG#ovk7d#mmCL{jFQ|^u$C}L+rl+@d21ikp8;$!HnWmm*+bWXWJFxdzg=Ob8~MXk^G`mTDz-HUfXI@%Lq5ji%T_x8)t}X z$}Qm%kk%&5ogi(|zTpw)JFv2cERGojHA_V-cZra_Ua4StZ53v{fx?Y7?0)s3^x2KS`UK@KZsJzK;QX!Y z*gG|gXMg>bj#0O7@7{%St&Z{KHK0AVN&$Hq%sdp6o0 z1ks-7p4F^W_IEV7Z*fFH-VM9$T>#7YfOJM=_OuX&%kFJHTIA1By^7+!I~f1^BTRqv zmng0; z3mg^8B64Y*omDJn=ZPCZGcO7q<*%LokbI2nXC>+>>zkD+$h!ak?7eBMWJh);_Qk!q zy}e$&+V_>U7mKXo&LY`lce7jFEw!Z4j3AF?NCLc#VF(s%cm}Wl17l!3BN>7K+c3Of z#)9n8K-*X|t!b&rZZ^r{UK?3etev&KTHe0o%jMo1{&6$%oLFw=&E>s%d;5 zsnk4eJJi<)96T61ZY!Fa0+L^as9nviZe(m-p4YAGoG$&+3<5^_k!R=<9IeKmy?VRi z7AS3*v^N#;nU}zOP+A<@z3;ZgtjP7?vB7m1$`-UeJ|7Xb^z>m>E(;G4Dm^*e*}Mr? zcJH#vX@%w%iU`6G+mG!>@A35ehN_im?MIx}uU?%B2QBpUU~1(G3{K3{`*pd}t$U-W zp1A|Deh?Vx#Zdo1%EP~;f%{NLXk)E-W_S<_eeLb#Ro0&#%g+?>fdd=b1l0gTjNGD4hKW+50y! zedq;@z4Xh8J*l^gw}slxwJNXZ+Mt8 z-YQ;O>{CD%RpoyWL4~%8ce+E+dI1RZ&dy`^=a(Uc$+fUPxoGPbH!wUt!AgzaeW=}H z<-*vs(#U!`xBnIDB*@E}B%Ia}*1yX&pkRKqwj1VjdC*aMAvDdt5+6-W;d zVmYrSt&!)6T7>Mcp0jngD4We9iXucczlGspV0c(yVF3t&_$KJ3+O}UFSQ|#F=DZ~F z?Ut(P@~Yo#yxo{5J2kh`Hfp`Q%w)b7pW3nEJqjY-pgS1Y?AumLl~@9&ZQfiOsHBu6 zP2%KkGF2by2#SlX!*JzZr_Mp^wToI_QHQ4yR9qucJiVGiMevpb0G&6kabhZA1s+25 z`=TB*HIO0xw>y{d^fz8a?}`qt0V-92>GmwfX%~p{d=3IJ z;6C-#6NwJfvx5UT@#6FF!w}EEa{~Ff58%^Jb-m@a+I=-SHh!EU4O_^1;&ee&f(#~Wz*qGX;%kg# z73Sy%03mXil%NYcBGWyyvEHvwj<xVGDD}B?o*`OQM0m8fyYjK?4)ATuh2v66l z^gea2Mv-)q({@!l_08X4fh0p%! zU*PurPvLD{iEq8|V$-?-LMxFk@X4{Gi2M$&>aJ0k@v+d~i^5!~rWFTF7pBc_8l|0) zeE$Y6{>fX&{`w4F`0szc3nc=Ff9Lz~vOa=R1xNPm?Mj(RWXp0j(s+b@{tK5b6o5eW zC!uOxO6uk7quDLLcsz9a&E>GI<7WB|wc7pp8T4N{jp37TqVV7*=CNRIE#?1cWF+%1SK)Sm*Dm5q|8vY}CqbM(tr`ljk(pJUOrHIHz5*ncv+; zGcT7f&GAfgTHbTC8zafJy0*^8QuLFpD=ap(X4g^{es1$`wtf+E)l(`hfWqb|D?RNU z019&}L=b_3xtOSx*9zz}1+LtyEt*)h z5<*Hm@xe)`ak>~cMgy^fc(Z-ZnfW=C%4Nu@67p4v6?^Dbug|Yv$L&A(OH`lR3~^u` z9^bPUPY)exTCc8+lT~Mapbr=K?ZL##)(@g9l0x9K!w2!)^a%`1&(_Bz{ZscmD^C!` zlc`y^COOBZrZCjsk8BriXXbS2i!bo$AN~b)VGytW(eJcXM%>o+q%uiMn&A}WP#uBg z`=DF~@P2HBFmyb^?R*^XMFtk)7%&MNs&cs%fY%@Yzr>k5T-bFIl;&MLP5f~^-{p(mp*e}B)yOHRY~7_r7|f5 zCQqyOmSe9DQQwiKquf5|IFPc?7K&v&{>d5khGZR=+xKXx-Xgwf@0e^VVSTL7{&E~z z(uaOKxQ?;)pmUsf`MOQPOhOnxEMb z@H~Miir{(e+e>{v1JCnNsgwcqwO!6~B+skqk;X0B%%nIoduTaa2tn77s?L=c-dcW~LovqH}UtD<;0PtJ8 zUc#zezTT3LCvKw{EZ`T`Z$kz_3=(|c-nQ)sGM#M(%lB?V-nlliigf@0AOJ~3K~x5O z`|GLFD;2C2>RG!2zjp2aXotO)>ABzgt<-5H1g`GfiEF!dbW~>;hV^Se8c~qR;HR&= zgqPlU3;BgI1p7}paL=q5z=zL2(^~z$kGEewj^l5=jl$dl8(eBM+R9r9*C7M_A|zjf z-JR3yzyN;y+Sj^RqE04kRBpCzlP5`1QI|?elIp-AtjjFAD}cYZSSBfH!w+~+eO!*k zK!{(R?lLoyY)gvbz_04l-R`+W(g8NWWjK9zuQ~SHHx&+3j`5x~w;ag81E{zd%794@ z6BJ1-Vy#rsHI$ot2pv50HN-R=aQ@8x1;F~zjtBcre37^M+y$b;XaSXA64}g3_+GCyPC2>8TKpwK-|f#abn!#XZ$5<4 zSH9C$zjl-22wGVzER@jO+u1DzUqvbu@~Bj*2!bkdxz2PL&jVh1DK=Jo@PWj{MC`b| z*r%Mid2ca5a$I(I!7-Ja1aupN|%GA`H$= z9b)((3!xKgbm2t%Ndf!|+1z9r{%Wou~e#F&<* zR;<9uqfg?+x8AOeERT(PLQUP0N%>zphQ1fqAh&H>SISd#@V~SpK&PSP@xn*0N=v^$ z>m7xDX)`l~SGO1NH>IA${i|-EQssF@O;j5v*WnZUrT|@TxziE5s{dgC0K64fm)IA1)@ zwQUD6?G=h5c<@1v_zDYi{OCa-0O}4Mr2A2Sn5z(tGpaSoPNHLZB{|H^AMv^3lY79)myW+6jDRKAIY_*C^wc53yQAE6tIqqvr z#Zn1T6d|9>rE(trV*9qHX)av5hHJNPq4MS>th*QB^*{Qr>%V>Dx##gWzbi35HHGrz z94b@uC{-#bv>2IMX}h03ehAYm(%nAYjH>w@r0+q5<_;0rXVk1Ur7hR23#Af*Os45x z*oo7paAeP3Y*@1btpM{K&of*gKAO9z;A?*m zm67$%-qLw+wXBhT#qqVCM}po3VNF;4N-n6qXItXx?IgYdUHaO6rLQB@8jh>gE;+pw z^-MWztD5vs8Dyj32dDLQQEI7@tPeDs`MMV4<`9|sn2G=DH(cqKT9UZbzoy5D>&`$* zpJdffr=L;3d|7E=0NB63G5>tuxv#Hxi8xytqCj7=ql4esY#a!!TCJi`X#eKMMwH3K zH*o{NC!a`6O~ucHpwTT?-J`|C+Eho{S(k)flgj0GQ@uV_T2daW(X~dKD1w)&m%-&d zj2!kicNvRE%U_12ecP?Hq*guN= zibhLUb8=vWx`UnsUH3v8I3Y{R)f%M)a9$NJw&G|j06Jvnih&v91zK4##XPD_2nD2L z{{4C>u8ltuQ%SwAE2TVzUvuE~m@6Jve=0qByz}yL{IZnDba?Vq9N!MHW^G$}zsw3y zx2RIB;$QvnuknkoeFJ?75wT6;ut%x4e(hcRX#dprdoMhPr{4bvgHtoLgAE=i8lI?+ zO%qb-6pv{@);6@h93&u-L0~vTr_F0WiF+VEtP#sQbr~=K){o@E9p?*c(v-tj-rJmP zS*BXjSeDt2+&1Xp;FaX3F6)R7YC$t{gC=*|OjV6Qu1cc}6?&vfZmLu#&V%~+_3Ev( z<9Vmy*)&?%W?gOo)uBI~f;XdWt9v5I^y<}a3;+bX+G^XC>)3YfIv%WFi?fd(PUJa> zGC_csfBY6i7#qdBP#RZN>Cr&QVOtodqg6WH5To}&a(`yL0;CM#iCp~IFaRa@zg-s1 zr*veFw}G4IvF?rk8*}S6UN4Ek#T4j0B@bXRYF_VF&?t9 zit1lg7L^!l#4|&K_@KoDuiYlol8_dU{P4s(crY=67mhrEeLHq83U7~X-G*!?gR_?| zElT+=di&%jxOV#%#Lw-+u5H`!(y^ynE+c7EsS`>o4JmF%BR zF-{G&C-D|#Q2*v4wQB3=i`&TbT9xdIk+I^+HlVwB*JY0zuMjTg>ABQ_R!;nP;L2HK ze)6{%y7MU}p86IZzVLl4tlQ?)Z_=!k`qXbvqCb#6f9dsZAF)tCSHaGN!`GJWe_gPfsk1&i-t)@E&y?3v`o;|?r+i~>mrKDyUvh(trVG#4z z&hc`)SXuu~#}vsqX%*I=HKxUU%iVgX%R%lnr$*^J%>W^qX~K?7SST-$lJZzMjk7}o^AzzWii$8q_ z@4WOPW(Efvrv3R>zJ`DE)=vG$ZQuR!w zBdeg2dtB1Q!KzHG#F1dK4r1H?bZnjU-NZNUoA})ALcL4?Qo<{ju=@}H3;3lXF8^o$ z6XtduN$kDGdxpC6UDAp~>yfg`@{;WvtH@pvv3m43nPfNTYo7j;_q%ORrG8f_)Qu6m zR9Yp>JfV5_B0d<^ndwL<3mYD}(qym&M*0lfE~#4E2nI$PqSq+BkCAP7({ zR~F6LdNJteQF>q3uLI}L*CduUU>5J4Ch6kcDLXCax~8A5?8bQ8EY-~08s4_~GSeov z^~*IMAHAke)G9BXV&gRVyL*>QOQeHn{tO^s2sBoJlu{_HGEq|#Tw6i}vEzthAykC0 zST$Ak&@&x4aW&L@vBG#}LQTxLqvy~ds z%s9aLS8C2+Hjm%j^%6Wt3}*AJUm`rWaxEYO_=qq+*pHLPo%-Qsf%M&;A&*6^l)+lKmMyX5dPyIp*TN>zxur@ zzWH-s$I9mSmuPCcSN|(9zIp_o9&Ud9RT2f63{D+=0te21hLML8kU-4|JVdoN>(uqn zrkTkDH|79*yXsNU)XWV2=7(=0`tSZ7y#L|bc>VQPG1Q;_G;|Wt9BmA`b>%+>Qxw-h zL2PAkBLk$8e33R&lDVP!)L;D|32iRwhCnl-m>WQwkW&Xlx@pwKnZ6n{Y6n+vlshw- z8}%}!_MDuS)Byvqvh4dCC;~UV3v=_rR><`JgV9&CEv)yQ;@5mm*GuvKQrDzWJG|O; zRm$OCKtvI|NMiNq1H3fx(|SAObxMcydW-0ZUk>Y>+1Ec){K*g*!qKg7hgoftp-HB<&yH8B-7s#n1CdLU&9QbrA< zRsH)))F;bH^(Rt6IQHxj@O_DE*V5$^A_F0+kg^OR+BXRBG2Bg%?3T}s$gMrQ%TDIm z1#MkJtB0I*yqsj9 zp_HQGn57c9a~tVJ`cVaS(};TmS4ZdEIZv=M?RIgV`Py#kk~#+FCVe}N;zYeI)eoZn zocND_i?w0?KDgzE!Sv%~QmWrhX{OcdTiC=o{8^||_My79E@#hM^ajTYY zbCLjdUAl}+7~tye<_`9c(qX&C0h^%_=(<}IH^!816mlG;YzDOHY)TK)rq@VzsdDKv z;bQvkl3%9duHOE-)C{Uv_t*a%E8lt>b33+T^w)j|^V{|#$`xQ+BHLM)gz?$5!&2GY zWguhR8&kT~w{yJg#sYS}Bz>J$Qdj=Q zI=*eu)ywS`rNz&W4riySx0Cg}S;@)onE$>U$;75j72 zSDbIfJ+;HuUMLN3RRn=d-3>3o)jhj#WBXP-YT{#~m2r3a;^#Pb^$NDGTaV*MkF{K1 zTKe|!m++%s`#s3w2+$>`ZBBRY-^0Iq_icRp#h2>Oet6~4Sp8_3H za5Zi*R2B&?+xUSFvz|uxV<%xd{>;90&t(gAOB?!5MuTCRgf^UBPcR$MQIL1bN=}H1@J%))Q6(ZEw_T| z7*yRFu6Eb~)O`cI+6+`7#q?VnWo@qNe4B4t5kHW?gTn#(nBnbEcQ=^(%2bnin-w{1 zyT%pgvK9S{`n?%-Uk_^+V+-L!h#aD5q1!C|jFuT~*#d0XATTureDo2sP>KS808$1J zVsYF?ImYZRCe*3<%xZ0>B;jqdZnNG-?R1yvwgK?(&nUtZ1qo%KFgIJZa{Z! zCvio=jEtk41a-xVR29Ba9dA?UQ{OEB;$Bi_1qokx7|!+9UF&!}-9F!gj|?VP4&vg$ zy(so}=h};WF4uH(vk@)EG@OA`H_-ZU7EJ@xC$JA|UZ#-5OlpyBnnrqnDO?3XmBx zW~nonGy_eD7XMYftk20uw}gaIgz4!S$jf)}`hi2}E2N8Jo`xDN{OY@`ODjH`JvOIf z2VFoNULkqs0@IC`V-A>I(f>`SZI#Ca&b9&3lz}FIOoE@LkwNEE|IIWb@>CK+>p^Zf z)FX%~E``CVs!M@cUCwfdOXR+p0Y+aX^&gk?x=}#QDB^@~PRAp{tNou=Kp=y7>z!sI z0w5Pu>RizKaGSRHdsCoV8Lri{u;z>ruN?7R4GJ*pr=RUL&^GOw#u=L{w^U9Cvd#C< zuA(*kr~eDab{@mS=e~vFnvH-k-RWDUb|cU(Uy84C&SPPrgedxIwJnKqIbi#CfpzPE z$;mkKc4MMVl5SDA!LeR;OiKljo7LACSldoSdZ~8)WJ3Vwz;4�?OqMR@1-fR$9`m z%w~P=8V~Jr(;YJLEp3##urbGj=3lOZm}{EU{?DK5bAU&xH7|UYS_%BPn;y{=S{@oKKnrkKj?1s*&SD} zVg21vJXpJ?Ygd);xOxp+Zrp_KsLJs`OePl4ae+-Pd`M0*aSF03&{I=(*+)HHIK!4z zaPTh;o=xoHFU+I=@+qwP>7OAxHHNWQzKN;BFJNKa)|$h1(pqQhP>uCE_n0-MIG5mD z|1?)1jz9SZ1C3Grh>%%wGRk-H$JYt6I>Pu%Ji7CneQ!T+MoF?!cv(OS zM6yzoT#G~5Ebz=T0v(u}k+d4MR~|p59?-QBy_YzdHUgVOy+)-GnJ$At#z)ZMjm;+A{K3cg_;>#p z{aaV#n}7C?x>~kL)gVCeM;CDI&PRy;8;O^j91IqSqb0YxQ&7m|ar~eBCh{x#I$_tM z3)imV)W7&4R^Ob*bAR}a`tu*Y`wm9O9wG<=$iKdT%t3+NbFD?$2I5`IN-hWKHJ2ZM z`~C?W*|Qg`hgUXDYa=fH8+_?LgRx1S_$qXZXpZZDIbwE`tDQRDvV$0UtdG@i zgr}3dZyNE=xs+Pny8I%SU;FlEsr}<^&~Z$5@*%u)AHYBRE>?yMxc$9f#^j-AP+7Sa zGIgLpcgskwHp0`i0?=KCWP#A}TKqHwAJeKXZVz%yGNf-90OrO7mFKeeLP2vvQ)O(~dbAYW>o*_{>?HJ9waDXJeB*gdp&eZt|V}`~t?Or?6}DR&3p{p=tX0zI5Pw%lZv? zcz6Tm*VCqSE}O;HZCmi#Z+ssB@b0OT`0(7Pc;?_?tQsCpRjwidiE<&=wUf}-cWj3j zL>PWJ0j2h<2-}e{#uVvGR%?Q;RH@*^>61AA%(iWy$t-xPHft~8Gf7P z+F&L9=9mJ~Jjy=6fiy`DB?A=PA}FhBv+IkDR4yYR*xNFJbz`HUnKrq1(o$jL}M_XD!O(5n1d~QIkt8U8CTtC!9|77hQ5ifKBmsi`M zrpuz@8a90SlCwgG*k+Wel#dxBC|?Z~GwH z9AlQbK}OjA=f96kM&jPFZ((lpeneggo@~vDX}MD_mqn>m>i8;W&+`yP%i|i%ZjlfI z`FswgQpp*mw5KQj*VhO1_SVL<1kRq7=(4|6BDD%KTQ5J&tTI!i2fVf%N-ni=J{OR3 zgEv=NcRRlZa&DojjPt9n>Kx?-MN%pUm*>!(>9H&3OfSy7D zFSQVr%%p7_HezyS26M$C^4T1=?c9dJRl^9w5I_FtLsb9gcYw(vp7?Kn1?yhi-*Wlw z;L$=Zk8eKr0&LH6M{Su1p%oYQtQx z?>5fWH<;Bk{@rw1(CsOFT_o!dw>2co2;B~${}Re-hc_wK%3Ng6+b{$!U6MF*Wbqxh zg%A)zKz_wAzPgDa#^>!*7={SL5T#NHQAGBFD3Z=i^B|~Nc7-U45QcNuzke03UIj{} zj#z4o785hOkf)pUb)b2qkiEIkGuw#97&pu=Ke3VeGL1Ouc&%Z+!4RUOx6z>L|(W$o;J^9md{O82Bmo z-d$AK&z>*bo1)vR{O(JaF*rSgyBjxPbVK*X!-%wHYDEqWDUGYJwiYT^^Q6X715jq2Y~|zmPQZGWa8i+l}cv^q+`sECAmd%sVSe& zAq>N|_U1DgVAZPFaT@?0JP;Ti6&_oHV2w5#_PV<`YV$Nb6n`Qk zzlz0eF3A*!g>QZH?=CL6!Vv$puk3IspXxb3F=m5p!D@6HPfaCSZLiy+k4*M-$u*@F zHFb(Ee5LYrHAii;MVMYWgxgy-Ir&;jG6m(@`}c8i@1BNvD%C1JKKB^_;K<&6=q)sN z@HSlr($MhG5We`A?_lac30r@qxzl!9S~s!^1BbVy@GGML03ZNKL_t*G#>@Jgi%_ z8eWQ%+-WJ7&0@#)tw0Ocw()t*pT=a)G&sJyK^H#(&7(eWsO8nu5J2MFd68C+UOr!V zT$_V#AT2abD6K1cBCoHRp(NcqbS;K_?Xcxx3@KF$IqwLr&9A2wAfuH6;%+lAYWek3`#Mmjy2$}UeJ3EyZ=BFSo5z66 zJm#S%dkne82k)~+reoJL0UttSAY~P9Gm1@qX%3tJ=Kn(P{V#CurC&mEYwc?D;1TRF zE;9MP4=H8G8@kJlve_I;r82^>{dNf<;QM}4(45Z$e0dE5fhYp5UzeDlZ@c=I$PEg+ zRklv)L2`2*INwPiISCvmwXrckcH@$?{C1*&EO)cg@(2B$0`PWE|ED+hw91PMGn=OM zcKFUKIHnt-j!27`7D9}Hb!V2!s->YjN`~YFH5#6*2@EV8%-ZoM1 z3F-?oN|4ez4vp-^aL#>j)fXOi4y;91*vI@D&5Of(_F(tc7(=Wa8bU6cL-vUZ_71Ft zIJ!kk+mnP#^BLgC1|TKAF*kTN-nxToE{Cx-t5W4}M%%Al$I#R?==#z0W52hjfNdK$ zc6_*Y<|KfY;3^IQL?5Er#w*|Jo>0rq<_SMj(vRbT^M+S!;-mnLo;uFD`7MsZ>1 zzN=?3a^kO$8^4F?gD+s>*z2gQSOY0^nWxv>%p7b}lb3GVQ1xR$+-_*r#t$wF zt0lZ%Hx6^zJ#1O8K6C4++A1bq)aE5waj9gr{j5JTZ*0&lxX|j=XR2w_FvkG3gO^I1 z$)*Fh`yc}!@A^9Ew$CJu0DH8%-aGqEWFe#GyLV~j;$rHxQ3O1A5dTdg&lAXIvnZF{ z2eQ7bqz(<2%N6wW6za~`CP^t#sU)|3VWEWi`6BZ9e0`HVPVatmQ52z4u}>XOO-&+` z$smd%WQ_IQ^K8Az^E@kE6h+A8a_H}`VDH{uL=m-VY)six{a?S2 z$p;g-x3?dKd>%oAn}ze)EDn9=d0hVB4mPb_3ol`9>;`SyumM}wugBVvbog4==~|=n zSFd1VW(Hf-Rl|wR#Oqf(^>5}ZLl*Zi}^Ns0vHO8hqV3%$O*59RG7I)l6E#|hq-l?M#wp1Xj zZQDBZF~QeD-EO2~=y*JtHYOcoL#tI9d39W^_ZR2b>{~t#T<;r39#7;D$tpZ4AC=17 zGUak{gyy9n&+{OJK-gf7|FTjx8wWz`v~9lcBZ_20hxAIN;ygDWMG>mi3VM1JPep9r zoX6N0Fg@K7TP@RK<7`v2ZA^{viC(T7Z}WQ7;B8m?lgmz8S)23NIW2!d)oOd2jk`yI zvAcWc5L%sJGyynJZVt-n8-J!dZgZH;RYzskCmtegOPCWmL&o)Zjx@Tl-c%+ig>Cld z%4TFJ8$9}`J}?>?2zVOFlxp)=Q;}A@Dh^CFOjnn=dV`u;G&j(XhilTEd`(OD#>X)F z;YAG2MA-TFj(4?ePC*#p+?6Yk|Mooa8zme%dKd#Kqg=N_Ti0(ubm#yIYq|^8uHL?d z@i#t0c10ijeX&F4T(O8xFJHpBt5*O3@&}(|`#*ZB<#q`G)5AlU7-@bT)vbH?kj?m5 zx2pL#u*Z~&Ce~OC+M8d^DVxb)|Bjt0Q!fsYlCJ<80R&w(p!Sp-`%E$cDM9J@vx*o+ zzeROvKxxw~H*UG+mSz0PDnK_X^0Z)isc({GotvY^JSVlxTyLnyY=bNrEV-GLZ!K{k zZgVZIUbDGKG9GcM?J_9o_2?V2dOC`(tqvX0+mLlP59QdeT1!#x?F+Q12dHoC7Q0U> zyEmibDBSv3(N9MUkOPoue9{flCLfUup{}O14Ld1F2nhI)GCA}y?;(F-4#Vf)#o)Cw z7(MG9*Cb|Vmz)JGCQxps z;}fL^$Z@%iqlu+W-!4y!-Dk_09tC)9jXL44wY=`}<{meV#ti>W^)J_a8|US?*KN{w z;p8Mr9`$5aqIx6Px~o}(%WzHlLT`2udqxg0os#R1rv9nd#q~1vJ+k^r-wd%i;x36X zZR+0$4( zG<^e2$5ULljy3tH_G|yl9JXEm0uaFMP3=2wZ@zg8Tdv6|wb;8@RD; zYujaRz5WFXb0vhxXm}uQbKF)PO$kR|n54@IDvQe>vK9&^yP!Sgg$Nv7MGml@7jFkdiSb)+GM5`&OFo*r-+{_`v||OOv!)q9tIdKH=lEU_%9~@G=p?V zz>q7A{^^I`UAWk;6NqF0awKcjmL>q5@>V=NC<&U#zznY ziyip8Em9GxT~w`Btxee|iVy@rEvj`H6B83C6bkS>fglJiOe>{CwHhFobH`4fpD&_X zt)N(3sPj>+R*}tS6CA;Xv#e}3hg>d;o}L0S?6wIZpnX@A$@uU*U5ALG5S2;=VHjfF zI%w~8a4?>cOYOMLsax_mS&}4C>sUF?Wv_IN>a%Usol?7Hq{n2-4VyOOr`3L4F70#K zw7XZfsaG^3-PZ3KxxAlEd`2!TZ?+GQuQ^)ho3HOScIJIyYBlEmg5FB?*-p)M)d-&Okn^+JyW?%ih*-ua>4HuT zUkDWP6ntvihK-n*na0>aAJ*sdSig^gR(*Q;G7j$Ajcis|07iyZApdwDZhiM)YP`wy zEdlA^%uQ=nw(7|yz{h(lbn{Q&!_Cu|(DQd*#g<=g-)Vctrp*Y$2-8nQShryvh6e{R zT)Ra(3`1PFb`ARn3lN#sF}{w4TBDttw=_>wBOQNnq;A`xbo{2{>$RizaeMQot~qV1 z`c{rlVrJ-JSNtYM#>cVh;TR~AFyBY>pgXIQ+|VTs$F3Z+5YII4x!sRj5S0X=oJokf z5r$5BW@8(jcN+@)&u(HlK+h~HGLj&*_>vD)bXRha!N$H|IXPC=Z>frm8f1-sJ)futv~%HVb2axw22zGlJL+bC+i%xF z0<}P4v8}m1{jN1Uuv8?32jBN=`_4Zj7iDT|YPDKTj3gceRYZ{?5u`*A=;`O@=K;iy z+b$bIwOWPm`_`dpWkbkjV_Y7FAy%&j1_prn`Pgy$!Gm^N*gAC|cP7=-eXJdq+uGhV z&(|n_V_HfXuskqmBWg#EHtP3Bg}b}%w4Iik4?=>tE@-T)h*YMYmKI|@pQo9;W&JxD z>6Hql$L&_?sLiQMiQ?b&MLzz`Wwh6U2LH?JHWejO`S=El(DLZe+iV5ZqS8w3xv4U9 z69?6uOm`mKM{l7A!-IpEnw`bHv4`l%7qE3h@(JB)wTj#Cok#iItMHHSz_tw=o7B=7 z?dn~Puo57QT07y?%H-Yt%g?vUmPKI{;mXY$bz}YX+#IS?^Vqg|Q{4$5j6wuqh`rn6 z>#O9@BznAb7n+(2DUD4RIZfqU}6ps0_#$qDpz$R3q~5r3XIYP?cHC# z{V>FaJ9lws(?&#&=r8S1wo=8$J9nWDeQ-c*jvW)?*=^L*Q-A1D4ES|?>N}Y)+%>u& zV3I83a!I`#Q^wh{Ox0*g3{%QL``$T``BAMJe2w7ijBYxm@9LX^pL*ZQ`dMQAy}8Vt zI#AaEu->P-F~v4i*wu|H1cT@jS|9Y|m*fqS5 zy*JZXuAZ4?=(nYqx{<8~aIIK^^Q7Xcn0lhL@>1_c@Zf7s+j{#JgL2s{_HNq_(FCvL zDiv(Hb(^);-stF*Hr%<3{6e{o)t2KtYnMjG#xXcO3;jUi;=EVB*<`;b!o%bmB5FE) zRMYY$B6#SXDPsGTYlu7#cN^GRl4!%7yV!B{8gla$gz)RLsZcCo$CYdKbhkHeLYVS; z@r}3dV8@kfC=^Qw>jySHaK~+GlittG{sE?KfOK{>L-}*FSJN4~?NM#w6#m?02Q1vV zg8qvq(SP|Qg1!|Pd+vLf+j-b%gITLyqnmhJlF4OLAgiF=6ViId(W%g+EMHk@4bk5X zp;ua6+%4jL2}e3pyW)7A_kvm%bh{}%kN>LB0sKZO0Uohi=fqrTlXxfl2<0^AwQ2WF z9`kk-dNp6{6^_1p!bgAzwgubfSGA^@Y}3cO`+2v>sauN-fCy5$57)*{+l{esClot+ zOYM6Q#E!*5U?21j!_eAnjVX4VRy03ftd$q*5=qgr;<6k#q_#;L1OdwBGK3KDJTEc5 z?|b#lVv};YETX7@LLrZyo*wo*=XBauk;_d|X$J-dP)Ko`rHi7-ca{wRD^>tIcM3$2 z#Q1o8d)2L5SW-v)#lp<#utA!&%PjX%>S&$R+a6ka)Raapw(?Gv3%2j>2x>l#`P)zK zuSVr?-NYeq`@B5c1||o|nrtE-Ep8-ka^m&K0|n^Ycz! zROt2~NXeIqrztgn^&VQroAxg3t|Kd3z$ z?C;06U)A@AE7dA0)c{ZK+wZ(#_-^h2@SS~5zT8CpuCUj@%q&(;OkiSV^PpB~sBeBA zBQ@vSc4%XM5QW~=7|HZ@%**brTY=x$YCZRTACGO_hNIs-+{Vq#G4cH&09b!_6n8gm zK&8#{lIt<`bJugYnv4ny=klMIo4M83J&Op`LSGq2rP`J(nrP(`(W7*hvd#N3Xa)iyNnzc2+kYr~0`afIDuhTdq{t4jMJOy@i5h z&|1nZyTl!FXpSNCkiW~;qT^}8$!<*Tx&<0Wei&sMJtQ)ah#;ke5PA!EAKF+uops0j zZK-fJ00z4Jxtf)m?6~bJF@63Csd8N^v>(^%&OADB~JBFRpIc)gap*Yi%t%YvmZ*%Sa`>6EfnmTRo z+Oic_Z{5Vi^mI#3+sQm|AfXg#+SG*vRzDoWgEeaqwsqp$rfju}1D~G5{dH@*WIkJ_6QeONb|M6kz#?X*pwIWTquYa2ZC z@uR;Vz!OLbhE%yoq zVE_Kcb^5-SxcT`gDGbA!!K1xCQ~4TQ_q?1a-duOjrzi@scCEzPwZPO=1*4+@=I0}L z9xy(>MEupY$L<5@LI2SE3P&tt88zmYT=*>r2z0t@L^K zMt)l5Zo}?I8V;KU3dLy~a+X z8_ZQYX{B*T4=41@`7ytly`yuYqh_-|II8CQ9XX$7t5vLi_z(|QclSoBj33`_)a;7q zo`nTGcJWdThj{gkaRG_`nR%=oy^nHF9#bn;w9U(oE7$5#wpCQ-sIFmtxoN}gI~aL5 zUT>R3>>e$o#G3mL@L=tl)Q-zZl&e%QGB%EQ+$jCn<-E-;FR=qbtkHY5-uCK82YTif zu=~Pggf(69;hNQm{A8y9KMb+@!9z$0>^XlCxpD;oGW9kq%9bkF_t^yiKl@2n?K9tO_Ujwyrrz(iIK`yTXu>=+r#+`$U`jb%61c{$ zy}f9E<}#1$d-;1eu=4%ChCe%rse>F3UhNx6MeG?EF{?FVRH2 zc5Yiklc4*WxCG^W(`ZdJTW78Tl#0r7tzG=LnE!}}{i-H=%(&3F-ShOF#xZZZ zJ)TW_FwHp^_NC|CVcS&?00@zVx+zPyGbN2#cUyRiTchr;0YYSJ5y@N_N*9n z97U1lJguCp=jZ3)J7i-NNkood9_EJY+}u1C78Wo$IfWny;2Z0K+N^fr+fu1qbDS1+ zUZj-B=kv%UgbL5)a_~I8EYI_i%jN223=9mQzrP=z=OLTTSUfeOnVA^~F^j>$0nKT< zRmx_wD3{BNdZ2n}2-ven;KmJ!eftE0K;r&=;Hz+pb~9`clbNDDtejkWvviF#y>8nO z(ybe5arSc3QI``hE^5^Ctzzq?YN@L(LcoLp`7SWW(;PLE?x51}eF7aF>ZO@B0Gd$> zKR2Ewwzek$3>Q}6*$ppRIDxm*{tnhMU588Nfv~R0y{UB&2B)2AlXP9ie%=Y?vRS-z z^jPBW`CKm5K4m5duyTAti(rh}7+7`xA*$JISDdzci$!d{aSL0n-LSA$S~~RGztAxs z&8S(wHln`ydGyWAL+u3t@w?u0{&P&O9PX;qwz-D{aGlr0W=fA%2c8Agv3&s8di@3j zfE(MkqS)7(L%bh`7@n8}0PH>gIda8H{YIS?_{CWiZd}5^ zxl`!7JBs}HXSn$*{}pC;KY=jcYw0{m)<4M!nRjR=l@OqbUEwh z+|=T9EJ%3?{Y%Cd=UoK~;Fw$OEz`jzwKhie?|c;U158O496;9Xm1bKgm)VY_J!9QL zTiM!7Y^|5c@iCt}`nUtj-%PX7?HP+po$6Uacn~57Da*AzXT7xHVPMCOPB`oi#e1pl zQ7cJmn)c`pN9};#Ocs-Mpn+*CY4HM6pKZa%Vkt5`r#h)a5pcjT&`#~ zhibKo`S~IWg#vnd+=rWE+^_TMc^+~(-S#>=JBNXReymxuI?;xZhT@3bsQdGci~u7e zqQ);!t;PqXml9{Uf?HcJn<(A9X{(%Sp7?}Gx5jg&S7F^8Y4q1APnR4 zo~_#;h6-4HU>lx2{J688Mij!=_)VgGE{AVE|3XV;$9)^2)j9F$yC-q^vx_+N)Z=*e z)%K!pXEPamp9umC z%+6}jgZ0gLJt8p&8bs=IJkQ<6Hv&UZT~g>0LxevW(=R z337Da%ukftO^xQEYmK3GhUBR2w8RxL4qcN~G%k(pG>vj`{%o$fk%G4)KG{t5sTcvu z+{D+Pc$EXx#nJp%9vf4CORm)|Y2D^y7>MAr_iTb@)h2z@nS*K<;7)Sp<_0HvcYGbR z$C^2=(?~m)^5rkgV(`jIthja&bGyEV`v>eU3Es6GHU2lZKszSIImW#2!a3$3ndF=1E@zsb5Xfmt~;>L&CMa753qG> z1-V=wKKVpqW~R+XwLxjXV*6zibrb3};<*_vQF$5}2JGKls3jeLoze0J$nCbXnNect zNM8ZdjQ>{fa_eJE*Dh?#taKSlLmH%c0NTBpL(9e6q-KS#mD)TLcS&UGv3eVAJ&3RK zHb&+;h`AkNmaOY&T&EV+vvkHdUIW)l;<(4Lp5HrH#DP!G;U}-Y(n5L7saPuE#~*!w zzyF=@B^qY4)hhaD=4#Hdv_Yv_w(ib7Y`SwB6RTF@!hwA)T?On#5r(Fw3Vt z@PNyC+r$>oe%G;p;)3Qm^^rNpO|)#2ZRc~zFMHFqaQg~YeDVe|QxEa*#b3nio~H~x z%u;x67c%GDiRt7N*#YT^NqUbcd!ySXAszi|r!!NuqV)+!%UuYR+j(^!NwTYTj}Ecx z2vXFKICI;8Zm}R<%oyBMyWMWr`o+`hIGCsBm^jI{LcNf*ChC3XULVaKHCt!fGhENp zk(9A}j5KYuj)+ha(z)pwms3F$l^{e>d+vD>`Fs_#v%+%P4uU}2z^zuRHD~Kdr$e>6 zF4&}eKCj`rAgH2Rt)f^gBA?GAXUN%HE{kk7m$*(B3V8@2kk7~I1_uYNGSX5I#8IgW zg*ZyK3xB2|A>v3}W)!dGN&^GH!GrNTeDXUHXyo5SO$&eRV(lS6E*MfyRA zp5g))dfPwH1OV&rjAHAxFKP!?eGT`06{t`uVf)qV*m&~}vk#coq;3*nM_X6scmV8o zucnbI$3zuDSYqq-8}OnCS9kA3DdkNeei&lq_ymrA_z5IL4M)>~cBO$9<`;0}r3`V~7!m$hfrY8BJdGpJN57#)SR zcU-AdEgn42L!n>?rkI~EA`Al*3O2r1ho)U5gwUL`OQjMfC#R6l=diNF!(fF%9{GH( z<%8NLsYBqV(>oB~?EUo90v~)JQ7Qoo3qZn_cGtZ+_ zPM^#}w`9v#6{Dx64kK*?NyZdmEMYEan_LF}-q=_}a9TeBMi88DQFCr+v5h}@_40JM zs01xvRBX6P>MIFmQ!$bd@VzYhvi<1E^fpuks8p_uB%2{bJ+H1r^Bz)s@Sap#0bk$z z65=fgdmCbPVG!Tjd=zjvKqpNg-}mvImtNMMZCJeqhyU>&?b-ao0{-n!-@F zA^W1|L2OKKZ07wK{{;%=5{iAjh}tw-a}rXbP%1&nI2sh+VoXE%H?O1j&pt-3x)OM` zGhSYQ{zc%=U$mZQ{0uffcL1;b_Oor3d;Z{lJpR#X^iR(($|9)9RG4F;_ZK@nNFyDe zGe8J|e5rzk-l(JZ%fWR7563?E7#}_R6pDSlsN`~OIdA)6h&A^g;P9!l+9ow!Tct-) z;*tkOJ59O3=cn4J=TbsH%)t+*Pz`QbY=aB^na-aM(HhAwI~^L_ zciz#E?i4R$~KioL;S8`d?n2u1Tm;l`h0{N$8sfw*CU7>%B&LCf6m*bz85`#1Nck z-4dXl^5br*MpIvNlWAg>pevJ=P9y62OGMu#&{JGMsi)9%bFN#I2?DIWcOU!DoUI3l?o!y zOTB^G3JEFEv#?Mf4F^8`41*K12$+L0m@X|KapaTJIDPa89__@=d{{GN2PJjgR~^+9IP&o+O_S!N=26^Eoe$--O>#;A2-usBBXgVO z5?0UDoU}cyZRD)&S#54~a_S`gO|;JykU}Z-;K@NnYEOT;YAG+r2mkx-G?AAEi-` zZFk{303<62=X3k91OTa=tYt02wUY6?JSt1)f{hj#Ad)3SQ5l}6N2QWcS!<~TYIV7> za}Z1-iWU%t)7taiUJpBV^k8nz&Xdh%kjc;nZ4^cDJP*Ue!|;9Ia`N{54D$KrQ6Q(M zr!hA-kCiJ|CPvBnvXSrm@O>YpQW<@Hea$m0GI^d?yOAqh`lCnVm-+F>68G*cB4dme z0~>b>vAB3^RCc4bm}^u!Wu)W9#_f%5*LFTv`APVFsc~_)tp?p6eXcqhkD9bxq{X|9 zR(Jb%zHX~EsMwCSBdwh}_fku%+btR$dr);H>2oSg#L`I!_+bP;3_A{>WYUAl3A}UaB>wIdlCRpZ6j!iABOP42nzEM?uzU3gAiWS*&gSkq)ZTC@A=QM z?(RKp|I@2!o2>@3NmHMQBztG(-V^FPsPU`rouwPA0EHWZnybv_8@J$xAub%)=c?AC z6_Zmq_Tk42OOx#d5b%MTHVs75L#7%u6^4Eo;`w(@Km=;Mxbd^7&0`ZoyAMVy;@@33 zL6@pzEu_QZ!uYFW#paS;$p9iyppBlIGvZm`@Y%Ca-(!}4b;<?@nNsUNu=X>vz0X0 zlG^JgJ_i>7*R*G52V^=ks|C4D=%mLktcMS~p20 zmF1$DnOPKzMfCI(Ff=rjD$in5KA%GrNmQ%VhWpIjpl6Nthj2p#taKGKL=~Bu zGk%Dp?|%#*5zZbtjJq2*v{bf`66^1d;^3K25g@ApYI7Sj(l$VjTh76?-gnJ`wEnw*56{aX2xslzqX;X{`~+*?`%BDk z*@yejHouxM&AQqNtz1dqX(=e5&m#;&RI9BWtu=wY`mUU=lYl>`VsXJb1zj$ev9M4= z7}}?TOQn+Y@0a7{dd03>&79j`S8s_dqcw9DBv9Ndbuqj)}B1gaW%$;>OP=2x{`no z4-)x>3XZ?^Hr{&mWt8)Fw2sA~b))xi;L~%4T#bNwG%x;3fWgTbJpKNMc=veo+ouMn zXYlli542556^)wfW@_`$udT_QY{1vC)!EN5J1~IvUVN_W8~XWj8Lzzgle(jF1W}JT zZ8{v&h!A+Csj?5)!3C)Ed33zz(6|JWK6*+*@Qu1aG&i`$fJgCK77&!z=|?6@9#Lhec) z<5rDq-I0V=QGGpi)tJPqJzm{!nU8msE@F95&!eX?*FkBNQ*XIcSYPo(c4PnuqZ0T! z$=eahDuQ4NVN^mj7?1gt<@&X`fIYgRXhACr0EEaQl4V3u1wu?{Ief2IPYXbJJ@7pD zMyQlkWHPJZ`xN0{2w-p!*s>*^4p^yFFg_mh(bH3CJ1X_hXmLphf!^L;Jbd_28*@p- zO#o?~ygQ|CW8(BErg^@1>T#xRnp^&pi0;tTNy40!cJQzy{H%5W zcq>UOP`tae9GW|x#k1SSA(qMAqid5xd^~m}>uWu{950Oa83 z#@&#<$69Ag8L;Q3R87L$ZgSZRNUrO$m%jnCe+gZywB*BM+A8_`qf*naitcrUKAW6? zNj-g>@Di2XhAcIr)(*WT=8DDFW%GA^#nk!dbJw(|Nau66leUe=T>$|a*(vlfslRQL z=VTHP@cmv?g9%6(LWu6&9PFm3=GaaADUvck6qReYSxqAdau8x3QkH86sev_X1p51d zFTRK)W-lx(z(v_?y!SajUqmjK)Ao3IP%1^4Oa=o9H$G;wSrm&!jE_%X=g#fMufjTX z-H4{9rco>w(c9aL-VSfe_!$9*4hbAQ7=Ioe1x}w{T0~>&)7_wMV(_>;msDt;uKDln z;qhja&K4f0OygB!I?=s}Z)r-(5zMn!qDCQb_EQojpV6XlQOm zYL944)74Exe3Oa3$Mere6#`kP*kUm~`SD4dJ#rZL*R5@dkFD2lVAtgz-1i$Muv*?atwem zwmA>xp%Z;GQPpG{4NY*xc`}Wg&7_R21egjDm+btR(E5#PYVNc|s|vN6%Ca4YbpDcB zVD___hxZvTnRDgUz_HKXgo-An(&;e;;+#>PZx7~ph@CK+zYiVQ+J zpt24V%|l2?l-Fwbxwn3Z0Fh;nn>M~WaV%ze)i;+V6SX1wS1Wk)tsfvngde^6M%O1~ z@4bE#hc8}10|oT2R`B|deu5vp`Nk%lT&{cw^j0LDzo@kspWaW_O+P7HW#m3JOJPTS zN*DFVNJQx*Gp9HW(|0k+)~R8(R|(+X*4#{~d@IQth5r)XX4)F;No>X*jU14<*!$12z2LAa!002S%zQ%=r z@OxM~^(vzNA*+AWWu`qYHVy`RZ>F5bflvE?^9}7uIo{*7+I?1~t&QgPl`WT%<;-`b z!~MAw4V$Bx_J>O2+2qiNbOfY~ZEaKv=Hg~w9!!kO-~0T%R2uicYX1=TyJ%f#8R;|| zaRtq|2GJ}bMgvkd*n8RfUl5dmbb%PD2_irsN@&Cj0LEHjWrSe~LKK{}G7x>R>WdI) zG#?<2D=3$C!+6P_T)q)bHm=&X4S4zG{QYpU7`VTqo1UI@QYVX5DisV2^gosOGmDx{ z;O)0%x^VkZocPsyJlT%&r{~hmC*RF$k3)Ily3^>koTxO8bbKi&Yu)$O#pAMzOf7ov z?bsZ8T)4dxoa`pMlwC5ZHDY7v>`nTn_g~o&g2dGpqj@9>54Wu%xRw+_g0<-p867>_Q2{KS2!RIdJQ z9~S0D*tQJngY`*wKV@lbk0WL|tL?(NKjI@N#neiM{=#&mR5gR*X4>+&H=27IdCq*} zoXqi#j)A&H=(c2zMRuE@MEy~;mbu4W8U`zz>dW&S%X+#%+U#3oT($Usice$ zMa!tw?PUln?|7=3ib01_pq`hef&&+jYy75CTyY zVP$0%Yin!Ry?ctib75~E9v4EOTCG9|v0+@Rl6X?Ef4N*n9LK2FJH3_r$sqbU9*4`J z*BCq>Z48HZ%9r2Q>x$cZ;v;|x%f{TvFX`d!UXNapiF2M5Dgd27-l!u^Tu8%iK(#wh?(fKyF*f03zw zy@D^l_dbfXhA}~%)U?Svvk(IK?9|Dgq(|F62ZwwjHsR6}&k91A3#$vwCQhFJ3}G|E z%HJ zR`r>-Tne&5!T}Aegb}8QLUr0_=Izn#>G(YT6&&x(;oSwCZE$T%wTYj1ZT4dJl~vqD zNyi1MtLubDs+&mV@qQOfhI)=Ob71N&SQvK=YZ$NIC0{5xDV_ss)q1pq00E-3=IKS= zw%dpsTUpwhV;-PEvDvm=?VW;UGmZ}=yWT5(iOI*GB$dXM-k14&k23@X7H|2v`odQ}ve^xr(>A)rAcfq<+ zFw@GC*DK)sMW^=ekY14KoK$FzeF0gqx zuc@;g=6Xl%MrsGpd{Wmu2q%we+nY8eHhOYVu6+)zntI@Nin7hsZ?%|KoxZKkqYj!e zUViTbeEh=mSQ_d6D#h{9ZOQe{LU^xnjDrC8C${6GmrmpPpM9KKef%CJzEoJWuEKox z)vsn=$vm{Og6BW{1W3=6QwSzZ7x_jg01yzeiJ%!lAjT{2yo(QCei194lT>_k@X9sp zy>=5KO6*D@BNUpQ-SUx#YUMJ1^yVA*$~*5NtVht-IBVRd>XCUtarfh&s=s;zrJ|%( zsf)uyqqZluePXrgOK6qED4A*|)3tia%G6cW@|dKkv8ldxR-G=dkS$u=fx`yiGIecB z{+bKbMVcqQDAhz<+?PiC0uw81KMmEzv?e${qrWtDHf~A){nMAQ?Y-}#uo7YMxBpWt zKlcXWQa_|HPyeDw1|)a32hr4q_k!+kYU^q)P!r^h>g!{x_R$`YjuSM`HgVsis=+SJ z>~i#v6@HI^YvfD9lJSh50A|KA(ZBM3xyM?O#^G}KUpIcF<;i(DhP5#<57Sywt^Gb4 zKq3qW5C($~q5vTZEVqhRkPSBDrh!0e=>S~9eD3O3D51?J*M6wr~I<= ze^+1s)sDvwZ_nfF-#1EnHp1+=ZBD8O#WgyXJ;vMkg{N(Yxl`XrZSd>)??_P=Ms~gD zeslZwDNUxuV9GLWCw-qOwJfy-qDDDY166zweR%r(h^_YD-ZxL6{<`b{+rJ@L$~xbg zBeu#xYwXv}oePT6RXXbC;^frfWNUPSw~|9>!bXJ2J2MDm+_O2zv5`^y{7YZXI9azY;npJQsPS=eu6@yfx(qE$R^TFyJ`uq zfNagTC+Qu!lsI)~CpUK5_NnuqV#mxq6zg^Dy?G0PjB(}2;SI@jQ5Z!y{ozLlq8NkA zYlvFkSYf_o!!w|^!j~!y6wtuoOP3Kw5vKR<$(`2F>MBm1`xG$(3@)ug#`<!OPck%GrYhpDMjj6nvH%w6rTLNhf3sM|y`>8aRR%I!OOuc!Y zF6y>@R4~Fge%AL9sg!M`>KbD;@pUqq-__@3k=eUwJxhyo82ib0G4cKxtV|8#-kX0N z>r+S3*s=|Ap~Q5f*xJky?GgPpOgr1fXOGxpxyypk$lF~$ye#z?!c*^T+)%Q7INJ29 znqvap{H%SXdMpH#cT|6Oe)J=)5AIPYS*rq3 zMkA^ql4{OblLQdUI*~=C?)~mrGTTvSX|~77HXlvPH9EA5 z*Bye)%9kzCW#gMRi(j^R$R&N_laWu;jZm-U_6p1Q=%j7H@50cO&t#*(**`IDLPBK{ z@W0gL2uMuoqNgE9!@0)1;`mGkTgUdGnHvgPstLwzaIOp^WiFVm1zJY*(k{2_ixbyL zSmCCz5@6!q9GayfE*(4SmAaWUd1nR(uU?1Vvzp{KYAvcRS86!+*+m?@dJVHvyKrmo z-j3vNU0g~*p*gu2BgEdDw-6Ts+}yWslXAFuv}Ji2&zwDv{cROc;Rg$}N+q10OV&Ox;~wXYX7n0a;q3)&_rQQ$#)K|VxC z&_03oV=jj_kL3b#c3EceYli^6vXAG+hG(XGzz)}v+~n@xc;0D0sQ@7d$hHHMmnQEW zsXPugslz0T>@wEB=4>*m001BWNklWGYvJF4Cqsq@)~!lDu_kX?_PgcU*UU z%^YeS48~97|NIRSXUeVrXaxVW|6xPIgoG z_e<341E|;Q*23^FIz>^G=@3u{m+s#$Ffoz*US9`3`Q*`pf1lmnE#+@n`O?e_Y}@6* zexEfKbypsFwMkB2hg)8+ z;ndkr5fww++`kWZckN8m8dzJ$vuDo%0M5Ml0vaW^gS!xh*qUSEa}Bn9PVernohUXMIC%M53lGK!(PWz@=(LhP5m<$)h1=9FrV9-y zH{FEbCh9-oH$SOM+mR2SDY^E+9zJZ&(X!rdLp3tbL6e}9(C)F?E_LY%=VO)+ zUE6h7@!0j+9t-&>C=Hn+=z|bN1VMjm(RR|K(bCcW1=B7tb0Q!_*y>|!J$g&+Yqiqg zX`xc7gl02p-PH7SOm6GR=*>-Mc^No+R${I9mxx)^OPrg?Ye$`>=hH9Sr|Jv$^SC^4 z-RR}#*HYW#R6feuy_XLM^AXXM?GEd0uk*#n-QDS*ZC|*?-OhYWE`FDlKzUsl*{&`8 z%uqGr`m8b2PT{tTJC2`h`@&@z>h#<;gGu~bxa~``4f6J+5rvz6nm&o1gXR z+GJd=xIPgYTP~#Cvw%w^W;2D9X4@QJa#Nt{rCUN-?l` z!DNL?tGt5NiPo0>q7P~@wS-LOdL>W{M-T+bJDn#j zQ~8-`8Wh*ZvWXxlAq<8fL=i&h8zM~7*x&I^)*(bcq>Ld%5p;dbzyL5j{6)80H%@Af zTFNi}A)Y3c%VpGRHAFdXg1CMiSX`7?T?JNGH&?G-hP6oJ zb2C?g1bxPuHgdF%YCmX%0EKE3lhZQ*(DQ}c^A8{5gY)O`@-xpm-|wEjjs4edU|@B< zbv+QhqFEqnEne(jtzd9<4G%|0J4%1sg9RM9cp1Y>D`=pA2nDhnI60B1Z@r4Xwa$QM z79G5D4O^C%F*~^n_jc~+nOqlz%?Mi-m)RA}6znNju=U|Gj$XX9q3?V2;w9{wo<*VB zXq97V07`9W14!#3K;f}I!456wi2|&pwK~dcwN#3$PvhV{O!F-v(%%u28lbdZPZk<5 zsOy%ir}52etMoI?2i+}gf)0@9Ea0G?Z5Jo+t^NI&yAR8LcJ*cauZm{^4jUlbITtWX zqCKGQo4pRvFi!;*2r8>6-@n5`8-x4NKR=Jc(iMot5&)nQ_M;Y*v9+0Z2sLj7~IpO1I zo#uj$_&!VxE8J}>wQoH>D=^zxWKY=GmWYaDreLP3%h_UYDu_gEuIzWgh8@M zTP@gDf13aXmsb|83f*l1wn!D1r4jT3miTEz$F&*AkKUPPEN_B9IyERBvp zpNgX_EPWQ$;^+vj96yYOv3v`Un}q@v#O_xV#2+*|+w9#OdG9PMyT; z9KQr9M(E~Gc z7`*f;;(HTouubWjrRH!N9kA` z4{<3j3}qslc3a|}7Rpm=d%J<(pN=0Ra~|8u<8e(p#76JJs6E`jZyxZ%1xZ=!r<@CJ|Vk|shvXYY;E(aIXz{M+4g>z9!VkrgtZvEre_d~Bh|4O zIQ@039)6z0(^|L@mJd&Z@c3;VD&M6!$CKJy$YYx5l-5Ewag@r_aA{=Xbm7dIJ0~t4 zmtRDEX_@B1#`{!vnm<+2E)5bZwMknxAtkIi;x9VI zag0Wz;k_ODFFJ)`2q`7vIJ+OeaRaz{Q+^>AYbSE^Q2w;@j~_l>(|eg6$FIMOue&mI z_t-wNH!-!t$23na{B4K1HRv9LKMKU!J+Y$*vkV85+`KM8oDJIPdpFRg4ixQ9QAU#a zfd#Z7VZQ;3t@x<^9Dw_CN_EpxT|D}|36EV7+o6X7Cg=aL5PCJ@vz0YH$&@5=F{7sJyqoj*R|M#Eu*QE*Mcg$75ohqSdbL4*dI z<~vuJ>3Hq>GHJZ?rEW^)5Q?W%dUy|EWfkG-BKq##L~&^zA`&RAL=fvY0RZ(a2N5wzes5Cn)tIn8w6+!e&j z0tkR$`X;u%`xeUeWvuTwjO9ZwAq;C+KJk?_H#W@8Z#>ve5|??U;IVlQm>%co8S1*n zr;Z_B`|N3NJt}9xew9DFKA7*^fY+|`b{mjZ91gtA@sj?IWrSv2fk>~O(q$O4Ffx+L z2x>EqlrdsiMHE#aWPpix{vRxlk7D83pTpYJ0YqU9vRP}Dk;5Jk0%`}f5XF|<7(x^r zS6cxP1^6wd7U-7^0CDTeE46z%z{m)2=#aqHtvW`bP;>(9X0wSXiV?^0h8A1*l1il# z8jVJ4qWbAuc)bx4B0vxXxfX3JT3rRMUVU`%V>6&m-VrIEtb731-}=n(jezJZ^7pgt zLV3^a;c50TZo>~=vXf4Jwc}>gJrG+GaO-nV|+8GhsB|w~VCm2S{rC07I zm~~)j9fM12OltC7+xPd4W)s)%+{SCqp9XSlSW*Z=O;OSP`9YDlK!<5rH73xZ`RaOv1F%sVR!NzIm| zypxGv#jo2hZzq&^OF>JfZHJ3AE!nbq)g}dP&1cCp@oW-{FMrUdlF^B05MJ8q-Ti{u zBV_emu0ELdlCHkX)zgih`9AvQR!|?Az}m4RsO&nB^16FDt(ogD^<|kTNo!@JMk>dh zM|TgeeW23G<2#EPoi@juoB=oaQjeQ zWy59ry&K%$!}Dgg9jb?$m*Z$t52~@7?9s7TWLw7qi4X7TI88bXLj*zaR80T}L9!9L zUN;Xzcyj38Jz#!5IbC~xe)H1lHO9@?y7H&#$FBML^Wfj?p3Wzi^LN{`aGc_L&vl@E zKkfG^KgYnD*N19M%A+3Kn#sJU8d<*JRF6rpk{tya~D zvG3}Q6h+ti%1%9^FvRrUJsu5}%w&U9yL#6Q3%GS)FLvCz2NCIW!PT)W(^EQ2q7OefOtm?GPTZrEPT&7*`*-wTS9l^rTD&~mtTi#?F+DGC?@J)c z2!j6PglsFnv_;hMG#X75i{1NOlbfdn zn$2bpHG6U>iXuc^+-jL$J}^BENC{lOF0sD8X-NU-JqFiu^U%hycqcgA_Dp8S@$26n zn|DH{SJ+M=E3OM~Qz_Xv+ZXm1i5|)Q@tuHc{o91QZW+oUV}E{r6154U^*b18nG2y^ zmBTbmv&c17!^2F_?SJ1bxlAsb6r`bU3U!K@o~8>@;H96{$x8u>wL11)zlkUeapOQf z@R~(&9HZIhN{0FE<7gHN7+PMz*u4d!wM+quNXtFI(9#OFE-j%l*pFhpfvAw^YNZ_n z7+P7y==?)y@Jwq=B2Qh1J-oDn{nu_l3W1ra$*%Lfb7mIhN)<5zY<;+h{a3F;LiGH^ z?N|ipt5mW5?i^WEtp6o>RD*qz*J8DfsoQtDTC_cRdj`d79qLqTMbc;!+Hj_Za+k8$&hQq*!+DNhbY`R=mO9xW_e*2gI7L5|JADqn(N7^ zC1VH~13?*a|2Tw97M|93?1qT9Ac$&c6t@6UB5JN8F88B4x)W=KA%u;kRGa#?9f(T( zRzBC277{4mzYWn^EE%oWAnsj9`ChVcycrdMxQ0FFehLWS{4*g^=h0m@08H}Hhn9=PY~1Qk9kI!exhxG17a|4J5*`u0>|7n!s|I0j~i%9 z2M@2GNq8*lKnw`sS)grcuJjEPE&)Ia1l46s{p>9a-@1%jzw-A`*|8roDC!as0R%Ir zTICiL(%(`>kg|y|7(@{CLkPe5l{MxIu?8S+$M%96r>XcePhHzqF+g&vF{Zi_H^ImnZ^W!z)mcyK z8@c}JGsd#1Tq@$(BS$;FVL~r`jj=Q~g5{AdSlKe%kqndW?4Cjp$Jldy8vQHD%~Q$b zO^imVfZO}`;O2pSkQ+FvWocw9mPWR=XY46yYm=W;E+GSfoBQ`6?(%jJN|pY8+}X1m zlhZRW?>jRQph*A86f3H$#F55TEtJaOJ}^$a_N$3&+ip)S>{LGIu=@@g%f_{?tDS+E z{N~c_(r{yC0kb!vx#sQK#p$l6u6}FelOJN_><_WN>lrK`K92ghKCRwe0szQgKU(5A znIj^=?!)Xb|2SxmEDANMdLo^CT&{_zsK3D+U#N}Z!kQ+JJwCX<8cm1GrC8ZqoTp2R zwg-w|LAY$)z@))=M>$+y&3sRDMQe?#X1HbBBbH5+&(uYePlf;>L@~K~Srh@LTkoh_ znZv`~sk7M)rWSIOLEk{>;J|@`KhpW$b$>n`cHa<4PveSK1$Q-RUpG+K@&FlI) zX34r`xA%@@>*tGazW3Q5c{EkOWyW`~>r7VZ`E4UD-Pd9$j*wOi+uCqpWtysK)tRZ$ za->$U4&|o_o9&At=j8qVt2dmwHi|{u+qI+ZqU}nphWF2%#o;}BQOdfds#w5hr%qyg zb{>VO(Mm6F&HhG+$_3n=+J(!*xwxMsWhGM0`zPz4&jj%XAiYrGBcb&IJv4{&NPaue5 z?3lfWun|EbLO|wx6%tOdJHZ69RsVw4#%FcQlt^o03|-%CoMsbmAspN4_OA{FQ_o>~ zut2ul1Rn=14LYAq)8mV{1(88pzm1<=X}awFtlo^5MV|f+5OIY5J6EyogFnH*tqW)l zjbiE4Ygjt|Wi&=7oN1Xk@%4nRK8xqheoyo0%AMPzVDr%N!^FWnFSa~7)=_M0TW9S@ z!Ym7omO>&;_1J*+56~sRwjHE4@yAS-S@td+YzsAm`>UIp!}#k; zU**S^<+cYMr6CH*?aj{i-#$LoBbg&^S0B2wQzs_{CMLRyx?vJRK!^a1Mtwtzw!<($ zVFQP4Y!=0_L=?qc-#QH>3(^~n2BN6<{)k!)SXcm>P2kf{B_557q4$a8uleoM&Tpyv z;|Qb2XwUB=mxnN)KKaO>PalT1)8(kiwhy|;-oAKG0~tM)A9D7R+L;vEII;DiZWPmG z;sz1lS0vLg%||OUHKMf)!6bJ>ywcdyEh?Pyx(xzu)VMiasZlVz^N zYArsFTPKYRgcw|2!@(=p5QSk^i>!Ce%%WItk~#%>cLhCFeKlK+39e1qdJ@{q89ixR zfqK2uTD20LrfzHgYpa4(1O4n@ux*|o#sNMD+GdO98tJmrWv~9ERp(ZeBn%cNYV5*AX@fhz9!57#~Az*M2lcCLl{?)F$lfr(FMqSFnskBEN|b7XzLiT zWd!w+?T7}oGpgMd8o#k&k6OuZ4QMH7){C+gnZP%RVFGiVU!8)>Amv+}Z2dVf1|(?{ zIu37(S|^_y#RS^0a!K(uOS{k zfv_}`@r_J*Eh|DK>4~7!^@8nQl9aM1lgoudh&YyLHoIT6{UnmU5-RR^K^&!GvG~Xq zZ7(h+6WFt}o1PSaY>?Wyth|&zO?RJ_pVto02GQ;Fu+j2zxvH~5+BwPf2<-#Mn#%^? z-Q=cS|JG@pdYr(VI@0s;`@Wd_J7vi>-}7hF{-Q2^o~E{LO>HO|Fee9exXZ@N`%Qeg z^I>G0i(3rTIxsB;)3z}u;Z!PqTw?kgRBUBgiq<(z$p%w}u65a|DU3M9-2hsXgff+& z?&$I5+N3ZDuyuGCdGD+=t)~DH9!!kk+95y2?u4fI?tzp7du}8Pw^g01mCLwtwDZlr zn?=+2?xI?)V*9o+j0|TlR@YXe!k?=CBon;78VA=02XOu10ZdKbhCb6vrN|K=_jM)q zi8^Ono#9STYBw!vpUxEf&@IpOCM?}<1d%Jea=A>}%1k_L`kUw`Yx5#)Qx^9s=y$@> zLzf%KGe}PIk(3gprFn#RXEE}@Td3{Wjm76)Mr~Z5R_{VDzJALc=Ih6JU#8PiCC&53 z^d_}OJ*m>LF&H0Z^e^EpEjkYQtSUYJ=(4v*LbC_9{Ty^`(z!9^>97X5BP+fNd0-3sjWU!dqD zAq2uOe59LeH=ERk;pOG!rzTH8vPpblp@BjnMyUkcx+Sr&uzBhA65}TF@>2VBvvg~h zjv1HQ%|1R~Pse*2&g)Mni+ntJ5VmxkvUqW7}%~Av`(3r*~P6i=3ARhyTRnoM_J>tt%KVyZhF?;;cgsl z{xz)(vt(5mMF`YZ7f=XTf0wAm8AIztZ@N|YJJYSww7-e5HZXv5&pm6E%|^*YCdp>x zBIYJ{;KIohUCW)`y9d*I_h4%J4o-gZDS!}?l}a*GSnDt2*8aWDL&oybrDI1SA+S0; zgxSgN=5jlwD@P8ayjI1|+jk)lq~DC5RDS9B(G73LmO|kCbI%}L}g5h8=JJKDM6!DIR?J zTbO(Ew@}@=-|E{;%xwGkr1958Q@kW->DrpPHRhcB%j&q&D#I+fCQ;jjqERY~qFy?Z zWsNcJ@j;Ou;Z*7AG%23u5;;!gwMCLp!Fa&p&~bz3!A#GEY5CW)eFkoii%*6dN85fS z)k{b;!97bZ%EsA&C?l42$ka!@c{XIXa)*Y1PM38h3#~;*HwODC3 zq8N=v17XSOA^4q z$~q2Ty3*C6?d@~-v9e_t!?8qPt%miX0o**WzwM6kZfR-jR$M!L0OND_+1I6CUM($d zlna>My$hF)AMGlwhhy6?QJ-t=fKDh#&n?sG29T{q@X4iWG1T?rKyqzW5)&!E0NCkg zeDi^es9|nS97_^gl3K6GeCBdROG_#XX(`f)Y1egD^qmc&^N$qk$rf0`sdL&bQ00PFzL^<vmd^5i=ABD{JCs-Wyn}TY$ zn}v?}CV*~@L!yW<96%Thl2UTz&Rq(HY6a!n*HE~775BgVZOpy$mk<~9>DF#~6h>kM zDP_7&YhVD_x;1~gLL_BYuQxVFy~jxE)bEW_u~D^Yz}GT%!d?Kd$&@crO6*(+09PLKFwP z@OEC@><%|A2F>lO(R2byakk4r9}ekGUg$`tbebZc?)DGtUKE(cAlL$IEF(lD4#@g@@D*fhd zGaIAZ`*vesZ5?}7Zb9`cPg<+~_&YzrU998PH(zbLXqyt9o>6D6x1)NafjP3WY{%Fb ziW%QZS+rrx*N_nPzUVOiR@F9j<UqT5sZ%MqHk}xgLgT{S*RCjkC92CbWt}I~tkNzd12kTg$Jc`AazK-gI^3|BW zJL?xs8s3LqEpd5knM#uWxJf|rtQG*KBNDqGL+Ya zBU1lZqvH{fbVF_l5ND6B6bMjkRTYAH@X#J<< z7SKchb&FIsg+Yjc{(dwXo%z7^3|*4Wy@~Dk?9|DQWcVlwLo~`o6l={^IjB;SXqJk& zdgM?~=7KLD>-}CcYWd6FFl7B>Sr)^ZytK_KOK|wW^29hU)_v` zG%O?ws^eBo3(|NL&)H)DpZ}!@P@j$+w6^)vS})Qs5Ac?)4hW;RJ--Rdy*QiBZ*$D8 zYnOg+_8l&i$@7VpG~K&U^vB8njYS+Gs8&$Aa|0uP@Ovo91>E@U{~F6DzJg}IeMpiE zGsCH^8(RmA-^{H}!<}2rVWT6h9Zivz48_E}#Hq%ro`T6z94c43FI1~GlvaG4;(f3m zkMg{`JO~tJYx%aV#nHU0Bvm;G7VfV-KC)%=FX?H}%d>ub7uybc;62dSO@TJ5cBPXMX8_+IRfE|rRCHa9+p-D_$z zfJ!AJYxo9~lMm$x3Xv}XFa8TH=w zAgf<=Jn-q}vH@t?R905JM^C*=-#Ke!gW68WEHby;{GgnIW?y_8bPK{yE0fzPW2dPn zqeJ>J^0{7RI-=U9^4w;R4=0`w9Na*T0d;H$OfOaa7{;`)6AEC60gs zA{5X>ZJ-Y~4j;hGRK5keW*!>vSR`I#sY_u=aTpSYF z&`FnNP_JU(<^^p3v;Pl+*Uw}6@BFu@9exh7Sb}zPZ(AYAD)x)O&8R5Yzzlyc7y$I1n zG(3u^=$|m8;F9*kN=uzL8>&-yEkUngbLH4{CHP9zto>9^zwWMbwVgtylZ%65mmFW6 z6+syyUMG6m?a8fgLP2dELpRQ2_`(k{bK)eHj{nuRwa!;=c`1)^DMWxMsv`_FfZn+i zIM~5KnPC{BTz>L)DaUcVp;N(x5Rg)$Ua$91t0#xdUDM0UKpX?-&r2*WJ|?9$K>4A} z#zAym0PC83^6|U%&j!-|czMa6NB20-!L&I-aAz##H+M2;Z-i4kwjNJ6b&8ksW8Zvn z&Gh**$In`dSu5=Le7v`JyPI}`zoxeWhY-7A;YAeFDDtuwKESjcix$st| z7hwm4kDicBH=0swhAyM!lP{aseoWcd4jtU26Sru&s#B>S9aXATRBAPpibV_!3|Q}n ze{vi3XGYPt!3|k?zSLT!f$(Tl}Yr9QCxn2 z@pr$2$v^(TaP@Eh_gH-P4K(|Qq5BZtPx0Kl`X3YJ=tTqW{>t>b-ar$%1Nj?YDe8VrEDIBr4?^-yK$l&zdtl+ZD&=w7tq`xDPW?h^@wVA! zVwhV6Y+K#l0uhpWM0+O_Kl8pug_!eX^yF>R<0aFa^JlZ=(p=HBbeM?`Oca>sC=r{A z59cuclRv`t?|ldJZ@!5Of8}=}gU}I^e@ossx%(tK!>=Wo^@7U-lf|FiI8~>rMi07z zLB*4d$2}gHs8XaoIk#W5e}~7kZ6-l}(J$r3dK6Pr3x$@H%87o%{mwEC)gz=?HzbqA ziSlOIbgn!oPpsD29| zOQjNo5KrZTbO4YNxNt#Yaq-c7|Hp&FJMnOJZoj+Ywa3Zs-oqusm3F7;Ws@6Y>(Png zEB)6@$Hdg?|9V`b{UOKR{GHAdAHQtBL3aP@dzZIt9$nv^|5zpuxm^zVz;!!W)Df>j z+@M;gNk6n{_|S@F8b2n`SA(?65kU3zQ~LqgZM>MV%*L2yZrShnsXR8M(2YyyQ<68_ z@K=-28gvB~XjSDFr_a=MRk{EY%frL?*~>3k<+4#y%Wjk9u@M49XqF22{M2#W+tK;y z*8s3MI)Zmze-)*A9k2cPrwFPs0vV^dQrB0>P+)$?c6@yL`3>cvQ7Yo%@netV`l{uv zTkz3Kr}6sRKSo4O<_aKNOVcCF?wZ8K4J_DJbndxl@eIym=geJ*rW;<;{q_7rAkl)_ zNqFMYQH#8Tl!Kbvt^tp`sZ{DoO)=eV=B{c9so+{% z{vp`akJ0xw=sqF_w`LCsHRss3rL74Lf`Fc7}~gb=9JY8yITtWYRCk*8vB^m=L`fGCPktJPcbfNB+Z_g#rcu|ECr0B9gD zXlkdQnU)`L^WMt$F3XyC+1cHYA19gPkJi8qYHg&X!l|v}1Ie!O&ZWcC=F01YvT$ua z%ErtI2gjmrtn7N`Ux+&6^;<5@t_voQt(WF9^O4;GI&)rg+uNM9QGd-XlhiVx%RV)~ z{hMk|akN`UeQFqtjiqX8P+PEk!E3V7IdayY&9O7M{j^!_mRpr{0YEmzag2KF^s~MV zoPK)#v(NGIC+Bcr|33V}&%a^4fAgRG=UvODXe|$oZrOrg`Pv)!SKoUpi7$dSF}fqI zjowI*=ozMMLVXQaEVSP1H!kccTeUW+#fl@g>Z-f%aLcrx->8bzI@ik8`z}sB54@HxSZO!;*t#HY4TdQv0i3^`^oLuFTehn$RHA|3!k5t_}~LSHtQAj+8WwyjGOJ%>Lf2Ves%Xw?)T;> z>xOV~XmN&5_E)O>~2g=H#QAdFrF~t8yOKhGugNg!jEWCy$37MNgGwbNS=A zO2v4my2`qqSY*BA0I<>(sbxow>eQJa${8I5+vLtajUbPOS-Hg!7pI z(_-OsHKt#J+I=dvM$L&Ws5UvP+jiCcLR1gh{)5&w)lPbtyAS5^-q}y^*S`5J6bqdl zV50O;vv<9wM5dbAjPdb{&*Q2>rqLzlYWT<~zW*j^X9M`7IpZe;|`z9a|Nr z7(;)*ykG6#{P1loudd;>)2DG@D*G@qVf;&o`h#c~kEOO2$d>;`uVK)*LLJy<%P_UD zksR%B)V2lM@6h%|<(R*@7eaf!lD~TPG^tI2QR@68aE>s+G;m{ew_a{rpY{PDzmquS z`P`dIb|0iMGUajgT{f1sy$1BzRbz#bf0=$; zHBy);RaqB4e5S`49!9adfQe=W%Qct`LFAa@mJd^N%&y~7TZ#9`Du3oXeH$SFBiHsA z>C)d#b{V>{v`&@Rb2BcNN879Y&P*roJ3CF6{_Z^RyqNSfA+oQ{7spPM#@!TnO7G}`c@ZJ>LXg9{M5J}L*+_QGxT#st*Vtl{a} zJHmLHG`031xl`hUIUmTgIs|T-yTZ7!ZyTFD4%bG#QJ3#(Aguv_I_^F~grIemvznd` z(lio2mAZx`3N(a>P(&kVi3$XHw?P}_ptKGkapr~7SQy`yTaJ(Fr4ru$#?RyD-ueLw zwTPIn0EEE3T|3g#vNuA#kkKh|NJq+&SJMsC`RATNECTGlISmd874cT5eyauLYQKF_ z7c~S)^bJzoT?3#ZJ|T=W6;(%7{ZZgu4JOnfMdc>fNSi=_KGOx;=Be5o45+pe8vqJH z^}e8*=86OCY~x*|{Is8RQRg4o1UDu-GEcU06S_F($A{>xO>)F1qB2%-qb{+Is* z)!`#pJ$wp_FMbsdpMMilgvKs&3i3H{Mw%KokU-ujEs_?Zb<*J6b`sDW>*suAf=(Nh z1{RMAsHu(|G`r)__Q%OCjZEWBN{n25AETEqV(sX!VD{OAKz-WK^~s?_hs0BHy4b+L z0M^&nAGaEtLX}FzIwiXkDi(_@-IsWlj?vusLv7)`K$3c%aeII^v^SZP% z-3*<{Fw^HY3zyFw^)?Py672fm(zvs7?v!6!ZPHP`?ui%Sh^NE&WUT1Q8G720PmXReDs3en?2X-yd~#j3eDYW00eZSNjmPutYTXajtmrZF;=$Q!Xk0xT3_~qBWhC(6#atP%|xV>izSC1af z9j`O_+L}9l;UX@C0p_ZR<(vr9(`+iDGd@_Q3!)nWLKPo!Q#>*S6)j%EV4jJ-cQ2`LpnH zrUJwiAAOW;oQ`9;sf)HBJq8Chg2UU% z&&rQrJ)s@m&WmPyW!qzMzb<~FqidsIJKnQ66Z{W23h7$ z|8eK4s(VQ-OzK>i>Ple^U$!dKQ?F@mwHDfVS2b0g53f#=*FBLsJ)16l)$(ZWOyHXU zwve?c?NSKH-eA2;n)A|*GXlZ=y%H^H^AkNBL3b6v}QfF!`&d5%J!MQu5p-#4P5*j!R3Gn1wnwp!9i3im7d6(pO?6N`O!ER zdJUixneC{10G%fd+xGQY{rbIIUcT`sJH1ZISC9Gbw-hV605W%sx)GBL)Y5Up9{Wvx zI&$O#$a$@fPUAoML`QN>eg~oplbbTy<905eJK#+&F4?wy+}3Y5P7#;JCU)hceqyb= z99JA4+vt`5cKxGywDB_6QCV2L6(!TnA(9hp)go=pCsMquFW^Osi*DqM5#se9{RIDA zvxb8&y@bi_6P6CcgM;|>Z~P+u<@esgx4-st7#bMx>Z>qL+}hllm;U6PpW^=i_+8+m z89eu2{2HG7onLPoN1>WdCQAWed}I{={x5$ULIA}MCekhX%cpSsYrlh6UV5Q>87(sL zni-at@?Ig$(M}q>^?zC?ldu4iTo$fET)2t$=I-&tw5Qc%uzIGy=+s?axzecb(hB2K z*!HuDb@^{97mjeHy)Hejqq|>DXz1Em?D+FPgD6en#^3pCh)ZS1f^E0I&E4 z=^I{KLGo%!p_A6Gdh8yt^Yj7jEKgV6HS^=cy|#Q)rpf2W(5`2+2QgY1eCOYgk@h!TtO9S$MTtb8beC;~15Sy~ulU zaS?reeP}it&h-2G`q&sbI}6OtmLcUZv?(AF$IJOM)rNYFbF*t;=V_TXa9-Z_;Wmc# z@t7Fb?F*D%UGw5z8!ziPJ_)q<=VOM6QRoQ6HzNrLzlx>$FBhJr`btB#D{p>Jf#2%* zf_5c6A)lS*8&ypF>%*t*F|r#Ub593PgV!z2l{K#U{Umv@g1fGn-f%xo)~N|2u5F_# z?8#nf#-p`+cnv6GvkIKqR)MZ`G=Y_*JB z+28fPGAjN3?IU(Tu5uk*TSKwo9y3k)^y(GdzIPY9ckINeL)|YZ|M0UXZvq`b6L!b;{^^tjTu0SCAQf)g)JBv=96c`=t zI(pA2j$>4-H4J3>y#L}-5C}*qySgQ-R+ISn;~D^9VL_tNh!JkgE#jm{i`Kk{T>tB=Y=_|DnkQ!Ibku@7zbJ@}e;XY}a zvN^)pd9(XIKmP6&^{STlv?aKaAmAIY++g1I(Ouy_P5jOn zpYz6SG|IT7&m5FOvGdy*zYl zb_UaTXYq}%ywY)8mH*Bz&B{mbzxri7|NcklTdTIxh#>=kXfsB&F6jQl1^nQ<--rC4 ze+=(4yT5M+v%rrYWH1zSFWQm{Sb5ePa}BdIfz2&lwD3I>$_+Zi7y?ZDbrYz{Xa-K{WV#|qwwEHZa0V9`QsXuY@V3C=eg<3 z!DQ=c@{gbSQ;fg=$5=l2JQhy;BH}QFi~|Isj5w}91U?6?&q3hg=`BdvzaQAYe{&7a zEGiaDs8*|}*Xt;kOOH*DCzbLp)M`hotH9m6_;=S+d0TS+IPNf)?QK$fFzgza?B1u- z@^vkm<^NaV9PilRSch{v#)Ya(SFamfZ*<|diymKpwh`huH4nevqH?tf?m&0TFnR2H z!_#oRxAijZ7uz~;>9!H#HXgMZwOvUqF>M{#mT-bj^$FMJEiN33xaDX)lvDr&)9P4B zEjTlO0XJ6e;Lw)ccz)~{0EyLR1%EvKPAcIWyPmo%^Ih5O{Xkhsp9olhIb`dTGl)=c$s$+x`$HlNm8<;AAHThkc%*-s(mI&OdS zZ=o?b?8qU%e*KE!@;&;6g!u^v=H$UoMa=N73FDe#C-`VG|!`blszM zK!3sHml`khCV3T?qH=vrxw&|b=aO49E{8s?=eA9zvAcWGm+u)y4BMxY2P<>@>W*vU zRaZQh|Hn0oW$EbRqpufNWiN5Jc zO;Ee2(P*IA0Z4G%*{zek$?~ZnJ|_Jf-R7;0iX8(8=PP^MGBu#%n9GN&M*(5*Y6(7! z%*l<7vpfVYtvPD&VPZELbnErSq)zd1w`l;`?Yq4my43l%a(#Kh-f{cGl<2N6?s=Q; zh~rkC^ zJ@_{t0YQYZzi}+5hHjeJwhebChp@DzH)Uzo9=a?#@ArD?uYUve!=u2q0Zfc$-<+LQ z7xIj3YHlnr>a4~f(x}n2zcBGAALX=8dalr%L8LvD+3WZ)uHAy|md$as*}82U$46)` zgOa+V$xr<4$oZdO?1Mi>b!-X`Uiu}hPaQS5rBMQ|e#o?6w8nPs0J=!qECsu7)4BDH zzyW#3%St0zEnV9Z`jA6Sv>quhA}u%FgG!PXJ!H`ysoGl^T87Ieq8b6Z_S+@GEgU*} zy2no!w$)>%aK6tbTW342`E{vAT!#7e?UBtT$7f-?^m7sGX+$Xrkup~iIDHcW20q_7 zoj3vP-VKyCFx4w1P^;BZDiyn)9}R*K#bOar6m_r26HHMQwJ^Q=fVW1Yi8yxWy;iFO zkf>H`SYNLoied;MEFXcE)krsASF6C%63}c)+_}?i)k7eT*Aa$WHk>a?y~YChYf`>+ zJHg;C{&wLmo@@+m+VU>h+*b7IoaM`HhdFtVZqG27X`15;4X3M?v_)m3D?ZL@9&_Zg zpYwig--wx?9tBSC*`jSf_Y3WX4_ zpMJ3|ztTiaHwnZz`=w{GytTK3&HCT~WEiC1fI35-1ll?@jMsnuHOPG@AdYQEIj4mc zv`$cO2ftjjUaewrWf>Q)Uqc+nc&i7~)iliFpi zYI~g4R8_NR+t1E{0{;92Z4)w@K-z4%HW)WsvhB{XK>`I^iv0apK5${f7*6I5046vF zfWa#_QNBHg+O9ol9GpTtFqD1?t+&3mo~Gk!bK0e1Yidre>aQuFt`s-N9D6jOlK@m2 zFLl$|VVfZQWU;7!2vPqKBm|nn+fbd@i~hUUF?`{Doc^!Ag}K*%19M;d4K#+gv0Q-Y zOiM?*4s0XH%ohj$t~|M8xk}$AzximpLrgQ&bWCX(E--CB3q-PxP)4nBipwzh$3OfN zjGjM>rK7Lo!Rgl!m-~|R1t5d~J=eb1ly^LIQK=+Q?&9F?AP7(@6;Z8Lt;y9+NP+Hd zcJn^TR4kUzXf)7hG*Q}!hoT2GGXq?@B++bc%vsWo9uJ7lpJpB~>f`Su{Vd?D;oH37;vSZw&Dhx013JZf_hYKfSaucY|%qxatB= zgT}F~T>m%ZPVMf#XSStaS_%BQ7FF=GnIGbnsW(vyia0m-As$vAKmgdYWe>KLhB3Q3 zgBK>ggeb1#2Y24VYr9@Xf1#Y(rLHL~-S%Ri~Y#0U{VS^f$q1SkXre0}>A zia`Od-nxU&hljDWm7i?&aCsT;pFfK@mYL4$t&2-I@!16oEw7@1V!G8eFO3Wj11E;@ z!sJ$jVRwt99<_DQi-q3+aPs_T7+zXUH`l7|o~jnw_-o@tuR1pEV7s(W1+PMe`2$TcpOoRGu5HaP;2J_vFjR@bn!FU;YI3 z@o~%_`$bf?jWf+U^WUkI>>TPErack?sOLbVRoipHbE5cM`Eu102~| zahJ9plqb-vOD5*EYmxm8xXr`8FX}y<@3>4Crl)w9BkK13qKSiTi_9Iv)X(fUTvny| zj*qqN;$%}ce)h>|E$+8A2<3^JUzbiO3>yf7ja&gNtcA**P_m#oLcQKVtyV*$(Ll9Y zg_J(& zVS^xWF0=-KFbu4T^irt=DJ4cnM;vK~&WU#+V5LzmmryDdQO z$Ce!eNKO#zX3oDCBX<5|^QD!gQ#;R^KfE38^o@AF@r=f^v8~DH_U@VC?e%o)$n6*X zf7d9bEfwnb=KZ)}x^Q%Dk3ICAty%WOaW*D?y2*u0+sE;Jf4>|P%eKSEZr{I+pZzkq zXU4|foRiAzEpb%9t#=*<#>eMpvNkqz+taq-UDkQRUI(Ms_v6ISFv_($4qUsA>jw|u{FTc%FtyvlgTn)ZIC4h2W7%$-YHvHB8KFm(;N*8T+N_!9PMQL~dJIA+o z6<^Vwox2eI`Wq-0H|}trx^oA^%c~^Bhf1^Q&~Mo%es@Nlrb|zKch9n!(p{saB1u|H z@~lS|d-l^mb!PV#c`zemE{UxDt5|G@Rc7l1(0r!7siFy&WUY$T~h~&6A8dKLPJ-)bn z@Ahwz%5tMuUdP;rf6!|d( zJW07F6PWr!p*WST^b9OL6U}_r!`M`-*D>F6T<0O3i$vF@kr6bC-5Up4WE=hM>FV?? z+?<`kj{jG0e{PaQgu2d{y*VHaxYFBP~F|=V%0Zm?#-@6QX zZyM{b?8C$5-d$hG(qLMtI!!Mj;tr&&Z{l`IC9sV6n(dDqBeB|&4YUo3=O33&6CAkt_h#k z{2~q85i6k=Ug*9}Lc?`4kHUK928N2`8o|^UML{l&Ph%v!QQrX8_Z&lY$9~ktrm%M4 z6zUJwFmmSmSo+c%sESEK2axlMJ5yKsb*cc3hWh z&wQUH+l+7aUZ%`!0G&4t`^g@WOgOE_ezUjtgIfxM-H45YbU#RT>mz0>>v7L2OV~V8DWuH) z-}mM9+n2jmW%@_mtUS3?-MaU^1{!0Yh}T`WGV|n8xt#Ch$&msE$w5aFgTUkZ0`6_h zV|HL19yo^cMTp8s2Nmlw|Mv1Is<|R2%VQWX4s}8~D!Dwqy8Q(94^G2pEIukI$di;$ z^UTM=>L@&f7+G9KzG*9hi-iJqZ{Gm`*t>Hl$_`_w(ZxkPclA0(7MIC}v%(@f@7_nN zSitkM@H#9bp&bl7rnlESzWl7 zrqOHd)~=Zxb(;F&w@_ScqdvV8>$`WMF*%dao89`7B#oh(YwWp4$I9G_qcjHgk#Lo# zSsqFj1kUZ&1zILY|sBmxY)%-Smo=jPCu^HD@IPH^j4+$B;jLScVfy3_KI)v z1k7F-g`}^S*~WX;7Sbi`0TiQAA_rFvHl?m&ut}9y@QVbT>Dr_JR&sO}Im5!om_3g45Zqt-{9bDspN?)!qqxhL^Vaiah zR7vk#WlrX=m(P??yX%es#&R9pNZX}*JEqmyrp?Wn{mr=%_N-Kbz7EN1oEY1bvG!&u z2m(<5V(oSiAEK_;>sI_Q44t|K$&1q3+BzDI29}nVoOoR74rrLvQRH&D`0#VP9Uu%t zG@DK5;b$PaIV%an7YaqlZzesOSF6=T!|j!o9GXoZwVFVq0l3WNIA1}(w^~tp8W=oV zm+T*lr{$3x-yYT7;<+$!(pu-@ZLgL3Ds9e`-PGiMo2)e%jzVO$nc^45sjH3j}Fu7vboFNva$@&E~;|KKM*= zS{Jiv8Ew$4i{s4N^s&Wxlb=p*!BnPZ9naakiUC3>)tnj+kZsXMXa}fXLBcKuB$Z!87MxO5ttoBlq`M)}c+QI^ce{D}sd6+aY zI*L;RA!`2CTn{2!OKq)1G&MJeTD5{l+taVb-gojaMw_$1fe8!^RC~%>dib`93e*zz zL_G@HlLzJ%o? zZy>A=lUxz=x4G)x!Sz|+6u8_XnSO3MtB7m@QyZwd)>2c!{hGo z^f1o3G6tyCYG^c?SYO`&u%2REpo{^QmLjj(b8{g!HW&aOoYw&a5Te~V{k(bFY5<*m zG-S!QH}D*Vxj<%8UZP8!q}4qNQ!BKd#(ZbbKTdhAS_+ zo~pFHfMi#=Uf%xa(WecjpB1ofl8K$8cj&yc;EIUIoB#cj;q{5A4D~VKn9;^J#|-+*~{j0N68j5(U46hpU%S&JSUvtPYO0!v^lJ zTyhv~>-;?Cqm&;2ZT(`d0-xpL6+G|dQOcFTAdvTb>>GK$!-HdIRT@?*{5ez@h~!Gf zaByTF7?kg1DsS4}cp^GBGK1O5736W$@6ez zWQIsD0&0Ajh+dk5M{>;e`wua?w1kC;aV(BUR|8i{B^=tTAJ{c%V7-R%CkqHW#=oIq z0y?^|g!!q7Oh(&TX>4H;)wOj5@Z)?6%{KO5yN(m z?mvu{;c3<_Z`ieSqk0qZ>v-2~s4aT}Jq|(R>o-)HXf8lM$pNAb zsjW?p+YA2fH*K`8anS%5wjs0-fx~cGKnQ)Kv|Mf>2sW^|*tWb{3xP}?z2wGeqtQgY zUPnH~$%iW}m-FFy9)ck3+<3uIE|&l>XMErHQ@w=cayc{_O_WMSjCa=henb(A9}|^H6bsRz;?>qNYOOVtb0v(IMiGhta~qGbeP9yv^#!zf8)L;G zRP$vb%>fdrni4z!)Pg4F8!O0pKDL#|aC_}O0D;-+6v}>)$TOW;g12#N^)3Virpn_e zj+aKJ;UmQT`US4w<+c?VOs1@AIOOmy&UW9B3pU0g!09T;~7 zslLs@Ft)IWCsUIMHYuY>8d-`Cxr+{lmZXmex-z-30!3ct+Gmo9to2pXUQMO$R?R4G z{^puy^L1fpy1$u(_e>s){I<(#wu#NdJzvG>Fbq&!e2D4q{acKl{T^=p;(v?wj=k1g zn$`yP|4L`4qfQfNbE8$HhE2!S(BhgV|7Po(Z>0=D@1Kui(c8gI&)YP;&X1yJ)mP2c zF5<7=3xkUrKU3bSB^h+BjjQISoMWz$s*LWoLdsiV)sDtA*U04gusfc$dzY&ZXOYg$ zG0?pn$@4@~8dtta>78-JW^IHRd_Rw=sTMr%=}54g^TgYl!!U#yByXhhJP);6&ES>n zY^&W4jNk3ff$bIw1>4zVWVG$(Wg39j>vaS{fJUR?yq#Gd*3RX0>|ZJsQ7o2XqwNU) z=TR<~F+4of_f5}@Mg#433#C#C)oPNg7vwn4N@G0%)RPlsFryIWYag;OPjn%-&c__P+bxUcf3 zB?Ii~g2mg^3U)>5YC#K^mhZr43@?rCL7qu*nB&^|5*{~Jv9nahq0SXnyKmjb&E2y& zf9)!s-@OM#V{sZA9>Knu8LVySi?WNVYwMVLJlFAvm z+aN|e9!`?TL!TZva~{Sg#xXOUZUo(p4({2D@HhWHhNq@B#iv}aW7q9FkTAv^Eh9_I z7++ZEYP7xc?c>O5>Mr6xH7V2H9FZFU>c8ZLzB&*|N=vVUqIuZ;Tut{3x_USrxS1uj zfwQiRagAmQjwxWad32-hu&E!?=NQ@oW~nRy%|lc#pTg+7{{gi_FQazoB>3rJ{x|l9-n~OCYU!q6uZy345vTl$_0Y0KjMWV6E{w zhW_k#vF&gE0L6v-SbXX0Xl&b)m`?Ar=5b=TZntH&In}(Z+a)%p0c$F%nsKSZ z$n0(Dq=$R$CPps3hv|3z5bL{-V(#^yL34DQR*r0ZbxLZT=t^H5K=&h4MAv48*tSjl z*cfcf)7KFQ-n?gPX#}0i**m~tXkSqkZAj~2etmr%jYbo#RtvS7eF9siODlsA0*yu! zjYb2tS}oPPn&(A*;pR0`Wz38mu}WZ4B|nJ0qc4Dtsof)oI)3?&SO5SZ07*naRFYQI!$wQv z7%hz%$I;Z|Ig~eQ#wM+Y ze5-{$H*Vs_{&XYrXMy}6#Qv+-5x_^NwVm7qW(XmT6+HL=W^diWgPlA2GTI(mUB#Z8 zx3J^x1BCF=){Mk;1-UMvyT~;nqGx7(YjdX1dt>x$Yl>VdTb(3d8y}~uq3JkMVR{*; zo*)S;yU-}5l$lm=6qg<&fA0=PKK>qRyANUc*ejO7w&G;V1B{eJVOAI7H%qVU^5onk z50}W<#6w7C7IRLatw*W_IoAXF?88WyM@r;bxK?W>NFAfu{;CCZJ%@>jDazEfE4n#@ zEz{_&ZK82nSCg+UiBZ`mjU-?9=*v2Lx+PS_AsHLnW5?z}SBDv2Jl(+t4FFof^>SYKbq=;&x-yw4j&UcS9e8*RHN2!K0xfU8#p686S7 zMV}qc?Z#(o%4Lksu5sMuPm&n)RoIS`w4Y>33@#0z%G*q9mdVry>N-^&y;3>H^esvG zxp1#6gV0i%jxLgLt>l!9hbg6n{r`b_#mMRSIJ>5yyZlV!x+Ml7IM!Q>0Dww<7`~Tx z$`Q=*BsmAXg=SF0Kw$&|4C~D$l=Fk|J+&6L!zS9iiArAIi@ZGd1MD0*f?dOhzyJii zg;r3*Kw%gZGc!cS+8%)A`V%}_zm4(om%$jrP;nGKQ_|bRwY#{nd=)#Y+c92x1?{kj z({rcr&E0R~;^HN&G*|G_4S*;Mbq~34C+r75w?V zA7Lb4#6V?28?^!q72n5C&At)KpAw5dH?$+3gVfk$9iwgO2{|goOnDG{%Vn^3h?5_j z!mIG`alL`LAV5I$uj9ib`0A^#;XCiY7aL1a%D37mH5;gG)M7lYj(Ky#4{vwcHZg&1 z6WtF+=YjwO8yni}`K;=>ve419=TTX&ISwHM^5*Ur&U}LR-+CP@BiU~9>PCmpT|jkZ z9lT=;Ky?v3?n!h_QN34^uD=0Ek>-4f#xz%EbMKkXX$-crJc@r5Ut4x}t-AV1G_hWi zj=)ByI@wxm6F=DVunf>80nyQG#@FD4$fT(R6x0WAU>rfmvI50NN}EK>L@@ z-|eeZ$t8MUR%EWj!pK#Z^i)gOE$7Cb_DU(=_AV>A@OBc`cJ*!Zy$fr*dilPbWhm{95CWVFZU0p6b5cq&at0ztSFKhX&1Mt6?^)iZUDRwgtvs5| zCRSEf!MSZzoyMzNE@|sM=N$EV1I=a=x!j}`zf!3r?%SHYmY0{Yu~Ea=*jVS#c7N1v zx4}6_p-|}CU|W*w`%tRYA`IS*7%L#^13~AxH`+=Z-n|$1mRDNYY)x8sjGd(nu9+w~ z%*?}HAH8^-+T}6vysM1e^a475ru4solsi z9e<~z&CilD9&5}Fh&RJW7ZkcTnfWp0TNh6osJlClD;F1KkLgaAq`ub$P&-V8yH5_f zg;x`Pm?FAP4{M9ac|Ime!-hDfa=o+u2=$y?YLH!`h{K+BIpk0^|iETdG}n2^OS{wE2|I>3$I$Z1_IH|}|EpV+3Q9*f{zc`0yA^PlwF< zBRmXMnFQHMwGy3gXwQZcJj*{pRDbUFpio-%hv=P5DS((S<*$ftf->^2Yhyq+tX_Nm zWjx>^#!mkg*!7Q55P*2)8)!_;I%;kTH)beZ0n_@I-7AuWD9YLF4X(6FIhcLk1l7qv zIjO{U8T@7qgV#U8*!zEt`t)8r_{y)KJve5i7gk-;DK#$h0mdMZ0U>>kNO}z8Jo{;G z&N;%+I3U5ij;FJRBfd!F9|WNWO6&DH*4H=Sd7kqs>&P%%IIpOp8`6zN1FcpIoO5t4 zoL5m53I(Ua-}Af?^9ma1BDNINP8X z+Dh=OcxIt&`6kK6y`*v1F@2_Tt>EUGXDgG_fVMtkF)MyIa?hfsR0J!Q38`s{t-6*f z?VT`HEyN{vLHWYFL#`+)07J0vnqubxs^4>LaEPjr8<_B?b>aB!&DxT&uRfC%n zv^fS{_?H2e;iLYnHgI61p>u&tvZ0bI2p1(Ia?Qd*62mQsRwIC$dmJSHE{ zVP$j#en&CQAYk59wCm1YjL$6~fZs9NRwkgTCq#eMwRH@xu3>FxFyX6Yr`s-ypN&>iPgRwoFWH>MP9mX1+<~i9^B=g{4Q>{@4E+?M4o(`%Yl# zH{b$_0G_F%V?`o2=WP~XAySLSKyJTjxoP-^DOV0+(|bF2#|oAQMD+qG8F zyj*>oY4tOmd2B`x)(r=z%RhFwyB{aTlRb@#78tJqaa#$?6PExWV(-@;^d1m)Hi1Jh zmIsrEfJ6WR4loKNYWHz-;SAo~{qtIDFbG^*_!tGhfWs3fv2$=Y03h$>@SpAd zc~FDK!{bMBWc)}hxm9vy{LH?eLJk4GKJ!M*kHyA~CeEhvXQ!MDDEWC5yF9SLUYE{d>c;;iAdHE&F@zh{t06+J&uWRr8FoefB zcHO;;=PzCXhZi4u4m)Zb)&i(U$iPZzI zK;-gJEt^cXtN~~3++q6Hq`EhWL_OlXfudO2BNTtT^_3<~wkzcpag-Jc9Ln7xxAv`V zt%#0ArBeQbx)N?myu{Y=xwF#z`Kd^mq3-X1;d(Bu<@hA>er>gy9Av%}V;IShsO+ zgwuULK&#cl#>R$b#N2MTwS8701nTw3$(0LlHk(a6c`}dn^>xi4xmYZu7)O__ebanC zkAZ;-IOmu!4nw8!a?#S#G8PvXF)=ZoInAd*X~x#sh@stXC*JDSZUbk|2rMmaGMm&A zY%OxxDjXj1O2W+9<992Ana0gOy&U?=ujA^Z_wI7L%jK3<%n~x~m-%EORyEJt2HDVl zMQaVk!U}QO7+I}1W|)neWqe!j+dDlg7<_B)qUnj!t8OaEnGvRQ5{`8A1M2Ch;>GR) zdMUc)nRUTku0KX8H-K{9zM6mvmz369%Yfh*E{>oTHn7rM#B^m_9Dly{2mxvQnHu(P_&+89=UN;s7*aBpKCfe0~G8o^>?5%sVIp8?~=Awy(~ zQa;*vgr(*hD!C#?I&s#6CZ04_@!Zf(d~N&jPJ4^EmdA#t@#63#e1zZ#BLK_=rk>2> zC3q-07WlP|8Xhk!I9gk$$+;)k+3`{(x3^fQ1+vl`FP;GB9EbMq!}y5Xs}dzOMfT>Y zZ12vQ9%4UTDmI%KURow*v*vZSt{%F1ih7~B4M{Fls7< zX$vse8-H%TOe?bv8)Z1N>ZSPT>M;4T@Ye<1Jhu3PL zeETx0-~SKblCxh~rAnm(T-mo(>9`R_g$sS{k^B@#9m)&x zPQ)>IoS&=J%*|(z)T*VK5pVU-Ygjq-I{4|o#?a+67`b>FOMVW`@g0tDq>D+eo@z>spyOo z1i-_Gz}d4;7Z!Z_09sPEe6xb+w0b0|wbS#pygZZ{eP=sghLk zaY-kpY@*{IwJHGST-qH7r-ivzjBJ3{=J%`szg*N_xb@sYQ*h1 zwi9%mM33p|Xq!r!lE2^amg}msBx(4l%RYbyhQXy(y!hcqaj5jnE#nAdvzcyBMe?bX zc0Fvr_Xs}cxV?8bf?N*kgZ*9MF|@i0za7ST@)(0hbB`Zz96$9jK7Qo{<|if)=6c&O zF4yWPHk+87dxHH}uS0+#%=VqQ%h;$^(Ad`7En23AMiDb&K#Qeja5|3co|G(WyUUXHoAR_VQuLgZi;1!I zw7Q(H*VdN#ZCqgE_#}Mm!U)^$TmW#~Ejo^jG zUB%aB2~)#Cdsd8@$s9z@59p>dZ5eYuc~D!zAKkx*k$efiG;;_$%2m=f^oWQ;*{WpG z2C%6mpmVg|zA|SXzmE*EdCX5@Vs*ed8mn>y$=O!*X;XHw*Cy9$M`arqjx=>23~7Db zJ)-pAy-2~X{%^){r_sqZR@`w+;=BPaTJU(I6NiI$JYidM8_UO@v{iuw7%M=Cb+Gs* zpeQa_&gnH9K03zM^q_1TLAVMb+Q{dpon`GtFTB9u`@rI2&0*l3ofwO}Zbw%%_s!;+ zB;WVZYPC=*6%#jaKMQKLBFua4Tt5vieGB%A1N)=&5uQDtq%!r2arJN)W~N$0N=f;< z=XkoF*?2ff<7{JK^L=vplE|KaZQZ2HkC#hM(Qlzrx>vgL*z>!3V{+`xV|Kq-_*o@e zUhJ*p{b1zeJknd2=9R?5wNFCdC&}nnpZpLW^YHxCTUe|=#D$07!I$>`T4HG?s=F~h zu&a+RE%4IJPr@VpeY!e}=>fH`NM+HZQ?EO|5XBLC%{<2*iy7D6xzoMV$}$|NPU5-e zzX|}zp&iH2X8|dN%4dKch=q~2#LluF>TsYOyAkfq8O~9%j?p9MFJSxqhY$iWhNT!f z8t>5ov^_U(qY$+5$?+F5@y5`L5_ zwHm(ox9>oJAq?f+K(yDWda}+pd-;P?_~_*mn49kZ05%f>Z+-sjXKDn&s%1hZDgwROe(*- ze(q9^TzU^PfA)Xl-cSA(Ru8@o;VGkH+VUo*R{z^yht3Byy;)=XRz3ZAh}vhS@db39 zqW(oZghnYM;+@$+K-r&2%o`nnR)?0&eRbE$rAj2{HY$+`(0ylRBrYI#w`CaZ`%21@ zIqNGhEr*S}0TWl#9wZE|@;R-KfTY%?E?wfvLbhhbEMd~`wD|6_C&kHDPS?BscyQi; zJm929;NZNDkk`O@4eekFjO8IjiyX){l8Cxv?^mEw@v(Pr0goQlu&}V8;mCYGukDR8 z#!#tLoQBpwWaM2e7BMj~fl8$u8+P}4pg0HutgWqMZEXz$1C^fAejcdZZadqr7b=yC zsmAN?zALc4zNsuy>C?mDKrc8v;+M3Fb&s1ICKBGK<&msg)G@Sx&L56A;F*oKdj;0% z)y<~1kbGo{Ze>amJsRybG{YJSei`NXnyIt_s|zGTaI7}xF;tuYn1_wlG75ePd0%-` z3U~{R_ByJ?F^$ueCqKlFq35w{li4EbaGNcX2iFEx%GSCqK)C=2sYZQ zxW0G}+bYwL1Mm9MWvn!paD4JO2J^cxU!TWPV*z`HcH^VDkCFFs*f}r(k1?ptA6?OA z`cC=IgVR`T*YH!jUd8dTJvhH~3wPEYV6s?^Q_JlOfZ@&QV*n&nkN(|W9>q`1zR?*7 z3KCJlQ-ws}H`fgC@`oScH7}1d>+6^=m9#6YW~Qf+^L<>pdBgnt03vXhYX>Mcnz1)5 zS!0isA}f9IrIVTB0P8>$zYVUg!3(L0=2k9GpB{}aF5%$CEAa_v*@ldKH{Bd!^HizT zkZ-j}Z#30Lx?%^`Gf3P>g=4}=d%hA@I{MqS#JZKeZoX*%SS@L){H_a_X#H&-W;;=y zE`i_m+g3n!BU@-libGpbkoW>#tAWa`ix~dSx3D}giPo?DCRi>9dR3KFPbmeU0@E&~ zps99nm54${Q~Xb&=t66I zm2`fyhN0^pVd~vK0WX$u{}+BEv3#_i9xFibCg4}0dqn7;dIjkbMYC}}-|5B1HC5&{ zQEAsyHJdH8T5Z(pbuh+aW94?cZF#|#{7qwOATqRGSy_SS`QThw@m-tXxm?b9&9pof zY#K=WzMptaRIymlln5Ie8(3I~PEA)Tn*s9-VHm>m*i-Q`CMgJj$B%)JK6<(m#HRMJGlda;pZ8h;rgahOE5D%5q9 ziOQkeAxV323q+g(0Fw`%VEcoISQ#D0nU`P6>@AuJfl}voj1#BMpt#XQfP80@R^Hwe z#%5N4z{w9!*uas z!|<}Yxq^eCSuCK?G&eM;ye=hj)t2-wx1>#@ZWQKxG%H0QjC3M2Z`SEU5_hn;Ptj8N zaS3!OT0e+tdSmZSwrnncDNGFGeK*d@}ysbZGf>7IB&u8T;2+|2IuxZa?^O(@zO_m+Dzugg*41HgLTWpT&LvhZpNkW z?R;q(Dvu|v?#bmdORHmbTlcE=ELc3VD0zUc5RAN${B+NhFw%qYhZb&zseH0v;Vj{< z{5DJdu4h|8>y0^Fdh{1~WzRp_6rW^GL3WI6#&Tg~*I3Nw%J}mB-vl5~%2xp}?3;KE z48Yvlb=+G%kC$hEq04tid>~2ycw^5mqnI1ea+@05kMV(7qpt!!IiM8xcqaG3^z!=g z+%MvA9g|Y*ER1*DkWF>D)!diy2=ZkRV2rk@x>H5J^OldJ9}oy@zt-rr%9ODQTq3)kNwp zy!g478PvU6(tam^XsI zuAr4vYHBE#NY^Is7>M5Zj#{fXOyen$I>qb?H_@A+89aof=2F5@P8wwENo|mNPiH_K z&jYq@-}R;Ro|IMpW5%-eLfIsqY&&T`c28OOa3yyYJM=>`527zW!gAg1AzZ6|hyfX7m&_T!` zaB2QSY_HDZxv?X0M;j#l67_R zwuuRBGp@e?fI_QhT;xVz6zVpe;6=s0~!M>{=-RcBC0ydXrr)kfQ4Xx9rBS}hzo zcLAewOPwpT6r_s!gR8gdy;k+Ih?K`Di?<8U6La_2H8{`?Oh78_{(kN-VU_Nkhg z09*e}`BF3MWTAu3|Eh#aVI+Cd`3FXOD!%&vR8^>}7WAv6(|0Aj0P`{Wl+C&%gO!apPD22ZZG+!tx-%4@J} z@ks)%y~Vew9}um_XV!0XmeJ*0eO1uQV$W1*fZHZJROLxm62wnb?W!wh5tm-g`&5OR zwC3n}=y_*FXIWLSTb1rvqF%9cl%~J2=ECzm-L?P#AOJ~3K~&Fa{F36E;gVci4rYoZ z$};B7IHt0RO2hUzQqqbpL7N8KN(Pmv(TmX|l{KTCM;BsH`AY6;n?y;mT*Eg~3PmSh zePh~9)MJ=g4_7*~hDuiVJLTh@&0xtXgp`RxcogAF$l&0LFWaAz|Wyq?fsdPFIn#aXLn(IVF9na{~>(N(Lx^dt{(LrP4vOE zen97bx^~$y(#eHe71?^WtekaRtMjD!+HumtX)7hoK<<^9@etKp=P~j9Z(+4EgUi43 zBf^oU?rr|2-$^rM(f(*nk zo6Q!AMfWX6pI0gt3!Q_{Z4`^{1IwRB5(2n$N8tMPt?M;gg>kd@{A~GcCB`+eW>T88 zStBWKn#@f#oTk2)u3>aFu(hOS9xjQ(O{QKq`d`U3YF1Ygq0(*A9O*l`^4P{p=88n~ zRbg`VQoQZ3WW()jn6_U8NI7hkwr1;yivW%GO81Bv=+nT+F6_?0P%eyU=?Z?N>l`WX zKsi60=pf82gQQY^Sc@;fkn;-2d35g2)^n0Ev)f!6)-ym28IugRea-MudElmHaE(DJ zdzm}bQjSxek!=Z6-xD%hGD^?25_w?o;5RubUov)i9DaZAvn6w5+SXQmJr-WzysU zdo`siwb0%JFv{S<&MI8SH&=JNK6)C*oObHF$e(==tNTx4?v0;CFfi<#uann)`mA&y zD$JZ0XiK;-H;jYO`Yn45^2RE9C?!g}(5&HG53XRTRl~o%dk#Oh<9SRJD_UFXe!Zn> ze>4NhF`YCc>Nr<@Bh3y2k?Vsf59N7O8FK^j@UxPNsC0u)dUZ2_DuYZuZ@Wr1l(u<|jR8lGGUW4-=jU85w<&{S z>42+VuWO#R|Be(T8NzRtmY0D~J`t$Zww!g!TGbD)tdvz2?mZ7zI{RHR7I*W{7N5%E zI^L$~qIbGeUKQVzk?s6+o=K!*2_0k8bwNo}G_JbO)lBcoMaf$BTBE1bk($0f+4!6C z>5be7GaCwfI+V#8R0tklJ?H|kscAd^yPGP#>RIwKKMH-PKDyUgK%)h6qq%?&@BRtC zcHp0Y3xOZq`D3g#=kel>zlR;ehpasEei?5c_{RW%cW(XxRvS;SYxI~^7yEifffGCb z9vMKu_Q8GFF}T-A84Ze8cD!v2Rvm0pft11^#P7^2RZXE(7cXhKes%9_q(rW3tfbIL zMPe4eiOQgR&drf4tQ1K1Ait~xaf&!jocahKzw{y=?dX2J@QG6&VPs(`HZ+zeY8CK_ z#PiqQ`v5TX zZ`1rt-utfIz`koYpsul|+kWz5Te;a5U7wu~0(|^(q?G8VJWL3@{G(GCURpuBVh;AG%s45Z4*FQk*DWULeG;h6 z9K^$K{04UY$?xC`zkL#Sf99X!&M*8o2nU8q3Z0n7*%l)exv#6ry865Np&n*G>v3G+ z%nDD8BLpC#uU&a`9TTTMfZuH5;n)64tnEJLQI5I`UqvZ|;`MWmGB^=QT@V7-DE>2%hI*YHHG% zR~BkEo8X)ym&-j9*HlSQ-Sv7M)#|`!T^uLL)6Mtq182|nBL4Tb?rtTJ?w))0yxf2| zdt7%|I>=5gyA5RNGhK^pUV3~6S9$fc9+}y)5M2{w-nv{u|EI8C8H&o4TBdbLFA5yf z{OD|`mqE((DxTiLE|9Ds^^d2w?KJ8YJ4b1fR0d|OZ26_(@pM@sIUbE8M?l)R?5@C( zoNR>?HA38&mK7DHdP&3Lby?mmOv8R&q1k)Zgi0?(e8S(|2CSj9U7uV^DfOpUhqMp%a^E z+sK|P9UjPeAqtC3xs&84s%KF0g^kt`$MZT{$vnIY3X$y$>Y%Vz86Ycv$K=Eif5;CSs82t-LC-tJ9>7g zP$=N))dn6tY693AL-eh}xY;FN2!TQ*G;j^)*d@ zZ}QZC>mIq&<~Zu>iy~XPIw&4WN9+D7wi^wao|ac=@o9eUFOzLO%1&D|`+l}mE{x*f zwr^Nb7NyQW@#8F&pM_s zz0)dOtQ$F+H=*i|c9OrRtOfNAu4G3*xwbLyZqf0$3mdDsM;(b~BwyR;TZYk=NHRE% z`jz}G4?Ozq0F#gA@WRKR;QR|mdv*{ubN3!*Z{9{}qd}aHc}9Cg=9m+6^Vn0qgm?JZH<<~n(4E< zT0P9wR;?VAW42j~j%L>??wTcNnN9rcO6SJaX;Oqv!&g2;_4Zk`ckIRD$*-X`I_+$$ z?(wO528zlrl-S6OdAak{;B^QHNSUdaugI@9>d^+j179w>In2lWIBL3#$9ux_Ug* zLTz&E5M*6@p?+m4vjj;RX?L1*S=0>kkOT94cwQMED*(hUOwX4dSW!Hq+cy}5*Mb0# zZpLCopku?-R79)QhVSR#dHsD0>0vtzU3Wx& zzA0)K53N=U<#P60A3qIRSOBhE5m?!p^O71pix@oOmxOD3OXKEa%bv-+?X@Z?t}SV} z@=^Tk)tgE^CgwKFn64K{s)wG6k@xaV68@6whg^xMn-3`$*@oM+Y`UbBoKr89j?=qK zdA-tRbOK#9oty{w;q~9e$vwYE?!BZ#(~KKPswJ-9B{r&6z3NP&V2CBs|_+H-Gn3Uh^v%d%d(TS^Qtg;iY@BSsLo~Ed-4=@+t zL}EDg)4ZO8z}2zPUlGhdlKk&*UdGTx@yFVS>bWgHM6t zllz$Z^WVeZmD9NUTmKUp`;S5?`phepOQt@LDHr9xFgybKhArSq}NU+gLg}h3z&%nw@2so6BKfU;u-IgUIFl zPMQP>E8%^s)rviFKPyzJlw+@HE^psIE_C^_z@0k)@8KqH#&TdR2hQv8yd)3in}GvH zewkxt#{zCZ+*^G8y&E{E^G@ffuX#~?X0)p<*SpI_<=3>brr{|$@6z?#J#*{eS^c6{ zQ>itDN*c11v>Y-HebcR1nBZ5*8}yyz)Z4XGTcZ~0kKTNf;l1|+K8xuxORFcV%Wb8H z2qRJP5d9m}wEj#2WTTXOTj@o;84u05wVSzY4{0A_FB!S0*4J7LmnGQN;FvGth{ zCgR59P{#DGq@pIsXUcL3&vVqJ|pDXma zj*&QO+(+@GE>GVymT{ENKOfR3w(5tb(e}#7u;u;lrPF6nU0siRkn9iY`fug@0ig4& zT`z8wT6!3hCOmSs(M`5hTX^wY=XLsdl#@Dm&`s-W6VuW%>$iLDGkNQBkc&1aX=m3R zbF!sV4b z?E0w^nsd9ty{0}^)`-WkC0CU~p=fE?L=8OEO5wt_uDQ}&YusV-H^pH|Shzd-`@B)! zFJp4>fHN!$-po$4-O}-~3)l6Fjgv69U8ZEtS;JjABwK>k$7Y%=s*hhCFDKoEDxawo zsE_}M=wW0!JJDP@q%5k8l@*RxvCLa#Oj%oR2Yo(r>+56+9?u36=h1e9Q3}@C{{^Dk zh^HSu#)V@?>`#_JdvD%Eq29#!{2~TcYuatm+{jB(dA*LA+xJkcHxU$anY~d1z}ny- zCUW!eTk61ctB}XWK!46nZtdBF()I@Vu0Um@hMC*llhL?sX5OSr58T1A6Xd68W zogSxbQ{?@7vLC8CxyhEQ6e5rEPv*C0CF8q+x?>*AzDzqBs-0b z0W&kIoVi@CV{HB7C71fX2jBP6YPC@)^sh_yypDJCXUrgdejeD^5Lj5~p9f>P=!S3+ z#`>16lhvO-2G5d5KUlmQ4(}c(NkXvG(e+4$+gfm!lx>&6meHZ5r!}CdBtJW)!n8`R z;UpE!fof!Re6GLKbCM{Zt}`Ytm+rSa^%A!i+G?I%jkW~@+F>1rRa3$z>&C0UY2F2_ zd*S7Id3YTIC;N6s$;5O{g^=TXiNb_}}Hfjt2Den|_7!%$=#nS-@H-t~!0}sf1y@on~)df)nF%;;cLMll95ic85>w;W#m9mc<l2# z!Tj!28Ru)YmD^bAtB6i{Is72Rk#iT33qstV+3EaF-DqHa1F!t(L$DSnSKWAV+b}SA zoWpN#Zoxiz>NLimEOcZn0T%WyYym)}R>LbFe25O0_)FxQEg%#|`_V1Gs2}rKA;BOJ z!si@*E5Jaofj58fF5Z9Rb%Z@=-t+A?m@r4K-plCeXElw=X;@dh$gw2LxS6Y~Ob~0r zaG94mLbCB?aE&k%BnT04P0eSjadAs(Z zUs0sDwh|I3u%$DdRPg9mPEoa`QvOk{rg)>bxGcRX%+T);E0a7A?V)kZzw%A29DEJa z-~V?w{=fVRmXExN2S4#^sLedDBFYBiD1=W*oKw0n$$!Km%Dov>OQbp2mKk z44&P2WCPn~9&SKQC14X|+bUOBagxfY6N{CtCKn1@sSGYd^rJ;8H(7Q@LREZPDkWn9 zO8TNJk}8!T`6!;7AsgY*nta+cFaY%EJjqG@;N~b@x4x3Cb#l@qCAsFlFMx~8`0et+@ zi#Ynpc?_(qL&?Tb+n7g#8|4zhT<@|=yO77dT{Bo79YNsd`rdF(Bf%Kft5uwO6op^n{0#h2vU#K|GhsgMYd%NGrMaY|b{e zVlo*Qn%vysEFopLbT%Km9QI0V;${7R{k`Pj3L8KDm)QAN{|e3VS89;3cUE@ zvx{3Jig0}|^?KIH^P=0U8jU6@mHuwix^zk4-aQ})wnmn=H6;D<=uX*X(O&X!<6;+& ztTwj7(Pyecg#S3)yeEM!AGX+f654 z0+Vy|sI1ozLf%Rgz4w8RG#r&R)ck~ZQgdMUt=qUeyDQs4VnOFZx8B2a`orO&yk5hO z-~sOL-qk%1LU(6(!3#Nd-MWMFM&yB@Rvm~9o_nPSJ9k*`DjPL$--pLJX71brxHJ%# z`)oWm$~Ov(f?pgR@h}m0rkgv56VP<78YkJt0j=^LP)Spc< z=kzS2%pEt1ube;0I4W*-e369El2-35*xJO^u6$iIc;jREw;rN4JdOI^eW;HOXQ+pp zY+X4mnHi6weEMhJsAn2%(|OBF4sP66YN4cCcwa(O$ZbAP6>P zwEZlS@B3I;0Tvg-ju-cSDF>hlA(W%mt)kBoho_}W*RQ+QCp&I>oMddSV|Wu!yVg8i z-lce3^0C9y>tt$2-THnxtJ_|)b$zNJ|La(qt`_Q@y)H2l+gzuTh+^(;_}ktedG@HQ z(YEL1aANkCP|OW(Nrvv`&8CJh7yP78Wj1=!AQoU4D2!?`^^$fkk4dK3>q?a*N~`7G z-nwE&99^W-g;V{?R0>W)Exr`x(iDaIu$H;%0xCL#&om78;!t~1prWkKLlD&&NUo|? zWqEYffGMU+f4b6}w?LuM!v3q*;Bk(-v%P`c;pG(^Id=i2jRpebKz*{w$wi9e)s;0I zJ$nx4k00wP4@sq311u1+*WT$za|jCgp0BU+I7fAT9RSEzk?rHh-!%GH9TJdUj`S4j zyR{1iTsnNH=PSTII&lIooc#oqwG9AF`$7@$U_i&4SOl}FI#yqNWSMPPq4$xr>DOH5 z^d(KTjC`8}<8?BZLVZ~@N48mBq1Da>ux;Sbo9N`OL%++ESxU)g{GES~^8IUAed#OM zIP`L4aY{z0-ug;;qF?bG8Is6;N9Q=*TVm8_7Fsp@;k}Fa+3ou=RT?0rlWI4QoTa7* z6x5cpP3qgz9tOz6E3`(@+X!BJojF1IHl+R06h2s-(iVIuR5k^S_#I;i%T`-sUlLf&E6AeT)(k_^26)Sc%}LK$gM5{0K(h= zTKN$StlmK7{$&6_t-Kq>=41H0iJ-V0#ae*!+-0DCpH$WZhK`_FSO;ec#D>L5gyj+N zd=p`zg4%Nj&AGZxt2pXlrOJyr;<=U2b~)X^UrIS@wa~eVIHr6< zp|L$ru{ea*EIYWhp?JTP4w8GGT~leZVEo7thA;$f+z?n^-h4TF9kbnAqq{0SE&n7{ zO*cMz3DU=E_pzT=2BAIMN+}y#(>N3l(~THEMsg9V%aPw;0vBI65*ru0uxP2?z`=`` zJMyGFC`^4vd0?IKE4}$hNz_M(+k1D%UZq_8%{E;f9Lj8{TrZb#XZI`wBExN^-WKuY zoF4J-wLCh4YX_g}*#owu<&hCwI(!JvUAcy##g$G@=t#tBlkDQL!>A4PXZ!^K&0-PF zVy|A2d#9zbQCv871P3l%!NBT9tZ@*eFNMC3^Di7ltJwS1qe&zf!{YcDglAt5F8jDS zUVE7>DR!`NBwfw)RIozylIZy-&nWh4Xg1pT+tiRLeFLR!* z^nD1AVd~-IPF|6BFfX3T5a&(ns_R!wU7+lXQEU$7%Uk)glepN6=N+sNnh@V3IT_!*&As|C*arVe;-)`QsUD$wlRsk)OquLvHlLJ0m8y{u>N+r8l2 zq&35S@8X%Rr*y?}X_0A~BCEutlJzHhrb)f#Xfe~N@oDcBn|~B9dq#YZ97Lv=nmX_@N0yTA z)XX8hNed#~$rvgR-HDHm{bA&$zh4<0Myp(iW2_HWoqMW{%5BWvx`Xn1o#YUiY*X`e zH4CWL^f<@CiGhq}(9oZP|LNPx;`uw`*oo z2HTQu?%N9{1a{nhfMQJv9a1-=dLGpoQ9Y|_d8Iwo$CT`6$=u1Ch~S+clTz;c4kqY0P;|zr)*wzW{S9F zuCx_syy$?5j-5>{K3zTNtYelgt1jKGkIpI!nL4gCO6S=N#m;rdm6?e$d(8Tsd^CZmtYe5^!q?X&Ll&K|PyyrkKb+ zT4&^eX_c3W!*qn~&e1NVjkE2QM&+2ix1Eh_1elH{lgqhT>S{T}z%WvA8@ToZuA_AB zPoT$0N}FuBodm4Y%4s$xGrCtgrPrP2O9zN+u$Y4mFb9@vU`oN0J3zGwtf{f11WWQl zR8-baJ^UA&vGG9hOoNo#0Hjh`gf6g`P5VBBUQ$7 zgLNC|n0YAfCfwA4vAImsbS9`4FlQ4O{3wsK<)(YdO@Tm9CouMdZ(-odX>2_I5>`)s z1-w)?<^lCx^?6Gf%TSO_y%FmDG2%1md-yMQsw?6~a|{Kv;#m*SRsRupbPfzez7yOK zRkeX#a`_$TrnT}U29g6kc`d*|M>s$|P)JV%x;j%AOu7p(jma52_{M*Q;_(NlJi3E{ z`xh~K;jc0KC%*$;s-U*xIc#j-kEP-yMw?II32FpAj(p2QdH#lOG~J<~ybG13MdX*S z1FdD${W6+`QIraU2uo!Y>UXvHjp8JVZ6EO4XqN!torQo&|U6j}Ao#S2t)GrR*NT+6%Xvy_v8eaLFrKgE-?f7WaDUfMvl`!T z#{5e$tn688b2`%J_>hPGsY#7;4M^^*N!%mi=CZntev~ zfAz&oY0ZqU!k#`Q%PH>nX>yHQYuanRY5B9xRk^ws_NPsQgTUUsPY**gCa-_yKUQ9{ z^Z7i&F#OEwbmfXb5CH4FtFSGK=OgAr-wy1RPa0+C`K(}E8qd}sC&>)9CQ&boYwt;| ziTYlTzFS0Zi3Onj)+LN2EN#|N=|$<@2#ePi#BrqVmA;W?-1^$UVvd5WKPJYdvXg2b zeYHUxZhpPAwMZ}Z)4;(`6I(w`>IWM~={AE^H_tmwj>wWOeJp56Qx>%v}?5MD0j(Sa=FJiRz`*qdc7G(-JRWqyR*A6bN3#O zE}usT4}cGb=tgAIz;tDF1Xm6|-<59?-Q2eqoOu9?>iaZ^dmhf7IF1u%KElM@JiNBr zZI=7?^qX!B4In7=?#w2MZtUNOQmuiVx9^i#KH5*@9V1q?MkyR7ps!sKxkkSlwOM8z z8?7@Z*N9{H*~aeqcB#!3)s3;!R%BN^n+FTpD9_!&&cFJ7c&!Hbp%)>>CXt1d{*JzL zm)LwZakKts>JMGF1}H~|bpKg8ZfKPYc(8kCe7GWscHX;>U3c!nZ-*G@IHmJDvxO>e zvLi!EdI=ekO*rUGtz?tf#ROP9KdF`9Ja|CAs4iKW@=kYcvngK)EzEvOCc8cQms_%o z#jJU`^0_qW%)*)siq?7eBMCCPOr_C;pi{q6f!Rj=Nwee0_3>Sph3 zHk%?PQG?-75(P`**nmd1G=OEz81TRbY{RmDjO|$<8<;T+d1wfNH1aGO%}AugMNP8V z?7h0Wx@%uvZEvZ!FL%$(@Q=K4W68+v-utSmsX0K^yEil9L}cEGIOjX(#EC)yn4Kk< znrfLvC>e$U+iovIwrLtaaapk$8HV@Uwc}IY+VW1dnxCgwU#GCz6s>-2(>}j&Y8{7% zwGpM0N8xc+CJ7ezU)QZbLAC)M4p*;<8zjYRI=mf*wZ;DUpG&^$2-*|Zg7_8_=JP_c zjHuPHUNG4t`ifZZWGUpwva+m_F_d~eE^ ziNjmpvt-Mb-yo(==3suRb4R}B&%DF_LbxwFrqv^_cu=+6p4cm<5c28ZmEl=xc@MeL zD=Nf}v^e;urfOW2gEKe#`=q0rSe@DHH(*t5;pxQt%tYv2ca+^l`JEDa*EfL}ShbqX zV57ee`JEyLR@Wi^eySQQE~!?%j?o88xOVtp;*8XDGt-#8b_4kxZ(^v0!$`T1l%suZ!||KvBP_8!gNu@ZdF@J%A@cq)MB(e~OC>v_ao3i9fL=6xdE zlN|*VP81{@)#fEp=O z``J3;A5~7afO=P-#EVljkZ!&$k^tb7B>iNT=Y!*0lsI!VBAq1vrwv|2W zaU|0;U|AMwwOX5eJi~6Mg3)i^2Fm4*u5%I9F+dnNmIJC;9npo%ILH~egPurz7oseYTa(-C{IOK6QWC?_ZUOJHF@jQw zVsmp>*vF!1Q$#Won>cz}YcHDE2#mugY`qXAvWP1^l8sXw(TI4NAMLCQ;3jZU&!%u^ zdM|G8j|PdgblT_CaZ)Ds-nxVQR9|zN=P^Gyj_I4X z8do@$XL|K^Zx5D7<2l-*XnAxP`CS4mvQm``X=zD!#I5K0J1T%BCFY*#PQF^IS*2j$Gz;Tizd+;lLXsx?lLa% zUkf7HhNr``vNRU4xxYXBo>40!w|E=fH_jpZ;10<08dlGI9vi1#My)&f#&g~J74%(R zr}X-a{z=t;qD_r9g0&k#D+IW+cW>f=ZAKgYec0&l!^qMDOx?W?7EA$6!Uf(>{w%IA zLcN~4U|V4Lm?Vw0&uENPX3qiG`D#Wpgj-C2z_kyKkNKz~QVG35pO^Ggm`)NU4?9W0 zdP;ELlJjbCBo-)jLE%Q04Q{_R{M(K`*3$#b%n(clm_bd`1f>*?bjdOYL|y-@y&_2uh&JRI~Jt6Pbg9oLg9i~|qBcAI6rlCB_&RLeg9U&Oc!4@cux z9kTxGPT8!NRll8mBBJdeS-o(p1TU4mZNG&ksxP9oCC+nnR_E~Mhit!MeIZKk_#EK# zR7~_GC)VMgt){NX{W4C}TM#sDn7BiFzgl zt7?OvyDIz09Lq$#1Ho!>Y#W`R56_&&6X(ujaA_5W&AnfIW%hp83#U$EvoBs|=D1W( zr(mZ{7BOgFkr^($^n|3rmwTKI@PIkm9H&J3&j07S4{w!?N3J=Ey_6-Z&aNb06O)z6PpBjH z4h^{88tKP>oPI>(R`ot@zDM~^D|q`+U~K?6cyKoZwoPO*8SL!r{6uYz1_07H_Nm?H zN~KaDgrHh&-G_btyyv58Gd5nLP9dC5VQ`OEd>kI%-yDq9lVWjy|5Pjusl1M_io-># zIDvmNkSZG)A2r@nmG)v^#H3<=-GFo9=QaS|iK?u;>?dJu(gt_0oG52R4U$Qcp_JX$CF>XhL>uA2MwBKHz`A!6Qark<+?B(^+R6;D!Mnf zAs$%;c$+v(p`55H=zb}7M?SlN!T_J~%%EpB$1(%lRCrrN_(UPgI6qA0^H2|(RS52X z0|e#q8I;Fo003)eK9BUq0~mG|oh3lf_kY=DoC0L&tb*ep2eqzm!S7joUd}-TxLkgyvW80yZj|Lb<#M9L5zDDMm;7DrxgOaC zf##@ttylij zRIjr-;>PA`E`xQved`V=zE*?eIZVV+8JYit4E} z9*mD-Xkpp+UJOvI5B6bx(!a^K6`G%zK+ncj<3uIe+!*Yd1Xqq80c}+XK0*?0Gop$;*cv%sfkVd*A)n2L)?scqb-c=bYTx8YoBxP(EneL)gQ>rrC_a$- z;K#kHCZPLlREo&1t)T1nWprPC14g}uYTpQ!zx;I+ClA9-WfU%PZF+ipp17_+`lt3- zb}*~={YH8DA48S|E~shX{`go&GQ3x^S*(r>V&K7AQ+F}oVr^&;)ofaW!kErLFtV@& z!(oV6Z!e+XXHPLZlV>|qbticgaBB|JccP>om1>H7bQGo|B-I_F#!x(d$@>!RR2H}s z3v3f}YyD`A+SSAQ`w{9ywi;=qZ2KoCXxlJ6tmin72affE;^X(lwt>r+sT8>BjXyLn zENx_K*O8nV+?%Joyh|%h9&xDC+J=Aqk6$+Ux?aBPNq#rF^;yNXD&`FGKdI7I#lwCb z+ApJ+rBuCVDEDPd98BudGVCi#MAlp8qY~ZN^2RnM5k%Xo_&yj;=4hCGmwf_3Sk{k+ z)$&1dCoX1f%_s5j=*1TaUVoi-B)fhqB*{E&iFnvp{Vmivn*ts}F%7)=^7FfTS`!Pz?A_SJvv0ly>Jq^>DccSWP!zigc;n?4+iG)RVjT5U3QxWL zUNiWGtxX18fKc4qH-#%l54ZVr50}oLc>*Us{1{{R76I@P>cVJdY2OXHcK9G1!^F&$ zo6Y$k%N@2d2YYDcYf%_h{H&XC>N+5v!mH;KO#b!6?;j3smt9kR&tX0{e;JD0(i|rK z^7r9v8@TXW{|{&?73*EZ7ETwzV1WCz&iO1pqV*u?aEkXzT4_HDKqqZ4YT}2H zJQdi)lfkpthB#r>iOIpXyffKTQtf6?wV1V5Txi6>#khMRiJl6{jARZxCyjR`s(01& zDZu`qZN|Tn%VK3{$oDSh4ost1h(0QsWj4!|DkwB9L$WgODY~Lj!Bfjw`cYD1)Zdpr+CHIwORz_v*1{rzwc z7%*HHgAZ042ix-FtB5d0N?m!}o!)~x`}RiijYCUgqW}S>=^P5{J7D{DbjDw<__O7m zLOx8F5u2H+$u7#NrJv36|1!rYe(?28590l0{oe<+22pE28*waKH+K%u#x0%P%-m?uN7Blkrm z5ul64arNn3pS+OGpYqYsj0e->z4BbUp-N4iZpGWz8FA%4b2--@SoIr;;{xT~q^T*O zTqfAsYOg2lVrT!`(UCfa+Ut|5UGE-=7(mvVdHX6}2A~;nqSJuS6w#dI>6*1{3iEp= zas5#1*o{%KtAMqk0i-K6oUI+2tCRetZezFQ0(XVpi_0ogHl7c>sEU3z_}`hR+^siH}G+XIpGanII>| zfVc19_G@#Pn%Nr}v@KG+7WKM+QVPbBeD&3@!+w)%a2xtjA>$YS^XO(bBePOOdTjw+ zcdns#?iTX%H&M5WnET3aqqyftKz%)_#`ktf#?yY=9pDcrAm9dd5jVS*ft8UVeAJ<} zWUIFamyR99QTI}_2L>pv9X*Jx-k#99r>KkJr4<;q)9kGQ@!)$|;}Y-i>|v~&D1H2r zNE{7JPhsEC{NAe0A?q`o;>*qC?X}J?9?nhPZqWT!XFzyANh3Rz7*r`!J`Z$t?XITL zNg~91ruH*rTaRqxvFo~0(6sBia9tO*T1|U`m0I3$fXz+Xa31sbKxqw>mO-fr$Js_u z#%)S%X=4GK*KT9OGNsj!fNz=NjhrY<8Xw<=)$v~sZZ~Qcia1wq!B*|AYWw2#@G|V0 zY8xiLI^6%H^GT^VTE@u!XVmEiBEDqkz?FK#u&vSLKmoYEz-^YXlJ#DE2V5G7&o5eU zMc%yMdOK|U6c6eBB+~9;k@gsWafM^=_r}3l%+2nPqK$evhe*^K8w%%=xt<+6?k}> z$qqH!Dc_v$^&HI=k82W!^4vUdn{$(s+wpBLZc`WHsF{N6D5_Q?_Ds}t)I0Iy*Cv-w$J|diFBQ{#w3W*&{Sm&hI8cUIRLhCTKvr0@SpB1w$5~6*-9by zP=!dlxq*y#Gk^#Bu z+=1_}*hkf|BOb%df|Yr;TCXfM3DyP&AwIb{ki})ea9j+nt~Ms33DOAhb(=f;h!kka z+SnNEgKHW-{u_OL9dV5B^mf6r2azpRkl!guO1WpYqtZJlbrmo-Gu;e|PD-|A;iD%` z;gtuk!*Xm;VOeShY^SZnLE$=TwU0??v#%FdjvmG_=OX%6Hv|9xKmaqVLj$pn2}(js zqoc4YbsSm03=Wt*IKqw-(t&!uB8Wy(|22_x0F`r-P1E{vGSCR8a1(!6Ut}}7Tt^SA zqripCBcAgi>p*FVO{xBmc}PrQW9r(cEB)87E0euKYkDCD1IV9n<%KYq_! zzlz-j+?w4V%P2TMIf41f2@EZ-VBf9VuYz@a!hnvJinOid9bjtG+(;O65&9@nZbC9}*dc0ZJ)c*M-qWWO6#4hHcwF5gEkG zW$%b8fWmQ1n5MiYCa2Enq@6TBg@fDRvfPd<_GS;DE< zRls}Co=sfuqccz7^amfJuw6vDQiEA{;jOaF3dbGG%#hEYiH#&xuTqWivd+Y57!u51>Voh8`US<~aLl4%;S zEDM!N1>N1zYkVsdgpa)}XjJ;{I1cJ{TN`XmDYRMFYqh%6hHcxhZ5!os87nKRK8){e zAm>5UNXE_j~2er}f@6|O#emcVs^D_1C% zmL7WZ5=CnU@v*U2DtJ@`af$Z}sCr^l`|8FP{#jlpEY@X}!$Y zEuw^=o=!D=Q9N(0_i1@_2v?6E?pP4{dVfF8J#_|8y#HZSQ)a(`Ynh4O?c+q(4j+U= z3{2cz(8!$lSn3DA{(oZmKmjMe_BkBdHyx{vYJV^r8+P<0+D{!glAk6y#z?ZRtLt=F zOX0e{p?sIQ>3q;Z*qW75?`PJQF#i2N#NY?t#`RzRAF+Al8Bn9OvDu1rVsec?sc7R< zF{SRhZ2x2H*}13AU}bnH)Rq&6YUwmU&}f5O-Fb3D|Cr}mkr!x98WA--$ryxZHX5T? zOg`rEWYIoMO31o~dfKLpq@gJ%e;5A`rXal|s9qR9z4q1Gs7cy(Ynaz|eP zOMD6<-F1~-i0FYdw-#{^G7sFApPBioMcE^2TS@&GyMd=WVP9^aEC4uo&~rTBzTG~< zRvge`Y5gmS2dMoDZ;+WKPM?B#wYq@#C#I}a@}cXWM54jXKUvj)N9t2V#c~E*xTb-% z;Q^eBxjQ&pso<%1--io=uI(aBSIlz3prywf2E|Ty7YJNjIDHD0T>NZON$JMyEHDd9 z-Mxp|t2dA?SHXZjnjx0nze+xb8wY1Qas)JcR@ziez2~=6CYHv>aPh>k_8;yc(ROz? zK0190Prds-GTT*vQmDrq?AB7njJYnj*_H3-0rYcT2H>LcG}weD&mi8qpEERfldWjc zK!s}W$)MVAatjC5{&w^ror$#g>$G1HApne88QEJGk@~Ygz~+hPvG(%cgqtfU>yxO+ zsK1+hpC4N#uV*aVb|s(1jf1mTm>7@QZ;w`nhp;j{gs$x!ocZ7!vfE;m6_+it>LEY5 zA${lW2p48!u6Xd-Q&PNjTnyZ1JKT)scYnSXwrg63&i>#C-gEuVvoP|5bsb-^ym+m( zRX}Yc-f9vL?1zKxR@x5GKv*`ggnHYfaF#p@N~NquCayZN*-UhWPYH2nGi`p3L$(cJ zr!xT|S-5TuhS6FudQzP_m`@ZX0p#*Jo}_&6^@w0AFHngkavP_&y6u@&5`=M(2mwPw;#b%*d4!pf-k*l3k?5}mdi ztVIX)!>?8IP0ixQW(sN=aCael2sH^@%LH*KoRk$^p+&0HYRIHgp>m260y~|8QFlRT zyi;aGs_#_r(LeeVR5y!w`JeyY(6Wx%a4-v|g1Gt+87v_8Prd?@Yuyok{J;U2zy4)B z`1$AX@>BX?)F1!XzlU2rbv*goU%}bqC*t+3fmN7>Z`ux?f8$NO{^~0zhZy{G*(|>L z+D|2VhARNnHpo)eE(O~kh;Qt7vVF?}jvOI~I8d#l)Cs4w7YOZ*cQt@oUtWLR zaa=f#1KW0d8Mn*jvetKM+y3C}t*tF=Y;2-bDj}1R1Ku3RLAB}+=FVg?u!IvXT-Qap zTt=~2LO!2IE|-(^jIOROq*5uku7`b16R<4aLBq(x3)HT{wl_eC3Cr@Iv?)^9+DQSx zEk@LjqVV6j6+e&P;p(?Qh1Cg?#JVzme5?+%n*oj!yB-k^U2O2!Wi2q*kc*fBcl2hw^wG4cC`ZU&t2HFZJc1#oN1N}Jn^ckEy|1qp;9bSSkiU;GPxOs2}r9x{P zc-y5~I*s?AIg1nLK88_ewm;8yV5cmU@}29KZCNOG6{L4A=FR=IQYDu~P0&BoV4}FR zbz=c5-@bIVW1S4vPgFaI7!SkOGp@(%balbDI%B8%TOp`W} zt5r1|>Vcg7`*(`qa(hC59XMgk-dN#Lw z7}8_`+r8a*`-RWM=G_Upw`U3zz=`u8!*dtWhFg^%iF4)1VJuFJb)>y|CJn1*gHRcG zu8s`h;>k}>z&4|DE{C_Ce-an#syjR?J{b$8m#UdGBI|^cfJFJkiF{8Mb5 zdI`&4{1s5s)F?&N_gi|O#pCsKNAbyy06U$+#S_P|JTlzUvjD(OcNgCI%rkiIjUU6R z);+=G(V;BcBHi7y2X!ljeK+Uu&hxv2i|e+HfBCIH z$5%f81@sgOf#s^148Hf;tN849Uia{8!gk*N2j9TOfA;4%@^`)%S@znYgQ!_)9K3X` zdCiG&x(EPt<@5NZpZ-}GEgIn&9iE=X;pyqNc<6{~{_PgAQLS$16x(JS$m6aYItl3~ z5wZE}hw*NQ{1}<{MI@tEM&Bnt!oENGT@c5{{nx&ZYk&K9Q12N6B_?F~>Hi#0FNu~k zs^LADXZ%s($HAgL@%Yl^qeozy7WQAe1;BgP1^^2-YT#hTY;MzMZ&w}-3c!FR&+5Y^tDVNI$ z$3G_zK&#j5D3{Bq)#|8LtH|X_&3ol?S;|HYu%Kz30~OfV*hHmLK`NEk>fbn+Szju$~{CV$lJBbRTq?2jn zP^UFe_?^u0EJMlL*YQoJr|Wp?^k6*}Rxzu-ZB+yQ2*^#U6ysNj}n$1#goSd<}NDH)G4Kbs$q)5iM>&e9rA zar_l={S1!_24>XX4?Oprzt4O25LBxa%ggPz5#J9R#v=(nPS#eGZW-KKkS-csCMkt` zlKA`-u{84^^V!EY54r}y%E)lrnP~wp>-NgXFfJcIf&*8sAzQ3~04U{i*m{J~WUgW0 z!N>@xNkHoAnzuXDD&K2&Ze#IVA7U)ugM+{FxwiUn_4XW=R#!1TG>ij#{U>pqzj7Iq zqoWw=>yO1xw99aWV3CVtkhXsMc8)&je68zqSYHTwue^=?y{p)oJ&onFUxHnT{vE=Ic{rojI29*~z0%nYMg2+j zG0UgYQvAYtx?=HCQdn>cPSplM<)hJ z1F!+jNl2Y0!vKyRC777leV=nDi4X$QG+^5fV!CG^IoY-Y#|h5zQ?GlcT$M^?RI632 zuWx`5f_gw;rsFu+*|G89fqJ5ir;oXAsS$8p1EqE8o=Aik(&<+6Xv}~R3$9y3E8ZnP zbry#Qmknwsj=woh8Ckx__vP>WzHH<4_fuU-gYZ1_T|v;IL|l%hjN>v>Jr!E+2S?0$ zVw#(X#l>?IS?}EDCpOMl+>^?UKcV_LC4?)ipwvGnltps z5rQK}ylmSSE<9ROKscyQ2BxDN;Xz!IsUFGQ159a`C!&Ay`zM>*EK7v%GKds|m3ek; z11|3GnZl(LM-x1qpWb@mSv>pZTj*KaYCZ=*VZnYR0o#lS073vl*+3_g&(|u!d9{Q*5f$u9(Pg&P|`)_qksHw@&23dWB>o~xA59?&qwZj6US|wa=O0y z%f|Z^lKxWuK&0e+{l`|RfZDGz=-{bXMrRZV;vd~ZkyF6?r7rT3go^vd_*>$t2zOoc9b)46P6C#Ll!l-= z9;VDBDIeCOq7YmR%iX^ZeDqPc*)uNr!Cb56+$aj>8z!5h_=n5vaF88tO7_T*%Io!K`JUQV5U`fp z`a>c){H5P#it4({1W#co=x*8G?7->D+qLs`HoE=M?Yh<7&EHPk zSYJH_+lpb9C8XH^Up?bfy8+t(B6XUV{@HKhIRd1+qmRT?SANw6*hxy&>v-XZKSHWf zYdGt;i&4yzp-Ls$v@2fY&!9@dpl6l8%cNT2Wcd+~g3amS{Y!1FBLDG^k$&fU7^^Pf z?oa<6Y#n?G_3i<r5|6$cfR%yk?P6g ztMC6)n3>)6$WcOYYj!^z!^G^B8{h{wyG^{yLhHEZ!7^{RChPQ)OEl}p?tQ}YouQ;- zGU_eG;pfsiD6NAKePV@Vzl84XcVg{sn}tM`N(GMNcYwRDi%O*eN+~usHyfF#T)3|5 z3$hl8;bxI6%K|`AES8W`yx-|`8io?smQJV9#ZuBLR45csDwUAW=P)oZAl(a+Yr5;D zQW>u6AfL}6m-EZHxVYcTMiy0`w7m(u9Xov#mTI+q9p7+V9F70|T7w_Us%;11Qyo85 z3sA4Cb!4Y94ef($x93)9HH#$=;FeE<73-Q!)T-AKMV*CPkNNq9OuBI7$?z^ul0lm_ zWcg~qh0~BdZ1v|kZN&}C?7M7xWqo436YaIEOx(3F8i750`7}5PoIV||O~cTy*@J@s zr5@&Z@Sy!Z`K=PI@Yro!%&qsy+Klg;(c8P!a*U@Q@2T^F^}&yH_?+e^prWabcA6F@ z#<6eiHgd(XZ!LP1#BByFFcOISn{8}u;pY8&NT*Ubao}LAwsdVrQ96~vrdIa?|&c572wn_ehwqg9BQczH{tj>^pzJdUObJ-(NT;J#>x80*J;_m zN_;aT>ivqgq*g8Q;>-o(69%;IWci1=GR1A=SV;#Jlo-F5%(5MQ3OC$}CB?aEob?K+%29-IQqlL4i}cq+m*q@May z?*?e}gEH1~xY18`8FFOvc?2@`hnS=l}`@1Q@Y;kuUH0kR24 z9ADf`AS*C{U%^P?Akfd5*5qh>iZlOOZ!^e5(+;&V>N+6<4<9C&2@%!VY!2n}dgzYb zzpi9iCerB?N~Ov}Z~N9Q;K~&?YFxOk*9S`LptJ_p&43WQ@mVzvP*7Ud@};!i;N`+J z<7J$QD;2|e1Q|-B+KvLz;rD|E*-#zE%IM@iYi_}Sb1)*2o_>vj;I3E*xG*E+tDVpM$A|v6Mu+pa8O~_c8F{_t16q0*YOeC_eiI zT-$RHwf<4qxh{YN2Wtmi>m)^?4YoG1Z>$EdL(u7C(4EO{6o2tJQor{e@Q@s2wq>E7 zwi=k15rF{*6aYK&o{w62!M+Rpy8Mv<74B9pf1DQ-F(78H1JOuR(5<(jN*n(x57#tiB?is$IMnZ@$keg8| zm4fTKFip!B0G@;l!)PA=yqg=d@7)8gUX8$$jZFePySoMPqi=hRd`Qo^Znfx9y7C&Nv3<8NBt{h^TSM zXXY5q-m|vdMyeiuN}?&CQ*moE0rM}287OscUUUuz$%7>8o*z5!zE0d~JB9&h_IV_x zp&_pqu1m49(muaVgqFp(OeFU;vwEUEe>X@s8s$Ff*Ah|o%l;X^S53E8uo-BlQdpcE z+m+48%Ok@`S8Awb(%9^4KVgqbrAirhZrlOhy$ig!A2a**1_mcHT9_Ee=)EPFHFjEF z{8_brV;=AQ@wd?Z^5IxP+bYHNXY3oF0KW1vY8^N-ec!|c_DxI#7x?ZqR0>(te_C(1 z){$(lQAb@g9ojb?yDhOrs{G|Euj%Shc5l4W$`6BLIzH#>sCPzk*-Np32rFcWod?&&FWp<5Qfc$gunYvjZP;JO5#eA2#3 z*$H4BkHjA&K1C^;`j-5YRP2Guj|5DFU?ZOBi170XHlm5fGN*BviX$1xT+@Kl!jX?U zvQrj5Ie8q1FI~at{2~B?wV?rga_V?T__so?VZgR5L2>2p&9iw)^p;b01)0WEA@+C#CD##UlRd-M8`OmtP5V45%cIvzC;>FCKx> z`?DC|H-#5YKN(p(9#|K}AnzsM8C*p-XfOx;VoMd?{xu;Q2>bi$C%<7JoUhui;4=Pp z+g0M#+U$Gpg&$)4Ti<};+PL$}{{TCOo`RdsXcPyvt_qgX{45H1+34>y*Rl7WIg72{ z&K`|dPp9ziGf%^4DBRUd2K98f!S4K-Cvg12Cm4RP3<}a*Wj%K^6Q!P7Vl;!Z*;?d3 zSwUUn^`lRnhcdhlBH1wzUtQKy=M|OsKsmZxQo|IdPC$&#)6t^@d-ecfqM8uWa5g`@ zemxAz<#JeGUk}Z27LQ1%VWD2HYj;62s#Gd)T^H-?8*p9PFc<^}(^RW9IF5tmWr|{v z_klU79cKf80o$e^!~|e9{>pteP1QNkSW}4w0u!!Vg6*sa_JeZ@qt?N55brSE$A2$a z9}WV~L1lt;FC8E!l5^M(z{NKG^<`5#1Hpbr7MFAKsS@I6IaexcBM2+7Rw?)ah;mE3 zrnsA#$pEjX%wQ`@T{Tc!=bYv!j)P}bUUyH`A_iWv03z3MpG|~L)*n7 zN`L+_=;1o%$HuX+`~Zii_v6hE&o#?Dd+G^n?rdZJ!2?{Kn*#ul)fLo=JJ{abfaALO z{=4tMP9Wo+d*U=UPY+?Gwh64S0RYAZhj8lfVWiB~_TIB+PI^3XK2a2hxT+a2Z5L0y z_dY&);uLBT*+U*DI(YRO23FUkT#+ohBg+ze?4yggeBua-U4^#VG8`9On>)>XcKo~{ zzNOV~9a0g6>h2T`pyFDO=4ZcIS(bWXW28OI8D2NLbQ=R7eivPLF2T-sWBud{*xq{r z^}!+71%52IPJ`%7|Ds8^HU+P>!7@HhJ4v2pU~C9q{LNp4@%hieNbgFH4lS(=598K> z3ie;W1p?B1JN^;sN3`;LU?Z4k1rrVR@Rem;c8_*{EF~$M9P5%sU}N02DYZdis}}*- zaNQz69YDy?M5z-PlmIZ8Wd1Va4(AqDv*=+N(ZQCG( zAe+shtEvdGCRb<)->R`dv zpBAcAyde8RztzNxg(G>?|sy*%Pl7w<%>9W@XYl z-bQ57tjV_*=}0fjK0Wif(=;>$*fzn+N@wPNEB;$OA5PJ~&ZD(f#2G!R=Im0SiFj~|QdlkGTITv^7%@JMW5?r!yHc+VTB%aB+qKiE%1i9gO$-~r@IEmi5Z#*Q>x`Q!{?isCF7{wF zWh%@!+i5Hj&li@&ugvRo-<`wAkH3v-{}fiveh#IHgS&!-qByGddKLAB{UYJIU3_}` z5C0OUzW5wwkIW*M$wpUbgB;VuCnt}?pe{xh9>AzGD?b4mmVFiw=YS=L5iS1mNEh*Q zn4Tk&sI`;kU;oL^ouu6uTk-wQo#EqAnBA;(>csm=r-6Z(iSh{{$Ye6u+S>B@R)YeX z0WWx3^__bDS1-6(#nC~$s?}PvAB<|X8p`D|48ugNmXYqUfNph@wvLx=+bEYypp+t? z&ugE???h~c_0sh{A#EaU?x!{yXFu>Q(xR7wzbW}0h|-D*CBksFNUg}CxV$+% zd>o(60zHioIG+_il>#Owy~XU~kJ}f;op3tGH^u9QTO9tK0sm3$Mmd%B^>uZ`AV)C= z6Q9tc(MQRQoo=>Cnl; z7@wI!Hj_bjA+Gb<8^;u)a+U0tj6bqPP_75ly62VWP7pv3>tA%=qn=e?PAN- zkA8sMxwo-BJd4W7v)DfNEZl4!^6DIBxg0JZ zJ%U>^`!O*;kI6gtn)hfEJhS5hou-N+Do6Ysd3W>ya6qSm9$8Wt} zmjb;jl`1wjw=h4y(AXKS^6>z1PzE#0vYLHyT?dY1Ba_Jl?so3&?ZKTp2DZ1Uu;ZDa zna#<_!Ev@>S^Xd+10cvDZ)){4udD$|y`!$esNInr42I*E)!)-eOr6P4@5C0%>A~Q-yEwjnS*9_G3JW!C2ZXG|N;=B%3)pfyrfhe0~i+ zl6GnvxVv!$$4AbF)>yBsgEQz3VG}u8^>TejR_aHeEcK`A($E)gX_BZ=;~FB z4-aFwzdxus0AAM36F>bN_Ln(k>@IXQF>1YB1^vBu@b166jkEvl*U)=lJctzlc^s*x zv`*3Z!UDz?7Mm*`02r=|fu%JZ{p1p^9yx?^8)^Kyws$anYYvWO;?l8rPUBW-qpuGG z%WFuLZDAD$_=Xq*{VQuYeEABlA3V_VCeyB+9UQ!RO$pZK5(LdPo%pT;q7z&-Bddog$PS{{cUxp15vuk!`~BHQjnzA7(ovua~wAxXo- zLTRK@-8goPU|>K#rr9t|U!WHuXk@@{tZkH{TCF0V&!eZOTkEKeB1$PzsZ=BDb~^G% z;viz#v)kWz{P>Vzn6NAh)v7)ie|{cVTx@SvcG^D?jg#ANPlqFe?gv|R_2ty{QHK## zj4SfeIZ8!MLB!CqrCsk}=4HL_{%l@yz&6jeEow84O77v>qifM`&T@lvTfU#Us=X?e*7l>lb`)EvT1!FljAtpDi+b- z!?DwPt%l{DZImh%#^#`)!O?bc!co_rZ5de&x5!WW@QJd%@yqZ=D)$ta30Igei7x7 zeX(ajC)Z~k>3iXSvY=C};;v&7w}1OF-dx#4*ROvS(+8##)oqn7oH~h<^a6$!S76jV zD-eLDCgg(aGNL7jLezVtr)d0@1Le4G#6GJvMXgAscoOtsQPPzOOeckf1(Wbe1VHP|3&0B*wv&8br(JRB?Q%SB)J`-!9EMUWp@ z_BluKRq?WSjcEUR2-e?*pKp)`WhB7q&%C0(5@stOtcm3Ypsg8jm zk?!r8LaJ6rs$R$3%>It^pI?4}%int+^zA#yef=3cfBH;l`K_KFTs?dUvsbP+-&>M# zxAeQ;#`?_#9RBaW4t!yEg0`2}*N~m)$H6CC2k;^d_68gsR<&W=Si|AJ|1}s#rnQ0H zafq2*<4|{@kRVvwBUR+6B9SlUv>_70h-g0he;2V0u^+n6Vf}7}!kp=P(I3`kaGyJ| z?&juiVBp+$klI?s_RKMqrjNlL8iAWFB;w0gV=l5qr-J_p62cPK#T(~7z}e#`VjK5b zp`Gq7>~wdbn#q6?f~nj0z}9i2F@{wos^KOT)@Y_O$c}8jUi(R}WauSgJ4#1z>$^ko z4L_aX<5BA{!=+W2Bdmqspm9R=?9) zye@-hf1g#oIfx&Xc*vV2z3cLkQ~VmsE+&IyUM5I$RHY&}zsj1wx8A$p+npFZW*N5u z@fa%AaKQd&Tt(-#9_-3yT^;#>@}o26h5_{5ps6XqaR_eSq#bom1Fbtiw#o}A*EcZQ z;}32PGr>P9GKh(cm4iziTwOiiFgOGIdiJ9?(~AeCMc7Uiy_sGB1XtIu!XN}sj+}yQ z)*#AXz%op{I6RGvAqK3)!*2U0r;tBz03!o~0D$SqDcoOL#F70oQn>?r_F}ky029N* z7#kYKST>LSRU7p^djRkwehtIGaQ}ehs1Bk%V-d#W{v2`>{V-!>)RoPK1cS>fDE1Vv z95V}89O_-)MDO}0>ad#G8Q7XIc7G9$Y2wz*{+2RR_iSxp`o=Ac-(Q4l5;&%bo3k^p zt=-8coUYYC99P*Q&kU11aC>NR8IED1*j2##U_Vv|2V=L z91OFd)H6bYwjl*=yKbdfK9%ah^fU>;PvK-)7Hr#wWmzo+Y%@xy(?mn}&vfC!ZvE z>#fe6Mg_F4kLh`N6#a_@S!{NP!k$qae_l|XvCHaJT^ngaVG;snM^gRVI$GJ> zz+e3EhcL=Es+Ag0tN|Gdu=tv75ChxABL4i1AKhv&T=M zt_kK!Ti%Hnw&TEdY}{L1#9zJpj+YrUl}7o${MR7A@f$ZI=cB)>- zi3=ZNV0jG=%;qXDN+fZckUY}Ga;j9)Npih(SIY!>H&y$puD*_<$6h=?SD;Usx=3xW zV&L3&G5-BO#Kw{5F#pQWqt-vVYvVqexE)DPRQj}Az0Cg3&%plg{sW9xR)B{Tv<(0k zo;Zno+3K)>|S-;G2v4Mn&G?x{qGo1mE8cif>`) z4EE-2MtilHj*3QTBxqDEja8490T4LOCIAY<$bb-_zu&>cL=7t|a`|etstw$BT^F01 zTPPNbD3>dZP17D(mOcwL;9+V@vCEpKfqXuX!NCFFJ-^BByMVaghHH^l0QOa-A!~a%tr=oSF%|wj|}6$m219*Ck{RF`On~7&xb%)bmZL4 znHlWAehb;1N^@+-8EJ)F9{Fr8_B(EsawC0s_J94)aPXI30SO3B(~&4f*z(@Dwt=a8 z_i%4&s$=~dTwcNG!jiC*69q`iMq94vs$o`Y|63Cs36S$$*-WWtNQg$N7Qz4 z^MCvIaEIT;lfV5H^vrbrI6aYey1OtpJq=J`^3MGRXeLd!0tH|+)DuxD$t;l}Z)GVi6A>Jb-Ch5HYW9JKAhvI$*rBQ$)F3Y98sNwrg3ICR-YTWm!_T zYeEQWHE-v%?wBf8M*2Iyyh7a^g6-Z9B}(~`vIDd z3Oon3AH*}NpE^092ix$KQ_IQ{Pvj*^RlkH4-2&{MSWm1=6ka5t&m5+T|6Hk_3Wmj? zZMlwURF(Uxz9p{BGs(+)$XoaRxiA`fFAv=2M^teqHLK0mB7fd62D170cu1->K&&$y z$64FsqPte*Vmb{RKAgPXzI_0t1aor~J3EQ1hf*szdaJUCwVgR_&~_NP)W-bA#~AND z4%29T9ZlNje5xBW1E)Y~4OP3`4BB=Ze{I)B-L0c1-GdWDC%t(@0F#)_xxh_8e6|q) zCNc2*&@@u8K^uA-4~`9|>B&jydrzT&o|#!+x!FB(W?RwdB@zqXZktjj$lp4N6R&*% zU4^d5;$nX&2nJTxVZsF^1S>;BZFOa2=>f8p3c9v-nk${R>6guQ2QCPv?%V|>1h@C^ z!%kOppBeRRZejY?9LDc2!hs3HaWH%B25i&9y}eVYb@-T)@r4DSf!v19WK*cj+foNe21T{xzR`H2aP&M!6BeTI(RW=q_#%CakQTaV6dDX#6DbVkpp zb+Xg=Lh4VsjQsTrnE3G@BfY(f?fs{)cItB|?l}x6lZPr-;>w5QecIj3U}{?`0#vmY zPp0z`;DW%a*_ga{ANQvwL%2uN^7=Yf*4NOLFGOw%S$h8(-v3wMLErQk%&&hDGgEs) z%c~9wZjbXjGdOYGOJ^(SG__(KZUz0dXOn7W6o=I@U>G@=Mi+>Ymip#pQ;I__9JdU^ z$ipzypzY+8N&$QJ0FTn=N(ezZoyO+oW?KQyj~lUo_Mna8?b5=+qY2n1uspqxx`1>l zR}y?GUXNd1bJ`H>QH9-gs1_Ed9qZ8aPTv#SeWtFW!!ce z0oq>Bwh0GvMlf{~Gw*FBo5lJ-KgQ-48?unVZEgTEq`orQ&9E)o?&P(@Y_Hr&%xtQn zZI#;zf}XxLx$z&#quyTNrI!f4_r1=(!A|RKqW1jwTGag%x4+TvO7=Pb>HW(%+}($> zeaVtp0RUEtu>bzQ$G-wV|CjHA{L*QV(-Y0xd&b7`e0!`74)k{>tU%Q{^%leCF^5(z8>>vHlxbXM>1vZX62Pc#52>#zajLki)!M}~%4+m!ASdp*1 z`WomDUxi_{x4EDdlKlv(Kaq`QqCCBK%>ae&{GVw1dlDZ&>+~>u*Gc-HtUpBg8{W1{ zt4+JMj$Ee<*R8;|S3%thD0Sfm1l|GwrBz=RWPrdh@^G9@5MqE*2ZUG{83D$|EC7C= zW^ZqA;Kt{Xkr6B}uV7+gtgTGa^?DsEE33%o^GKyyw;dRU7c5>Xl~5?;|5^oYKT2vZ zk|G)Y4yvb*H`3S9^VZ{98EXgovUUDu@w@7C7CpBzKG)epgKY#1uM>z{&lu*V4T&IX zI((C~h|xuSZZ_gt45eMF^axEEVm4bageNtclGKF-SMZncNGH|X%(;txZZ5y%w;;UewShjLQ#**Zc6M;<{yp!D zOF_SR8K}D;FYN~gn!2PL7jNM;EW~b`) zGiDoOZ92u{Qf8nF$A9x@64epIbeI?*FwnKNgW;v+jswiaG#l(oxi-qjijqdU_VKBRh`k3$kXkvs1+8<`x{sMY&v7+R;Ca?s~mmhhZ2f zmCDFwvl8f~lxjh+?zpK;rVdJ7EdB3r=Z=?Utd#VGO@-Rgi90dtg8^cAx$ygbhqIo)9we&(n%@s{WP7}1 zhqBC<_{#9ItXvSlmo*Uenhc)RW1;;!o7M1ZD)IBT?5*#vkWrfhW|oDF9ZO|MeH7m% z+vN=K!=t_XGVB#0wCLn!eHEpR47Yca9=?pTEH41N6`Gy~C?!~3_11^2tUVr0EeP6SrHj-llhtPJlS{=2`lgv?YLnTWt;*`(*0`TABi zFzeocW0+VUh{nG`G<|Ch{VVH@P#vR*>6p2VWsnAdJ-5BH9q0B>$IiGtw7eqd+kDj> zSX;y5#8}6Jw)@sMkZPs{6pgO_<7f@I*y`)S%>y%79!Zw9e6z0?n|-~=mMcixHS{g7 z1JrY}sV-)9U6;`V#}%?1py=E>Et*PO=Se|eR!hjNEg*aECUQ3}A-%PV<?WVq$bblb%pT)K4= zUAcT@&~{ImVCYT-D|asAgKP>jfA4R{Zl|?(?6;Z*^H;Gm=MYq;9olVOr#A1xNs?L=>&@5zJC1DFaJE~ zmwpChsDN*!v)FK}c>36J%r-XuS*D3nLy$PGi=X@KD=6ghIC=gfZ1(kG@xUw$!@w{6 z)R%nxbBz-jPaHTXZGt9*z%otzjn`iD^;?%jBnh!oV}N#bH9Zw}ig^0%cR?Hot1E>; z4NTs?55sYB@kDzkH6OTk9aDGj;lbz#E*|g9sn4P00__Gf$$LL|!H&XeA<9@Gy`gCG1QCcpFl!p?Q$ z;&1#e){j09CzS;{yuL;eKOZuh^lw>?9pKmGdg9+WWEcjJe)s{~0C4%(5!j}Mi97Sn zCzCBCa~=sD0N|3y*PY0gMIq|%OYC;u6IonS3+Hs%M}pfm1!qH z+As{{^Ep&16_{qeBfi?7G)ko`RI3K6)e3Ss`PAui=O~tz+Ha%tfH6W!001BWNklv(ef?OhKi5-7={ae9zHmz7g3tp3kI+5nY41OC8l5ko_&7vyu+S$$n?zhtdNO$w%- z1kE=_Ta69V9E($>tl$4ES_)Y2*eRm`8a@izNF!qiy<%y^n5~C-lDUPJ>(bn(z+<1- zGoyjmxg9--_GayFL_K_n5j^m}_*PM*k5+!vwhx76%o>^a4^I;Nq z)39&BWkgaZtUn74d!JR;#?9?zoa`NJ9tsrqU4L@p2G-uZilwrt-DzbI12cQ};G-*7 zP%M?u)5wmsb^k8z-noOW-d>Ci4dKq>g0Jqx@Cdr{d8}=2U}a+is~a2m`1&=ZEDO`4 zFgy%FL=FD5TOp=>I#5M*|v`qaynqjc3pQR%?`tiY1&5WqlPw=?nojX_(Yl~=o z`T#9YXVCiK5>l(rF#rBv$MX4agQn7Mn6ZB()r3!W;fL^mrWWzR!FRKq0LNU6_g2r_77 zk6|-X{kk-+M15x?KNlnc?kx;o(aeB=70P-GN{f6YGc8q|fDB;OmIe9yV~l~)El`>V zAr>6RfMEcgodhEz4oW4URMOjrImvC?MzL6|l!I2vOd3XLX6ZyC;hWbJi3B=2+R@h5 zhL#q+yp&~Gu&iih7)4p>bUKZ;w&+gBe#wip7Ek#Dmw zFlK`gtHxVUAApYAz8Z-39uwdS^0ifoTmL!z+jJY(3xxe7w+^at(9c70>Fw`bufpKh@4kwJT6_r0I@m8L}<3yZ9suCz48#wj`tlI1aXQ{3JHfj@HFH zPZ8xvwU2+BWba;J?_Pr0S>Vo{#IzI&k&$$)*Qv1Hi4LM*s#4KAneIazKDees-Z{^^B2^>Im3YrI1PE z%9&Gm?}tBy!8rQnJ~QqB^%HW;gDZ42;TONg_uA8>>ha#*f~e9!ipsam%B`Yx>J~b0 z{sO6$XIMG$F0TFd-wi!)J@{j%2xf`m^Z;$?FxF>K=?9hXhN_=L+5urP$n2r~sY{e? zoVj=z7hgGt<(}@kN~TYaj=?YtJX>0-*>>XBUxW4fI4=HwKSS$Jr(>Thn&{S=Zbhh{ z{kBB)SzvcdOCeJSseYT4#&A(ubQ__*g1m&Z2VqOKhf*Q zv+8!8;1wuP#jh$UOqAoI<8hVzl>yrl^Xg0Y40js^41%@J4qQEZ3U)vRHB~O1KMMdj z_vJ-&FD}D!fc1!KZToL&HJf)#S*HTj*U_gf};&>W6V)fq}p%QH(yGLEp0ltar5I*0Jc- z;Rs_mbMZ1Vxh(}lDEpPOO0TG&VfG`r;KUUEZMtq(&x?TV`jL%$N4*wAbqhgvS5(x{1LJ{e7{n^OH?;KS1t59e>9fxHb`{QuU zVp}b~xjN?dN3DrtbYFe-s#ZE%qGNsiTGew&O`@kj;_drRFC&Ncf-7nKbRmLTqWw`!)EbqNduIB|l2 zQiei-gZN^x@e?-!s)PHJH+nnGi$=#?u(z;QSVY1w(VO*Wwo!?lyq(8tVF?Mt#86f@ z<`xR8DB5{+Co||uX58&LyM#ZVyN6@#-2jPaj12VjAhAr4f4qPP-6`bqTPPGu=;`E+ z3(GXIw~|Tw^6gvb>Fh)%mBv86fPGzEusb_ZC>8NwX2#cddrK=?vstXHueDy`2gfHcJvWD^&!0!W4po@)*KFxpUO}Q{yPyGJXkS^!f!p^$ zO{1Y~WdP8&v4K>fhESJwO3TA68^jsFgJ*{wuHg)dZhYsL1sd=<~NaE zTZOf@jO@&9bltg(WS(OA@HssF-rvC1*r7_fTCe*$SkH#(MxCtoniveVezz!M7zW-v za~3#rwxNFNk$fhDTSt%J?b)BX@E?$bhyYVT_r^;YsGn;&^VQbdDcembM5oE(j6-Q# zDJw;39-J%`&!H5`iUzL*NX#U*`h=ckM1KZHH2LoWDwbjF( zbv+zB2DMK;=vpm1<=@7wLr2>$EFW1WI@oC-YBPwv+(zO-ro`PQ=MLVUYF8s>AwiGm zgtO>XpPkiD>dYPF{MC>0N|?j=#p;=zmf>LlAh>jCx4Hs$m&m84KKF@ytC{=E%RJpo z`7T{a6a(~)cLNGi%3&W;vjz?CZ{6s)fA(e)0)?e;Z z6h)E_JoXRe6uo2y5s_-C>(8eery^DSY1L(!gpR$cwl!hribi}_zH6(Ee@{1+E+ z;kENv?yfIzdt!J56T{IeXT=X1Yd+q%YYf5RAhnAeS8@i0VXF2*4AE5^0v`yN+uIXB&=O^Zv@d!2tlFHNCnoN zC5&tL5tS&`&ll#A_KqnWw|X(An(>)9V~;FsJiyA<4Eov*#5`vsyfQ)3Ors||4B`73?>q>~Y_ufX+&1FL zGz|-V*?x#D_+r6>c(c=H3R%;Fc<#lU-s+H6(@sNEB@z_zW~0xZSg~g#CB#qit=&6J{fPfBYA-N@Wbr&VvyWJ4^O~ zyZ10M^Aw3f2@VWcCEM*QPJnbAY2DaFqFC0#go0Q2wOEQu(E;Xw^&+S;)8R9^Jgju({b-AN5*QMy1-SNE+72`GVe{ zYU8SpZ>|rA2lLJPjH2!f;-G`~`MGIndwBWkAPYgiCY3k#;%q&E7$9nl$O>4po$3ov z6Le0Ek7K!q$NIIeu3_)PNA3tk0x$}r!iNZpPVj1yeHQkXtmq{_Nk6$QSXD7 zv#1wi3%gG3FW6?=ZG3g)x9-#_KIoe_8J;}RGeXuY^@3_u%1$1(Q$!}&shBUQ^jljt ziwnpmyQ&1h)F)w&(pq5=H=losmSj76G6PsCE`fldJ=qS+&_Ux$VFj0;Uq)M^1w+}l zwfl5ubsFqj_v{NSy(L(j2qY!CL0?eT5@*6VLn9h+sE=!%i~%c~l* zTU*#Dx1-!7?@-&u22NhNie#0QqXhe*#6!D1AlO&CD~s>A!@xU65&_Z&Sk&c2Y{^ zGB$EK7={r`=WvIR$o0b9d*LMs{Dc7o&k@6=+AsJrkN|Oi&-ezD=bd3Ts8a-EHW+i@ z22Fd9BB@|-O^gb7PJ-8lvS5$|3?l`=@95>AE!gS9SQ(D92F7fp(}U>l28M>d{=cbV zRNh_I7*I{8Qz(~hI6I%dI+id7T)fCoj?C+bV!XbdVm;jiW@W{F=*VL9ruJKHUoh|u zJDXsgNSdPME3%CFMZ<=Q)D?f+UGDtQAm)esi{7_W?i@V~W*C^b|F}{Pkkjbms+j>?dgTn(I-6AK#~>h7 zcyajeL)^Q`l+T9yE{N=s)!r(h^P?@XjVlrKHFePX@EV4H{Leuc!~EO7g_RTUct#QZ z8Lq8E;$MmP?#Q`PzryM|%zqcjj)x7finm4nQlc;2vapc=PzJzo{_`(!@zwKK z=<93VLXZZ90iXtP&0g-cp%wigQL)fI)qka^K?!k!7v%ldd)Qr0`e2DRzGhkj&AcbP z#4=x)oJb^)Yi0?OT_BY5QqnJz7>0p#I)z+r3zXLa!~pNaG;Q2y)C`|^fGNo!D&#KHz# z?CZnj^Jl8u!|HP3mGc0AqgQWYWcn!_nC^WN-d7o_CCARRaRTt%6aAAH$L_o@dN;}! zUogD#3PE3=)Z>lH*ccB4UtDCUGe1+Pc!~L1LSSHD|Jz6<;$ky`l+}XnmObch@pGKb zkf;p6aNAzU1sS?mr8+AnHG?#l7JyuEMw%!Q&7{u{R8{!@*DInE@JP4N9bBw zaWOOimlp*noC+gGV8Sff=zF#R#7wr`v$%wGzMuu&+m?lm_WHQ$C^9|12d3?yb#UtIvz7UyW&PrFXP3 zPEJ2Q2#e^g>pd4iVtoTiaa_4?f!^FnKDXblO9r?a7Y>ga3 zxi#32v3)+qYDiFLmE~vgi70!eACUR(t(^5`hIjrxS&UZzcPtAJ4@}nWo3l(4-R&K? zbn7P09yx|;dHx9j&VKJrT>k1B=6-MqYeSCkdj=xZEr-V}A?p=nN8N}e7 z{SsGyYfmCEz!(LC0|LIVuby*-@xHbD3Fn)=7(1w4(0TpmW}ZIP*~QYi;>ey*YTQlJ=fL z4F>8+r13W=&Q#XpiXy)CJ-m~nqnI2W^=<#HkwKIMpPX#{|kFXJ0O{}km^ z0-wJ1jab3thi~3S%SH~4X~1w8)c6%iI&)R7XBHCyNvg_LOBs447;psBsQM?bQuT)? z#TT!ey}AUs_-h?eMSn61qg;krD#9%1(E8{a27mE?BeA)H{Lp^P{N`_C?a-_4D5Jg2 z(Wq8=4dNHmw-L{N)hXz}gaHT1QW=E|Z76`op%leZ34{=2Qq{9d&Cfr>U;gEX$YwM6 zjoa}^ppP1$V=eb$?Hosx^9Q?S;@OqDO{u=s@_AC< zR6%h#l?8UBf-?YKK(cFL8Snq_LzFTp{QRA0m@`O@+`NV1C$nG_uqz=e{Ju~${V7jd zF#hM?#P`4Z9dyU2yrF6@8w5<0t%q=r0k8l3Q-A~$Lkt99fDKF0JVen=yno%PC^JBQ z-9+ebe&0mSV}8#*dFxHr!P%&k6AAp}oA2YzkA8t41z`+ptz{_)s0f4F|AJ(~D>G2CkqJa>kTObyoN-VRYWL;ZzV zW$}aw+kI=C%2B91aUwS&t>_g44o+OUh8ri3VSadL7c+#(Vt*elzH%O?KmW?533SU! zlIW^Ldlppd&L5f-ew5$d0Cszjc70=O<_y#9`*ZLh!Q^B-4E1#p%d(JeAXDFN7fOMj z{Dh%cY?eo~w$y`pRoz@|q(SpR7-6dJ3&XcTZAierFnsGhw;#)TNnX9LV0^2OU)W-z zjqv)1k;mbrInnwQ8eJ?xF6=vZA^s8lB>^Ql=3jjMG#6+=p9AAZx2>ZybflVDE17)Nml3b>-Q-J&8SglQ&nHd z?|$E(pHUU{sbq$98LZ8H>3l2antAJyCr`mlg2xjRb@_8r$s|r3IEb=sBUP)~DJkc78mr?iaXJwpG29IFz?lC4;H)ao>GYWveBNN0WPD*)}ZO#_;r05UuK{;C$2=2QPL|uSwtyy=F9&ZMA%} zVvj^G-nPx>JYJOK^T5N0F*0qda`-TTX##idG*1CELN-UqEam;_N_GxEzx$8z&cQ!I z(yF!=E}BGnG}NF607#f={K|p<2*E3&{q6ZS9b~K91-Ld{Qxp}$lx(XNvF%1m#kLe> z8EZCY(m0nyGH~qLO<0bDN0WQ&9!j!Q!Z&~PV>f?NCJk@_&iT(9){5ZLK?`xNr2wo zmnUHRWtL;7l!^Yl$Z?^x@kA`Tc3p^+&S{IB$m}h&3c#yKcCk^ z6K|!DcB2dib&zrLc=Kl;Px`Y&>x`}gx)Y=+77(c0Op2=aPJ_m$df7*@#<$^xOiJ4GTw&? z87N~^bmSMWzgl+{suwAb_Hy6B-usULKnoYLEvu=43*|&YQ#^k9%^ysq&uKE}eC;>Q zkCnZ;Jn9=8rvDAQgyA3kGjw115Kq4Sdsuk&KK!Du001BWNklR2nT zH2&-P@0zZsnD0)jK{4Vj)GZR3SDo)QDt;I-v-8%5?cmVO+c`Q+cZDW^wvCI_FkXLv`0S-G{KB9gtMB=GNPSP?c3fYzdu^Io*!D6Qqp|Fx z!-om>>;X)(d5K?|C7Dbb#bODRHdg6rmn6G)MO3h|Z3mWBf6@{mwv87YaL=^?r9~Jd zTX#k~KQ8u@xIz1>d4_|qY1q6~4X=vrI+3dqyLvx5UZ$S!vR`S5>Sd92&8%k7}P1<*n7crH!{>W4Hj0kbHMFg7K+ceY<>t@22;HT=w?)UhIx2zE zDyr^})-K3@8jl+zAdZdX+5%dh+(GjGHMFd+q3!7nlsdbybn1O+x{UvtTyM#!0%`S7SI-d`7@eBIN@r)?i||d;#4E>7L~eiLz(L?Y zKN#Z-%zajZ!uj+WK|FiGcTauBcf-us7#G}Zi8hw)yKka`OnpRwY4T(-4dkiZ)j|kC zB9XxQ`a0N4wgTKRjEXJnz_x+8x%#TKy4aZQtg~f1Ip-iQ+1n;~4AJ;z`Ca!whH=iM z%4dID@1Kg_y~nATy}GYkTIMR(O%>abD&HM!cC=z@?>J^hhC}-e65FzH`{-d94#mLi zJj}9WlA)v*QA4riOcjj37^0;=5t=v9-mdONSdCf#N-Nj+axclg$ASdQILz;c)v zU>JMy1PRB+mD8u1-v4O-04&qQ|NG&O@SETKcGb4Mi;FmY@hj*#y+rbU1N-mXhv_)D ze_(&z<55>at3?E*W6%JQfT_)bc!555JD5-~CnE|yD zRiIq-GpiG-epmIWSe?kd$5N0=_5yXvHegnQ_0N5I5m!&2tUKGn=)eFzc=K)i?9zqW zZNGIIzjEgv;Rk>ESD?TDC&2r^40OlO&Ky;uk`&+xO z?F7$&3>xx_4v@X)4I{Muq<3vn+z*(cZCA63sh@)ZHuIgwJ7y7T1;Cf3OfG#>S3mRZ zdO$b-e)sS}%D(C@jN!nYdl;E|qTCU&RE>aWmcMXI6W0PZ+`dhB#`ZeI zrF9f+8wJ@+qL<+I!B1!$+v`P2J`a5K5yN}$HD|1*3ADEIfS1=^BVY`;af4xFqbc3{ zBo3C|Zqc1E-hIL2+;z%kt;0y!)Uht&N&^E zYYW)>C;u(%OdFwLPO9`jfp=z^ao+mGJ*33S}55V)XG7FbX_8@L~eD`=33>f!p_x-YTLDO9}r|sR{U=?jWly z>{pG7XT8=SwC~m1Z@)BtuI-xHYu^X)3q&8mks}17qd=_$bT3K_!vJIKrON;=u4^}V zfa3b0!k$8dq`*nST10J7pVf{DBNc=C3nqNUwlM4*Ob~|=#X27KVq!1(tG0!ULH*d4 z|0~j*=#`@UC7k8C3~esb?~ck9$j_2Zm>nI)gZ=wZ$TTMt{iDgfAe3R?$vjm2t6ztF z;-cF{5?2K8kIp^BdEQ66PNKi<05ZuYEacn)DV5|OV+_ZRH9nv9^zeD&+BJr?wI&SG zBl0(GY^L9C>$y36w2G2-uM1Q5$$$u%Xh(87vW-_mP#7?5ij$YG;;XZ#P)w(gYi&iT z&I#V26dkMlM?ZYyHZmJqpfJ$;Yzh6(o+H=ZifboNG-shRfNVO0_g;AoKm7C)STV4O z5UD-6AHi@aj(v5*)q4*P?5_kM`=2$j<>0Nm=v-OVLTY4)w&4lk=7}EGx;ouO)Ah*X zy%Rw5LjkJF)WkTLL9qA1BcyW$Fvyxg!q4z{a-t~#+d{TlvM6TKNal;seWPNrzCOQI z7tuaCe_TK3Rwu_-Dj_{Th5ieFhOV0*W7STBj-SKKcYh!22Tq{WUj5$I);INCjlQtN zyHC|KwM4(863;Pr_J^X&WWG)rNg!)*s7t+smBcgXGXR-f9$m{TD5g@_YH2*-Q**_S znRP48?@z6EcdI?8@|TPMOx82QzIbjR-noPM4Z(`Vvl4vV3Q2&mGS8A6^Ojf^Uj%pd zEI}?8@7SFX(=nk+oxe}@yoJF*xzXDB_l0BeARHdlx2_fa zIN#gWdu}hTmTmPc+5XQee%7O&yqMja6h~leKL;IrZ;95P_a~Essn#S;UYD&x%)M`19E{`u!HOWY5`z~@(eA+?xabdRs<>6JX5dX2$PUlf~4Vw{&x>JHjA zO<-&cAcWw?jqSNLQ9!FfEEsiUSs)-tnlH)_3wxxZJ!<>`7iK3aFAAyTWEQWk;l2tK z1}xi#;cQP@HwpscFc@}Y*-660FbpIt3q>W{WoTPUktmnl08l`fYcq6t0K17YF;@3409fkpN9arz6>i`m)x=>P0rqxZsJAhEfM^~qD1`fGm= z>-*25+};Bx<<)snfwJB<42lRnq)x=L4|(^U3fU}OCvuvX<*OtRH_Hx=UcU*`aWFSL z6k*J|7>0p?-d=q0);qP^CM^u?9mT)*yZ=7$?e8Gf(NgmmuR~K_wJ5tLx2OPEJg4HQ z-CDe8_XOBQcdxlekQ4|pBEIR3pSzlvCI{2IMGV70I-PzgiR$eT#(;7|6||b^!mZs` zIN2QDuG+S0Bz4f3YW1rEzkWR`NiDvs z!P(xG&K7K3KXn{yogFBqQZ?-9H@=G;vz1@`N&In_ikZ!gR!pUi1XXbv|vXGo18v+IbEZ2~p(HefJ@w&e{Rx^^2*1%Ii!!h0OSp*o5h29|pH z!+i6^Q5?Q?8|jU_cJGBFl3D~ej-QMigub0}>DEoG{_z*UNCzf9IFHHEXr-nLnKU-r zS{0k!fQe|n59Uz({Ez-I${Tr{`7eJ9-N(lpxPs8LD1Sk3lV9p5mupLUVFn{V{9i#R z#q-yG9h>7vK`s4Rie`TVk1!fZ(8$$EtHOUSF~c&qjXa<5(n;@u_`jT$<=BLUBNkYR ztYCWW4B_wNf!h?qv!(vh1`_!aMy8*lZF3XFbPBhR9B$zHB z)P(d=surGsa9hJKjXtlno|^j5;?CGS4L!{y0fqutfX>=ZoG${lV-y{XEQy2##u)6~ zmb$w^u`CO=ZKGT+BawLVb7rXo+`I`mb-Map{mC3KS_aG%00zoJjBI8D%zrY<3UKHK z45A1Bdi8S@vN(vy4cZ?@o(Am?vJc_e<|T-U@^2U}RgJRKXs)a1Ck*sqpM&&^>ozlEcd;R}y8TU(LOWE8f`?_F)C zR`c@!&BeKGsXnl6(2v_Kr4sP;DNrggSQc>NL}T})vy%rKefAkcKHsE4`b55E+lh_0 zAA1M$#%dsh{$}!HRGU>=swy%J3bl~gXc-tBn68F6dFd)lP<(avbbTBRrD$8tOnEV{c3_P{nQ9KLlMW>HpS5EZzZjY1zy z?uFqv*nj7~`&9Ev3_OEv7BG6BD-o z>m>2VTkDDE$-x*XE5jhsVr80%y-kzz3+K-_|F zd(Mxu{R^f2euQcquI^bC5sHF$2Dt50PA75u=wU4M_xbvYE7wmR$C=V)^vyqqQ9%Xz z?CM`OC2B@G9^4^jZ;9hYgsa3ia^CV{aPKz12%mr+pXKMbDYH>1ZvuoMooENC(eF-6 zLv(Q>0gQ}r1$_Pb_JC4p%)JQ0xtS77i}5W6h~_}o+lq&jR@&(W>BOTB?R8OK8DWr) z%shpiu$o#5Y5dU?MxM-q!a&FJI$rtgOO#ScTshPHjNA2!AiTsqF-jCeGqdPeSwp@h zgX<@bS3SOWaS@aEAHuLHGMjl<4LX&zE7ZNij=P$rm`&rx>0{Vvk6!|Mt0jw@$B!aW z;^ccFlWtmOiZCgp)424?Ih?+D87390pT)IF$E#x+$hAasy4I4}kzpiCW$bx0?M{D8 zQIY!7tg7Z7CEV=Z70;?3GvL5-&zZ^>aNzDenAE|O z(a~7f190bDXT*~1mT989y9?;CX>kL3&>`hvp8>M1>3ej zv6|EuI#Qdw4r=G$9-qVxYo}^|^|)$8wznU>E%ofzgDHc-vv-!!UAtZjy83kzrJeWO z>MCak795yv2ouHiQ^)aaZ~*0)ff&V93XdlzKn(*E4<5q-AQlD51#of+rvV1XwXW0* zWc*qrZN~#xMVqL)&pXcqqnv*y)nsCVU}y-Kn`2m6dC{W@lIXvxYWL|bnDFCuYbKb0 z_O~a>XSsM;?Mb(H#M{8%RkchiZz*%pb4uEQ2$=+c?&r&zzK|ITrRcf#B}NoE4^(1G z24p%g+;DQ0s^udwz;NL1J={OAzdB)5cEJAkOThOIg||_}tBYmke_npsPMLUcU_a(Y zhQMN^cvm zqxa%pf*B@e-~DZD>^%wQu{Zs;N)U4KpF@5Ql4f3c_zb7Jl)ZY)dz_apP~FqwSLE&F zq7!ex3>O~MO)L6^Xgb7%0}}+PdN;p8pod?NT(ai( z?C6%0m_7VfpO^lC=X>Mf7EvYGKH5H=*3@evm6FSz#X#HP8%QL80|$7&+nHh8tgyb$ zHYFx`Q6jLp<50Yam~F>#U{{i{1{+KxqM# z7U0m$%1(b!iTv05Tr%*qbJgdKC}eRpLNp4_t&MSYjjzrEIv$l{4kC!5{VP}_Z&0?b zMb#xS>UXst$%^pLCS)L;m~s5tS-%JB*`bU>9?$z&>+HZrME@%QtZuAhd2Ov~(6;w{ ze*4Ie2;`{cjIAD9O%DbknSY0Qxro5+R0=q8qVfJ(T7Y-nA^7k^2FC#y!?q=s*!?`S ze9D5jn6P6Q!mdd?>3)0G|0eOa6n;N31Azrq-xCnVU{DH1NMxKx7(?6o2HyC^Cs6ZB z3k{`W8p;e95d)%VMBlbUDa;6M{n}4xIi6q80V?6Z3@$1o1P+lprjSYFr|-Y#_Hg#X zCGWemaYd zj&^+d<~JhilaItZarWXEO(NEBI z0HSgT6pL9VS(W&nTh+t>E}cJ%)y~dpH#MFRu5$>}xpOtas$4cDFh?}pEIF3yn7me- zII^C9hA*f77zVNM_JRKt3G>A-)KaD49AC*KFgy$}wtX45f!z(Ny#b1HdmQsXH>6~s znKVmPgG>dn!Vneeg2JqXM2c*+eARMltBA2jGw4`Z#a3$z?jP7+_ciaocOTi!9NJem zklHH3feEu@qib;m%py2>VU|$|Zjtn=Rj|=jSVr5L zg_AZ#nCZkoklD&t%2&y}iPEXSkJ2+KGEmFFa(8##*Sp@{UiY!}h+~>q=N%4ug%(wx*Wb&1W;nwYI>&B1ggw)s3V|*u?L5Q#A)XHzM^;Ce?KvgSEAR z-itp($F1Ag+IR@;IfSKi-$8El5DLAcpy_PHzWn1=o!9!^49<)gOjyhJkN=8JWv{NU zp#Ab9E56Wzh6|w?45T&-7=JJYFyP5p{J`z)6o0l8$sqM0*>>yiDneN z=u%Wc5`R3+whEekPbMaSi3x&a5?EfQD3uzI+%`?4LS*bdo2U^~il6{(>8O<}p2I-D96z+SDrh#9RnBgCD#CE{_)*Lc4Z^N- zp+!EE!OS?%3OoMbF@&>PFG)o!fn6e?+w0brq@7ORN%W!5`sy8sryH9Ms$Vu48R7qC zvji(E4D0K_!orIkQ!P>Lz&IARmw*k^Gk!Z$+LRIvtNYaB;I`nQ*z$Sj)G8oy)xuq1 zC*NR^m0RYxm3e!lqfKPp$=$|Ny8v8V3E-E%`c%UY^XMEBAX0Js`8%5$<+$m9O) z2Vg(E3jjF$pL`ps?)ZzJ=NA`o_1+z9pP#`d7)ceoyXzPyC1ckiIBr3HIO zYU7GrYYXOvhcGbv%+;S!^cyhulxjk7ycaOOgo-^<2SH&@YR5k)w-5yHcFV(Zx09GDfy1e8B*0XLNhVX5xhs8 z?ANUr^+=%sgwP7vEEkxl3rpbovP3p+Zr6zUUW!?^G5%-@(-V6l1y>3{UK&Byg!2=Y*!Nozy{ZcCWxDhl>eV+rqhK00FiCgzKD_FCBxmewJ~p;c{4uFg{IN;8K5#| z?VMh`3g59_?;+fNynp(3wVz-Qr2MP~WecpTTC!>eu%K&GuTYFa*X)u&jw7=_xrW)l z_ynoRe&Cf@hX#rt$M0^Pza6qWeZAEskpSL*pO5*%1%~D2?LFU%eZ)T4X;p{b{WeDl*cKy@3kV%8n49A8wOcrH;}&Md$0AoV?pa*InM;>J zK{UJ3sc0Z|fpjWgz`H;CsFE>R27q||1;tbnAHVZfO`ErD+xUNe^jG-ct+&z9S{-M4 ztxB#p1+S%7(-VL9_wUElUWui>IFOZ`2xQRD*IgF- zdU4^E^EmVQC9q0u-rcB~BvaY==(a=uw$9wb&`19#tfx=0zUMgBf9-d1cj8#2vD88q zVb9r4{7&9GE-VV^tM+oz^0REA9wjic)LX>;Mk{*80xBuD1lCr4mD%+izVY)<@bSBE zZO=tVkTVy*LeIjIyZBj;3zF8HUn2%tjsTRl@U*QZQGH%7RvI7Qc52)0xPPOgz_DYy z{dd`&LMcNow}osr15#&V5z8`>+KzH!bxJ+&4*u zHa~Z(Zu9fXI$!KPPOaE1w&_|l2)FA&*}7kVD*bvnX|*br>J_ER45qW|P_85B90nLZ ze(Ozaw#7@}Sxc^+I)Oup+ZdUiRmLl7@h}g5kfZgBxIfaS54XKk4zan?kr~3f2mb&7 zkT7@8dn}|Wg_)B{U~CL<9D=)d8JbiTAW&W;sE#Jya0m6V3I^JMuCCPAPneuR?e%P9 zDy1w-y@-{B1iX}0I+sT_mqR(71SJL@?yureuOht*i)de7gPMR}T!m>n7nP_6djsRkb^(?!8WI4k+!``Z9-{TZ4YbeR0PGZ4 zDh2!8x3IqdGz$IWpvl@RgMvpM9z^3EiK^37Qd_$Hf<~`~+sL;@2GsDWUQp7ajc6r8 z(y|*{*z;%_ts9#tWYT!NccSK)w^P!E0w(W0@KGH)MI!Gk)9!zZtmEUr!~{WWE8sXLOtZPc#Jfcthl0|^ugkJbP|83l+cjmgR#t%Z z^~RnyLJ|OTAo9G{Y#-PMxJ?(5%`6Id4sNFd(rRsWVZL@M7!G&*>fkw?%+~*v8dYr5 z&+jL)y4*ve+H+|!M{ z4<13dZ3T%XS2)YDQDqy?3?r{c4W(3P^I%)6w)Sg;oLJdJ_e17>d*q>bh0F3{KZ`KvGy;Ue6VI`1EB=GsQt9+wF!9JS? zIXi;>?jE#cGFVty#Y_kM{P5=NP07*naRHTz{VjIw0N2VX`sn{h*(u+^f z^5{0&?_5Tyy%*Ep`vc_r_h@Z`o`YIW{OV|_x{VU&j`+!9u{|0#_V%HUK=dJfd+Kqb zJhRYiT$>54rebTuon^TvOZK8`K>)CdHV)pt3)`|Pc86ax$}#Xvi3e}ph3VL^$~HFJ zTCv{Ij?Grx*>6ya!MSdr1=JX0%piYikR|ViAU6AfMO$ z=*40QrfCF{%ZxG2$51E~VB0nrW1&^Kf_xH|Wx=vc?Ef>|#Xh1>xy(l2u3NTZ%zkt%d-r=QYiqWr&!3^awG~r0?_>J2 zn>f&3J5$|ydpp)TJJ7ni>23@9z2!E2*4@q0?72&~KfWF!=)=>ec}3^v&tL3#wpaXU zA_^W4vODEA)mHTKHS)9cN=oD=xl@@ZkGlOB%3ftLq0L(kP0gYE*^)aZkzLR`ZUzF& zc0kHh^PoAdCyk$-fiHw6jKV01YQXwZX|3-VL0836Db^w+RflqWT>ASglyUi$vu<_d zVmeio0~g5~ruL458V2^=y$>6_I*nObv?(m<$CDGgid+8amtSDvl*{Fpl6P*Fn5KbrI@N?E zXr%6dZ?CMc12Z%Ak4N|K*`TZhgCqekQ0h-)!o}f1*_tp=RsyA)AfB+%D4cV3{LT9h z+aHF-gRr`aP1W}P{&XB0LEAy%odg`q z#Ps->rhsRMhq2zlvt4(rt)Y-fAyF!0WM&qEzK46oawUrahGHg-r=!(_%XhQP>=}bW zDfT>?Mk-eXAfQn5C1}DoDvk=V-+ylLMnnzO_DUGF8q{uQ!Fd?KPHZfrW%?Gfj~^mE zGlT5n9nj7;ES>%(Z0wsvp??pU8BLuxeno0fi(jva02p}o$X}AT5CLW~lbG%l5pEO$ zQ*jA$$*$+nw!VR4CI!bZ-OQsqE!nLtj6a&f=+qM>K*vj&2ni;sy_AAV|3rTVnWB?) z)AnVR?U?<;05u^z8x*BmvHBYu112X4S}NR=X&QBBkKRtH0@!v)Y2>f5 zIF5sr71D6_TS6>u9We@!?Juzx_U6|H(ACLW=R8LmYtaYrx_p&qRUZ3|7pGx>;CA_I`@L7-~2&zh1nLH_U! z>^-_4nN;+0ZmQ$3*;%}{TC&KuWRS`g+&dQKS`t9Y1|;%U zGsj3#7arTNFmeA83^2@$k5w}0%WJS~8z;WH#K(S0F3)3{v-rkOMK*bJ12-4~B#a{FCz~W-5;=3S7B>E6XqsFl-BI|i# zfWZcs3`B@e7*{8OYt2PEks6GLb*} zsn*tT?NLbrt9FkZg^s56YmD}^eD#Bm(Z7ETxpRYPoBR&CCu>*soF5uQqFBb^)!Xhi zK3>yfJB5!zx2bkU#2o!1q+YxAMM^fyaq+|iFh9>QJ^i9b6koh{V{>`zV2_R80wwM? z8FK6>BO#F7G7rEI9F6cTi8^kw#;_VdUGaI99Aryd?is5EZF4PXf`JES^VX(oLqgFz zYPu}He@?e7BT2~y{qKJYoOm5*t6t&w%IQ-$a_tt8v_mD}Yux~7wqdzja55+%dLDz6! zUH#XqeR8M!vAi&gT%AECD#u)VETm?OU}-*oY?O;=ow<#H>v!;k6|iyQ9N5q(N*!IG z$xIDfM~n$o+r+`y^@++Ed;NH-hg$Xh1$mkUD%R&wky1}+L+K3{$H>ZW{LiRpGaY?% ze%gdgOGsfbik9_FoWA@OZX7>`Tx+~{yb)>H%z-%69gWa(LDl?Jn@qP(Yk5Y*UG`du zVLpxO5@zF6vpZgdO|nxsJnpp_MhcEo1Y^~Mtq&a{=;#1iT7aPG!7z*pj*WHtT`vOX z=JU-6HY9;q`b9{&Tt=Z#Kt5kYv1lWakk?0PF~EP}fU)3(?~IkI?9e3;Yr5AJS$4Dfs z;&vU^13Es}y{4*9zyx*A8?32BFS-vvF2bg85+=SneL7YG-Su1!#gaF8KUjjiw{o8l zF@7=U%keVE-{K`xQB9Yo1#JTWA$;-xcv-8dDTaK$nP<>NnsmG4XO3f{OF~&5shUMx zgi$HOxAh{*dUjgAj*uTGVJ;_kyi+~{V3r&lxP1?0GXZMoD;a~pwLvKk+`0!sS;bKF z25obYDIlf+1LF^-+!s<_ku>BAnRKL}?YN=>c}a)qrRz)S1eSZdc?QHIheG>W>*&B* zM+egR0ur{3fw^a(o?M0EQ$Cx)QeRKgucsa zkjfQ+nD5!@-KTi|*&Ss1J23X$b5+~sT3fK((~XX$wNRxWCf;y|M&w00P}MPTk=LKt zSVr>M9J=m&g0{z3;GhGAu5qkR4r2M_d&m#&RgT|@(dl@B}ey^4jISn~X zR^8@;dgl7eaqov3Qo|*YFJs@G`>-tw&xQsX&R`l>S~hbSe>9~5X)j$OL;`7@YVn(? z{@{wJz_->j?0wF6_L*uA%ws*P2_U9hE^Dx zrU}ckP%IXkIJ(Bfn{BKfF--%-BE#lpWBmlpX$%wy2?pR9xxL3wP+9TC5*_fPGVPUue$>MM0PlF?ce4ntGyaFsIAn}a%Hq2r-Q(^Xs6!^Rag7Lyl}0S zlNO#24TRobRf?q&W*44g@5pG?cDdFTJl;Ejp(nF0o#wq)y6e?jI#=FtuUniTPFc|A zkrQ3n5p?3~yWp`|($xjL{yIUi2z>S#f97&IG*rc^xdd@siQ|q@DID=hJ>I(@T0YY% z&7%^_@*P(#Oh9I(HQfDjv7pcu)ICd(F7l3DB}}~8a3rReI#6Hg=M5W=e#g4n+VHcB z7w{|ZyoJ^c4EiGs(Z@{3`y=npm$Ffk!HpgI@9^V7Qad7D7U5G+?QKYNA9p8KV zou-Td0ET+|F!VMjmCKt2{BPzzMN4ZdEQ>pzkL}x!WBc|4Zv*p-i@1LOUgW;Tuj#-< zHn)XRDha2Fi}G4>IT#Lw9xkP8brqMX_`*L{3I@~tCguY#dF{VKDb?QK)bbn#KKWNj zEv#eV+_$iD@|A$zqT3+h4t)Pe>al;~ih56pXPY1OLffPEA=(OyLuT}n-$~`y;$AhW z^rgQ~X5f>x0c0q*&|kve<-l-5U}Q}JK);W=?y6`6Ffa^F&0=V3)}#0Ink70-pk~-s z>yM~(g1V$lw+w?UJ6)u9*1yLS?|V`|9***qzFa~`+E;lhnFLZPzVPh$@%rwiKMOS% z#t;}h%^1^yo{Pnjo7p<3uX5QA#fABN9;H$l%gZY$6bdj51Ga6$w(Y>|S%pFYjKR0h zwr%9|d8AUQ%9!Q;L?YqKc1;LDM~6S_v}u~4l%lt{w`x#zEuoacwr!--X=E}x>yYs2 z=E}W_=Wp=aj|NGBA{X!6?)TvBL9-q4eXgdJg8J3*Z!pmtv`xpl`Z%Q~)xWFNqf~7x zZCNAWJaU1ts0<~xJ1~{H30{n@B2AGES6I(M;|`P6jSVoyQ2IAFaQD;#Qm;+m*uDce zdGKJ><5ba6KR>HF+UO!}^zi-qtnO{U8~B7MLbR*c{o`$K=YN?D0U-=iQ!jQr!JZGl zu4)eU4&qkiKDo!AomS;wS!J($&Y7|e@M{^ljcWiC5`XhQQ45B6&MtKuReIM&+JkD) zw!Yw5Wt!Bi;ezQ_^_{xlIg&UGxH1P6YFGPM>g|D@Q0HzwI$j-%0w!?t$Was{RJ#h2 zLOPA7W1}Dpn7sR-f|$)%Z|1$}Da`%FW#GaSbe|Z<@xSx^y2b(kOaJO3mRSL_-#mft zjt-0u4de1{z5x2w<0mlC(*wNGg9kG+`0CO{06=G38%`Xkt+(^p4DK8`gnhRj#2(k7 z_s(Hx^B}s~gDZ7ZlW6Z^_#F@P`si3Bj>jvS|1`P2i0&&NqT}8rl!i{CIC&h-o`Wzl zE$$f9@zff57^(_t>u=Y5WFz%ec;Bi{lX^>f0OhYs6f`U<0jMbr1#T5M*igwuQ=*HvzbF#5Z5;1#Gi0Z6dHuGP2@x$(O*%V)zWUb9ybvLTAeBmC zb8|CvL3Gr9MCIznGi28mN@-|SFzzRCP%IX)wY3G)G?7TGqf`p6&dvJ@shCU%7-J|D zHsLr$PxY!GKRN*+-f+$ezd#b;+;I_x(FTL0D(CQrf2#H*(SoyiUk*uV!QuLx6Evz? zb50N+>=pmK=50qpHJs@EihyS)~U z)_v1@5?KNUW)Lj)_rti=_G&jLY);bZ3~JK}W9gQ;#rQ zC!kX?lY>mbSm1iA40iJw@ImxLydcJ`jM#(&JDtGX*f8!MitZFFWYV~P@;DN98SP7J zFe!KZQx_}%t6d#UDJ>mUo-Z$fD04G7&F5~{A$6){B=NS9W*;ql_fFS+kDwwD; zd*wcU{@?sF3=9p_4BB4m>47=v;MCHUNaKksD)6e^wtht#9h^ikVi-drw~EZODVVd5 zkezvg&L>w;8W_a0H-7```_ER64Z0^g14mSd?7wTe%TU#09@+&QG?U7DU`Z_i*w@?CpowadE)>wdwyrrB)pc^gLEK{Hv+8IFGB>4E zbHCL8Yd1<(@0_94@Dojh)7RfqvkgYe;sJMr04GoS%T(<)5#agd6H+NDod;vAu5wkB zQV>G0wMDSDMv+LUM8BW(56(KrD)yQKN(+^7aDdHM&--m40=}ABmNOMSQ7~2jrA1g~ zQfc34z*2ScIn0sk1<-zA=_jj$`)9sB)Y&4;wFm$@0WFDXqJ38ZGu-3ULW16qI6!rS z%57piUN-^*ff}|X#v}r^pA8S<*3s%!VuWnua`^PhS2csSg{T4BQdGx+iUXvmG+$KW zpb;b#-41)XgPr0?Dh0gzF284=e8RA@f)|u6qx!F+K0URb5PiR-f7Sg^wgo+zOdF5P zLF*5&Q3+~P!mkC@E57TseFT1$3pk7bUE+84@iR+|Edv%s#y^R$Wman*%q+{==~^|| zYVnI@S@>(e^ez1HU;KH^wu}&b_QvaY<7XeEWj$A+tN8gB`}=V9)X4~Ej3)BF@#}CR z1a4EtP*NP@sYIe_ z|KlGZwLFWdU;lf70o&Eiq)II!AjpZYwhbnu8&{g%KC0hG9sA0ACVwH-UncDxSuM{? z3y9-r<&70B9rp>~%h)N18)zp&^aLd>&Y?a%>a~dH!+}-Nd}g3crQQQ!Es3$JK0y(T zBNIIMpIx0k@lz)HcJIC@zeTWYx36cn*)Zz;Y@`?ecLvjBAcSFJf?)rCzK3V_s(lxD zc5CVeQs?t|Q0hOzGlu9o0Tm3@g9;31iW>^pg6uDd5$v)MGLD zv9ZwJrkjdKXmEWAj(;|iVw)yF0Miy3d!yMuj4|YkMf~fZ{1~Nj8Oi_n1l~D!J~H+N zcu$^6 zYz@bxkwlY5GMkY}viZ=5_)q@GOfr*fWRgB4lSG+lGbG1IwZvvG?5?gom&$zs5=bBu zNbErD;qFf#9?#$E5gvg+CbGy|mW6Qlx4HZC`|i2-zI%V`JkZnnW+rh=wPXVGGt+oH zHMuAJS5Bv~a%dFC@7)LcDpj3GBU)Zt!=2^F!1fBJioH1B_DF!~6GyT0<2ZKvzO>@S zq4D8ijK}m++!z?Z%IGMDR@Sr?7|`vK;%{z0*7FiI8?Q-s(~QSPz1?I!kN!J1FmU7N z*gE|-woYFL9iD;}%fJ+Gq+G+l?w9tJd(*Is?|z8BUbBUW1GB-#Zpt- zy1IE=JioPNVSC#JPz51eHjy2;**VMTgbmQ(yk~)s5*()w7BR~?&2+5*K&cC#deB!* zQ+ti@w~mAL{^jy!?Ujsu_4Y)~p?*$Y^Gq@($K)!$*0H%svngureQB(6NFR>P8CPfH z2{P2^_rZ0y5Lykcht5U}t2`27AooH`P{F116g>EG40ChpqP+8XtuiD4*q6qokZ zrRc;703cXc0Pf%4->BQ|k*?~X(uCiSDbO5fi+`CzBZH;H@JnP7ERB^In@3awGRJN) zbvpqOTG10W1AvMB_@QaY5`0yo~)ZKiPrz-~1dK|KV?=zo)llBW^Gf z4-P!IDF;iF6D>JxGpZ#L_~`OmcS62wO8&Rn% z12^fwskWxEPrrQ(J^$=okPnwys@G^~5f|m?r!0Oyt@jb1TIURL1Q_CbuuHp0ZLXku z?mC7({eST+J%aqDuVU@{KSZr(uwGXkOXrCy&yong)ff&csMh%tcfls13$_TpIq%}Y zkvVP$B|K2+sativVk2;Tw0sX2Ke>vlZ(hRs&|qxG?XE%*j_0DBPPddgBw4BA@WLXF z-+O=>9Kk5fohw8KZtlFz#a&emr;3m=iDKaMrRS~4@AUmyBoU+(@?F5@AZkDEE1Lx_ zUw%H%ix3Nx(zbx*%TA5Jx$jf>z84zqSp+t-ZXo*kF(p8yQiAW-;QM)@j_y1_sSA@c zcW|u=&)Wi}MG#U5KsFpe0O0DZAy%p`{RLzZ3lwPp+wiG5qPbZa8xK5-*PE>|Y8lla ztpj73(}`^u*Fx=@YKGN~)#5nhXxp+uo0Sv6GLKs!?`l^6sU+W}Se6^Tclrl#`+Piy z?RH33#l}&=vgbvFvfL2&cXTl6?Y9X&{E%X8ZU6g(IR_5QC$XQgg z4d+-aGnGg_Y%up>W+)a@z%!Gximti&noDr1YKf&Y)>V95RTpHw;#aJ?bjzi`fP2_= z+^m}mJ3~w&Wh-eTlTEv%^36Ch*V^VL{`_Y@36Fp0Tfc_h?(U9^$H}Jg!~6dVR)XV$ zk8j?g%s!Wh`D+g(ynYYWT)q{{(Q^9EGql0o*`o zQZviPyheL(SDk(0F>$Ntz4IZ)e*Qjc-J_WQ&3}QygsfL-RsIOdG#-V%&Y9Ohotl43 zIW-JWbs;YfHLzpg) z5swoS)MgIkCV7qXIoWBOXP)BoP>vEWZiy3f4KQQ6%0G3(vnb7pPf{M6E`|PWBX#}~ zk^+B67JLy1To>Yz&>+ zG}J035=m66HB>4Uq+d|VuE&po8#neJ88p(`wqKWBkJhTm^>w?1ieF7Q)?AjmdYL#? z6n2fmy>i4YUZ3~jOTPj0=49TM*`b?pZ!r&oDFPTD9q@E&65GAKxN!CJuqCDoW#vp% zD3$QXKl;m1pYz`3w=pp?Vk{d)GY@BR^!^-NIAB3BIPoVg>Q7lYQkQ@ElMk-a@CoyF zOd0^weeM63(z^X2F10GFzewut22Pv^B5pHUUIt=j^gfWpZ7K0*ktkWJGefr2urs`l z%$3Bq&o%(Eyv{5m6@ZX8u=v_C|73`t@gTkxndzA1wO#C2blMg<68lbhJ8Yvh&x^$| zygZVol(0d5`vTC@Uhon&`dZS#?D5V7?5ZUacyf3Gqf5&mRL`N;h{lG7fbYKpd>s$7N zcWw+0AYCkBaAmFDqmC__p~mM&swN8{%a4${e-mAs>)1K|2A+K59}A_;x_M5Guy=D? zaoj=)iPD1Nt0(sx6^A*P1{BU;i zpbQiQBTt?|%s>)_@HsZN(UmXZ*u95v6Ao&Q6OL1*>}~;5a|>ZTAH?XeO~d-KRYR2g zWF9Z-C)Mvj9lJ?~q|ciDmlfJ?|AlVg0h6M+o$yrE&>Y#n?*ame$0 z$!1Gw5V1PY5mexLvOPD*l5F-nQroK4YA6;9!{RTX57hPQ$B$FxQrtL;;0l?N4kk3dQdP(_03pJH)$>yM{iOIFM6QfNc}pxIqz- zS>U-)TvbPuc||AwTID+203#Y@WQ7Pnr`DC-6Gc`eeu5&rXP-Sw`{IG6vEl-(Xrd8& z4gPXQz*EDh&x8VD1Rg!LDT`fZL5$o*rQU;fSu}^1$gxmP5&Y==U*aEp>(`KMu-K_2 zDlC1+!u*kGJUnr%wf+_Q=u2EchBSd|K`7L zdmO1`3Ljp-2G95L>Z#Lk90#A=yn#bQ!}$KYUk}TbD;50suYQL0^$lFU{07dPK8Zw= zUAni=oe6e%E-W?_>{XgMd>Dy;@?G5e@`IM|r!jaitA}(Tu|G=9c7TZvl9glM1#xR2 zwF(m3>*&ApD~$c}Pe7dn7XRMwW9!V9;HR_U2wLf@`PgKNQ@hcV6_;hI{9?73s*mq> zCiQJ32(JWX`DO?f%|YZgBDWOjwU0l;l{YS7tG_SC-2fM_UPJHZHtwA|fu*U#@N64y zgYUwrxv+f?Q;!yK?Eb?#n6}~8d99d8l<`Sf;je;c6KIyrH_eEZizAF2L`D4b2G#rZ z3@j^158aFiAs_^8M}TION+nULRN=Zcq*C!W9PBqW+Bt2yrk?YC3eWT4d9D%cQc8^x z)PMkpSF2U{zK>$Dh(e)=_4N%@DivejLG(7Wl_#A}fl?d0yLtG&3(woCUm+kwcLuQS zoM9Jq(5G!>P$5gO?JR7oJ7QOK)YmS^jddlE=WW-^>jq=Fy+-Sg4vh77)bq`i#A;h2 zNM+@9B`1}RO~6=IHOggVj>$Q%=~`eY;2>F6b*hobMAfK%&wS1EK_NO+iT4wa!?~Up znYKMH+3@O)qmAjHm?)k%sqgJ&B0_*mmk4}6*aW?>@S;c5Dm7Mv$dV$jBO+`OR}-N< zcI4NkNwFs?Z2t>nBorst8iMRlP5kL8bH@yfWWO~3Q~ zB9TYQ%EZQW%`2 zj)25fPE_ye5y5nIv`A`MlN4e4YMsIs`fvOKV?X^rVYyX2dH46Qb>=dveZ!z6`uRo4 zAL6xU3jD^(`{=q+WlSppm986P*2vnNUjbsSDFTL_sn7!FX#g`7qyC$jibWS~_U8Q% zIS2fMweE*?Y4}(CwnZK*^DcQVtDGUqw9A~zRkuLZ=|<*%ri7pJby=#@O)aKzn~wRL zXoihnK6xOD;>b3^Ce%&M37cOpL(Kw2hz&wyoauQ5%*SMyUVvYpSSe)<4;GI59Qdv9U~#k7Ig#JUp&ctEkp$aD>1}#|}@z z`iI}Z?)TopP=7yuapkjEZ8LuW=2y_Oy@TD}9+WbzZ?=n~u0j#rJ9z^R(dP^QCb)#5 zYMfO(td=t)%=UO_=Gh}8Klu^tXA9VV{XMK->9Htpj>Kh%GUDw0zZXS*! zZ=!D0mhXGgwZMj3La9{7?(VJ@aXM(r{QOvEE z2Nlo8#oN!tX&VT31UU}D#~&ZmrM6v?MR@ZRSCogw0m4Mu7N9>!`^gAIiCMaIJfQwJ^xXlst!NBWWbZ+{0r z{Lc597G(_5tph=kG2T0Q67w@h;`iHt*xfdEMTi*Vw@-q6`y{Luqe`gsov(ZqKYITc zSa|vrSMT15EcdVf`meD2FaHGe!8$(pj~C(n^WVay({Z9d%ErF9G&weg$+59mWvTKH z2%arZ!V%5H*lt<%Y-4I2M7P7}8!wo_-KJOO(Rcd;WIy>aQg=RsbNU<}{my@h?K5vH zW#jkJ?vfP0p2*Mmdm{=TV=c z%x>JE*xY=EM52a7qID;%R={%{g=$pW%?#J_vH5(I0XwQ6*$`s_&NAp_$0nn-e2uvt ziH2-ZK2_C@`Z+P>v^g$?sM6#zY9N;~`BenooO7`D)Dd~${Dmn0;?Tp#3z%D4!W(DL z#jMeo%mxHDI{BDJj8x8(!^)ake0fqU122a`+C)t6*ovZ7Br^u>42jq`PCudyND(!& zII%d_TzV91F;vXgd3MCNQ;0a7B|Z(}>&Ov!_;-)6CoWM!>K)js7V!TpT>$|6#^hVb zI4Obqh+Kx>D`1C`VkebW{vZ7m_`~DC;84ffRO#r%VHAfCVdLiQmh1YIAX%#7jgLOT zwbw2ppUY`wY|Fw>{{Vio9__k2BKK$C<`&N0yoFjKfsZf0+45KzrIN{5nWs!7@>mZ} z@c*idV|O25>d`!&jg8{r@zyqo6Q3ecu7>K{C}W+d4(4kSAR5V{_`13_M6VT`(rZgd zY^|c}$$j)+{~4&Az{;0@3;84GQSKjum+1ku?3nx|z6=si{%G8;-gaY(Doexbviu^N z1o&Usc}B*(Vr{P76E~eOrx($Yo2{~z(2^e>GlOtYmPt~qJ)TKGy$AIk<+s7PY_zsP zH&H}6Zp->YS%1j+q$<%xn`!j1sOA+`Uc8@X6lKgd(~FZK+Ld1jA+W48Y};&9beutm z83cJf`P}Ge0Y{Duqq{q6FmRGc2W-nCVR_e0A)D=j<2XpR$%link)%9wPfuIl?6C(AG5&Z-SZjFT45~eC_69^< zv--BwbtC?Ip|3ZM*Ua|m`SOyN3EQ7L7d-c+rGp)DyA`Y~U*~cqr2nf(Snf;2#=J!m z{?^L{tpu1`{GuMKtvMqCflyz|?D~BxO5lJ3|Bu8433>)BjFY?K?s^$2_mCw+V z%VA=qah9aJ=T0GADq(1OJse@arx!OaoNuwm=ENob`1eyN6;ZASB1t9^=+0)F)M$-T z$s~ULoi8hWme7;Up(mTe>eFYy;&$xzIJU4bbAJ{VrI~#)GF4J^$O0 z8RFL29}V{2sq=D@Uyo=_kx2MRrGVbvV56Gv`=At3AXG|eWY8?vb+Nl!fa5rDoFKTA z@B5NHR-{_32G?~pxx7>=!*yNwz9&VB4zdzgLx*sY5{U#732wBYG_VDi%jGajmPk=q zwE!TQOi1Oc)hbG*GL9UX(%Na2*!`r_ZEPOx5EY9-P@X4Go=<qX;XbN!soog3kP z)ncNzuVePc*G(Kyl}+WgRIR$qiJ5fjD|KaUri#%;y@4#<2IXyd^(?F6HCZZFpB4qF z+iIC?A2;w!unF(c(h}akdIiHH!}zuT>mM`?=&BOGJAOueQs!Ffe9_Yg?7#;?`{q4Fi;sZbbd1oSTHv_%wnr0w7O=C|+{e*|1OdK`

#^Gw6-)c~g~{_l-jBqWO>yau zH*a(Wtf|a?C_x*8YKrW_Z5;afA0u()m#A6YsGffZ>)-wNP&j%4UaBiB*Sy{MV~9hh z=PD}&3FM@D(Y>?Uyflj>M(WTvh#)}gzxnsd6m$UKhx37}|NXE%R?-7PWxWMk5|W}! zIHIC3IOk*Z$qI&^t=5m#G=6|x^AzWa05q!!MNKY${I?oCPc$f-1sz>{lSKQmKqe zrGjFyh@8P03y>qM0RcGA<#Nafku^3qH<8Wy$mMd#<#H0(XVeH#6GGs5KJxiIeBZeo2y@Qnxe@yWmXw{SmRz_b5+ zU5aAUj6}IyPN2<+ZGwx}Uc9xWRet|G_;9P#3?TmDiF3i#;KdTxwcs*{E z@$vD}&+y8~Yse?pt$EDuF5_@^5U&o*ph_v0 zOF_tbLKR*`}7pfwq;>>V4z{!j_aalYa700;q{L{#r0QT zL9K-hT%90s)$zipl7VA-x>UwaPiyI^yLWbR`qrJ$z--zOs;Y^_zv_y~4T~&VGmjD< zMZ~Qlv-A)E(6#gsnWcNM$|cz40<3BoweA6Ip8pz(hfkt7dKA@e_MYO-p=L5jwEQ8S zGb!lh>vEr+;P5gB)Ya#zltsW~0ItJe?|^Y9OLENsn8uC~j~WJ{9gYD5U0a~vW2iHb z1-O1M(EJg_5F$S(*?hrpDTO5&sS!~}b+#5aF9+Pt3p4+jq%|JdQJlxRq^sgxU3wHL z-fGntKR0iKy@lsPotVi%)NBWqWlnz@IA=%qW81*Riv)#2ww@N)fo->^%Os?g>;^9n zS(dfu%sHK+R4Ro^r2^k?Z9JtCMX9t;gK9|a$(r(dVaB|=Mo3;yh*VCN80D`| zay?OgR1LQ}7Zc0zdePPwIfM@5wz3UGcE;9YG4hQ)fu!NU!?W=bJUo63yFKw!B)g6i zIBs9Mh*z#&2c_KJvv~Ci$e~eOIu!(qNhK43oY&u8gxX{GA7XrA35jy8?zm)%QLa8= zRrV2|f(aj(q=?S)`c7d_T^i{ey-Yay+&Kb5C>9rkW8Vi{w{e}$lg_{5>Vl%`@3o#N zhw_bnfXu%*X0__2RCLO?h$x5i$l9WwkJ(>ze#hG~%Zy@R8&-o!qeQ7;8k>U_zEVm- zcgjF2z6`?qS6$j0lkfYe*7fhHdT^2EeQ}xIay{6d2d{yC@bmlkaeMY5T+hSQ*dhG- zm%q}&2-~Auvk!1*ZZ0^u{S4jz`Y!PA|D%@LU^c&*2eYs}5BE=yNJUZhs}qFi3DYnSpk{1^WNb}GQ*ul^oz>SDcQlubC=R@@BL zG{V?XeX4E5B{q*$-JjZz$T9fZ!*z2a!sZeG#oBr;s+Hy0>2-e^?kvtT4N!=|7J?ux zvh<+O3c{bD^EmW{D72S<+v=kxg>QngCV(b`1Y+uPXP-Nn|{ zR%j2kZL49>D$_>lWHNzVE{ERU9_^ZCS;)lL+({`#p-_Zv+ZY@ih;-17ON5X;XQQ&L z#?Rt;(XCq)%ggQ8kLK3|pj7&tqgSm~G-uImn65WlPfR>iuR{%7O4U*7NKkKIJZDCZ z;%a0^a926IvWmaefM5{Xr^1#SaXXF|wr|0Mm#_h%ug~hrW4k_x@6~&?rJh8p)@q^7 z?cw5M{Oa0O4E6Qn2jBQ+#Jg!svM$$xx`yal5gB94Z%8DzUW$E~r5%P|8q04l51Hg4 z;5j>OTNaNL1_1B86GYxFMh9km;Uuc#n}KfmdN9rSIrUg-m=24_s{t239w4;p*r3{MF{h`nWXubQz~^-K)=88+`dA z%Ip*s*W#ief^P`F~#!&{4s{E{RzBm78~ckiq(Jm2dE5;gJ!zn zWpnV8OlXV-&5Z<_y)0KEZ)ygh`3PBBdI(%a9KSqTrkDv7eO5TP03yJ;pcl5$goGs_ zfb5`-3l{m5In6mjoE08VLg!~(IZ4CP6vXpEJa)&PBpk83V#a6D0b6v~X6`s#4C8=W zpVz^BrqY@_dgS1t9p>nxm zOh@H;9x8@>pPQRoD3was-QAVIW{`TStd$3VM8c6Am?@>GR4Ulo+D3P`Zk$Ub66lJE zbU8ATkc{m+JG&?p3h3|ekBlH56$MRfr&6iFbzO9IW!m2HOew;sYf&k)n$fLWY`1d) zfCoyeT6*x-NH>zGS7b7ORn2(3zFtHtboIV$bf?iqW zD68GMBep8b>S>^5X#xuO=BcTIOfa%RoU1}*;&&AM3Y5J(hfN&1cK0qme{c^I-+mRZ z|NcJ&Msmhz1yQ6r@W~)qSIjmh5%HLLC|~2hIHa!ge@D-UV^-;uzy%8H*4c9v#K_@BKaWj14v|ueQ(ddR*#0GJ@_S&9g+U z4GkeXS-{xir{Od4>e_(*^-Y|-dk+s!9K%Kv2W^%5Hn%W6Hy^a+1H&t;ID6w3?wvl_ z(bUR~h+!0YgQkrD%LMbWZ(|GRKEH`_CLI}Zd-Ult2G=$K0I6~XeQR5A;lK;=gr)T( zuD0^Ax)REBos~^KTLh_9KtWI`lwhrIpl|aTQl)jIw<>U+euDDY3=%u*C?1+YE!U62 z;gfK)eW>;fqBwC#$zow|Gl%Jx$r9_s)bSy1P zYifjTK1zn$WtTyd+`@a3?@*QEnp3N5`azQc_GdhS^h`)=n_072U}lEEvVcQ}fX9#R zdc-f?b>d~EWHJfQ3(`4vP)++n$+p>hiqE5$mVjr^+Usw>%x2QMKoWKC7C)AyNfMN= zo65)c3GAajCIh=X*7BMKV6Xkp@ZV`l3k4q9Zyt;$7%9(@T%j2V%pE=T! z!!{$=aj<-747TTiQi4Yxet?Ts632WGhqv?aCV(ds<1M!<(y<2*F|n|OWJ%6QqRL3> z(+OlYqLd5X4*M&w+?*Oo5c`E6+ig$ARGp)j1t*_5LvZ?Z@OyO?`wS_-Zayp9{*qe0L1rEdH09F z$ybbJR2jr{ElRgoIp3hh!e8OZm`@cjyWzYM^u|24EjtDw{zy_66Kp0|Usu_AK0 z3f9)xc_Ib6VwBBhrRdipS(b%tHjAE~?#ME6$@hI^GJ$>eMH3+wy1Ftbl}fPf>=$wa zcwCC&#}-L|q6*)yz_QxYk2C#Z@LT_?RgNQ*j+4dnV!dYiUQ;{jDlTgg<&4d0JM5e( zla*-q74fl(!`1D=rhir#L0fD`&cUiXZwKW*ed7&m_4lC}z5em17+hVi`*||lRP$Dwh=wa{Tq$z@(A~ixhP#00?6j>? zcQmtT+iBQhf0Agrp&I!T^wqmavL3&8%EKE(GIoQXqoON+QY zJBy*dKD>3o49eQ2L(>!J9+3^IKl$iGlk;N~w?gaSx(eSf z65`HBr3!jexU$+{~B}1*}axGzvV+*JMry<6p6T@fvp>5~Tn&c`D<; zB6pT0Q@$HoY%eIs(@=3^wwRiVIfbh!uy`v7N5EoRvYK*FX1a3cHtx*LVtjZ6mrkES ze~&p`eIt^yHE@I=o>OHe{hDcvy7VkdyZSm~QnfcDQC54=#Mk@a=%CW@Fv0FF#p-J3 z+FZ}iVY{@1TzUi}-6y5DH^2Td#(K{nrv!U4-eO`;AsDOB^T} zaWK|3h@(9d@L(Zfr*Wo#CTz{qz89Hus2T^8f{XEyz-&%2xv+poGe=Q~NOf#k7ET>G z+VEMbr1Pd$R;_rn+tZEpp+Ss2ep>GnaAAYJxq;OUxR#B9wGHg__2Ah^V@L4e)m8Lv zZlQZ8kHKeLISBw`OUrN_2ajfsL_ViZQTOgHCLS+^@;;OAgQv;Il*t#7%jZ!^CjsBg z4+mG*(7U-E@^Lqey&>WWaeEQx-=^4__Vy-7xfGNsmylRnhO@QC=hv=}?2{Yty1G!y zjiX2$_%v{WfLB9#a0KYOg!1qNKrHOcT!h=zi)!}(+%C30wZa?qS!FiqMVAxxNl_SC zMM=Dz8At2o)Vq>3bhnvL6o{GKV+>?>HoYPb$w+BnDH~!2teyDHKZ=1Py|M1 z)Q_!DBGI3mOsdX9yl0U!0XmoPLq`W$woskpxTaC%c`E;tuk-P#GetZ$<6=(gn{9j? zMe)nEM~%OfPEtJz5A~WlZVwFsY)?%lLohkHPeVE&w0JBE}W#h!O!nA?5&N4oP-BqPChLsfm?3~eEF9|U zf>m*`w6WQi)3)t-I66BAP~h;wBAhV7wk(5*W^evf)b&Kwy_(hpUe0vgq>H7-axYfj zs^X2#w0UqayNL)1{;}T&k)p72^YRRr%CaQK+M;tJ31=@qmNUKRQZl!r_`>(XoL`vp zHVczO!fUp`+k(F299Ob@{L5!|aBur5PWF!DoslydHu|aCm+ZmgnQv z`Lo7ygb-XfaSErVkG7PtZ!e?;V`-t=0O@$}kpQjR`atQPnARH~e}ewC4fxcORyx(D zCg)e=n+T$$0FHu!dF?~z|Ba3t5piqid3X)vZ~hWhCyk9S|0eP?7wh~heoJPJu8Laq zJ5_(H^&0V~W-K=9x{9z(o+4DZqHjyld(n|McdurcT9mJ3oXxl!3xXKbWpTLKEC@4UPISfwxFpEEc4WJMJ;V^A<** z1fkk>%?R*UAH0vpD=Qco7{sX~M{#6)0=8|pz1iX1=QlCBw4z{eeh0ejq^>XO%xE-I z8k1NrP8)l}um=7c(N8Ccy~P(EN20$!*cHtJNv^C=Jbn6N#{|R$(d`+cSVj-VPyFkE?oZ{H_xAowUC(T@Zut- zXXla47lfUp@=~S)GSkv2tKL=7qS@1B-zHtmv~;KQqzx5BcjvM?Z7m|#js)@StdqacEFHdkzl0*ac> zN>voeqNPb>Y(5u7aWf97LJ`5iR=T%JjqW8dO8fBrA^=i1#+r9FQ|i_Yidrim#Deb^ zF*34^bh-%30!k&IQZYLhM>%1;u8Z#OEP8u;C1-2L38FNb?*XuFSzJq{Qpo2ENT<{2 zF+@aiVulHG-9(rMYp*-74+>cpK{A;@rBZEP*g#ubfFZc~3#Vq_Ihu43Y=Sh+mAR^t zlGm3dg=XjYd9hy=G|Nc^OHFYK{QWoB?DUp_iI0}xNY7;G zCOO?b0ae{>;<6&L7M}&jIm`@AA-Z9DuwmEZj4wVx4GC!_3GRu%W50fnPT9lJdvnmS6f4K@12@3= z;flqbk5DRul!~ycHQ2kmuzkSV-Uyy)iGY;1fl40mJWx9e>J!-c6_9Er?5k?^gIYGc zOb%|g4Ton-jhjZXW|I*o%76aENZsMBLR+?gX6%3TQorPC}3QdA}6pn-7g;}AC(VP z8zYh*&J}h)T=vjo$>>s>?$|A2V0pZ%9Ac778qHbLxxG^-+j~Cp6d?{MbrEc2j`pw_ z90ZOXBN!fjF2mXrS(XjJh3A>@`^!m=6F6@Tq#I zqJda+(34%*O&S75^75UI%Jg^%XcrjO~l1GLKA8`(HmOm2Bx?29Y9CH&>$CjfwNjbB1< zGK->H!*;ERl2?;tNX|hme6)HC{i$9Y>zM?Ti&;c(-h=!MOq#|h$`_0H@rNJ4?N8&Q z+c)u*Od7-e{Y~pJF2kZ2TAq(|M0QJ&Y|Fw>{{a5}yI)5t5kIgAyDtwG9M{9xlVuP} zar44CWBF7ffm9P+{*k#y7<;-53LxLpjhpAqZS6O)_r&Itg&@am|LO)VzyBf1nKZ6l zy4X^isd5FxqxIlSEU1zl+L}FK{SfhjI3{s5HjSBmAu>*BPlsYvO6b1#2~Piy{{drO#>e;oe_J96hY*S~M<~xs}?! zj?r~YuCIZ#F4J;Mui|a7tjOcd+Dg6wTF+i(vNenC${gB)k8(DRn-|XmKx~I?0H~x= zxOeI#Jln?j<0s+Mb85hse)R!9d;K-McIF(;pE!x0Y!=Bx0?9r2e4M*}1H;R!ATEUq zN0O=7dM(RFx@5sNe6l0?uZa&opEaf3FF{?$J54X#X&Zo~5H6Pqo<7|_PTsn@!vuI` zgPUpy;uHvZOn{7TBPc7rY`qUAyt1qEU9kNdOhn_NDQkg6>ajx8AQf7c_g?d!*DJfY zwY7w_oxmGICyWB6=#-n`RFkyA()#v8d>hp&@e7vcm=tx{f!95=*YwbKbV?ssVH9t^krU!mW_;aol-Q4-)L%W34M1y zKw@_t>9s{T#a&c}4rA-oTY;lCv9K|CNExMR^!lCY!iu?$d5oAT2*ZSs4^fvPfyZ&sOMV!BMSz$CTFUM(SYghyu`rBtVE+nM#O*p`j#> z9_>Op&C6Jp1=|qOB9TZKffn1<*xTESuCDe{6)`Fni?A#b+d=zfphP0k5v71_+i>0I zAEB%jqfFEa71=Ja>JAtBrUSKK9Xv-Xbj`|My&YoUP-;8GP)9d=%H`QPa~wvo9g%CQ zYD@W_x&xXUv#C}O5Y50eRQ1mupFu5|z_ZbjSPqj@3k&t#)EwS3cdKfxhAVf1l%=nn zJcXWI4(E;?$N0zy2K$<)zEUZhFW|`BqwwkQ9nRvD;p<3nB=bF!!c{*Pg>B63sAbG1 zfrGEi<#Y7Kjn#EM+?kujr88&nXkiJ5hK7;r>e^GAD*j}YO${KI8bmgwZ|EG%9f4!D z7wI9YKe-H>Eiz`dh=U7b?+W$VoDvN*yaiU9<8oGlnQ5TZ0l1^1I9~Qkov9SlJySr~ zntmVhIQd-XxL1|=O!y{n;${-54-36pTgZ3kP%@;&Y=sD=7+PC{?Xq;%L4O1ksd5E< z8=Ke~Xl}S}M!DTQrsw8y=<(CKb2E?i=!Neq*t7`%z3bcPTi-IQA>t-W04dVR2qPf+XcgV)sqFX_PT8AWM) z0+rFp@TnFKpM-BGU^3)!YNRPMW9;_j9{sD4QNDqb4(i-8q?F(g?lQt*jGQ%*e*gNN%ao(|7#t!eb8NQ@i&$@X+mE@x0 z$I8lnBDBr>Qpv=z8&l)*&HCF5MN8Z-o(2a2#{rHWB^YWi_+(2&Dcv(xa~vC$N{~6~ zMH9oHwc3jxOD8GV0KYc}azgCjUnDDTjYsQTNw05`+>Dp! zTePC3K$$z59l2$k%Oh#CV@u(>p~GR)!Djy;sBPia`Lk^YU}01!m9VzCiF~Pu53XOs z;n6XS4Gkf+U4-S*P}kqPv4w$+4HUCopmhb=+VD_h|H*0<<4aF)>ed~ok+r?L)F+>} z!|UQ(li!Z`md$V2Y(o&+Y))~?$ns)bYL3aD2emi$FCLjCDULK-Z%^OgEX$0DJg1Ip ze(N?I%faEE<5CR*QD#)Ngz}wn$88aFGbirgw=8#}{+D8_vV-?mKF5>d1^}Sy2X2pN z`)6=CH;SG_RzXJG&1E7tfs~yDi>R%0SN-k-jA+Mt@~LDJ7fzfAk8>^P;~AgOuv`1cq?rfuG3no~j!>i57~VeTVsfigYLg>wt`Q`{KW<^>qmct0()xI~OvYu$ zsAnolYaH?W4eH2pimuD&j@xS387@`IZ#n9XtMU(@-zu*)&3~%YZV>(4&98aGEMqF@Yf+QC%IdjnkT9F;ea9wOiO$)_EP?ofci@Pi_ z3>W)+;Ww+zj%Rn5v0W|TP}cy)GW}Sumhj2?EP9h!yf$o|ZOH^F2&tM?pdd zOjY(k2>Nc_uh)GcaunOP;)} z>4rWiGguw7uB_!GLfH11DRFB^uRTW3{ZCP@=Fq!+ABoZ?+^$~i9(@Jnk!h4hrcv!< zJ5t1@Ngk~@DtV+)f{*!k)bbYNZnPsagj7c%?tT_WFY`Ihy~Nge)CLZk`Gyicl0db{ z#2J2-?}uhEn)4i!NMHiemQb42m&-H7CL52)e?=asCK;9giSsx*$*Hao($z0AA64&1 zB=IgpHHK-H#8Jl_ENWelA|NCM%jyClRwR%P(p2eS(s6*PDT-PxgTB5Vq+8&3DkYN% zluFhMaVUNnD3NgB`+i5#W*sCV#DPz%*xOe|KwxW5+qx>w1fI=nk9b|JuPP%=0GZd7 z`L0+;R}1Q(nXULLw^Knh=cqF1)j6)nbvf9Mj#w64^AZ-8CZ|C_@o44%2fahAu& zkg8UY$(P{ON1QH{F|o9SIYoY(Ioy7p`M@Fa5ylpuDuxL;x|q0L@FyLmoK+RFP_E18 zqiC<|N#iZ4dy*?>$60lfmNT;mGIJj4aD9;bZF2JP4(jJwCH%CwGx17MJP{+oCJB1<^3fTpYr;?D;^Y z3{W3dxftAAxd`I>fM)@akuXN(O;;ZSN#v zQ+afvwoc_-@_5ZEXBkhMxFXZ-1<02>vIOOMj4>TuvhjFA%c6!(eX{bgE-9#_zD05V zsmG=fs@PVYpVZigI675Q6e()domkV`*SZ{3>g@$yd4-_E`&}Z5rE9KKD)op`ot3p- z1X-4aWHO0-J`YOqoT6lPjtT`pw_OK%6W_1wW8|;qUr)1cRSux9V$E@{s695JCYk%F z=OD;2CT=H6F1&5kAv+r9@_qy4=Y@U9k+wx+vMd3($poGq8i|b5+6v{1MHI_rtZi-L z{`?~VK~S1+f9Y*lmW94w{0d}i2Lv>9CkF^Jg%U1({27P^eEim%@RVRYjL-LOZR7OK zJ7D>*JUBwOLreNCZd{h1rs?U5Z$))&5BiQnjpQU*FCJZAzGwY>Jc^P{^f8%gwM!hA z9ZV*d%K^uZ0S_N`u1(LcVs`bHprDu>cpaGpcY@d{FJrs-1d{`=Mb_UcE@5T&9@0)X zjtss5K*Ywt%IU^p`X3cwRu;VlphXNClRE{{gM2T{^x zJivB+oVj%y_fMWcEh3s=!g1Qt!-=C&F;pjsDtFJ&G62|B7l#&~2EnsVo`BatkHqNs z{RePrE{0cDktvkIOjSarQ1|XGX70~oXl1Rw>4pcLU>R@OGqqh0 zqfb^~fx@*M)RK$We$O{W%nf;+;Qr)mB03b$b0=$#E>)*(wH_P$qFclfW76QVXEdre3IsMN0qBodC5F`;;m0Fo>z4ebAMr+wnf1EV%n5}bE7g` zK$VTwtA!IvzEYFh~NFdQc-I%4DwJ8aOs7Y)x>7UsKhK zaRIVgUzGO5I%XrbuW&F?TI9z%*VLs0HJYg?v2c#;hvoq}!nSO(brUJvJ$owl^A>6T z$TR?;cWWEjodU{hYuH)Y!EwI^*LIM+@Jd_lij>>UV`^?5;|ouOsI#{8R7}P!_2~jo z%8H}|VH2QkMjXGiqpWR>)b;%!Q?2IWfBW-4!+-L-KSW=5Jmtwh`TIYRjvWU`Cfny# zDoqW%(RSTtSlN7?%Zq``EgMqQI{cWOmCZN&oXK$;VBdqT8shD#l9!y{igUb1GuBsH zVLgZ{Ls9BvS7lrsM4=9xn?0}$Ax_POWJkx zVA`B4mNUh#Q6)ZA<`A_aqU0EF7RqvnxsE=wTBFwL930$kSwO135Bc(Cf)@5E?m6O? zWm!n2+TR4-X(Ge|rS2Chbu%FZl+xJm>eelam6bO8YU|5svrVGPea-rg(#xtS$)r&> z^KOwF$!$U7g0cidm3H+|5UN`a3vHs~R(*4_h>Ip! zewR_W*7IE~Yw3 zl=gf~&&^|YW+u{UyB(TXTB=8==5IKUPK9(N^JnZ^z1yGnhP=VbWkS1wo|hU@Eiw^rzcwqR?#YT6^a;p z@)V**malqZmb8GZ`W=rgJ~iGS`d_PRlOfW)ErGSJ2KDcT>m~oJG6?ksn#l>J8jGN5cKOS zb$A&WkDGI>=u)eC-XwKGIC9Y|fSwAuRE*eFUuhL=Jvi=~MP^Gk?9i!006 z*xtsojScK&6`(ljBa(%pV^*VgZ!s^IyY(snB<`z!gxrd&uox0H;=-J%C zsoQtqIu5q_`#O3LQ8Ya}kAd~gFwGQGm@;<)z=jWsnR^dmfnxsXG*(B3wRYI^KYQaA z66Gqq`YveZFd**Gk(W1lS!CyAz#(4e|IA7rRZP%HY?B=WfL$pfv9pD)r8)H8yN2xY zG92H>v$Nkq{?hBnPoIUKObe}W(ghb9aoz-~_42$9)!LN%Rqw1Bi9(mDwj7~QT+Bpx zEUE{gU58XEAfD=3es64Z0ImO@hP4=QW-yc+Jy#uh2Ab=)L!DMu9u!cWP6LyZz^PO9XGJMe zsU)h^8d9kg?0t?#@w|xb4E8)9jzimaMz?JnmSv$@eK}J?QwprF12=9^l*{6k`Zr7c zhP&TeRolmX%FWs}fn5`D<|JQJ*B{dwWK!jc97N@eVtJMGnaaq0%i!7sge?sMnj?xa zCqNlmdV(au<5UBHm$0!j(E1K!k>-y~V{3O81Gn!WwY!Ou@8ei8hjZ6&!gK6~vTh^l z-q}T}Qo-nx6^uV#f*xU;C^8hJC!wxAYI;yn@hsE9;K!}dUO@5lpj0x6|LXVuqdm1T zH3irHsKJ4?C*8Lw}(o+?KIjA!uwi&w?+jDJuN?K)5DEGqr@H4@g7ajn=2 z=bk#wRb?0%J&RmR&Quc^pxLMZAW>J+1Tk_?-ns|d^DujSrZpZyDSEbd@Xjyamo~|A zOvU>ru#hQ~@ztOG4Sw?8H(GWOCzOIxB1EHR`UlRLncU6O(6Y09{W0E#uo5s%ACwOa zZOmbt){jRYui((*Cx$hMt91#0+2b>Ub2oox@BI81NR+EVSqg+3WT+2XD8PO+2U_2J zoVSX21EnWX3%i!Kg@5R9CCGqy7ekw*uj}I;W%GQe0BswTgsHvWtwIO!ALO zZiyZrG4>;!D5zSforQjatox>v~PgQi=oSur7bmB3UE_ zP%kh>8?vXF^r*pkkyq=OHwx2=$6`C85j*Nw?n~BK13cJ`>Q=@vFz1fqIfek)IScaU zWDp8MDDIs-g(ru{n?3BNv;8(s~B2d z3!k1Sr!Xll$WkK9$oy$Dd56hEqG8w;o)Xu$1{<1HM{W@t^0!LB<7%p;N(asHvRbx1 zGChmdNR%fU*Y6ZwCNcWj52BRf#{K&^HZ_H=HaD8KLq~_+K{^rWi`boK57Mt=5%iBX3{Ck--(J{omB4h=^paXvW2&b&YW>kw1#x7#nTE zPUEeSAYg$QRU1Mb@toS4h~g>4wiyrb!($O6`LHm$vVy1MhdSnjJUus$+-@E$(7V`Xf#E&ZOEM46fE`GPAJJWyDa;^@6Oh#41HO+c2jMLRD089U0a`ZqQ;Cm%Leu6N;EQd#_MeU?M2C%%7q6_qn%iCSgV-O3aV zl083Ji_jPWTeS-8!Y+tgLuTm#CgO98avr@Gl<;<0(9ov#g^F z{A&DqZC_aRA8MZX78_Z1~k$~q&_f}-kwxE!P6c1YJ%94_8Z zycy7*46}DWdXTWTNP~lXqx8@a!Bj+?NXrU%wD0@j?{>&>5~$T`@Vw?2@MR)G0^76a zd3)YK{<2b(E-$=J>>!Icjk3*0X}H>dp6c2XbzaxMn${$)<%X=%48b)6n5|IBA3sjXKNeNbMxWdu%N5@201zN zmAD4UE2fDrt2$h{oVw`6&S4&FOyx%g#uG;zsc?3Y86<9Qmp=-I(|( z1B-yz71wuhbLE$Kd+Ik}J2uXYTn2;3axEg9mw$7ymN{;70Lypes>~{Ag(xk)GxjPd zfJ0qFIMy=(c|VrS{!D+x&&Y=rDj{_hC8@JEz^S-+{i9Fu<6nEPt>|GUvON#Ed>%{{ zNJFJw=c%h$gj1_20yB${1^@&XKf8vjufN(b3bjb*uH8U3Ukr`jsE<9nQ^18Q*KzfY zO8|g;cdmoV0hziAMOdz{rLGFzE5bMH!49F$cxi7u^Huy zMSOPq7Iq)p$9IxRe6M=|J_r)k8s7Nu6MXpgWo-BL!f!zV*HtXy)SbH+dbU=V3%SEK zdpf@I6yyy=YW5P@4U9tOkfPkhh$z?f*{H5#`#~n9znM%W{&uSL_C{vIiT)%-Tx@Pf zG_XWP(H8q)y~}L`SE=;>z}Yz{LBsJeX_D5t01a!f)_Fu{KCfhnmkO=OL=3;8?q24W z!QFZ=Z~7u|!DHLX9L@tU^I#T^=i=_^_}Ku4*4A<9(<}82vph*3cd8EVl`HlrteS_f z{rKm2|7-7{oQdxUap}`57r#g3<0o>IjlTi zGt4wOw}6THCEmO1g50}{gj)l7_z);pU_D)ey|o3e;DD^}!0}h$P98y`eizlFCsBO& zJD`~?2q@gaF}OpcLBDo=p0SO7mR(od*uq>ht%RIsi|I_u5L2j2C&YLl{D$4*&`5t#nJf z?^(VN@jh7z&M`$EOW=j&)#oAW?Mz=Df0iO{<@KU4qBvrn`;TKE%geE1>7#zuQ} z+vWd^e7^+MwFW?tp~{!TkP%RL-Y$sU4VhC!>sWQ3Y^v9Iz2Pe^mClKL+#mF@jwnadmJP@Zf8GECvSq-3jDh9R$R5kG36i3uR&QkQUA=c#SJ&3Hy?V=icgf7~ zkGPR%iO9V7zW1v8RjW^<`sK}xeL3fRCn8Sx<3#SQKClxo+e)Y=?40 zw!YM(Oys+kS9SH8hN|##ef%n{G@DI0UWVA)?aX42v37!rqQI$hXL0=S5j1Po2Q7f- zUV8;c4j%YaHf<*+!QO}yFAHGr+;QxkJ6;=K_F;8vQ8VW zr!^M$e{vYcb2s339C;noYr#}HV7d_%)5TmKeyvD)(oGa4mtvf!e=SB&`@ou!b zHRg~jYy3m&z%k71?I-eg{3hJE1ovdJ5t2dQ^?|iWdmC;Rj4YC@k7Ses1(5bu(7JjK zNp7&`wV%KOXkR*uPrmYZaP|IgVe{xQ43`g6y5rK*^Q=^j!?m6xQB{Zy^>>OV)4U$2 zCuUu=;+y7t)n%xf4U&JlJu@0L*zq@S8FQnN_%=tQQrE1`)8|L=tL1pun=#!)YM*kG z9L)vkz%az%lX_9lxEPkMidX$@Qn>Bu5Yy{M*Nfs~b9oss#@*b!cMAWDtyUA(T8u^+ z+U@Ii`@v^HX_}xY?6z*MHpZacZeuVQz}kf!F5&g3q5xJ_++R(uO$>nQjrQBc+|$tX zJyVUnB}an@$HQogpS0?Q&oS8*!|WR2X(urpV{7i}4@Ji@IdR-%?2eRUagFDZ7+l@A z7q36^;I?mo$@3f+uR3GR+owK2ukUOm58ZV)?!M(#7wFn5lQX189{Kn@Zug%a-@5(Zh6lL>x(R^s{HToDldxX~P8o9` z5HG{{a`&ku_0lnV@YUC_bn)8wS|;);R*dVH!)+yf@E5NtV{5orMrPb3vY_sIsNEaj zsh>ZM6ghtKz3*)K`szAr4Tt#BFJHv`wT<#32QKCSGlu%kc+miP%aEfAqJGk}%za$a z_Nvg2W+K9cVmmfQtJN4&&a~Dn=|950SAK^6!JBdVhrfqQkAGjJ zS4VZCAf~vG0uf&O5lbho9L1HP>B~uPh=*_!BR7R}=nC;xKO^#1@-fewJp7Cq8~vda z&*M_o2K+CF`BnAT26LBN4ikI<$YAC}YIP6bC!)1Vr&Y$#19$y+<{+5^a4Mx#Q+F?Y z+F;t4761!ddCJsn()Oa~o_h>VocMIgwjKIBZLYo^WQ;+#+rj2$AM^8byJj(eIy06J zTP?}xvcGB4p>LCAMhJR2-`9Lr>oXcqOYKj`(`G~o@c_L@&BO6DXlo!($8S&MU^_*Q zteFA{@ZP<5;^X7>3vAQS=3r2^(F?D?hO?i1f`=Y^9JhBDU|xA+tkVIh&GFTzpTRRv zeHFd=IgFakiJP~Z!x0{S=@l$pxyCj>a?d+n=WMW+lb(4b4v^O*YO2zWsO7`(K0U8r z@p#vVw0xhA;wbO0CspC)Pb*DZ>RD1NlnW}P1IBxra`PT>d@PPY0p9oIW5^PC#>qxSgM$MaeNKd*65yCbQ*+Z9m7kNzv!m7;mRZP#_uQ?&|skc;kWlarwahcx|o4SD$_cNtUDA z>%$fa!;XHlHhGQqx->V}C9DrLX&ld`ii?xOT>+WL~-;8@@BiVGi2>K{^t9AAvkp96?GwO6y&+Ey6nZI_g?Z;>T4y zo6GW;;k+tUjzuNrMa4V$TlQdBgF5}Asyy-c(~VTE(|jK2`0*z8?aQ&aI7G9#olQBr zr(K%O*7$nk&yR-JY`R0#gX?#1azI%YE+AW*!`dON9gY8P!rJkz7Ipw@-J&w_%K}9a zFSE5H6vaAVGgvFGv>MxLH2-q{PXbTc7R|;!r0IOr%Qi1h%=Q{`rI=*o$6NVtiW@(u z%x$<*%hQ-Oe6KMsx15KYwi{zji?B2KQ+@VpU%|@q-kA;v*O3J<7>zLey(jR^hrfiw zcb!0Y-{K4@5N|Kat$AE4m;FSwCfz7wi^Y5qnslNB+72sQQ@3&`d#Ic-twG}BP*;-n zaGu_zmYIfgNga|S`)PSG&!q}gg&{u+8fGK>^FRH6@bCWSZ)0E0Ro;m)_}w46UD?bm!H-kj_8 zus%Nzy9J)x$TA#0e*q7@{A#%doGV`EC@EW?Hg3nz9hHk*Uq}y#5|?=QZwc;s<1LuN z;`~iVCYF0rySDoSq(zR~-unP2PMv1_THgBQ>+BuQQ9l>(_HJowrus>#>Fb2#O zCBMiwaXiiS7P)FN8Fy=2P&i`3@bxqcM&9a3|E%?q>B+!a>HWzVV16EW@=1ej?$!Lv zsVH`)Cpw+Z*!y=IjmGEW=4wX<#uyZZMUvFdi{TJ>`su3nbRM#cVt^zGH>6La?@gw7 z8ue+%Y{1inud`)p{2aG9YFnwap;CNlOO~slnnTKPp+-qaRH9Dutj+H)k-n#8+|70e z&wcgDnzovrHU|Uz?1ksC-s|B<-~H7}jO6Q;m0NykooV^vRXlm|xhR+CdKA~0ax}(! z9_4<%(8G2ezNQ|CADH9eWSQzH9BJF5?b&`qJs?I>GpeW0WYhMwwKe<~zyCktKmEu5 z1l>*tfAB~D2fqI3m+Tmt|NIh%;Y+1CDfMNCnY;{jKQ(26kI(nxB3>q zw|@FF{QTSB!p6dM-l*${n1EKZE$({joteFq)seiGo~|m+k&ZVD6|nIB-2Cb2s&aE< zCM|RW{_4bBwD|R+r~cw;bb5WU5nXNs@?MQSSn!^XwJ`N1C1AnDU+fBna6?jjk2noa+kMgV-Ig4T41uxyCHHdwC-aLf)0RExd6+ZodovEoZ$6%j zQ;c~_T{~9SI)tpQjG@sj)(cezBdM5hbum1?QDM5~xnZmfTx@CbE zpL_yWmzS#>dj`t$9RK`J{{+MFJpArgzKU-@F$U!yorXWE=x<-i0X+Wn^JpN)OJ9Bz z=WaS$oBor3^(^MsdZh^<=4rbqH$`%j0oTE+%o$p1^DX71Zk^7wwGpoY_;xkgSgh#) z@{MBvuBHPAoX3unCqM1l)ZyH%r$u;Je$%=p5!XDmr?J>CiA+dG;~TlP{tA(rF0&@9 zLUH|B&p~?j+gCW}bDjwKO-0EV*C(SK-BAw-3Uqp#c;cDoM5+MI?{NX4pr1@jTM?6(p-GNG@LlMh5n3j%M!z6#Ea3ahyT1X9@ZKL&%Qb z;u34mq1bmA{k#Xv&y(4>(?v1A2-|47wrjLebmq!B6_AIUWoZq(%;G3Zo1mpG@5h1O z<|Q$P-tOhcE62^%m>A;sbQB_!t!VZ!eJPIJbSuT*>CvI}ju3%V*H}v=&Xf4O(9fD{ z@l@oD*OHg(Q4$4e2^oK`u2a|!6fR7w2;RtX8rmnr5^$^^qu3W-9?y&2v*iB#o#&d9 zy^iYeyd;z2)Q6o`BJ2)&^ic!vM zYsEi)7*W~}WE?a0{~FVQ^o>$-y}(-q5PXy2o#v?ZCtaFq987Vlb=FDmD3^Mw;~&PJ14k@teez#%3MsH_o6O^5RXWDedMl+av9z48#F;(L1%O9>@iJ26 zc;mtQaq8AvFcVoIu?1iOYfWiq^M9!X25FY#n}7D_`15al6YC4J--LYh+&Mh>@@s7K zvUfb@9WBt>c2f4IcY~I|Z>*J$8Hi#>g#43Rb9R)WffPCJeDfXL{pMTcsFHGz-krSv zzS?$u^re@ueCdj4w+sz-^OyYRYdSt^4Zw{#ZR1eggxq>tiGj6n|NL09ZY>^2V6BC< z?nblbnGcX$TS0*Y>FQOqK7Jo&G(h*=*UFr_r`|%kehpdo7>4_gBiox|m^5*I;Wn&3 z_$ydgdkdRiz6UFF-^S+ATQS&wQ`ujHuH;w`pJFwdjkJ!!(~`KFhp|Ci_qzz<#M^$l za?%}cVcjLyD$3_r+wj~Ha4w+h6Wa2O3eVH@JcBGaq%qiX^!eQ^#Q&tLMOicMbPwVy zw*^&M4p4^Ry+c|eeGe@jp_M^utuj5$J7wNgRA-H-*O$Wj?JQl7G-n}WTH_mf9mFxl z9UA-gw{LuWY7Eft_mO4Q-k<-vQ<^4dx7*m<+{D~mcNg0wwy)h+>2|R^H2=dsPR z3D#N^c@E?j-A)I;{j1-{|MsVUQai?cc@1o-6T6ij(&u9wo9of~RuYNBW4^~jtgW%T z)>C=!#?b|pOV(~OJ`dkbHz&7-t79cF>~CFu^|NwEH*Jry4FB~X{7?8tzx{7vf6cuQ zON)#6PyW$AMrVBO&fotxe*?|N^*efW`@wHa-90;FqL51sp}Hm+TL{ugiS>VJ3k8Ld zFqQzAQxo~dMtROzD$SgEPIn$UWWl_=mZjv|fqr`f8F|~T-XOUZ+JEUX9{uG@C7b1p z#Cza6@xf^%d4ZD;Z2geHH~;L<(HLe(M!91B#KzsCJBP&7J0WO@orKmN5iL>>_dRxtc@EA+`>LT1uYr5Tma|hAS2SD zw()tO3{U?;KoMh{X@3JtC!fKwKlyzmd4}`f_)T29|0xXj9zxM}9Lj@{S*5Y%3=fFJ@7HswqzjXh+NuQQgrEy1c zRw@}M--2}tr;fwbI$zU5JzMDUTJ>AD7}Rf_k8H0v&GLP#Qg0`u zn-iy|Mx%jdvx$Cx^V7@p2BJ=!|*tc>dxIrxT1(iaQS3fkNe z>P@^Qxd{W}A4J$X3N@JR(bhpSM{%Ty)|zp=%yFO(Rh3^X z|L~pEHT^q|q`l5c_%n>hFE-U$VTh08+7X52Pq76H;)7fZm1Uug+GJLqY7D`os~qmi9hgyys)3VHiHobEIjC zG!0h+vn)fa)q*hwi;D|L(-c{jAxVLmWx9`2X@FmXec=6=xSnKuh`27z6#^BiD!$^}^SDvN5=&4{gCFThA ziXv!v!n;y$HmcQ=u>_F|&EYnAlC)0arrz2Pj-5s)*b4uj2D55>HBCvv)WbY)RE)e^ zDa68Yy;J@sOk1aCbNnE6J^5W~U;dld(D>T1&sQT9`e&mfB|dtzU+60C?@PwDK0eRA zmuc^`Cu|45Rn*^kJUi`KUBwg6KJUsp@|#$s-$qmN8(;|FD^EXzUp(J>2&0`+_U;zBMB|wn1>K zEZx3EHwFSUx)N|LS)yaQKa27hqVdk_Cq{!1Y*6g=n z(-hVuu!;A=E;R`Lx2kuhp}Ib49IKh{ zVbZ+|m}nf*fkMlPuG2I^{IJ2U-M2dF&6-_zSvT zlp`;kJtoB6x!X8w`$&zyr7hG8H5oO_W4v3-pjf!@xQa$}p5qnjoy7bcEy|rc?zg<3 zqX@!;ZfLm1M%eznyY9e8{6O0_`M}Bd-^UAo@PEVpI)5bMr$ zW=x+O3+jPUsbSxi($ZW8q#$dXh4U*F%N{>SaVM{aL6^Mo&jvhpLZP zhq-rj({>|G@%Mk@M_5{{-$a@igT;CBs65x{itk5`0C{fk+H13m=@^)8B=H?tlbbF~ zb2?x>IUiC%B_OxuFxB6jf<>?pYr6Oho97`0+ktSE6()gCUq@RJ!vK% z-yqA|Q37Wkm$$k5-Z=d(mjCE~!LhTauy*$yIQQMZi~jy&$h!+;5Uy!9-V_6rS{c#d zs}vy(#6zGuTN(Z4kFdPF)Ep>t-i4q|>*^Xa7{tP%%ppO}dY;A|mBU}9=DCb7SJ>N9 zXvb&DG^PZ}=lEQfzICJ;SP!l>u#Sb-`D?0^W;>4&jV~-isu*B;~<1un0 zH(-PsjRw**-S$<^{&39at$os@jm(Y!t96g9R5Yfi#dSAMTuR1xbO@YvxH!O$0cI}E zQJIEZY|y?%xfDo2w|Q{SWBi@>fx{uA_INgIw|4Bh=)ziT4hHD7+f#w&VtjLo-+-Bn zav>o+`I_fQ%NtMhhC#h4QlI_i9(v+8n-JcJ17g{G9COI9;o<};!s;-bbozw3wko@( zMR?V9yAf!99=PKU;Jx=g>yi*vVdmIxN776YYG5=@IjYsV8lf$oCdJoz%J8H&#(abE z@@pekocOh`G0$dxP8Q>ZpkmA)%oyqUtJvG0I$vj+>4q$u|73wlY*MBSe;-NJ&UR{Yge5i5)p*@Dr&2`akw~-_%y50DaO`4`iDlkp6>Ez@h zTbD`Gq_WLhtrTfG+nB7vn_;*ZRb$oqc=0qQl_f5-C=JQEZOM<~8bC}cb4>`fakxdD zwysG(R-xMziE9lCTs^Ri%ZCnNv)jeRLkB0e)+GAy>=|6Rd>M^2#fc+FG1uwf&YN%9 zQd+lu@F5o0*2`ApE$O{z6F(07M(ZZpI>0ymk)B)aojWF7iQ;;b)O4k$ybC8x8? zk9*$cdCJjEvy5*PjFsKT;a{cYiF9x6=*w-ZbO_jCVIMz%USqxO-49_baO$?nyzHj4 zXL0+x@5AI4>Cml0Iq%StbMrj?VW#G2goj^x1zDp31BO_++La2o$tJh!{^Q; z9p+-am9Hz2BuGKn-?xwfp^oY?Bl#icWghLj)p9-}h>M1vuFHPU3#7TX5zu;=|IVeB z6?KtP&;L!XTt<5NLYa3`WN3Ww4p0ak~16Zq%i8y{@i}3J!Vf)DQH5e2a*j&c210dkv7O+5?bb|K=290DMiHQ&D*yso` zwX{W6g_qooxTZV|9Y<>ZxL#;S<(S>CROBM<5H-q`Rf;FEIbWB4{gDT-y0iy_P8*}v z&NwB0N{`a(7$#+p8R{if#j(3*fh(HSAf@@?YKs%YHK1XL#pltlis&;G*k=A zRwJ3Ev9pxkmgUb67tuc;HrnDcw3=qY+?uwI;p?$BB42%s9o@8TjKR?Z+cy|Bo9-%! z-AWvkYhX>k2|$M(%VDx#pdg>j+SFn}izbvZsg2~dCM+j{{C&A3T#uJ6uGYqes$8P< zlP!VVs_YktLjd1EhR*sXQslVzxC<9%Samph_8g9#K7+D7yvK6Xpu*5{4%BiV-i?9jK-aY?>o|4 zRVW4h-oT=;L(m-n%n)1*QNSBsY!F||6aHRG$~ceKvWLG94WORO76`eWeg|mo7s5dQ zK37^mp~6a2zXr@c{K~#1ynojnq7CW}uT7$NPk)5B|Hae5yO*&1yWhYQ4?cwNKlSxW zuXUREA`e}xNbPJzD|v9u{e_cxAZIP0N&^c zqjkFR{&la`u2Z}3Y(?#YMtxw(yvgo)%a*Klq~y;OSbqTd{6lBI!` zXr-5l*bLN0x&j7vqX)a$2Vjs4M@X++LThCO7C^tXAL+GKv^FmS?FLLXLgUhTB>f(W zg(V=*0c&B`64*|T?7%_TR>!5iu!zy2W5|~FyS7RUio-|IXIxH}gv-Q&m6>WGd9bb< zEkJ8b%B7LqIHX5HoQvui6~hmDvr*`2QsRl&?~osdcx4jB^a)vVnagw}^_EF`371?U z5{sd#7|xXXX@1gR$ zKHjl+GF@YUJ$rxyTl0A_Gc}t{^m@G=$9!3qRW6)bYcYyA-RSrG=#AZnudG}X-$tWw zvvpPa!{HFd7>q_EY;4%6;$&G4V<0w8r)i1<2lkIWU59a!Bt@eU+7Oz}R&-%JNer4( zdQ;jeee@A99Dep1@U)n^DqOX!vg$X5)ksEK?S*S*sF*t#sJLt?X~TP-iQg7$U`H5$MZ zPZ+%PlEqg1O4MP}$+Z2J}NLOg~M>z4pM>z1wrLqlTGugtRv)RY| z`UYF~G|c8k|76`g=C)||MrdIG1B>IM)7W?EN-%zW-4@n2(BABi?RsgMhj(<9L;7%} z`tly++$-MVgde$QLqfDbIv!bm8#?ET{NHTby@k?4C~Fy6)QK78*exNt*Z9=Sz6lSSe4TD z+`3Nh;PEB@_Bn@~p?;(pkR>qI!@U2d)h|9RT>V+lBaaw##`|1XSDkIX+pUlDX;G3G zSZhCb&ajLz=yW=`cJ10W503-JBq)llH&B*k7>zRY`vYXz2%DRmND{{}+`a+1z+4m- z>+1tV%oDISgSCAW#b8{nHTKot=Ah~T17pIqNMl-PHueLs>br%(BB1mb;}S!Ha1Rva z;c;7Cdr6L?^&f6o)Ut{5crI!4-X)B7z+UrbFFcRl_!hdO2M*#}k3WHKr-OYmL|bCq*S?0N;o3?igT@P?w zm*zD2Nkxs~#hyrkrEgMkqIU$sH9+R7um4M|lK^|DI?H%e>Z;oN|JyQEs*OAi&EdPx z*@0_+b+7?2zq*0W=5$wO-tyroEUjF_{MtGeudR(iuitn~ESWBocGT>TaP;(9bT<2C ziQjneeq>v;%Hhg)(u z`Sg}9uav1vXyfwbUdiKL9Sy6a+pL|iI?=%a>PKxX2q9nW+JvMOE>b*)-o!Wq=VCsD zn=(%TXk9*srIXKK&zsL8-Q2*+17F4F<9`Fa!^c?vOa|BTeLeBg=r|_$9#>{4PN>-E zykfJq4phd?Y9xRX5l(J?=7LHC{&2L#lrgQ?)f+H;OyW2Oo{Q*hJh8YT8CEyqz4R@n zAm|>`s-ztE`e;S0M`QW;G{Sns>K4{(R{FdEXiod~HL!0VaO6mig9o>+_M~Zwq9}I# zN!(e;7=w1ZJqDHCN{?NiXUcQn(xs}e-W!wz-0p-jnZoEp4jXvW1`0bwQS^{y$#_FH z4S<;VTEv}ii3r6#mBemIR?Y@Hyh<}oD;@io4;(7#|^hA z%RFhhHwQPld#&u^k%Rc;$RYH*9bDNTdRN^Fy>sdmUVZm%v<}bX?mKTo_wZpf(iF!I zO?SA^w`q8rVk2++tovG9BPN*`%s_a8p!p(~UQ(fnRjysrYTz-q{Po6q5pf!_)|OtS-636zEX$E)8H%Dno`(ykc^>!f zRTLJZ(Fna>4}-xFD=RAi%y{E;GG6ek&Yu(C=)JMAq4E#Ir)e5JY}sr!F+V>S;NT=l z&}>$FG-@;&(M{Ml620?|#pdQ`U5a|DlPxhBMc*VBig5`UhVy8SPdQhUyjt^hZ!vdi z7wVl{HP9%IBRh_PQxv##_yF=o3ImHX$B%9KX3|lX;ndl)0DxO=x(Urj18W-_IC9{? z)VMZANm1a)`SY;WARXmngs(R{@)q-$OLBc_FDT}d93<~o;q3h}j1 z$N!(B07l}(Odq;dgV;Ie?{o1qhqv#Jzw|YZ#dIRWLFEwV2H)+$& zRFZ$uS}C=$*KEz$S(j_M1QzYhAv&7_R%(=a`10ptFWx#I{!IK!YUVN22UaWILtfGl zxf;rKU7waQ#p=V}n&Bo~UOquaqkZ;2$HN_CUvs~#1c zySr5A05nI`Je0)C@%H4Lp5g&999~CpyUA~U2wHOZLj<@o>z-TnWXf#5<-^c3eDv~6{Xf%o* zNVgWz8>PL?BFi%5d5(>ZjWW+H%aEq2aQ4>kTYT_A0Tc0BZA=27i8S2{z>I%;N-IXU zQR~G%trVfNR9k-IbFE4y#Uz}TFS1M$x#@V^8W^Ub@wJYlWt9vQYJ>h=xUL*?X~pC5 z6%)PYOd48_VW*9^?z;z<4jq8q0dMr9EW@*}yo?Xde2n|=xD!hY3pliIAC~tl&7796 zq38cpL+@N8>`zBhf_i<}rzvkvC7ns*Y#Y@iv^9lGFl}9_CN1g1?>j>=TTxZ|98=9k z^>WW(7jN2LSO9Lj4fx=L>zhxNim{!p<^b8};ZoIpcqqItNeHQ9DrHEr#9A%$${9@; z0vlG8RjQ^{IZ=Ilex3o)bRK(fhGe7MqqqZ4PNnr5tG#Lc!1+sPZw|`zjmp!%Ie6g{ z%&+$X2Et9BzFY9Ij(OJEK-qAbJJ8=)zZg~K9=^zU! zsSaFkjY8!l4yXa$YP=G$9^krzle){yj+-aI7$03ZNKL_t*6VTuez+JPD6NCxXjHm(6*RF?yPqwN@B&0?GALaE1FCWfi0T(KGKM^wD6 zeJuaWFNn~1)SN@sp=zN(+XV{so=W0318Q<3UGhWTUM?<|{=9#sMTa9@flqm>i@agpTh$x3UIs}QFS^apcim->roi%Y z7^cy19)LDC`{;DyyL77#CtFLNtNZ;vhQlFxy&m#BFaK$ZdAjy_j7B5mx${(g<;qp~ z_H4D9(c7&2A!AMR^YfKA-gG+c&+WC&J3-b0SFRv>)6}O;p(c;{W)PB+bSJoM75K!NevNUCZrH8cNQh@Pqr7st5O8}WFLgg(_cwndP?Cmtqz z5B57wTjlTJe3+~!$1PLS#RUsdt)s=$|AHJ0RwBlf-xRy82 zZN=3rAEI&Tf=hkFpr37`Jz7Px7$6&DDAs$J>tBIcSwVh~ALtqPxgj*<6o~}+!NbTq z2Z6;7@-)ZLS`5=JMx8}qzKJ4fV0hptJZH+5_LE0!a1N|7A+M*D5dhs#SZ&*+cv3R^ z@baEV`Ay0qJ!bT1qOf5Mjp^jKt#Vh5)k6ybFD;KF(XEuKJPuF4&Mp9i8320x z)c88&*IJ582~OXtd^~Hc9^46vddFZPF6X=A)|VD=;m9G3S}mMCc2ixGPDR(&*YWO0 zrvLzR-7X%!`ySkV%dJ?Lo0~bU`SlIleCngJMZ6@@dZ(28TEC(2-a9wx+@XUoiL+&X zF@NT=*R?D|S%w(JByku%v?QpGUzC}~!R_o6f;kCQj4?=(1f$WYeD*XL0B6qF3h(JT01IQfWAM&+xoO5n zwMk$is&$eyfmEN89h=?Ml~!>+SOwIze39>~jEN@rYsEXww?iH-`FJSD__do5T1Dt> ztP1++I62c6?0D05h6EO8j~&ISJ8s4L;zFd2W~0JdoP7U1yz=&2ICkg|<~m&*J9G$# z_s{0hjJFhT8NcC=q-UIy`Y(PFhno{Zui90>SORpHZs^lfO3)DKQjhbpRY}zXzaQxlEF__xs4Ew3Th z{oKMcuZ4y4#_xHgN6!v%aU`w%I>%-PE%c5BtK$KK4HyfU(GW>tfdVku2#wWCXkPdj zXf|Pr9E~#{qWQtwFvehG?iiBw0-ehrz;p)44;^*6HkugSbPGmb{yLDj!zkI&6UY|# zvc*&4>i(Vdj7aTY#S3`|h!#xXm(1m6RlXD}@tkfWLWv=fS1ySutB)B;3*w*v>r1EFcI@D_@f zPxBZ*a|s{&zW04vu#MVAl$8EejT~L(*w(W|jb&f97;!6~9G$+d-c3TpgHTx`&tar~ zK<%dQR-@dtCg*EYurNt!^YiH>>>bTSu8&Gf0oA2S&xp1TiSHdnX zE=CtW(=`3Ud)O|Z(Fl0vnXMi8o1V8%M={%8EU)S?)8*pBayi1&mbOI6zuoUbg!8Kc zoR_EYUbJ1FanD}vyALZ}!Z^HZQ-jTJ7dB1s!jq39--f&3!ElJ))iq#!fZk#Q%X^%c z(w(|tEh!4juWzvBaK6b=w=C(~emPuI*yFn8<1&Z0bSQbbZ0706-&BU!yJ|j7?={w# zeXi8Wf=Tj1znxu{)!UD!wE=%#sE#-7TprW%FlzmHxuhPbF|tI)D8G=dD^sCgF}(;P zl+MYgK26I}T7;aesDVTRZkx0`!f48Rn{fGL}2&Dr`$4@U{aj|?o5YgYhvqe(K@M6$64lVwO&ua@uA)fFJiV4Hi8 z6$WTwB)-5i{x!ob0oiRLJ zg(`LI*sKWOZH?z>{f5dAvj)U!tF0Lb;z_Jtzgdz-tM9{Vj>^A;JA4?kXO4$`zS@19?rmKo;+{ShaUh+qQBM;0#(D>3nl9A>+-5{+^TXuT9=By%^Ag4# z4(ME{K6>M}&XLEzKDhdNrMqt*aMy&hjg3Z%;jkDx)Y`RM?P{s&<}72(_^`G<@NJRR zEVLJeT+1B{2H4!}V>le4*^IYQZ0*-txn7&+1={U)xxO1;%Qcm@26u~=%YR{EzI@+o zHY;#Zbz0L>uLrEIT3qjot!Eki(`jf`JhD1H{Wr`n&a+8IXyoXg{Ti~=h~is=A;NI& z%L;8vItL5yJu&S2+R`FU-F6Gk96vTiyG^E*H$TSffAtdH*t3aFtBrr>Z~hw6Z48k4 zjSU?C=(KRsqqPFMm4+k@-`OX7NZw!)wxn!L-h1IYx#v%h4y`|h5>{eyuy66_IB^-l z$LUt&#$-G^ExM}?x2q*dvk4qI;;ww&9aP^XQvIwBTcx^iP)(qdD|}LwGAtIIl_QYr z-`1%}wxXQXwd4v|sP<`9ttgjN{bH8iBJIGh_s#7#MEgbRL@>*kuOBJ_fogs(CKsEw zJ;T8GjVl?Y5i)z<#{RGNJYA^#!b=xqi9_M!f642bsqN)Ra%KsycKh=44d_z24ttF+ zJ%{9(bdH7)aeh;JDB}F-b)RFRa*dgEd|u=YG6d;TL`%5IfwdOZp_ngoFA6kQKEaXy z?|(&pc@@dhA}&7pBW&D!U(h043`|l)s;N$?;h-@NsCgPv@t|_WfhmtC%Mq42Ht%gD zwfX}b{u_-zKXM9IPhEcftYInt%S)`m1LuITHj(LR;xkMFVTvySbjaTTue?B|<+s@I zRH)54h_3?Bx(r&e;J@Q@UK&2NaKef1kN$DVU;A;{zvIul{YdO#%mw^m|PjoSe!q41jYdG-hCH(^Ru5u z=F}ey@bQK7uok#<^(u}ZK7udbcORA(7H3XtacvEIS5}mc66!ahPN;iIFWAJ)4qP{? zdk2I%Q>Z!6?>JS*tJa!gX-q?*9>CMk-?)68MGj00rgt|ro4|00>*{S=;u20(Sh9Md zTYr-}4%e3q!V%+jC8;5C{OrSNjg7Feu8C1&h!8d}pVSQFDaki_rgNl8Ub)`<>Td3ybF2Q%E+}fi;8l$|W=g zXJF?RFudhXm^4NIt_M-v{Rl?4-38n2VtDj8)|U?i{Ykta0wJ9!s zG|w@=zJag(G;OCfPbdNW8M2)H;e0;+KVnX&@ z{w@Dbn3!vca=lt=y@tgOOB?184{9cK1KP9YNZ&Er5bUN@Cq zwtWi}QLUV`aefOh9p3buEoH53%2I0GRJK&8YZrwDHrC;FWz*}yWCd)NBFilDe1O#E z$k4$2>IDEmdhH5Ko|Wxv`kP2M)_^=idhKf21L^7tOg4h;9L3tcV;IdFbVsZ1@b$4< z%Qi_5A4S&bA_HI-_n_E+04uC_WN&d)$!#4W;?TG=l#cXFX&D1W^7W4+5u$ZO=wOuKRF{IJ)h5w>v5=@$Fp`Z;sBg40)bMH!g2%Y#_@raTwcLi@{(}X)|z}z$qWMA>5)U zvZzzFs#~?(;qZ7KtyXKt4xnC7T3rR+eRpedx27v@J|NWt2cvci=WjZKGskvj!}hiHHN5`p z%Xt5%FXHBZ?^n=jR5*p3fn@2m#leVHs7u5B1+?VX`dYXR-s{X-vxqywk-d$`Z!Kl3 zZFmLI6Exe1<0?bc9)ay8{C(je%C%c6>KZb6*{&hH)%A5=B6Xf2WQ@Z|4X9(jw0L@Ybeho+o%0`J z&&g-8@0UNu#c%uw=f3${7%U$VrHuhl{$5j6UF%7n9M&bLP^5hLykac`K!pP&u%_}& z=7n;;#sQcQAvqTTIZ8>IFX*rKL#OLTC6Qa9W8#l<9co8yw&!J%X~e$D+VDB67pZwV zmc6$uyeZ2^oQ~$S0d3XMrVI_JIgi)8JEj=KXS&|JR895$zcrdR?^&tSao1DbefQ3% z&B+*pG)>3eowuG&nx^AZ*we2XI1nCgTy~q5fh-$|&DPc;0PR)j6@>%Z)&gs5>(MKz z{WV{jxYumD>bk(yt1B3d;+xX_#_1Tf+wL0c{rmTo@2b4Fx$xTq=))m!^(tV@&Vyi1 z;mDkvU!5${ysS!o@w7Db(bC_)jcpIp@<)PVDV3FfcW7rvx{mgYGABQ7lO?-~=Cyj`?CMwGuYagxCkWR|u za9nN12re0;GVdwO`;qdT&~4l%KL{u}CLw=YZs686BT7~-WA3N_3QPa{|BT`7_quXe zi@_ZaVEw7@BU@MkERgR%gwc`XE{p4QQV>$*=!B;iD|fx@gsN|dS_mWS1?RA=;j<3Q+eF(Qd|5)oBwIp^Sgl~&|PqszzRi>6Mi zihF>OTSWYAB4IeoN)tn&yln}OQhUjn$is#yXw)8W8C@c+oA_FsgxAqLUN4a_;}~>X;nVc$KQT=dOhGLKe71kcTI38b$)&hb8}snSH%^; zU(gqHeW{9v)#Kk7N$sE>#Z=*EAD8pSaDkXRl#xh_aIn_~!VTSY@R-u|9=a1Ir&1I+ zec}X8K5$=cy=S49-aLty{@Z^EoV# z9l=PeLFnwplh#=ZCCTI1IEHl*gaPQ_9T3XBFpn5XeSw#JHmcS|Olec*q2uMLlO2Rj zLR?cXZ>kaBc4ghCNe@44u)c0_<;rJOf_Q6j96Sjl%im#ov7YjAJa^?|gfu9hmd0T+ zZ8>h}Ylxv|B|UqL_`d-;s>;W|Xv+y5ob+5YLBX7Zaj%SgzVm}3oVeyp8n?cUnDYlp zHKC0@qajQ-a_@^AX4t1J1_Kyx*UvJTEQ2*oph!`iJB?;B#3*T@b>R%mpbs;g!)D)N zH24H_**aE}MJ#{#0t|rR&3B+^)8V^f&oV{_Z-Q-iF#Ot`<1zxn&x+~wE~E5p?-5cvE%hle`|F1ERd!ak33ReHowlw*KYlqtqNJ`m})p2VmKV3 z(HI1`DGvt2Xq-IHF;b_}27>|m{XViRN59_>;#8%Trb)1Iy3uGLNfIPU5|pXcYN6Zh zR;2aC&03!(O*?ZYVe7gyV|cv^!%JIo%>G!-(_?;{JsvmWeP}zCaVWiXtVR0Un)$B2 z(0N9Ijm3GG#NzGy?!gtdM`5e9vbKgi&oMtYhqD(i;==J3?)dkA4NpD#rERC(8V)hn z>y2wetLL;&GPGlZ`JsGHmbs4by%Ci z$J3fz9@!tedeio&MYE^{A$XoPE&*%mBo1?|8UzHXT!_%TLh17KDTFlfa7d}mQQ8nR zU2RAir^)32wKNa7N$sbr^SNWeJvu>vYkwBn!e4Ji;ruhX`{(MoW(>rJ{aacjqPI!; zt=_A!W;%s1y-FWR-1~P3f~rSM2mr}9xsP3pOC1MV@!q4+BbiPdK!+kO<{Jc}Zmvh; zwUPA=Pcmz$XyA<_;il~na>YTl+pyg|^F9v!><`gcyMXt9=bvHq&MzZxb<0rF@W7v| zft#-5v2UO{>k|S{`O9;eSV$U=1l&yd%X?m@`qY(A)+H|L z5tKr=rsj{Nz@Z$mvVA!jQC{+xz+tInVXb(h>(95C8xZg1AUSsZv*V0O8BZEFq%SgF zGA{6Ayg2N`SPMu)+w^Mt)=4WpJ3-6Kz=;!|4zTZZI#^#{4>m;W>zX*lz<8GB$nzY- zVF;9+=W46o73lZFYpnbIL7A^U@!aqCD>pRfc_BbOJ=^G}?Ia0-I{?hj&sT&umEPNS z6J5Ouy!P7GM*g&X|N5p`A3iR}q#Tj_S$>cI<-AsV#@76u->D&uouo0*25k?b0n2=E z$uM~%#YVS_LAQe!pZM~O?G>lNaESN*@)bPy-~0>g`wxGBG)bc#=Vu|ULwQ~;Taa(? z3t^pqtMwfTxb-IOI$#_Cwm?b0(;y^ZmU>kTFq`0;thc5rKpP*s`u#L=q7EGMG$*GO z*I92A`s^J{#5IXfZ_#~Lw`n}Y$36}BRn8xdaW&GWGKAw-_Po@@bQ%c0dVPxYDy|1| zEz4nK((Ziibo%@jrFj$4Z6(mwn^1Zi@lEF&@_PjF!V*Y5LBEgn4t)=4l0H+#Wn)r{!b>S74~~UC zL}WVB6PT_Gm5R@=gl)f;vX@Gx=LbL=w>>A&v%#t|bB!R5iSD9O@iFV#ir0eoinkdMa;3Wh4EPospAxq~xVGb{SIZ2yi0`=~ZwanZk=&^sr6J9R zjdjU*Ix^H}K^1Gk0Pw|T?JsCsbUiTe*7LPBGclHil)9X+YMZ4*KEz)*#+Ck8iKi#! zGAV7$mOPnn+V<~re0ckX&ftaa-)wy;1^z{0{71qz#^fgH#Sz-DfB=hAsJu3U7fZuZbP^)8UQtrzL( z4`2pv16^|Y5|Yaof!1CO_CJKPH|@pI&5yCtxe4aTJ~TRW7~Xswqy2{g7;FGYnk{^I z=YOQQR@j~rxp9jGao(cTxutC(u ze_`M9n;1g;9+O2@r4i;`ZD-(rsigAVtQvVW?v6<%N{`f@ zdc9r{GRv}HleMRfjUGm$5mr{xV6Am-t{cVhZgaF;ukCibSYFFeZuu-sb7&qrQ5ZP>J^@LtT#eD4nU>PC2mMDEKa%Z1SZ!y+hn;?CF^`T)8>0a zY}#(MoJYi2X%c{)Oz~!(C0(xM#nKBEBnr=`59LWY6Zod`@+oFTeo|4Qvc*o$O|F&C zjjOYkm4LkKc*VaML+J!`E{i}x001BWNkl@WoBM8b z(>-A+(WYmAW;+gic|KAca8F`|_$Ofk`Dp@pZ&$Z0F+2yRNdS32<+L;>Ssj8pNSLeH zTnOo6(1x~G5j6K@)BvsyVo3nvOQOMh9Ad@69WOVf2berV_v3eP@aO*uN#i))`X~Q! zIX*bWm4#{pNR^nF)SvM*wV^|Uzq&rwal%%M)k~I5&MOJmeCl$nXkp1ibG{_i0*VdL zX1tilmu8)+mh>$^??C^m)c5ik1la zJ1>zG_S6THl!xtj+m40X8t~pJ0DbNpkmnX(`jV*y(165>bY>+mD~cL%@}blAv6SQy(*@s#Y`(;->S$=8Lln`se|a> z)j7tb{#J#2{KWN;x|q|*n>zix3ioc!c3UkgZ#=X-JI#udXTivX5lBNa>O1dCSq|5m zA@;4p0(|VzimPEUJtF0EPyXepN?nD}td1Ke8jB(F_v@arM8rR66*)l;jPLd>kb&Rv zlCVuZDY(yDUOHZ4jp;I^Xnpu5(#;+$3>p{Dp>g31l3{}6N`g-|&)`7sBNXQgbXMNM z$HfT6p(EI{f0^poXkv8t0|0={Z~qW^XWmJTgGVtsbQ7#`{IOvYd}1w(NwDturAbAZ zI8Gs3K{el!eM5iUzZ5_Yzlue2O{XWveiaAOU!|rmy=l{CBBR<|#@713tY0ER#}HnK znPb>KlpkSwp_~ZIOnQWDotV8LtkEPqJ&CHU1ym+&t?=(c3$i|v8>UrNK51K`P`+Iy zm!e%H4*%sPcIHS(+N9*BzEDr|zthrAK)uITVfiNPSot|GCR>E=Us+F|rd1&gE1m9V z8jC)x%-?&~_Bqkbe11Ivh`UduoF$^?7AcY;)B@TeSlruoT#u2d?*wg4XW{X8X5IPh zSs=?So_HdjR;$%SuV=8jx*B}zcDv%hWVhSJ-o1OH=^Qv<(QdaYZyTT%1|Z8Wf=ZFj9)L8oSfbDo3=Y0;CtUQ`0yEmxK6eXqvF@jo-NKJoEzo zG_)C~K%QsAsju6MGYjqMhqGQYPFJ3^k)Q@Fc1V)V^XmrUV3Tq%W8e`&TKdfyCV_5J zq>C~qdP996g`sb0zVTavGf5mINC@W{I|8#a2eH(KlzJTlt7GaKFw64A!f1iwe$Rb) z63c(~$LOWYIRAHkrz|C}s}vJ9@*FA|vx?R@5D!IRtdHV=I_#bJSk{Ju>atNk`tij5 z`4PaTG{H*b<~~1o!OJZdq_sj8_M}$sV(m=|n(R}q0@NE8^f>VUFWB7kUwMr+koKh~ zPhZk|qMI|RD6t=T-m8J`1F*behSchl&sAK@iu&kypT4*4>p`D<0zCJe#n-=H1)y8l z+}y;~t5>mS&mI7PwH6y28$sCNa9DZjd1Ykfe>f{WUPwxM-Z?=?jre03bMjx%&&@9!PR}8wA zif?V!C#gR=aWmd{@cxOWjPDONZ4Yb+S;_R8c)xtxjVS(5;h;)8$)@ z40kInEdi0s52m86@RE?KH3^=63^%*jw)UM)tEz`W9gmkUR%#o3pS~qXFVkg`Ir};2 zL(uWQf_+WOcQkA1ZYYrwTjD761zs@*4h5 zdu!nBqf_Lq7m`1S?aLi{dkd`~9L-RV5w3}k4~?*VJM!-u+3=e1@esD8%u}Pc5ZxK| zU3v_ousRK0E>jUo)-+bCa7<`qqFXY~iG7+?Gc<-JV-hU3Il212iMaiTm(;2mLH+Ii zxy>LxzDrLYpz`S!WlmM)_j5i`dXQo7!#LH%Yw2{U98w1h+rY<5%F@u$5#A>TR&XZX zEheY)nvle6TszrsAldX?3A4j3) zLf*Zg$^?;4Oi$tz!@xQX8Q!O~b<%OAK2(KQ<2rIx_?RrwvT!Axs|6ed`BeD$FyP49$BEfsXufDXpfOO4I7+7yaT@@& z6gdS;N*$DNn_p@1>5`9ax_?RH0F7z7PyYn%S6@J~dKDJHifQ1|V2B6af5Vk!`O7$W zXc_axRhZT?@}*^5olkLfc^Sv=J&HMdC)RBSq>4RgNo^F(vXjRU~&}dHj zJ@;X0Ec%o}c@V3gRry!pV4g>~L0gU{o*uWW)bYWX^wIVS9+uajio)BK>SNG2=T-w6 zJ;@jw^76)eM~(&B@Fwfx*9!Ps&A*Bg-T9d*H*fi|>2D_{4CwEIGG$(2Z)z{AT4RX0 zIpJ-k+trli;k+@{Mv169=b@pFL^cL(dyw3mm(IH;qZ_ddylX`7DW8t76!6;^`52_V zH_13Pju3o{EezzSUN{Ufaa^O|7~h49-+Q4o%TOcNx*o?8x(xB}y!6|n z5Jy+%HC>pP);?J-+1@_xy(k)${RaS<`-AcLIZ~>*{%28=G%#U`nnoH#SHt* z1gXmqTx2Gy&YbZ|n8eeIExY>qYA@FkEOX{gZK1=2U^~9>zxdV*NdMyh#Od}t@SFbt zFmm%ZuW<<0ILPKBqgQ75MkMGWwChN2hNqH+Q}FI{(ZC zJV7_wfNVrcao`*`jc~<^a}4eYEXMaF7pfX5ye+)nE^b2MEgTyIaYcpTt2ZD@rHIN1 z_}MIhu?Ng#Le;#E^A8?V|CZ7R;9L{Ix2@B5<4c+asBecB7Z)%X46w4Yg2CYbXYWme zEXl6(urJ@My{h+puim?-XBx9%2FqY20Ft5tAQ>V}h3p6_EX$4%{l^Ob&<_P2jPM^v zSc-7S(ho0Td68w&rX?CA1#kgCU}k{93}(=n?&-C9-@B`~s;=$5O#jGt-&t>FzW1uT zr+ey5^wi7Dd(S=h=Dp{f@8n(P+V`_8Gsi-Wjg6tN&v%X1tXYHM;h~nJ&GbnLsP>-4 z(l3GYPbS5EMsI}3z@P@d+{2LY$l3(?TrPT%wn=JD{}Tc&X$zW_|F$-P;3VI9TYuO- z@!Wn~-Le_YZfBz^`tDnA;^v)6ytw}$_KlC{by|dR_wu_x!-_liP-~>ERnGiKX!%iE zPJO3I)`9fOXU}SS9ssvqGTfn$tg=0aTi=kMm#@k5p!n0Owjz#|ip$q|i@-6LisyYC z_UDsFzV`u0J*Pc7{oLM@d@b$`o{!8ey)Id%-)C&_#Ooy-3v*m9@6&INGISlduS@%H zhkv2oS*t$0MdH|4Vmqn5ZE%cGV$v>y``8wt>XxxQIcBt0MPs+(_h_R4iAbw$8NGSk zCc3S(_Z%mS8~DAVrQmV=O}zP2AH~Jq9p~)5EkEWE!$@3u+k1+7vd+t;t4<#Fl@?D< zf&=@l{Sl3sb&M${f$qa$bP(qZ31sL$EX@s(ENw+e2J)5cMgkea4lgmU0f>LRr&bSf zwyeDXj&|4fJpgLqjODjGiUqqFTCpx_5*DK5Ql`w435Yjr%fRt1wRS$uhEJInSPNX6 za=l3Uke(2V);M~xu`E%Xudk!aX)*kiTetG#oR?^cI5isiqW7nTVs@&0bXa7>^Xb1j zoy4!6ebGB+%l)QfSU2sf#=6r zhMxEi&CFo$iBnj2?Pj}H`Gjq~IM^b5IzvmgNN5d^wNw{leyMsMsT@68k8^$od!Y zwtYB5$8-n=qx3Ylx)HmHUX?9^_nV zNN4BJ7#u;mdkdPY)*?ZI6$68~@teP!r|MsZg@HlbM>9Xcs&4?zz62xnIvx)8BSD7w zR$1xb2vE)pH7w$M%q4n;=;~GA#EB=}dwq(HTy4L? zJs!K$>A0m0yfp^5)}GrX$;X>)ojCs_3iUP_$l@GL zH*x7A-aUF01KU^QjeqfbNOrI3X~Oo}TeqNuVqtMKx#eN z3i1sE(q4(h!(@ZB&u0C&A|Fqd8}7yMxbIDslkUgWY*pNsj^Sx9O$=XIk0EYDpNdJ_ zy^w`^-B6KxzyWd`SX()C$J1SwoGcEREHLIOQ_CWiC8@zo$?5<0i1u#wWG2o@ODWKV zV<30X^=jzgisx!11K&+d4sF>gIY~v~K@Z|Wu&;(pJ>|}(b=r%-oIh=e!y|cctOm+~ ze3KZUcaW?JTU(x5wvKFLzn7vdtE_K)Un_`ua>E*vz$z=-1GIwHzvHW*Ij`l%euC8> zyo=fOFChK=mw@3>w|owixWpDL+dQ#Rl9*D8Qrq!qTU+m;srRRojtI$M9VN8Vc~bB` z8TRfAa4Z8qRE~(2Uj)sTf))?N>cBrvhjcLRgkO(hAWV5=V1j={(KY68jB@zzKimx| zq=up~Pe)V*@J#IzLXlwv@|F)8iECIIsa#)JtwA~$(12O%OE2GIP%i+w$f4ogdS(XS z`Q8tZ{lT9j`7geRmp=arUU}{iMu&&dA6cN$DZTRUdsubr4w6P{K1}Q5K)JOd03Gv@ zxbJTLQEx&d4^L=sf%408d=L%5$iaOz|2eNkZ=|tKtej5LXb4_re?FeUwIbTSJwc<9 zVQQ-Lyq#iZ4^ecQrwBXSd-4rxU1#Ot=tt(Y*i~}#{3c62x*~qLUq_fTOz`9ghbDa{ zf+zos#dk&4b%@nTOHCd&_sqR$1^31EvTzUU`It_A*3*8ol~2pA?{R&Q%M*44=lU^W zcVxfOGK29e?(L0s9o8EL(Si{smRs{gfH zw{Yd1Bq4lWd^|r2Rwrk8SG`D`*7u43xzD*f})!vBoUW%}D7UikE9Bl#1dRI4boAMs3 z8bLbPny^#v!_3$Up^F-A z9g&w&2e1IXUv$b+hniBW>DJ&_jq99z=R<9I)gJE(a*>v%8V@c^$KNjGss z&m;VRY*&wi?C(||d%9fqOVaN2of!y=py>qrurVUF8EHGYAewl4^_8v6UY55b;$45_13rN3*$R*etgHGOxXVL^eJ5Xqjzxc{sRnsZ698J`FU(ux4tKy>#yIy z?o(&5;_f|VKP|qNU)AgFmZBx&)Ox<3<9Q(odouvN1#JbbpX&Kwny=<3y;?0#EG|G) zHeQOJ`?ewO=W;@+Bp$0X0oT zl06|||JQYkgJu23{rBnt=;cS>#>$`n4701ZV)E5DfYs~UJnT4$I}}MIjg{W7m94E0 zjAYpaka;WcAW*ok--NfGiSI7v)j>*^Khy9x^wzM`b_kh-=YV|wNjsf>dnCUE(%vp& zUf=fHl|~d_j?q*+^?offKk<=H25(1M6YovsAh?Ne(m)6{kQNLuJ3-d|pb;Q-D#i(o z;UWW0Iz4fp7g@3*(srN|P+QGHK00bPf!nu%ci+wM(o2ciNu{r^FS>*F5`FUM#tq=) z$tT%keJUDlMV8yUPZ|x-UW^Qaa{Cc1}wvE&%Y4=K#?i?!ilGIOg`b>C&~{Mf<*AFVB+7R-+O;N%VW;(rbOJ`A8kDF^erp za*g#E@2`}^lST-Dhr)xfWTYj*$M`nfz(l+YBuc<$V(MO&QN8+?^ zG#xgawnqm|4XHscXbzk>;^vsxdIl-`;6O0|c@mWzU%Af6m{im@x7V$~%@H!*&l$bcT|cJX4KzrR0OnzX${n4JZ#UhU4$>)k)B&Tp~HlB8{v zjD-4V%AzWYVUoV4-%W;dGt7(*oZC6xv-H<*-^P*e{ut-}hrht+e1b#&)8EHS z2M+ecbJgS>jGsA&b=UJP*uBNa!HUtuLTVj;PfusJzx{gw4{Ka%eOb>saqlK}&%?Xc zv#~wT)4kpIPl*%CQp#W2)0cLE>`yF>XU96n#y%eVxYO3H3FhW9+`ipi{>8z_i_c$T zWE}(1{yEy|!q|w#R(K!qFnA0zTYf~rkK@RhUu!%rCvFFn9Jay1l+@cO5v?m_(u6Fmc=JFg`*E_w&hk zsk!#If75mMT9U>b|E^K1m>=LR8#I#tUOBgbow?7Fg5nZ9MRcJ9{1&s!9>{y0<`x5l9x6l$TQ6cs2Zx*AO zPDX+CCgN$l@~!QG`0ZhCX?sFEmu~@$Hx%8||PaeERU8 zeH+L6?&042U2NLA7N0tB5Sx3Pu)X2hb&OA(#qzuN+BE|tex*gyWTBevYq^|BM=!XI z3w#4{-%0wb_6_Q{tMlcgeO~Do>U^BE&&Emjxla1DhkN~Wu^2!xw&pzjXHpK2$5S(d z>G|gq96Od_cJ|Si6%Rr9Zh;2ZI==_LW57B9FB?YDC3B!y463EOV?R^->2w{Xbi~JR zDG533YG@uPpbtC}Z1a@V(R~Rm=na4{M(7ZhYt|Enf)zjqmSQ6JseH0v$#w0YfT}-kJos-qF^&PO`^&T84mNIASY7eq@zw z6YfG-4%GVoB@LOyld8$q*=Hzrj%_ea3CXn@tZI(ieFQv@^bz`s}#}6IA&GqY$73_9j zg|6JVfs^0+8D@Swfvazx5BIolP^ z+)`VxtbKFON3!?gyW2`o9rLZ?KpTuFzqVA?Z#x6Tv68q&^z+BTv*oxLHt6F*D_17C ze?P;_On3P^(LLoJLFc$RCPQZ4xx~=nnMEI5mKf6Z_QA4cYmz>bkM0Bd;~33rVUnuW z@@%=L;b}NB1WO^?B9LD2EXO%{`#K&Wai#R~rBsqP$slzN*I8Eo_#DfKq7#G*xCFfA z{P#<5UgnqBIQCnr^D4+DV_rxh|xp*0k z{ysb$8Fus`^|cju?_pqWo=Kmtnr))q(qy%^+)dFAVcHEL>oD=1_gbli$WlwKWp!?h zEY2-XZ}Z1}4oSt<@kv0{2M;n#O(hr`djf?o(Z`0SrhtN+qdrA!G)_=aQD<@jHY!Q_{OU}PuN~@_a1hi zK7%zkZX+xP4i>7>!m(5%`XCIzv|I)`!BJXlZ!3?4SvZS_<2ck}Rqd&0%xw93JUr?S z*T&QPWNk_@qM_^fLZWy*Uzl}2jx|D>IQ*FxiJTJ}eXAxvlFQ2_hhS7Sph5#0$oieGd58n7o{ zWKDR~wt$bBH8Rs^!M9G@GLeiP>339Psp;#LocBUwr5g3 zV1C=a>6IFga#*mHkKt7GDS&p1hQmp3*rgY2^E5!f)?tKOxq0i7U!vm+dW444yh1*% zo5;uEr%_3LDI+ccIR{OWg1#$L?l5-wDbG9xkaHsROl_K{C%vzAM8YJI?^3r=uReh1 zi#!hMwcIoX&Yc7L`ZA1PudRO z!;y1^G^*rZSoua5HHOCtqvz>ROK@Swc4V~#7q@T6!_kp0S|X=rvx#F96Ued@$0kl= z)hoNO5}&U`PA*$hmxFVU1V@^la^{B zkf_~9Z|5D`2EObgzjz1r>z6V8%9qeswN5z4yj^lR<%G_>HnsNicsUkW+f^$P_=TV& zO|j;rOS7hpYN3gCE)RcGlZKZe+tf?vnN`_RWE8xxhYj7t`du8D^U1T?06@tRXyDcr zZ1~H6g_-r+ap%Q1FuQ)U;K56Tcq03kh5Oum*f2qHd&=6z6+AasFAzL(VWp^IfFnVQ*oDaMmtW^XH&Bz5<#D2zWo2VSE|lk-C+)3ZDedk3R8&Bq29J z_gGMhh)*dGAMkk#CkP+=(bi;O&*>ZiY9kusUT=~k$_Lc+yoeSb3|B9^6Vmpp8%k5) z#EA@h_b#n^UZTaPPJGEn8GiEQh}$$jKL^a*!qfBM#b{khI@Jr75>(WawS&IbAUehD z$S}_C*@-KgH%BC{PM2?7$B~mKaOuWnj18xF?fDl_tJP4eb-#1>hHKZcbK)$P-?`VC zgiSg-v}E{*?blTARHj1{av~#BVHfbRxUqJg(o_E2^fyl>6`)iskhiWA8M!e73 zvMo~cY+aFE(ZGE1ZRL}py?cQqNpSAmlV0o$ScDkz*ooUAHBXb@)83KXmluLh!u~I% z;M!4^8tY$iqEak=4$mwKN>qvDb4zsTmzcFv14VwL_3bqut7o)Sxo<3UX-PC`yk=1q zSqPraN?}RAOU^sI1*t9le#iMG?Y~@~YqD+0(@2Ej)w?QMlx2D4X}#{rqRaEgkd0jM zG_nTLa`3b|z2)cE(DvCFM&@{u`x@SkTB*X8c1M+b0yG_PZrg?LM@0*h!!(dE!8qXG zJioNJ0DY7VF(%$Nx;}csb{&oOM+N=iq0!%mhod9yD2#3`?oZSkO$<*xL@miMy_UY9Ay-1K@YHSQwwiNqi2aX-b=1W)5H^0!5g+3dHGXug$_%Ja$v_S?S zENu=S?n#GRjTm$juX#LOZ+KGj<0Z;+ipz*w$6^ijXz0QPU|=A_fdfy!pR+{W(foY( zC$aQK@mORLrtOBbmlKOf>vAmWk(gTB4qBcow{59`KCjl1Vs3Z<=Xd7EFZV*XkDNog zb{IcBa{@ayZNiJc`^%X6?JwZvgU|KEcWi132R=HERk!b;fxZ@&rMQ0seQk`Y_Z0WA zsI_znWb{`q-R6@cwFkogLfn^eR-HCw{3I`rhwUL%@vgkz8Tsig-m&*3q6wacZ})6 zl}2m$MSc)R?;$Nc*E?{B4TSW_=bPdLUp*0JdFYAz@Mv=@in(zK(^hJJkB>*r(`y@x zy!6CO89U^)?as&L(gl9xlapjxQpq8|r&C#(tlS)P$8AWwC1c)1aV%4}DNmC{^LV(M z#~UPGmRu}Xjm0?+-fGqg`n9HLmy}ssV*XoVQGcTq53gz*3(%rxJxb_`YVUuYOzX{uXY-Oo?n@)tq#*3R29EXoMwG~2tm^3iEez#{2V@CDU8 zUc%oY?T34CoM&1#BI>x@zb7Fpw>3( z54Y?!{HuX#Ua~e-vPMM#48PWKvg0ii@{(zl=G9L9vO7z2=f|&)l#UyDTI@hTkWV^J z+dZ5XJ5XsP7vE_{_9z(;uq&d;8M89$)(RiU^{#7tzZMCkL*2CF;`JL!PyI1`V9wgQ zCH$q(MSeG=1!O;OtqTUSC@EyhJ|T zx$}5dJ6r0k%pyBP_sjCeJ&hPVqvsY-+kmd#TRQB$Mbnk*Xqr4>dh>(j%P_fiH6D%( z1iwByyt%xI(m|gHtQv7JDSpB37 z&&I^HRalI6t`?$`^smY6Hc-Wn!m7k}) z-kCwyEKXJMD@QFnO?Cb++>tsgN;v z8VORQeKj=t`!Km?4UW8cxIl8E)wd_{>W|;W?AQ?A{@iD~`Y>^F|GrA;jz4z*S(0G; z`3tBuXxH%u)6RXZYaoBWA&#Zv2=aG$?`4*#lTjS(Mt-gJinJ>sSFirS;$h{*@J|{I zU||91@9&At5cFzezoj67BM||Cv9J`%L7w@#nGLC}T2l z>U4})e~mx0{3NcR9Er-48BTesz)#ycUGL6t@nXi79}f);0b^smEMV!(diyO@%p(); z%g4q!7yq5=GW_Q{oyE_ge3{bsoov3E$VYYY`?dTU&5>{L!uh05=~HK*?>!nbhf?Bg z;OPoE>NRGS`p4fvm)B62$M5=Rfu3dHCrC>jR(0g@Ht|l_(i7U_(Un+D=~)abb3J2` z9j~vCXN$?V2eJ3)@wV?+*Fj=xEwQx|w)R%KYWIrBS_F-sC1y?_CpB}c9N)Q`r^)}- z*-2Agn{j_2X>*~zTw`fcB&dUY0<=q~dWG|fdE3Ys0R5HmfTpOc-F;hPKKW+DVq+kj zUR6f}HKbS=9Kh7rsL>ALYWU$S24`kLi#ueDAfyd-3eu!V&_o^dZ8`se*TP=NO;fGH7+dLe~(lh;(r^{3xoiavAq;@t? zl`$D&W${1|oGu)Q?=%~_wR9}eazq0!D%-XK|2_TOr-7*l7<=~zNKwOsSHFz8t$Uc< z0ieegl{x>*Az3SZnxg;iO>Fp!{{v%Zj^OIA{4S=qA2fCHxLNRQ!LfXsnwPGLZbcow z;8SchaS%Y74Ex7}Neji1J8tnn zfZT~S+~aOZjCg;Pu11r6?56g#tDo~x6jnZ`;DJ0p48?(TIP5t9a5*A_t|M0_BS?uhmdx%Jt+Lvjzh12vpae;0J>LNTJ^j{F}igNxO(+TOVK-39qm$=aor4YKcw}% z8xFLs)sPd8!tv02qIO;A_zd?~F30TXFmA6~gG*btcH0DPy7b-m@w0muajQ0m?D%;+ zw`n^*bNEv|^Id!E7W(JrF+4pJUF9rKVUS^CJ7Jq2B`rT>2iu~7Y|KXr_cUPEUVzRU z^H}U#mVs+7OYxmf$oi-r-(p+mp(O2<6y>MfyqwIH>S?0{Ns=M!(hxst+#JdXMDNG) ziOE8KTO57rG{s&^TvGoI=N-n4#pD@Czmhkds+_!@!Q19b19^>PU*`Y!rIlk`PhI7D zK6s_PP30)F<#63*pLv!ACcUKiy9jyZ4r+YCqW8}IfLY)d>*vyg=Q*uq)w){$E~<}} zkGEry&gNy=JT^kXF;2|x+lk%MQc24L#gDG-Zz-3oJ8|QupV<^SmI` zB>h-~ceMo|t-LrEon!I*y0?$botNKRUCx~Yn#~NK`qb0!;VjX|le)vFWh8BiA62#3 zAu(4L2TNNf@h`VK-X;{@Ne|(}@%t|y#^jn+K+^eG%d*x<1WAJVg$4XSfAL-X`k(z{ zEFT-|m=|w?(B^#$4ZQKaA0lbywrv6ZZL7m~=n5^6s@=Ew&R%G@LY;XVa(_;KFYwi6 z$Ot&c#nuO-Dp^k&g{-?M&Ik)J3_wa+{2%RYI2z4ocC{%RIR~ zN=)zc_G*Txb%y+V6yefLpUL=**7A&=f7im*rxR{ti-Q`xojOR@1i&7mBGu=&ozFg@-;u5m#_-Y;kBi; z4KlryFjaY~5n(27J2Fu=p90Ngjcu%@pYhY6>@qBpgA?})=sNFPDMEZJ^mX2Y69mK< zCL-4aV$SPlx80JPe(?=sYVF_NZsK}*yzJw$9!b0Yje$O-{WaX!xB)W+NBk+_9B zgt;}@)ZG$qUyIdkJjPNSOY6FID_6HPH@CDPdWkHZKAqw62CnFYXE)_}9zk&# zGM%-s+{@wmIyTpdqf)})b);Ar>_^&{FLk-GaRW{i=;|soJ2!_UNpSJnRlNCseg~U= zbRFOP_kYk6&%Q&Mec-%{ga zX~${)m+$3xzB5|sNZwd_>plBaoT4fhUS^zk!u~JQ#W8XmZ^tO+c|TQ?wgF(pihQ-o z++270Er=~k-$V`P)r89$REHg4agZcSmvD-I z__pRFq}M^QVv_B_bMgJbc^{I-PKOtZ>tumRs0+Wxm3Sted%(JgVjy0ZXO()$Tbq4| z_22(DSpC!Q;QZhIN4R_FvuF;DxpD+)>9+;X8m#eW{JsvWXmDOkdc61!2M3V;PTFDI z_#hSSd;G(2Od{zL(Wnfev9M2c7&9TPz#RoocWLu1T?e~XOdk;~+d=C~ZR8V#L-NAW z(mBuBkzve?3`6!@;<5bR1JoB9ZM_rt$}kz}KOQ2;UBU1?K@$Nu%azahHLZTGA!~D^ zQ66A2^^|VGqX)J_ztw%On)C2vRz5EVc+Phi&9Hs@(vI6p^mwWFuvRDJS#wDo4iOZ~ z*gt6>rQOWa`rtU|Zn=h+!%97I>cR45IJ0jzZmnO}TdlJU*KXZHdi*+0{qNt$z!$b* z^MUoiH`in3rp;aPtT&rjdFO6h_vEXbr_exO>v(87=R&V?mOvPyMd(@0v?5=Y#ao}q z`eHg=rt)&YZGE_Sey}vL=f%`*aLKn?-j(!!16uHWk?9uw?6h# z`Xj;WhLb-S%I33peoGIfv9fn&$9@zPaMYCy-d>s2^BIqz+GyX5WHWV!M>qzF6c z^CewU-rzem+s`|tJF8aV$DjL5$N74piQT(!etZYk-nfb9KRC)_3A8}ji;%^%4Uaua zEpFpuWuK#~Qp{fnCCmF%TFf3n-SuSBQg7w=PftO!S@YY-1 z$6lw_I>j=#-;TzxVBEZU)q`$)toPQwO)*F zRW85uWk|l@0q{l89BW%|pvY#0r+Geo0tamvmzNyAt=5sE37WeRt4CdM($m^#V=$er z-41ox_5pLZ-%17~DO%@)(xmN)efw}>e0#xr$!TKuE==s+1prua_a0t+{{y`Fl{cd4 z*WS8?SAO~)(kwwOr3Li)GI8DpVNMP0S}r}Q6itNP|Gj9GuN$mZ@pV|S#ghDruxbqd z7GvDvdQ_9mlchIYee`ICEK9I!SJy0-=ozG14M-AnwSi7IKIUSOwr6Fsc(_|zVQzP{ zpW)e7&6C@i@Vh4d$&(6eXyT(6Ucilw8@g?VHZ|uKkkt~r_t8-d4-R43$SAgc=>>e_ zAN^-N@lCP}TP|J3a~~c<6E)0Z06=IRiN*8Zv_(mtPWp$0+XK$#%Y(EB!e>0mNQlPR zd}G&QzlrmbKD2*d``1*a=2@oI6T_t%#bUVpp68G9UvZ4gad}x8arE`nP1=6$xqR2K zix+|U`6nesbzmKHDZH0tgEsml#uOpH@+Rhasj7Er0-gcPlPuwyOG*xU+P_x* zLFc{&9oj;?vi4PxJo;{9*(%)q;x{pU;1#UnTf2PAFN~$Q)xS`$h zcrTV_RKIWQxcDD?^@nLnTV%i__W-~1tF$#jb6A+~DHcl0_m{4>rX`2tmSkJWeMYsc zcA~ZqrfI5)XVgMVh8&!CW3V3=c5TPG@$u-pIsEe@Sbq0DQY7e~UqF&(m>(K6M}38M z8k(I$eSty+F!C7rDBjlP7_J0id88EYT7@28x4R`t9HEl&rn0o=;j|3!c58EkA6Dr)!^@kYso` zHqyR-{LleRu36o6{Tj_Cre|g_JUEDd|K<-d^54FNul@JGhc$=CyXM)~Xkd6|27|M6 z`1DVHibnfGbPWykyQ`c-EqMq*hJq8(QUN#v5`b&q?D;<2_X4?a}aU)lUgTNck(_5H@~g1sL{s@H+O9+Cdy1`NybbDm0K==i6F z@<5BtZPRN$afHUN2(5Swss-* zZY`(S7}k@q$$CgE9Bh0jUE*u9A~D=Xc!{?af1h$$eMqMlFYB`_xCP}FTAqoKr~lcf zU&igVYtXFIr_VAvd0-zJ^*Xkk*W2WTN$9D%n@g?FAmgzIYFCTG!-w)Z8aVOX0o+=* z1`7iNmE{eT)eeUEF`^3$kZcww>Iafv?Z)J>177S*=4U5}WevV9LoOJPx#)YTG| z<$MUy0SP!RK6>a7Zmn5cAeE(~XHMgzi3uz;7BD(Ig3+O2{K^|&!07NWk}h`a=2S~l z^vySrv@t24)?}l~{2ND@v=my-?zd@o#m>}oZVBY1Z9WAI?4QN6fwZsX9qX)pCVSt% z)(D&bwNl7@F|zvIruBL=;R>=pp2trTb6du*c)DU6S{4^xBBB@;?VLJ~mRI$Jtc+f7 zEIZ-ZmaX}7;=HIt4{!7SXuqM8CrGKn*eC5oCFBzo+=&FiVj*M;`3kBwzL zcwM9gt~Ms@`|>39v3n?+r`PT7VL2Ve;1XDztT%(=mQkjSNd?ndUY+wd8lLe9_S%xl z-M95F+WMPpU08d$tjojuV0;6r1<>Ni)8*erDVmetqiNH$txT@+({M>fiYW4vg;vk_6*hw)D(*=fqj;K6$2XsQ|RUL5CKw=Ue3Inypi@ zbcBLiLU|Si_egB?pW|-*RUnY|({hsjoV7sQ+u?kCf6({YyuP?NW5eqsJ`Uk>Nu;DD zweeyPS(R_78A^KUCT#=2!Gj6XG{f1m-R1X`P;q+iWfp@7AC&4BD%0qfrc>LODkY&S z>yB|)Cd=?^Wr=@0kxpL*nw&_TShg~C!USk3+u%N?EKQZw&}AXBx%Jy{Nk8u0ze+%<#HX^CjS&L+bf7R8{d_^d4Q%^C;Kqcp+%kn@bx!zo5hM)*dE3u zed4A`YWzcLzDkoY`AsgNni05$R6 zEW8yx8Z^TAM`}O@zqrX?4EM7f;CdFW9LV}siSz8#y;=`as7(%PHzIR7?PxJPy7e zN#0T#Xy<+;2h-e3;r!@LX+X>UFrFqn)1X>gYUyEUAI$e_%le;|unNU|RqoGaZVrxz zVgOmDw}3mAXK_aB$Ava*$WN!rPo8)@RP14tx32c*i}-n%-s_2p={x0lWceCPP(8Bt zl}5gjvmB!m3E5T&T;*8co@9P6-j<%u2z*Fq@sJa5BVKFb;bVzdIkMF>`ttA|OsmOq zcwg{pF55a5qtS7e5LGFQ4r%PHttshM8OiW+Tbb;=c)R+)eT=FtjI}5_S|Q(*j6q0j zZLJ_rV@bxZ=q=E;02#}jh+oob^66sQ%F>7Dbg+*1UwRn{GTd3Us-p?p05Cf=gmb%h zB28-8e(s`Z10EaUzEkGbpT7ed5y6uPJDSy7Sop+q2XJM}X3P(EK4JSw)8wkv_~_6< z>^ph_8Tt|G9?qPixQIU{ypj9(Y_it#o`28_E-l8%olwkwsX_}2z|2g~A}rAobxl4_ zwa@&#Rrp%F#yt-r!p1Uo$G=hp`;;=igzD%71;WL3tEDXli>p>Q~@@EzYhik7ddOj49=i%uRtKSbCC4TV72e&^N?C#qf zaRgf%_k^|2{K=ygD}dKuPwUg_VnAoBrIF8kyl*wB7t56WB3@^|J+&NCW6C(EwG*=BOkG;>5xINNY7L^cOE~zPoBA-udin`1IR9MS^_N z_D6>f;>zaEPxQ=^1dWoNG_oYYLVrIReSP@x8=t|e@4Sn_nK>jt>nk&zU==1}*U@aZ zFZF7Q@X7wj^}dc##Wynn;yqC7)H3R%oN9R6mjC!-29nO4$#>h{z559izC<5OI&~_; zrAv>tjBdR5PI0$4qNI{Cr+Y@Wa6>34ol_sclG?o8wJ^f4Jc6eDetZ+m!J$zP_|_RX_* z37*nP+lxU}fp0mLyD_p{58}o@ILClB&trkV*XcZ2>|lt2O4;EE{DxsI({VSER5aZs zhmsEl4WYcCL($;k%BVTE3={w9-^0*f{tzp^_s6*VrN4=V4O^LnNu_dv!t&ZpDlM*f za?+E#J5ePvG$7wR$(xAlIB9Sc>#bbT#*}Cx>L`O4MYW3sI%Liw1CRk2J$DA1|KyKx z=Y=og(zpHrvV>Mc7X?=>{MR9Y%&8e&Yw#@Jw638qLy%D}w@3sp-jn1GrYW07ZC60& zpjqzSS!?I@<*Bhr+H&o5p1*-Ugk7U^c$fp|5X1|UuQSwJTsW+jre3-T@=&aL`)^a! zF|F6}qpy4c&A#{t_LX<<;`a1m4u6(x6hevT2 zz8etTYkf|f$dIPMzI}_+CQJ0mq~3hSM-@8aFfC58ps)nL98gQoh6e$8U^MuIA%AY4 z8t6l#ZKvdsO5M}(|M}1H*1!4=HvQMXiEn-Rt4NXrzw@hqqvxH+wp_f7LmwVxhd|cF zDrXLIDXg7e=T@uES}q2h`7$cW7wz=)W@1N%2GSk~_fs?R)_9mB?zi&4nh!)yqOv|$ zh01`pwty1!5{F`d?4_>;lAi?{8UnU$%g1TA6SqB_RGz1(4a;$Z_UkRywel6oXtB1} zm&)bQ;TDL#s%4=x+~3QfOCw~;@9<|@7G8ce6quOnSZ#we{>bx7<7HShX0?S3-}*Yp zqxf6$dPvdnb{4gjQA|hr^^Hqdm4EELXXah{WbM6u8{Eq9P_2wy5JH5yFVCCM(T<{M z1AmtiadRoC=2FfCd>3w#B@bx_%iP3#ZJ?*1Jpeo$8NtQz?LY!-KYO7q5q&rfZ4lyH zauRnSxofyRse~3bC%C(E#Zx(98vy192XJrY3bR}-1Mgch_Ccf9^EJq}`#OTOdnXuE zkKVuu?fbsJ;N9~qS}}I@Eo3(sxm&t_KgY-W_dhG%&JsOJs_Oq0`+l93V`Hr`n^F~z zNG%b!)J3+FTVg3Iw?`)q?#I;FSS6_d;P&0SxP0R}uzmpBcWlR&^}QeI3;@?rT3o za^^WT%9bTrDfIK|MEJ@tD_nE0&GXKS>|{AcF2}{5onEY1^OK}{9T**bGG%wFEB&~C zxc1ZPek||%{*=ZV0sC_Dy_dM;9E0b-r8cHArLNK>HIa{v5>ZB{mX;$k`?ZMLlzZkyeYA?t?a3OC7f>2I@rPuR zRD_3%;~qsZR?UUuT8VKbuJ){)XMw!kMLGWVrH8shO-e3Cl4D6fZuwI^xq z1)treZA!5%_3Y16J8660z6AAphSR6J=fS~adD@)f=C`_A;FA(Mo8^r#O5G#)ndPb<+VFBCB{c0MATI z#z%_Zma;rgfv^1e53u2T{{|2CzKUzV^gGBByZXmMaotNKkmlf-o2JC1u{@=;GOu6% z(BA_Go(Do6Zc=FlncUHoPuQ-pbov;m@Ik$frjaO@fPj52d;ZC|-dfKKgvr?a7!x4h zRXRYyTI)EvuzQvb3Rt%zQxnmf=tlz&RxHDNpMC`ZN_VHZw_*kU>T6#`lBW3FU%!o7 zqk;EdeF-<$tt-qIqpW1|UwD3gd9prUzK{&Kayux4$PxY>jz9%gizvqY6yfjru9k*O@f75EOOx*9JG@V-OT3u!*e!C}))%`IIr@81btj58V zj^ko!nP_n@Su}gLgzqPKlIuQ8Z$NSh)1YmuaCt+za5yAQH>0rk-0&bK_UwwZQfD+h zHj2BeS7H3@dE^ndnvz^w{)GM3F$R8}sI*@DJvzE`|30qVxPe1^_LQc*H#LRhXD85C zujA!|&z1ULq3(RbHc^=^;)u9PYg8T4GF`EcVf8tun9q=@H1W6T*R9wpTIw`L5NLK5 zxN!s6zrW+GOSD9fnW~Kl(immw`DQZKc3FK6aQ&^zq*xyzxf>hSV{UM;ROa`Oe}uVz zdjxmZrPz6B9P3}mKMpSjZM|>_+s|IW$b*MypsyWu4aX|ewi(=t%80YYue4zbUw*`+ zztZFIyoREQ-P|9LxK(3Suri1eb6@+Rx{pX7L-!vWf3YQKiMTY@PT1$(Gks6`uGEL= zsr-Is{a@{Q5yGg3i>+l`yiG!$Bn=DzhYu$>dNf1RelDp*F??8_ue(@-E-&T*mEl(V z%z7YxpNLa2KBxbaz7C^+CT>evLTNR~lD%F}n+VB~&HK4bUseO{y~<}H2elj3l2TMD zOM3rS2XYGq$oCQ>uV3&tEc-#sAB~qowJS?ghLOE^CGQ7C<;3uRtZi*RFCJ=3v2Tb= z?&EG5owZn5`XCY?##>cl7aHYBtM{kvaUuJ>ltsr1xI8pjyWX1c9OC_VSFgmx-d(u8 zu6#lCgXPQe@3|Rp;Mj508cp;gLlYUAtvMhGvi25OBxQb=zO8CR7}`qj6t2$*q3;ye zwrs@to#S}0d|9d7oYGnix7MxgD9>WiaHhj-@0=L7q4H#zSaQV zylx$ahlaZ1#VN@$>_2uK8?IbO-$J9Uy=l|1@SV9&Sg?4cxyD*UTJc~RbviFvE%80~ zy(H$=2-x~@)`#+ZJVT_i&Yu9c z1h^UW(1asXA+R1C#N^9|u<^~)7rbf4!C97WSM58Q z_)9R1_a^DQW+J_nJl-2JmD0+hLzgx4EI=v07G(~$Y*#H$24LBl4={NC9Ik)ro0xj# zH8h6CN_a}pNt~eGhzGKzBLL?f|D5bOC4O*B21ofgk>yMCOl8RXG+{e!O@I!&ZHLvw zP266$7AFtvD`=;jHeR`k@iXU;04>m$uW+xoN)Kh{YoKY09v{=>Q1PBGfAgca!s=(5 z2G_*onpHUV!XeBJm4D;_au7Y+a-!b(+-pd(4AY|{9Up()DK+}~aB1sSq_r9je)tg^ z_hEv47!TUX3~iDMZK;iVpmLoAkOt@s#KwrbVMPGi1K6HyzCP;Qa#t&FiI%9C78Za; z<8hZ7g9Oz^fu|ih9|>gdLfK>stz4uBtS7^F+VDT|=5&9>a{S_@7b<+N0Y=0+Mo5XNUWa}T}$$w`S{4@q!GZ=+IHa~=puW?ZEpDvn$HRi z4FTJ?0~aoI&qHIw>iLRvRih2lO82KW_d@JCG`Q9(Y^=%)Z*ge_VqD! zEJjh4v<~vxl0S=E4J)0Gd$r{$4i!s(!1B`pS8p0Nk00npgwsYmiygB)Njo)fg+R9L9tYh&a}_`T!#_v;KlwEr z*txSX?bO3*oIH09`^Lxd;ptO2uyYss3qFeY@exfj7ASvv_X3}4A9=HAp11|Eyo1j5 zeFIxgu^f`hEZL)_xw)l}%bz5=cMrI60hJZ#KYr{h*u#*1~C zTIchPDmwF%Kbkm$sT0RBzWdWSyl+3&uU=g_Z;ZB|zksBfV(W#=7@nGGO}Db=G|FYx zHrniO10uZ!J!xCEkZoz6SM%cc0FH0Hx1jIav~j=5;#=DvJVae4P0S6wCh>T&43ej`wlQm*rzvYm|G8~Do7RhkT1f*2E%pUGKZDYg zV`aVFn=HrHEn&Ybwh5)#*7s!&GSX&R;d^bkuA_;&YgXahuJOu~nCAuuacSFDBw2?3 z#sX^16q_$y#?bVvs2|mWq5@&TFOL>jd8wx1Url*Bp-%T!uEf2SD=NwTaiW{+*J1PJ zD_D8wE`Shu3H6r?$TQY{32V1_Od=Eah_pA-EouErnvzo$Odm@p%ksu?Hz=fgpXb2? z;M}e1W zi&HfF>X_KQtE&mym#$yOwc9sw_x=M+&&=S^?mc+rxkKpdVYlu;{R<1&dFCv(T)2!{ zGh<7jEH+DSkSg^bUCm)!oJf!$c@z~ zR#yqGrQ}>rX-cIj&Yy7;pP`P10MwVaZN~LY8!57ClrF~0lNYU)?!}M5pXB2k2YPwfi80g2<&6@xK`#(I6 zu+o_a5^@(PL55~)H90rHT+))|7p_CXEg@t1L2@4SqX&cBMYJ27RslJ_i z_9ku*4+DGlB)D*)H(eIPsO9;JbX_@qrj+G4+RLZ&#?n^Pm%3~nz>&W*)z8QulhT)! z!hdyw?{qmzz)VvSNAjjU1XtWsJz0H=TaNpS$ZyNI zukNF3Ps3^)Y^_jy!ZzBLEJ#vkc#d#$#;$b@csxVfJML*@Vk)+_U>ws++?>lkH#Asj z7qCv~!SZD|w{sjDu3STc1U00PM>zAn!l*{FkJ{LS{#!%&SX(r@coz@;@IAc$g`K67 zwnv7Buz!3UFCBaiZ@&LCq-k21K1TisvN}#%`Ng1^9}xcU`wJuk*X?n>-Crx_$kyDa{HtwYzHet zABB0OR$4QTU3q>P8IT`_J?!c|FS-u(Akz0F8l}2hzsvi!puJKV3b+d z`j{n4*n8tOkoGgDe8O{$rI(f#N*=vaHQ)C$Y-4h7^-7%EHI5q_)|>V!qbx~qc2|xu z8~uIQdhQa2re<0QI($P-0ahdJThX|c-UGKqc7M^_lexWa4W^cL|4rga)9tluF!o>y zqxYvklk3Ci4fU=motUX>qHv%0g(5rNE2g#9pjzzRE4Le;qjOB%TYVoq04`n1uzmZ} z?;9;q_jLJk_Q)q~F9sEPF4esZ50ydO^N?AwTv86M+iT)?uIC$leK@_h{NzAR7p`8x z^vnz%&dy?XZXQE}gIKp}H3s_o@zQ~V9r4mM^6(*6-<(AM{5-}_pKYC4(It{A@<9U#liu$Xxe^MUZk295; z+aJO&AqD-v7}-_b1SG$HswZuai~u`!p0moK3LDwE<5!e z=FXnM&9RlJ?>&UZij^W?&AfG43RnKNhj^yUGgqnLQEWK;npp|6cF7XJSoye&v@5lo z>`Z@~xUy|?$45WS3=iYt_HCFR9mU|>9QGeS0U)2WmP=m;khP&SZ#xO9x%{$isSd%# zko&vbS+g4F$9Ghg`Qt$I0|U6TYE^sELT*%>?OJQMhmXS$WZ?H@;DN@t)cJWy<>Rev z)cYZ{ssLJZh~+PKSb7ZrRHy0beAP3MEKS`0gwnZl`3LJqNmWBLo%@~I?u63f_NQtY z)~0da(%K>o|3dj(pWj=#9A|g$>Y#o(HJVMl{qqlyrYSC5yNb>0*JIy~9gDKc836Ww zbOM_$Uq%01qjgj?g>;*3>GPU|u z(Eu$U<;av|#c_$UGORw5Wq7!+2pijX=0!%d1l?lNPR6{pnDjfQK|7;3J|^<9m(NXN zON*PyGG)&1U@0?kpQdr~9l|Uow337;)Z6l|dA7g=Z-5vWEt?@VI(=okhE20F~yIjvg00&eoj?Pr*#r-A9|#}##XoTTHez7_U=$Iz7Yg*-c(w6z53hXfh21o*|_7trW0 z#;s|Z;`;5|Xr?JXedzg)CTx#An8LvP9DoFCZ`{K8nX{nXvVgSpVL1OSr(jVOw%&d& zcijf~RvQw(`V+Lh=()6r{5jnR%g@_V$H*l{hPcnE*w3V#iMZzR4X-~)sbxM{nk_v} z#8XNm^J^=hBgy1NX-?8-FP^w9sT%gR_U+li%iYrA}0pb^O%lpMR*q6U5y409g ze}l~HlBwRq)5~9kqdBrHiZaD|w;Wmexz`%rX!g>{_<%l3x_n&3w1$kxW$K=MR&Bh7 zQl#ec@Rj#YEcs8ocM|jO^)nkk$eec>r;}*3_8Dz<&SLDZux&5Isq&~2AGZp_jt^1XmH}KP=A0kN-yma6oc5d0) zQT`Z>O-*5VdIl>e?_&JSIb;AD=x4LHxMk%hUGaMsgNGJqss-1ce^};aXm7=P3mUge zPty01>00`yF?{ZGx6uL*qw74D;{8F#0yH;^Mko!pQx?lpN?kLJo5{b`xJgR(R8QIl zfYDK4?b-wr6WuGPZoqYMXrkC9@X9L#)-gEt=zulVf#9+Y0NH?%KC+oZ2PuumR}bfM z*N&8lG!eh#Cw=uu?{nPpGV)it%9dj z>SWmYJ=@~kEXiH8`SHpU{GrXudz1WL?2Xu*Hb|jco$qbp?d{1|K-XFmw$JVCY{GV+ znUP^!9@&Eag$2~pCU%{gKrIUpFhK|dfc*<@0!=}uKB}ED+0I=46t~x|#<|@)aeM9J z?uzy}Xl`f_XZGyE&eLa+A6C^w4fR&5$)FB5%b_ibz#!?>IQ0%dwSI|BUbADidf6Wj z06jeo+`5%v=g#f{_!2$6bo+LOsj0_Zsvj(?LKc*G9!MFFn4d`ciFk%xE;LzqXRVn$ zO<{Iq2shWSt1Rb(>1lj)b^^`Wc^v<5{$G6RAN~do@7;%0%a&t#54&{(K>z###wX4J z05)H^g8D*Jta8rUQs)ziI7p_C*fvBU_wbO%PQ^p-UijVv(9)~0p9d@`rt9!qdNcB# z^<8!U^824Hu^Vk_y=dtJ#o@1qpENG9dBXoKQ06i{8@q)S(cmEP`s)eadMn@gq05a@ z0d$9*^L%AGtlTS**i!bH7*5dn^%Y^*YF-z~;Po)lut}T0#M_)txTi;#hYX6_N0why z2miTkPp_zdwnv|?8%;(2h;#5?JPOY_%RAWRvBW~X* zrM5U^(?eSQPv?;#Wd5PIhNj|U@iqTT($O2?*FmZ<{fs_3$47JEUlZj&dh&X|U#{l| zcIL~)=>6j#;ZyteW5b&6z6$m)8^)^Ln=m@M_&bng$af=O5N|~KM7kxss11J>r(!J4 zc@P%&{DnLR*S!)0ms>C`RWCTXQ;ggTO-}>;{Xnf&o_2|zK01Fs!};^wI-QIm7uiSJCyOuftwM7P3;2^C{s38rD=3F&W^mxxajd<0Q%I2_UvWX! z*;;OztevoHzE7FPq&4wdE;iOyKX18|wL~Bp5tf)%V_|)d>SV2ZH9s?yDxW4wO8Xo_ zB7oOY)&%0ZbCQ^s&J04)o~w+&RaVcw=WjAl+j}Ah$ls3W5C0QK%>z; zkHyEw#h!r0m*qT*Wc1#}Rw_J+`3Bq<;Pziy z#`yLhIggr%AX|SU$f4`XpOM`sD^P2HrRCN_T2_s|JP)9T3=c;}Fu#b4gJ*{aF+bRk z{<#I#ior7pBb}t@qgcj+c$|aBA4tcXJh&fsS9N}hNw;+8{(X#%jG({5hBNo4r*ZQ9 zIrR7SVgL9}jE#&$(wa^7*_Zj)~Vp zdQ~zWr|nZB?xl|Y?=1G4Wf>;#-@}oUCs0djc;(O`Y~Q%4V(vJNPEVuWXkz^AIc&Ui z6;0Gzn}E^z2zq9ho}6u;*Uc6x9xg}wp6BauT&~al0ORZN0_+=UwPX92M#okLp2zBY z{#*AQzc1-`U2GG}N&Cjq!}4vJ9y_58t^Fh~U0T8NiQ5UXr+?Bmkngy?WlL|z{dEJb ziomjj-NZ#cm1WEN*>v7epWV0vx8C>` znnNR4cH&*E|Fi!Ulb`t;nBH?Z!rL!LmL-*x27+4om62>w9aM|8W2_J8lyO+E6|Jp< z<>`aoGV&yq<&I7K0>h_IU~a`mWCvcUFkxFh)1hQ8EjNkU{BaYd0kh^QO{Q)U+a3u^ zZKppIc!_~}eLzOeQ-<2FZQ9t?gl$d>{r#BOy$khb6PwOoMXiwo=B&NDcc^^`4dmcD z>@S^(n(DxY-C=uj?JAtxy%V?Aef*Z8W?6>gXD6_0>$d1FW^;psI6pp)U8g77Bi#l= zsBHrIj)gVai%A?n`#qKPx~Hpp0j}LyH=lZu$ae|SPNJ21}Uus!Li`1wNoByhyh{Fw}|JnOtl*D#v2KK^rH;- z?%|2;xD6EbpK`B2ds&@fYFSncV|uuj%g1qZe%Ja{nd)`2WGSotm6&u?lJz0|zFQV( zlPS4%h}k2)kfn^`_}yBQa$dUqWV^<(rN01D=PK%P9LpEURi&N1bj9SQmHJp(8!Ca@ ze6HucP%KXu76fbSCoLi08^p)2L6$~y9s~6{64s6yiSv6v4Yk&;%(Qn(K+BdtZj2)FqzJ0lr@zLl?lJ5&ToI`FF5(6KS^&vrZ2k(#ar@a%_)BSzM_tO$eh|kmG4p4 zHpZLZi;=V$DZ9sg)!f&Xey+4r93c?yg-9W7p0yDnx7VgTt!G<0u}x14z5H^5_utQO z?HbVR+$C#MFZj5shf}rO80L=qQl8gSjK4fd^p#gWVQ9M;n~yenX7{qzv78{4MajG$ zSFt`C&&B++q|Mt>b?=Rn)uEKmi|dt@#C3r#&5uRcYum4EJ9>VxPquzm6I=UHm14Nu zub!<{9R|PB(nF3k^w@l;KL;C zh1m-OeK_{QbBp?|c4F^tBw2>tC(p2Pt!IB|tZ!={>JWOJj8}B_Jz}xwFTVRdy!z@( z*uHHG>Lte){rIhSuwmnR%%v&bJ9ZRbdiB$#{6pQE?&Rwjjx65@tUHn(M<@;IF4tJ3 zuX)S~J5yAqwVfQJYum~#u_tFSEi@YV|Gxh{{Ki+mh7|=T9F$R#Wf+*BZ(kq&;0RXS zxz}DG&2c(eSQ%Z{-=O)XVzTB%-iOBF)G9KPpOcJoNKYs3U($WgFV*SnZ+Xx9RuK1f zfAQY0#qo5%N`Hv?yS}GSy!m2KokrtknT|@}EmLL_pNUD^V`IRsT?sBuLcT4_JFVW9j)bDS>orWC?MZWWXmL2;%8wX)?El8$4j9A-|k9MEPSAxOM&XaP{gp zyKx*hzw+CdTfYr!-ux4+{P7Qv_7CFW*1f29E~qYxD>?p`KbLvRT+4XSfm+E2&OU$r zK5cn1S$s$@;Zvuh#;<*b1WA@+E+b!yh@IDYT| z)?K-QfyR6*WSk)1bvs4cTDwiVNlO{+HMs`b{kXnq!(*GU-FP^M^WT04JAeJNs0|dG zzecl(b5}0o`s8gSNrD}lH)D8kD4IUr2Xw$ej~qTaW5K?vZijCL||B@(R*{Pf%Sd%Ir6%Ko926gh{wkRYF^5D;d*BsdjmGSmRj5dr$TQ<}JZ34i_GyI8e+ zIez1-U+bDrE=&IZq&3-`NRDa$AmeWO$;Xq{-?)JnfA#@;U!Jbgy*5NP0Nvw43eUsT zUTdJR-yGM`o_?@8Fpf_pE|xw+5g+MulufFxiuspliJon$ig!cWcnr<*kO)nu<>*Wz ztAst5Xi$E3twayzkpBJu8_9q7t!n98lp<+;)TQ0KIBumh_4a~d{gIgKTYp)W#I5vO zmJ`$0p3b$;Ery24U;K<@@Sg?gxFnwCk&;sX(1%XTT2KwE_+Y$+JRg|17~N0Xzr+8z zuP*H(dG47=YbS2Yyu4piEeVMiPuzYM>BScl966HV;>F(hbc>IRk&Aqbos?V5w>-a2 z6C=W7l85KrWTH1o_L$!BO7C#I8i?C+ZSeVs$mV?IRo{U8$ zOFuT2Hr97|E#tPfN^GLM9@Q{*jIaN!JY9Jy5-*25GE&QNv;3wkqt5!d{0&uxtp$y* z3_0eh3(J)tYfs}&kmF>^BV)Rm`WGVKxu@~7*IvQBl`BeHr&E&g1uaJ$i`o0K?{RDR zB&=2X``^J|{PqQW1lxA4veAo==!?A=kEwsXqbIU}ee^^dD4W;F20@Y0Z^1k4C8Qfm-1=Sv|@Z!RSY#z>Y{*DQMw{PsRK2k!`hC=KRQ!jNp@R6whA8- zwBpnMoFz-tiX%=wAk@$%{8|`Yg~```6%Y1(2J653ZLEIl+gSMW-@(HA4aiC+Zd(9v zl~XK8N%!Ki`)z1bXROt%jD8?P@~Ps0#uaaw(k>#m+-4Jl*Uw|c_x=!Q%;DkQ{p|_c zJXomZ_m9Ys(n&L@fhn0b?GzBm=1u{bE-yT-M=wd1!M3L~$Xww|#{{fg0@MNU-(9@| z$DTikhohsF-$50+w`v8}EZj!Y$fui=>EZ1~wbcfmzYp2ADH6E7;E~eot^4?^|LC9K z8z25tY}vI9eFbBEZh8ja|6l$XU;Eu($J-zN9LvYXFucy6v|Z*bhIa?|5 zRKa>`@XSN%&6cj_`D|F-+HxRf5s9{apA5TDtK~b29XXQW`t{y;b%UKLZFMFUNG6=3r%z z(S>3^HO5aO#_HtdDMkU^k;U%vZd?ajf55}Pa(69>mo4t}K00UUYkk;7J5AcU4j+=6 zXl5yDS+l*HbU>9{0*Vgh6P0Rg$C127JaV)+v}4m|{MOfh8MRt9-Wmbt*sc!wjuXV+ zIkham4v~z|E>AtBndoWS58_9EdiH}NBK%%)G&Q6NHeGu^#TH)cXZ@5$p7bdwKBeu0 z#>qTC5Z84v>8k4gUhwfd?__xCr37o%bd`OHKEd?3wHA;47C$GA>thxEJlqFJ%gg<$ z0l5K1uzF}ORI1n(V}q#u({JLNzy51jwW8XDsMp?p2g~k0FdutU)LS2lrLOgM&L&Ha z_QY>lQ_|7F0|3DC*{EkG(n!oI@AK=JALV&7W#1xX+L$+HrS{_)ycU{Y;_$O^mtxP7 zumafv9|LgBAMA}jDMBs?<@^IS&cxr4$Kv9cjo~)Mvu%qNxBj@$|Iglg2FaCWXJX%b zndMOhpkNBV;o6{q?w)pNH)e-p$Q8-qYL~-h#8Pfo(o#z*qzG{pQfNaf_e+$55gU|3 zX0^dkNI^6td@X^(bj01XcmP_X4Q-_wtmH;=jJK9iYMaCsuKD)X9i z&%N)yd(L;Ri=yn)3tAa`?E6Eka%B$7cM=|}e7xI9U9#Tc=aVRx_htSq5_zo}$kZ9H zxXo3|ZCB1(mccCci5L% zwTv=6d_?B!2aVihX;QC{HU;xA>+>!NFZ&3IKV_|pGOY|&qPAqB)~4VTv}w!LL%)Tt zkGj6=pK6*ST|whc+g&v@+bts7L;BnZiA!GeUAJX1egC)qTbzIS14O@e5D)#`U&J#9 z4|P_lBt@E*^VxmnfBIcCY7sD8@6l~v+85!+`z=?6vgaV}2_DCPX`IYCbiQy~^9rTW zGVA=+G+F1kI!S;Z|2W0-&qr9(-6gVp>XV?bjkr>!X^cZYGaAd&Kw4kV>WxkQchXTw z%PZ{j$u=0>nplH350^XmYoK1ox4-#I80ql9%dO|m@fr zN!z65EDh{`e2YO^Eqxz-!qH0$HubB=kI>Ed$&O+;97$npYlzEP)9E2 zOZkgr4jCHMVI>sy%`ACZmH~i zb{Tg1BC^s&NrIu7X>9(%pWw=T1LuD8@1wcSK7CmOG9IqMng2bk{&*Y#Xg#gyr&v)vOtkk zzF;Xr%HN{dGncV+V;-0o!qCPEjCNSxBu(*`KYIn=-tsN1%ef9Eo^N2{pMHcl9(xM| zV}q#I!s@b|0}cqk?<+?>D5jXQfVT{Qt_Ge%vaTM0PE+94t;}}lm1Dk7ed-n2HeDI; zQKbY4fl`%i3+W8`XvD9nSne&k+XA z`JlUOUv!o(&qpQZ@!)8Kq~+z36&(i2REh@f_Q}2X8VwDVykMvVb%LEKFHxsBIwTY2 zw)2KKO1Fu%xtjNpRD@|a49}&VKt8VXuZNa$YKKl)3fZ5|4iBTtYONl|$RVsAiu2Kx zjG(1|28W@q@=ofMYeUQ(~-(?GrIM5$~gCxh126fVC< zx#_dkOOfK>d++1JLyzLhUAB65>cRy)^x>y)H<~nCiv`@tu(Ws}g|kFt{VmH^_FCRE z`RGXc-S$LidjXK|itLxR^PJlhzCEE&feiWEz|vcBx6k%iSjZ-r`_!lIDWnyvh3Dt- z%M6eHdc^kir5ly}%}TT>iNeT}+llQvG&G2B{l>3iFO&E8=5LtSsH6pmpU-rUnlEGgzm8aii z4QwCqy+r%>N7%U&xNsrGXP@0}X+p%GQT`YJsX$i0#IdIgFMfXdO_37#R zs`J%hI#r%uLf5T2h1)|v6Rpv-ggT7d5R_Lhy~@(K#oN+eh>Sc^E4z4Zd+7Q}sda8T zFe+_JN@z;sejdittsF@mUF``c?OAo}%_M4~ypwa`mmk91!4VvI_AxxXdru{KIDP$( z|2`TUMzMDD`ogrso64VHp0bZ5dfpLY$V0-kr9&aw(^FJ7l_sq<*MmaipdKl?o#FCJ zo2T5uZB1p;bVJ?n?_=vetppWY3*GScb!54GGQZR>zK7HM@!dj&u1qvb>RXA7nd=H+DDX}(6+9s%FplD|1_x2!^|--K~Dm&2tY zy<_!2t$`?QB>r-FQo%#t)@w;7v9~R6dhaaS27o961_!h6%gaF8#h4|*W|e$-25xyk zou%dgQgSJiw|X6tX`GbJ;ZdCbm;N@k{(t`% zyMO<`#Lb7E#<^epySTOg38bxsn)#ql%HWqH!GE5y#~mCR=<|WVaYzha(qOjA%5Tq5 zkFlH>RUHLh8EJyJv5euF8Eky(9W=)#aO*dI8_B?6ZhqfoOlnI?$V>BqFntI>$4njS z{ZGE5H&x|3`I7cKC?)2S(=hKAipA=32icoQZPTS!G3sdKwpDM*YRk-_K*~H-AA0MX zh});ERUKbn`H%hxC;s`X82FbT$D{wjui^Q}pQtQ-6vr5z97i-Xgs5Pp?#R?S{KmU~ zSeCQs|Fqm7Bio&z$JpMuNNDWWVMGLuC3xofN%F`Dr?kY6YGL!zl&>wzQl|iVVIkY~ z{Ecr!7#QeUj6U7r)M#|>EGauy_0mnm^_frF;<1Eps+j-)AOJ~3K~zAFOsnG}@!P(9 z$d8Hhf!V+THb^gv-98_gz~FYZG0=tN;!QHL}|eYt^pvw@dheg$Y|wq&z4 zVV$NK4{M4Q$!ZHws$y7Ek@P`Ar1|Ytx`x|Nd4nVq_E!Tr@Mjn?v2oFc7NJ7 z&^dONJc@8MPg#X;w-`B(sNYEYsmST$r^~lz^m|;bkLEerY}B7$j^BD={^2|}zVu19 zm(RbmXIZ5MZ68B9u4P9=E1f^`Yn^X>PrY= zu8~p1XaZ;|eVgT$r)~ool5*3s*)*g>)?^|1NM0^qUm4Q&fb{Q3&FI24+OpapL9Ml9 z8yLGei-D!(6|6=Rb}BeL|lk`aL-=Yf6Vn{6U&1GIQqn+XyhF9006h<=J4jx5AfxupDFZ54lOR?(7W$r{grD- zQrZkdr)|?oURj-_2G{tOd%4{tveu=P&zc}cAP=>0qFRpH8_-W9953T2-qIH`mG2Xg z+9c0@lKsWEkEDMjHTY|3HEH}QZ305IKBvqM%0kk%z2kbZo+pahT)AI3WwE}FBhq+T z>y&$4$Bd3Mem{Zr`b|i_&vYBM(mmTW!gE4WaQuN zQMyy=e5~TqNbTg?1W^AeFKK11p&f!Hd`;Td(pio){zALw!~go%bJL&SwiN@5%h>+;*;ZLqo^r8NRrS+T-*^EB7N5lWiM1H- z;`ZtdU)bAm-h9&bmOSOZH}6TY1U|afqi`go${WKamZlIYr`j{DVwZHH*}JiOjvh^M z;6Q|u7whz?Pd%r6FMFq>hej*>&DFmp&I)+|`PdRcZ>A9vs<9m#@UNWtBcK)|?(y-;{OL%u!!~-#@pOG84W8q}!=lzHbbO4I&Ut%0 zcHo+R@iCUCDF;+Fua$P{-|G_xed?ZGe?7&_%*ye%d!GdgIvXoP`SNsto<#I@iPR}_ zf=-tq^JI?TW_zb|&0CsNOmBbu5#IjjL+shUqf~lF>#knIb3c16DNK;jp%@pbA}4MR#vV@J%fzK{Lq#A(M{t-4=G3CJT)7w0X9F9$@Cb<#X5YUO(sZ z?qWAx!26okOAgp-(oS7nA6kfIUkNRp!_F}rvS30|+*`D69k6d-geXdJ;X?QPLfEw$ z543pXkwl->`1|;!2y0tDfxNm>-_!Mw)|f`oGQX9tbIP~ktMjjtCm(C(qM4} zi|um=m0C5ePQMa1Y9}1I2I4w_pB73QNT2heCzHAMmG0@xE@+tghNJV$ddMt_1V9Z@ z3l#%sEn#-2g=NdQx$lRNdxoXy_nI5C*!$UW9N*Xb$y3(?Tub_s<+7Et<>v|0ly19o z3U|78wy~M6vfh5`ES3fbF|%Q^=XK~cZ997oyN{p5nj5oi+l!xp!+Vkc2`vniHjN&y zZ9P%WzsjvE?$6{l1C^u4==>8?ib&^ODGb{w-;*a()awz}7atPWr@Mr%T}#orm}nKL z_jtEk88n9BNGpWWcwX&`=I2~5j1J?ohxX&*)KsBVOUuhRe&#f4wHgi|dJKa(rw7!U zO>Dk+seOZ#Uvkv`XivAE^z~2D4xQ|!d0Ad?sC2$vCvmJsm_F)ERh;|}@w?2d2KPzu zTJTbctM*}}qBZQ_)_*BWo+T-D8ZX(_GZOihdB37|o{-MbdcyYMI(hCtf9vEVuxl4^ z>Qwi$ul^$HU@xKE}z096C1H%a8zis6z)uI;*w#{w7tkHZikf{D-zIQ zTV?3{XancRmjD23hKlpuTC)b%*RI8OoMkO(6ZKO|b{}(dyP<5~+_KTW<@-*c?Ptzn z^70kYBecC|VQ3=X=cdP)Jgb7Yy6->peeJSDKRy5Ec&4h9GFZ8+B~%uluOwZ*3@k3* zRuTHN3X~+k#~-I1KkIJhPgavOdLx~vZ3xSgCv|EHe>Btj)E@1!+>66QxU#YMX2SW! z1)RBd8TCh}@bu$PV7TPX(0h*`Z!g%+Zn~-oZJo3hZF3KK78gT%(k-880)EH^R344B zHBxmmtA49-;^_dcBP|^6+hG+sqQTs>bIP+iW1V7|XZ%(zRLq=~Mq6lI09UfAx?4eQf_)_0y`|6l~Fh;1?Y4RwpciPADsmR2X&Pqq+>QUz1l>pjyQ947xjpr6Ph6oAme6H61TF>ZG zWLk<@X-X2{M?XsO;)@X~+>FzwKJ|n`Z&7z(Jyjpy>1>rJVVms^^q1Rk9+`GKzJD)H z?Auc)oqV3I>F5$7a-$Rx0q><^$ z;AclVZ59@(FsuGWZQHB<%N<6Y^9b>EWRH0|tf>8}T90{c*bDp9_YJHx(U`7V*Fx(u zZ7RYwa`D3nE4yW5HMWT>MvB?-QA}^yBt~c_r7Lm$%r&gLaurc)0W*+oP^}?tFKBj@ zz-?=$6GkNFidn80Lvst5I)AaJi?-L?x`pkh&$7jGd~#g3n$&4L-ub+;i;Sr?fwXn< zX_j-t^c74`ZMx$ZZErbu9uFM<9OKt-sw+Xs&Z2gr|Go|8<7cq;)a2{}eOq7D&g+QV z6CuaC^uH1BkWY@DtS&2$KhL`wIJXnJcoEpL1^q?aed^kV%jexGg=H$1mun6?o{t_H zA4~lwwZPKQ5YFw`R;~)y=dt|H-ouB#(!i6C9LQa??WFc=Aa9e(PWp1=s6K*(*T6b~ zJKuj98k;!^^pT>($6#socOK7w`-&dHkUl?^>w<7 zQv0X_Ei1vrSg4xgU;P$DtQ?JteJyGsnJ`J+d2iDAcy=RIlB76u=5|X{29Z^_E{ZW_ zwdbq(Sr|EtkM(?swy41RoZr*wJCz;wLxtoIr}p3G5XP7MtQio_yNraPana|e!}!Uy z#eNO$H?xS3997BobLzJ37B?5QkL|y-wUhPR8iAoc5}k51#1W8xdzC+D4WvlZ1aDkD zk2hvcW5>uCHV+Q9CE>U;X_e);IHH>#vu)0P`}kO^>ND8??Jr_#_DKN1RK*3*T#H6# znEeFZcW#;0+O1~S>u#it)0Z)E{U#c%!)Ww|J>N2+HX#3twpQ|OH?ldb5uEG)EMAZ2 zzHN|q+oi_JoM*4_be^_Z9XfwL#qe;1iE5Y3_USI7BmqAEJiFz2C8_MF)(wu=WoYl3 zq_WstdP*Hnc~q8#Or>0W^r|$%uNgw^mk!|3haSX0y?8n7u9K&*>-Z@QEG(hXUa(zb z8azXafPa7oKzfOMpB#rv94}F82%pPCVg2*R?G}@$R3cq!RURf~arv_U)$9Z5Q{l*8 zV`=NZ&Mcd8Y>q_Nw&g%T(?qsVxeyaH$9N z*st}2Z%b-BtgH=|_pDt!FV)3I(ETV?JTzY$P;;_$on`gA+atJyE`KEQ`*7LiA%ILk znRFkO$8{D5%J&ORP6Bgt5iVTlU7b0u>6}MK#aNoB?zF6syTzJ>;AKT-N|#>RWjqzH z6{Y9=^IV`+sk7Fx-p}%7l)=kZzB2JPQugiSFwahG&v2ejv2it$^&#yfJuedP@_g24 zDm9CAC+m+}q)k(Xbu>|Hxw2ypk((|dN}OaZRjbZHu!$3`(czkm(XSK!W}&hW3> zqRb_CiSQu|H8=h1T4>g`KBPV;Oa24_JN+pSbIm zKMh|C-#$!~N5cyX*mP;S{oBdB>*Ohn-MH17$k59fBjdk(X3kcV_7Lf0Inrv)ET4dM zg8TM@kAyXL_7}B5aJDQJ3j-J9TzO+n-pz7wFO@toSM0-S+H|pSK!W7+B&Q z9hWCV1fJjWFH3Y-mS*SYapKfzU}mm#9$5;q|LYv zb8RbY;{3BxpG7LK)^TX3kvfov6Wv~a?d_yBYk-Fzj?ipo8=KQEpk}XdaWN*YRz{Ir zp_uX>sMPze@o^;5L!^V~ondTg;cZ*yqIBAW6{=~-)1|Fa8vmoP?j?yp(_KkBjQ3B=-z+s*J{{P*uVhL|+K0tzZNQp%OSx=dtwA+JKG&7Gypd`VAFOeCQ!`DT?2^j8x{;_Su)Jm+u0Q?~ zmZr92;Oucc@aA7&?RWnPreF9LreFM)$ydve=GM{9p9iS(@`ZVI>lCt`15uJ-^vuU< zwPS?AYnL#1?GgYWZltK)XyE4Z4QyDvh=Hq%h~hci+W9E1J^mtYt=)iIdml%$;0_9Ykrp>Rf;-H&<2Qpy(vnyxt#?^CpbbKS~EdVZ^ zbSjTI){cIF(moI8(!#ReJ}XrC&^7h79bLvt|ewqLpL)=p>X zKA;*}EyHcSRK@#1n%YR)hV+~Bl;Hrpd^(J$wL!6l@Dg?sg#okV!zHl6beN=ksggU> z9Wi_j!mpO1lrAUNMy~ZqH_DBXzC8I?L*5TGJPb@tWv4@Qi=7>Hi=l~6M#XqKl(R}% z(ynn_EIel0KKVG;#&{Y}7mcT#wrTmNq3d6U!g7ajZ`u5so1AbD=jzNZEK6aV-J&Y8 zlyi&vp>{q?^Z0r~I!EQCv0RE=Y~ z&1I~cxrPV{8W;e*MG@Q?+HM(IvpvE)m#vgCt51yKxdj~f;6q&5v;pV0ZiR8USS4B< z9>Ueh^;kP|9ZgZ9bN$M8&7MX!0w${UolbJ;xW&RPl{-lz4K6KV+u3uNyfP!~o3z~n z^pgH8tjSKK;hX6IZGmtsEPG^@%C}kaY#=_ylHDNf1=9R}9<)RK#c=+}-Ps1`{5T)G zua=E+`ZO>$)}L6u7wGu$&JMBZH3nWup8nJ%px+eVqekg8!t+1muhW=CqRnEudgc;- z{)5+0|2Ga}`_vTbwQ_#kyscCc>xPg#jo1G89Y+5e^ZNK!qd-3#$g}lq|0K`j<6+wd zlKntSBx}H*9hIhac-V_8y#Qp1ST!P}B9w|H*X4`b|>W z=0|n9yEY_sN+ToL+;T5AHd`38I*%%NxLi5bb1jmwSdKi|{6oA#7LSuf+jZd*!U)l? zQE?55%ktyPc*Dw+WsQk`y1a5YmY3}vCV#x)ah>+uYM4LNrd7-I@82mZAuN^e)unvC zmZk3!sS?(slea01Zmn{9rye!&H?}^&q-dzp05JTUVbW}7+l8WC64lVMV6;|TDL=}{ z+&so+Z?W=1c8wz`heO|_1<7t9UNQE4avTwWv%9uqVfgM^xV`S`H9T_kBaGd+g+^=9 zp!O8V`V+?Go*!=Imi5O;Y^z5h+ZWHv<~l^$FBV?rzjz%em!^>Ik#CdOWA$ob>ptDv z)NBGXGw5hzUlpxd?hP(qo-VtphPQO0M1B%ALd3c6dbG;I^gVs@Z0ZEF{|{OM7A>A(2h!t`;HVExQhM2S0aQy)kXwGR(-Qp>GY+5aZ10RW}(xvui@ zyyitXpUR|G_Yp9)EOY`*|59Jz6hHFHguMZ`;wD;_yZ2(xe4tVIH2*-}4n4T_9pGVz->(v0(E-X*R zkQ_Q6{g!ftfweZ)!dImD#2rVzywyk!EPiYrsFt*}b`zG?Zo$1pg522o0@ z;iBdMmWDTCY0W4Gnm4gDu^qMM7?y@N{>tHjpj!eqdx66Sb|_JT!&@EDOmpuGzG61hfHj zcCvQ%D_ek_sdT!=%GE#;DeaIOLQ)*Z*tum(VLDB`#Z&fM$`Q)T^H6KYaHnTVxA)yf z<2P^Op^rYnWDX~sIzadw+8V@`sM0v84IMr9XkeTN zl*4g(Zrbvc57NVQqT0Lu(Y00GVIJ=bU&P!j`W0 z4?n~1;RyS`x~o+3vDsN{ymYyJ!nSpSBRQ>o&}(UN4w@m-TGoUH%>MP#U}Xaw1p9U= zhoL;5v==Q4$FeE&>|NWDq5(C<`L(em$Op~EE`C`PUSIC6rBmKD){y#)17%r?G&9Mj7&H*yZH=MRXfiw->9ERYq|eh2!&m75;ZEi|=hn)pv=Roit(nFEx?VkQ@i| z%OGWZf`!o`oY=PqXLjxg*4d)#>(=7^#}DBPKYtrzH)dN}*xf)ynv~axoT#>yLrtk#~yXtYm$m8WRCFj-soUD{*5E#g0C{_IJ&YZNJQZI*|^ zs4V}wXC9v#{79DK6SrktnQ^N-eB3E6?$iBE-P>!nFP6S{$2ZUC%gd5)56324SK2cb zHm=cLP5HYNotQ!Lzr2o-Km2uk^M#iXl{xJTsn`g^twdQXIllVHP2NHUKr9U-9{$Zy z(nBD9m%iUpqeNa4nTBMue9ZYcm#5TRwX{+Kt0ZX$xwNFC-61V)+bq1ZN z?aHME+in3_sK)&N$oxEJ*NmZAa)VhJ8d_Y$o)agq>%=KEPzU$XTZ`GK-WtbQ))*mk zH=n-$lVhl*O`P1b8%uW(t`1R@rWl!<#}|J7HiqUGgeQjI=o}*vJ;na$w(?37ZLG&h zZMErGAAwt&rfHn#WpKQ0@kc8a*)DnG7EhgL=U5u6kFEREJ00tMA@Z77f zq0zce(&-a@gbANVcH!L9Ksw2d#r{d#gfa=I1BB0Q{0&x4IGkD=9xp$RWPu9z(-9A_ z)S(#dWsq3i_f}Zm2$GK5UXrgYQSclqjgyE}afW=Fmr1jYZ_4!MPn+pJd#druy^$Co` zG2*4m9{*%$6O#HE;>Ha`%h!?AhOs=b7I9Pqq6pFQG9sj?&D}!0xB#Rn8Y64a-0}cw z%j+{HaSe^(t(f1i74@aftwq}{#Zn)~;+iQej}D`j&SPo)6ae5BfW^tJNNe?0dsv2Y z*{2&OpNDosJ2fa>(4;o?{#AK}RgJ+(chVR)BKD1rAsQWRmDX(i2a?ul*!m&{2dFu? zNZ69?h}FPJk-$x4S93OXLVIqv~RW5s$a_E zYDWBk$;&giHL(U4w@j^AU3yJxuV2UB&yHi$#pxDUwu~@oNI9|`5z<7}ZR$exxR|da zc>m$Xhz8)?U?5pSfHw8w^MGr4ZDzY^R~GgVojR3baIk;c_Ps<&0vtP*cC;YBQ#-HM zBwtUka>G;@G;6R6a2)`a&IjAPJb3v-qaS3==KPY{tkbT&TtSI@No(0Kk3c|%dO+W8u0$0u`%HJ=OeuQa*Blv3Up1~ z;Afj(M&+N8m9m;VR-e!l5IQarxh#B4eP6x-mb_u-SaI62R2I8eCw~kqQ@#$9buNp6 z^z*6O6Fc)Obd$ex^0kQjOeM^yo&eoDHZ;qOhxQ6B7-cHV@afIceK}3t( zHqslvQzn-^K2WF}84A)G612I*XvwnjM%LUJj;v3WJ9 z(MYkp9ARK!)r;=aZKf*r+Di9K8&`13moo*}6sqQHV{DCqxg6SS7Xe6XaixVoaU5fG zc%(R8l3=Lqhvj(G|8Qg`$6p`m!QD7 zQLfzloPu;%ek;qmNc?l}Bj&+D;45E=@WUUbn4P_|uyJ{d!=>)D9PMH8IYuh2OqY+D zE%~^|#>Hzn{23CvHF|-?bXj~OO)sb%R^}4;`E)AsZWWhW)JFW>?~PX{6p(IwZ5{y0u?oWEZmT~Esn(>A7^j&roJIOmXxxX7%r z#_hh(#%d);dQF0lL43sGFn88xeSPHmGH-)O@#L*7!>CN@hvv47Jy#9j-e0s00F#pu zu3bwpGt(P>y#UwMUHP4sW6NrlZ>7zvD|Kqk%Xj;@@G|Kg?@lQ%uYRE<<(HWZ4PoJt z$ME?hk73=rKStxdS1@$tBGyb_#{imW4z9)E$49Y*MNA}1Myo}r&n+UYjUpM05ij5L zQZ%A5q=+!Ed>wJJgk*3%P#Z^m@j9@0v0aO{OtlS&mlhB==d%*x1W_^w42@!G-DZz} zb7(UbH#~r(-bB27o!X^7fQ8NWiI>Z3Cb2xe-iWaW{UXY9qR76M$JHN%wewXP1-@d? zaoj-A*Hy*HPSuu||2A8Twn;Ha1;PP|lQ?E&)j;mp?7XhHJ!Cr6&e+fe1TK zpT?fFWF1!gs9my9+uxjDg&HEEi1buNt}>5$Z;r~}W^1fX9bU`%P8 z!4Lw_HihEDqkJB?wy1k8SdPw~1*WFZU$lJ>QJMnBj{}WHaau2LNjt9>ZXg>}gq&UW zC~Hq}=yK$D`CE_Rsrb-{Pi|2Tm?NZ^*|-5W)~zkBFo5W>t-#b|skECeO=JDc)%GrD zA2iok93U6{@G&x{O^~kVYRJAxDF&<8e*sIlq3n)U)+IADWxt7Id$)M7w_O8@U^c+_}=$Y z%+L3Rr+y;6;fWT{PKf8Su(Gtl^2!U?LMP^#xom3=$c?z|Dq~fJZs`GNn*?g8` z(8UzBMsa`Y#;;JGq~_IU;Blx zl|1p)eOz7TMmlbT$>j%fA)%gl);O7;DA%qh`zxi9qo}m!pyI9ZjpJ*Mntdv=87vIV zaW9SS-Hi`buyIw~?daGspxI1u@ZkM!4c(tq1_y^cx_-KHy){2wYNiQ$l{E^~C`^{= zBQqNdNe^EW5fWV9v7bCp-YKm*udc&`*&#{WRH8wko7k=_Hpb61a9DZ)HMcVwnaA~h;Z+`Y4kd`f4A=K(}OeH)lZ|jH{pH%SS zd;zq28zFAr7O^m@jk8_3I<4NsQ_d?G8U=gjq3%+0iQ0UrMf(&^KP&VGtoV+ip=g6Pyc7&`v})+Y7} zhsMwp7B=n!>Jg%bfBfh5eJ>)Z4`F!m5^Al5*vsSVv9!)Ufp~t)ZX|=lUDu}^<%8^% z20?jFSU;`)Sc5&Fp`bJr{L3$DEf6hF8BK9{^F}o4HK87*qRY&Q%@?MDB;(aYiY8)Y zi?`iA;Fy7Fs2WQZ=YVL082di{3`rE@?2heN94>oWmQD3W16$5tz#~ULLYhR(mB9D6 zX&~sUN&3$(k9I~&%s6D<*IvDj9jDLS@r$-6uHV4e>?|g(-Dta1Tu*3`!Ar2?x}OLL^X^lhdQWA0 zthN`s?V({HQm%aNvg5h*$mHuza6rVWkGgQs3F&S%O@yDog2z6+OMasC6^zN5@4RTv;wG%N>3S`DOO1Mg1|m zh>Gfx|4vks+ojf5D(6}BnG8~cNqkHQ$043N8a;cL(vf12!e|mwt%XN4b>U(&ki(Nb2 zrJJ6-E7|V^k;jv8uB$KSt!1<^bQmL-8mv5cGn*Z#ZrPBLS0et+VrCwaROll`ps`6(4`GvzABU{MO$}ht$ zt*7y-=3(>U7cEN|on$4s`!!r{ zzDX^CThQiue+sg0IPP^iOlnKgbrI-(5{Ze+=@rYrdcXQy>viC%ry{)fUfR>!oPq9f zv6Vaj2}zGgXJuN8vMpbWPNV%aQV!Wat=_7wr*P|8_`Qg#^lhG&?8)wUI&R@ItK&`! z--l3Xr*aj`lNXoAx2k`^DybaCmU`Xyjmk9IW2^NEKjeg;8k)3ii5ldB?Q=V~+9Fy^%oA~xu3m?xV^!O-{|aaZE%=c+X@-R&Twr5QA_tEXl>+fHu2EM zpP=4o;N+g&h4SRlM+Y7OQegA>OU!cMwiOR^Xo+NYbpXpDpB=?GZ5biK@%?-8`JM;5 zlD*e-@cj?4;mQ?ZKSfE3sF59V)@ZFjAe=21Z1YpK?H($_q^HEk+j>lvsZx~&(AbzG zZs}j=IViov%#?<{N!*Qg+VW#TIDL1xx>Nh-lTT8lX@m#vtghInyPA68+b+_V)%}x{ z-bNd~KGkt)AZ<1Rp4{^QPVC=XN{%E+uw3#axA7Y{@zk3?Z;icfoCUb1kyx3}8*}YN zzniFueAaExP8U-;f3r2oK{7#~m z3w&1RQQlP|b9Gvt4cfE}x^D8f-{s{5hL%{$UKZ3^x%0?YGkGsTaXCe@&2QR;`Az(U z>MsKTE(SRI&P<;oq_|ZeSD0%jwFpsoke0u@bv{&=FGXa!o9R2+zh%ijh~^*e_Lj?W z`66vvq8lT{jr9}w@X!IwjTSFJd+Nx~v0?fOq9#8bBWX*NO#-`J*|qlD;Y%5}p=w5T zJowS4K!j}JcIj)5eX1`vu;cV;Ahlc2{+>zcuHz!mrsZ}!qDkF4S{NS2%{%Cr<2XsM z?&?(*lF9nO$@P~(hV=cGnq+zjCNydDst$t zn8NrI1N$q-Yu_9pIf}=Da&W@u)e9KXr#@AoZf!eF+=i;=a_&?P8hI_i?c~r9kV8A) z%_n*CQEYZ%O=-RJ&Llxp~1J+ zA_$}<@?ok3{8<{PF#a^kgJxNpltyYKT_fpY;C;_o9LUM9Tb|d_lG>G-jqU`DdA*#& zmn5NcUnreBOGfHJ$Csp$&R+`AZKrkK{Z4~}z|&7hc;}to-B{(Q7dSf1TT*$f9hS$E zH-w=xZayzRE{yNX;;S-kSOu%);nQyTIxc0)E$ScPb}o{s`!~C4y{osA&w-P(?6qCt z`Xm2@cx3ss*3wQ%m3XS6&x07O(aKN-w9KuLD3kEAYIDdN_L zqp;Vfytl6^efQO$;p{iIVLG~m#>o?Sc=w)4`M19GDE`Ku`~$>W%iWR^BI*tLo-)4K zN_tzkC7HAryeERMJx*pNI($n`b<*H2hSCsz4Ua0^9^qC5FNfp_^{{R*YrX@&^Kz>2 z?bE$OM~Mc{bRJI`xA~@Q>yXsBzMc(JGfA+NHi0$e zZ$>2TD^L28-au&!=~||$HQcQTcI~xQz*~uzLfT|`{l>Mv z)USO%tftXX;J|?hwOWb`7kbBcC2(S(k)ZveJc0lY+rg1+4eYzzbrkgEggST*5c4mS99bmL8o`^#PIwA zHe9?So<#$7@N?MxW&iSEFu%sq;?dy%**Hbsda@qeZx_!!PJUi)rBXSZ4?kg)^Q3f^ zCUAWrHF$9uEnBAyt+c(fumCJBu3!Oux(lh>9+#g#65or`hA@<$M%$~}*7U#Axb65z z&7;e5qmRT`Zq!>I8Z14gr|+J}stYs+gL zv)c1CG7rzEaW_xv+6?TsjisfI52YsxA#XdCFRA4$7MQmkfVKosX>=zf;+;Fc)u`NJstS&^k!O`t9dL)!>w&e5Y?fR$ zhiYKAEakO(eqFk8RLIhOb>d2w&Q-hQEVpy8YxU>C^faS31|*oK1=~>s%&i&4k;Bhm zxx@}=0QmVcPvPk!Z(?%#3gTu{NENfvq85yf*aB^|)l4RFwxpZyM~?8o$d zwv=mTgBC`Hapdr`c0mf!$ffTGKWT%BSQNuFokQ3ALf-~8JcrWAz7$Bz(>=Dv3UkMCn z+&Kt$DQFxaV9gB(+c5DB3T~coiMXRLLiuqnA3T?LFZYrb7J%htpycb^r#_YLrPXZ2 zeD_&M{}tuuFhuIZMC7rYa~gEZ@gv2@k35X&&6@)9D7rj{=<5#xhs*7Zc3Y?65j?S49K<7_Kc0l8x7cfA`bm^MaAyACGNN%q8}Ty9&V4YCB9j zOk})n>9WopeR?H_@M(J?SDrhTYeT6gX@@iQlki(3owT<{2i>VOHU=C#7~$iOQ(U^# zTi(6E(dEkVDU7MYvgkg{d53Ux7N_%A^$y$4c~l**T4k+PImNuBBeJ-EbRt)o{?=K2 zd(R`IyndPH#JSv7ydUN}P_zGT^o&6|CDW5l%#MwsQC}ICqSSE`HAxver_0x_;`Q(U z39GeN!XtY!TWal^@)P`y1}8=_IZ^(qP)E97 zb3IPD7~o44xOYY0aN_dI^VIos_U$Q&Q)7fiXYRFd_C=(4p`DX#4d2m_Loq$Tp(;e-HE@mu32iE;9EYd)&* zDSh`mHvIVsy!2lePa03o%;1ruAGLjo{=7iGZ6#}^PXY50qQtj(VZ?`*W7%yXne)@x$d)Ag+AW^x1nh%vZdPY)Khm_ zcG6m;9mDDosrlXa=%!{0{oRTWh238?F#+t~A0duYoIBS$zLq7^J5YufhE2Xlo`rL5gNe%E)UwIV#YtR-Cjy++j67 z$A2f%jfn{?3=bm(-A2Wir}0~?+-( zW4~kCuF$D0TH>71~Lwk)V{&*YwuGjcBK}ZgH00ZC!hfNL?$Dj3g`C zyo>R6s{Zrzp*%$`r74Vwb?Xohy~W7iWF6`svK4uGAskNn%jqZ5S}rDSV{C`LIWnQN za>KO5+SHb*`tAE9d_9;^=d%)bDNRlS&psRVd{I^}z=Y&ig(BnAyE3i1`C(z_obUGJ zGKOXL;ZFGD%Tn|yE~l9C+uYSR$>mqR{%G-{1)$|Vc~m7|e%r`;bn@J~0aLPMs+lw- zAWG-wKcy^>-u2A?M@SJx36g;t7RHA0@>jl8dcn4%H=lVLS2k}%6eC;wt(?A=1DI+- z0M4rW`;Q&!YQeUnM!k+#zWfrFh6fS1m$~Vyv6I$SkZwsiy!Li&%AuXz6Ye}Py*M<4 zm%s8QEDj8!ff|-E(Eco8u)PCXo+RdakaY$Nf#*z>y9sSN<<*h<#UZ)gSU`Q8pnFY7 zeC%f-H%1#{Jyo4m$usbW|iTz zpnmUkJ|Eav)_@#S__c#oDE*&bMg5JlsMl)c^LV98U@P^blg??WTKhkZrkscG_yow_ z(x+JP%Po064(NSbNVcHgnzq&_@<-zk`3?>Fyd~I`9ChpRyCmqG@&wd!iO_hw#k5|E z+x)U^Pjs6}>hYkyl_1<|U{BL_VaxUiwE+*;_Di1}tz8Q|_+W&osg>bh9(%0@<;xMm zF?l^ERJUS$R2JWt!M=HXs^+g&P8p0{C9a595mm*go$~IEbdM^_uMGP4IrFj5jj*m3 z5>>mfsIXUZdhOkJ@WVG=$8?FKUo~Eoad!Q*zh!i84hN2YSXkER@CY7!Yxs#6;_V8_%Hc1%rSd~B>!u}hPa%}xL7HkWR5XNTGL6WXby zUEpj3X&)reHU_ueVwP9lkmjRst^dhylu>?s%F_5AMNUQi*0RH^(n@R0>1p8P$rUc7 zPkl0|yl&AtLg(^lA*{R-QCfaWC?9P$l3m%j0iW-Apj@S9<}mlcS)9IbzA)+F;u0pV zU2jX}bgmwivS%~h4GpHJnr+=>={H$EVPz>#SjSntqqzOT2*GO4`<>RU z1NQ8Ruyt#1`K}ZuE;~nPQ~s!21sjLzr^ltdGOe*Nziwr)beQtyO}lH?JpN^HX+GYz zv|2Uo+WjY=e7Smuqp1Wt+{c&@64*K;ZKsiTg4A3zhf5fn><99LW_sZ4t{phNdl$~^ z+=1(BJHP$t{I;!V4AwnNR6}Cc$+CG|+c-b$`R&_qeO-4qGHIIGIEhPJHY+{G=K$|O z5Wj?d9qvCX+j2=&9Jhp4n%+P5DQ?WpR?6er!1at~`%_a-k-X(iNNXj0`>0&79h%LM z_KPenv_Z}9`_%vKQ9wQmZFk7$8^X+Yj_qNO9mRD0IxsVH=hUN5-P7D0aN@+uKGTpT zWT)+H9=WL8ym!>c+cq|rnx6jiaSD**x}LYYuw@HoCMQeDfBy0`P7KZ=`s%(?>79&n zl+zl8A7i4^%9&CBc4+^eCcPm?kD#_^+={d8C%a6N9ioM0D?p?RS&!j9!pSPZ-eRN| zaO-;}WGlNoH0#gtbu51SI6C%t%R3{bZ&}ZO+j>#gHxw^DG(0WQeRa~dqw#Uz%U_Q0 zz3=sQP)*U>UC}gXbwV^566ViOi%Hw5t@5n8`C)vh^_^|J3@)KBvn(YX*A4ZSUkK_| zE8B81+x+qXtpA)SPf`D@28?~T_v(`dZ%(~(H?{knurv|So)Xng+*E|ifxC(88`t5@ zXP@p$>bIVH5|6+AF1DP#fCvCT1Si`+?A}c6Y~^*4N}`4Yy(XuSQZx}GM$=I7t~I5R zMZ}FVu892;&hJceW|MQjyWXOKvo^-0D_t&qr)y5#E~)L zb(v4Xw|sv5ZS!FvZ7s2!pq<#g&prMG4(u;?vx3tc4o2b<0N0tRMRKoTUg#lwm95B;XA_g>X+5XkAw4z_xAJw0?bQIeD3!{PVV?ULROm!qoW- z`0&vKxn+$G597f{9|RsPf7=t+KYr4S z0T4Ji5iO+c7U}OGPH4ySmPXqypd4fmWZK8+uW&i z>sB_gynFZEC;R2VsYrc{=l&mY(2XdU9i>j1$Mu*O08 z#LAB~VVlSHMf2L|=NxX`3=ccJE4{h${59v-b~WajUe=G=(_Uzm#qwU~be_wT`DWee zUvwT>#PT{hERD+XGUc_gGuK~Q*Y%08agwCCc(J#*Z<<(Ed zh0C;fSSdU0wVGELpHuoOWrej~b)*=|W4Ckhb6j~U#`L`}F~81bIr>= za~6Mg=XTuc;Kn42E^eK|z|t~?<`$VPL$l1}{dUB|Xl~HSdw$#2t`?G8G&4Dg(Oa|F zeBqL4Bf$1C=w8A77b!?bySPyLJUTah3Do9G=d@;eH+T>_gvn>C?*5+#K-v=eJvmjPeneox`$pI4{c&OYy$f(no?EIcohA z@=x1dQvkR$wHa3@^L@zxaN+W0y!V|~@%gcn*zpTb6sDK*XpF|SqQ<*=?6pqTCY;Xm z$kkA`X957rhl2D}3#c#~qg!^Dola7yKTz!)CriicRISPeC=xy1_yh~SHHZy;pv;z zzYgk~l^ZcRqZk zQG}z19>wVgcIG|}=Z5uru&W#G3|a{g^3#`I#Epq@L`d6hATRu|6}8oCr5O``)hJb%4Zp)_{q`)I_I5iG`*gR`{5yP232OlO&QE`WbKl;N z_)B{cMa4Sn@psD!zK;%S4B(x>xP3h~c z6Upe*%|tB}mmdl6wYx*xf4;-Ow{7}5NYmsbuy^muow&W)R0c_O5?`k0l(E}GxVsyw zlE0I(R+|6q;MonW<|vXH-+a>U#ZXvpC4YFwE*#qTAl9xazV_KId~#&T}bj>(fs%3OVgORabrc~?}Ucu7qI>GnV|L!KLgV8TsO-bHn@G@-`*i@ z0Dh86;@KGXX(_&KAngu-+qDw0TX@%>5a5<54<{<`%L@0K&fm$Zc%x5uFQqAP@??so zrIjnA6U(RCXlySg$@t`tt(K2czn{_{8S=&Qafo9hu35^}>e9>%PS@u#@e2p=@b29u za_CXYKU+%b5Sk#AqaC#fK=zSKudi~p#&u2-t8yIc>p?%<8Ws8XvOPqO!&YCgtODQ1 z;bTat2jqXgU|XJG+7zGcMC~R!?MtTBr=N11ODC`TH%Hj|jGnxY;eGrYgFg+w#eIz~ z+f;^!+y8!}b?bmf9*NN5I=@_6Nn6(T8kV6>@T*-;Uj1Zvcuq8L1lQ$P|AhF3u|_xi z%RO&v{LRl}^VajbMRDEq!!WP1^)70s{IRIhI4653o#kh>?TFCEpzhk$r{nwf;^xFS zr2V3wJnweux#W#tN4D>(FX-B`^xwpf%#`1Joh(7)NbNuA3pX0OB zr^;2pplw%xo3DI|*>f`;<#!U3r(E6|>Mz)~4-n&hRxk7BGuHYn?{NPm8^XGE#y)w} zdM3K2sTb$l7Lizpa{d zr2mw(H-^6>y8qkOuFOMpU!JrL08s>ti~!F+AK}e6Q&hacq>$Vr==C7Xxm7bJA`}g7 zDddUUp>p!-#(CtGYXMu%vzu14z@9b8N)WdctaKFQ(L0}fjQ9V?KgZ6I^}v7iSmpX8SLbm3-~B)F|E&8< zeDk0F#~9zexiF8DD^t)lrLNuS+u9wY&k)yem(;Ycu${8DTZEsB?Lz2(+G_oXr3{(2 zQJV`N(J7CA;tKJmvfVEkmwy78)yCDw)jstpOlb-%EL6{TX8`AXIqdNwk9YVt2Sa|j z(n@kVNA4|7u{1PTY7^6Ue)W`^Sf`eP;KRvxRoZc3mj#9K60MqZk~Nj!*#ekZ8hP5bb&*#DzK>il zcFJ?KO3C%EW7cEOKoK9JUeHf@@R4rh~o&&W{S&~SFW6VJHMCZ zWRz#6t9S zeoI%bv|>mz#X_6)js};Ou<7C@IQ*k!lD2}bhr>G(;rlj5rvJ8|J_`Uixpy~iju$U< zUr8F7pU32tnfAnkzj4mC5V(Eh<9+#Lb(|yq6m=-!Vc8#CkIzmcjajY)ayfm9m{~Cr zeTQuZ7vn4v`G(0HmJhOTYxL=UAvwDBnnGxc%9j38iBGhQd^Fb>$=%pUqg~R@QHsu7 z2a*)gHyY^%1hsgugKzN@sRccM<5i>$NJPumnRq3 zGrhktnfqa-)=%5xx6}tvy@0HOvDsN%Us_u@5B~1|_FarjjN$Qr^RHsf&T>0gTp9jm zZ7Xdxs@l)S$HuT}{d%k!9j#ar(HH-_->#J2?_DyETO4F3*qiO7)hk2%66JHZkuQI{ z67V-Ii{-XV#7fRm@P5X7n6pT%bX)^z8-w02StA>3>wF>V4wL7VokvSc!0aqAHr8>` zeY!*F$`#<_kM9hFull@6IDHX*FAkTUSc$K!v5BXn^0QSq604P_>03aOVtB_S)|R-* zVqke0W4C72(p9T_H}{`} ze#>X?D zCozrGjlN#IZx?MlnwS6{e>}nmA7tRV*VGA!D9<}1J#d6yt1>2weZ5p~fpv9IO}wh* z3DZhF72@xxm*Bs;gY3=%)s8xEeXX7--1_c@K6ye4=fgiV%=&|V0y?p{cch_}a||b9 zx>*`aq-Ol+#KfiOd#66qjFvV7+yb) zU;Kl=mwn$jQ7Ny4sG0n3zm{9JMrK5KpK>ZVS^e1=0jYS_Jl+`&l1Rj`T9hI7|CDSm=d;1AoS=5NAcmo1BKTn9@_s9u3lNhjoI=?zxklmhU%`4?z;rI zbasai3GHxzz&S5phf5Ic%gpn24wxnXkb}b~Z68=R1=&D8V5WThRBZ{C)3%dc0%*G? zycRJM$mi?0#7ckZ6KE2|?J4vuCc8MA`YnNKt);?mj@C&we(95=b?bnG2O}}oUb_Y~ zo4qZ^>g_9ut2@Qe7GC3g9fz{{Ek3;_AFr=`ImKy<0Qa40|S zI!&+=b(VTuTOU%trYsLf)+u5{Ns9F|Gq|>XJ<<}ldlb>w>?|Jr;KSBg9L~OwWm>q8 z>cr*FkV>Yr9PZElXXk>X*navfqBO;4`}bjXP4$_*C{3~c>Q!7@x2~%j!q(4R#lBBJ zYo9^l?!3?^$UuAud1@QP_ghfw**={}{Y_ib$Gjc+Ga#%CxT`G5YGEzZijS4VvMkG? zPDr{M-ptb^()KRLcct-kpY9)8Y43P1%C&uG03TsBzLf|}Vp#6yk|>aeNgVAa5En*= zFgI4bxaY>LTe$JTX$*gQ6_dZbu5?{xt$ds-L%F_|sGZkVlJ<&6B2MF080jbT~;5l}_p>x>3q$m73Cc`t(Y)!??9#`+8kWA~yO9zZJEcjs4RR}xJM}L9AfBYRh^Pm5%5}d1(Ufd1XPsgrtK0S5dQ9O0v(aweIfXEKe^BmIF zk{FkN&(bm_b-ydKgiSXd>eG4x<@rADR*rE=a(t6Q zy7$T0;%OX+_KjmXaYUg$xOVP-GA{TjJlQBtri(NI{OM*nK5HPX!F>n}Q+RdYTNYp! zYq0L<=1pLBwm$)JH`DSmR`m2&VC8{xwQ{+8PwPPq2{l;e`cs1|4ybuLxnXGi%vB67 z7B9r!zIii-e)DM@dgeiF*-(7?#{N%_Vf@BTRuX|(%S9(^>}zffg1N&{yUkPR7UkNG zLqV|oQkK;FPw^Vka*~kPcSP!x7VOuK4j(Yf7Ll%E4t_OQ&cdB`lb3YMley&+(GK>= zlfr#>dz`5R(kdzVsbdm2N8&V1Nxr*)v|08`>N*La`xK(_ao~j)s9k^XgWlgUVrm_RN|qqB2}5}F|7+9v`{2HJ9wmWq&KaB&IGym|z$zxW(( zPK@ShuhDukKoUDDQs9N{f|EA!=@5O(`d z>TWc$tA9sER;|cB-Ie6)n@;UCe+2chjxLvD4)<>QV~qCsQn*GWVa?KPkNW3!Y{Tb! zcNf;@_}Mc!xn}@7pZ_|Zd+hPT^aIPw7+zR_8&5bQ3wgtNEAi2mV_V*09HVN~=F;d^ zfy&1z4-fNrD{qKxzrijo)t#v?%)c$uK(byOvLCS7%_C5TBzg-=<{T8X3+H(Yss2^wlv)_Chn6&q3 z88>+{wG|dx!XiIAq-F|T2ejF~bVB6IuX}$fKzN`spsb(}DlZFXvJ|Dw#&qJ(u z+j`N*^4hDx!$Y{7%GUMP`89=fiL^E7yKE5|&wVz0>yhuppat8~pX{)CQ?wkvm%{Qb zYmX53aWq>gv!|bc?v@~a?wh+?i}arK{zfcJ&jL{SDN9Q&CDWk4Xxq`IO+b=FxN!rR znOPZdedhsdm&(f9Ij|1ZFF%bnAz_7gLn{LY^%PUNJRxurdSadTnY#g0_Zm=3z*5{F zwH%aRpRiJnE?mBh`Nak7DL4`O`nt8awr(9ZpSxtnyMaHXkUOC#9)1{0pC_n~4pq*} z6>=Wy6puL#nvyk)F5^42?uM!DVh{IC(<=niBzLA3$p`-3P;cx}T`(2wpvX zs=lX2Jbg4Ua%K8}Nv25^uT#5sVYcMmZU_J7U%{4*8!=JhriV=zFJX9oq2-W_4M}O5 zQ@RT@Jmh*Pi|0@d>^tWntpN@#Llz4!*B{}l0%o7PZ*6Kx{5}v)OC=I)C2dXDfIH2` z0dpjNOJK|wa?5@u>!=|)=}xE7A^-_$aGR&Jgl@Vz1I^Cq>sw3IS0Y0b%5M@@uMBFq zcd1?nq6n*UCA4K%^a@}13W4f(o{ypYf7P;90*9?8m3>OxVB*_pTi)rYnD2s5 z5Q(W>a+A9;IQ#bWkvDPVxo0rFX;as-4J<9=xmR9AeW`&428340B&J1dfIFeuIacEq z%A_|eMIE)Ii5GwJ3V!y*7jb><+Kx`#j*|qNFI>W*x8HA_HcjVi^3%5IO(xq!pC0Yn z4shpUN>2l|Z>?RIsq+_5Yc_G@@H3@kjgtgpw`TF;PkxF75e~ol8eV_?Im~RBEM5Ov zvx)tm9K)`Yr;s2^vqfo2#VuRoy~~{gs_&ojy=M{|TkklxsZvC&2XfnvY=gMH z=}V$$ZJB|cW-2X&jHk0LNM6f}X)mrWe}5t8b!TDYOP7GR-%iB_tv=nkl&0B2`%dgI ztH)Z@i=N<@lLo?dD)$!JleT;$^~;iDu{A+x@uA7VRE3wL$M!#n2*Ay`a=RM0ojr#~ zKRAj8>fm}sBXxN$nH*i^cTPS^qOsMlmF0u>)9A2B#mO)$9p@YF1KNjbr-%dTINHp9 z>kY|y_aySg*@^hLyfrjYZ!Oy9o0BXVqt?PK=fNdSln84fV!Ad(v#n9N#UYnKNn{~W z2c7c_+w@;jUaIs5iDm!lXrmVd2zql`itRl`Kl#kNbWmxkT zmV}*96nSH2&wu731?x%Ii~~?mn`x zwZ_#&_JFTj`Rpjo;Awm%J*pa`YdMN2`pqvO8XPR0UX}=S@o5fC9ky}i_0ZmcFg zmX)CqekK8}r*a#iqt;ewI+!J!7jZXV(bj3F$y~eYeowbTlLqrKi`}CAMca&~rn1lF z%h>?4lDnes3}6iuf$L7D8_LwLIL+N*^mJmJb(&|j`b?1=_X>q33;1^q7K#lMqKij9 z#nrQyu;=gOFWN3k)+8c*ujUFkxNkr3@9eKsb{?R%L9iTGxBK5c7U5--{M9WR|55V z-${RWEx_&r=svA3t<+nf$A;AWo<|Y@>2R*!G#KL0MM6#YIlXgdsq3LXIe8L0w{F46 zP`Q&Lttn3}jsExm+KmG-%g@t;<FZ)JB%L^S3vYg~bq6~a%O&JEteJW2c zy%gcqS5wT)tX`RVd;oemshHOz%1j$*eqk(EX41OXv|43WeHuk$pLTNHZn{(K%)I`Z zK%b!E+bg64Iez1MH#PNdlets7q2YxEeEA1I2AXcEZ)$25J&{QFR5`s7x3ouA;{-s0 zCZ7B0t9awN!2(_JZCf=FTb2%5{^*^rYy{55DOuySc-~$tkHY zIp;pvEZXMaY3~d?+P8J?eOg!me)z)_P5(C7Lb@ILG*o6a4-=mN)VwYK8uy|BG_vrK zjW3A~`{>Hhn@2wY0KE9blcmygy-NC_*4BZE(z!)`R5$+UF-Yc{125@^DZJ^ zmXPc+Po76Q+?V*X^!*z0L+KKsVPf$Fny9t3W38=e<C zJn4^eZPaOReDMok!0=%4;aeXacm$28j!oyMJ^e2|#+G+qBDNwMqjQqh7`HQgdnM#g zPg$I_`lxO(b{{_pM8M~}A6Su^bV375%ZMAzmVGCmgFa)H&)8&P{DgLGp}7<`)|RBb zr_OpHJ@3Y43QOT`G(*eE(Abj3asu;*i}_DRr}zCHq0}x^Zl>q8l+Rp~wl<`P zSUSag@p*y(<`UeR|8N}S>3tjEm^hu%*qq`Wrc=dP&aK<7F3ogqg#O53xI1) z09A?aMVZCveOg^;Z&PLrga&OM)|-z^-Th8{`~*!y=RalS&|<1MPyc% z?5?WTTI-(fndy-`vto8{@31HKjySs`Xe2?S8F|LT4;aZGAdW^e{-F^tLeY!@pdI++ z>qU0}03ZNKL_t)8Fv3WX2iyTCa9D8F?acIu9o5q_J*~BtrB!CcI%8 z3?$b{P;f;rp8ca|1r=2FgXc~jR7MgOImH0o_Z?2 z3Kw6ov%w92*D6YP#SWb7x*VUnlwG4(1?^YmHUeNSeQ@S;%*@T=z^+{w=xcn=`i6V= z(NnFZYSD^Ja$pL?$6a0dy9Ty$4VR8O`mJ zFuL&(i(Sg5Fa%DV2oTpF*43*9moG1UJ6!X_;>s#w29T-q%FAzCqf(lkm927`ta{ps zH9CQf^QhT5@pP;Me(9U;F<0VrwBDvyyCA`3MxY9VD8)JW1cVUBJ~@pqo;i%Wn>Q`4 zClN=qkjipa#Y$H?j)#Y;eJ zON;9cRk3QD+`<$js$E_`G{1tlrpJ>^pR_%xl(?U-el(7+|M*RZx2Fv;VHCkcwpMo9 z2Ey3j@TX^Rpmfe_f&h5F8vs2EH5en^*4UYho)7BvmtbRsh9Dfwtt%l)l`hYsqB3Z7 zLh*#@8sk%zQfO0`#piMi0jpj|eFP&RGx9uvDqYuO+rbKX`p)T!uO#WWldcz&Gm50k zs$;QfyYzHYD-PT3ruJzjS?fmS7AZShYpL;%Pfr(!{G>zX6-T0vVttJM;1t5162fE0 zbJOm=d*NT_QXySlhG3j+i0XlG+!owl*fht*(`#Q9ggoo$hy#`qtTcil)!MzS7^+ zl`5MSwMJ!W?cG^vU^mq=QZ4>uMpmsZlx})(5c9q4-0ey}vMt%VbkYMDY`=aJQBN7S zw`?ig)<(4X&K>Nyc0J*&#Hsw}T>vh3C#1>RjdVJIv1;$^Ja$~Uj=&gP-Myw5TO9udjc=I^9lzdA<<|Ju=Bn^v;txRIKmH9W7OUx{<@L#PP zG0Bt6TjL?pXQf&BvdQ>3aORA`ks~X+on7h-by`+wSG_I=D>hr@Iz;cZw#Di8FxPQE zv>KM``0LVvy?DH?SO5<5!wWD&eZbLYa?@7k=P@unQ^!=Ar=1ECJz4{;BeI9icgax$Xg&yNUYOPd zNzHU1xSG`_+u!WCP1u^YGKF;wILF>L34TxWL2iY%z_|F^e(ySMXHai1uy(Ee9>>6w zC+)ApKq^Bz52}HzS1=z`Hv<1f4BB}jQ`X(35VSf~M_#$vB6GXSUpnD$v9ot6-T}A9 zG+7opf8q~iTTYOaGo9Y zL94Uapbo@h9GT6oefSvV_#Dn0J%WkhV#w3Opin^W0&~}937B2Zpx@H8;=eU6kmf!`)nc8ayLW*~#b9Kl z3!uAHlp6D|G%#(HwkR)5r_%t*H7m#!+=YsMRc)HnNW-PU_~;0tazQ9@;Q@aBcpPhn zN3dgaW2fz{w{D>_zW{cEN=NsUy>wSk2^rHW1K$b^=e}H-T`=rd9_zY&@`4NA<@c<# z#S|ogsx@s&*CUX1-&H}#-~1Fx4q#@eOJJFtuB3Ybw^NQME7^5T)^JVGm|U+IYIC$P zE{V3VNe<$RBSycB$V=m(4O=o_mx@xK2&BJfPk>U%;KGIFX^Z<_wTd$uV`yDNQACu5 zC-U03R7j~4^{fQr$x3KLGh~ugGXI*E(EU%))#pfVAE;F?04W-|Oj@JaSv!V74JGu< zSF!)>dF;A;1$Vb>ZrUI^G&P0eAD>djN^*^g6!v1rTdnA}ec))@mJ<;wicp3@h|+w7 zeP=FU*Tt*2vvo7B@7mF@UAr${#*V8uP+EwDTNbw`LOE$CZSEyQrcWw?^VIlTP%n?7 zL|a~EUH0mHEQ(Q?sVb$luS8ppb=s;W(OE4&EzL(L3%6_E+aM*sIN|vAdo6JW;~Ajk zq#$WK8~d5ZN;yO-++C?m$}~*;oC5^vx4a&R@eAtDi&XA*6lC;KZH8gpEI%z)pli87 zK4F$^_)U_(^T?0J8&SI4;@qcs8XpHf`pDqKiKlD*>{4-Rw;r~UZg(klzWMeCUIXNc z?ALnoM%62OcjE?mV&>5|_t;&H1*oT5MbAPtS;Irbi2*sSnUk0kNgBqpf#?a{bFrvI zfoXCva3gHn7}s*zR^?xRPCvGlWoFHR!1LcV-?H&n{?`%NSu(KF%csvB$Nh~PP%RMM z?ez1IKY0gN%YbgA?8y7KW7YU1YRR@IX?f6fYYjCMb3Cb|U<+vtWt8ex^#CFIr)RKwY@+2h@4kEm{j;;U zyLl5HuWA0&E}{eH&ZAU|FfchI&g`HQywY}vw1lHmx~U|t4&lBxS`v`RRwHotJP#UY zk~%^$pNuNYtu07>r@0s>J)x_5)WHh6)Ny+F5V&<~ zIV6F_)|r*xw_c>vYTX@Q(<_MPD4dte)@zqf%NMK9<$Zf_bNe>T_BXaA1HiefS8%Uq z9y>Oy%S}ry(`Rh4K2P?*#nm!D_lkSyt4F6x|L1x%K4-oNam`m(ku>RaI(2pmmqTTx zb#=e#`*hv)Y@>6Qb%+$k=lW!;^x0%u&n??2^&u>K@TPpy5_7M3^K_83h)=;HWN!N^ zH(MDGukqn+mcdvT#d_wh({=`}Uk|KbZwGQ=0XTWmV0s!bZC;P1kpt*F^vf1=iispe z0Clr!xK8%j721}fp8T}M?yYon*wTw8Ma5>wq-|kur~a7 z9LG+b#>X!{kC}mimfGAuJBw;h4{Ajn2^}g$5&C9l(L28Y3rj-v zHDGqOwY3})OFR`N+b5g&?m(Tyqun z$Vjj2Ya}-YPRi_5Zfo5ZW|PacUCvHYMeG1(o)_-UXL8#1Iru}Ar)QzuBTco_X&it& za*++x0K4W{E=LY}Tmp>)#V94d!Lo_wL-HDu?_F9P_4NTecGxjrF2`+2W|7ZTt68$B z*!!DZ$I{@|M)kI%?oME)r=5z-zs1hcM&-I#z+C|)PvaGl5rtgYeKJb#^gITpXHi+G zA}|J5_Utayw&C${9Q@)O2FIsSt2;qU?!p{K^JMx(5vnP^g#kG&6ECs%O7&>rebaLY zr)SZ#uz)p>9wmKYWiIomRpXPW%q`T7%B4CcEGKnHl`tVLt(x^cPk9Oxr_|3XKqN|H z6>tE;ce34SX^q{wU-@fg zt!5p!yR@=tdK&or^Ulf*t<2W^JoyGfdtD+ZSM#RPAHQYH(Ii?-=hNw3+)L*SSflZ7 z+}g1XbNynMVg{YQZ~@nU_%U{E-v)dqH#vL=-QRn6Gqc1|fm4QWMEz@(aYlmLB!BzL zEP{dCv)1LKXTPS9@oTy~jc=KQrmx9uC{Z-KLx&^9iAPZDc&Z{8lO#?YJB#Mu4q1 zZ=u@LgXy8cwzO{j{RbGDn5yGy?MNi83c7tPPejmXAsPU~PsXtR{sTPNuzqoEd+-3G zkDnx5RpV8*v-)hUEZtZ>MwnP~c*2Ac7;lnIbZ~MSTW;OP?XAs64BveF4u;3Z(LXZ_ z7~t{R<{Y=nwHkI_y@s7vt|6$!iOxey7J6Q23DuR*(jO+)zh_HpS|UhG6H*$oH3tdK zrr4t#hctWsb8Q*{Q!V_P)1>ceJ-)r$-u1lomE~!{^Id8$jgJEl9(1;jqO&S(3v520 zyyn^(eHhAJp(WO0P9w|I_$6JZ)*#AYVF3(oZ`)GHVH*Ih{mb|8xH^L!2R9T-FD;ho zcUkhx^eQZSuC)$&AueFCkH0i zlt7WCLIhEaFpd!yjOda@X>IayNkj0oVrVh6GE{S2 zTKV+wp^XODN%E_Xed!k4j$9k=D)j{;;aoXDE@QuN|)>ibm?XByNjI z+HG@|l-!m!8t5%kaT2xFeX=}ex?YJbd5)Ak^IAV6no&XGOid2vGP-x8(>StZQf`;j zJJ7Q*O4&|Q4E4-_k8ozWmm_Yc(Kf5i_47&h-o590`+ZOLX_GM)7VI(3hYkfrg9dkL ziK$uz?%!XIn$zn-mYmg`{FPO%=6ilb$ob`pkuKAZ_*}!HjPf)#I$Aim#Qi^fALG~V z0WTgdlwQ}Y^^Fj%^ZnMnPUF|K{<4^)l80N1;M*+B+^jsFwh#DwA)mQiZCy^8rOo!w z0j4_Wm! zQ`hoh+V)V zPTTA6KS1y7d`gaR9fKt|NaOtyLe&#s&BMninFw(h;?cUbEwyd!!$;V2@iImpJxNZ% z%5qwk+75vA)I{>hasMI@x8{vD+>$QeCrPOpS_T{m1V^Vl^<#&2R>mgAF5IEStm@A&X-2&RI=sp1bol3YfXsh_IUMaUF9&hFb|sq3`e1bypU0p5DcV50RCRhlAq zdM!P$&KGO)+W1uk)xhF_^-2fSL@VK0k;{)>;QaB`U!%X zNsQH6vEUa_$SAIv6ZOT2zVcYxUECq$4rteST$EmY`&|r9PT`rcag?G6*LLn~D*xtN zcks-opNXj26lF}BYeMm1al?)XAIKGWo}wKg9vO&qfN%Y@2RoDT*#*(8Sg|0PAT^Dz zFUqz|s~xvp<-M!U_Y(;xlwQ7hjcBO=w5+E~U0Mz*Hv1&FkvSW|J{QhWE*J7i5S4Bh zugcQ=%PS0#8#TEwO)nt+-G2f6gYOs4^7@-^qi33rho(9$e4;3v5;V)!`$tDZMTqO} zx(X+c3y^*4&}`7$9>DCYF`N9)TmxvSj@1empSqaRab#@<%{E;bwZsvN)5r+#x(6)V zuxp)so>l=|LIAlLi8j&M5~L$HsheZS4Mx%&Ax+FOA_%J^d?uPMEuQ-OfnB@!cdZuS z$`yn8`Q>R({ySErjApQH*Gy2H@#yN{SBFGJ+)**W5m1_uV5f~#`+I;&Ch9)Nk2MLqok+s9NUsY>c7klo+qF?ka zO!!2EQsVd=f;kwCo+PdA22VZA#`q*KS_;v#!Ir@s zUjC=lX*{2;{FXWbDqGf)b+n~hvyRBE$JWltQX)gdY7FGNM`v=7<2I?;E$^r3@!I4< zy^$DLE7SQ2Nd%i7VV_oNB~dHbxLO6SUIof!gWbCWWcW99sY}a3Qs+j$p{}{>wAA>z zoX=f<0#S$MVe@^xm>6E2->_4+fxaFD2a83f)H-3krfO7{{`gS7Ut6F#m0tJZj7a0Q z`pS^?`|ssjn2HcTKbLp9+G&&XpYxd)D56 zl(c|mK>9olz?~`77dkm2jd9b*F7x=g8sqfIQyNWczP4CQ^;M%F0M-hh$B7BMF={Ev zmG|0HW|p+$%0xxW%a(P0(qE^gEw?30Sy$tz!R`HX7fmCRfMo`KZx>sbdeu zLhfqK7?j+&V}ux*oI>B|9OnA+Pw~j2(Z^44=*(I4Pt71k35=o;iZCk)qCUmWId1ap2r}tbQ^s+^)2o182O5$U)2h=0l7pIaJ9$kiNoF z-_#tAeR3M8*Zk?T$1s->y|t%W#qm!*O*GsTfqdP)hX`VW%X|0KTax`g83035(>VC~ z+2oY2bnH+)7F?#OpB*J7R?=PY`BSbXL*r+8PL&b-9Z4=AQWgRFPN#8@bRi>aTMbZL z*UghFTPW(6E3IlJJmpZ*LFR|8*v?Kt*q+m@StU}gq` z(^If3S|I#^T=!qShGpU4^mU2a(umclv{32we_wss7`qWR_qE%lMx*WOiSx;)hk^6a z8V%+~`s~e8!j0o3%%-$KFZA_bW@tdoLD^TDX+85*3{6hM>X*YhR|801Ad4}{avD|Z zrz7>m#QzwN%Moxfv|pwn>N;&VL175I@=Ab@J~DXpXzA-;T42pJH4Ch5F5_HJms+g; z#Zlww-?_T-)8;8bgUnycMJuBfmU!M|&Ceq9HqBJ+QBWn&(ZMOzr~yn7yK4bDeC7*m zy?zVsfesAxsh7mAOmdG*#0CLsD5Ix-#Q-oS#-59pQI2Z3aA1Ga?HZVw!K)|VMNpFr z#x;+p)x-gS5^9b(!EZVH4S)Bs706K84t!%n=3oypu z*=L`Q_I3%ldDBLLYlT)4aLxlqF8LM6dM$CGqJ}H-_-7w1O_x*jt(cga!k@nL6W|~G z8h+z9f3^5d=NO_z4A0U^UEiweDkJ%-R39{Y>REtUe$N8ex*RtRQE|Xrd~Ukx?Q}VM z4ru-)KeE?hYSbl%)LWb+SZ2p7enP&PXX}WQ-vpSWKOjuCUzaR-PjXgD z!oOS@JKMy#{06NrBkkJ<#BqSRIg6*KrS>hxzRT`0UA0^r$Wh{-2bvcjK2;zp>pW@zy1Idm+oT2*LP!m0gsF|j~`>z_>|yz zZr}(wtxV%jiQ*)R_u*0Fq>=yql!brOX|nI9(=|hWU8=tCt0j%X<^0kub?ad5d<=;1 zuHM$AI}aXUVtNVyuxfA+Th=!|qWjU>wHTP1!Mgho64x`W`6bsrwiQU8PW()2>xqMr zMCZf5QfDHiwS2zQX-nRhmns$D)mM4!KKsnz;X~`Vz0}UzKzlGTmz6gwn!{;D+Lq=V z*)O({qwq z6?%W@X{K?t|GB5hH%t8Kis9;_<+V!F)4&HG7<}z(0fvTv0*Bak=_^G3>EOe=t<6$j zKEE!rh^&^@Gitr8#_cXz+Fw_*pxWfNQS>+fR9)$EWgbcXI`Z(jFHJVCE>8N{p}}ZyE96J=GU5t; zs{ngvxza?nQpWA=TXErFzAxPR`wwvR^ylcEwUMOAK2SUxI9V;1F+fbxo zs0e^xnV`D0r~I^m>byB)iIs@%buNd&vNn7M;u!8J>jrtup*CJ?#^dQMCfV7EGo~?nPsBmJh001BW zNklzVYEsPARF}7d1fem-=E0N135)XRk=25Cf3Y3$h zGmDC}?pj7JRrwl36C2h~59&KRd`rVnAlfC(1-3*T!Hj@3spDxsn0D|d=LG#sjQVD; z+gX*RuGepl3&4wt@p)7nXm=JsN73>q&AZe(EyXh{$}KhTY1O19SD40iWdk7}zjW2c zbj|*ktB_U%#-6eoQ+#g{lmEpZ0sscS|LX{I6uRYF4KKa_b5!ORlGUR6P_rfKtzxP1!Gin{l3K6XOnq#GqO1^|3ktrzh2dO=XFS?wJ`rK$H z`}ka!+Diux06>5%SAd5P?P$-<0psIK+m2$`qewZHib*+?qj`M&<)C)ISJ~XJF%{7a zEQX3ps*UEMPqkMRGrNXXQXWFAarPTU1(T+-K;Q{7+*za`H}z7>*p`tgFcyKf5Ze}!Qr+F$!LEwG)rm<~w1Z`g?zf`wt%C zwHJN`ySL^?`r3N)7B<|!k1Begaj*PHDNex7~OReN7N{!}J@l`Ls z)j?_mTz#(8MpSz%7+d4tkp6J&3C>))1OtO3d-mo!Z3Dnue;+1CR%2*v3IPmCi0Yh- zur0TUECCz^jJXs`Z?3jiI!mz}Amzfev_Rz6(xrCMGtb!Zym%2fdv^KoU@J1GzZ@zf zkD9|t{t}8=A(nzxrY*UBw9?wsPI7Uze+~ypI!2EgS8{Gzg=vN54|5T1Pc<7FK=b2Yxt_Dzj;s|Zk;p2zDyeH#H{oc!kN zm>C$zY*%Pvy!Q42z}D_PpVX zPpOLPr4rGmGWwi6K!r(jK z3DDp*>e33LIJTcwXmNIj=JRINR~)P7r+0OBjnm6>{`_`FN+-DmN=;zBzy3PHiDwYJ zu)9!txqhT=vwYIC3@RcVeA}%|< zwaj-?qr7MHT1f(7fa|+=;?n-Tg?ja1!+M-L@ho0`_kENi%h^hZ>pE=90WIGlPc>7& zFSjlchoKMgD*morx25)(ezP8)B}@Ci>$Keh4Gr1<`}PIcycu}($l&tj2S0|8hfYZ4LbkY&bxoSRd7MjNhiCd&MYX}e z)NImYm+1LOXKP~Y<+&Pq=Bk3R`&&r$N#JbzUKZoePeiK1>6utnIy)8s5W)n3@HnXv zaMd<`l1dWX0ks~X2E$z~BQ~nHG%)pS_cIJ8!i5^2l)c*?^hz z_|kFOcF1PwRyPLATs!BNdF84fif7L1WeJ|;HZJMR%_{e6yLaNzy0w@Y7{Ju3p@!|c zcyJ#~7+~X_d+Iu=hUw@p#M=Jf!bg2`xdpEFq zw;l5b53I2|j)BR^rEA0DFiESFrM&wx&bgH;L#@nq<ZN#wR1g3nDNR3eWO)O<&)<_V>hU;spkVw^ECwM1`oW+{No(NaoSyhAmQ zBDG(dy15@ZkHj!WT$6nVAjT_OU*_VhMkEcjMP|0t{l#I3$yKXVo3k9q-F6rR=$oBG zd7%nAJwuv*t-?D%88yg_T~Vck>Hfjg_?$U@6jMWfxuI`%4ljK0VPYO0n4UpTt%eAu zuB+jwVDu!y`mACZfu&16bXsbIi2PcE_Hm1R!*FAqyYz--qEA0H2!a5cHgz4hzuMG3 zd8K)SpO(|L+0+uRJ}l#Fv#e``bhW@7vV!A4rX6B3Y4d6XuWtli+FmHR%a%RQjq`qU7*E_KE} zyvwC#Y04YvYK>ECm%79x<;-ka9R6)aPHq=5PHJ!6?O!W9Z7o^(q^0&okR^IyLuC)T7=JzKU27$z4P;U{U>h&HG7&>q@)*#x2+?b ztIel=*?wA`Ym}UF$)_w*2rkB0z{@A!6TDH%FgzYMSXrs={OpgiO(;Lh?&}+8X>avC zJ$pS&?4tVAXMR#Hw&(Mp(lQp?gW0{k5k@u$P^-&uaw9s8w6Eo^n;Nx=L$#T@dX<#;S!$SBOCV2$(0tU*@B7Vlv*y{=Kb@JvK6ecV7P*zW%ef z#MN@rBa&w*WDN(YVV7<8$}&lMnO74_02*Q2dt91HTGFK!X=sQ(c1V}Yaa+=2O$nU_ z){P8PogyjrWeL-*mfK!d`qcu}jpu4}W8pKgxeK6-yCnCo@RCU;YAJfK*_Vz%FbELT zVr;l`56^@F&K^00TDkaAy7&Ag^iR$Sz*B#ot= z>*gLJKn#Qdj)tEBfiD6%FfcQV)lVi6BSf`+EJ)VwXCAp?2Jy5&Mo+>L@2IxdWxtte z^D)R$6eMv@?zajP=K_ZQSt?}%a<&dtSyFs(%^w=HYcV5E(sN0!IH$!pEvUF8RTiNr zg^f87^F=~-p8v8Z^d9ihRW6Z;AS2MF6_eC<8jmj{&CdgmA1`++y7Xlt|9f7H*SYJ2 zYZCR9A2@HP2F$voG`y564Fjcxz6vfJ+Ml@rNK&;N;O4e6V74KslnV5+(P+5lLb;;) zp`Yx%RFG!Xl~x;Q(3}UD^U^iHR_4!*ELloQHo9eg{u4T*CY8Q!I+h09gC4EJ_Vrym zFg-X}sD~4)SL5>DJupFlO}FnR*9i!7tD-u;E~$Q5-o#JJDw4Gs*&Q9`Z7xvur|;6z z(E9bj`t<>3W`L6?`6(wf(D76b8HbOPUD6QD>=Uz-Zi?*hjI@&7-Hmdn)mN;A0 z(=^i0XhpF^vr^@!PnwddMJ>xqd_i%BZX2`c&=+U1`PLna)+2*bwT1u?^8$&+!)_!GacAphoIQHDse0!6`|$QRUQd3X z_~0X~d+-opL|Pg6)|T8wBS$XG!B(%K9wLmS3UYd0K3} zr%oA^%Qk>XmzJO6_~|+!EJ(d=MM-i7Dl0pkOe4{ln^)pp71>K*jQ~KkQb8OR!?VG^ z|2+C;r_j@co>-f|wOO0D(7G5{=F_9&noM}ysVX^&CU8e z-nf2_AP3({!j;4^Hr&34uRnf*`GG$C{Nov8AN7gM- zZfxh?xN|kAYj|uaG9IqR%Iv&GCtZfgY@m5;Q8$mDluWV%e98CDeK&n;Z0oB<`)RSb z`n~rIPMioZJlw`cb*Up1MXlQ=TGa(-QKPaN-AlK_hnM(zR+)aOgV!4${$iZPJW*<) zCDsaHV1fX(o^m1kGXMmC?KQl9^Z@p5FXq52S4ZofDTEBle0sgD8a!%NZKHm?`&R1T zPTOsu!9ifxt^hqfKol8Vytv#gT0AWku(mln4{)=Wg5{*IHmLTIJMWl?zvO?n43n>1aKhOf(CSvmP|C29CB!JP-PkM0g=I^aqkRY6h7-Ml=GT71ar zhfL4nq|HftrQutz{u{^oC?r<@;-Pp)^|8>*StXxTHq&S~jydSxXF)F>w>@AD^>8g=u*10v@|dPeD}LN`X^5sJb40`C4ffl zR-|&dtw~FGN>yj$$V^- zkq(eXIzq(ED|j81XCJYWQua-!)I40`EWXQIbW6_JNQ}9%RoGc$#m;#}#?~|E0?jXE zc~a>r>-1eSNq*h#E4z2&!omH8+P7SE_V6K`J$wiNu<7nyJomvTs5xmuAuC+lwF~DD z9awa|AH8@2&wunW*5AGl88^<<@h;6$n)7z{(`NB3b4xnfSC)1zOB0&LohwtKSge7$ zODl&SJOF6$UJ<G4nzx zN4l7LCGxkYkt!AY0f7E~;MG^{xSl#?Fgv?EZSu*it(C)+KU;Gw)rN%wb*ZQ_{@~Jr^Rz>_C6!DUC%a4#On> z>F18&;OFNsG&WUlm6dbsNfae#4oiuOEYg? zwOW8EvI>^lx0fg4MY{~n&8c6O65xFqC~st+hVfilpj}L1#HvO91(j2)9W^{YT(T;mi$ zOzw*-(D9Q2*a0-Taj#2H1uf0YO}`=OwNk&AS(L3j zY?LRx@}~g@prsGJ0tYCzz6+Y1L-=Rs@ZA4?5MfVa$k9`+V*B+QfFU)lbk%J05(dHGRqk1tPln(TGQ-kr50`&!7~?*mUb|BJIdCEwt*N%^z}px{7gDN6YxHP}lr#-b&_b zUmbesr2ugZoIPuB<3{J}D~2~(DVOQ1?&i?0k@b~R6oC{iZ*i23=OtFPznhDAA(4s1 zG7=kTw3Rk8OSE7SW30;Ky0i>Uu0wJCFFC?8qL9wqx}UP|w3@p{XIjN&tT5^H8^R<} zn;CCKkUYXijG_IbDM_vavL_O&oqYYZrZ*`yOHsL4RM(Y4_cv_7hcCZ?=imPbfS!jT zVq8494_Ef=Zd-k)j~~Oq@;Pj|ehUDjf5Q59PO&T_-XbpP7GV4Kma=#0D^EoXfI591k8FhS{Akjbnot3+6ERAKPE2T(p8fa~ z*5ADkZ7fbBAEbI>e>0|G?ChFb-9F0yK624vs~QKlOf3tvf1_kGx{)IK7IIZ0@SIH(Ez=j#l2dnSd8kwZ)~&POj~)$h?wrBo z=_Fu%a>Qb0l)E9DEgJciEB0Ud)B&SK{C4HBteb}x2GWxc(84*@y`!UxjQKwF;r4FjOk+ziY%-=H zOde zY;*+GN{@Piyv}eBWtI?hKC~MqmPW*N;+AP4QrR3`r|mXVxokl-0F+7wH*YQv z({%;L*2`haUq+fW6MWUES;*lt2)Xx{Vyv5oO3f*CS_9NB%ki1ZWILpRn1z2{`T=<) zliVjmpxHIqT2NVrH3n|Iddmwb=x7c17-$Wi{riRhljN4-0UvL~@P@}l?(Qa|I`@>^ zjpbMxkyo~rd&_aCwNf|#Sja|{HAh^=n>PbpQOdo?F{tZnvlETWmzVnQI#?Sq3UYs! zo{j8a=8LwScG@PleN7rfTi6@{VsrwLPF~~LLXpb@l!S;7h>~4FLC#_q+UBWM-SUvs zScK$CkO#bdc{)YaDsbkE!Pc!o*J*o&(&QvCKHe%|Z7&7R+gP;Tto6{RT+CCk`_@4T z#`Q<0Pb=JHo@%9nN9)%$=oQoKgK^yW!AFJC0zhSc0SCS~uOfs{i(*d?i1aEII4#zr zz-fxBA~dDJdDeY+?>D|KQ)HExZc!eH_UF;_g znX+6QO>0-NI^6s|<)AIqr1Dv1WB@)#h~0lU9c?VOD`lLZ6s>^wV^vv~y`xRXq57p! zGNWg?DVChNW&M+@R^in1&!)yk>jkp)75*{QWlRkXHGK@@m!0A;#N)MV@X^aJ;KchM zfm{|!h;i=lLEPHD6;Y{uj_9>=85a-iLmYmmS4+N^bKtrATUofwk7l$9FWg(Jf8m zUww_%38VfOq5tollX&=74k37cOQH0oY7IeT1j3TskF>d=(-YEErp=lfGwabRrllxC zK4Wyc%#|en`N%lm2`#pZ%B2$aZr_eD4De||@M3}h3w5J$8MS0CP@GfxkPJqSRP-Mr zRr=}Jxx~jcGxze%i9pl}+laOPe+UQ52|X+mn+9w{9(MJKD3pw@PWv)t7tT ztz?bB(zh**$y#kivGt1ifUeV)5Que;R$+TbpG?4ZJU;8kfVMkRSS1Sj#BQ+^9*R#s zbh$T>=KEx^jg*Z!P^dXAT}XL}Qu*ww*^-2ez1)b>vK;^BQ3*2o%5~?JE%_6Dv~4?I z_T@6Pjkb~A-PIGg@(@4MMz&`8T*G8k(zagCTM|#4W`gUqePz!s)GFyyPYr;cg&KBW zzLJz+Yfhj0EQ7-tu;&E8^NHQZ4fq`MJe#ubZ9_)dB9u2A2JOVren5TGkrru6Ghc%QPBW>;JA5MAk)GXNiPs3I$Xpvc#zJ`ec5j9Jb{c+->D zWlj$bpjxS<`b;W<;jsyXafDbr%b;Ehr)B7GbCp0b*4bFaqb$KR_e@68Wr$6OZ1OlE zDP^&1$znn6Qq^S)@Z<@wcCC$k(xsI}ckUQmzuwt8mSUE=kT8ohcay8P3wS6^T2abr zG+>r%g$qU|R4rMK^q}3Bb2_6O*8ySTO{r$T4=po+v_#>55 zFf-HsdfSPm^Xt;&L)4w9$4AZ7^;Jaqtx|LINvrRC^HsNN001BWNkl{b8Q?ojK16aI-WK=3emdDCO_BEEL$!&yD|pl)t+%voP6ZgX8vu{T|Te}W23{W zXSH$}ldBs?)96xXC@PgOJv3N9O481g^M?=M&bBRBsN^42+APiY^fLtBOxMZz8)2SSB%CLI_ur!S`W9fY=z1sh%36;t z(R#Yo05V5UYjd-E;gbpc)GUTwe%VlK2+}KVmhm*7(pr^ls`T_=)!-neW@qrjcTeIw zFTaW~XTulU0%!xXb&IpE*~WRwf%s1npWDJ10ZL%0&(#6*FYY0b_g4Gl$}Y8^wr+tEg zB~)ufCl z(T7Zotj74raB6(6?Aw!xzbgw1D95$L_Okxoee}*QsPQ1nv&7Zx8^A$U(z3Un@Kf zLbX~A=dWEwwN^v$?Y+R3)rIo8oJ5ZRb3k}nDzyh%kM8SrUfp{Ack}t5fLv|U^|Wqx z_ES+UXHeg8R%8{<=Ev}ihU9~`j;p(OVWBt8+g1+_;n{5MI%@#UHLyya_J`5}O9vpJe((^v zui8>21Sc5d0&3X~xwO|%Lag@0GT=@NDlTL2MQipS`7Fl?&KME73^1!q$u1=zm36p4 znp)`|T~SO);zx72CYc|)rp2s+X+^55l-FlD$Qc^I?P-i!xs3O|_6kf!^z5E; z54LXDh?kyu20;)YY!GFeXtuu}KY!&Vy!iId(LXhdz{JU+&%~+ah9s#pmQLJ~W3VFG zm07i{*`<|F(ZyUBI#F-q-%D9{mpV_)>1=3S*6SA|5>7{4k<%G< z&j>dlizqCH;FFqcE{fww2E;Ha*Fd6X=>Y3jV29$nR)WjOVlu{wEnjYijZj7nm-g?& zt?gUu_^L}Qg{qYve0Ka99Q^z&%2AAokzvgDrX!)Wi|%jSfc}|TY`Jk8LEWJr^;4!; z-sQO@F@BLZ&adsta{*{C1;{s4bK0d@!>6Wz>FMRe=UoD3XMyqYJyNI1pCrz%nq&q>+@ZGr9mLVLrIB+ zf0G=+=Q+!>o^^03eM)e#Ro*6?ZpnYS_+36c~FF>FTj@^v*3HhCzf76u7GdilZK3d~`Lcy%pTu zvI)1h6pu;^SXtxqXO1Sn2WO_xFOGGvb0@6NSh63-$xNb6(exk5D6lju-wn1#`=gP| z_c5D4&Td69ncsNRHnPZPU1O433qqzvB66Osep>Ks@b|a53IimfI5pBnSI{GaEKrPjcl6COzm$axL zA!-BzBnz`WMwj+S$Eg~#7>9v%($-)aiTk${0w{%!HR{G4rD)BI1JjbIp1kxvU?uNK zAf5G`vaTi91E5w)vnSa`Y6tCT_O;QcjFEKu#4#^mFG5>x-Nw<=pTod9aMPisR2MzN z5+VelJuZ5B^&sAP?Q2cf_0H>@=h!EwvH9lh`mYj@C_u`fz4@eskCK^9*T|ilV#m|5 zR&taWV!8?msfLjxmG`XV&!(ptK-X%3F?No2X=P9pwQi(X4s(+WV45T2ZLN?aDW{L(%cFE}TtLj6(FNMX6&VV-#%J04v?`)V z+kEBt>u5hAG-K8!8jd8CfSA~~tc;?@LZ=L6~X@nN5d*nP#TbC_rHHlL;<>J$(fB+GgBTF-N z79W%U0PnMmCLxjbqfxhIfpBIc42m)sPUvV znq0jKPu7fJ>y4X`N^@6EV9J++G&Yv^G)``0SY9j@D?5J`$**Vmuz8nSr-u)LyLVfg zeT$Q0isx;u9<8P2vfQ$>>(a(#c-8`=)(IEuxR_^fdIn+CSm6*GgHO(Wf%#wBgTt>r zi?zeWj%S8ynfuXNW~t}Y#$kC+mYe;w{G;_WQ}&8k)ZnbkA!B{1Zk$E^x7G3vPEBLy z)oZx6YiDkW1ATqiwPg!VojY5o1yQMlo7=ac6h+u^@fynW5lGidK{`UngP7@e2(mDc zjX};JZ5@$T5p6X|k4Sohb0>LUm-1=I1+Cug})f{yJKf zYO-=I<@&aCbuC7Rx!fzh>jBWda^=ZVjYcSaKOa*|bilu*{+YJTkb^c^lfycej_X^T z>7>I5rDPMdbWWnSNcW!f+0JQOcI;^KX_eQfRT+V)dE**K+lHzkkF=$|adgzI=T7p> z^w1!pa!K6}K_^YPKG?Ed+ojpT0YsH?loqVB66u6!Oj$F;mVYTPla~a`9BExUk#7z(l0(w8 zc>LQbS`4nfaRV^M;J|?Z1^0?}X^H6US%W7}I$MX&qUcZ8y8M-gpVR5GY=3@~na0*G ziq+OwiDc>bTz?;~@7z(WLzD9`f9EF%fB(1e$}fH$>({Kw%`!MOjh=-C!9(T7T(&ps z-bo&8U3c|8Kcy{;LB@BNe75E+`}XqKp4~a(&IeaB!P?WnlZWRMt)YI|RR_Y%rE5V#X1(>!X zLa82?TSD+q)KC;i%e48CxwC;Z_lPNkbYj;a#Rsru`O6SjvhF zT7>Rw*^IlJH(~Yo1YUdlBqBtJP(rCbGWMz3`0RH#Z^q}(wns5Q&z`9SJ3mP+WYt8x z+c^e1lZP2^ns(#hx5Tg9EB2-?odLPo)nhRL`s7K2S6>ZK00VSsiRkQEgR56NTgPI7 zbCET=8Re)32D)8o03nUu^1U?RRhJ_t(8tubelSOC%rg|de;xSa&oTNx{x*K|FMY3& zlP>p&zw@RX2F>a8`XhVBE1CABnF7ik)F?KHwHd3T1MX{BM8G_mJ`X8k`*ni8AWlIRvK;D0vHqE^5xDsZUdde z(p`GG$uIdfk8y2T&CfCax@Oc$sDH^;OW7c;T9q*wiQ?o=NpWwgJGU2pVD)<@i z>ImEX`}(dOU5D)zP5}&V?AU?X{?0mW+q$%2NSijaaY&mCv}_!t-jk&>3b&3?mkxJ# zY2}bH=(sJR=#0qXSM8RUB(IRyg4B1JPCG-Tb*O&*rgCJ8^Kr0=W1PNl9t+>tiM=Nd zVPtjw@yuIp-A3Q+YzC&y!ls&sx)>Nh;di;Ubj8;RcGKzXL@l-gx<+DsogCw|MufE> z9N*eXApra$d%li$IP-OJ&#?DIi(E5sw(T2fsumb zH*JTO8c5PoYR7Gp1XGgl5;=Xl@{Y^r(^3wF`+~?XBWs6sXKjwOP1u@qyU#i*mryHf z7a|=&n{z}crN*1naX;Ma1_3^Q?iq}a3}@#5s?qs_2M~uLc3--Juol!?PyW*J>u>yj8>v)tigaK9~Dr(jx1xHP-{jqiqf-X*XDS&afZ`Ql- zN4!~UP3L53pOjQ|g-lx-vdUZx1qd+E*N@si`2=s>`U&EH_`BHuo3Ep%+}IuZ;{JU= zY_R9TNs*2|9M|uXg4X_u z73*dP*uV>@(~5JcPzR*zH9O1#s7KLe;LL!Uqiu)vNZVYKpNNV0-+31xHGd&n;(~(Ka*+uFm>|H!@M@g=`fGUYt&_0hR;#Pg*})(POxyZ%_Q+wx zr4qJXy9rkEkW+kA|80*TvvaCcXZNn~OgZ(N01NPaSVL; zp~3Ov0XA-II(wHoKylo8gLP-9F>rQ4a~e3OXT3Y4vp_SY^_zhuJWT`bLKGXAC2=yM#jeQ{0AQ?_bhqDBlSS`(p76~Gpq*5X_bQp(>`)RcRMIsCD|D&vPx$`e*WL4 zm+Q_X=Ki}M;-3xtF@nGKEBH&l@?ESM&R58@%EU@z?o*+os*D4YDK9IG4O{~>^*%iY z#`)i+r-`<11%Lqe?itL^qGQo8I%%lx($h=Dq~oGx>1bi}TPgwdx|UxKD-7L}sU$z8 z$RRRb5=G_)_#`auOID14fDm74A}-X#IL% zW+uSHhf6tY+fkQqb~Y+E%XsYK6paE28%jg6t3M5#vb2twotQ2h*oV2i%_qhH?_CED z7dy@w0Cruzg2BmY)X?MflGh?5{-(9L+!Jf?R#+x!eZUF3-yXC$-Jbsh(E zzcmlgnooO`9PsRQKFi6L!_thFMrf0BfKs)F4fpQj{>BZt?dtFC!->O3@K68jPY^{B zHmq4w=&0sL>(`=Z;Vw$^k%(y-2$_tcYzLx8fk-K3L@5LE`{NpmedtEZpJ@|wmsSQH zIuzj0A^ZKo1K_>)o_?I#s0UxxIk*y^+H$uk%T`<@pVZuB_ayMFerb!At4TC!bu?;K z4wKcHesMrBTE9(VPY&yU)B1P6joj7Rv(}&1dy23v9kw|*7zYY-1BV4pomY47!uf*- za>u$$?Wc?T_n}rUD$#P;3w-r9(uL)vm-=3SeNl88pU;VFTjqGy zjp`~KAZnx^;qU(z{_?N>8U_mnir{dWZiH?9aWS+@X56z;v~7>2Fw!s(+4q4w54Gi*YPQsM+FnKq0zj@M$BqT4*%L@``?kU5%bjmSCtuEN z81&_(C7y(M4_r$1sLF!7Eo?hCz71+8pz{7{YnKK3x6P>H8 zJ8QbsEcx(jka3SmJ8t{RbUB7}%7$1S`6}}|*O7_VSGhqHbskNMM%gxfI5e-R+1w>a zR&cEj*RE0Se^UzZc-<&IdHy+=@XM@K(lo!YfX5T#D21VNpng0)j``{WRt*edNSvWt ziy}N4dx8yX)*=umON~!WVPw%KkXm@uKmrk9-M5%`7zw5|z=N|&w zhk^bc3=gfsKwlqj-oJ-SH*Vm?qen3_H;13T{~l_O?&JNBKg4uBqRG*{`*3Xk0jwGv zO!e`tfA#~+Oiin6=H2VqTpq-0|KvZ%+9te$Ee?-Vv^QyF@}=+e3SLxO<{F;U?jl)~ ze&5=wq4U$-yFjI4Ff#Jhc^_8_&CUYT(<@u{(EQ59neA!2&ly|Rlhzg!POux3(k5Ez z`kZBA^-wKF{0~oJ{r~juqPM4#n|$QS7{ZzxnJG+alNgxqOC7SGG!D*6lh#ku^~SU` z?|HVY)66R8w$(UKRsWV-;H0Z_;Ea)2#bp4K`#nqB=KIz;tUEq`EaKn&=fLS- z(2kZF^y)kBV%3vLfw{Hb%{^aIqAQJ?^{CK)1KHCoDy&_|T|OnE(DOOf?qw`ft3R!C(3z|<9JT?Gr z;dA3}+rP{+x>DB)qM;%FUa16F>j`Lc>Xd2w@m5Q1Z1yeROIcq#>i#N&>dsM~_^a=` zfLfY~^{mzaTBet!(q0&@fuO4dC#JsON(Dbu1a7Jop1L?rb|Bg;58>cFUgWSHC@{^( zSIzhL;Y>Z+wXAPq_39-#g1AdeaTwys=qNrp@f?nP`Z@Y$=WuP$E<9N~ikZOy%m^cT zJ7~7QAG7`a7?_?(*u0IbE#t$uPMLf-n~c@RY16J8mKv>+#my$|1*^*spf6oAD3!X= zwwIeOUIgynU+z{|YF&oP&X-kY+Az)FnBRGO-3NODk;ey(h|fTk)dbxbL;2)&toe`f zBPowQeu4vM&kIh-J>nin?#gRboVw@s4&uA}uDc`RGxH;L&1aO-Ai48^*+)e|w13rZ zw5n=H0WK#{{~J-Irw1E0ZNOarAn-T-H{d^e1@C=&3a=c07VAex8|I~1K}Kq-Ggivu zG@p~#W#1&HvxXBok3|}0x{B2=3$0scH${K)iJiUE(>WOyLCa~d{<6}SXH1)uP_rGk zWtwaglUBa73XxYiGU&2dO{x*4!I@5za@W&Xpk_ALanxl~ZJkN)(B`1Lowjgh@u5cXK- z<%`#^;nIy8s_gjjG{*ntzeM=oe-A_JMld%&k4jGuYX9O>%>CdDDqq`;H%EH_0LBqT+w+nF|LZGWKt zH_D^av1XJl2J*w_71E55+WW-$&IA~op2p0;08CJ@zxSswH9m>a)x){RGy|-gp>4_> zoI^W3L`iFokvRAPqf2Tnn!dw#>%BI1bo5Vj~oe5E*spu*_nEm+Q!WF zE+0Lu2z4b;tJ*i2uQ}|jtztTVpw>MdEfJ6!Lv4eWE=c5hMq6wwo|X=2VUo&T4+Y-k zbzP!)ZfDvO5GcKPsUF}$$~u6Qcj#=(2q7Ze+p-bY_UuAbDq*g`=?`66dWy;=+}pAd z2!MSTE-uM)y1RK3!YIapGv}eLD{>ox5p&*Bpngee?oBVMJ!{?$>{`1Qce-?!z8W+? zZ%=vdB(*Zz@^N(YI_0!wlx@wrJmyB6hx}4B_6Sru=0lPvO5do7;nn!;*=HKIJ)xmq zgn#1=V5qlH^2+=I!Z=2RQqnrfeKq!z8f!fgQezHvJ&luG`!tg8dZai45nub zfTYFrMCfc4)LTnZAN5h{Fm(TDHguh~S11h(*pEv`j|Mn<)*koVZt4Q-E)}I#MAv2j zwKOJcV>6OFK0pnz*k!?O$z)j(N!NpVd~NCc${?HBG_z|4-dUm%j}(g{+!rYx=xEzg zh_Tn6tQ*C>Et?R)pw?3^bPQvcmX02-Ux#x?4&uPM^Ozi7)$!*uHZp>%dv;>SvC@amA9&sp?YzzT{GeV&vW!zaDL{mK?1Wuehg;M?C0P^|(#`APdXKWC9#51w9U z!@!`SK>G?7ANcLJ_l^M#l&x_(hfO%B%x6`7;y(ceTCJkXRVNyhHYw#5p4mW zo=3Wm_ByFqjq_n_EZ1l$&-jm4^pi0LwWx-kvUUEgMG@jSM!8f%Sa+Z{#-LiOAqaw$ z<5Uzyh~gNfFhr?TO40%V=Bhw%kLu)S7cXF9d;+f@e;%kX*81b0{utkV?j@{Qw+5(3 z2mj*AWjuWH1i#=pk>qC|et`RrAM3t+avSBp{}-r^_T!J%^kd<#{Q-LZn_oojpMHq& z^LzO0uiU|Bzj__zlC9U=8i)D4e~o{IKf`aI{$DV(V?6-ig(FAt!jYo@fY=zsQH1$w z6@M^LLbX=K_g?=7PM-Q0`?l}EqYaz!#rO7O-@d*0#tG{vKfkbm|K|sP4)eEv4Zrx! zZ(-et-FWrM*)K4+uz;_hIDyYEUc|3_g$^uOYj|KP8pf6ba?Op)Q#_8V{h z4*-B4zWWY#ZrOtUJ9Yv9uHL?dFPijBZB?Etnn&uP>~G31)1==_DP?he#a4`BM(K1} z%^I^?p*XguP?hpj3|;zClH|Sl7&yP2tha#;TaC+g>t(*i{6?E(<%c(n20@IuzFxfb zt#2R>8{-{g3>Jt#G)b-|SaLjnOWoc;HsuzPfv#K)p|s5VW65CO^vV9+yP#W#NXCVuwqZ(_E;Ki6@)QZA$V_uj;hAI{*r z|M9P5*Y@qX{fJ8;f&d7OMc_b`!r-*MnR`J!rf)_#b~9(7h;lw1tlvpHeOgtQo-P^~ z0D6o0wk(Q@>ZH2Vr8Komdd(_FO5_p`YfG{uy(aoJid1fx{0@`vWC`Z55fZ5*aqwn+ zWqSS9>#dZ$xCdH#V4W!I`b&sVLWDAExVvpLuI$;3$QXUUjJ%bFFdJ*;T}x~_4X358$*eu|@hDnnqHFHKBM;lnRJ$1ncXUq|0Sv9(cZ z1K77qoqjN znE=O6eTp;B94QnibM)|b^nLFLf*tE}(*nR;UmvdT*nv0*vHQYhgh2g#iBRBde#(TU zEfSCF?f(DSd($8}lJrXKMMP#+Wo6xkDpVEfKpnVmG=S~~(1SjJ?&)KOGn^r3c!=b# zxJxr0yIS!FCE0RCiQMJdtfaM-iCSrmG}0)eII_9Oxo7&Ao@P_kCZP z8KEDM9{#z9M`UEy33NQO0x~1qJv<^k+`sp|&)qp&rgv-Ko9ao?F;okKwjVca+60)U zhWqy|Oi!=OH9}$?Vl|LkJM$K#-Qt&+kJD`nA`#GtIBf@Kiz_$knU0rj4b5b4I0FV3 zlhs2K9c(S>mtY?`r5Oe8KE{YT3v~Ut<4yzRxH6EV%=b%t`^M?yH@2|vxy=M z)zqN*!9#`V$VoJZC{lTey8b59@*9cy6X>PaC%aJ`Vm)JV5y(>?U3NPs_?VWTfNg(P z)!QwU%YwPwH?WaNCw+qK*rjV;>##7FD8gV(_K7Hiqa%1=OhbFIJ<$E}+R$SneHV}O zJ9Lv`vHze%+3%XU5M$9%9~`SMX?ojD{-H!ROlZ#Z9@*hQ-6>ky!j?OC@u00W>$aIj zVHDec`(<3XbOp&suwd`rP4&=C6PxdMB0fEvdC$10!Tz@?u}zarvfY%}I%sgAEZDn4 zuR<>LWFZ;_UV2HxyYH^d0=gq8C>WG)^7k4-iTQ`)~n7L({+dM6}&Y43rC}!s7 z@a?zX#8*H28e-8X-a2~*eZxaIvU?A9wb?dG-|!HA^5F+4jK%Pk&%Oqo1Y4cGb`^IX zc49|ME1ucA4?|;P_`&I)0}ClwzxN$zfBFhgSL&oUO%v98576<4e-G`CUT}`5QYrl4 zy z>Wd!WE?d<6ht6saR~dItJ&<@Rm7e&Tuj%4@IT|NHTeoO2&sx(M^{E@Ed} zJD&dX0q1x@EQViw^>w>k5}~_y>o&WMXc`)7>}`l5nub4W-;VRK7}z}53pcLAFbpSf zT!j}7AAv>!B%AB%(YUeJGd%^}P*rS=)c)Z%oLY3TJU*%V3ja6Q>)qoe@=y`kGJ$ZO zeV6m8u=*BfPY;kzTX^cJkW)Vnc)aY7;P$vY9=XM2@vWg_7H6Hj7nw?w;{0=mvj%Jf z_IUG+AN>%E$>7`ddT#*D`zJ01inSGGKONMjka_A-er@rot=#+VWfRffELhLRdtEsQ z$lcSk=gg&6%Mpb+UuL4QeU`4aZ91(+vot*S^V9h7_)$!icn2B8qEUSH)z^R*U%~fY z{$p7CdVv5z+n1g?fPI&*U}Nt90J_@=wU2mkIWphvx^uS6-zT=eiYOe@Rz-gicR&>n z5e)HoqPAAU?5u^pzLmX>Y}14Yu@vMRufXz&<4AUEnx&)mynD2=Su!%yUo5bd7)_z3 zyw?>qX3hD=Z4K71GtJxkz97_yS`Tz87+YD}fW4zLk9?sHUe zrO>2NhkDaQo*{=hi`?9j%H!qO3x+*x*&OID7LtqT?CV8AEQb2(8o@s)Lrj?qIYl*({r=f+Pv8}{ajHT6Xj*jl?|AgaBLb`!TkoTRr7Fd3tVBL zDd>a+_2M@c5C&~Oj%aKI`unkBLEAw7L?}cEid;-{ZrppxW1<6ARklbEyhCzCuro}E zHidKCfy>A=ud8URxbI4Jh6!!5la&X`@s+jN3}_>>%61sA{diz?drsK^mV-2@3F+;Q z%7;k0o%i{}OO(#NoYi~&qoWqe%QaL~tkMNTxX{;UVPaxsuMzaESbm#H6q@Do-Pe33zL&;TNkh)LCKSHnN4xPz1lCeM|dWP*p zAaBganYB1FP?w?&Q%b=`S-#pf-J?M6RmBlo@7PBxR4Mv)MKWn*bs|4AHVSGD@YW^@xrmAh(;oIz&L;i9fza-V{%<}H7d)>p#dm} z#_+`#Pa+YIb4XP-wb8iOGPEJhS#y-w1w`fC6RG;#WH+BD&{(zcwRLDMu} z0fvEEzG|t+Z3!~}3$pG)6&zw8;oV~dwF>hK+|KV>`NFbRe#_txs}Hp&bEyymJiN+v zzpHLgf2xWri)rOrunC~{H#Ut(*zHg=kq)?gyajt_hg?BDbs|$orf;G_T=u_iFETqW z-=%l|;O5w39~zV+%hx>L`S;jf`x1%^HwMbDMt(h(o5#|X+4(0X{xZKmdxoN{>VCHJ zm}2kn6mfW|kxmDycEpGPMG(B9bOo5$33+}O1fNh6B-N4=TgI}Ijc z!h6I$DU7*Wplg3|HG@85s+YKf5=4<1!n2a!(-4mjDk^~1Rt<@S{rja-KxgO5UNh90 zLwF%K&#XG1%$?nOarX8nYSZ=+Z-y*)`S!R%Lw77;zdydKmF{>d*+O9QQYCz}_ph;? zN(UXGWM4nmn02td5-kjFtigCixo_zqmKWFW-$To$1{4)8ZMAI6vT*(WJ+w76BCaTF zZeanpJ39aXJ6qe()z^#ZxjEpPJxizJ=r%Oh*9W>5ZC5@uf?BikDl-^|%}1x^J}v*e zq7{_;Waza}cS1aVSf4hJU!A-or$isH%&y#VC?ZD?{k}AwO734~6A28|2IP@rb4Y&g z6I_2ag?-z$BNmN%r`0s1A`xc-ihnKLdIfIQlgi#g@0)OlW(cSM;~`M`PU`L$?& zvf7qEBtcdU|iUaF$ zkO{HAu(l?v7rAzWnFywnPIO9&L0xQ?4=2;2BuIy8@&47)f;eQ0#G225HZ!Y>*^bu9 z@>0wuvTyegV(FNjpU3#*Bc86smCNvhWR>NmXzQAZh~#WBRYFWH&mg! zu_0K6`lo=q!$5U)pyYN9`N$^|OLqvDm&=gX*z|ddG_O}HkdFsxEo&W&XxG8pohUw6 zIpl|qB$P^uVGvB@7H1RZe(yC^RoGZrg?Gf&Ke6XP1UYk1RZTw6=8uvbVUUj9a<1<{;Mz-;U*j z$XrzcM^?b^ZvN{QvBiHyXDN56@*dD~j<9p0MQ(r7L3>zBxE}`HbwsSA`#9yv8Rl;2 zfwlxrrc#(H))4>QXYu)Go&^BBJ8}=^=XOAUsSS$&8ux9-&cplc4Es~Sp<}?74fch; z)(%uBfZ`YcIKrx77${8?+j)wM)fZ2AR4U<-K2MYsC4{==gNPA9B+lKzB?(q$Cg6M- z>YRp-eV4A_+TJ~wEXzLDF9pobWgZmU?_vjJ^YArQkR!E(SxIh786*$0OX(X$#U1*l zh;N39w~9iB$^ywY+b`=0vQ#O;&E~R|;XX$NUo`^} z$10Ie>P{N5UW`4;VsuU|d29~WpS=z34^IHq!TL_R1}5ueC`+MtDTl$R?%w@$*j>nB zTr`jOUAliE-mmmc-onhnDB7!!3T15D_yXcF{~$1xFsV)#RBYxwu{sYGh23JjDA3EI zG2fEebVeC2J9Ad-Rs;O-*4Z=I{k8uJH~#Yv@$p~(2w7qrkLvc|NnoG-2GB}7c zsT4lGaUIEI62*xGYAP#HR?JsSpBtIPM}P4T004c@KHThhVC&7NI{-~X&2OK8@ue5g z5O60e6}(iLpm|qz1W+p@?s|yUU@p3IF36q7+gMnz7wxRg|7QxZhRDUvQMV5N{C>PU z+xOsbvru|m)}zI`S&BOHe03rSIX_I#&Z4WU8N@ zwkT#p0phbqX6l&%3u#mj4q>q%hWP+K@!7e#Ky8F#y0{n*H#cL`qi*P+f!5SpU@PUC ztHzu;yS*@KUlnETVbJztiuQKEahUZ1w{Kf3zVfzx#gJHs$RB=Uv`nZ)s>(o9({>5) z0Z=B-aMEzX4e%|g#G3H|gAd!>g~^Q!os=eCm6a#fnWZr#vw(rkcm}yHJJ!|Q6nvK1 z6OQTGSxnE)q97JSMX4zM4v&qYw76K9SvNO7kNL$#SK6Tq_mHkG0*Ye%;P@N{u6N*e ze>Xn!rI*DEcZ~t%aiCN*1SY1Z@X@tvIQ8sN0KkTd3TUt}F*Sut-CfW$4Le)gP!Nlv zqSPI{eeowBqNbo26Eo9z@aPe&%e}C!^rGy)eF-mq(Ef*ZrAeARoh z3Pa)iJc_4hNG%}Lz!L62bVD;TV+wh_o|Tme2A^=}2}Ge7m!Q2fhWw{q{D*XJ@ggs|ObB z)oIwu+H~VA9U9U?&19K^w`cy0%uH$gxh%!W5n}y=nuM{K22Hcj)wOo@34+yXlVRKU zNB)vcP^V^YWm&Es%Pk+XbX0(r??jyoPHrYvtM0{wSQ1@1jOF*YokSNnb&pd!rF3!% zJFnlsja@r^%E}-fg|Vv)wa4wW#|NsAJd|`!mlc z@*L%YmEgzu3d_kPR($uP5F9fz7Ut&Gx)#BaON)}<)F56Z`UZ*uv7L(l@7~`@7L;@0 zz5pUMA z+rYNXEvTui#Do9%1N3(fVS08pr>DSLik?~F%dRKi4~w>KE`N(q6R_KRk=ObHgY; zwG#!g7^Y`uQGo*V|1aMG0CXK}!PMX*6vkpGipMc~<^jge+(GoWjyU@7;K&HdOG+^_ zKZj@}g5shg)NQCn3p7N|p2OXZ8&F+Qfh%`zqcl;BL%VhhLEDk}G-^MYME}Sz&ivnJ zfrfHa)@?w%sv6U?vzR*n0FRFCSYpsN?O(i=v$fM^-Ci;kg6qz!kLhXP=1mK=wdX z`f>5xMI?Ub7@j|TBx`!zG_mK}HKbDp(wRjaOi~;6*(ALiTL^-Brv2cpN!u_LPc@fc zbUpP?fSI))$a;^dNCe}R6(}2>fR41YxT{X;Ew*c_sbaX&SV%U6}prvxsc2#JkPqn3|bEX~M4W z)Yslb`sqf*kG7#88pUEVg=8v;L_CgySQPJFI1d1L<=AtWNG5Ul{#}ej3@j`r(bd<7 z)`m^^%u|P5_iBCbIxc+oJP_4UP+p9}f&!#W1Ji$f24}X{;}>3dG3VdF54K@pW>z7i zGL`BL%Re+lzNXsMwmt~-dL!l`f?zF~q3Shd(yOvyvV+-N7O{jNJXhX6nDi@#M2Ljhf{qlT*#GfmTt0LFBh^(| zw-P_~%u(m_+` zckB_lz4%#m)V>De%k*lLU&j^~v0-S~^PU|%9E0`U>%dnz?`qf>PJUi36wS_J%bmNZ z=^sQo6M)#<@z9>sRkr-waM$(qp<-kVMbop+t}Sxlwp&6H-RLr8`;rH}iD7+m=paoY zh7NiMZnGNE_bD4kUe5w^i1m%-_B977Z)w+LZ-dNr-QHY{oD&%fKQFQwUd~c5KQe`` zx33`jUw#SAjSWIDkqVJi3R`dA$?zG*!o57goRQEwv6Od9wHjTSE*Lb-C8y9eb`4u< zjtR$E8HrehQ?DQh;`8^;>#YTdb#u2hFMiBfB3BRWd($()&s1V%pLHh>}#b+kg9I%zyVZaIpv2xhreFf!d9T&(5Kye-IWl=i0h6*3s6$CpEKG zz8GI-9N$(nOxV&hy*oO3fjmWdKb3IodD4(b0BjAMg#~*;)=ENUi#;xy=z4))-!7k9 z&(C%xdKBK9`EziQH;c#U_#y_`P);B!XtKAS_04t;yU(Sm%*=J^l_-xeg&hXD|DKgD z`YuI#N%WrE4C&^M?HJuq74Rv#VObU?XQok7lz^`5n4O=)Vlst-SWF0#27t-wX_%IU zL_F@;M~lfMX6NT&=(@Ah)8x!FOp`ph=>=dh4OA9kW_A`oeE&TFz{^LE2?5Fvx*wr; zXb{H_JSANB^u>>HVEYcVY~q2|6Vuc9@ZB>o|Lt4$v-$5|gjQ>pHTQ$di2dX?rVb3@ z$7LEy$g0|te}5h~CuVVfVvs+BJHsgX(S6|e?e9}FGl&-!BJnGSP}tdl&Gnm5UtNO> zH?QOH?tS?FZ}+0Ky$&aiAH(_gK0;N+2DEK&M{j)tuJ5lyX>l=LIcjU%KYIT(4(;59 z2R+>=FDY?$;u!7g#g)l%y#D1c0RX=J_M14gb2pmm#8tXWTWj&kPyPho|M|N}{mDatjwclJJa%}k=RXCQynb*eV zF->4*1}G{5R&d^X2oEHaz`1i4tW_U6mrFkm2Dfbx?1sGpcKOQLRD%;4FZC$1F|Dt@ z4)@#JvR-!~xrmud4`Kf0Ip9Av2CA!lSCm(?-TCM_k%M#Xliiuz8}d9ng?v5H^Wayn zT<>E!%JPTYGrN0gf3B_8wdwPu>A8~2?J%2v8yV|~+c{?D*w$Njpj-BWr;7n}<$_oY zgo}p`;^{NzP&hpg!(w}EF@A0P59lIdjGt>ToR&^)HF1Aa z(W+#39tLecA*iVVo_b2dxpVf9%(i@9DToe3`BR7>@D3u9yR63v+0AS}GdDY-7SnkP z;&v*z>!aecdthLO17Dv)9+iJ)}HZoI#z1{>=(;)TOU@b&L}7q5Nx1PWp?yi;6^fsqkBwR0DCwzlD3R~I^a zdvG$d?KZ_X`+Kl)_dNZC6#xJr07*naR37~Dj-9x2=QhSBCzS!)01*9`pFwPL99mO3 zcK^ZWaA?C1X(7{DiR%xysM;}<&fe0 zVVZW}aE?2ygjfb#xL{#yY_+fIZc%==Pp)>6I(=@fpA%wUrYQSTr>!g#^Dt?)+k+?) zXQ{{cZosej)igq^9um_tXzA!cU3V|iuvf9s095x6!PIqJ)GbU_R-mG(d0DPk z+ux7P4?0mgHUSd`QZO>(JGE}9{bz%Fbm%cEx~O=ie~`B77|TiDJJp+~LN;Mpyu$JZ zZs%Lx!UE9I0kpI%TUA1=5pwsGT#Wo!>l`uni)#>%i#psu$Mi-j>vm1JLWz3H_>c=-K~VBHHaAq~J-r5!A< zSr)1WhGAr+VJpLbb*C0=M6yV&nJ0w>nbTD4smRYvh9%_*@gzahfTKtG?|%Kdg@+GU zpAXCWKnM{_>0|TF8{~KJDtl?ap<30UeSa=0mRfID^JcH>aC;t3Z^`(w?R{kHbaE}4 z<+1Z|#hLjaEr|EQ0?A~*KA^r=*#_dr`5qq5Xl3XK68)J_v{5fnD+a#kIpIU`w#EDt6zX{Y$R27aNTVK~TOwG*T$3J`v*8lKBeD2;~qNubC`rlo~)oS3{OPy$MYQ`_U{8^zc zuO7Eo`mUCCUfxs~$7{`PcvtxZL=;40_|nOjfs^7c(p#H12guD~Ijz=2+R*_-i%n9aJMI`BTq$Z58=3%Jk!uGJQ5AU8ohqB@l{Nl+|LK#2*_#-sd z)?sV&X58-V#M!Ht`N_E?%-{Vs^sl`ER40(mbUau7!?$s5dJ)<`Ih=VKKze2Yf8X}c zp#S^VfEvEt$^Pv-aA5lm=X-Hc0>A#nF9NTB&OQ(|@Xpg`P`9xL3k!>w{hgQ5P*;bm z9ry6YiRYbs-_jyDe)teJR`Zp%0XQpr&(6=`TW`LJufF;kK7Zl`XQnoT^?nEH{^1T@ z`PP>)-#?DjKmP{4X<0yV0Zu)86epiK>IAvBHa4QAp#duVM#E5CyLIN`>Iy0jiDlAUUIf}s=WTrY8>YG3 z!}6e`14ySW?Af!r*A4M_LDi3Y_3d6x*zDKv1DAJo(rZxpS52Bh(yt6eBFrGxMkLK3 z>1l0gnf#oXez~9~>G?t?z;3ZX{C)k?Yf>(?okY`%Er5%?ve_TFd(jhj<)NTnud6mT4sxkV@IxLk|sM#dop_@nk}6mHLa%Dw)fV^U`CoH%1h+ zC@&T#Hj6x)U)^uqw4_v2z^3Jj_f2!l$CeQdWhnl_e(c@4ZDq<2;X>KO1WG2SP&zS* zhKJoqBSOLi?3Pf|JAhRGBP469QCVDqQAvo-2X#GtPQZ5B2}j_Q|Cpafv~!R-#?OPC zXHdN#{4G;S)MD@lD>JC5B3o>^ip)U~RAA2Mdh_$Z{rgsC_lgit7FNf15w3 z&(Fb`q?k_(f}-p4v+wLLD5B8_wl+6AzCzD*$t3D~dxfisES&oF=v`^TG4IeVFCV{q zT=x>40iZBajMl0{dHw3S_8n?otM>WRH2$7H-h;DTJTL9X#b-{Z*03>xu1hWdUaY0? z^|*mek9sgxRS_s?8vwLzH5lm_ME?gjQG0Ah*7ReQ6^PHxp?YA@c^2GTVmkX!Y0e7T zytaCV%e$XCwc_O8Pi090D(f-ClZ72SG#G}3d-v9^4ywN7)1o)8CvVhJ>XM5dyj(qs z-?-v;Jz1yXU}F;fE}wBTVUbJFan0790n1rMTRkFEX5h9K=!nG2;Cp!JBQaix=Ti0;&N8iMqqb<;0-U{nK zpMmzjeIChF66T-2g`a(O1jYedLv3ql#IL^ghOi6s=bwL33=)6&HNdohSpF*{MIyoT z?%TEXmK`$Fmi=6EtcQPoS%VhyEf?qZx_*c! zAIop2$d-AKw?|b6$~JAd)mZT}=gu^eN=!=?TK3&NwrYyJBJW=5H^d%)O~8q`^7cIN zduD;cGFPW+x%(-pO7#EL__=I-g?xU!S;g-5Df(dPC_r@yKyy~mwkIZwK3w+QgoZRC z!l<(OK_?=q6s`xfsuQ=4sjEA1>cr^CuDBIa%} z+}j}T>_WZ1EJql${RBbN?A1PX9eCjd4Ig}9t(nODX(rad`XJYZfb(Rg>u(zL6jc{!Q3=?TD`vMM*ZOr}}+BB6G>%1x4+4nGz?K5{6Kp!ttKdk1q1 z;>&Kma}U-xuOgjJW1+GDU;lG^U%TnqS(yL+9as;?aQ46M#)a_(U_OQPFYZDroyOSI zB)*DK6lb4*d+yG+G8)e(#E9i zD>P)tH6hr~J$(cbLx*Jnrez{xL{M8-f@oyAT{)!W03_O91Y%e8>f@QQr8)HwsjnA_c9Z6O1GnY0!Hm~@3AAN} zD{($fSZ+Hc_wu~b%Ou%N8`XldIHrhc{G?dXT}Iu@CbUebjs5qatrZ>ZEq*tZH<;s( zx{7? z)OBq8@^dK#FW zUE_*{SQp4ed{#qko%)rlJ|~tVht+rmJyEwHmCP(5twxTrtI3mL+_mIac8lT`DZx_S zr`u|g$EF~*dQo8^%1cYpJ2Z&;>YA+SLo5x&Q&ZUdpc8dHeHjP3K>`r$pfP(iwpWzh zFgT31JNJ>^ZeXIkEU#-;j*P-crx9I93IW@E7Y)%~q3uVOszhsMne6#{C_d1$^J{l zq8QJtYMc#PB8I{PO*nqwsjO)W=jO5F`pwJ=+YmS~t0^7xxKE98GAdDmd=`&e&@i<) z4%4zwQcy*nhWaUH=gi*e^YMr*rDsy>2edA{U$wy|`SN~NwnV&ycRrb!@8P84z?w7J zImhSmnN~bJa~bjf=bb=7+W@doSb)j$vW#fVTaXUE$`=bWcaMA;Xp4gLoWwDRK3~;$ zek|n6PbzfX-igXEfZMm%&+ojJdh<$Ldp+pKk0Y}2aldiGeay{l-MBjl#Ip9xEIZxx%>!(m$YA?ujwQM79Ki7iVmPTyZxfMT)8_?4!eE#_tQSklaKxu)! zLoVwCY_PoJGgf(3VH!NGOLYmd5+|)cEh`p{A`&t1UBitlX&jur*Zb#XL2qh7u5CkVf&3+#G>GSavR*Iu8NLuYYK4X7xQ?vNpEFX z)TZTF5C5I5+!}NcYi8-zYd-nYY2f|$EgU(bA(2?ZC# z5Keye9rB(_)q{!5EdM^GYxE+z#x9|p^ZM|B z_;e;0x3GB2pgUe6!*16JZ;N6+IS^N}*vs2T!)6s!VWo0@abeouC9iUTsoruL%;86%#WX<)^x9xx z0Jw3(!p@yf_PFqALcYJ`(ui|*vhFW@=SFgQiQ-#M$0u8~jvyIuA2#jft!O)1kEeFJ z#}XM$54+Ivpc5?ETF=ll>NW@5@4d4LfHa_#lJ$TB-etsZ98u(l8@X_3VwBFR*s zTHhM(!JXk=SVI;}(^T3aGE$KU77Jnm5oSbLwQ;o^y2Umwa?duxagp2%0)$(GNHD^u<(^KADRz(-uQo0X0gexevZsxD0hP5R7*H$Oj1 zkdkXEs{m+t``j7)%B!yj$noSLnoJ@-JC}P#4VWq^2_)h(B&KIzq|<1-dmlCZ15R6^ zE7Y<8gmh*d+tO$Oq8d;#IfaJq?!1GxTOM?vV15CGvux5j_1%d67tywr{V=ixsj|Iz z$es!HYH0L55rZ;RAsp(!Z7;~8a)=P?1ss;BY=)?3ehEIES8RoDb}9QxEog|(%_Fw3 zfJKE5TSjqF5jM2cBN{8gL!jaUYwbZ8C++Ea8_PBkt)qxZ5GFAIxczNt5_dZ8d+zSkJBsWf}+Agl$VrX>*mcF zj?Gb1RmE4AKC&O}ySJjSumHvJBE0@fZvYxlT~PtOD)?&BPaqq;Y zdnlM&ux*U#S!kAp=MFrDlH!$#;*BIzh|MoJldidiA?q((AIRp%VUW{^J|@}Aq>AYP zN#`AWE$hzi{7YXfEEm;gDZ2K|Ot@g!YGY;wxN^mUmG6%h04rxbh>;=U8TEMVHFi+t z6_CdnH6yZh-n6nVG`hr|aFiCtsURqb#*nBeL8P_}r2*oMbkjt9W;QcvT2=@}zn!S8 z2dkCH%iW`{Up!5A*kzbj8dti%kL|V30_*8Gv{uRIf)rl+YP^V2hNV`*SKUDM3wT z6{3+SHrH=*jz=R=fm|Q|{7YC!E@DG@1ybo0n)hr$A|6L|#nQJaew-06C{PB62Z3f; z*mLC?HVh0yPnn3Ml8DVOVsrf_Y^qtARo~sR=YY&K+Ie1lkYYY4dm2y)zS={J<8++3Fm)a8f981LNqPXV^TrL7PE6X@FA(#I zJXD8~OarEc<5jgVV4}aKI`Gz&DqJ{huV}mb>L;k{=|v=+L>dNk=$VziHR#X;7e2Qr z;f(j<>Uhj%VC|k-(JYtfi{c(8cQ^%m+M*xI5>ikE5puI})#VnL^WnypWsi%o7`!$m z3-JUX-|;V7K3NdtV-RN}D(O@9tLo&BGD$A=sl8`Gcr!&hoyPp)VxY9TX(G0`NNS|o zYF=F%QR3z`XU~k@34fMAYvrCmb(5juzH-^i3AOJcfy{`Cd&CIIY zI>}Ghrk4Gx_SnNVLe`N+1g*F4LpM!yw6!3WWrfcD+qPr>pKr&_jtBVQ(nY**ZCfx zYC{=G&VJ~xUk0|800->vMTKz`6?!j}Ra#su1kcs4kPiB3M8W(55>qoyU^M$Js{`!J zoiCV8Lw82CkBi5+Z3Kvs4fKr>+oKFwM^=SlQ!cHxOXM8xJIbaz2kT{)rWWR_JBL_( zq*7R;MNpSM-UYu>ZfdE>n8frVTV!gX$aJ&aSI}{)=j|)#KYtTX{nm*<>1qGN`8V_R z(FrHsaW$f^T-2`Vb;RrXKha!%WlhsjSGFAyy%3d&X2heVh{wtikCg|$Uakn*+fo0h zXiow3E@jn$TRuD=^ZM{TqyXCH?BB%9Fk1Rs>8KnTL(78>bhNhk);C^Ii1s~OVgB+d zeDoLZ;Dd^4JagnJB;xAecM4uRwhWlvr|ZuCR(w|$kd`A)fo5a5txb#U8VG~7KNYCR z?CMuoX#eo*EpR);0y80PXz>UsnliZ?^k3{(^~AZipM zQBZ|a@cw=|3A1eX(B4mNFNuK;lnBd0HT%Yhu7)(}k$F&oCJ766X{I9s(}01E{R5a! z#L-t*=X+mO<>lD-{9$O{n8DCDKEk!iO6=LPHPAC*Ze*J-o8(P0Gxu$hI#UAdeqQwb z5}#0r5N=df0;f)CSX>0&d~;=2-w5&e!`oW*=gYFY(;t+_s`#>fM&#P=pc~Qdwxk|k zEK4kt9#hwjTPBnVYe0rOQ0gY!oY2TuF+nRBQZ86)?&Jip^7dw0V$bToBz0WgsUGS&)TxrADc ztgVVxB-^XXgjhR!iWf3z?2RmWYo+fNeQRth1fIW~EMZd~%+9+lHLumXS6*Ds6$=Z% zTW?u7bxK1lwrZCRvBnS?ncujUA9r@!?V|6LACs4%6S=PH{dboc{Ec}u(2qAi{17Dp z_A9R(8O7mq=QFE(dGC@Z`<+!>84yQIn-3XeTvhiEmUMT1zl0Z$T`qnr_Dp;X43^#t zvL{kij+W`&DU)`mv0!hzY=BQ;<^nPw&FtVML&&W|N88=|h@?}vxpPO>S|f9B-2(&o z@%!)N3opJD=uS0Qh$4waM8Vj&ky+=9JufB*TaLVKpXcumvjo|=$#o9?%xUO5eM*nN zT^1rY=sK`z6Oc-2NG9#Y!6qlyx>g~cG~}W)yLqo)xvIczUOK&wiieB7Ri2ysUEz!v z)cY#dT=vS+G1(HX&aS0Hv=oA2iM?}8F;EzW4Xrh*2ZvBSFzD=VX){s_?f35Cep?$B z3iDfd%nuuehq1ALATtqK&n%51PG)w8q^b26ne|hSE880EJyBV38mNV02_>-dsGSmw zBfItLp!viyLggUD>LC{vCXS7M{!~lI!$&fH%ujt4`L#Rxg!;eucYlrB3*7?)xcak? zU|b)>GymOJv!*Yana%9-EbbC4b8Jx+&R=e_O z0BTFO!GeaWM6;q!`6GxwpQq*Z75ifMjwI|Hx9ZeUKO*~NJ6|C)rC8ominlELEc5(Y zD4Ll?)$mBxpltw%*Oa5>vxji@U;Y=|FZdn~{KXa|nzILOcQrSmIn{}xso6|z4Op2` zQm!R!QF2QXEk?KZCbYgjMJO+~R|qRE2Il50JbJX&H45>hARj^BM6cbWk$L>SDEh{pfCL$QrcW-qeh1_wM?p39)jB zq*7?T{{ULra)J$YSSTBtK-t*DiUe&}jE!OQ{Z3R34kLxAv+cC$%wx3W0$KF+5_GQRoxtpDZuwSHR0=9q zXFIQQYXvWh69L(crjmWBON@Tc^&Pm^)rD*Scp4*dGjPy0uc0{i8m`Z9{`^QVPvf0V zbzgEnNIyRs{{-dnIwT4kep8qj>(Drn3 zG45?`MLc4xShz3Q5#Y`7K+dzvLPA;PM*|o`m}|8`!tl60yl10 z=;>MOnuS6YaOfaV0|H) zOsG7A{Qv+U07*naRN}dxpN8f$1A~S)slvkOZ#Gp@f{&g#;wt0jt{u3uJ=nygT##)g z&$Y(ILkF?<%2iytb_G2xEoj`mbJ@zivu!KVhJluQZ09K!MyHW!__DlgW^5SUv1<%y zj)+4UFPzm!#V|ind;xJbj>%vvs;J(*pc07aiIU%vkfVlpypcWNNECV9$NlnaLiwUV z#`3WDi%GS*6M}2PAl|h8+KsreFW621*2NxJfBrV`XP?iW79f5)%AKfxj@|`hB^DV; zMSq$od3$-IRp&&XAV}J!AX^_5R12V7m02oY`P3SKT!w6iS($#D?ydm9*`tA9l|4T` z0LP)BY%B!+l0(QLqeO zZmhY|uzVsf7LRAE7xhO5yCZ5r`Q2H4PcI%dH)5VGpYK(Z7u(TPP>71svOw1lvHaLD zG>n!99Vj0jLkbZ%(~K>kvEvagOi!VvvJzHpUDmjPAgCD_MB&^#st1QqIW$7FW&`du zbLB8J{y$^QD$Ad~2b#mP#ei(L^`TNPymtbjnzQ)M1%ID-dCSwIW({%g z1@A+A%HZb6!PtkW8GEPkXEUPCCf7sMoq1V|{fg5-OpH}lV2rIi>w~`GA#@K6pmJsw z54yY2+R)&eK0Y^xhOTaB5{l*c_B6uFRoXD5&tjj)o`Cw!)fk@XhOWm@9#_W+rOZ^u zH_6LeU3m3metev=Ne($Gh<>B3MkCLiaZM9+f;7New*5cfRgv$hre(OenZq-Sl@(#< z@4SjT4?A)HVHaZ6r6?})58Uo)*o5kVL6l5QgZ1Y2C}}T$raR9xBq5mHRw8j$$EP1Z688}UUpUg=?^#4SYE^y7tz@D2yJ)oBZ)|c%raL$ zFfllUMJt7ds%i{wT>AE4Rl_4l%*>#2cm&n`Lr6Ii6Pp3e4ItU@h2xTacHy>|b`!Je2B* zZ?C1KBGgUBM>QQP!pzH}k}>;Zy<8>E&Hj*HSfeF7rcqfb!mWBg&KNv0Q&wpNBP`_&{Dp_-KiDGepaUc{P;v@|Dm zw6YDKSi6v06W@}Gk!8LWRPp3As)mL!QoRA$P_?%O4KM7)^vDG6Kk7nTW0P5^jH zD``j3%q$u^x}5v5NbTq!-!>Yctw?qP=PHhb_;f?lfPw8CXm6#<3;Y~QY-t<7F} z?B2b#uHoa0Lx=2VDr0O6xOPqK&ki2c(AjCN(e{jqly+=mVzBH4ox04c#v(1?9NL)56P$V1xTd}0=n=)ZAG$+BNZe#b1~ zeN@?~Dt;UU%NRXl%4w z!RRPp7#7m$FnBwJ8_T0HtCby*7ptso)pcbrs5jrHzGpfH@{z{$8enj6 zwXdAtIO#QRYFFY{-m|h%1#3)30yjJ;ZwNxEk zc4p;gANkuF>hr4j9q;_&5ivhoOWU3lEqh%#V`aU)`j2bSDj%#rBIQNc^hdAb{$G6; zmml6k?bfEOLE8W@SzdH$p9+6OXafP;_zjwL}A+U7wy6NjD|bBB7NX{WWGfhI`PiDhd`BP~Y8)Ew}DE>vb_$(2$0K;m(JcyL}z) z+jm1VEm(#Y+z6FWF*=5}yZ2EsGM3qR!yq%BIf>@Nf$n@4SKa20B?tnHeTIqGJe@3Q zsJE2kq21mBvnXe);LhhJ)Y&M^>J#XxDd65c3w3p&Y!N~n$8vQ{`=!^EY21Pw7qZ<% zK&Cii89an~qOuJ4x3poTsw!B;TdPpnT#L%G>??89_w-`J&@hsj)grja2}RA^qN#l6 zZlM}Zx|Es1z)TNni#KC%<`K%`8xb>@gWBzS;NLW~R6Ugw;S)<($-Y4BYeg$Y3<6-a z5qoZS&L+unPi~Pi*l(j{R?+6`a8Z)X=M2+dta5l1$yh8<(01|R7F6Lldf&f*i#Km% z4ceBU25k*&y>C_*zWSKB#g^r?I$e5Fp#U8sHRl(S!oBs%P1@aii*Uv6%{}tpw<6 z*{@7B=N5ZB`W?b|_D#GxA7k=Gc1xauIb#i^SFCroG%e61wGjDZE*{5hQ4tK)i@iiF z6cnJlsR5Rzq3!lPSV%*IeI0l38hbOi4Zzw5H^-40L!anzcEo13RRLS&&ATKcrs@+Y^339Ze_>9;sU0S zL`_2#DguljtRG^%(YJc;;<@S;l*CE|uInuvQ?@ViVSZQQIrkF^29=-MJ8kY|FTLH! zzIJz5kA05wWZD1k_SIWtGBTX}qSs&iJs1bJ$aw%rXQmES_YGnp7DGpSYp~lYiejQf z!@K7{!t;mSyLHGgbsbYBC18RvGoaOL`d z5RW4&D}l;N4fFHB#~)jmm;ih>un7^u7rClBemb*PI+-tvwmJ2=x;16~nR8=Vi{_(? zS_zXiL^_g-b*3d+nZBDd9Xg)5ts*axT%KlGD4m?d-m6y;n_B>zFsEgdUn?`#GmEvRpa?NNiiU^XXnNR%o~8y| z+q);Pdue#ojl$VES0JOBNdtawCuPneW2HM-`Eg~DEz@K4U8C=p7q6w(AWNOCX9>A= z2*6&PW%FhYLqpbMX3MBrqRfT8a*FB1H(q2yAU%XQZqX4>Ru9DJWVRo7N3Y?;<}V6Q z1kkX#Vvlb*+2EHx+qrCf%_~hXTTJY)Rot7G#3q5)n3$eI^+E*-3;f6L2W_p0%`c#-qYL70Rz0K_kAQ`RHLg&Ib%9)+aJi7`poCh4Xn3fkWlEN~ zFy_656`V9;nS5YzlWI{4P!Vb>+=;ZGmBautVm?m}a2xYVzVXflc7 zscF~osnU|XRy!-4pGSOl4&~$H*mm=_^Bd|Jql3;mE{()sS#cCk&S3wAOGrl}xNzht zjF*+e(sMJ;YWw?9JT)zt0XF2dMOE#{a%THn7j-A-j z)EwY0DDCH@Sr(+-E&!R_$}R=_^L%O!3+W_E3M#OWn#1{?xAEH6-$Lj3Eo_SxBWlE< z>SJgb`5;LDlCQW)g@k0Lr3EN0<YfrHe%g@!J9b$c= zt+5IEa=wfN^M!?&EGrclu{uxVuXU6m?Q;miH8zO{=!b0HaQ4Ob0TSzADW630z zb@FV8#}oPbLPdD@{oX-GGN<+q+~#Q@^nlc+7xiqF*5w}Em~CQ_URUG;RE2imb3S`q zFh8xa(-88c&%mK-06lpT~I6gm*gCAcMm>vM!Z*RlH&DnJk8Ad9N0~ap= z7O*GuqPj(oZZG~!?md4*4cgzQE$Fg6D2J3NMoq@(@h%p`N)$g-$U-^y7{S6Db^^=b2 zY2c%e9^bw*_*m=3edS|fI@RorVbw`^zdbtu75qH?R?JG zxL{#+cCBlXJMtmTbX<}tqfCk+rIE=n|6fI%E#Z9O!U7_xRMv?tGjp>@rBm3yZF``A zZSfw>4Bg^=iCQ}M60+?)v&k7GEeo+o91*<$12erCnjOHwy62#2Iufx`XwYz^;T7TO z`PXjcA@@=$y9FNS{mOCMLbB9AQ^=w#4QCbuANU&9d{u3OoE2M|U51f1Q7}J`g)G}| zwl*}N^$&g(eP12I_uqRLKmOn}e(m+o!N?NaH6Jg;g=Y@o#82OaW?3*YW0k$3qfLj? z8F#ZNQ1j;@I)1%Iq!1zUMe z)bG^ntc9+w;AKUlKwDdWc2->-kVxc}HD@d?+B=~vhi11_UY5_(%EmKQBD8%iZ|?1O zjmx71AohXs1n8wfmZ;rKK(3vid)tk%$w}P!=qjv#xDLGf`jYAzVtG+hS-IlZ&|H7i zIx(G9RNXeF{V#L3vz14Y;mRDgeC>W8+!8XgjcDC?EBD@RS#6i(g0<(tckfzgZ`Y7z zp_&k%G6d_(S?H@uVuf>zGDka?T#EX7vINM3OL83N6ERdY*J5XY6(~z5CeiSyn~1=` z&eCd_(2;WWSRggz{gny#Xz1=A+};B3v~s>&j;{{90`0uGuk3H6e3$$0`FFSFV{=%| zS&5pD53E$#YhsJCI$_E7K32@jQaC%0rp_){nud>@Cx=8-&oA9o%;#Npk0kLWx(=K;!QaxW zS99Z;AwmFt)~vVA?3LGRJfY>Oxvtxrs$$as_2p7V04KfZbLHAuwvkq32i~c?tOQvL z_%z_D^A}JtHU>cat#S!Klha<`y-Ntjo=GI|&dC>-p|&M+sK+Jd`Vw=C)UR}SpMo~zfesjC~Ttr?E3z%_Q$ImT=W8=_5N3CCIMW89hr zu`w%xTjXL6{%!&gj)-Num1wF*!>JWApJkm|Mt07=G^|9KA=U?$JC;Y*d-E+N+nC8U zGPz}{G-vO$d@p4=P}>IEC4w@Ppg4Qw3hq4Y#Ll+%9CGnHpf%%tjZOk=X?o3dhZcZ| z#Yz0M^T+swt-k_8v-R?Wwa1<5E43xf*jTdJxi?d|``qExPvqOmsBM&+e_!ksW!~-f z>3dzD{_?iRhpm)t^J-)k;nD!4Grn7Su}YP{M2;QE6}kOJtYz?kZ6Jaak`4n`>CSZQ zq2Nlo4Kobd4&lbOZ5p<1$$NpWAndi$^6tkRX$ToVi$T3a$9qrH61B2L`PT~ABhlAafrXgY&uq+Fy zR0?`57U=n~n%KWCoukc(v;oth{IXq29m;$a&E;L0B}51r8#ah5OwZ4Y?Xs;+Lt&vE z+&w+<){4HC2_EoSs1}8iAqf=o=bBQ9O>8O$~vrp>8Agx-7IsnvTs$1!FUlg0&Ym zMUAa`!ly^O*|a-|gLXr?sJXPDjvSJk;x) zx~I$yE78y7BOr?^f#{PI`&_S;RM|Ifm9PLglY~F>-;3?6Ah#O!o9fR0CM?9}7SPbu zoi%8?B#}VtuC2KLY$vQA-NLQ*?bxwx3kqW1t7oPS108LxXzF}~SaQ+12YdZXHd&e1 zp8Er+4#CgUd!<}j?YUiEA8d#x7dv)n*t!+y=>cxuTuTcj#9Cu{H0J#B`s>W@V`5*& zMil-@lk$kcqsZhG7d>L-@$^h>3vxI9BR5+Wd1)T+l}CL~FSg&jB^*Af+9 z{i^t4WBeWBXGI;^0%zf3Aog-;!jD5B^`%P|cJJ0uU%%Eh39(eHTubw3zy1(8k^8Ky zp{YY@#h50M>54(!x!Hr(-<*dvHv;@YFd?G0uOB zE5qw;Uxc9<q7}miwWPK1TWYxP1+&709B7 z7ZGN^Q7U5K-4|aF0=IAN*pA!V$t)2c?6`gtja`rMsG$KjcklE}7j!^gDO`N&AT-Ou zwwt%n-1!iF^>w(mch9nwe{V}W?zgw0uD1`nuY3Y~3o1rjnE_y%!lF?`B?wNSMWcs( zXJQgtofJ+fZb4c!PelR^=X!odq(3d-*ICa5dTI)I?>!4Iys&=j7$Q4X=GXJ1WOT%# zl+Qmu9S=nkKxJR~jkR2VUZh!r+~ce9+VRier)NIQnvP-b<*TUfAIw};2NyNfq*)wk z=m^Y@J>T>)Ov{3%iB41%VfG4^QDLR}n|#D*F~4{1-DKG=Lv(6FN+I{~boC3CQqOGG z#9Ecu(oE-f(upJ1rkV1rbw6yZs>0`=e-Yn)`%V16Kl}lH`IT3Yh!zPew?wm2n-G` zy_}T`*v_w9x#zZz@iC4b6K!49Mwo=?$LskqET-l$c|-yjY0dns~aYPX5L6xl9wBPjp%DlA$%W`>AI3j@1MS<}5zjIMX1HbpHuercPui<&GcSw0HaH*0 z_#d0F3^Ee(ry~3N-KtE85ZMro+JFCldsp@w$C01E>K+a`7dbpdQsTKZP2I9&`G{k$ ztz8?)8n%NZNcJfK5+FffAV7jV$NRQ)?tad zD2b9t@euE0hBMQ7sHv{2uNltpu}^%KmPI}<`x&Q zvc3iYczSRsuzVpF!@a=)6fGOy8oyPJq7%*bwp?#ADNUpGRhSMLIUy)rqUej%sDUeCDLPI(Z14i5LI? z7QIPCK~%eNK(tKTl@P3NjE&;X$S?}Am{!kT0_)Sw(Wh{Cc(CT}W%W<>^q@p69J_cK zF%-bfXt-(%4SI9=POdN5f<2t;k(V~3fTkFM8z~z(2G2PQ0)^Jtx2fa5TuN;cW4A;a=J%dO+R;4=dweA~o^MTna%Q4T}$C*ox=i^jQFb}ztB z-;u+l@?09l*%3?-@(#y}&xpHwbYr<#c81WSMM1Vi!|cKW-uvX20DwZV5GjaPv~7I& z>MMBe<6j}ZnTG{}7>aJY#Ju38vOI(PiT0)hIUr*Q+Xe>v8~Hr&=n-)B>h|8{?aT$i zGhg(2z1rYcca%UhJFd26XG2cG@Y4M&B8zo5Bk}Ibc7clh2;S(iaoB@z3uA z0Gu-=;N9qb5JNFGif&MaYD|2wAl#!CP_}iMHp%r;%U!m{G%fCAXBv}i)vDiAuM?;L zRWhzC3oiRzUk$3ir-4E3;O!~WW!`SeE-y4~ZX&g|?#>kKePY@E0o7xy+gGwZB_88Y zEqfi6zQbxzxf*PL-tg0FL>i7fAM3L(z%?D!j^=d+&*8ibU)1BcTRM|+Ms9%5)wa9O zCV_*-%{-2Oc^U7&e$JP)4FJvQG+ue_CHy1?JpSz;;*+5^wD)u((bX0BoUR@}isq$d zWEPj*XT*KNC=nD@p8yLnh(psKt?=H{{Wy=0-k-AX#Sq*X$KD; z?0nnyBL)Y7jt)MbG&In}Ybr)Y2zq+tW2F*s>5_v&fgd|~5a{XQ^=)m@GPNSsS374^ zqQORqB6-ObNcV8Ga;nS`&&#q#*41UbCERBlwXaeAtV}-Hs9&(^arXf%wY2Cbh`!r0 zKnc~AkgDsA^<)wV&l9qzu-x2?rsn3l)t`^Yv7SnntznfOS1f;%wNy1C%`9@JGx6Ol zdF)uE^YI$xxk7x;D0F>9glP54HK+)F+v;sm82j2_FCa?XT0bUQq9UWjkA(P})JUB~^kEV9cZ zy0YA{3MD*q{sOL?I2LJP)7a1umR43Ux43|{jg8Rq0FY~J#6~jVCJ`g$wy~6&OeXSH zJ7Am#%WXC7Bja$fx5$vT4I+UMASo!Yr%n;cumgbkdEokWZ<@yI7QrX1#?x+{uE9auAx!R$b1*y%xe5`J8+Yzj8YK&(%`8 zd%F|2r$g`{HD6Z43`((t*an_!+AC1*Z!Gh@8MusTUR=hh3m0+mnQ$4H&1CTW@#A>^ z(_aAqe)7r3cjtB-=Fb%y3%<4rC-O@&oAN88y(^N8n z+|MR4u~-CoaR9BSe+K}NZf%S5h%~URCz+Jzdx)^H4& zQvtaqE9;!9Mi-=i*4~38+u1wdp)xS23PFLu;87c9%c;48#d~^_p|^{khf^53dB@EH z#kOY_@5ika-a9`nKt8V%wH;*!@~R;yJD6YpD}OGk=RvnO{e1Uf_As|&{byEn{`DgF ztATkj46Vir#7Khty8$T64&EXH7J#*c<5B0^#&{!MK79uN9*ZGAy9Os;2)_tGuBj0z z+Xg9eTi9}?49kQ`dr56}CjIymC16>>Ea8dhJ9!a^dvF;TR1V7m4tV4pN+bxfSzv9= z!NkPQw`(sVnFNN1^*Ok`9mr(Dug_%ka*hKO3It+~rfgOweOH*Mu&$^i#vBxJiUz;f zHIIR*^2mWIgS>0iWns`2>eZaO8vPFS_iQe;w0M)Y4fZuwnlrdFGK{`k_rZMUR#}TI zxuk2ZIg1O!=)aa!j-^Z~x$h5+D6oZO;@ibbaD7gF>%89Zu((d8=Z&pw@O46TNf6a) z(dC)y-4(4Sks-wrEIeszi_SfoTtxO@2ihXa8wbE_eiIj$mhehvpJsQnGR#VnZF05M zdXM#|B=%T+DqfJSU)3)z_r))QTYrdlv;TRnq40TA){k^sAKC643d026n{kioKm(ICJDEE{KN1vt5Ie9D|_%tWO|^GYV8ZDHt# z`M>`uhW_L&BnHD*uCkVW@?-{0u|~wK7^ZVMoNXUe3}Z|9ocS}y&%(V zq8ZX+dB1*!&xJvOYQJ*waaq4n=Tv4 zgu9lR_YiK&x$KlBqk)0Je!}!LaQn7{-CB3Low=i0vUapG!SkA*i&%BMi^qsyBY6L@ z?2c@nwOsnOg(4VH)`ATi1z4~__iSKvAsWOZC<3rS8smuavnDMIt&L5Q%I+7;udLv` zk3RG~cWUe~EX%?dUtNVWJ`3ju9{|Y)kRQAS(!euYmwxmGPMki0CFFM=zu@L^v<%vs}wi$$nfD7lTF&q6RO&fwE@Lp?b=6ebh^ztsf$8#A8qe z8X8bH85i|uBfg*2P#uFv4AtxMmo;<_<5Ukz$WKkmvVy&tPB}-B<-XN6imn`DnZ0ZP z7HqdpYU$W;P=eLaP*d3vvtvM00xY9HV1pnAt4!XeIhkW%7C9-mmcTBz%oei#>(&jo zW>}Bulas9+@6QZ!2$4ViARAjOU+p|1j}`TtUQ)fgm%XOyDQaD8^vF*_oVnSUVzW52 zg2jEp;7SGyF+k93*ch|ig+J6*28uw;LKDLG*<9P)#7{r^0IBvgQvY-T$=`SbO^3o4 z$ba?hX&k?J32k#vz{XjjJhu3_ilOMfAx!4U-k>5_rY|PLEJ-GcPplzsCVGR~qNRoY zt*;ZJHB-*!qMI-5i(Iw=81@9zb^6PnHdME6hT{cYuXLIp@UA+tk@g@VV+?B%W=zSxIK9vPc~N3(%`Y$55U#ix3IOf1pqj7pc}((dkEq- z_eM*^US%fJKYR7Ea^992!>;7ITEb5s(e<3L-IVm%RGinn;?Qcu*?UBaj3Fjj#0B@_ zoG!Qh3~b z00R?u%Xei9pZSi@eDSnXwx=D5o5h}-*ds&QHmDhzny6t(xfQ{a%JQ;mWaiI>ztnl?%%JS3R&?xiKpm%wEQ_Y@Uk>f-0!kaldu}QQPKa z5(HlvOfU<^B( z!VR5hwfMP~!s_R8P<)@%u&hqAjfzjNT*g{o3Zz*lY%i^@;PTCz?)S4tkKxY9FowtP zplf{{wiO2>^6blx z$n8_Nn$lbDxL1oLCkV%gYkI22vKq_sGC5tKP3xORZ%)#BKUbB|G`YnZ&E~a2N*fV%EGlNtzftGZAlCx27eh~%4w0DI?ah$TB9bn^+k+fC%CMhpx zV;*<9ERN;dX4i9~w#ev^*%*Gb&uZerQLphXr?Xe;O%9)$0-Bp)NZSTA10TVT$B3rK zy+6yNop_efuMq#DV*Eco#(b7w_=q=YdwF#gxiV?Hvu(?bOSZ-n__ek)3c`|aIp)k; zCPxHCj*MPLjZ=F?5WVEF*W94ata}ym*zk@e^Rh%Kp)LfFBi3|T4~y2y3xN2&m>i)? z+C{=PTNXsGVhjE)4BWW~3q>?-ZsOj+09G@>#BBh0IP(~ew++k7)CsVCR8KqFj%ZN{(bXE%?6^!-lLd=fZo6&wLUiJ}D!?l@ zvYnsY01k#{IyKmN%r7lsVQC2?{UH-$m5^0QRo!%4MF3@0p$KmB64%7G6jg$&No;+z ztb(d0wYm^Oe6PF-g?ibjZ%ZXc_|6*8#UgO;9xyrzL)tdbP~FKm0c~&vXMFdep(PEF^?&KnNj-=eIygz(BGEMZ{2qjkZP`1$TB4 zO*dv}sia|@TFzyrmn>BgY%qJ1z|}G}a)L`ntp5zCFP8Byr)odqI%Ro*8a=D7e&!2j z=Q4;U1A#EEN7#J8B7#J8B7#J8B7#Qp=baVh69l8hY$`uEz ze@~clkNT*UbN2b$C+h+ zsehc=ukTSKQhM(>Ma&Pui9agFm1)e(EnxoSh#_t7QCz-t1N}X{nygJWz|GsVKYs=N!SJk`we^1g;(|`9q)|1Il(spZeGY)ngz}mw( ze0KXoy!g&JbcL*tSxu*L{qPuGo}Lj}!p4orwqndI9%bhvQsinG(zd}aA)SV&F&v8l zYikaAdr71f&WQwFeO>R>(E9<4i@?Id_SMMUG^o9VN_7S`zmos!Puvb#9i$uL(IDO{ zEMsO(l>e1H`a1fN%{14dHiH`C$>JhzO-_1}w(n0(VQpg_UFAt^W_}*d{5tUY1H_VX zjQ&BiEODxeNssYuWW|+$Ol6>oj%ch}?sisuWO5oC|IX`2xvXeN>vV3tt?Ya)U<_!3 z{f_8M7NXWB{;z%xy0XGnEN^0{yBF!CZZv0-DV#ZSR62I({v;A>>nI{77*_fpn@jX1 zD5CRE{4C2-FM~S>Uj42uz24to_BM=z>JjHpc?nF^`c(&|sx^t!WpO4~N!lXS8Q^P& z>AnuUG`pIuejd6rfky{>14-MqZDVX`7^OcO!rg}tVBNflqa!1sI?iN&A37h;BDuN_ z8=Pp)NGX zn6nsX0GRJx^vbgg+>TOCBm~ODZh1zil(JY^axepfuMbrDS4{$=$~jYVJU0q5fBZ6z z_Vi$|H+(;=##|2ZT;A=8p6Zaee{poztUI zwY?cW>NO%Ch$j&9V+-;5TTKGVe;;v|X8`5ME?+(bw~XU5p@0HxG`O;*6zLfpe`*xR zpBlxrAH9#C|LcF@qy85B)^}bHe|8qZdOC%~+6HWgv8y;2i}ukHMigI&$DWwTbohT8 W-BsdlZ4aFQ0000 Date: Tue, 16 Nov 2021 14:26:04 -0800 Subject: [PATCH 19/31] adding readme updates --- nav2_smac_planner/README.md | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index fa5f3b224d..404c899d8f 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -1,20 +1,21 @@ # Smac Planner -The SmacPlanner is a plugin for the Nav2 Planner server. It includes currently 2 distinct plugins: -- `SmacPlannerHybrid`: a highly optimized fully reconfigurable Hybrid-A* implementation supporting Dubin and Reeds-Shepp models (ackermann and car models). - - `SmacPlannerLattice`: a highly optimized fully reconfigurable State Lattice implementation supporting Differential and Omnidirectionl models. +The SmacPlanner is a plugin for the Nav2 Planner server. It includes currently 3 distinct plugins: +- `SmacPlannerHybrid`: a highly optimized fully reconfigurable Hybrid-A* implementation supporting Dubin and Reeds-Shepp models (legged, ackermann and car models). + - `SmacPlannerLattice`: a highly optimized fully reconfigurable State Lattice implementation supporting configurable minimum control sets, with provided control sets for Ackermann, Legged, Differential and Omnidirectional models. - `SmacPlanner2D`: a highly optimized fully reconfigurable grid-based A* implementation supporting Moore and Von Neumann models. It also introduces the following basic building blocks: - `CostmapDownsampler`: A library to take in a costmap object and downsample it to another resolution. -- `AStar`: A generic and highly optimized A* template library used by the planning plugins to search. Template implementations are provided for grid-A*, SE2 Hybrid-A*, and SE2 State Lattice planning. Additional template for 3D planning also could be made available. +- `AStar`: A generic and highly optimized A* template library used by the planning plugins to search. Additional template for planning also could be made available using it. - `CollisionChecker`: Collision check based on a robot's radius or footprint. -- `Smoother`: A path smoother to smooth out 2D, Hybrid-A\*, and State Lattice paths. +- `Smoother`: A simple path smoother to smooth out 2D, Hybrid-A\*, and State Lattice paths. We have users reporting using this on: - Delivery robots - Industrial robots - Vertical farming +- Solar farms ## Introduction From 1610710899fb2044c10d46d4625281ea9e5edebd Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 14:34:02 -0800 Subject: [PATCH 20/31] adding max planning time to state lattice --- nav2_smac_planner/src/smac_planner_lattice.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index fdd8f18e6d..7604d0d5f8 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -149,6 +149,7 @@ void SmacPlannerLattice::configure( allow_unknown, max_iterations, std::numeric_limits::max(), + _max_planning_time, lookup_table_dim, _metadata.number_of_headings); From ac46c0289108379761bb1b7859115b886fc5d77f Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 15:04:40 -0800 Subject: [PATCH 21/31] adding dynamic parameters --- .../nav2_smac_planner/smac_planner_2d.hpp | 2 +- .../nav2_smac_planner/smac_planner_hybrid.hpp | 2 +- .../smac_planner_lattice.hpp | 18 ++ nav2_smac_planner/src/smac_planner_2d.cpp | 4 +- nav2_smac_planner/src/smac_planner_hybrid.cpp | 4 +- .../src/smac_planner_lattice.cpp | 192 +++++++++++++++--- 6 files changed, 188 insertions(+), 34 deletions(-) diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp index 2da3122aaa..c499d0796f 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp @@ -120,7 +120,7 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner rclcpp_lifecycle::LifecycleNode::WeakPtr _node; // Dynamic parameters handler - rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_; + rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler; }; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp index 027ff66b2e..4395db12e2 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp @@ -121,7 +121,7 @@ class SmacPlannerHybrid : public nav2_core::GlobalPlanner rclcpp_lifecycle::LifecycleNode::WeakPtr _node; // Dynamic parameters handler - rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_; + rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler; }; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp index ec5accf0c3..c34204b18e 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp @@ -86,17 +86,35 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner const geometry_msgs::msg::PoseStamped & goal) override; protected: + /** + * @brief Callback executed when a paramter change is detected + * @param parameters list of changed parameters + */ + rcl_interfaces::msg::SetParametersResult + dynamicParametersCallback(std::vector parameters); + std::unique_ptr> _a_star; GridCollisionChecker _collision_checker; std::unique_ptr _smoother; rclcpp::Clock::SharedPtr _clock; rclcpp::Logger _logger{rclcpp::get_logger("SmacPlannerLattice")}; nav2_costmap_2d::Costmap2D * _costmap; + std::shared_ptr _costmap_ros; + MotionModel _motion_model; LatticeMetadata _metadata; std::string _global_frame, _name; + SearchInfo _search_info; + bool _allow_unknown; + int _max_iterations; float _tolerance; rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; double _max_planning_time; + double _lookup_table_size; + std::mutex _mutex; + rclcpp_lifecycle::LifecycleNode::WeakPtr _node; + + // Dynamic parameters handler + rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler; }; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/smac_planner_2d.cpp b/nav2_smac_planner/src/smac_planner_2d.cpp index 626a94e07c..861fd08e75 100644 --- a/nav2_smac_planner/src/smac_planner_2d.cpp +++ b/nav2_smac_planner/src/smac_planner_2d.cpp @@ -170,7 +170,7 @@ void SmacPlanner2D::activate() } auto node = _node.lock(); // Add callback for dynamic parameters - dyn_params_handler_ = node->add_on_set_parameters_callback( + _dyn_params_handler = node->add_on_set_parameters_callback( std::bind(&SmacPlanner2D::dynamicParametersCallback, this, _1)); } @@ -183,7 +183,7 @@ void SmacPlanner2D::deactivate() if (_costmap_downsampler) { _costmap_downsampler->on_deactivate(); } - dyn_params_handler_.reset(); + _dyn_params_handler.reset(); } void SmacPlanner2D::cleanup() diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 6dce153127..5c53631815 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -205,7 +205,7 @@ void SmacPlannerHybrid::activate() } auto node = _node.lock(); // Add callback for dynamic parameters - dyn_params_handler_ = node->add_on_set_parameters_callback( + _dyn_params_handler = node->add_on_set_parameters_callback( std::bind(&SmacPlannerHybrid::dynamicParametersCallback, this, _1)); } @@ -218,7 +218,7 @@ void SmacPlannerHybrid::deactivate() if (_costmap_downsampler) { _costmap_downsampler->on_deactivate(); } - dyn_params_handler_.reset(); + _dyn_params_handler.reset(); } void SmacPlannerHybrid::cleanup() diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 7604d0d5f8..0e8f8ae174 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -27,6 +27,7 @@ namespace nav2_smac_planner { using namespace std::chrono; // NOLINT +using rcl_interfaces::msg::ParameterType; SmacPlannerLattice::SmacPlannerLattice() : _a_star(nullptr), @@ -48,74 +49,71 @@ void SmacPlannerLattice::configure( std::string name, std::shared_ptr/*tf*/, std::shared_ptr costmap_ros) { + _node = parent; auto node = parent.lock(); _logger = node->get_logger(); _clock = node->get_clock(); _costmap = costmap_ros->getCostmap(); + _costmap_ros = costmap_ros; _name = name; _global_frame = costmap_ros->getGlobalFrameID(); RCLCPP_INFO(_logger, "Configuring %s of type SmacPlannerLattice", name.c_str()); - bool allow_unknown; - int max_iterations; - double lookup_table_size; - SearchInfo search_info; - // General planner params nav2_util::declare_parameter_if_not_declared( node, name + ".allow_unknown", rclcpp::ParameterValue(true)); - node->get_parameter(name + ".allow_unknown", allow_unknown); + node->get_parameter(name + ".allow_unknown", _allow_unknown); nav2_util::declare_parameter_if_not_declared( node, name + ".max_iterations", rclcpp::ParameterValue(1000000)); - node->get_parameter(name + ".max_iterations", max_iterations); + node->get_parameter(name + ".max_iterations", _max_iterations); nav2_util::declare_parameter_if_not_declared( node, name + ".lattice_filepath", rclcpp::ParameterValue(std::string(""))); - node->get_parameter(name + ".lattice_filepath", search_info.lattice_filepath); + node->get_parameter(name + ".lattice_filepath", _search_info.lattice_filepath); nav2_util::declare_parameter_if_not_declared( node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(false)); - node->get_parameter(name + ".cache_obstacle_heuristic", search_info.cache_obstacle_heuristic); + node->get_parameter(name + ".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic); nav2_util::declare_parameter_if_not_declared( node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0)); - node->get_parameter(name + ".reverse_penalty", search_info.reverse_penalty); + node->get_parameter(name + ".reverse_penalty", _search_info.reverse_penalty); nav2_util::declare_parameter_if_not_declared( node, name + ".change_penalty", rclcpp::ParameterValue(0.05)); - node->get_parameter(name + ".change_penalty", search_info.change_penalty); + node->get_parameter(name + ".change_penalty", _search_info.change_penalty); nav2_util::declare_parameter_if_not_declared( node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.05)); - node->get_parameter(name + ".non_straight_penalty", search_info.non_straight_penalty); + node->get_parameter(name + ".non_straight_penalty", _search_info.non_straight_penalty); nav2_util::declare_parameter_if_not_declared( node, name + ".cost_penalty", rclcpp::ParameterValue(2.0)); - node->get_parameter(name + ".cost_penalty", search_info.cost_penalty); + node->get_parameter(name + ".cost_penalty", _search_info.cost_penalty); nav2_util::declare_parameter_if_not_declared( node, name + ".analytic_expansion_ratio", rclcpp::ParameterValue(3.5)); - node->get_parameter(name + ".analytic_expansion_ratio", search_info.analytic_expansion_ratio); + node->get_parameter(name + ".analytic_expansion_ratio", _search_info.analytic_expansion_ratio); nav2_util::declare_parameter_if_not_declared( node, name + ".max_planning_time", rclcpp::ParameterValue(5.0)); node->get_parameter(name + ".max_planning_time", _max_planning_time); nav2_util::declare_parameter_if_not_declared( node, name + ".lookup_table_size", rclcpp::ParameterValue(20.0)); - node->get_parameter(name + ".lookup_table_size", lookup_table_size); + node->get_parameter(name + ".lookup_table_size", _lookup_table_size); nav2_util::declare_parameter_if_not_declared( node, name + ".allow_reverse_expansion", rclcpp::ParameterValue(false)); - node->get_parameter(name + ".allow_reverse_expansion", search_info.allow_reverse_expansion); + node->get_parameter(name + ".allow_reverse_expansion", _search_info.allow_reverse_expansion); - _metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); - search_info.minimum_turning_radius = + _metadata = LatticeMotionTable::getLatticeMetadata(_search_info.lattice_filepath); + _search_info.minimum_turning_radius = _metadata.min_turning_radius / (_costmap->getResolution()); - MotionModel motion_model = MotionModel::STATE_LATTICE; + _motion_model = MotionModel::STATE_LATTICE; - if (max_iterations <= 0) { + if (_max_iterations <= 0) { RCLCPP_INFO( _logger, "maximum iteration selected as <= 0, " "disabling maximum iterations."); - max_iterations = std::numeric_limits::max(); + _max_iterations = std::numeric_limits::max(); } float lookup_table_dim = - static_cast(lookup_table_size) / + static_cast(_lookup_table_size) / static_cast(_costmap->getResolution()); // Make sure its a whole number @@ -144,10 +142,10 @@ void SmacPlannerLattice::configure( findCircumscribedCost(costmap_ros)); // Initialize A* template - _a_star = std::make_unique>(motion_model, search_info); + _a_star = std::make_unique>(_motion_model, _search_info); _a_star->initialize( - allow_unknown, - max_iterations, + _allow_unknown, + _max_iterations, std::numeric_limits::max(), _max_planning_time, lookup_table_dim, @@ -165,9 +163,9 @@ void SmacPlannerLattice::configure( _logger, "Configured plugin %s of type SmacPlannerLattice with " "maximum iterations %i, " "and %s. Using motion model: %s. State lattice file: %s.", - _name.c_str(), max_iterations, - allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal", - toString(motion_model).c_str(), search_info.lattice_filepath.c_str()); + _name.c_str(), _max_iterations, + _allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal", + toString(_motion_model).c_str(), _search_info.lattice_filepath.c_str()); } void SmacPlannerLattice::activate() @@ -176,6 +174,10 @@ void SmacPlannerLattice::activate() _logger, "Activating plugin %s of type SmacPlannerLattice", _name.c_str()); _raw_plan_publisher->on_activate(); + auto node = _node.lock(); + // Add callback for dynamic parameters + _dyn_params_handler = node->add_on_set_parameters_callback( + std::bind(&SmacPlannerLattice::dynamicParametersCallback, this, std::placeholders::_1)); } void SmacPlannerLattice::deactivate() @@ -184,6 +186,7 @@ void SmacPlannerLattice::deactivate() _logger, "Deactivating plugin %s of type SmacPlannerLattice", _name.c_str()); _raw_plan_publisher->on_deactivate(); + _dyn_params_handler.reset(); } void SmacPlannerLattice::cleanup() @@ -200,6 +203,7 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal) { + std::lock_guard lock_reinit(_mutex); steady_clock::time_point a = steady_clock::now(); std::unique_lock lock(*(_costmap->getMutex())); @@ -295,6 +299,138 @@ nav_msgs::msg::Path SmacPlannerLattice::createPlan( return plan; } +rcl_interfaces::msg::SetParametersResult +SmacPlannerLattice::dynamicParametersCallback(std::vector parameters) +{ + rcl_interfaces::msg::SetParametersResult result; + std::lock_guard lock_reinit(_mutex); + + bool reinit_collision_checker = false; + bool reinit_a_star = false; + bool reinit_smoother = false; + + for (auto parameter : parameters) { + const auto & type = parameter.get_type(); + const auto & name = parameter.get_name(); + + if (type == ParameterType::PARAMETER_DOUBLE) { + if (name == _name + ".max_planning_time") { + reinit_a_star = true; + _max_planning_time = parameter.as_double(); + } else if (name == _name + ".lookup_table_size") { + reinit_a_star = true; + _lookup_table_size = parameter.as_double(); + } else if (name == _name + ".minimum_turning_radius") { + reinit_a_star = true; + reinit_smoother = true; + _search_info.minimum_turning_radius = static_cast(parameter.as_double()); + } else if (name == _name + ".reverse_penalty") { + reinit_a_star = true; + _search_info.reverse_penalty = static_cast(parameter.as_double()); + } else if (name == _name + ".change_penalty") { + reinit_a_star = true; + _search_info.change_penalty = static_cast(parameter.as_double()); + } else if (name == _name + ".non_straight_penalty") { + reinit_a_star = true; + _search_info.non_straight_penalty = static_cast(parameter.as_double()); + } else if (name == _name + ".cost_penalty") { + reinit_a_star = true; + _search_info.cost_penalty = static_cast(parameter.as_double()); + } else if (name == _name + ".analytic_expansion_ratio") { + reinit_a_star = true; + _search_info.analytic_expansion_ratio = static_cast(parameter.as_double()); + } + } else if (type == ParameterType::PARAMETER_BOOL) { + if (name == _name + ".allow_unknown") { + reinit_a_star = true; + _allow_unknown = parameter.as_bool(); + } else if (name == _name + ".cache_obstacle_heuristic") { + reinit_a_star = true; + _search_info.cache_obstacle_heuristic = parameter.as_bool(); + } else if (name == _name + ".allow_reverse_expansion") { + reinit_a_star = true; + _search_info.allow_reverse_expansion = parameter.as_bool(); + } + } else if (type == ParameterType::PARAMETER_INTEGER) { + if (name == _name + ".max_iterations") { + reinit_a_star = true; + _max_iterations = parameter.as_int(); + if (_max_iterations <= 0) { + RCLCPP_INFO( + _logger, "maximum iteration selected as <= 0, " + "disabling maximum iterations."); + _max_iterations = std::numeric_limits::max(); + } + } + } else if (type == ParameterType::PARAMETER_STRING) { + if (name == _name + ".lattice_filepath") { + reinit_a_star = true; + reinit_smoother = true; + _search_info.lattice_filepath = parameter.as_string(); + _metadata = LatticeMotionTable::getLatticeMetadata(_search_info.lattice_filepath); + _search_info.minimum_turning_radius = + _metadata.min_turning_radius / (_costmap->getResolution()); + } + } + } + + // Re-init if needed with mutex lock (to avoid re-init while creating a plan) + if (reinit_a_star || reinit_collision_checker || reinit_smoother) { + // convert to grid coordinates + const double minimum_turning_radius_global_coords = _search_info.minimum_turning_radius; + _search_info.minimum_turning_radius = + _search_info.minimum_turning_radius / (_costmap->getResolution()); + float lookup_table_dim = + static_cast(_lookup_table_size) / + static_cast(_costmap->getResolution()); + + // Make sure its a whole number + lookup_table_dim = static_cast(static_cast(lookup_table_dim)); + + // Make sure its an odd number + if (static_cast(lookup_table_dim) % 2 == 0) { + RCLCPP_INFO( + _logger, + "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd", + lookup_table_dim); + lookup_table_dim += 1.0; + } + + // Re-Initialize A* template + if (reinit_a_star) { + _a_star = std::make_unique>(_motion_model, _search_info); + _a_star->initialize( + _allow_unknown, + _max_iterations, + std::numeric_limits::max(), + _max_planning_time, + lookup_table_dim, + _metadata.number_of_headings); + } + + // Re-Initialize collision checker + if (reinit_collision_checker) { + _collision_checker = GridCollisionChecker(_costmap, 72u); + _collision_checker.setFootprint( + _costmap_ros->getRobotFootprint(), + _costmap_ros->getUseRadius(), + findCircumscribedCost(_costmap_ros)); + } + + // Re-Initialize smoother + if (reinit_smoother) { + auto node = _node.lock(); + SmootherParams params; + params.get(node, _name); + _smoother = std::make_unique(params); + _smoother->initialize(_metadata.min_turning_radius); + } + } + + result.successful = true; + return result; +} + } // namespace nav2_smac_planner #include "pluginlib/class_list_macros.hpp" From 6bde2505db56738b51053418d8a7d8e73f79e70d Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 15:09:23 -0800 Subject: [PATCH 22/31] removing extra config file --- nav2_smac_planner/test/config.json | 2028 ---------------------------- 1 file changed, 2028 deletions(-) delete mode 100644 nav2_smac_planner/test/config.json diff --git a/nav2_smac_planner/test/config.json b/nav2_smac_planner/test/config.json deleted file mode 100644 index 05cbd11aca..0000000000 --- a/nav2_smac_planner/test/config.json +++ /dev/null @@ -1,2028 +0,0 @@ -{ - "version": 1.0, - "date_generated": "2021-10-28", - "lattice_metadata": { - "motion_model": "ackermann", - "turning_radius": 0.5, - "grid_resolution": 0.05, - "stopping_threshold": 5, - "num_of_headings": 16, - "heading_angles": [ - 0.0, - 0.4636476090008061, - 0.7853981633974483, - 1.1071487177940904, - 1.5707963267948966, - 2.0344439357957027, - 2.356194490192345, - 2.677945044588987, - 3.141592653589793, - 3.6052402625905993, - 3.9269908169872414, - 4.2487413713838835, - 4.71238898038469, - 5.176036589385496, - 5.497787143782138, - 5.81953769817878 - ], - "number_of_trajectories": 48 - }, - "primitives": [ - { - "trajectory_id": 0, - "start_angle_index": 0, - "end_angle_index": 15, - "left_turn": false, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.05884, - -0.00273, - -0.09272952180016114 - ], - [ - 0.11717, - -0.0109, - -0.18545904360032228 - ], - [ - 0.17449, - -0.02443, - -0.27818856540048387 - ], - [ - 0.23031, - -0.04321, - -0.370918087200645 - ], - [ - 0.28416, - -0.06708, - -0.46364760900080615 - ], - [ - 0.28416, - -0.06708, - -0.4636476090008061 - ], - [ - 0.35, - -0.1, - -0.4636476090008061 - ] - ] - }, - { - "trajectory_id": 1, - "start_angle_index": 0, - "end_angle_index": 0, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.15, - "arc_length": 0.0, - "straight_length": 0.15, - "poses": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.075, - 0.0, - 0.0 - ], - [ - 0.15, - 0.0, - 0.0 - ] - ] - }, - { - "trajectory_id": 2, - "start_angle_index": 0, - "end_angle_index": 1, - "left_turn": true, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - 0.0 - ], - [ - 0.05884, - 0.00273, - 0.09272952180016114 - ], - [ - 0.11717, - 0.0109, - 0.18545904360032228 - ], - [ - 0.17449, - 0.02443, - 0.27818856540048387 - ], - [ - 0.23031, - 0.04321, - 0.370918087200645 - ], - [ - 0.28416, - 0.06708, - 0.46364760900080615 - ], - [ - 0.28416, - 0.06708, - 0.4636476090008061 - ], - [ - 0.35, - 0.1, - 0.4636476090008061 - ] - ] - }, - { - "trajectory_id": 3, - "start_angle_index": 1, - "end_angle_index": 0, - "left_turn": false, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - 0.4636476090008061 - ], - [ - 0.06584, - 0.03292, - 0.4636476090008061 - ], - [ - 0.06584, - 0.03292, - 0.46364760900080615 - ], - [ - 0.11969, - 0.05679, - 0.370918087200645 - ], - [ - 0.17551, - 0.07557, - 0.27818856540048387 - ], - [ - 0.23283, - 0.0891, - 0.18545904360032228 - ], - [ - 0.29116, - 0.09727, - 0.09272952180016114 - ], - [ - 0.35, - 0.1, - 0.0 - ] - ] - }, - { - "trajectory_id": 4, - "start_angle_index": 1, - "end_angle_index": 1, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.22361, - "arc_length": 0.0, - "straight_length": 0.22361, - "poses": [ - [ - 0.0, - 0.0, - 0.4636476090008061 - ], - [ - 0.06667, - 0.03333, - 0.4636476090008061 - ], - [ - 0.13333, - 0.06667, - 0.4636476090008061 - ], - [ - 0.2, - 0.1, - 0.4636476090008061 - ] - ] - }, - { - "trajectory_id": 5, - "start_angle_index": 1, - "end_angle_index": 2, - "left_turn": true, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 3e-05, - -6e-05, - 0.46364760900080615 - ], - [ - 0.06423, - 0.03646, - 0.5708977937996869 - ], - [ - 0.12415, - 0.07965, - 0.6781479785985676 - ], - [ - 0.1791, - 0.129, - 0.7853981633974483 - ], - [ - 0.1791, - 0.129, - 0.7853981633974483 - ], - [ - 0.2, - 0.15, - 0.7853981633974483 - ] - ] - }, - { - "trajectory_id": 6, - "start_angle_index": 2, - "end_angle_index": 1, - "left_turn": false, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 0.0, - 0.0, - 0.7853981633974483 - ], - [ - 0.0209, - 0.021, - 0.7853981633974483 - ], - [ - 0.0209, - 0.021, - 0.7853981633974483 - ], - [ - 0.07585, - 0.07035, - 0.6781479785985676 - ], - [ - 0.13577, - 0.11354, - 0.5708977937996869 - ], - [ - 0.19997, - 0.15006, - 0.46364760900080615 - ] - ] - }, - { - "trajectory_id": 7, - "start_angle_index": 2, - "end_angle_index": 2, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.21213, - "arc_length": 0.0, - "straight_length": 0.21213, - "poses": [ - [ - 0.0, - 0.0, - 0.7853981633974483 - ], - [ - 0.05, - 0.05, - 0.7853981633974483 - ], - [ - 0.1, - 0.1, - 0.7853981633974483 - ], - [ - 0.15, - 0.15, - 0.7853981633974483 - ] - ] - }, - { - "trajectory_id": 8, - "start_angle_index": 2, - "end_angle_index": 3, - "left_turn": true, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 0.0, - 0.0, - 0.7853981633974483 - ], - [ - 0.021, - 0.0209, - 0.7853981633974483 - ], - [ - 0.021, - 0.0209, - 0.7853981633974483 - ], - [ - 0.07035, - 0.07585, - 0.892648348196329 - ], - [ - 0.11354, - 0.13577, - 0.9998985329952097 - ], - [ - 0.15006, - 0.19997, - 1.1071487177940904 - ] - ] - }, - { - "trajectory_id": 9, - "start_angle_index": 3, - "end_angle_index": 2, - "left_turn": false, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - -6e-05, - 3e-05, - 1.1071487177940904 - ], - [ - 0.03646, - 0.06423, - 0.9998985329952097 - ], - [ - 0.07965, - 0.12415, - 0.892648348196329 - ], - [ - 0.129, - 0.1791, - 0.7853981633974483 - ], - [ - 0.129, - 0.1791, - 0.7853981633974483 - ], - [ - 0.15, - 0.2, - 0.7853981633974483 - ] - ] - }, - { - "trajectory_id": 10, - "start_angle_index": 3, - "end_angle_index": 3, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.22361, - "arc_length": 0.0, - "straight_length": 0.22361, - "poses": [ - [ - 0.0, - 0.0, - 1.1071487177940904 - ], - [ - 0.03333, - 0.06667, - 1.1071487177940904 - ], - [ - 0.06667, - 0.13333, - 1.1071487177940904 - ], - [ - 0.1, - 0.2, - 1.1071487177940904 - ] - ] - }, - { - "trajectory_id": 11, - "start_angle_index": 3, - "end_angle_index": 4, - "left_turn": true, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - 1.1071487177940904 - ], - [ - 0.03292, - 0.06584, - 1.1071487177940904 - ], - [ - 0.03292, - 0.06584, - 1.1071487177940904 - ], - [ - 0.05679, - 0.11969, - 1.199878239594252 - ], - [ - 0.07557, - 0.17551, - 1.2926077613944127 - ], - [ - 0.0891, - 0.23283, - 1.3853372831945743 - ], - [ - 0.09727, - 0.29116, - 1.4780668049947359 - ], - [ - 0.1, - 0.35, - 1.5707963267948966 - ] - ] - }, - { - "trajectory_id": 12, - "start_angle_index": 4, - "end_angle_index": 3, - "left_turn": false, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - 1.5707963267948966 - ], - [ - 0.00273, - 0.05884, - 1.4780668049947359 - ], - [ - 0.0109, - 0.11717, - 1.3853372831945743 - ], - [ - 0.02443, - 0.17449, - 1.2926077613944127 - ], - [ - 0.04321, - 0.23031, - 1.199878239594252 - ], - [ - 0.06708, - 0.28416, - 1.1071487177940904 - ], - [ - 0.06708, - 0.28416, - 1.1071487177940904 - ], - [ - 0.1, - 0.35, - 1.1071487177940904 - ] - ] - }, - { - "trajectory_id": 13, - "start_angle_index": 4, - "end_angle_index": 4, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.15, - "arc_length": 0.0, - "straight_length": 0.15, - "poses": [ - [ - 0.0, - 0.0, - 1.5707963267948966 - ], - [ - 0.0, - 0.075, - 1.5707963267948966 - ], - [ - 0.0, - 0.15, - 1.5707963267948966 - ] - ] - }, - { - "trajectory_id": 14, - "start_angle_index": 4, - "end_angle_index": 5, - "left_turn": true, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - 1.5707963267948966 - ], - [ - -0.00273, - 0.05884, - 1.6635258485950573 - ], - [ - -0.0109, - 0.11717, - 1.7562553703952188 - ], - [ - -0.02443, - 0.17449, - 1.8489848921953804 - ], - [ - -0.04321, - 0.23031, - 1.9417144139955411 - ], - [ - -0.06708, - 0.28416, - 2.0344439357957027 - ], - [ - -0.06708, - 0.28416, - 2.0344439357957027 - ], - [ - -0.1, - 0.35, - 2.0344439357957027 - ] - ] - }, - { - "trajectory_id": 15, - "start_angle_index": 5, - "end_angle_index": 4, - "left_turn": false, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - 2.0344439357957027 - ], - [ - -0.03292, - 0.06584, - 2.0344439357957027 - ], - [ - -0.03292, - 0.06584, - 2.0344439357957027 - ], - [ - -0.05679, - 0.11969, - 1.9417144139955411 - ], - [ - -0.07557, - 0.17551, - 1.8489848921953804 - ], - [ - -0.0891, - 0.23283, - 1.7562553703952188 - ], - [ - -0.09727, - 0.29116, - 1.6635258485950573 - ], - [ - -0.1, - 0.35, - 1.5707963267948966 - ] - ] - }, - { - "trajectory_id": 16, - "start_angle_index": 5, - "end_angle_index": 5, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.22361, - "arc_length": 0.0, - "straight_length": 0.22361, - "poses": [ - [ - 0.0, - 0.0, - 2.0344439357957027 - ], - [ - -0.03333, - 0.06667, - 2.0344439357957027 - ], - [ - -0.06667, - 0.13333, - 2.0344439357957027 - ], - [ - -0.1, - 0.2, - 2.0344439357957027 - ] - ] - }, - { - "trajectory_id": 17, - "start_angle_index": 5, - "end_angle_index": 6, - "left_turn": true, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 6e-05, - 3e-05, - 2.0344439357957027 - ], - [ - -0.03646, - 0.06423, - 2.1416941205945834 - ], - [ - -0.07965, - 0.12415, - 2.248944305393464 - ], - [ - -0.129, - 0.1791, - 2.356194490192345 - ], - [ - -0.129, - 0.1791, - 2.356194490192345 - ], - [ - -0.15, - 0.2, - 2.356194490192345 - ] - ] - }, - { - "trajectory_id": 18, - "start_angle_index": 6, - "end_angle_index": 5, - "left_turn": false, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 0.0, - 0.0, - 2.356194490192345 - ], - [ - -0.021, - 0.0209, - 2.356194490192345 - ], - [ - -0.021, - 0.0209, - 2.356194490192345 - ], - [ - -0.07035, - 0.07585, - 2.248944305393464 - ], - [ - -0.11354, - 0.13577, - 2.1416941205945834 - ], - [ - -0.15006, - 0.19997, - 2.0344439357957027 - ] - ] - }, - { - "trajectory_id": 19, - "start_angle_index": 6, - "end_angle_index": 6, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.21213, - "arc_length": 0.0, - "straight_length": 0.21213, - "poses": [ - [ - 0.0, - 0.0, - 2.356194490192345 - ], - [ - -0.05, - 0.05, - 2.356194490192345 - ], - [ - -0.1, - 0.1, - 2.356194490192345 - ], - [ - -0.15, - 0.15, - 2.356194490192345 - ] - ] - }, - { - "trajectory_id": 20, - "start_angle_index": 6, - "end_angle_index": 7, - "left_turn": true, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 0.0, - 0.0, - 2.356194490192345 - ], - [ - -0.0209, - 0.021, - 2.356194490192345 - ], - [ - -0.0209, - 0.021, - 2.356194490192345 - ], - [ - -0.07585, - 0.07035, - 2.4634446749912255 - ], - [ - -0.13577, - 0.11354, - 2.5706948597901063 - ], - [ - -0.19997, - 0.15006, - 2.677945044588987 - ] - ] - }, - { - "trajectory_id": 21, - "start_angle_index": 7, - "end_angle_index": 6, - "left_turn": false, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - -3e-05, - -6e-05, - 2.677945044588987 - ], - [ - -0.06423, - 0.03646, - 2.5706948597901063 - ], - [ - -0.12415, - 0.07965, - 2.4634446749912255 - ], - [ - -0.1791, - 0.129, - 2.356194490192345 - ], - [ - -0.1791, - 0.129, - 2.356194490192345 - ], - [ - -0.2, - 0.15, - 2.356194490192345 - ] - ] - }, - { - "trajectory_id": 22, - "start_angle_index": 7, - "end_angle_index": 7, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.22361, - "arc_length": 0.0, - "straight_length": 0.22361, - "poses": [ - [ - 0.0, - 0.0, - 2.677945044588987 - ], - [ - -0.06667, - 0.03333, - 2.677945044588987 - ], - [ - -0.13333, - 0.06667, - 2.677945044588987 - ], - [ - -0.2, - 0.1, - 2.677945044588987 - ] - ] - }, - { - "trajectory_id": 23, - "start_angle_index": 7, - "end_angle_index": 8, - "left_turn": true, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - 2.677945044588987 - ], - [ - -0.06584, - 0.03292, - 2.677945044588987 - ], - [ - -0.06584, - 0.03292, - 2.677945044588987 - ], - [ - -0.11969, - 0.05679, - 2.7706745663891486 - ], - [ - -0.17551, - 0.07557, - 2.8634040881893092 - ], - [ - -0.23283, - 0.0891, - 2.956133609989471 - ], - [ - -0.29116, - 0.09727, - 3.0488631317896324 - ], - [ - -0.35, - 0.1, - -3.141592653589793 - ] - ] - }, - { - "trajectory_id": 24, - "start_angle_index": 8, - "end_angle_index": 9, - "left_turn": true, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - -3.141592653589793 - ], - [ - -0.05884, - -0.00273, - -3.048863131789632 - ], - [ - -0.11717, - -0.0109, - -2.956133609989471 - ], - [ - -0.17449, - -0.02443, - -2.8634040881893092 - ], - [ - -0.23031, - -0.04321, - -2.770674566389148 - ], - [ - -0.28416, - -0.06708, - -2.677945044588987 - ], - [ - -0.28416, - -0.06708, - -2.677945044588987 - ], - [ - -0.35, - -0.1, - -2.677945044588987 - ] - ] - }, - { - "trajectory_id": 25, - "start_angle_index": 8, - "end_angle_index": 7, - "left_turn": false, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - -3.141592653589793 - ], - [ - -0.05884, - 0.00273, - 3.0488631317896324 - ], - [ - -0.11717, - 0.0109, - 2.956133609989471 - ], - [ - -0.17449, - 0.02443, - 2.8634040881893092 - ], - [ - -0.23031, - 0.04321, - 2.7706745663891486 - ], - [ - -0.28416, - 0.06708, - 2.677945044588987 - ], - [ - -0.28416, - 0.06708, - 2.677945044588987 - ], - [ - -0.35, - 0.1, - 2.677945044588987 - ] - ] - }, - { - "trajectory_id": 26, - "start_angle_index": 8, - "end_angle_index": 8, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.15, - "arc_length": 0.0, - "straight_length": 0.15, - "poses": [ - [ - 0.0, - 0.0, - 3.141592653589793 - ], - [ - -0.075, - 0.0, - 3.141592653589793 - ], - [ - -0.15, - 0.0, - 3.141592653589793 - ] - ] - }, - { - "trajectory_id": 27, - "start_angle_index": 9, - "end_angle_index": 9, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.22361, - "arc_length": 0.0, - "straight_length": 0.22361, - "poses": [ - [ - 0.0, - 0.0, - -2.677945044588987 - ], - [ - -0.06667, - -0.03333, - -2.677945044588987 - ], - [ - -0.13333, - -0.06667, - -2.677945044588987 - ], - [ - -0.2, - -0.1, - -2.677945044588987 - ] - ] - }, - { - "trajectory_id": 28, - "start_angle_index": 9, - "end_angle_index": 10, - "left_turn": true, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - -3e-05, - 6e-05, - -2.677945044588987 - ], - [ - -0.06423, - -0.03646, - -2.5706948597901063 - ], - [ - -0.12415, - -0.07965, - -2.4634446749912255 - ], - [ - -0.1791, - -0.129, - -2.356194490192345 - ], - [ - -0.1791, - -0.129, - -2.356194490192345 - ], - [ - -0.2, - -0.15, - -2.356194490192345 - ] - ] - }, - { - "trajectory_id": 29, - "start_angle_index": 9, - "end_angle_index": 8, - "left_turn": false, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - -2.677945044588987 - ], - [ - -0.06584, - -0.03292, - -2.677945044588987 - ], - [ - -0.06584, - -0.03292, - -2.677945044588987 - ], - [ - -0.11969, - -0.05679, - -2.770674566389148 - ], - [ - -0.17551, - -0.07557, - -2.8634040881893092 - ], - [ - -0.23283, - -0.0891, - -2.956133609989471 - ], - [ - -0.29116, - -0.09727, - -3.048863131789632 - ], - [ - -0.35, - -0.1, - -3.141592653589793 - ] - ] - }, - { - "trajectory_id": 30, - "start_angle_index": 10, - "end_angle_index": 9, - "left_turn": false, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 0.0, - 0.0, - -2.356194490192345 - ], - [ - -0.0209, - -0.021, - -2.356194490192345 - ], - [ - -0.0209, - -0.021, - -2.356194490192345 - ], - [ - -0.07585, - -0.07035, - -2.4634446749912255 - ], - [ - -0.13577, - -0.11354, - -2.5706948597901063 - ], - [ - -0.19997, - -0.15006, - -2.677945044588987 - ] - ] - }, - { - "trajectory_id": 31, - "start_angle_index": 10, - "end_angle_index": 10, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.21213, - "arc_length": 0.0, - "straight_length": 0.21213, - "poses": [ - [ - 0.0, - 0.0, - -2.356194490192345 - ], - [ - -0.05, - -0.05, - -2.356194490192345 - ], - [ - -0.1, - -0.1, - -2.356194490192345 - ], - [ - -0.15, - -0.15, - -2.356194490192345 - ] - ] - }, - { - "trajectory_id": 32, - "start_angle_index": 10, - "end_angle_index": 11, - "left_turn": true, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 0.0, - 0.0, - -2.356194490192345 - ], - [ - -0.021, - -0.0209, - -2.356194490192345 - ], - [ - -0.021, - -0.0209, - -2.356194490192345 - ], - [ - -0.07035, - -0.07585, - -2.248944305393464 - ], - [ - -0.11354, - -0.13577, - -2.1416941205945834 - ], - [ - -0.15006, - -0.19997, - -2.0344439357957027 - ] - ] - }, - { - "trajectory_id": 33, - "start_angle_index": 11, - "end_angle_index": 10, - "left_turn": false, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 6e-05, - -3e-05, - -2.0344439357957027 - ], - [ - -0.03646, - -0.06423, - -2.1416941205945834 - ], - [ - -0.07965, - -0.12415, - -2.248944305393464 - ], - [ - -0.129, - -0.1791, - -2.356194490192345 - ], - [ - -0.129, - -0.1791, - -2.356194490192345 - ], - [ - -0.15, - -0.2, - -2.356194490192345 - ] - ] - }, - { - "trajectory_id": 34, - "start_angle_index": 11, - "end_angle_index": 11, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.22361, - "arc_length": 0.0, - "straight_length": 0.22361, - "poses": [ - [ - 0.0, - 0.0, - -2.0344439357957027 - ], - [ - -0.03333, - -0.06667, - -2.0344439357957027 - ], - [ - -0.06667, - -0.13333, - -2.0344439357957027 - ], - [ - -0.1, - -0.2, - -2.0344439357957027 - ] - ] - }, - { - "trajectory_id": 35, - "start_angle_index": 11, - "end_angle_index": 12, - "left_turn": true, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - -2.0344439357957027 - ], - [ - -0.03292, - -0.06584, - -2.0344439357957027 - ], - [ - -0.03292, - -0.06584, - -2.0344439357957027 - ], - [ - -0.05679, - -0.11969, - -1.9417144139955416 - ], - [ - -0.07557, - -0.17551, - -1.8489848921953802 - ], - [ - -0.0891, - -0.23283, - -1.756255370395219 - ], - [ - -0.09727, - -0.29116, - -1.6635258485950577 - ], - [ - -0.1, - -0.35, - -1.5707963267948966 - ] - ] - }, - { - "trajectory_id": 36, - "start_angle_index": 12, - "end_angle_index": 11, - "left_turn": false, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - -1.5707963267948966 - ], - [ - -0.00273, - -0.05884, - -1.6635258485950577 - ], - [ - -0.0109, - -0.11717, - -1.756255370395219 - ], - [ - -0.02443, - -0.17449, - -1.8489848921953802 - ], - [ - -0.04321, - -0.23031, - -1.9417144139955416 - ], - [ - -0.06708, - -0.28416, - -2.0344439357957027 - ], - [ - -0.06708, - -0.28416, - -2.0344439357957027 - ], - [ - -0.1, - -0.35, - -2.0344439357957027 - ] - ] - }, - { - "trajectory_id": 37, - "start_angle_index": 12, - "end_angle_index": 12, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.15, - "arc_length": 0.0, - "straight_length": 0.15, - "poses": [ - [ - 0.0, - 0.0, - -1.5707963267948966 - ], - [ - 0.0, - -0.075, - -1.5707963267948966 - ], - [ - 0.0, - -0.15, - -1.5707963267948966 - ] - ] - }, - { - "trajectory_id": 38, - "start_angle_index": 12, - "end_angle_index": 13, - "left_turn": true, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - -1.5707963267948966 - ], - [ - 0.00273, - -0.05884, - -1.4780668049947354 - ], - [ - 0.0109, - -0.11717, - -1.385337283194574 - ], - [ - 0.02443, - -0.17449, - -1.292607761394413 - ], - [ - 0.04321, - -0.23031, - -1.1998782395942515 - ], - [ - 0.06708, - -0.28416, - -1.1071487177940904 - ], - [ - 0.06708, - -0.28416, - -1.1071487177940904 - ], - [ - 0.1, - -0.35, - -1.1071487177940904 - ] - ] - }, - { - "trajectory_id": 39, - "start_angle_index": 13, - "end_angle_index": 12, - "left_turn": false, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - -1.1071487177940904 - ], - [ - 0.03292, - -0.06584, - -1.1071487177940904 - ], - [ - 0.03292, - -0.06584, - -1.1071487177940904 - ], - [ - 0.05679, - -0.11969, - -1.1998782395942515 - ], - [ - 0.07557, - -0.17551, - -1.292607761394413 - ], - [ - 0.0891, - -0.23283, - -1.385337283194574 - ], - [ - 0.09727, - -0.29116, - -1.4780668049947354 - ], - [ - 0.1, - -0.35, - -1.5707963267948966 - ] - ] - }, - { - "trajectory_id": 40, - "start_angle_index": 13, - "end_angle_index": 13, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.22361, - "arc_length": 0.0, - "straight_length": 0.22361, - "poses": [ - [ - 0.0, - 0.0, - -1.1071487177940904 - ], - [ - 0.03333, - -0.06667, - -1.1071487177940904 - ], - [ - 0.06667, - -0.13333, - -1.1071487177940904 - ], - [ - 0.1, - -0.2, - -1.1071487177940904 - ] - ] - }, - { - "trajectory_id": 41, - "start_angle_index": 13, - "end_angle_index": 14, - "left_turn": true, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - -6e-05, - -3e-05, - -1.1071487177940904 - ], - [ - 0.03646, - -0.06423, - -0.9998985329952097 - ], - [ - 0.07965, - -0.12415, - -0.892648348196329 - ], - [ - 0.129, - -0.1791, - -0.7853981633974483 - ], - [ - 0.129, - -0.1791, - -0.7853981633974483 - ], - [ - 0.15, - -0.2, - -0.7853981633974483 - ] - ] - }, - { - "trajectory_id": 42, - "start_angle_index": 14, - "end_angle_index": 13, - "left_turn": false, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 0.0, - 0.0, - -0.7853981633974483 - ], - [ - 0.021, - -0.0209, - -0.7853981633974483 - ], - [ - 0.021, - -0.0209, - -0.7853981633974483 - ], - [ - 0.07035, - -0.07585, - -0.892648348196329 - ], - [ - 0.11354, - -0.13577, - -0.9998985329952097 - ], - [ - 0.15006, - -0.19997, - -1.1071487177940904 - ] - ] - }, - { - "trajectory_id": 43, - "start_angle_index": 14, - "end_angle_index": 14, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.21213, - "arc_length": 0.0, - "straight_length": 0.21213, - "poses": [ - [ - 0.0, - 0.0, - -0.7853981633974483 - ], - [ - 0.05, - -0.05, - -0.7853981633974483 - ], - [ - 0.1, - -0.1, - -0.7853981633974483 - ], - [ - 0.15, - -0.15, - -0.7853981633974483 - ] - ] - }, - { - "trajectory_id": 44, - "start_angle_index": 14, - "end_angle_index": 15, - "left_turn": true, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 0.0, - 0.0, - -0.7853981633974483 - ], - [ - 0.0209, - -0.021, - -0.7853981633974483 - ], - [ - 0.0209, - -0.021, - -0.7853981633974483 - ], - [ - 0.07585, - -0.07035, - -0.6781479785985676 - ], - [ - 0.13577, - -0.11354, - -0.5708977937996869 - ], - [ - 0.19997, - -0.15006, - -0.46364760900080615 - ] - ] - }, - { - "trajectory_id": 45, - "start_angle_index": 15, - "end_angle_index": 14, - "left_turn": false, - "trajectory_radius": 0.689, - "trajectory_length": 0.25131, - "arc_length": 0.22169, - "straight_length": 0.02962, - "poses": [ - [ - 3e-05, - 6e-05, - -0.46364760900080615 - ], - [ - 0.06423, - -0.03646, - -0.5708977937996869 - ], - [ - 0.12415, - -0.07965, - -0.6781479785985676 - ], - [ - 0.1791, - -0.129, - -0.7853981633974483 - ], - [ - 0.1791, - -0.129, - -0.7853981633974483 - ], - [ - 0.2, - -0.15, - -0.7853981633974483 - ] - ] - }, - { - "trajectory_id": 46, - "start_angle_index": 15, - "end_angle_index": 15, - "left_turn": true, - "trajectory_radius": 0.0, - "trajectory_length": 0.22361, - "arc_length": 0.0, - "straight_length": 0.22361, - "poses": [ - [ - 0.0, - 0.0, - -0.4636476090008061 - ], - [ - 0.06667, - -0.03333, - -0.4636476090008061 - ], - [ - 0.13333, - -0.06667, - -0.4636476090008061 - ], - [ - 0.2, - -0.1, - -0.4636476090008061 - ] - ] - }, - { - "trajectory_id": 47, - "start_angle_index": 15, - "end_angle_index": 0, - "left_turn": true, - "trajectory_radius": 0.6354, - "trajectory_length": 0.36821, - "arc_length": 0.2946, - "straight_length": 0.07361, - "poses": [ - [ - 0.0, - 0.0, - -0.4636476090008061 - ], - [ - 0.06584, - -0.03292, - -0.4636476090008061 - ], - [ - 0.06584, - -0.03292, - -0.46364760900080615 - ], - [ - 0.11969, - -0.05679, - -0.370918087200645 - ], - [ - 0.17551, - -0.07557, - -0.27818856540048387 - ], - [ - 0.23283, - -0.0891, - -0.18545904360032228 - ], - [ - 0.29116, - -0.09727, - -0.09272952180016114 - ], - [ - 0.35, - -0.1, - 0.0 - ] - ] - } - ] -} \ No newline at end of file From 49b059bb989f00c9977a366cd8a1d75d3e9bfd6d Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 16:36:30 -0800 Subject: [PATCH 23/31] fix linting --- nav2_navfn_planner/src/navfn_planner.cpp | 2 +- nav2_smac_planner/src/node_lattice.cpp | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp index d07f70e2cf..2ede7f38b8 100644 --- a/nav2_navfn_planner/src/navfn_planner.cpp +++ b/nav2_navfn_planner/src/navfn_planner.cpp @@ -39,7 +39,7 @@ #include "nav2_costmap_2d/cost_values.hpp" using namespace std::chrono_literals; -using namespace std::chrono; +using namespace std::chrono; // NOLINT using nav2_util::declare_parameter_if_not_declared; using rcl_interfaces::msg::ParameterType; using std::placeholders::_1; diff --git a/nav2_smac_planner/src/node_lattice.cpp b/nav2_smac_planner/src/node_lattice.cpp index 9570104b83..3840b34c4f 100644 --- a/nav2_smac_planner/src/node_lattice.cpp +++ b/nav2_smac_planner/src/node_lattice.cpp @@ -419,7 +419,8 @@ void NodeLattice::precomputeDistanceHeuristic( motion_table.state_space = std::make_unique( search_info.minimum_turning_radius); } - motion_table.lattice_metadata = LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); + motion_table.lattice_metadata = + LatticeMotionTable::getLatticeMetadata(search_info.lattice_filepath); ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space); to[0] = 0.0; @@ -513,7 +514,7 @@ void NodeLattice::getNeighbors( // Using a special isNodeValid API here, giving the motion primitive to use to // validity check the transition of the current node to the new node over if (neighbor->isNodeValid( - traverse_unknown, collision_checker, motion_primitives[i], backwards)) + traverse_unknown, collision_checker, motion_primitives[i], backwards)) { neighbor->setMotionPrimitive(motion_primitives[i]); // Marking if this search was obtained in the reverse direction From f364aff71f87649ef9b27f5bbfd0286d0fc922d5 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 16:37:48 -0800 Subject: [PATCH 24/31] updating test --- nav2_smac_planner/test/test_a_star.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_smac_planner/test/test_a_star.cpp b/nav2_smac_planner/test/test_a_star.cpp index e4d4fd7bda..865bae0050 100644 --- a/nav2_smac_planner/test/test_a_star.cpp +++ b/nav2_smac_planner/test/test_a_star.cpp @@ -157,7 +157,7 @@ TEST(AStarTest, test_a_star_se2) EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); // check path is the right size and collision free - EXPECT_EQ(num_it, 351); + EXPECT_EQ(num_it, 352); EXPECT_EQ(path.size(), 73u); for (unsigned int i = 0; i != path.size(); i++) { EXPECT_EQ(costmapA->getCost(path[i].x, path[i].y), 0); From be1993b68d4d9975777e00766f37c8eeff8d6c3d Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 17:25:49 -0800 Subject: [PATCH 25/31] adding several unit tests --- nav2_smac_planner/src/analytic_expansion.cpp | 1 - .../src/smac_planner_lattice.cpp | 34 ++--- nav2_smac_planner/test/CMakeLists.txt | 11 ++ nav2_smac_planner/test/test_nodelattice.cpp | 50 ++++++++ nav2_smac_planner/test/test_smac_lattice.cpp | 118 ++++++++++++++++++ 5 files changed, 189 insertions(+), 25 deletions(-) create mode 100644 nav2_smac_planner/test/test_smac_lattice.cpp diff --git a/nav2_smac_planner/src/analytic_expansion.cpp b/nav2_smac_planner/src/analytic_expansion.cpp index f22acc12a7..eff51c7bd9 100644 --- a/nav2_smac_planner/src/analytic_expansion.cpp +++ b/nav2_smac_planner/src/analytic_expansion.cpp @@ -239,7 +239,6 @@ void AnalyticExpansion::cleanNode(const NodePtr & node) template void AnalyticExpansion::cleanNode(const NodePtr & /*expanded_nodes*/) { - return; } template<> diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 0e8f8ae174..7544f023df 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -305,7 +305,6 @@ SmacPlannerLattice::dynamicParametersCallback(std::vector par rcl_interfaces::msg::SetParametersResult result; std::lock_guard lock_reinit(_mutex); - bool reinit_collision_checker = false; bool reinit_a_star = false; bool reinit_smoother = false; @@ -320,10 +319,6 @@ SmacPlannerLattice::dynamicParametersCallback(std::vector par } else if (name == _name + ".lookup_table_size") { reinit_a_star = true; _lookup_table_size = parameter.as_double(); - } else if (name == _name + ".minimum_turning_radius") { - reinit_a_star = true; - reinit_smoother = true; - _search_info.minimum_turning_radius = static_cast(parameter.as_double()); } else if (name == _name + ".reverse_penalty") { reinit_a_star = true; _search_info.reverse_penalty = static_cast(parameter.as_double()); @@ -375,7 +370,7 @@ SmacPlannerLattice::dynamicParametersCallback(std::vector par } // Re-init if needed with mutex lock (to avoid re-init while creating a plan) - if (reinit_a_star || reinit_collision_checker || reinit_smoother) { + if (reinit_a_star || reinit_smoother) { // convert to grid coordinates const double minimum_turning_radius_global_coords = _search_info.minimum_turning_radius; _search_info.minimum_turning_radius = @@ -396,6 +391,15 @@ SmacPlannerLattice::dynamicParametersCallback(std::vector par lookup_table_dim += 1.0; } + // Re-Initialize smoother + if (reinit_smoother) { + auto node = _node.lock(); + SmootherParams params; + params.get(node, _name); + _smoother = std::make_unique(params); + _smoother->initialize(_metadata.min_turning_radius); + } + // Re-Initialize A* template if (reinit_a_star) { _a_star = std::make_unique>(_motion_model, _search_info); @@ -407,24 +411,6 @@ SmacPlannerLattice::dynamicParametersCallback(std::vector par lookup_table_dim, _metadata.number_of_headings); } - - // Re-Initialize collision checker - if (reinit_collision_checker) { - _collision_checker = GridCollisionChecker(_costmap, 72u); - _collision_checker.setFootprint( - _costmap_ros->getRobotFootprint(), - _costmap_ros->getUseRadius(), - findCircumscribedCost(_costmap_ros)); - } - - // Re-Initialize smoother - if (reinit_smoother) { - auto node = _node.lock(); - SmootherParams params; - params.get(node, _name); - _smoother = std::make_unique(params); - _smoother->initialize(_metadata.min_turning_radius); - } } result.successful = true; diff --git a/nav2_smac_planner/test/CMakeLists.txt b/nav2_smac_planner/test/CMakeLists.txt index 609b0b4174..0b04e2580b 100644 --- a/nav2_smac_planner/test/CMakeLists.txt +++ b/nav2_smac_planner/test/CMakeLists.txt @@ -86,6 +86,17 @@ target_link_libraries(test_smac_2d ${library_name}_2d ) +# Test SMAC lattice +ament_add_gtest(test_smac_lattice + test_smac_lattice.cpp +) +ament_target_dependencies(test_smac_lattice + ${dependencies} +) +target_link_libraries(test_smac_lattice + ${library_name}_lattice +) + #Test Lattice node ament_add_gtest(test_lattice_node test_nodelattice.cpp) diff --git a/nav2_smac_planner/test/test_nodelattice.cpp b/nav2_smac_planner/test/test_nodelattice.cpp index 2b2f546117..3c652a075e 100644 --- a/nav2_smac_planner/test/test_nodelattice.cpp +++ b/nav2_smac_planner/test/test_nodelattice.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include #include "nav2_smac_planner/node_lattice.hpp" #include "gtest/gtest.h" @@ -93,6 +94,7 @@ TEST(NodeLatticeTest, test_node_lattice_neighbors_and_parsing) info.analytic_expansion_ratio = 1; info.lattice_filepath = filePath; info.cache_obstacle_heuristic = true; + info.allow_reverse_expansion = false; unsigned int x = 100; unsigned int y = 100; @@ -163,6 +165,7 @@ TEST(NodeLatticeTest, test_node_lattice) info.analytic_expansion_ratio = 1; info.lattice_filepath = filePath; info.cache_obstacle_heuristic = true; + info.allow_reverse_expansion = true; unsigned int x = 100; unsigned int y = 100; @@ -219,3 +222,50 @@ TEST(NodeLatticeTest, test_node_lattice) delete costmapA; } + + +TEST(NodeLatticeTest, test_get_neighbors) +{ + std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); + std::string filePath = pkg_share_dir + "/output.json"; + + nav2_smac_planner::SearchInfo info; + info.minimum_turning_radius = 1.1; + info.non_straight_penalty = 1; + info.change_penalty = 1; + info.reverse_penalty = 1; + info.cost_penalty = 1; + info.analytic_expansion_ratio = 1; + info.lattice_filepath = filePath; + info.cache_obstacle_heuristic = true; + info.allow_reverse_expansion = true; + + unsigned int x = 100; + unsigned int y = 100; + unsigned int angle_quantization = 16; + + nav2_smac_planner::NodeLattice::initMotionModel( + nav2_smac_planner::MotionModel::STATE_LATTICE, x, y, angle_quantization, info); + + nav2_smac_planner::NodeLattice node(49); + + nav2_costmap_2d::Costmap2D * costmapA = new nav2_costmap_2d::Costmap2D( + 10, 10, 0.05, 0.0, 0.0, 0); + std::unique_ptr checker = + std::make_unique(costmapA, 72); + checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0); + + std::function neighborGetter = + [&, this](const unsigned int & index, nav2_smac_planner::NodeLattice * & neighbor_rtn) -> bool + { + // because we don't return a real object + return false; + }; + + nav2_smac_planner::NodeLattice::NodeVector neighbors; + node.getNeighbors(neighborGetter, checker.get(), false, neighbors); + // should be empty since totally invalid + EXPECT_EQ(neighbors.size(), 0u); + + delete costmapA; +} diff --git a/nav2_smac_planner/test/test_smac_lattice.cpp b/nav2_smac_planner/test/test_smac_lattice.cpp new file mode 100644 index 0000000000..1777c293f1 --- /dev/null +++ b/nav2_smac_planner/test/test_smac_lattice.cpp @@ -0,0 +1,118 @@ +// Copyright (c) 2021 Samsung Research America +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. Reserved. + +#include +#include +#include +#include + +#include "gtest/gtest.h" +#include "rclcpp/rclcpp.hpp" +#include "nav2_costmap_2d/costmap_2d.hpp" +#include "nav2_costmap_2d/costmap_subscriber.hpp" +#include "nav2_util/lifecycle_node.hpp" +#include "geometry_msgs/msg/pose_stamped.hpp" +#include "nav2_smac_planner/node_hybrid.hpp" +#include "nav2_smac_planner/a_star.hpp" +#include "nav2_smac_planner/collision_checker.hpp" +#include "nav2_smac_planner/smac_planner_lattice.hpp" + +class RclCppFixture +{ +public: + RclCppFixture() {rclcpp::init(0, nullptr);} + ~RclCppFixture() {rclcpp::shutdown();} +}; +RclCppFixture g_rclcppfixture; + +// SMAC smoke tests for plugin-level issues rather than algorithms +// (covered by more extensively testing in other files) +// System tests in nav2_system_tests will actually plan with this work + +TEST(SmacTest, test_smac_lattice) +{ + rclcpp_lifecycle::LifecycleNode::SharedPtr nodeLattice = + std::make_shared("SmacLatticeTest"); + + std::shared_ptr costmap_ros = + std::make_shared("global_costmap"); + costmap_ros->on_configure(rclcpp_lifecycle::State()); + + geometry_msgs::msg::PoseStamped start, goal; + start.pose.position.x = 0.0; + start.pose.position.y = 0.0; + start.pose.orientation.w = 1.0; + goal.pose.position.x = 1.0; + goal.pose.position.y = 1.0; + goal.pose.orientation.w = 1.0; + auto planner = std::make_unique(); + planner->configure(nodeLattice, "test", nullptr, costmap_ros); + planner->activate(); + + try { + planner->createPlan(start, goal); + } catch (...) { + } + + planner->deactivate(); + planner->cleanup(); + + planner.reset(); + costmap_ros->on_cleanup(rclcpp_lifecycle::State()); + costmap_ros.reset(); + nodeLattice.reset(); +} + +TEST(SmacTest, test_smac_lattice_reconfigure) +{ + rclcpp_lifecycle::LifecycleNode::SharedPtr nodeLattice = + std::make_shared("SmacLatticeTest"); + + std::shared_ptr costmap_ros = + std::make_shared("global_costmap"); + costmap_ros->on_configure(rclcpp_lifecycle::State()); + + auto planner = std::make_unique(); + planner->configure(nodeLattice, "test", nullptr, costmap_ros); + planner->activate(); + + auto rec_param = std::make_shared( + nodeLattice->get_node_base_interface(), nodeLattice->get_node_topics_interface(), + nodeLattice->get_node_graph_interface(), + nodeLattice->get_node_services_interface()); + + auto results = rec_param->set_parameters_atomically( + {rclcpp::Parameter("test.allow_unknown", false), + rclcpp::Parameter("test.max_iterations", -1), + rclcpp::Parameter("test.cache_obstacle_heuristic", true), + rclcpp::Parameter("test.reverse_penalty", 5.0), + rclcpp::Parameter("test.change_penalty", 1.0), + rclcpp::Parameter("test.non_straight_penalty", 2.0), + rclcpp::Parameter("test.cost_penalty", 2.0), + rclcpp::Parameter("test.analytic_expansion_ratio", 4.0), + rclcpp::Parameter("test.max_planning_time", 10.0), + rclcpp::Parameter("test.lookup_table_size", 30.0), + rclcpp::Parameter("test.lattice_filepath", std::string("HI")), + rclcpp::Parameter("test.allow_reverse_expansion", true)}); + + try { + // All of these params will re-init A* which will involve loading the control set file + // which will cause an exception because the file does not exist. This will cause an + // expected failure preventing parameter updates from being successfully processed + rclcpp::spin_until_future_complete( + nodeLattice->get_node_base_interface(), + results); + } catch (...) { + } +} From d841fc89c4e0c46a47e7457268c618fc646c5246 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 17:44:23 -0800 Subject: [PATCH 26/31] adding system test --- nav2_smac_planner/test/test_a_star.cpp | 56 ++++++++++++++++++++++++++ 1 file changed, 56 insertions(+) diff --git a/nav2_smac_planner/test/test_a_star.cpp b/nav2_smac_planner/test/test_a_star.cpp index 865bae0050..fb5ecda287 100644 --- a/nav2_smac_planner/test/test_a_star.cpp +++ b/nav2_smac_planner/test/test_a_star.cpp @@ -16,6 +16,7 @@ #include #include #include +#include #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" @@ -23,8 +24,10 @@ #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "nav2_util/lifecycle_node.hpp" #include "nav2_smac_planner/node_hybrid.hpp" +#include "nav2_smac_planner/node_lattice.hpp" #include "nav2_smac_planner/a_star.hpp" #include "nav2_smac_planner/collision_checker.hpp" +#include "ament_index_cpp/get_package_share_directory.hpp" class RclCppFixture { @@ -166,6 +169,59 @@ TEST(AStarTest, test_a_star_se2) delete costmapA; } +TEST(AStarTest, test_a_star_lattice) +{ + nav2_smac_planner::SearchInfo info; + info.change_penalty = 0.05; + info.non_straight_penalty = 1.05; + info.reverse_penalty = 2.0; + info.analytic_expansion_ratio = 3.5; + info.lattice_filepath = + ament_index_cpp::get_package_share_directory("nav2_smac_planner") + "/output.json"; + info.minimum_turning_radius = 8; // in grid coordinates 0.4/0.05 + unsigned int size_theta = 16; + info.cost_penalty = 2.0; + nav2_smac_planner::AStarAlgorithm a_star( + nav2_smac_planner::MotionModel::STATE_LATTICE, info); + int max_iterations = 10000; + float tolerance = 10.0; + int it_on_approach = 10; + double max_planning_time = 120.0; + int num_it = 0; + + a_star.initialize( + false, max_iterations, std::numeric_limits::max(), max_planning_time, 401, size_theta); + + nav2_costmap_2d::Costmap2D * costmapA = + new nav2_costmap_2d::Costmap2D(100, 100, 0.05, 0.0, 0.0, 0); + // island in the middle of lethal cost to cross + for (unsigned int i = 20; i <= 30; ++i) { + for (unsigned int j = 20; j <= 30; ++j) { + costmapA->setCost(i, j, 254); + } + } + + std::unique_ptr checker = + std::make_unique(costmapA, size_theta); + checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0); + + // functional case testing + a_star.setCollisionChecker(checker.get()); + a_star.setStart(5u, 5u, 0u); + a_star.setGoal(40u, 40u, 1u); + nav2_smac_planner::NodeLattice::CoordinateVector path; + EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); + + // check path is the right size and collision free + EXPECT_EQ(num_it, 14); + EXPECT_EQ(path.size(), 49u); + for (unsigned int i = 0; i != path.size(); i++) { + EXPECT_EQ(costmapA->getCost(path[i].x, path[i].y), 0); + } + + delete costmapA; +} + TEST(AStarTest, test_se2_single_pose_path) { nav2_smac_planner::SearchInfo info; From 83733653e373f4da6b9713ce7f16fac64deae8b6 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 18:19:23 -0800 Subject: [PATCH 27/31] fixing crash --- nav2_smac_planner/src/smac_planner_lattice.cpp | 7 ++++--- nav2_smac_planner/test/test_smac_lattice.cpp | 12 ++++++++++-- 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 7544f023df..c6d9ca7ea2 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -57,6 +57,7 @@ void SmacPlannerLattice::configure( _costmap_ros = costmap_ros; _name = name; _global_frame = costmap_ros->getGlobalFrameID(); + _raw_plan_publisher = node->create_publisher("unsmoothed_plan", 1); RCLCPP_INFO(_logger, "Configuring %s of type SmacPlannerLattice", name.c_str()); @@ -68,8 +69,10 @@ void SmacPlannerLattice::configure( node, name + ".max_iterations", rclcpp::ParameterValue(1000000)); node->get_parameter(name + ".max_iterations", _max_iterations); + // Default to a well rounded model: 16 bin, 0.4m turning radius, ackermann model nav2_util::declare_parameter_if_not_declared( - node, name + ".lattice_filepath", rclcpp::ParameterValue(std::string(""))); + node, name + ".lattice_filepath", rclcpp::ParameterValue( + ament_index_cpp::get_package_share_directory("nav2_smac_planner") + "/output.json")); node->get_parameter(name + ".lattice_filepath", _search_info.lattice_filepath); nav2_util::declare_parameter_if_not_declared( node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(false)); @@ -157,8 +160,6 @@ void SmacPlannerLattice::configure( _smoother = std::make_unique(params); _smoother->initialize(_metadata.min_turning_radius); - _raw_plan_publisher = node->create_publisher("unsmoothed_plan", 1); - RCLCPP_INFO( _logger, "Configured plugin %s of type SmacPlannerLattice with " "maximum iterations %i, " diff --git a/nav2_smac_planner/test/test_smac_lattice.cpp b/nav2_smac_planner/test/test_smac_lattice.cpp index 1777c293f1..b130e385e9 100644 --- a/nav2_smac_planner/test/test_smac_lattice.cpp +++ b/nav2_smac_planner/test/test_smac_lattice.cpp @@ -57,7 +57,11 @@ TEST(SmacTest, test_smac_lattice) goal.pose.position.y = 1.0; goal.pose.orientation.w = 1.0; auto planner = std::make_unique(); - planner->configure(nodeLattice, "test", nullptr, costmap_ros); + try { + // Expect to throw due to invalid prims file in param + planner->configure(nodeLattice, "test", nullptr, costmap_ros); + } catch (...) { + } planner->activate(); try { @@ -84,7 +88,11 @@ TEST(SmacTest, test_smac_lattice_reconfigure) costmap_ros->on_configure(rclcpp_lifecycle::State()); auto planner = std::make_unique(); - planner->configure(nodeLattice, "test", nullptr, costmap_ros); + try { + // Expect to throw due to invalid prims file in param + planner->configure(nodeLattice, "test", nullptr, costmap_ros); + } catch (...) { + } planner->activate(); auto rec_param = std::make_shared( From f1ee7282892943bb45bb9606c27c38b486a45ed5 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 18:22:40 -0800 Subject: [PATCH 28/31] adding default model --- nav2_smac_planner/src/smac_planner_lattice.cpp | 2 +- nav2_smac_planner/test/CMakeLists.txt | 2 +- .../test/{output.json => default_model.json} | 0 nav2_smac_planner/test/test_a_star.cpp | 2 +- nav2_smac_planner/test/test_nodelattice.cpp | 10 +++++----- 5 files changed, 8 insertions(+), 8 deletions(-) rename nav2_smac_planner/test/{output.json => default_model.json} (100%) diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index c6d9ca7ea2..143e4e9740 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -72,7 +72,7 @@ void SmacPlannerLattice::configure( // Default to a well rounded model: 16 bin, 0.4m turning radius, ackermann model nav2_util::declare_parameter_if_not_declared( node, name + ".lattice_filepath", rclcpp::ParameterValue( - ament_index_cpp::get_package_share_directory("nav2_smac_planner") + "/output.json")); + ament_index_cpp::get_package_share_directory("nav2_smac_planner") + "/default_model.json")); node->get_parameter(name + ".lattice_filepath", _search_info.lattice_filepath); nav2_util::declare_parameter_if_not_declared( node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(false)); diff --git a/nav2_smac_planner/test/CMakeLists.txt b/nav2_smac_planner/test/CMakeLists.txt index 0b04e2580b..824c203c87 100644 --- a/nav2_smac_planner/test/CMakeLists.txt +++ b/nav2_smac_planner/test/CMakeLists.txt @@ -104,4 +104,4 @@ ament_target_dependencies(test_lattice_node ${dependencies}) target_link_libraries(test_lattice_node ${library_name}) -install(FILES output.json DESTINATION share/${PROJECT_NAME}) +install(FILES default_model.json DESTINATION share/${PROJECT_NAME}) diff --git a/nav2_smac_planner/test/output.json b/nav2_smac_planner/test/default_model.json similarity index 100% rename from nav2_smac_planner/test/output.json rename to nav2_smac_planner/test/default_model.json diff --git a/nav2_smac_planner/test/test_a_star.cpp b/nav2_smac_planner/test/test_a_star.cpp index fb5ecda287..154817fa29 100644 --- a/nav2_smac_planner/test/test_a_star.cpp +++ b/nav2_smac_planner/test/test_a_star.cpp @@ -177,7 +177,7 @@ TEST(AStarTest, test_a_star_lattice) info.reverse_penalty = 2.0; info.analytic_expansion_ratio = 3.5; info.lattice_filepath = - ament_index_cpp::get_package_share_directory("nav2_smac_planner") + "/output.json"; + ament_index_cpp::get_package_share_directory("nav2_smac_planner") + "/default_model.json"; info.minimum_turning_radius = 8; // in grid coordinates 0.4/0.05 unsigned int size_theta = 16; info.cost_penalty = 2.0; diff --git a/nav2_smac_planner/test/test_nodelattice.cpp b/nav2_smac_planner/test/test_nodelattice.cpp index 3c652a075e..a12315991a 100644 --- a/nav2_smac_planner/test/test_nodelattice.cpp +++ b/nav2_smac_planner/test/test_nodelattice.cpp @@ -28,7 +28,7 @@ using json = nlohmann::json; TEST(NodeLatticeTest, parser_test) { std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); - std::string filePath = pkg_share_dir + "/output.json"; + std::string filePath = pkg_share_dir + "/default_model.json"; std::ifstream myJsonFile(filePath); ASSERT_TRUE(myJsonFile.is_open()); @@ -83,7 +83,7 @@ TEST(NodeLatticeTest, parser_test) TEST(NodeLatticeTest, test_node_lattice_neighbors_and_parsing) { std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); - std::string filePath = pkg_share_dir + "/output.json"; + std::string filePath = pkg_share_dir + "/default_model.json"; nav2_smac_planner::SearchInfo info; info.minimum_turning_radius = 1.1; @@ -120,7 +120,7 @@ TEST(NodeLatticeTest, test_node_lattice_neighbors_and_parsing) TEST(NodeLatticeTest, test_node_lattice_conversions) { std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); - std::string filePath = pkg_share_dir + "/output.json"; + std::string filePath = pkg_share_dir + "/default_model.json"; nav2_smac_planner::SearchInfo info; info.minimum_turning_radius = 1.1; @@ -154,7 +154,7 @@ TEST(NodeLatticeTest, test_node_lattice_conversions) TEST(NodeLatticeTest, test_node_lattice) { std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); - std::string filePath = pkg_share_dir + "/output.json"; + std::string filePath = pkg_share_dir + "/default_model.json"; nav2_smac_planner::SearchInfo info; info.minimum_turning_radius = 1.1; @@ -227,7 +227,7 @@ TEST(NodeLatticeTest, test_node_lattice) TEST(NodeLatticeTest, test_get_neighbors) { std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); - std::string filePath = pkg_share_dir + "/output.json"; + std::string filePath = pkg_share_dir + "/default_model.json"; nav2_smac_planner::SearchInfo info; info.minimum_turning_radius = 1.1; From 4c2b5ae82ebd04a0ca2ba3d5ae326885e66967bc Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Tue, 16 Nov 2021 18:26:27 -0800 Subject: [PATCH 29/31] adding corrected exporting of plugins --- nav2_smac_planner/CMakeLists.txt | 2 +- nav2_smac_planner/package.xml | 4 +++- nav2_smac_planner/{smac_plugin.xml => smac_plugin_hybrid.xml} | 0 3 files changed, 4 insertions(+), 2 deletions(-) rename nav2_smac_planner/{smac_plugin.xml => smac_plugin_hybrid.xml} (100%) diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index 761ed6e19c..5e855b3b3b 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -134,7 +134,7 @@ ament_target_dependencies(${library_name}_lattice ${dependencies} ) -pluginlib_export_plugin_description_file(nav2_core smac_plugin.xml) +pluginlib_export_plugin_description_file(nav2_core smac_plugin_hybrid.xml) pluginlib_export_plugin_description_file(nav2_core smac_plugin_2d.xml) pluginlib_export_plugin_description_file(nav2_core smac_plugin_lattice.xml) diff --git a/nav2_smac_planner/package.xml b/nav2_smac_planner/package.xml index f2c5654915..929e1141ab 100644 --- a/nav2_smac_planner/package.xml +++ b/nav2_smac_planner/package.xml @@ -36,6 +36,8 @@ ament_cmake - + + + diff --git a/nav2_smac_planner/smac_plugin.xml b/nav2_smac_planner/smac_plugin_hybrid.xml similarity index 100% rename from nav2_smac_planner/smac_plugin.xml rename to nav2_smac_planner/smac_plugin_hybrid.xml From 36f32c07b794ec48bffd5f1374dd14dcb39aa7d2 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 17 Nov 2021 15:02:23 -0800 Subject: [PATCH 30/31] adding more test coverage --- nav2_smac_planner/test/test_smac_2d.cpp | 4 +++- nav2_smac_planner/test/test_smac_lattice.cpp | 18 ++++++++++++++++-- 2 files changed, 19 insertions(+), 3 deletions(-) diff --git a/nav2_smac_planner/test/test_smac_2d.cpp b/nav2_smac_planner/test/test_smac_2d.cpp index 0509a7cebd..ebbac996cd 100644 --- a/nav2_smac_planner/test/test_smac_2d.cpp +++ b/nav2_smac_planner/test/test_smac_2d.cpp @@ -108,7 +108,8 @@ TEST(SmacTest, test_smac_2d_reconfigure) { rclcpp::Parameter("test.downsampling_factor", 2), rclcpp::Parameter("test.max_iterations", -1), rclcpp::Parameter("test.max_on_approach_iterations", -1), - rclcpp::Parameter("test.motion_model_for_search", "UNKNOWN")}); + rclcpp::Parameter("test.motion_model_for_search", "UNKNOWN"), + rclcpp::Parameter("test.use_final_approach_orientation", false)}); rclcpp::spin_until_future_complete( node2D->get_node_base_interface(), @@ -123,6 +124,7 @@ TEST(SmacTest, test_smac_2d_reconfigure) { EXPECT_EQ(node2D->get_parameter("test.allow_unknown").as_bool(), false); EXPECT_EQ(node2D->get_parameter("test.downsampling_factor").as_int(), 2); EXPECT_EQ(node2D->get_parameter("test.max_iterations").as_int(), -1); + EXPECT_EQ(node2D->get_parameter("test.use_final_approach_orientation").as_bool(), false); EXPECT_EQ( node2D->get_parameter("test.max_on_approach_iterations").as_int(), -1); diff --git a/nav2_smac_planner/test/test_smac_lattice.cpp b/nav2_smac_planner/test/test_smac_lattice.cpp index b130e385e9..e323f92fd0 100644 --- a/nav2_smac_planner/test/test_smac_lattice.cpp +++ b/nav2_smac_planner/test/test_smac_lattice.cpp @@ -36,6 +36,16 @@ class RclCppFixture }; RclCppFixture g_rclcppfixture; +// Simple wrapper to be able to call a private member +class LatticeWrap : public nav2_smac_planner::SmacPlannerLattice +{ +public: + void callDynamicParams(std::vector parameters) + { + dynamicParametersCallback(parameters); + } +}; + // SMAC smoke tests for plugin-level issues rather than algorithms // (covered by more extensively testing in other files) // System tests in nav2_system_tests will actually plan with this work @@ -87,7 +97,7 @@ TEST(SmacTest, test_smac_lattice_reconfigure) std::make_shared("global_costmap"); costmap_ros->on_configure(rclcpp_lifecycle::State()); - auto planner = std::make_unique(); + auto planner = std::make_unique(); try { // Expect to throw due to invalid prims file in param planner->configure(nodeLattice, "test", nullptr, costmap_ros); @@ -111,7 +121,6 @@ TEST(SmacTest, test_smac_lattice_reconfigure) rclcpp::Parameter("test.analytic_expansion_ratio", 4.0), rclcpp::Parameter("test.max_planning_time", 10.0), rclcpp::Parameter("test.lookup_table_size", 30.0), - rclcpp::Parameter("test.lattice_filepath", std::string("HI")), rclcpp::Parameter("test.allow_reverse_expansion", true)}); try { @@ -123,4 +132,9 @@ TEST(SmacTest, test_smac_lattice_reconfigure) results); } catch (...) { } + + // So instead, lets call manually on a change + std::vector parameters; + parameters.push_back(rclcpp::Parameter("test.lattice_filepath", std::string("HI"))); + EXPECT_THROW(planner->callDynamicParams(parameters), std::runtime_error); } From 8da0f29de39043ca752db5d1433b104223a09c37 Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Wed, 17 Nov 2021 15:06:42 -0800 Subject: [PATCH 31/31] reorder tests to see if natters --- .../src/planning/test_planner_plugins.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/nav2_system_tests/src/planning/test_planner_plugins.cpp b/nav2_system_tests/src/planning/test_planner_plugins.cpp index 5d4b52eb87..a6eca85212 100644 --- a/nav2_system_tests/src/planning/test_planner_plugins.cpp +++ b/nav2_system_tests/src/planning/test_planner_plugins.cpp @@ -170,11 +170,6 @@ TEST(testPluginMap, ThetaStarVerySmallPath) testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.00001); } -TEST(testPluginMap, ThetaStarBelowCostmapResolution) -{ - testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.09); -} - TEST(testPluginMap, ThetaStarJustAboveCostmapResolution) { testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.102); @@ -185,6 +180,11 @@ TEST(testPluginMap, ThetaStarAboveCostmapResolution) testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 1.5); } +TEST(testPluginMap, ThetaStarBelowCostmapResolution) +{ + testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.09); +} + int main(int argc, char ** argv) { ::testing::InitGoogleTest(&argc, argv);