From 12c5e3cc74cba4c6b28900b7ec6be35e638044fd Mon Sep 17 00:00:00 2001 From: Steve Macenski Date: Fri, 18 Jun 2021 15:18:59 -0700 Subject: [PATCH] Hybrid-A* optimizations and completion without on-going State Lattice work (#2404) * major smac planner collision checking speedups and improvements * fix linting errors * wireframe for state lattice node * finishing boilerplate changes * adding more context to each TODO and notes about path to completion * prototype for the base plugin + refactor out common logic for all planners * commiting speed up work in progress * adding in improvements to overall user quality of life * pushing updates to 2D for faster / smoother; hybrid for smoother and new heuristic function; a bit of rearchitecture; deprecating smoother to make room for a new one * adding smoother prototype * adding orientation guestimator * correcing 2d * done with smoother * enabling collision checking full SE2 only when under inscribed cost according to current exponential decay function * adding doxgyen on new function * linting * testing working * fixing looping at end of paths + simplifying code * fixed cost-based issue in smoother * finishing touches on smoothing * smoother recursion fix + crashing issue resolved * incremental changes * completed hybrid A* plannern * adding images * purge state lattice work to merge in just Hybrid-A* improvements * linting --- .../footprint_collision_checker.hpp | 7 + .../src/footprint_collision_checker.cpp | 45 +- nav2_smac_planner/CMakeLists.txt | 23 +- nav2_smac_planner/README.md | 153 +++-- .../include/nav2_smac_planner/a_star.hpp | 114 ++- .../nav2_smac_planner/collision_checker.hpp | 95 ++- .../include/nav2_smac_planner/constants.hpp | 14 +- .../include/nav2_smac_planner/node_2d.hpp | 63 +- .../include/nav2_smac_planner/node_basic.hpp | 6 +- .../{node_se2.hpp => node_hybrid.hpp} | 183 +++-- .../nav2_smac_planner/smac_planner_2d.hpp | 20 +- ...ac_planner.hpp => smac_planner_hybrid.hpp} | 43 +- .../include/nav2_smac_planner/smoother.hpp | 247 +++++-- .../include/nav2_smac_planner/types.hpp | 50 ++ .../include/nav2_smac_planner/utils.hpp | 109 +++ nav2_smac_planner/media/A.png | Bin 0 -> 235271 bytes nav2_smac_planner/media/B.png | Bin 0 -> 213018 bytes nav2_smac_planner/package.xml | 3 +- nav2_smac_planner/smac_plugin.xml | 4 +- nav2_smac_planner/smac_plugin_2d.xml | 2 +- nav2_smac_planner/src/a_star.cpp | 466 +++++++------ nav2_smac_planner/src/costmap_downsampler.cpp | 18 +- nav2_smac_planner/src/node_2d.cpp | 74 +- nav2_smac_planner/src/node_hybrid.cpp | 648 ++++++++++++++++++ nav2_smac_planner/src/node_se2.cpp | 462 ------------- nav2_smac_planner/src/smac_planner_2d.cpp | 127 +--- ...ac_planner.cpp => smac_planner_hybrid.cpp} | 216 +++--- nav2_smac_planner/test/CMakeLists.txt | 30 +- .../deprecated}/options.hpp | 6 +- .../test/deprecated/smoother.hpp | 141 ++++ .../deprecated}/smoother_cost_function.hpp | 37 +- .../upsampler.hpp | 6 +- .../upsampler_cost_function.hpp | 6 +- .../upsampler_cost_function_nlls.hpp | 6 +- nav2_smac_planner/test/test_a_star.cpp | 51 +- .../test/test_collision_checker.cpp | 20 +- nav2_smac_planner/test/test_node2d.cpp | 63 +- nav2_smac_planner/test/test_nodebasic.cpp | 4 +- nav2_smac_planner/test/test_nodehybrid.cpp | 219 ++++++ nav2_smac_planner/test/test_nodese2.cpp | 214 ------ nav2_smac_planner/test/test_smac_2d.cpp | 4 +- ...test_smac_se2.cpp => test_smac_hybrid.cpp} | 23 +- nav2_smac_planner/test/test_smoother.cpp | 104 --- 43 files changed, 2359 insertions(+), 1767 deletions(-) rename nav2_smac_planner/include/nav2_smac_planner/{node_se2.hpp => node_hybrid.hpp} (66%) rename nav2_smac_planner/include/nav2_smac_planner/{smac_planner.hpp => smac_planner_hybrid.hpp} (69%) create mode 100644 nav2_smac_planner/include/nav2_smac_planner/utils.hpp create mode 100644 nav2_smac_planner/media/A.png create mode 100644 nav2_smac_planner/media/B.png create mode 100644 nav2_smac_planner/src/node_hybrid.cpp delete mode 100644 nav2_smac_planner/src/node_se2.cpp rename nav2_smac_planner/src/{smac_planner.cpp => smac_planner_hybrid.cpp} (62%) rename nav2_smac_planner/{include/nav2_smac_planner => test/deprecated}/options.hpp (98%) create mode 100644 nav2_smac_planner/test/deprecated/smoother.hpp rename nav2_smac_planner/{include/nav2_smac_planner => test/deprecated}/smoother_cost_function.hpp (94%) rename nav2_smac_planner/test/{deprecated_upsampler => deprecated}/upsampler.hpp (98%) rename nav2_smac_planner/test/{deprecated_upsampler => deprecated}/upsampler_cost_function.hpp (98%) rename nav2_smac_planner/test/{deprecated_upsampler => deprecated}/upsampler_cost_function_nlls.hpp (98%) create mode 100644 nav2_smac_planner/test/test_nodehybrid.cpp delete mode 100644 nav2_smac_planner/test/test_nodese2.cpp rename nav2_smac_planner/test/{test_smac_se2.cpp => test_smac_hybrid.cpp} (85%) delete mode 100644 nav2_smac_planner/test/test_smoother.cpp diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/footprint_collision_checker.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/footprint_collision_checker.hpp index 662dbbdd70..c90bad5ddd 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/footprint_collision_checker.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/footprint_collision_checker.hpp @@ -72,6 +72,13 @@ class FootprintCollisionChecker * @brief Set the current costmap object to use for collision detection */ void setCostmap(CostmapT costmap); + /** + * @brief Get the current costmap object + */ + CostmapT getCostmap() + { + return costmap_; + } protected: CostmapT costmap_; diff --git a/nav2_costmap_2d/src/footprint_collision_checker.cpp b/nav2_costmap_2d/src/footprint_collision_checker.cpp index 20d60b3442..09876fb7c7 100644 --- a/nav2_costmap_2d/src/footprint_collision_checker.cpp +++ b/nav2_costmap_2d/src/footprint_collision_checker.cpp @@ -51,12 +51,17 @@ double FootprintCollisionChecker::footprintCost(const Footprint footpr unsigned int x0, x1, y0, y1; double footprint_cost = 0.0; + // get the cell coord of the first point + if (!worldToMap(footprint[0].x, footprint[0].y, x0, y0)) { + return static_cast(LETHAL_OBSTACLE); + } + + // cache the start to eliminate a worldToMap call + unsigned int xstart = x0; + unsigned int ystart = y0; + // we need to rasterize each line in the footprint for (unsigned int i = 0; i < footprint.size() - 1; ++i) { - // get the cell coord of the first point - if (!worldToMap(footprint[i].x, footprint[i].y, x0, y0)) { - return static_cast(LETHAL_OBSTACLE); - } // get the cell coord of the second point if (!worldToMap(footprint[i + 1].x, footprint[i + 1].y, x1, y1)) { @@ -64,23 +69,22 @@ double FootprintCollisionChecker::footprintCost(const Footprint footpr } footprint_cost = std::max(lineCost(x0, x1, y0, y1), footprint_cost); - } - // we also need to connect the first point in the footprint to the last point - // get the cell coord of the last point - if (!worldToMap(footprint.back().x, footprint.back().y, x0, y0)) { - return static_cast(LETHAL_OBSTACLE); - } + // the second point is next iteration's first point + x0 = x1; + y0 = y1; - // get the cell coord of the first point - if (!worldToMap(footprint.front().x, footprint.front().y, x1, y1)) { - return static_cast(LETHAL_OBSTACLE); + // if in collision, no need to continue + if (footprint_cost == static_cast(INSCRIBED_INFLATED_OBSTACLE) || + footprint_cost == static_cast(LETHAL_OBSTACLE)) + { + return footprint_cost; + } } - footprint_cost = std::max(lineCost(x0, x1, y0, y1), footprint_cost); - - // if all line costs are legal... then we can return that the footprint is legal - return footprint_cost; + // we also need to connect the first point in the footprint to the last point + // the last iteration's x1, y1 are the last footprint point's coordinates + return std::max(lineCost(xstart, x1, ystart, y1), footprint_cost); } template @@ -95,6 +99,13 @@ double FootprintCollisionChecker::lineCost(int x0, int x1, int y0, int if (line_cost < point_cost) { line_cost = point_cost; } + + // if in collision, no need to continue + if (line_cost == static_cast(INSCRIBED_INFLATED_OBSTACLE) || + line_cost == static_cast(LETHAL_OBSTACLE)) + { + return line_cost; + } } return line_cost; diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index ecc52347f2..05b84e4f8b 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -19,7 +19,6 @@ find_package(builtin_interfaces REQUIRED) find_package(tf2_ros REQUIRED) find_package(nav2_costmap_2d REQUIRED) find_package(pluginlib REQUIRED) -find_package(Ceres REQUIRED COMPONENTS SuiteSparse) find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED) find_package(ompl REQUIRED) @@ -35,12 +34,16 @@ add_compile_options(-O3 -Wextra -Wdeprecated -fPIC) include_directories( include - ${CERES_INCLUDES} ${OMPL_INCLUDE_DIRS} ${OpenMP_INCLUDE_DIRS} ) -set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") -set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}") + +find_package(OpenMP) +if(OPENMP_FOUND) + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") + set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${OpenMP_EXE_LINKER_FLAGS}") +endif() set(library_name nav2_smac_planner) @@ -62,16 +65,16 @@ set(dependencies eigen3_cmake_module ) -# SE2 plugin +# Hybrid plugin add_library(${library_name} SHARED - src/smac_planner.cpp + src/smac_planner_hybrid.cpp src/a_star.cpp - src/node_se2.cpp + src/node_hybrid.cpp src/costmap_downsampler.cpp src/node_2d.cpp ) -target_link_libraries(${library_name} ${CERES_LIBRARIES} ${OMPL_LIBRARIES} ${OpenMP_LIBRARIES} OpenMP::OpenMP_CXX) +target_link_libraries(${library_name} ${OMPL_LIBRARIES} ${OpenMP_LIBRARIES} OpenMP::OpenMP_CXX) target_include_directories(${library_name} PUBLIC ${Eigen3_INCLUDE_DIRS}) ament_target_dependencies(${library_name} @@ -82,12 +85,12 @@ ament_target_dependencies(${library_name} add_library(${library_name}_2d SHARED src/smac_planner_2d.cpp src/a_star.cpp - src/node_se2.cpp + src/node_hybrid.cpp src/costmap_downsampler.cpp src/node_2d.cpp ) -target_link_libraries(${library_name}_2d ${CERES_LIBRARIES} ${OMPL_LIBRARIES}) +target_link_libraries(${library_name}_2d ${OMPL_LIBRARIES}) target_include_directories(${library_name}_2d PUBLIC ${Eigen3_INCLUDE_DIRS}) ament_target_dependencies(${library_name}_2d diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index 0bd57feb4d..5d36fb47e4 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -1,14 +1,14 @@ # Smac Planner The SmacPlanner is a plugin for the Nav2 Planner server. It includes currently 2 distinct plugins: -- `SmacPlanner`: a highly optimized fully reconfigurable Hybrid-A* implementation supporting Dubin and Reeds-Shepp models. +- `SmacPlannerHybrid`: a highly optimized fully reconfigurable Hybrid-A* implementation supporting Dubin and Reeds-Shepp models (ackermann and car 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* and 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* planning. Additional template for 3D planning also could be made available. - `CollisionChecker`: Collision check based on a robot's radius or footprint. -- `Smoother`: A Conjugate-gradient (CG) smoother with several optional cost function implementations for use. This is a cost-aware smoother unlike b-splines or bezier curves. +- `Smoother`: A path smoother to smooth out 2D, Hybrid-A\* paths. We have users reporting using this on: - Delivery robots @@ -16,16 +16,16 @@ 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 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 `SmacPlanner` plugin which implements a Hybrid-A\* planner. This plugin is 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. 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 `SmacPlanner` fully-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, CG 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), including hybrid searching, gradient descent smoothing, analytic expansions and hueristic functions. In summary... -The `SmacPlanner` is designed to work with: +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 requring SE2 collision checking +- Arbitrary shaped, non-circular differential or omnidirectional robots requiring SE2 collision checking with constrained curvatures The `SmacPlanner2D` is designed to work with: - Circular, differential or omnidirectional robots @@ -33,27 +33,28 @@ The `SmacPlanner2D` is designed to work with: ## Features -We further improve on the Hybrid-A\* work in the following ways: +We further improve 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). -- Additional cost functions in the CG smoother including path deflection. -- Approximated smoother Voronoi field using costmap inflation function. -- Fixed 3 mathematical issues in the original paper resulting in higher quality smoothing. +- Gradient descent smoother - Faster planning than original paper by highly optimizing the template A\* algorithm. +- Faster planning via 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. -- Time monitoring of planning to dynamically scale the maximum CG smoothing time based on remaining planning duration requested. - High unit and integration test coverage, doxygen documentation. - Uses modern C++14 language features and individual components are easily reusable. -- Speed optimizations: Fast approximation of shortest paths with wavefront hueristic, no data structure graph lookups in main loop, near-zero copy main loop, Voronoi field approximation, et al. +- 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. - 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 2D `SmacPlanner2D` plugin. +All of these features (multi-resolution, models, smoother, etc) are also available in the `SmacPlanner2D` plugin. 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. +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 B-Spline 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. + ## Metrics 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: @@ -69,17 +70,15 @@ 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 can be used to smooth it out. We also provide a SE2 node template (`NodeSE2`) 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. - -Additional node templates could be added into the future to better support other types of robot path planning, such as including a state lattice motion primitive node and 3D path planning. Pull requests or discussions aroudn this point is encouraged. +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. -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 SE2 and `SmacPlanner` 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. 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. 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. ## Parameters -See inline description of parameters in the `SmacPlanner`. This includes comments as specific parameters apply to `SmacPlanner2D` and `SmacPlanner` in SE2 place. +See inline description of parameters in the `SmacPlanner`. This includes comments as specific parameters apply to `SmacPlanner2D` and `SmacPlanner` in place. ``` planner_server: @@ -89,44 +88,31 @@ planner_server: GridBased: plugin: "nav2_smac_planner/SmacPlanner" - tolerance: 0.5 # tolerance for planning if unable to reach exact pose, in meters, for 2D node - downsample_costmap: false # whether or not to downsample the map - downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm) - allow_unknown: false # allow traveling in unknown space - max_iterations: -1 # maximum total iterations to search for before failing - max_on_approach_iterations: 1000 # maximum number of iterations to attempt to reach goal once in tolerance, 2D only - max_planning_time: 2.0 # max time in s for planner to plan, smooth, and upsample. Will scale maximum smoothing and upsampling times based on remaining time after planning. - smooth_path: false # Whether to smooth searched path - motion_model_for_search: "DUBIN" # 2D Moore, Von Neumann; SE2 Dubin, Redds-Shepp - angle_quantization_bins: 72 # For SE2 node: Number of angle bins for search, must be 1 for 2D node (no angle search) - minimum_turning_radius: 0.20 # For SE2 node & smoother: 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.20 # For SE2 node: penalty to apply if motion is changing directions, must be >= 0 - non_straight_penalty: 1.05 # For SE2 node: penalty to apply if motion is non-straight, must be => 1 - cost_penalty: 1.3 # For SE2 node: penalty to apply to higher cost zones - + tolerance: 0.5 # tolerance for planning if unable to reach exact pose, in meters, for 2D node + downsample_costmap: false # whether or not to downsample the map + downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm) + allow_unknown: false # allow traveling in unknown space + max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable + max_on_approach_iterations: 1000 # maximum number of iterations to attempt to reach goal once in tolerance, 2D only + 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 nodes: Number of angle bins for search, must be 1 for 2D node (no angle search) + minimum_turning_radius: 0.40 # For Hybrid nodes: minimum turning radius in m of path / vehicle + angle_quantization_bins: 64 # For Hybrid/Lattice 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 + 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. + 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. smoother: - smoother: - w_curve: 30.0 # weight to minimize curvature of path - w_dist: 0.0 # weight to bind path to original as optional replacement for cost weight - w_smooth: 30000.0 # weight to maximize smoothness of path - w_cost: 0.025 # weight to steer robot away from collision and cost - cost_scaling_factor: 10.0 # this should match the inflation layer's parameter - - # I do not recommend users mess with this unless they're doing production tuning - optimizer: - max_time: 0.10 # maximum compute time for smoother - max_iterations: 500 # max iterations of smoother - debug_optimizer: false # print debug info - gradient_tol: 1.0e-10 - fn_tol: 1.0e-20 - param_tol: 1.0e-15 - advanced: - min_line_search_step_size: 1.0e-20 - max_num_line_search_step_size_iterations: 50 - line_search_sufficient_function_decrease: 1.0e-20 - max_num_line_search_direction_restarts: 10 - max_line_search_step_expansion: 50 + max_iterations: 1000 + w_smooth: 0.3 + w_data: 0.2 + tolerance: 1e-10 ``` ## Topics @@ -150,24 +136,63 @@ Many users and default navigation configuration files I find are really missing Some of the most popular tuning guides for Navigation / Nav2 even [call this out specifically](https://arxiv.org/pdf/1706.09068.pdf) that there's substantial benefit to creating a gentle potential field across the width of the map - after inscribed costs are applied - yet very few users do this. -This habit actually results in paths produced by NavFn, Global Planner, and now SmacPlanner to be very suboptimal. They really want to look for a smooth potential field rather than wide open 0-cost spaces in order to stay in the middle of spaces and deal with close-by moving obstacles better. +This habit actually results in paths produced by NavFn, Global Planner, and now SmacPlanner to be somewhat suboptimal. They really want to look for a smooth potential field rather than wide open 0-cost spaces in order to stay in the middle of spaces and deal with close-by moving obstacles better. 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**. -### 2D Search and Smoothing +### Hybrid-A* Turning Radius' -While the 2D planner has the smoother available (albeit, default parameters are tuned for the Hybrid-A\* planner, so you may need to play with that), my recommendation is not to use it. +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. -The 2D planner provides a 4-connected or 8-connected neighborhood path. This path may have little zig-zags in order to get at another non-90 or non-45 degree heading. That is totally fine. Your local trajectory planner such as DWB and TEB take these points into account to follow, but you won't see any zig-zag behaviors of your final robot motion after given to a trajectory planner. +I assert that you should also consider the environment you operate within when setting this. While you should **absolutely not** set this to be any smaller than the actual limits of your vehicle, there are some useful side effects of increasing this value in practical use. If you work in an area wider than the turning circle of your robot, you have some options that will ultimately improve the performance of the planner (in terms of CPU and compute time) as well as generate paths that are more "smooth" directly out of the planner -- not requiring any explicit path smoothing. -The smoothing is more "pleasing" to human eyes, but you don't want to be owning additional compute when it doesn't largely impact the output. However, if you have a more sensitive local trajectory planner like a carrot follower (e.g. pure pursuit), then you will want to smooth out the paths in order to have something more easily followable. - -Take this advise into account. Some good numbers to potentially start with would be `cost_scaling_factor: 10.0` and `inflation_radius: 5.5`. +By default, `0.4m` is the setting which I think is "reasonable" for the smaller scale industrial grade robots (think Simbe, the small Fetch, or Locus robots) resulting in faster plans and less "wobbly" motions that do not require post-smoothing -- further improving CPU performance. I selected `0.4m` as a trade off between practical robots mentioned above and hobbyist users with a tiny-little-turtlebot-3 which might still need to navigate around some smaller cavities. ### Costmap Resolutions -We provide for both 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 60m paths in an office space, I was able to get it << 100ms at a 2-3x downsample rate. +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. 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. 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. + +### 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. + +In maps with small gaps or holes, you may see an issue planning to certain regions. If there are gaps small enough to be untraversible yet large enough that inflation doesn't close it up with inflated costs, then it is recommended to lightly touch up the map or increase your inflation to remove those spaces from non-lethal space. + +Seeing the figures below, you'll see an attempt to plan into a "U" shaped region across the map. The first figure shows the small gap in the map (from an imperfect SLAM session) which is nearly traversible, but not quite. From the starting location, that gap yeilds the shortest path to the goal, so the heuristics will attempt to route the paths in that direction. However, it is not possible to actually pass with a kinematically valid path with the footprint set. As a result, the planner expands all of its maximum 1,000,000 iterations attempting to fit through it (visualized in red). If an infinite number of iterations were allowed, eventually a valid path would be found, but might take significant time. + +By simply increasing the footprint (a bit hackier, the best solution is to edit the map to make this area impassible), then that gap is now properly blocked as un-navigable. In the second figure, you can see that the heuristics influence the expansion down a navigable route and is able to find a path in less than 10,000 iterations (or about 110ms). It is easy now! + +As such, it is recommended if you have sparse SLAM maps, gaps or holes in your map, that you lightly post-process them to fill those gaps or increasing your footprint's padding or radius to make these areas invalid. Without it, it might waste expansions on this small corridor that: A) you dont want your robot actually using B) probably isnt actually valid and a SLAM artifact and C) if there's a more open space, you'd rather it use that. + +![](media/A.png) +![](media/B.png) + +One interesting thing to note from the second figure is that you see a number of expansions in open space. This is due to travel / heuristic values being so similar, tuning values of the penalty weights can have a decent impact there. The defaults are set as a good middle ground between large open spaces and confined aisles (environment specific tuning could be done to reduce the number of expansions for a specific map, speeding up the planner). The planner actually runs substantially faster the more confined the areas of search / environments are -- but still plenty fast for even wide open areas! + +Sometimes visualizing the expansions is very useful to debug potential concerns (why does this goal take longer to compute, why can't I find a path, etc), should you on rare occasion run into an issue. The following snippet is what I used to visualize the expansion in the images above which may help you in future endevours. + +``` cpp +// In createPath() +static auto node = std::make_shared("test"); +static auto pub = node->create_publisher("expansions", 1); +geometry_msgs::msg::PoseArray msg; +geometry_msgs::msg::Pose msg_pose; +msg.header.stamp = node->now(); +msg.header.frame_id = "map"; + +... + +// Each time we expand a new node +msg_pose.position.x = _costmap->getOriginX() + (current_node->pose.x * _costmap->getResolution()); +msg_pose.position.y = _costmap->getOriginY() + (current_node->pose.y * _costmap->getResolution()); +msg.poses.push_back(msg_pose); + +... + +// On backtrace or failure +pub->publish(msg); +``` 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 6158422a7d..39d5788b97 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/a_star.hpp @@ -27,7 +27,7 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_smac_planner/node_2d.hpp" -#include "nav2_smac_planner/node_se2.hpp" +#include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/node_basic.hpp" #include "nav2_smac_planner/types.hpp" #include "nav2_smac_planner/constants.hpp" @@ -35,15 +35,6 @@ namespace nav2_smac_planner { -inline double squaredDistance( - const Eigen::Vector2d & p1, - const Eigen::Vector2d & p2) -{ - const double & dx = p1[0] - p2[0]; - const double & dy = p1[1] - p2[1]; - return hypot(dx, dy); -} - /** * @class nav2_smac_planner::AStarAlgorithm * @brief An A* implementation for planning in a costmap. Templated based on the Node type. @@ -61,6 +52,27 @@ 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 @@ -97,7 +109,9 @@ class AStarAlgorithm void initialize( const bool & allow_unknown, int & max_iterations, - const int & max_on_approach_iterations); + const int & max_on_approach_iterations, + const float & lookup_table_size, + const unsigned int & dim_3_size); /** * @brief Creating path from given costmap, start, and goal @@ -109,18 +123,10 @@ class AStarAlgorithm bool createPath(CoordinateVector & path, int & num_iterations, const float & tolerance); /** - * @brief Create the graph based on the node type. For 2D nodes, a cost grid. - * For 3D nodes, a SE2 grid without cost info as needs collision detector for footprint. - * @param x The total number of nodes in the X direction - * @param y The total number of nodes in the X direction - * @param dim_3 The total number of nodes in the theta or Z direction - * @param costmap Costmap to convert into the graph + * @brief Sets the collision checker to use + * @param collision_checker Collision checker to use for checking state validity */ - void createGraph( - const unsigned int & x, - const unsigned int & y, - const unsigned int & dim_3, - nav2_costmap_2d::Costmap2D * & costmap); + void setCollisionChecker(GridCollisionChecker * collision_checker); /** * @brief Set the goal for planning, as a node index @@ -144,29 +150,6 @@ class AStarAlgorithm const unsigned int & my, const unsigned int & dim_3); - /** - * @brief Set the footprint - * @param footprint footprint of robot - * @param use_radius Whether this footprint is a circle with radius - */ - void setFootprint(nav2_costmap_2d::Footprint footprint, bool use_radius); - - /** - * @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 Node pointer to goal node if successful, else return nullptr - */ - NodePtr getAnalyticPath(const NodePtr & node, const NodeGetter & getter); - - /** - * @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 maximum number of iterations to plan * @return Reference to Maximum iterations parameter @@ -227,7 +210,7 @@ class AStarAlgorithm * @param cost The cost to sort into the open set of the node * @param node Node pointer reference to add to open set */ - inline void addNode(const float cost, NodePtr & node); + inline void addNode(const float & cost, NodePtr & node); /** * @brief Adds node to graph @@ -244,19 +227,12 @@ class AStarAlgorithm inline bool isGoal(NodePtr & node); /** - * @brief Get cost of traversal between nodes - * @param current_node Pointer to current node - * @param new_node Pointer to new node - * @return Reference traversal cost between the nodes - */ - inline float getTraversalCost(NodePtr & current_node, NodePtr & new_node); - - /** - * @brief Get total cost of traversal for a node - * @param node Pointer to current node - * @return Reference accumulated cost between the nodes + * @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 */ - inline float & getAccumulatedCost(NodePtr & node); + bool backtracePath(NodePtr node, CoordinateVector & path); /** * @brief Get cost of heuristic of node @@ -287,10 +263,26 @@ class AStarAlgorithm * @return Node pointer reference to goal node if successful, else * return nullptr */ - inline NodePtr tryAnalyticExpansion( + 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; @@ -310,9 +302,7 @@ class AStarAlgorithm MotionModel _motion_model; NodeHeuristicPair _best_heuristic_node; - GridCollisionChecker _collision_checker; - nav2_costmap_2d::Footprint _footprint; - bool _is_radius_footprint; + GridCollisionChecker * _collision_checker; nav2_costmap_2d::Costmap2D * _costmap; }; 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 81fbbf887f..78f6c2e4ad 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp @@ -11,7 +11,7 @@ // 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 "nav2_costmap_2d/footprint_collision_checker.hpp" #include "nav2_smac_planner/constants.hpp" @@ -32,10 +32,14 @@ class GridCollisionChecker /** * @brief A constructor for nav2_smac_planner::GridCollisionChecker * @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) - : FootprintCollisionChecker(costmap) + nav2_costmap_2d::Costmap2D * costmap, + unsigned int num_quantizations) + : FootprintCollisionChecker(costmap), + num_quantizations_(num_quantizations) { } @@ -44,10 +48,47 @@ class GridCollisionChecker * @param footprint The footprint to collision check against * @param radius Whether or not the footprint is a circle and use radius collision checking */ - void setFootprint(const nav2_costmap_2d::Footprint & footprint, const bool & radius) + void setFootprint( + const nav2_costmap_2d::Footprint & footprint, + const bool & radius, + const double & possible_inscribed_cost) { - unoriented_footprint_ = footprint; + 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; } /** @@ -74,7 +115,7 @@ class GridCollisionChecker footprint_cost_ = costmap_->getCost( static_cast(x), static_cast(y)); - if (footprint_cost_ < POSSIBLY_INSCRIBED) { + if (footprint_cost_ < possible_inscribed_cost_) { return false; } @@ -88,9 +129,22 @@ class GridCollisionChecker return true; } - // if possible inscribed, need to check actual footprint pose - footprint_cost_ = footprintCostAtPose( - wx, wy, static_cast(theta), unoriented_footprint_); + // 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; } @@ -111,6 +165,25 @@ class GridCollisionChecker } } + /** + * @brief Check if in collision with costmap and footprint at pose + * @param i Index to search collision status of + * @param traverse_unknown Whether or not to traverse in unknown space + * @return boolean if in collision or not. + */ + 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; + } + /** * @brief Get cost at footprint pose in costmap * @return the cost at the pose in costmap @@ -122,9 +195,13 @@ class GridCollisionChecker } protected: + std::vector oriented_footprints_; nav2_costmap_2d::Footprint unoriented_footprint_; double footprint_cost_; bool footprint_is_radius_; + unsigned int num_quantizations_; + double bin_size_; + double possible_inscribed_cost_{-1}; }; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/include/nav2_smac_planner/constants.hpp b/nav2_smac_planner/include/nav2_smac_planner/constants.hpp index 39e7bbd1f8..8bd0db5575 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/constants.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/constants.hpp @@ -26,6 +26,7 @@ enum class MotionModel MOORE = 2, DUBIN = 3, REEDS_SHEPP = 4, + STATE_LATTICE = 5, }; inline std::string toString(const MotionModel & n) @@ -39,6 +40,8 @@ inline std::string toString(const MotionModel & n) return "Dubin"; case MotionModel::REEDS_SHEPP: return "Reeds-Shepp"; + case MotionModel::STATE_LATTICE: + return "State Lattice"; default: return "Unknown"; } @@ -54,16 +57,17 @@ inline MotionModel fromString(const std::string & n) return MotionModel::DUBIN; } else if (n == "REEDS_SHEPP") { return MotionModel::REEDS_SHEPP; + } else if (n == "STATE_LATTICE") { + return MotionModel::STATE_LATTICE; } else { return MotionModel::UNKNOWN; } } -const float UNKNOWN = 255; -const float OCCUPIED = 254; -const float INSCRIBED = 253; -const float MAX_NON_OBSTACLE = 252; -const float POSSIBLY_INSCRIBED = 128; +const float UNKNOWN = 255.0; +const float OCCUPIED = 254.0; +const float INSCRIBED = 253.0; +const float MAX_NON_OBSTACLE = 252.0; const float FREE = 0; } // namespace nav2_smac_planner 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 688e6ea5b9..f5a43d0fef 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_2d.hpp @@ -24,8 +24,10 @@ #include #include +#include "nav2_smac_planner/types.hpp" #include "nav2_smac_planner/constants.hpp" #include "nav2_smac_planner/collision_checker.hpp" +#include "nav2_smac_planner/node_hybrid.hpp" namespace nav2_smac_planner { @@ -58,10 +60,9 @@ class Node2D /** * @brief A constructor for nav2_smac_planner::Node2D - * @param cost_in The costmap cost at this node * @param index The index of this node for self-reference */ - explicit Node2D(unsigned char & cost_in, const unsigned int index); + explicit Node2D(const unsigned int index); /** * @brief A destructor for nav2_smac_planner::Node2D @@ -80,9 +81,8 @@ class Node2D /** * @brief Reset method for new search - * @param cost_in The costmap cost at this node */ - void reset(const unsigned char & cost); + void reset(); /** * @brief Gets the accumulated cost at this node * @return accumulated cost @@ -96,7 +96,7 @@ class Node2D * @brief Sets the accumulated cost at this node * @param reference to accumulated cost */ - inline void setAccumulatedCost(const float cost_in) + inline void setAccumulatedCost(const float & cost_in) { _accumulated_cost = cost_in; } @@ -110,6 +110,15 @@ class Node2D return _cell_cost; } + /** + * @brief Gets the costmap cost at this node + * @return costmap cost + */ + inline void setCost(const float & cost) + { + _cell_cost = cost; + } + /** * @brief Gets if cell has been visited in search * @param If cell was visited @@ -160,7 +169,7 @@ class Node2D * @param collision_checker Pointer to collision checker object * @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); /** * @brief get traversal cost from this node to child node @@ -199,40 +208,60 @@ class Node2D return Coordinates(index % width, index / width); } + /** + * @brief Get index + * @param Index Index of point + * @return coordinates of point + */ + static inline Coordinates getCoords(const unsigned int & index) + { + const unsigned int & size_x = _neighbors_grid_offsets[3]; + return Coordinates(index % size_x, index / size_x); + } + /** * @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 Coordinates & goal_coordinates, + const nav2_costmap_2d::Costmap2D * costmap); /** * @brief Initialize the neighborhood to be used in A* * We support 4-connect (VON_NEUMANN) and 8-connect (MOORE) - * @param x_size_uint The total x size to find neighbors * @param neighborhood The desired neighborhood type + * @param x_size_uint The total x size to find neighbors + * @param y_size The total y size to find neighbors + * @param num_angle_quantization Number of quantizations, must be 0 + * @param search_info Search parameters, unused by 2D node */ - static void initNeighborhood( - const unsigned int & x_size_uint, - const MotionModel & neighborhood); + static void initMotionModel( + const MotionModel & motion_model, + unsigned int & size_x, + unsigned int & size_y, + unsigned int & num_angle_quantization, + SearchInfo & search_info); + /** * @brief Retrieve all valid neighbors of a node. - * @param node Pointer to the node we are currently exploring in A* - * @param graph Reference to graph to discover new nodes + * @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 */ - static void getNeighbors( - NodePtr & node, + void getNeighbors( std::function & validity_checker, - GridCollisionChecker collision_checker, + GridCollisionChecker * collision_checker, const bool & traverse_unknown, NodeVector & neighbors); Node2D * parent; - static double neutral_cost; + static float cost_travel_multiplier; static std::vector _neighbors_grid_offsets; private: 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 290ca13162..0b69771ef4 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_basic.hpp @@ -28,7 +28,7 @@ #include "ompl/base/StateSpace.h" #include "nav2_smac_planner/constants.hpp" -#include "nav2_smac_planner/node_se2.hpp" +#include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/node_2d.hpp" #include "nav2_smac_planner/types.hpp" #include "nav2_smac_planner/collision_checker.hpp" @@ -55,13 +55,13 @@ class NodeBasic { } - typename NodeT::Coordinates pose; // Used by NodeSE2 + typename NodeT::Coordinates pose; // Used by NodeHybrid NodeT * graph_node_ptr; unsigned int index; }; template class NodeBasic; -template class NodeBasic; +template class NodeBasic; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/include/nav2_smac_planner/node_se2.hpp b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp similarity index 66% rename from nav2_smac_planner/include/nav2_smac_planner/node_se2.hpp rename to nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp index 6a10f75086..e2b85f18a2 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/node_se2.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/node_hybrid.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#ifndef NAV2_SMAC_PLANNER__NODE_SE2_HPP_ -#define NAV2_SMAC_PLANNER__NODE_SE2_HPP_ +#ifndef NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_ +#define NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_ #include #include @@ -30,10 +30,14 @@ #include "nav2_smac_planner/constants.hpp" #include "nav2_smac_planner/types.hpp" #include "nav2_smac_planner/collision_checker.hpp" +#include "nav2_smac_planner/costmap_downsampler.hpp" namespace nav2_smac_planner { +typedef std::vector LookupTable; +typedef std::pair TrigValues; + // Need seperate pose struct for motion table operations /** @@ -65,18 +69,18 @@ struct MotionPose typedef std::vector MotionPoses; // Must forward declare -class NodeSE2; +class NodeHybrid; /** - * @struct nav2_smac_planner::MotionTable + * @struct nav2_smac_planner::HybridMotionTable * @brief A table of motion primitives and related functions */ -struct MotionTable +struct HybridMotionTable { /** - * @brief A constructor for nav2_smac_planner::MotionTable + * @brief A constructor for nav2_smac_planner::HybridMotionTable */ - MotionTable() {} + HybridMotionTable() {} /** * @brief Initializing using Dubin model @@ -106,22 +110,16 @@ struct MotionTable /** * @brief Get projections of motion models - * @param node Ptr to SE2 node + * @param node Ptr to NodeHybrid * @return A set of motion poses */ - MotionPoses getProjections(const NodeSE2 * node); - - /** - * @brief Get a projection of motion model - * @param node Ptr to SE2 node - * @return A motion pose - */ - MotionPose getProjection(const NodeSE2 * node, const unsigned int & motion_index); + MotionPoses getProjections(const NodeHybrid * node); 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; @@ -130,31 +128,33 @@ struct MotionTable ompl::base::StateSpacePtr state_space; std::vector> delta_xs; std::vector> delta_ys; + std::vector trig_values; }; /** - * @class nav2_smac_planner::NodeSE2 - * @brief NodeSE2 implementation for graph + * @class nav2_smac_planner::NodeHybrid + * @brief NodeHybrid implementation for graph, Hybrid-A* */ -class NodeSE2 +class NodeHybrid { public: - typedef NodeSE2 * NodePtr; - typedef std::unique_ptr> Graph; + typedef NodeHybrid * NodePtr; + typedef std::unique_ptr> Graph; typedef std::vector NodeVector; + /** - * @class nav2_smac_planner::NodeSE2::Coordinates - * @brief NodeSE2 implementation of coordinate structure + * @class nav2_smac_planner::NodeHybrid::Coordinates + * @brief NodeHybrid implementation of coordinate structure */ struct Coordinates { /** - * @brief A constructor for nav2_smac_planner::NodeSE2::Coordinates + * @brief A constructor for nav2_smac_planner::NodeHybrid::Coordinates */ Coordinates() {} /** - * @brief A constructor for nav2_smac_planner::NodeSE2::Coordinates + * @brief A constructor for nav2_smac_planner::NodeHybrid::Coordinates * @param x_in X coordinate * @param y_in Y coordinate * @param theta_in Theta coordinate @@ -163,28 +163,38 @@ class NodeSE2 : x(x_in), y(y_in), theta(theta_in) {} + inline bool operator==(const Coordinates & rhs) + { + return this->x == rhs.x && this->y == rhs.y && this->theta == rhs.theta; + } + + inline bool operator!=(const Coordinates & rhs) + { + return !(*this == rhs); + } + float x, y, theta; }; typedef std::vector CoordinateVector; /** - * @brief A constructor for nav2_smac_planner::NodeSE2 + * @brief A constructor for nav2_smac_planner::NodeHybrid * @param index The index of this node for self-reference */ - explicit NodeSE2(const unsigned int index); + explicit NodeHybrid(const unsigned int index); /** - * @brief A destructor for nav2_smac_planner::NodeSE2 + * @brief A destructor for nav2_smac_planner::NodeHybrid */ - ~NodeSE2(); + ~NodeHybrid(); /** * @brief operator== for comparisons - * @param NodeSE2 right hand side node reference + * @param NodeHybrid right hand side node reference * @return If cell indicies are equal */ - bool operator==(const NodeSE2 & rhs) + bool operator==(const NodeHybrid & rhs) { return this->_index == rhs._index; } @@ -216,7 +226,7 @@ class NodeSE2 * @brief Sets the accumulated cost at this node * @param reference to accumulated cost */ - inline void setAccumulatedCost(const float cost_in) + inline void setAccumulatedCost(const float & cost_in) { _accumulated_cost = cost_in; } @@ -263,24 +273,6 @@ class NodeSE2 inline void visited() { _was_visited = true; - _is_queued = false; - } - - /** - * @brief Gets if cell is currently queued in search - * @param If cell was queued - */ - inline bool & isQueued() - { - return _is_queued; - } - - /** - * @brief Sets if cell is currently queued in search - */ - inline void queued() - { - _is_queued = true; } /** @@ -297,7 +289,7 @@ class NodeSE2 * @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); + bool isNodeValid(const bool & traverse_unknown, GridCollisionChecker * collision_checker); /** * @brief Get traversal cost of parent node to child node @@ -317,7 +309,7 @@ class NodeSE2 */ static inline unsigned int getIndex( const unsigned int & x, const unsigned int & y, const unsigned int & angle, - const unsigned int & width, const unsigned int angle_quantization) + const unsigned int & width, const unsigned int & angle_quantization) { return angle + x * angle_quantization + y * width * angle_quantization; } @@ -346,7 +338,7 @@ class NodeSE2 */ static inline Coordinates getCoords( const unsigned int & index, - const unsigned int & width, const unsigned int angle_quantization) + const unsigned int & width, const unsigned int & angle_quantization) { return Coordinates( (index / angle_quantization) % width, // x @@ -358,11 +350,13 @@ class NodeSE2 * @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 Coordinates & goal_coordinates, + const nav2_costmap_2d::Costmap2D * costmap); /** * @brief Initialize motion models @@ -380,46 +374,87 @@ class NodeSE2 SearchInfo & search_info); /** - * @brief Compute the wavefront heuristic - * @param costmap Costmap to use to compute heuristic - * @param start_x Coordinate of Start X - * @param start_y Coordinate of Start Y - * @param goal_x Coordinate of Goal X - * @param goal_y Coordinate of Goal Y + * @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); + + /** + * @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 void computeWavefrontHeuristic( - nav2_costmap_2d::Costmap2D * & costmap, - const unsigned int & start_x, const unsigned int & start_y, + static float getObstacleHeuristic( + const Coordinates & node_coords, + const Coordinates & 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 reset the obstacle heuristic state + * @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); /** * @brief Retrieve all valid neighbors of a node. - * @param node Pointer to the node we are currently exploring in A* * @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 */ - static void getNeighbors( - const NodePtr & node, - std::function & validity_checker, - GridCollisionChecker collision_checker, + void getNeighbors( + std::function & validity_checker, + GridCollisionChecker * collision_checker, const bool & traverse_unknown, NodeVector & neighbors); - NodeSE2 * parent; + NodeHybrid * parent; Coordinates pose; - static double neutral_cost; - static MotionTable motion_table; + + // Constants required across all nodes but don't want to allocate more than once + static double travel_distance_cost; + static HybridMotionTable motion_table; + // Wavefront lookup and queue for continuing to expand as needed + static LookupTable obstacle_heuristic_lookup_table; + static std::queue obstacle_heuristic_queue; + static nav2_costmap_2d::Costmap2D * sampled_costmap; + static CostmapDownsampler downsampler; + // Dubin / Reeds-Shepp lookup and size for dereferencing + static LookupTable dist_heuristic_lookup_table; + static float size_lookup; private: float _cell_cost; float _accumulated_cost; unsigned int _index; bool _was_visited; - bool _is_queued; unsigned int _motion_primitive_index; - static std::vector _wavefront_heuristic; }; } // namespace nav2_smac_planner -#endif // NAV2_SMAC_PLANNER__NODE_SE2_HPP_ +#endif // NAV2_SMAC_PLANNER__NODE_HYBRID_HPP_ 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 31f1049609..ff235b02cf 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 @@ -21,6 +21,7 @@ #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" @@ -85,24 +86,9 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal) override; - /** - * @brief Create an Eigen Vector2D of world poses from continuous map coords - * @param mx float of map X coordinate - * @param my float of map Y coordinate - * @param costmap Costmap pointer - * @return Eigen::Vector2d eigen vector of the generated path - */ - Eigen::Vector2d getWorldCoords( - const float & mx, const float & my, const nav2_costmap_2d::Costmap2D * costmap); - - /** - * @brief Remove hooking at end of paths - * @param path Path to remove hooking from - */ - void removeHook(std::vector & path); - protected: std::unique_ptr> _a_star; + GridCollisionChecker _collision_checker; std::unique_ptr _smoother; nav2_costmap_2d::Costmap2D * _costmap; std::unique_ptr _costmap_downsampler; @@ -113,8 +99,6 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner int _downsampling_factor; bool _downsample_costmap; rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; - SmootherParams _smoother_params; - OptimizerParams _optimizer_params; double _max_planning_time; }; diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp similarity index 69% rename from nav2_smac_planner/include/nav2_smac_planner/smac_planner.hpp rename to nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp index 0f49dc7a4c..109913b7fd 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#ifndef NAV2_SMAC_PLANNER__SMAC_PLANNER_HPP_ -#define NAV2_SMAC_PLANNER__SMAC_PLANNER_HPP_ +#ifndef NAV2_SMAC_PLANNER__SMAC_PLANNER_HYBRID_HPP_ +#define NAV2_SMAC_PLANNER__SMAC_PLANNER_HYBRID_HPP_ #include #include @@ -21,6 +21,7 @@ #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" @@ -35,18 +36,18 @@ namespace nav2_smac_planner { -class SmacPlanner : public nav2_core::GlobalPlanner +class SmacPlannerHybrid : public nav2_core::GlobalPlanner { public: /** * @brief constructor */ - SmacPlanner(); + SmacPlannerHybrid(); /** * @brief destructor */ - ~SmacPlanner(); + ~SmacPlannerHybrid(); /** * @brief Configuring plugin @@ -85,34 +86,12 @@ class SmacPlanner : public nav2_core::GlobalPlanner const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal) override; - /** - * @brief Create an Eigen Vector2D of world poses from continuous map coords - * @param mx float of map X coordinate - * @param my float of map Y coordinate - * @param costmap Costmap pointer - * @return Eigen::Vector2d eigen vector of the generated path - */ - Eigen::Vector2d getWorldCoords( - const float & mx, const float & my, const nav2_costmap_2d::Costmap2D * costmap); - - /** - * @brief Create quaternion from A* coord bins - * @param theta continuous bin coordinates angle - * @return quaternion orientation in map frame - */ - geometry_msgs::msg::Quaternion getWorldOrientation(const float & theta); - - /** - * @brief Remove hooking at end of paths - * @param path Path to remove hooking from - */ - void removeHook(std::vector & path); - protected: - std::unique_ptr> _a_star; + std::unique_ptr> _a_star; + GridCollisionChecker _collision_checker; std::unique_ptr _smoother; rclcpp::Clock::SharedPtr _clock; - rclcpp::Logger _logger{rclcpp::get_logger("SmacPlanner")}; + rclcpp::Logger _logger{rclcpp::get_logger("SmacPlannerHybrid")}; nav2_costmap_2d::Costmap2D * _costmap; std::unique_ptr _costmap_downsampler; std::string _global_frame, _name; @@ -122,11 +101,9 @@ class SmacPlanner : public nav2_core::GlobalPlanner double _angle_bin_size; bool _downsample_costmap; rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; - SmootherParams _smoother_params; - OptimizerParams _optimizer_params; double _max_planning_time; }; } // namespace nav2_smac_planner -#endif // NAV2_SMAC_PLANNER__SMAC_PLANNER_HPP_ +#endif // NAV2_SMAC_PLANNER__SMAC_PLANNER_HYBRID_HPP_ diff --git a/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp b/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp index b3b0fe8237..a9c45d4cda 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smoother.hpp @@ -1,4 +1,4 @@ -// Copyright (c) 2020, Samsung Research America +// 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. @@ -23,17 +23,15 @@ #include #include "nav2_smac_planner/types.hpp" -#include "nav2_smac_planner/smoother_cost_function.hpp" - -#include "ceres/ceres.h" -#include "Eigen/Core" +#include "nav2_util/geometry_utils.hpp" +#include "nav_msgs/msg/path.hpp" namespace nav2_smac_planner { /** * @class nav2_smac_planner::Smoother - * @brief A Conjugate Gradient 2D path smoother implementation + * @brief A path smoother implementation */ class Smoother { @@ -41,7 +39,13 @@ class Smoother /** * @brief A constructor for nav2_smac_planner::Smoother */ - Smoother() {} + explicit Smoother(const SmootherParams & params) + { + tolerance_ = params.tolerance_; + max_its_ = params.max_its_; + data_w_ = params.w_data_; + smooth_w_ = params.w_smooth_; + } /** * @brief A destructor for nav2_smac_planner::Smoother @@ -50,90 +54,199 @@ class Smoother /** * @brief Initialization of the smoother - * @param params OptimizerParam struct + * @param min_turning_radius Minimum turning radius (m) */ - void initialize(const OptimizerParams params) + void initialize(const double & min_turning_radius) { - _debug = params.debug; - - // General Params - - // 2 most valid options: STEEPEST_DESCENT, NONLINEAR_CONJUGATE_GRADIENT - _options.line_search_direction_type = ceres::NONLINEAR_CONJUGATE_GRADIENT; - _options.line_search_type = ceres::WOLFE; - _options.nonlinear_conjugate_gradient_type = ceres::POLAK_RIBIERE; - _options.line_search_interpolation_type = ceres::CUBIC; - - _options.max_num_iterations = params.max_iterations; - _options.max_solver_time_in_seconds = params.max_time; - - _options.function_tolerance = params.fn_tol; - _options.gradient_tolerance = params.gradient_tol; - _options.parameter_tolerance = params.param_tol; - - _options.min_line_search_step_size = params.advanced.min_line_search_step_size; - _options.max_num_line_search_step_size_iterations = - params.advanced.max_num_line_search_step_size_iterations; - _options.line_search_sufficient_function_decrease = - params.advanced.line_search_sufficient_function_decrease; - _options.max_line_search_step_contraction = params.advanced.max_line_search_step_contraction; - _options.min_line_search_step_contraction = params.advanced.min_line_search_step_contraction; - _options.max_num_line_search_direction_restarts = - params.advanced.max_num_line_search_direction_restarts; - _options.line_search_sufficient_curvature_decrease = - params.advanced.line_search_sufficient_curvature_decrease; - _options.max_line_search_step_expansion = params.advanced.max_line_search_step_expansion; - - if (_debug) { - _options.minimizer_progress_to_stdout = true; - } else { - _options.logging_type = ceres::SILENT; - } + min_turning_rad_ = min_turning_radius; } /** * @brief Smoother method * @param path Reference to path * @param costmap Pointer to minimal costmap - * @param smoother parameters weights + * @param max_time Maximum time to compute, stop early if over limit * @return If smoothing was successful */ bool smooth( - std::vector & path, - nav2_costmap_2d::Costmap2D * costmap, - const SmootherParams & params) + nav_msgs::msg::Path & path, + const nav2_costmap_2d::Costmap2D * costmap, + const double & max_time, + const bool do_refinement = true) { - _options.max_solver_time_in_seconds = params.max_time; + 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; + } - double parameters[path.size() * 2]; // NOLINT - for (uint i = 0; i != path.size(); i++) { - parameters[2 * i] = path[i][0]; - parameters[2 * i + 1] = path[i][1]; + // 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); } - ceres::GradientProblemSolver::Summary summary; - ceres::GradientProblem problem(new UnconstrainedSmootherCostFunction(&path, costmap, params)); - ceres::Solve(_options, problem, parameters, &summary); + 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; + } + } - if (_debug) { - std::cout << summary.FullReport() << '\n'; + updateApproximatePathOrientations(new_path); + path = new_path; + return 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; } + } - if (!summary.IsSolutionUsable() || summary.initial_cost - summary.final_cost <= 0.0) { - return false; + 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; } + } - for (uint i = 0; i != path.size(); i++) { - path[i][0] = parameters[2 * i]; - path[i][1] = parameters[2 * i + 1]; + 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); + + // 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 true; + return acos(arg) / norm_dx_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); + } } -private: - bool _debug; - ceres::GradientProblemSolver::Options _options; + double min_turning_rad_, tolerance_, data_w_, smooth_w_; + int max_its_; }; } // 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 eeeb921873..dffc88062b 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/types.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/types.hpp @@ -17,6 +17,11 @@ #include #include +#include +#include + +#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_util/node_utils.hpp" namespace nav2_smac_planner { @@ -35,6 +40,51 @@ struct SearchInfo float reverse_penalty; float cost_penalty; float analytic_expansion_ratio; + std::string lattice_filepath; + bool cache_obstacle_heuristic; +}; + +/** + * @struct nav2_smac_planner::SmootherParams + * @brief Parameters for the smoother + */ +struct SmootherParams +{ + /** + * @brief A constructor for nav2_smac_planner::SmootherParams + */ + SmootherParams() + { + } + + /** + * @brief Get params from ROS parameter + * @param node Ptr to node + * @param name Name of plugin + */ + void get(std::shared_ptr node, const std::string & name) + { + std::string local_name = name + std::string(".smoother."); + + // Smoother params + nav2_util::declare_parameter_if_not_declared( + node, local_name + "tolerance", rclcpp::ParameterValue(1e-10)); + node->get_parameter(local_name + "tolerance", tolerance_); + nav2_util::declare_parameter_if_not_declared( + node, local_name + "max_iterations", rclcpp::ParameterValue(1000)); + node->get_parameter(local_name + "max_iterations", max_its_); + nav2_util::declare_parameter_if_not_declared( + node, local_name + "w_data", rclcpp::ParameterValue(0.2)); + node->get_parameter(local_name + "w_data", w_data_); + nav2_util::declare_parameter_if_not_declared( + node, local_name + "w_smooth", rclcpp::ParameterValue(0.3)); + node->get_parameter(local_name + "w_smooth", w_smooth_); + } + + double tolerance_; + int max_its_; + double w_data_; + double w_smooth_; }; } // 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 new file mode 100644 index 0000000000..0c58fbfc01 --- /dev/null +++ b/nav2_smac_planner/include/nav2_smac_planner/utils.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__UTILS_HPP_ +#define NAV2_SMAC_PLANNER__UTILS_HPP_ + +#include +#include + +#include "Eigen/Core" +#include "geometry_msgs/msg/quaternion.hpp" +#include "geometry_msgs/msg/pose.hpp" +#include "tf2/utils.h" +#include "nav2_costmap_2d/costmap_2d_ros.hpp" +#include "nav2_costmap_2d/inflation_layer.hpp" + +namespace nav2_smac_planner +{ + +/** +* @brief Create an Eigen Vector2D of world poses from continuous map coords +* @param mx float of map X coordinate +* @param my float of map Y coordinate +* @param costmap Costmap pointer +* @return Eigen::Vector2d eigen vector of the generated path +*/ +inline geometry_msgs::msg::Pose getWorldCoords( + const float & mx, const float & my, const nav2_costmap_2d::Costmap2D * costmap) +{ + geometry_msgs::msg::Pose msg; + msg.position.x = + static_cast(costmap->getOriginX()) + (mx + 0.5) * costmap->getResolution(); + msg.position.y = + static_cast(costmap->getOriginY()) + (my + 0.5) * costmap->getResolution(); + 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 Find the min cost of the inflation decay function for which the robot MAY be +* in collision in any orientation +* @param costmap Costmap2DROS to get minimum inscribed cost (e.g. 128 in inflation layer documentation) +* @return double circumscribed cost, any higher than this and need to do full footprint collision checking +* since some element of the robot could be in collision +*/ +inline double findCircumscribedCost(std::shared_ptr costmap) +{ + double result = -1.0; + bool inflation_layer_found = false; + std::vector>::iterator layer; + + // check if the costmap has an inflation layer + for (layer = costmap->getLayeredCostmap()->getPlugins()->begin(); + layer != costmap->getLayeredCostmap()->getPlugins()->end(); + ++layer) + { + std::shared_ptr inflation_layer = + std::dynamic_pointer_cast(*layer); + if (!inflation_layer) { + continue; + } + + inflation_layer_found = true; + double circum_radius = costmap->getLayeredCostmap()->getCircumscribedRadius(); + double resolution = costmap->getCostmap()->getResolution(); + result = static_cast(inflation_layer->computeCost(circum_radius / resolution)); + } + + if (!inflation_layer_found) { + RCLCPP_WARN( + rclcpp::get_logger("computeCircumscribedCost"), + "No inflation layer found in costmap configuration. " + "If this is an SE2-collision checking plugin, it cannot use costmap potential " + "field to speed up collision checking by only checking the full footprint " + "when robot is within possibly-inscribed radius of an obstacle. This may " + "significantly slow down planning times!"); + } + + return result; +} + +} // namespace nav2_smac_planner + +#endif // NAV2_SMAC_PLANNER__UTILS_HPP_ diff --git a/nav2_smac_planner/media/A.png b/nav2_smac_planner/media/A.png new file mode 100644 index 0000000000000000000000000000000000000000..8e04208118d16d5583679b4a53e972351fb5efc0 GIT binary patch literal 235271 zcmXt9WmubAvxP#j;uN>y#R={dhhn9;OR(Y)+$kE|T?)mW;_e9)EAH;l5-1X!%Q@$} z@1Mw%AKA0_tXXSjZSW^mc`OVv3u6lVv21zMu zqP;wRXcmz#pGn8OG`(PjguP;sYe_E;T?jajHISl z&hIXzcnW9}U;AHmt?`oI^-rUoTa&Kj_E9#{bShZ+iGj)T_`G6tedwQ65`>AIVSz$G z1NsgY6HnZFb68}IpO%)!xD{LQaYfbG@bIusRo6A$$$huHl$2CIQ&ffi6WS=3p}(MN#cfb9d_0{`YZO-*SkkeI-IKO#D8D^cLGk@5zPPc{iApokj@}uugzed zP6wD+0P+n!S>tVeWPU#}EqCHmIXRwWDK_R}ah&m}K1zIDpto@@N&cte%GYAuTff5} zb5C!%OsA@PGPF<5VbV@QV*$KM{UpRweI-dwdZ`EdeLFVi;_-f!@LPSRP#lGrYvZtK z4b8f&y;H=%Ve=i?=+}Fd`~|GzL#M4a0cc{mukQTXrfEK#^CRor)$%u)xcO=Vj_0F& zJEz;|@%|+MD+p#%szzBXSNmf1s#H8&g<&3lpMkz@K2#gIaZ+f!=(9f6LvxKkqZmpb z!lerb?t0l%XKjY>ewU_V0F?NXQTY|B;eYQr`Eyz1aV$8$J|f_TR%_c~)Li zO4GLHqhO+M2%2|6v11ule1HEc>_s%VM9@zuQ`hHFa~$zJ9c~Snh98q%$94pDQ(fhz z4SPyS(QcrlqvyX@WmvZ&tC^&^LC(!#~hto0ZgmVzWW$n`!ynT zO+r}4V9svuxMlHxB3JADt}o-`hNa0}hcSOKLIgcKJ=9QpG2qbs(r4?3^DDg?%>v-= zRM}BCvpKse!^i>sFnlFkJ3ZptD~dcP|FFG@-ksWkd(((6dFOF4U_k5|>U1~T%4QJu zYXr=c4I-g^v0i#8J|5~<0wV(RtER$=IJ4yei z9^i+>LATNC`YLbOvmYq?-^%DGN`2rV?%c43%pyB?4~0(u?O{u~KBN85lmkbO^ALaj z-wp?D`1_}xG@F_{QhUA%%1uA27k+sHyN!J>)SzCWcFuN={BDPWmhv~lql*Xol>31@?$XaypbtdB^EAZx(TRQ ze{QrRz3dMxb=L_W5|Xt9ZBuFj3l^S&V--^J8|w``kj7u0OeY z$=D6K1`9fWBal}mII8XM!@(2Lda3Th@`J(a8fZ|oxz*cFYJo2%fdY>Sur1+bS$!z( zg|AIYfl#5wLZ9@z5e=8Y-XEaGAv3)4IET?IRrln8NMtz8HS<;r^!aHaaAy?OZPdB` z&s(J4LI;G_I#jYu?p^-&ju3Cqx#DiJiO=J&9y(@EbaW`qe~E-`rv<~^!FKV7=23iF62?XAsn6?=UteV`Ar~BWowM372M6P7p ziB=kamydfTa%rR9VO>mJko#R$K#I_uM(|}DE)*OO{z(^#iS#W|&DI47z|*!3Ca&^X z{xf#%AMczba8?(;%U~N10WZII9PDF;FBz}zDlJajdKD+|kUF_FTZzK+^zR-&)zQ9B zmLJdQvQF}NODyq#h-Peh%!t>IYTbu3=OqZ4Scav3vWuz|H0_Ej9G&sx*#3d5R$$|S zD>w8+H%XcPYt9+7Y55)biYhRw_ZYT%4TS}sp>g*_jF#e_cvj)u38+*^puE6f9TXdO z76y{+0f84WW)}6IuJ z4+0{Xf4U0D9=*Mtt=|@B#<>UO?`1vQI5JKKe;+JCRym4`lre0+xbpw7x+p!g;VG~H zoMA0=7;Z7ven0LR9a4&hGxEbCm+C_Q*GRKMx6pp>Nrzh8l`#2ijU@zbTOpC=tdwoZ zalU?K{iVE^%kHY2UI=eD^uCwm%O3m_O&)EbM8Go=!dTKW$vGw62o3Ml{0SRFThD92 z6N#64*B~W_b1xCh8B9jLy45e1inBPL;PmLByemRuhJ}Bts-SRFuw77k#VDTn+3wvCJZ|yV41f;cs@V`jhZrEAYGCU9}HLH)aQLf8eZ0 zUj#-VHQx}bsT*ARI@tx*(roZXz4~WI*d+f0F^V+&GoiWclbc-wYXO0oXem6UBo&wB zQ&IR4CAKQlb#inQokk+fM6yj~JwfRz-Wi!eOI064rAAkkvFhZfVya28h$j>`$w_62 z$8GVOhcBnPNO3lXXD|x+?E7D4At49dYJVxx{Gw7F$)stA(W#MufF3}<2oZ57QC3kn z#^296N7Oyfh=H(Yp+hA$B5zy0{((V?TkKS)_PmSSZ+0Owvso|Ir2k0aCH^#9$^C6c z6HqOf83hkPNuqQ5b%RSWf6>$+?|o*M3K5K`5K5L4ViC`2d{`+>$A~ z&cUfqo9ODAEl#HjT%*aXecf))P)7C zZEsNh5I(5Gx$_s`D%!->jEx|l1dVfIKUed5$Phk=xvh~O78s4qE%8IDuVQ@(tKaGW z|I7M{7CpI_pqh92&t=N)GvX$l_?B0k8_-4*&<53^-9uARR9apNfCr@&SgufR5))@Lgn|L}&MI&UK{7wnT z7VgC?nMXTYknLt42wr9MW61!CEbJN_yit4!*OnXo-`s?RGsP{pzhbF2DoK%wN30Uy z4DDt`Hc;c@w>~1&6LA$wLo|VwQMo(0ReAp7%HwKxIyRSxXwxLi?R$l~BlGuwO&Yw( zPG({#3&r=<@>R&1-@$e#xo97%y?y-p`orz+j>?T-WU53|;vR{cGAFK1Fqo@bH*f*t zYw)Eh$!{SzK)?rwlQH#0dUjlLe(nYu zC!sEbO2B+-p!QK{L^R0~LrLD`YFvRZuQKFAAg#(b_+l_REfin&xRZF7|4y6tWsCNnl`Fr|oB=uW7_tkSiz-gwPX=H~ z^sj^zC;P{X76Bc&&loiU5WU5Gw0~N@_x2Q!JAP(cnhN;500n06ZvwMxv zE4WN2L5adSg+i7)x!D(qw5t`M!19FF6-11H&;NJA7B(^09PuD$6axw0^`bDWbTyne ztVl$)o2PC&gl1{SlCZS1Y+v-Vn=E?ahv<36CPO4DrI#%cP5So~jcj%&Ro5$PvrUoh zWMrl(GvR$-HY)665H}4$;){Hx?6T2Ed&^ z(yVKMuU(Q3bj>*5fq(3BHM!}K1P0U?L|R5Gb;^Uu3}$ik=N>EWmgb$=UlCvCj>@l_?x;lG zF4bPK?;3Q>gQPmt>(`5UK6OG-_?j1Y0vQb%fFz@vo%D8Ym>RoYANy2`)9}R^A)1@T zW~`GH3&wil>!YCJJKpk=Y~Hm3Fmub{r*Vfr;!3>V(TSQwT2k7$iy9@rLu zOS}lQy9(hv!>)D8%iZ~;15~lHuGoO(EUU|%bf~tGPcUyVj<%f>nHDx-*@_O`FVRb) zqaQ$o(Ee)1oPFkfZ#{Yf5D3vGM^9rnG{}p0;C~;F5j{mnK;|oewBtC1413fN{aRDe zQl@SWl5$6u?rk|tFpKuNx;f9(`#$Jvxa>ztYMVmB`i^<|?9w+HLZlKpKw{fmKVWvo z*41k?>kNQ%{6jke&pPIQ!s{+~ceJ~q320vZ^$I`#LB#J7wL4TDxf54wtg@Z%8i^Et z3Oxp5X6+11pxY6Mn8&#B!H_U^Y@6S9n;FYH8j;prV$DCj`wzY*(BHf7SuSP3Lnr2I zYkBbxm|qS1ClA~7FBj^%?}cMHAB`Da401l?J|g(of1*xR`|9w5O7afR*ZUYR@cN!z z-EOL&4}uT9X|=bP4bf2Gf%|K9=@n_m2SXpKe7dr{kb0k2AJ7A8?)NCvG{nCPl;uW0lle`6=Nm~9BE9;_{w+%hK`wts&{ZQ=iz&z* znc^aVk%^Xn_$dSOK~8axPoA=43u*Sk{G;s9*PAlx-*#R#DLF*H(wWOfO+CW#1)(O8)z8E zDCAFjOj0rfptCBeZgx#5^b*)va*@>>H>4(DveVw~K1V6MD`;v5E)x~;STw*&Ek^AC zYo`Z0JfobNuZz_oFB8~e)?bfxyqgN)dxxh+ zFKUK9y_TAgkWhyYEyIGQ7zq=B9AZ>Z%fG)pB&y_HjgwIWPD?MIBV_PpB`X;w8Xi%OP^G@XkZkavuG0NEuCp)b&s$S6J+hOp z4wx?Ct(hm$W+J5f7UteS-K0dzow+Nc|^zp*hce;?32o$gtCq?=6j7;^C#UXB` znbJ>&=hD+$A%?NpisB^T=MI2l9V!L7-}^yx_6c=cX61EyaOM0UF+6SiZ6auHCCQ7j zUmr@pOgr7mymB5WD0{>Z(0;qj zC}{Vq@I&1Cal4CJB1#ymQE!qnqzvE#})P8YPs?R z71C$WDbamNS~LidBBw@fq@{yVC^8 z$JyZ=a;NZ<<7+nhFPJa6MRkN64j8Pr1Qn+#`HGx52!>r>RZD?C8jXZ#6!Q3xN)R}PQB6jaM&@6ofQ}eWYH;PmUCf=B1L13y z1bce_!!E_f8PY;YQj76lTBjk4LX&h7! z@pC;1%!T+GwpRzbhUdP9K2NA))7?-KC2PGJE1_tTP`I4tGipc7Da?t9%G$42a9<$pE`VD zQkSX{4vm^{=4Q;lf@QYE9-7C%`RR-0z(~!4rV%(^U*WBTBBDcx

!Shz8ko-qB(n zi@<}svA~{f&lfRwPW?dj+y^_Oe!zZ)z`FQbwkH&DgAeX-_s z?ttf)Ut_1AZq#~3i5QkiDPQn;IXTswBg4*-Jx>oyQmPnQyV@WxfI+QAK+07F|1+MS z`&V^geqO6Sy<+^qGvdwa)+94X8wt8I)lO;z$cre^6k z2#Sf8MD6-%d%JA-#Apep;{1cFK`4j*h)nWb{xv1Z9bV*{`-HdooU`C!8WqMzMlRAb zm|*Z2N>{hZ%{lDkDYoexkf7l8RqpdYKqO8_;?93+P8F@pGu!A{;pnIlelCz46*cJU zWaLVo^3oWiN;N%7kulJ49C7vC4C4XkE`{;)}$5>XkX72y2PgVy39 zEb29_&@bqpGLBho!V3n#3y&tT%bt2gj zIVc(RH4PEY+7qQ$H1qB{n5&e1VPZFNlu#)0T7`&g-B1v8Fe*uBn*zOKVhW`zz~-Hi zPkz0eV6DH9l|$rNrATDG2POA?C#H06hINsr-PDb*Uzx_~m7#(g%FeAT8g~t6TXs6c zGmve%!ya^sYmx=%_bvt&RC2tt&hq_ZQ0gnT4!5K9~e0(UAcH1 z&C-9p&P{eH49gemXpnnz4mhL)V=Lxe(t7qJqX9UK2t2@Dv-IMkaXWKum|__6?Ktv7 zOdIQl9Uypu6w!-RWB-`KpYRQ7G!RQMOtpJ%`Kl@U$^S$0UNN$;OxaD%ns`o*9Vb~5 z-8xX|XOftk%`2sWT$qnT_rl`hD*paNiK}0g8Q54BO2&tH5wiw7=toUs^s8DspY9kD z-MYzDGu$9hxTB=KwlWVuxaE+Pc$k?Xkz%eS|vt5-lg=3NF@JU{Pu*;Iz#5K;lZJEu*iwLDYrhg!OYE~{W=`HY9uMf zU(tz=FgetIwyO2G8C&1JZI*KZ7-??p){aus3SMAbWtmzG^)tuCPd`~FW2I8_79)d| zAzWZgeRQ_UkLWZG762x5$L<3@du5ppZ#Z^WC&B1XVo{PrQPza2jy_6rC+@(d?(tL5Fv z3n?Gd)ki(7GU>Y!FX6y=6lj^G%@E8P{5&D#rwF@!7cffi3ccR) zzQUk(K1wy1iK+t(^Lp@dw~Tp}W*qJ7?`55?BWQl^A7?|fCjGEe+~~5~=2F6a{^?Ho z>P?1%8acb2{V(DE+?Cb<^$vdtO2#UR@FNmsylP91wSj8x)h+W&PjS}y?G|Tr2?2=Q zJ%zjn2cIb3*(C9Q9aO8coo?W<0CRa<55c2kMQyXG2W+Bg4QPGB2&!J5doVgqdYBns z@c3$vPnKCEJ0|F0s?hQUjxIjdtnztMv6MO2Li~-oL+_=C@OHMw(V~K?BpNz!uiTIL z{ReJ>cs6R*@wfOkDhUIN4q}M=LQzAWE${JIb_Li2GST>a8CQ5`rVgmlRAK;mq)wyop0rOdH|-f~FGzRtqee3&Rioq#`n zT!F?rjHs(6%pr>M9l@mL7>RJx)9ZM(Inz{?wO7;wUE+OWfn@abel}O01bqiS;kx(f zjIef&`vJ_^EZ>9iRK&B7~Wi{ImE;-sOR) z5j37S-s0|~?DcYJnW&%!0GgNQgQ&KTYT#Lm8J|g7)7Lp!1PCBm_js(aB)0!E=(`EE zHk6qgZvh2WpuEy0m?&&iri;IicxB9C-ic>x>_t^Gs=wkTEg^7##f~l)Sz4{~RJI>D zezt{_YuG7Sh%EqpW8F8>o0k^OExW&$grekN(c_Y zB1a0`6;EYuQ)LXtm+&of>4*ZVJASO!K<2|0f8#Q);uGc+5Pd)bhfuTD!mE7#MDA$* zkZH($-&=qFZJL}3)cvYTkzpqfbh!vbWi+O*|AkREn*b*?1s1W<^wDCj16DGuHN)4* z@MH6pPB8V@eRRBoNiRq_O*#e>isgCVoOlmr{k_X84G!vKtL~uUNrx56hhyEyOqwQ% z-i?s))iX|631ac&-H+@Caiup~K$QFzb)FV(R`5ljqWJ;-bM$=SL zj?&gYY>x^p#Rxgn1kX>!59xjewBtA#F#|R%ob8XO@xc+u^R)tjZx-Zf$ODASP{@^{ z#t4T54}glC?`;1tJ0Qq)Jq9TmYB{ObumwXx4N7D-=1Jcwd}w;bA&!gxoFmyU_JW~x zeSO{oT<|_!S2;y{tDl#Nq4&owIf568a$gl*-(ZU@X+v#Zc6v zW+Ibj6?OOh?*_gx0FBdwfb8%YG5qC?M8oSbul zhlxG2{@)8w^T8KoXQ_0vUwj^F&(#fg=LH7^8vk43XlP!65mC!BM^iL^9w%5J1%&IH zzz$K4hd#edAfnl^1x-&@#|6@es={2NC;PZf+O*~?DCI&%eXkIj;{_T~{U7h~qf-WdTw{Hbuwmw3AL61^7wO$TlYD!`Z+ z3?cRL>m|5c6e07#^tLkcfxMyS;ireiV$JFn3ip&5`xNOgy&QDy4uj}61x(l1y2kMf z81lauPH#+&=7sMsZ9pGZcRM0 zwqbQxcY_1in_n$rd7YeHxJ3=bE9KF~_YJ09u*a^fh0;7(%sYLwgRr~qRQ0i%@Nzv) zNbFnL@=ODBkvRSgPVsPb0ZoaY-2&)QC(iDWrtz&$HW|6S_1_4;mswvgT%u}S4YSJQ z>{Fe`gSi#Pa~9ZXh!4*%>d&Jl;Xine`XBMqA2ghN9pJ-v+kE{-zGF9px-zg$aaRc6FLusT))`aNM=gwg51%czmVZT{rezB`V)RnxqcW9i zO7TaQQedXRWZkP;hhBlQVIR@&`x19ppN@=_@cHURB7Ro7C>sdZYXe8JXvD3m^p%u_ zSghDoey~>rk!Bdzx@A@@T!s~8?wu=FIUF)}x#z1$aKk`{whrdCq~>NRo0yO9wumaR z5~@@gR&7)5x?O@%#x#KKoyJzs2KjI?4`Ww3|I*N!$=+XDSrBmjL9Wv)`ruH$j;qsl z;AFo@>LishYGLR}Dfy@aqVs+zMIAgKwp#1%N=#{|kW?U-`onM~BmBw#V{NV>DGr(a zYO^^B9+Lx=1gl_gY;a62)f@EM_gx3_H#+ek8-x@WN^`~8%TEVXaYH2Cw<{*{TCf*6 za#nhLfT*5B7stljh72VkorpbKqqu(md*|#X!l|a%@dzCq@E^)70b_#hv5&Y_XenoE zZFb_;S4S;Ec&BwD1--=_14(^;JD;WKU*}qmL@pu&n%P=TD}PLU+M7ByY^7Q=0iI?m zrI9AB1v%yyI%`Po+5l8j{qeC>(TW>Yn9M0#6bUotASy{r1o9gNy2`wn3ehqP$`AL+ z$D{;0bL5=^8ZR{rGg`CQs;F^2l=x?ONPj<%fHI;x6QbfTj##j zfqOm@hm3_943I4Zc#A0x4L{!RU42X$X3H#4a#2P+P1p*`br{u&hicjdivnT_9V0cU zRtbUcZW(VyO?M#8P2reH`VHdHo{&&D+7iR<>%$}NqQtCDkBZW;E+@UpY`ei`!msb) zJ^V=&vrRj8^WAupOn;YybTHHIk@eyOR}~G(mA(9ah>9}eyL{=9kE=W$x4`c%4~+p} z^z2je`wvwQK&Smm-5k+ZevLv^hCt9BZA7(W_(AZ$Jr;4HD)2p3Me(TdU+&u}&Z*mK zUlBcPm6dwM1+qi*!k!1OLh6(BgiWhDQO&^t@xe%EdrC-oe$?mkBWcem?5>%CvBN~i zY_`j7AKOB>(3*LyRkePijD;h)`oxw3PrQ@U5u>wEWzb7+!7HNl*HVtbZfh@P)I02( zjCM$@3VcCt02f@L9go;L_KO`OdrAblo}^NJ8Aa}RY7|>dXGKcp_RY@I3d|i8d`!VO zV&2cG;#02eiR(Uf`K{5d_HsKFz9^{{x8pLfZ+l2MmCEl=D3s>RN}mmA0e%ZIF|PH5 zj=7V#E2rkzUgx~R^z4fAp^(U^9iU3Q7tNNs-*Y_NKyVxhaPw}ZRAR%NNwv& zB_;KCsk_cbWbwOYB`p#Wp3{uOUI7@V*}{3Yn^YILq##aers@3!A)S{JOd$1NavTCw zd;L3_v{`nGk3_N}{;2w+Dq}e-P7p#3yY>L613*Qw(klHmvor(Bo|-ur@RMA#iS0uI zznkHXa~1)aqD2yWRLY2GEs&3#`2Ncs&?YET*>iX;rBmm`LbZN&>Cd=l$)=rXe-dy9 zjkiI_E;U9*$2tMUudrP*7L&53LcoUo2)FnLb*qu5cCNTC-`eaqCrU75*smfjy8yQ- zEA#4khS{HMo-_vZ47m(xV*w5i$Zqo%^AL_-=CzvELbZQ0&xex6D&3+Q3&!zbN?4z3 zUW=(?8&#LzWM$Z%hivK&*3#uVzX>9bhTyy8I*;Z=U~BAM1)+2~MA)|6*bbh8T%rzA zWrs2V*REsSTk(l{4uUMdg=5=c5%*L{O1ZC1phXuqdc9LPjrOt4fcB3R%FUKeC%YvbwSl@SN|;n|R;5(80& z{9%%tPTgq0_mg@-cVDD6$S;D?Du7{4ZCxEZU=Xy_i4jnND8A+LKf4Qlsg)RxNv8By zaVk!ZpKG7MaSja@_<+<{kBBaxq z@oGtBPUN%|BjkZF3cTZ7Y{d!<{r(&SeI^;h6b=<+DcXs$nKAqVBoF=*ffd4B&5m^2 zLRR_(Wv|%#yI*4ZKY+>8Zoh14(Q%Vg078pYnJ1{V>JlSF2FX8^8Q1mkL&CsKmvi}T zmQ|E$0vDKJ3?9mkme+qebRuNbnMml4QoEwQgzaj>Ws(o5oT2ahC*BPv>PojBavEy~nMa6a`=Li$G&i1E%hoXG*)=Lnvve{9S;NTIx!3HM) zU#uyA>|QLOrggm$UtG0!fwp`jp8P*m)|^4NIl9b6pmIwU==6hBzmOKW)=(e?>g=$Ypu`;I=~8 z8*5sXm05n-e`LBARC@}t`D$OQqzE_Zu+$(Bc%n1U6s5bFb8KnXLPD)@&$EI$vc^n6 zp_x2i!S|ObuP_g9y#Cbup)1kH9%0M(lKxAkR>D_`pv2l~e8@n{h|x@bP5U(VXO)lf zKFt)rM08gE0NxUo!kFyxHYE3ke`M`XJZUXyzV@9zMkUit&&eLQ)Ic|t^iqcN88G-3 zV>{!;3zG7iSy7&LVqpmX=R_#O-ma z_pFG^dpNc%Ec*eoa$VEE>KH_om$NJ81yLf{^!csDvMUyiAR0x;PR`gGTQOT5Y#WSg zPSA({T`Rg0{6ZMFOn7xpqV6E(-t4(!8d=_IWcNBdON2mrNTD)t{c%t~X=LRx@t74| zc#;#C)zsmB3X$zZ#b_*Z2rNCtFi}h$)C+^_ePt3XTweT+-dIHVU8xSY_0uC}t)g+c znK`?$$&;%wbowJ~qL7psP&AnAKUA{ZwLp!(O!a8HVA@uA>o88Bp0dU!C@`?D^bR$a zf~^?B+75@j_YgzVn_uuaXinF?8oN?)Dvj4lHfv^jB++?l>uwwcP*kku-gV(zw-9Zm zZU(|@SD6P+b0p#Dr=Ngt;y$)U05JWP!+Y|>FUq#=R&IQx-B%@=&p}%fc2c0HIte>; zul}9?rULnFs_tUc(yO=jkp*_&HlpSYN(_+>%)1Bt6A|VRt``fW0omt731iD{bR567 zU-_zC?H8$YzTru+`%$H36Gy%hZtu~TqU`HxGz*~RsxN%v1~d%#xl4jEIs)H;1O2#Il?41dp1g#as< zyxnLa?%jz8DY0@BCp=E(&O$*MN%6+>evjTwOkiC)dy^0mRBco7iEnY#p-^r(Z6rr4m)j?RmWj8c0^v>fW#VR1& zJhNw)EsbnfH7>0!1%zU7`3jXFTo_NT3ddAU(A}rl3HU+K8@CERt>6$ygsf+}9L*HPyyUI_Jk+N}s&DPA0froHFKpp`}-G!{>U^&QYPP8?8%l zOmlu_R4tNy{N{{s2fJHeP>%ai`QS;I0;hn6eqTzGXJKLb1QfpB28wu5a5cxP)-=mq zwoGmY>A)yz0|mEIEsJMeX*3B-fHQSN=t1#p`*$pxd9&W<5?sWKQD|v^E(Nh?9*eg z={?E$1j;=+_?C=oY)}ASan$@rwrVSXX+Xme*720DVy%3YcY0okBNc(UY#j_h*BUtS zz!V}nuGqErWp1Fy2Z;QjNxyIb1^>rQzpSR;Q4Uae$Fsg8yaFHI9wkI8Zv25le$3f!;s@r=+W5AJ@kbcYld5c9GBvLo&@{atea$GUw~1a&5Y- z0`RsW=yYOB5gU4Y2KpDN#s5R%MY0pqLhC%i0; zu~Td@*o%EXAnqP#0dkV^yGrZcX5LM?C)BYWaTGf+ zRta^S7mXXsqbaB}+I{cEwr$Mj58SZa;LQnT`H}B7Rw_lKhfd(w*L0L^U=b)rf?DnW zx}X2@AmM?7Y25ovOq25N=?_rx~GV0+0$@U1`T&op5~1?u@Ey11ZtU|E1< zJSM6=#cPf!-R)vROGG2kP_AGI%XQ!seZi3 za%58F94D}_Gh<$UP*v_b0E2e?m>h>d1Ns8KpMtov#02@TpFgyhA4CtO8phmWMj%DA zDXog}H1xx>OCpDg51%rBe&FNcS0wsen;cTlUX6%zzpZu&bleBHm+7onIp^l^C@hQ%$)k9z}Gm3_h8F44d+ZuZ8+4($* z?&T^LX!u_%&kSXUr8fchb|YOaA>d`w{opT|>qOf!*DX+1KR~q-uM4{>Fdvc8kp7(8 z6t{0_ic!C+4W(j<62BtQ;`b!rGWuEJY4jXX_1Dpe2v ziljno@#-<)M#kag;sZC`jMatRmIIAHbvxJnJ;mt?HD>`&z?0va_UfEZ83l&fG{IIq zNWAvJN>U>1GK{4b)=#G60=$27&l`4rE%lMyX{5}rOIXf-O+n;N_$*caLO|ZjLz-6H z9}_ST!ym~mt?+ew0Xq=A_KoqmxgYSA43(_H%7eqgr?Yy#_?I4yH`TF+(yUF6bvzEG zGl*pZk30`}*hBEW{VtP`r*l}SSSS95(vm~3_#Budvdo!L3Vuik%13=+l2rfVQvz3r zPypa(cR681a9&dBnMq^EaV_3C2@Y z(~SfT3LGRTNP&sq-v_aNATrZSnM2WwVA~&G6^?W^64SjmqxhZ>;U#Au=$r303b-F_ zEKz8$8b|6Pr`{m+&hxk}5)v;rhS^ptwlLnzaP(*tiG)b(i%X^`_NZw}`!7B_P^PiO znNjb*HT93XYNmNTNr6WQ{3OWY^L+R7{5kHbPvU~64F~HR5DoYU#f2b()LhxKpYKnh z1FR++(omL7N?ia=9H`U4oE~84VIKq6+(>W1(^(lf5v;MjSe`(E7QxIY_>RCG!jWX}=;%-Q8jgk?dw+q0o^35J`J;v3!E6g8+Wg^9@wI%%RfF^V;Y*rihQe zU&F%tk2so226Xrb9e3wUB4*$ivS(oWL^8X1o3 z_gIMoR=U3D71)}w@Lhx!OrNld{a{jYPh-g)=*CRF&iE?47T#KAHoj_&=%scY|8$8us*|hQd&+R{u-f3}M=5k%iV03ZsKHupJ5-L6hQ2dv6 zTM8M%Ri)PckAFLy#D+XDMJPV42v=3XvgAt%#nbS2|M9vbbasc@x*k&1g1wcO@-&*H zb?z7GUF^3>I83BF5jE_xU8WfHXBWLL6=n_uxg$@$z!Z$jW>i$#B3uT$rAR=*VFvm7 zu45{~Z=P&lJH|ZSu6%rsI2P@6nWk5HpU$YW99kE5iM>F!Vl^@D14itv)#tF*h6$y) zjY{aWO91bwU^6Kg)wPMhx0?lj`LVwv+{2}9Vz#_bX9Z5dyZjWW&n#s72tmv7uQ;Tjb`a#x#1 zij6MysuE{m$nXBO<09h#3BrXMhw0`6kLl_U8{N_F8zII1%*?SvIT53f?dkM{{ifZU z?kQSSCBLJ;+6?-?>58}f);?=WObH4e5n(AeM+0LH|JLR;p4izO&AnA!PB&V5>D{)+ zOLHG4M{|+8b>c|>IED%3q;RM!U9~@T^Dg}pd&dqhx;erwbp9;*_tBA%kt%cI5EyGg zcL``P8sGoIUI!Pb(*&?F;vF)-w@yldH10a7VcY`A{b$)?`apnvku*8=tudKMoj-lBv_^#lW#tLguOG0TW8W z1bIcz6TN6S$ZZUz8=|w5$KnYq}a7Ytm@e}fRNLXMbly& zye@OUHw3ljjEa{Oq=IS;3d34^pbM|*UrZ!2tPS!?`nl33M^eMQSikA=#j*E0D};T+ z`E6cq?KlHFJ4F{M6piQQNQC*+)c4j_fFb(10&OL2RSn`8TjDpX0`4sOzF}DnYx-*) zlIUsiDb{ANYx*Le-&IWXH~*`h$e=X;=ax@|spZzzCMPfVXuP~Hw(b3S<{zx^>eX;x zi2W84hx*FTL&#%i9bme<^ec_n9$G9tHy?U3pI@$Uw^rFHghJ!-YJeXyZ!D+Wn9bLM z|LCgF*Hk$E{6;cQ+s8eyq3zJe(*TCH}=p&)f;Vkq=3swy8* z&#p||GX7RQl%gfet--N8|tM6A_xfI#i)^1^7bb% zKKtxa^{?ln0xf(L5)QchPT9xRxUWyITB!5fg(F|aOjmRc7B*G1>jfWxD%krRiS-j^ zADOZ`4;XxW^RpV*U7qWyE=Y0nE}SjWjEO%)-3MU)8_KPQ{q0&!1ipk_p%#%~A~Z_Y7~nn0)%T=>Ym?CKL3 zPN90cGYH~f%#Q+ZBt1a*_iGH2KIGeDv{7!X>#z-Ygt|qo&~J9=$K$~gF2gNcY%$8g zRgE+w?IjS&<|%P>s||gj*jQvj6Cozi(_e=D>R?Nyw4HcL5p?U**r5boJ3^HO+KDNH zicNxHW;*0vdM($Y;)U=Yj#!_qdN57D;K|SPlLNXh@fkFr7L?8%Yl?bt>@_-~^BM4k zSNe}G{Bio=tz~-a0>p2Zku`&e_gyS&q)v$jbfLe*zDIa^N*pczCFqoB7wgAe^}h1)yN8elneP6laW(Y zO^*j!(K@h{WGm_%t&WR$5=nP?ps5gsvz&A8O-i(qWiybu4$ zX+XB0ciPo7h7aDmf}wZiGD`gQU*tE4?a+aKK>BK8KCEN$=zlV`c`YV`wIHMXa}0dp zvLA~zX+_2Kj zvS7^2Skg2Q=dMOgIUid5h-f8-FD7Qv5#aRbU4~E3*{aj0+M1mDfj)n1uxm!FX!8V7 zMBk6Ib#kVS7xS<+JYCOUKZbeRTMh>+(ARiF|MsR~~f|F#WF`@2lfJ{Ii$) zQSi+6;3w>{%0bUo=VWqKZJ&(Kjy?urUv`AqF+|!}J^}5c(^hG5~N6r#1Kp8 zvy|^x;1n*{rMg)bcQpqtS{k-^5s!b3K;s8qaz`!#cIq*{a8?3^A*1TO_cG&HBgIv$ zKzp$jlmGVu@DdvwLu;Ul^Dh9!Go9Ri%&jxcxo?x;e;4J1=r8vslFV_!D;SdanOXjA z(g}dreujxA4X_iUCxuVro$3FVjHUM}bUmj}`^sAxabMg3?v{KI8>5bz1a$ZsBv#uQ z!mBtdRNOY1!6fx%GJ=9;R4fbyv*%r&J!j1jFUeWngdBv!a0B@b*mb$k`OofknLE+% zSGiqTP3_}6@5GVJoYHLy3Q%w|in2v03gO6op?2+tJ0!e`*Z1i!MoPF*oNbQo$whIC z$=9<-gw5TA>iW9cljHerX0BAyxX zlczMBKJ-?s(_YdsawfD|Buk(z@yRRb2EUK3OH};axtFP2aTd8*FMGCs`>$pKORuduR z23UUzF%Rh~<(FI~!}>~;wmznBSnj(nVaC<4<7`#W+Xka;Gbtn%7!eX>&iv0egCDb0 z7#C+96&x)T68Q?n^6$dfD}*x|Nf_vcKuTvx>y40=>0vH`z4^jM7kg-vwWV$#jO@$IX}LXf!F{2=T%KHkT}G znv3ID`SCBGlOau7p}$Te@*Cr%9xsdTsY=yYcKApP1JC1LR^oGmlS9R?!~wm zOBDUso&K!|-i7La^++Jr%T0}6@Ln(9Au2Z#Hy8;Rf_{1)!{ za;7lL6~%k@aTY5wZ5R|73oUDC_-TLr#?4ytc;W8S_2(u5O`RrDBTbKv{a!YcgV@m` za}XsrZ>;$pr^YCDMGU5gQfsHcXT`fCpUL)^DKv)BD=fz+89V&claS$)1e@RhaZa=p zn)|IK!q|JLU9_oK6gSYuNI`NgJqoQDZ2&xd+gMg@Dskt#LaJxV?E<^Vp-U6M2c(wg zUf%87eR8G}IApuiy5-?UX!M^VMOFo1jjj9`3)DQkecmMJ4lCs7*GI~}IQq|q4CSHC zq&};ait=&$+R$JrEIwPe{_98&z_`HXCNj$RcJ=wyD3w&1p*q&5WChk9uKAAGHd`SDZx&>E@QnoD!;(?@Hv2s6&Gd|&+iiYl;d$h&LdEN>OUQf`oQIb8F0P_pB;yuifrY`KqVnL?l-2=o6G_ugLEMAEbvaIz z$e;LhmidaVkj#wDT&=xPeAWE>%5D0AmN-nhsS&;06K#WeAt9XE2$8xTirBmIXN_*!9>a)4UaHTD5aA8oQjlRu!TiGL&DC1t&AV7 zGj&5hBhkjRwP)SG*frKzY~SfaPrHI4Sa155iz=pjL}d9(;xVOUH8I)V;$|v-at=#$ zT9GSM?|{@>-@#P06k%N>tBrW^!>V60JC6XPDEoiso#nBO-b9D+{bXYq^VrqayhHRUnNbX0A$|r~{9z52 z|B$c6ha`LMRrENdb-WR8`Um}eyEAgMhSgeRt_h-+OO6;&fZ${ zM6o;81Xq*%UaGOqdT+iTz|%?Z!N!Wm1Ng+3s#nD$|03T|)D5hUEnC#bqPi<{0h>CZ zIoR?@lB4LnDGS_)Qd4TUTxp9DSadY_z&G4o&vlxPkg+zE<$HJW0bx-(*&5GdtB(v- zzN#pPEqgPho$ATLp_43ah@mHb*NCE@@(u#QlCtP?A*G_MZmj%s2QNMpfTzA67p*Qv z%SMgI+tfcJ`ktP;&eEsJEa}&%d&-Y2{$Sf6p{J3!kWB-Pc$LE$0{w+2-d}q}PrNJ@ zReY~itgrY0PCTee*Fto2E3i-530E)Ty4M77`#=@vzswi<+L}e_FIYWIgmj2g#lb+L zq^qyHBcPSMWZu#V$syS;Ws-{YNuk3ucFiief^(yqH3`iuBt~EmtSekZLOZJXX<;L0 z?eW(}BH37|y)Y!Bwo^RqcEKV?8dj*F;dN&2&~$B75oQ7UhK~L~#XP*j?22Y|rSQgs zwO8xV(bPwF&s9)XqiV4&X^pa;!F`1bbZA^jXwy^8Re?owx|it7XJ**=OlKfFY91uJ zGsN#?D%>(P{`MnE;;RH;dnnv52?CO_Q;DFJNWX>8s%MWCF;=W#I)j<|B4A=m%_~Fm z68bejNQf`d^lE{J5NR|`2zt%k^Yj3i!0ak%he!yUe|I30@l5DreUzZIv)XEj=7}Ug zDaRh1{yOpXUb;Iu z&j_p93?Dw?OT+({jggd;T~Z$eG)~YQ6UwgP%n2bE?)4qy^&NFQVjdc6_4ho_Q=%z1 zd_M%|*J($jkfqnOL=CIes?+oE3GjQjxLrRPgK@C#Xf!>fUfVVa6t?EuJdPGNK-S9k z#=o%?`mw$aDxJjFVTFuctgtwewYZ2%M`5EidTN1R#jSn=hf=hE7{U_dI-Tj89>Zkg zcBX5vqQZA_t!1d?bxqtR6V>!x4%{H`W&G7+^Eo!O*s{73V#)IuT9fA1Pd^`u{Zw z2lP+i4MMD*AE1Ocb+xKSZFGu+hxlw{ky34Up{WcS!$Q>OwOIH=SX^*DfBN#Dq90

}bPxC)#KRsABK|j%iKEAA z6$P@`L)2G2PbCLvD$6+quNs({r5R_` zRq$say6RY-ElWxm`;^&+kI30fWLAVrn)YT1CU*LljPv{jbffr4Q{}+h&yqSPYqMx%%-o8?q)Ruf14KE7^$2lT1iEm z9GXBk`LAve&9jl4tr;hU(h^d}W0dd8_Y<+j^=LX@4lQcX>5PjH(t1yDuAL&~=X-4p zPt|IJ^RQh%lMemMkLoN;nUZol4t%p5;4h%j8BqVqx2Hu&d*O}-7DqLgPTA$B>js=W z)50+R#VCzzd8>v&w7-jHVvK2ll{m1sca~!$@bO@3an)=mx(SQ_PN8I?c12Dhx(1bQ zAprG;DHJTH-u;fFuIoIZmL87hsAy4zI={b**K6DOf$+egRA~%DZz|1*&(lf391?J< z1truodc|ScJz;m7M?9DI6|h0w(cIuc?n{>J?I23Bf1Q(Zl{9#Z&zBoPwKkpVU7)Y> zFFrMlVHdkJalr7et2%%2Zgm1TO2hcjw+_Q7}|VIUtv+BZDw#R!H= zd)8&Xh7_|`8eF~Ouc^6uPc7|ZxC?7FNQ=^Dg!k*v4PI$_xt7 zgVjb;lT|Gw@Zj&~WV<0G=u)`^uZLVveZ z=E{YB0oUGKK1LCxc)|G;O{Ee?rz_xvO0i#*>pM}3uZDL705z`rjH9^KArdz4`EU!e zUz}$0P&&dt+h?}+Wbu6U3pS}8M1)7-WnfC`B1K4V745%HH6r%dN1XlrXHfXQOnpGh zRhiY!!#t z;(u+plC&+7v8v_uTMj2!giP-}kz5FdzkQd68TOX06Pw!Ue#?YrO;Wr+RDVCc^fmf9 z!SdNpZ?2~bxeA4bk1Ly(->z1DhY%Rbw*U4k&^Ft%wZeD7-PM5y4Xj1i>$P;|W}1wB za13qUe)iIqN=#NX@l+6hYz>i!JK2v+#z}AQE@6|bQnh9+u z-6q2_5y4hsfck5W1y_yBb^YcOBrJB92*wtvD65}#6RCTsJn!r9Df-Me=e z(xk8W7b#4$KM4t+*1S$=GulROS^|83JbV@>fUmJHfDn_*Fp+v+L&2CFXbpq)zW&de z_%CIPt(3eE$tUvJG+~_)(aQxx#P@{c^9hi9nj>rlel(t%b!9QSejKrOA0>~tU|9&m zRra3yPpHTo`qdNmr~q!434+9V_=7k+Tod=-$WSrlEYmO*rZFNwIL+npl`abYivSk2 zpZ`J&XB&XCSNT3sfjdw^UAaY^7T{#X>yjQ;#!8yr1@G!OM*y2-ejsMCA%|3wS#+eL zaJ3RC-fku=ZCnpB3aTY4(lE~|yNVC0e`m(c=EHvTBUCS*Xfh5hwrs$P0-aMtoDgVY zM0i#0;X!$wnFsoIN%MtIq~y*jR^9!kVWqvEiaOn8$f(O7CH(PP0uFs=&2+KRy*G#B4xLHjllzzuK>#(}JC9x&c>p4^Eorf95{OohRpkp{}f zs`VED)>}UYW7Fc7dlzrvBi6Bjo>e!zta9`wl-<w23Nl!s=smHO8l`^!m5PDcK-R?o4BINjT)0?jiRPHA zn(5)(_f;^^pkGb?*q(3_^|SiRA=UjHT~z!cS-ENxkn}?vg?*zy{qM$=KTAvIZMzsh zV}@T@YmYLhC1pqXIBpL|pjEw5S@f`_XCAU5V;XJbFP&*ucT;zh^F<~YOZ{X}twszF zgSFKUw!7Y5-qjYq%7{JZ&lB2TOB|VL@oXNsi#M-ZWSrE-~C%E zOyqy`m;cJSKO-5y#GW0dsoW1xcvP5(uw8n3<2v;2q-}^5`Ig`u=_@toz&zVJ_5?^&Ynd%nY{`x4OGrVSf-Earq zBocEYSZb{$Ven0aS&Rm#s@c5!d`5wjsL(dO>K^t$8|i{aQT*l)ypc#}KezY`k5@i2 zy;2!Qv)_SGiKKY(n32LWSF19OQ#so@2&!iB2WXbuP_Kh^4#_NqTxBDdYs2Y8A0vFe z_abiXaPs5-rW>ov*0;|1T#hN&gnD^YvaJ@j@c=FXrfIuKHS=$Wz#nt#m!9DxRslKh z$A>pX*$+-uB3qvZOtAi~oZa-~ss){o450j*{n? zLQx-Hr2RKD6iv{Wu1yQ5__EC84lT;?k5N+BUSM{9Py<-+_{R+j&9A$+h&oRTlG!R5 zs0UzPD3B@$iy@N0ItRBt;h*Cw%DYs#QQZS)hDp?7&aUAIxYUZrng+^EFC=k7==f&B zq|vjm%cz8Ud^Il3PqHr6zUTw9CCuj!<6=6izSoJmf2XkA;XH{F-j=X+O1f1c;hKG9 zWyfNOwDrcjo?&*e&UlHE^n--o|hFW7T9gb&S@0kVBJ*m*cT*iFLF z_PC~evY`|xK8H~8+-HIYMWIvYM~!hdvGB%Y(EClC|LUHYKO&*LbViGut{E!RvKT_6 z@}1j1Mfhk^)iW9jTGOZrs!|k3s=a%2(nZgJnZtwZ>#`&n5?x&?DYW03b3#=o>rIG8 z1_Y|r3>1{gzNW|x2iH4I{?u7)l>AzU#()K;F5tK)IiIw% zT+q;$zm)iwsp?c#m@`iMF6h5l3-FX66_a7<4If;zI>ngY2D}Ncw^913Uo}-j=HEH| z#=YefnSGiT1SQ!h#+(?XA;d%QKF1g1&ba5yxP6ryY=R;3Y{ehj-^6p0tmo_MJ3D6w;>G*UO{~;W_xa3YP7a`_Z z09$kdD@OLt?g$ZS#t&~=OH6ye9e1;;Fv)Pa>T*4O9uz(}ca2(M0LSBNbj_ZXZ*Sdl zIqvRyJ+|_4r`&cU{wM&>$1M;cEGey#!g~+}Q@QZ!Os;C18#48-kY}f{mh*Hz#g8pa zmlGZ|vq}PQd{sd7x|g%8xQ4DrFe-~<%gk^2y5V(%Fuu>MLSPN(GW^=M^UG)FN{6!> zd82IT1b{L6G`%`QP)Fg;f#Y$(dATC=1HKUd+nFdJ30@pA58nsXHw1>54n?EM1S>7r zf*EiWaY50>izi?FqpAyBAB7G%$Mw62N=z_(%takmLDVs4X>%W$L}XFMbb83|UAIqM zHwJvM%I4Vj$til$msfHN7mR|Z>-sUbM8l}FMZRB4)OCCD{g4`ncTD29U8mR|cgef* z{XAO}7d(y9ehvA7#6WKpOF;^`*!?s>2XE<=*6Jzu6ixb+Nd^uy)5^u6N`**ET&`_h z{V24AykL4BRR%B@gNKq|6(RO^-R=zQM2w88PPgRoNU?;?ZN z1VToz__!DQkn5%Cg~DC>(s^M(;G>`z0>?ifp`6yOHRF0$JLIZq*t|@Y-pQWxoo|tZ z`?pzkWh^y?3dmyc9AOZSX%=2;JaO5oDH;)wejLbhBM z2v{ACoFX8-GWyj&b1fGS3~^0S-0@LGWQ-oB&a|Lfox~si)BR6(T8<47-1FL>U-y)%uOZ1Z~&Eqt5#=k{qb$S_(D^$ z_nBdbB1lOzpe-LRn?ylL@Ss^!d)2JO2`0ru3pNYy{;^8n>_|9>#8*OXML@V^Xp zxu+e$=*2ht`~#fr%fOHh$F)|Q_x`XTMVRl_H}bl9Q_LIww7#>6#%o|c%zNvzz%26T zY!5?@Ysece-N$ve%PH5KsLG|P^vPH`rjgth5Z8!&c;sMlcmml32U1Q43`L{ zpY_9BSpo1%;1)_{Wz)1bD6BPyoS>Ag7Z!x!*Fz5{ftBCEwUfcuhTF*5o8`y; zK7=uHRQ(rm(;W3^`GIha^O9r9K8bPEMH$shu)W<-VpT zg1Gnq08HnxJm5ihR4nD|ClC2>~^>AGDrs>^hf_=@>WU@ceOdH*heztL6Z$02= zO1#*j`5z@NGdiy9a|G-ROGsxR)HX^BElRPA>MkO+->-M8*`69ndC&=v8c>#??Nz=^UEvd=cGcCARY7ZvMn zNvIj%Dz-RT+=ac^PZ!NRliT=tjR^uiaM>tc@%1~cKmUr=Ln}fNx0X(odQBDdU4fld z&+Hv<+Tw8)Q@8aTr?!I2YBjYmHFINqVZ6d|fmC{M4KYqs#oC^C+&7 zX@@12X5$U6@ zJNX9Q^(iIoL98c3`UY42zBUn@ZApHDpC&F581OFYsm%tNx~mbq{Q||Or48-nUr zFVkzAJ8Qeb^v1rr|AHx7JOjgY>%-y@!0N==ZJusOoSGD(;5L?0Lf*fK#PG36@U|5$ z?QUol4>@DZ?@6$fi@C^ww{gH)*Wc;f0ixHIH`IhVAE~Ca}neXi8|F%+bNOMJ6^Q3AAp27mP z)O<6yRgjVR(g%PnXlJ(DSHYln)8tsqqCxo0R8G{3h3LHMBL|3M6G4lF^2UxTF#%M ziI7=SfUWC6RSta=ILI5xSik?Z%f}<``}5l2NzyM3GX_d7ZdPbjB{6JLw+68y@J=1_ z|6G!aK8mQ!0743>)w z_k}Kwl(8Emxk9t0?HlVo6FSFL?x-SWF+LJ%@<>aANfxWh#r@;S1~Q)l;QWx6)`vMY zf79?|jZa9O+Gi-6YZdg~x?BFQO{dz688ivYi1uT9=C%3$N-VrYVA)OErd2JiXoO3j zZ*JQtDrR$3l-~?lHZAUrH*^tc#4FhFa5{(Tf#>bs#hZCUEcjOzZgz4tEvdq^)nizk z!l^_I1kzOI!UfYE?)y1osemU$#6YIoL|+|!K%5@8>j~&nvEdeJ0lP|f)`{Hsv%ye| zEb;nI)@r+Gga^^hWY%Eb%;(sdr>fg8TsLXmWR`xWlH*1Wj>bkIH-QZ{@j{9oc%oF_BiCk`*3iTv*o$;u#r=nA() zKMY)&$E|?2@MZ38TCOsqf0Tdhzbhx4NOor5={knZ=$C#ow@)RJ9ZMcNBxHDi>D#5&EnEh5RA*cyyhCPhz>{m&Z}wzX(mA0L99wvV z&n{M+?3aP%CN9D41>0F^4d37Hd^w}sfc(cIVjpT9T6C{x7@d`6mr5>VB_JH>6Yg`% zdjBN=>ymKAieNKK-BEyju4!2=1Y5+R0>9edjQ3&D_1N)aN7)m)8V3@}(&px18}a0A zTNp!LtC%)(kzn~FxECwZKZ%?a!~WW$%-TJbDdhjy5QsD0dBs`14X&eE3#2KKdQ zp%NI+WmyBwHh{^{ye%G41|k0C2wWF$NaV^Wl(e8L?D2{Mbj*BX8<;d?Kc}` z(5Cve6%2UehFKC`bTd+M$rF*sAEPnM;~RiZ(30`NyR_FW1aQ6$&q%pH-Z2JlHKoB` z2oQ6e+?k3OzWmAI;!CVbgR3b8=&Q4ZI+^=N>z279nM%dE4D$MT1<~PI;P%9{Fh+36AGtArD%`SCOG=Y+_%x5E#|Y8xk+0sXKuL% zMzRGrfUas$ad_~A{gbDi4SkbmudE|M%>jM{!xSZRN<<|EB?(F zdpquN1eI&I$v9JN_jiIFzq7s<0J6RNwf-nZ0}$p-zPP`ym^>9SC*$A}1UgNj1Q7wH z!3)hhyV{Q!Z(~_cGRrYoIha;D6KJ(x%H* zy+_E(W5Dj+k=3|Woj_18LS?6<&5!Y{ydDYgR)+T>3fDlHq*ULq+#>Y3wG$K0tD~ZZ zRWz8z4turoPA(5CO%|^fzT3l?&U4u_bC5EJK2bFxZK6QhOyTAo~66L zddV!1`vEmbLbJPttg5)<8x4vt@rHb#rXW-zEBTF+Pwv91O9j<7hW}%_u$81u)AtAcBu8<&{r(T<8am_*RubVJp-M{G$uTOLgC4Xh$b9cTBs9NAT zbh>a@-{O2=|9c60XQlY#Iqwmrk!^l-H#=M!S-hA1iw6JX@5PN*;(4Z3YzOGX({jJ`0dBlMk%@ z1=CHKtLM!!^XD5!ZS_1AT>%5RMxbWBMs8VYw@*7_C|oF?Ulyp4^9u=`gjEIP5S9QZ z^IE3fwjbIAc`|N#hZvoa+|Z*F4&aKDz)?Z@4Wa?uUHZPxAbQ-1uPhyb3G&)b(#|)p zuuT~7wU=a|+X=$r{}DX`Y+Tw{+xzP#f*;@V-O*+2Fu@F8O~~ruccBiiUO4-VuuO(C((Y|)yFa@3PfT!n z6DJHR7)+#NPb1vfDK64XObyAOaPRT5IkTGF!Lj98eKYlWt>v_O@Fe$L#Z0>^nt~6G zvDB&ZesUOWZb&C<&o7z;YL}Crpvss`A+dhB5gRO&jKs%nZAc)2=;NDuU<}A1S9Gfx zCmqPyob(n-nml|BG)XREvZfv7qriN6x%y%el>dg)cgWQq> z#elX%x4#V6^z7io2!>h`7?FEpm71_{`MG6QUV0l5p>5Wge*1#`u(gnhl+MW{nX-IG z^1L*aVvFTsF-yCN9rNp~APj-`tbMX$(jaRM$2O2JW*%*(?Hk*l21RQY$HfM|Hq!C6 zo7Ixp{@Z`bxRs^2PwjWojuU=(yH~ortD*g}RLf@#e;bTBTgFMnmu^f#8+`9sA9u|T zdxfEA{vet(#w1(neT<_JeqFot3>k8S;P`~TH&hwK|(pQRp zI1a4qS3uJS1a9knn5G7W*KTRewDZtGGbs$lF?po#sZ1Ey;jhj37nZshsnx!v@=ar> zk=7`5Zu5WP>$^3F*y`0NmlBTST{K3P<#7Q`iEPrmj@(4(SQHcHSZOv-f1@^P3@>id zbkz*s;Ar>yeFQ0MRe zGfcGKS9!)U{mE;?Gl8gzT2Q_S1ZHdjrMu$ZUU-DE{!O3TWxX@7PZCwR5WXcHkxi)b zC)Hg!ulKx`>L)qM)>obDqF+@x5A-SuJ#Mx&s>{1xQe*8x!zOWi`5(QonbV}VwJXtyPV9+d7?T^fG1`qXn};KiKKp8 zU;;h*tb%hkXvhXK-raiQ`?`&phrUy001Xs}<8Qer2l`!`&y%G7;XT2(i=E*=1t`q} zaF(*K($?Q$VJbCe11-B2;{;^eCFIx58nb@_uZ+RXh&!rcEbH zANuw6_BDBmg=t8ti(dNfvq#E)yRvU3!tze11f#@&AFmd|A7uPn3~ViKqKfp!>J5VcPYzeG=-3##Uw)a^6b2 z(j?zg8y-i_D2;mn?%M(fG3|mrL>($t69$5lg$X&Y+Q1`gzq7r18QYUuaZ$dLE#iJ> zF^-{U4|Z55(#3EBp-Hr@!Q-Eaic-b4|(u8esX>Hb;|P~)f$HXX-3JvTv^*i4ePDfB#<|IqX?%+ zGqdMKl=AsRbCr<<1Bhd%!&9d!5w{N-(+}gu#>Qv|cUA5?BVu^Gyzn~wj^Qzt_!Vs$YW&{xl zC(YNbqSh0G@jktt(QQotsY63&7yZ@sN9VOFOU<8HbC<)d)_n)~;MXqUm}g#M>>Vm& z?-MFcxaeGS4y}ufY8!nWC+X8!TTna6<_D>@f=b3ueX?9yiDz4j1uXS(Pz>G~ryTN0%>Hha$fhX{U$#-bcCqD-^c1JOWG}AS|mdkybQ5Dk(&AAEc zhwFW$3oR-+?TgMaX6LfCHO+d2d!e4yuTDY&)zbUDT0U|o=2Z2F+GVBr*OPd)Vkt?< zB**r&A4yNw%_1nV6YRMgmWHe1gv!J)II+DBMvI7{hPLjXKz5s?WY(=Ptz&nHp(~L7 zgm#S5s4`0*MNoD>w@xj^un3?Ke9r#?D9nVvn&zH>I-vDPvNk|3L@05>mhM2wyHw;` zH(^n!r~2E>u3&&d=cGd}sO3f=&jhH>c89EqWe6**UJ76^oI^<7Q&Mj6xI%q{(FNGo zu`AAt=QliDe=A?99J|+AqQyR0RVi!?TxqZ3iFc<{vsf*AYR8p;wZ!TAiuEzS?7m`; zx&$1b79x_+q)dL9+RpyzbTeq?LhG^Qo{$72yl9)fvk4MjW9jev+Lt_}tsDcLhD z2o_mQ;K`4RFMUS38kG`-l>~5D^kYm?61-2U*9&DX?M_Legr&JLFPUPAK51(IsB}}7>to;~>pS+ODQJ#f<}OclcO`oBoBzn6Kfbj5s|9CV z(hJp_s^5Jg^|G@mggz+8%o=fmpkU67BlX`;j6Sy{xi=;^sVKC_yeZGoBZe^J3RndcS#iOB1(%?Pa9=TNVM})JjZOQr zJonfOd#DIycwjqxrbJWPgEG7Gzf1uhV4A*LUSO765@!c>Q&s*~Z&ypT-h=Nvv% znB7^S#AjY{pK>+vY@5;&Ygi07E_KB zUIrh23QX3r3m3FN5=eB9yFSazuhoiAMrAt#NpG-g+_fl;M!OE<0Zrj$h;!>EFY%I7 z4@3PoMkyxY2ghE2Q5t&tjP=rWZquGXta>R`?rRYmpX8pLhEMd%7K(1^pbj?=0NGAI zlOn#Tld`zwsWLTl-EjSEG8Q)|`zZZKQ$tyY?QNJeat>V+@R}VIx)e@0dj^}}d+>jX zrHm~w_;mb7{_~aj3;s**Yr*{9cV0M^8%9r?psd3$5uq__3SW7O@4Vu*i(mn(;;rLk zopl>HEG++?&3Vf>Vn4*MRfXld{vN_B>cO7eLa(uEH=-nSe@6TB1y(P|suM0FQUhlC zkiIqXg?vOP2}afG;wH)6RTiV-{N1%B^Ti}fikq@eK#CAZ*L+_Q8WpYG8HM-M+NUtH zP%9ILwW%eMC8$`%PXG9`)+EC^4Y_1dGal)XYCC%z-`phy5a%H_psPWTZsrG?IIxi* zB*S=<49FFM*iBTH<0j5ic`@2BFrk4n z`A^k1p37d;mdT{1O!k?Giyq^M_n8XAL-Ym-y@DI3-pEfDK67l{Q&w5 zVQkHb8~vR@e1HAd9F#-L6)|-$14Zx*)YYPs9co(e_K%nH#L!= z3gS9fb>eSCjO#z_YuitwVxI>s6(P)iNyeFO=y8sU>&o^~x`fMcooFoJt@?`~jbB=y z5AqHg*v%~#A6V9<@SBpkQFLh5eYbt@M1xvf#_qhv-hPa+3>1^3HgU=D#rkak{rwK% zWLQl^^loD7n6p@k7T2QeBaJxA6wz4ZspcOK%7I3%DM7njqL3-^NA{dST!wQA1MX8h z%636}_iVpK1D)1(-8T$&%1!~Jh&EX+_G8&2+(cJs&A>o|kAIf#;zqr!%X%ys8W=XYqiB$3V~uj z(@jwwp~^neikm+XE#Mr_5HDk&r|g0A}VT z@qRC7pnD&rO^9X;F9`xg>AZuPEnYz6pioI)iYCO%0XKE;j%u>?A~{;5kqp_^e^)^4 z8>?ysAvLA1!(2maeVHlZ_+2HFIyX#^LraOIgth;hY#0@bG#O}%uXG;(f+lt2vl!l=Sz(I8AETU zi_OFTN^}pwYfYrgl^Ul{aVXUN;O@F1^0$Js54F+3A0d4l+#S3eE3D;rTe~qI$Qx{C za{JIgEkme*sca9QueJnCHs395TzI@lT~fSmQT@SsvUV|p@`NDQn3eDFtZNtLKbb;{ z+fWe&rqcf3)N@`_xLFI#7L%AL3mG9^88`q>k`&>xh_%i zK$ecuE{!y?#eH53QCO*o8wiZBdMD%Tqp$+_liFw_U~km?w5+KG07$Mcr2EGsYd2xr zKHtpkUM5~Hn3iihhPN&z8&JKw6uUl1EV5XtsU#sfdWQjZqyF;92Mw6w5qwkH$Tos_ zI7?xg<1PUETZMUsw-eynVOJSYFB?rk-8A(crzf~2<+fz4o`On(o{5~{`anVX%ERl! zQ9(8YX*_u$#FoL5ZcH{3v%GBj;lVB90A_M|yk9Wmi{o9?+4k^e3fhf?z`qps7Z2?2 zjbo@jDLY}ntF`!R{pd6+qh$LsLBu+#gofqb*fObEe)5mL65a5dn;DRhjuatQBtOlS zR!G^FpvG{}oE_VDk)0MVLtU1#%0!E#!?JIa>PNkzMQ`|`l0JcwCsQ)U0$-kU64K6T z$tY@X?|@h0N#10T$)jxppZKEdly6N-tL@9KgF8p9KAMN!*tW0g{yLnSokL>nab98U zd0P(=x9huroGWL4w4Ng7$SWUz7)x|OCJg!G6l7c5I2AHC76HJFI{Rd6gpR*`qRx;o zJo^zJ>&H&+kI%PZHDQmG6W4mSM&`7VW8aj?+sQuEYj>8dx`=rVx3EIRCdMd{4S)Mw zMH57p#3Sn;X-T<9v&aOwRa6|DCmO%&woH%N7cCF2HR6~Bi92(i^branD-kZde_d?f zuuom?LJUXlyrn)U_Qyq*}$IkspW6dMso0OtNV)-ayu20jN{Aa zcfaK~+36rWM(ux+0m__u8nH`Ag4;w>7v?W+ybmj>4%2xu)t*Go`M8CX2dKd&Q>kS} zn8~dr={eV9*9V#2u9n^JRQ|Ur$`M9bT<-*lCCo5iU2yjE5XTeHE#R4c`%UCo&21XL z9BOdrD8tOTqS&7GTcwwBfX#y)$0fU=wDuBxLu!PGk)qS1liaaft4apN1l4?q4yVKY zpa^Vp9ZaQaZj2kCYduqye>r&8g`l?XW>>yG`we8u3kqAeXsn{{qEMnKPICG<{|STj zI@*wxY3T!#PJeU~yIjb@QYpV7&I6bMR)^53bJm2Q1i_bT7a9jRgxAVBGW9>_*`sOv zZW+*=z24?_ht6-xWr(PM5YrAcNMSyXp`p&GCdLx%-zf!F@@dG)GF^huk7Y?iJ#l~r)Zt7v_Nx?}u4r_n zTMKU_xxwmOnOm82JS2m>CvEYFYFRpW~}jMlC&Vx4gE z41L1*x(ZtR>_6l>q3-OH-b;>z6Y8X_j3ph2508aC>UKYov$(2lm9dCy_Oag4vvYO^ z`gnL(B(?VXMLlre=*|omB_+Gpe`KKqdzZc=4{L~IspJpW&7~xlp7YeLMP({=-h=W( zrhu3>he0mV(G6ra1Ltyoy;qFO#6C9BvZAc+iM!aN@ti}KVJQYvohN7z;E#TW#6FNl zbdNW3I-lksh%7mN+4kwQ0rmGDxBXCJc1mqh-Nv23GK)dGgGTiax>Q4%wLnH^Z6PF^ zna!PNj{Cj+9rG-pm##`G-}A#?ou^owKH(zh;17=yXj`-eV_7HDNB!aK&z+AITQp}= zFx?FuA=UqmhTP0yc_i(h7InM|+}e3KFxy337rG#^JsZAv`DvkKN_twzpUzxYacqYd zmKZVtWNzOk3G~nh400|FQ+R+cINc9@x^od9z24%tObz&0PTv7`E7O~Ds#FNi3qMq46>Xo6)=`n$=hv|@@*MbqD|7pBAOH4mq`q8Bq@vE zL3%UmnvLAXJ;cTtv-*>#WdLBba450ye^~&iOh9as&urH*3N)61k+Kwp-1fX{?2alqf`1SYnbFrh{8~(NQg1#-Jf&G9N>?cUg7WH z17V~?CILL^vm10#KzB<@*{bTAQC7pK(likzY!*BVYhz` zuT_Om#=0WDpyWsw`&s2>XDW^i%Bh5;=dQs2CM9||r(}0VZ_`8os+TCL44;pK z%hii#@TJw0KxLbcowG}5soyx7G1KBtq7!BWDn~Y=BnLqSg_T81_)}TJD^GlV`s7JF zXBqiir4^{ZFny~XLiBp@PQ2-gx3YxAhU1%;;Y>>bD0}~b!hHqBzx-p9w!IsxX@v4- zLz+qMUCzDlNgOCUupBvhx`0i&oY4JD(We5qKrm9Om|9R(6r__v)IPo6Yr2N9!pmhP z82Q_yhQ7P@-0HymT49ZtqWlq*{KGjcnwN{A2!R*1))gaE z?3^&f0LyTdxLVFj?sRT5V>CO(BVYBHCA=OOGgE0T@%HpMpa2hhdZ!=Bt}G`svWRtKbnJ#!Q&;5W`{sK{pAA5qpy z#TeX_PUrWcvSpu}Y%NS&_rhYl%lHJtJW9V}nApt_G*cCf=+4WMrh8VHQS+}yDsX`& znN>giwoZ+&ZH{J%boA;eBr|<= zrTpwyy=NI#9_brBykv!D>yk}~6>B4UUnQ!v_>Gqu9q5+{THeGZu*?$s8_MwE7)V0E zR|Pd#boe-_81d2OuYFqKri;?7?`{2YUYZ6LuP!;0;yQ)MXWlo_h-zz4%j6W-wEsub zSB15~bp63Q_Ca5DK3J1CY`rFK`Uu& zz?Xh_B}Ite(6oM@>HH)xj@4M&>7cAJFpy`h?Z)lz=nRi4FYJl0X9{X3ld?+kuazua z@Ou$le%Qe?3jCY8Ra7V_E(cH6+v)4YXN{^~iXn;JsteJ7?$SZCzw2cji=%ZHYTwI` z2q)aX@eR)B#VKpN)FsLwBSAVEN0{Gmb6N3ixkrcGmOl*$=Ja8X)Sk?;n|-C`gB(AS zK;)IcT+qlY*k48Of8@t#hIdgj-I!1Y!#6+p1~vN5)e6DEhkMqQDq-zCS};< zmVW5Spbm~h?E73|F#?ZvH!WUBK9g>mwAjKOgDZ#U6MUZeaUM9%xvWun#j-Av)rrQtg}o5Vbg+;>?e z0Zl&r1@M%QJ}taw+Pg%}0*CGr5QPM?h=c>*6o=(`XKrIc05$WuW)Puk!^QrbwVNWn zQdc)1I8>pW`~IP3)n3n?xeab@W7Sty23>Q?pMba9&nuyj>OTnJs{NxR|H&3tu}b_& z#!tcQ1=#}s@%Te--VorRtR1Et5~q;Wh(z!njpv?A_PE%GPus_0Gxk)X3iRE}RAOt5 zXDFrol`oE4Q_a5|T38lypihya*CKvarMWz*o#qj!8PCeYaxCf1#697PtQG(>c&J*B zyYFgsk(N22^|v|aP(U?Tg+&mCU558oa*+ZEH3fgUw*eGK%X)=4+OL=8Uqd}8jTn$L z3xD~jX+#x$mY=M0^PppJEK9r=2Wkg`Q8JEXsE z8g1n1r4n}EgnwhA#e)H0r?0p);hQ~%-j&q_t0dp9KZ@{08R7x)UYg)YbS?C&01b-J zL&yU-{CT>k0K|^ykl!uzAX z&9M-HEIeSk~7X|(i9K1GuRoB2BXDcnjyA#$C61AhWzj!skgXPEVF*@k6w zYIQUw9gi(bBYd0m+)<;AS(pNpDjVTss zBg1+qkB^pjQ5XLz5=;IAKX&zfUVLcW4$e_MEgCzH#{mVnGA6)#W8MiR*ii4H3HX6l zhwH8j+2kA4UtNK9ZDXzj_EDg#+=)b{({xUW%!gf5~Y~cL$yU=X{rGK5{AYKR*Vu z?nys9E&p+-?^Q5KaW;8&yIe5G5L|fu;0Gk=L&eZ+SJvI)II-V3{W^qwn|7)~#Bi97 z#KxT$&3W6Cja&h6m&iv~;6IcPIY0k8RKn@09IYe`0c#;QVy+LjCutki4wS}!2NOZiHuH1Ik}GyWcC}`M7c0UbF$C=hMS zK}dFG`<8KRmXJ@X~T4~v=%a0|T z&MClDoEgIJtcL^<%Vb0`8T5G*M|)+(BCOxI?KcfYedp41T}?v7!ijImFhsSSSnqwI zq;)cQtVsVSeFZ%Fyn0>I=pO08!vZ}0j{vOCt^N_IWY+@lh6OQRoZjY*oL}Q93QtP_ zPv<6Y*NRInFo(zE|LQb24yFG|UW{FOJ7cu90v8nF1l}Hp7r(#XotmJaY(;`o)+I^* zO2g@5G27CO{no5V)2RnfO_#eRP~ygI_(9^8uPwgyt7CuQLZXA%@0F^c3+M-Tz`O_G z1tx=tInNkf#y!gc9~2I;%WZ^#-=avhh#fjygfy_%?ci{yS$@Ej8_Q1+nzVSu_quGO zM|>+!6sO3iva=JT7|wr6$7ISP-m+{B-f~4=&Ws4^Yv@*O)R7P_FXij_9UreEkgcZd z#5RspUOHqDUyfk~FJ6TJV}xhE?|xRhE7q3=)Hti95t=-jkY0>h6A4yodv_G*EBOk?#?07}ShAI*1S;A@+n6h>0 zoAtE4I3fxY_roc!hxP{6E*2r&yzJwX)hn1MD{!I|2pLBVNC#5~nkf|}?xjST@?vCP z2+?qgweXg8F9Kpe+C*0cOSd*%e$*)#nav%vFF&1yT%R<6aMv(OmX<#|N&hRZm(S&^ z$XhM1$!vjEb(qF6@m8^ZqmekxyA3W`g-hEoj+~VA-vF65P7H`MYz@c!D@v7}SGl2! z#04k|zZ$Q`1vyW8w!@cI%r(kY@5hWiGR4$RVd}yh$|zt|$U63=uc|asb^3L3$x<{C zN#)TjI5=lFQvI_m)A)h@(`i8X{n(=fUpHBG-+c5F>`DnNyuQgsMFI7E6+*=SHYn(y z{_)e;ApGublP21w)$ovHBu4#6x$1+GX_B8cGQjmyGm~r$JFYzCbRXHQnqPg-O`>+G zO@Z^_BG?`Y!#>BarC1@o1Z_RDHFiGq)cQ$Uy|B-WJJP?LuaOGCYKn+eZ*{S8A#Efe z^Ger;eC%@!<~_fRFD9ObK9+RWTkp@C!37{z+luc1ZR0#_*wC5zB;HRI%1G=jGLilm zGw*DY{49&;VJ#f35FTIZ(yF$F85y+fCihjXt51(fzby#=3uWjwVSVSocy1qDGoZq_ z@C^~_@3<=GKky*;3jxjqqz!88&h?q=Dw%)~hfDvFDj$H0};uz60?t=s*vNJfdZ z@3ZyUJVEf-Rx)YKXB^|~z^yPd$41>x9g6dB!Yhe+e z=8h3IYir+xe^wyBQQ&y$CyG#&P0f6v8gE$)WN@yX1xHpiy-DPDVZ_tPGzD`-^P2^! z6^*(U8H|lKa+$c~v_;Cy>>{9X?(ph_OF6V1$&7kTK|5>nE(ClS;3;9?^8e0UN#s#qxN_hIORh6Ia zS#oe4g@6XutQ3npm9iz{HSWZDo>Xz;Rii54;M>iEqYF;$E!D6|8&F~w>m}Eqc*G|ILcdYw+`oU$UL&>_vgQTn^_a0xL_y7D zr@Ib$^eyrX(-pdDKJU}!515dkCZ$ZzTF9*0=BJ%?xJmvWtO*grt0Xs_%>436Kc0dvxtPF+M`5vu~`Wu)WA!&*#bI9yZES~)H7@=5CE2I7n!GW z`tZK*1qL!cZ4R+b+y@3OA~&928^!h@7EXw!XGDe7fT?GI`L80W?V2l(I!Lzh&R zN39G$naKArlufL&5Bd16y!ySqJPLjX)$Q4{r2cghAbQvbUS^CiCobX1^9MZ(xT2Sq zL6Z{xS1$utdxAm!llqEuoyve(x;^6ezh#!y(}GT>lB%vEuR|W^NVgI#x>jYE1f8Uj zDGV*_FP5q!hAA1=m6j1|<2#H7VMVe_*^w*rd~ve@IOh3Fdy6A-9x))wrF^#XI-#f< zKkG-?tVfjPoZ+!01H>dx$ckRXh-Ov%2N8l(I}{t<5cL0qCl z>^hP!gC1<47p)-<7^Jym;6^jg-{ZsI(I)@o2MIVID*eUlBCn~wetXsoccDpaFYB6s zC4U5_Jl%-0Z*yrU{UNc}@r=n1#FE`hKIo&~G1f}ivkBSC7ft_eeNG4w+KLZo>+d`? z%n1QY`ElrJ%f{+C^x!Rj^XHaiUq@VDyTqiPe}Y%SAC4_4`JL!q5&KMa-$RK)+R9e5 zpOk}B>MH45>DxFEE*Czg3z z#jW)N2sBo)*GIVbQNLPH_ZsTR4xxFM30`zuw7kG1nh?ZdN8c0B^Zel4g;9=iNoYA` za%uLri~x#AxMnTo;v$V5XX|IYkZ3S9HQ@*fFJxPBhatgG&5DGQw7*6+fsvVZj57VC zl}3sfbQXvOuZ*&}#5{{ki(+8YYGo?%2 z54!0Cx40PzYp@>>~eaiYdI`y8!EoQNNzfoI%NSL?!P|Pj`QObmI+5hf76_dvLWL6w+Uu|8m@2 z_JoVB(w4E~YWJmVi8hErYIACL{&~>aUT4-aQoi&=m5Te&4P&ggIvaZrMEq8k8mwLe z^%K!6xvwquU z3A-F^fEK4Dq}iugS2k4Qc!h@xcv=O_?a6QX70aJYG;8y6(nZ9~?wr^oM<0YT zB+sN}Qt|?j)-2sQNhliA8lvrl618Ie9a;ulz^X9_ znLi323VbTcNOj^r%ry8y%|0K5mxzshAeug6+t%x#@L9HM>`J-8DKmt->%0}sKmq(T z%glJ{VY}A)n{9{oGoD}n=TnoD4|eQxFm^aq~|NZ$2bO^7qbn#^(6- z6U<`OhyE&!{5>|P?BZ#`PZJpts&QIXe2p0*0asYek@9h2uBiqWCoVF6SgCkmCSMnqGVI(hQ0Jb{#NAmQ-&1OZUt7{M$@J_W zw6G@)5EG;dQoJ|DnIA^%*U!&AJp0hSm-go8fLAO^hG#}1x5>7jv&HD_Q9a&qj9F{^ zr0ewCNeM%_Ox~MFZ&-)$RrVzs@fyRwDD}PFqjUDq3Y8%G0UIO0ng*aWH^jf}csx_h>sTu+;cd>4# z`YebA>a&=Eqs`YhJP*LIjTdlQ#4SVxoDzF~y7}-w9=@ivhRPQCO8U?CCjze04Zkys z-6#f(u&5m_BH$yXQ>y!EWQW8WR5D$GD9Ki65qS_xnQQ%+k{I4+AC&F$BTPR8Dsk-T z(pfWEeJ)^aO_;^ComdYvds!ntyIy$de{%=B|Mcg|>wWYyB%H7TkI^aXF=tBC5cBA7 z=>?~m;3zp)$$n#Bv(eO<%*v|jJePJ`@0zRkyu|0|_2ehs(siWfT=Ti`UYk`e@6o&% zLBwWuF8VbW*+SSzRqr&XGwJj)L*udqlMu+MlUO@?g>Pc}KG;_F)!BAEY9|)LH`&?# zUC2Jb27qrfXqEWKtmoBC`hJi`ziZFCnoNF(jJ;=!XeF}~AX*-Z4MSh?_{M~d0(*yX z%7nrq;NU>#{L1(r6RjE&jiLO-+-<{@uhaF`@37Qell_}U>ffWrZJw&a;>eYeIay-J zq?oDsM&n4XD02SCo;bNl;XFUn4DAzWBRq$ZvaVq<@^xQrL+u*x&`aqoL4Nc$tzvS!!W!DT%y%Tm0k-iOS> ztw>(x^W;a-4oMtx=$8yW*6ZNpdKFTLkuSYTG!tcPbOlDWUb>(HIOk=<9$ zcYnx@AfB%vlKtgkr4IEn(ZriwWs#iu5}L~+ZEj!hRMc3q@X>U%4#@lC%0dx@n%P*- z?<-Gt9v8ekCQs&&7#)e5uZOpNl+p)=;UdB;r+GI|88%RTxc%|v+857&{oz)jW`D?b|(r1r&QO0Hg) z9zBc>jPYvwAL)c+2rRt<8$KR?D4NkR+<}UfhnC?JK2#)fr=y)+eo#E2ww| z)ekJaBjz;fckybuW|0q8;4hnsj6$rBQJ$^)@GFE8)|V;|4EdtL3nQPcx4fL& zL*evO(k|6ocG4aFOeE`l+U`I2F1+qS`RCpd*@fmmvY3$`KjtoQWMKHPU8eM0yCL5m zR(de=?Gd`VVf4>9G}kUamhy8tvQnQL%eKAVG=HmK%XvJo>KhuY{W8Zm7~Vd_tw_rD z+;O^yBt84%wyog&KFQ;IA-MHl;u*%1f$Ov*l$Gbdj$>~nUkfyj_W=*f&OXlkg8x?z zjKzc$d|2Y%3KfdwO}Z28VCz#9g%?+c=U05qc#Y^k`7(x5K?ADM5MD|`X|;USVA{VW zr|g~eaaBl`)A6`;2NwG6&gee&C{f;jzpgLg>ilPgEq^4Vnw2?OSr5hG+)Xz9(X;d9 zhq1VB$xoTbzLG~k(iR{^U+YB2F*=*Mm3VZZ67<2g)NISRXPpD%*Rjx>-2o-c2o4#B>)KiPD<7 zX>*A0x*EWX*uc|thL={k(sg$3-40?^qt=AGbJSRSfoZ)V#*Ba(>q?m)v5D!LNtB58 zjS(vS5t?&i86Km9lvTQyWkN;m+sO@`{j$N`-u%w*PH0$rn%W0HS3Xm&!jn@NNO!(A zy~3^eKI+`PJlC%UohspTE(l45r~`9;ihhY>ZVt&--nX7M694nBCo*x7ZT-VJWbI6g z{SC?|jdSfGbN;Pm(>OzH?BJ{q;&o{G{EH$tNJE02Cb2_?){I1!;e9JbNJj-MU@L%4rtanq?G5MrXZta$nfEMYBlLLBoMFd&V?M)BG}qyR&=u9b*?r~&dz{iw+vO?Q z&PCAGiBGxYW$Awd9u>yVlnIupsT}m$iiT&gTWgojp7U=F>AR1UM`RlMq^G(2imp}$ zw;0oB?F}|kg$RijPL^BW1MEMxtz~&0PKcN(xLYcz`E2@(vD;fa^k5>va8|jkfJeOb zbP^sbyNI=2kXuVwtQ+y!0}zRQ?c=&Y;d1g$J#i|h945jbXx@r2{q7!nXIu1^+piiAh#)Gq9i#o*+~J3(SZhGFRm9T*$_uPx zMgplmbmQN*@tJBOr=*t-_GxS=TCo|Q?=-;axmv%=Zf2!e1gW7WChezs|3i8DMbB)7 z%)5Aut=jaBNDD!_3$7^kQno%K&YGV=eyzHDiL}W|@y4T7ii9=cc#uaO`;flDI}lEV z3>Sn4;Lt}(<}Lm#HB9}OWiPy?aXbb#n+>P0m;JiCJic;1#ZQRH$Y8VuduP14hV=E% zi_7eFBP6NCHqt-=iY)P^`|#V=#D{fWm6PFTkMKATL8B0z!%D{sX@_t`Smmv|%Op9d zUcHCO`Vk%@@nxQEuekLMn4kdsodK66sPH=iAKjhvd}CtB4(heL@|^h z23Gy}sgI^&PUtVh@1iF&k3o;08O_kI9QAJEk7r`l_8KvWU5|BXqecPEJnRP4p1Y6Z zwsWzCo!(I1nyZZ83P;PXFQFN5XG&dp+Q>t*Y^%1Ut=B3$S+Hkgk=XmbE)*ilq;Z!)0cNy4<`+6YQ)al3@`RxbGK@&JN=BO zLD_4NcxSRWqxkD|w#uuR2+G;0?5LI`74LPAJAgb{30p4%)^@f0PBtB_#fSFk342L_ zf33aCswLzL;qs;?&Ae=7S#}CGKVB06QV%rbjotU%_vyLq)%SUsNiu8rsKtHHZ+Xn! zeH4Q@3@gej+peF~5?^iwjKg6gI2C=*QcF6al5V(WX5HmIf%|)_lxR2sv+~p5r(ibu zWBW7lzhi7qo4AvRF3G1QY``NvWLJ0W%v0Zt^fkZJU6QgcUcvfj*nJCLI~S1k$+{9e zevQD;T;3!kJM|qLn__1q<~!SM5kknYp~m6`D0#fT&X0d>kMew5>X^Chl#D}oWFP2e z(ZCf4`Jj>c}V>K zU=fa30aSTZc8eEd(i+CMw7!)1_jICkL=X9d1bRBoWhCQ3__(URJ=<}xD zFNw{OdGmaGv^Dq5qH^P3fu)inJDHa}aFx|xoftPghsN{1qyny-5w8ig_|{&3Veqg6 zgBm&7+OA32kOYI@t;#P8-&hL|%L@p{l)UH|g7F7vDE~C;Wf% zTy|AeW2D|=7t_c6J$;;+uNzT3KJR(v@+`BLKeZNKQTfBn>sUjZn ztzYvVmg11ojnSj#VNTR8U>t>}b282yal_1_=iQ30Zkydbs`sK|KnC%QAav%23gj3L06U{W3$zX+cTs( zAbl!Vfwh(7{nX1EaD52EM8r{d#M7e#v<}r{oHj5|mt<-~GdiXj82T5H43*aTuz5-9 z__?XEh?IU`441*ufmngmD?^Q|6~GP*-WI#W`*pco2>n%^2r;X!Ib_h8={o@lBh=5} zt_au=TaJ~+pj9bJANseYL5H%ME+cMR0=d**Q5}Lo?UPrapR(p^AwGb05mH$=e5sR- za~8J{9o5bPPx=5v>lz*RWwMHH4%_hC@Pvv&%of4b*Pj8Wd88c6q^l9Ekc3!k?pqly zSu%l--y{>OT46?Sj~y-(Pm3Ny#{yK6o_9ZunlOc;hFI4&ikv+veF^;PS44PEuVFe< z;hPbjARnSK!Fys<#wdR)f0xd-ZWXsUP3tov*QSl$Y$Q0Z&8>ew02eY zjl7(|AO~g7Sq778Nq`pZAxmihlu=z(X75>9 zF9+ps;FIJgjq3^aERo+3)vz_xJ;(&vt-qZ?$1RcZf!cbU-l>@^7RGrueb0QmUBey@ z#vk|jUA{xYdm?^6yGiB+sp5FNt*Z6VKa2$}yP_+;>+^FZ#m<85?p88yR_&`rryQFY z@js$$LpgWh`)mo(}FulR2s!u5B z<6{!sm5hOBicVH`oH#)+{hoHOVZMVmtt)H-^kBzvZTkocw05KK2pCs$^ znT+Zkj2#p0-eRh444UiVB-K>hTv`WVXtwk@>-!L$&U8}`-6xflxy_9uQ+em;RA~In z6x4cG=BYgYv+OL`=I8>&e(|i1HIA3djoYU_hzf$_De8C%&Verb%NU+br%)m z2S3(q4N0WWNBf11{LAX{B~So2h4I@1IJ<|`T@TVjanSPA?W2!LJN3VrqdWBuOTBo* zyWpp%o9zW&4DaBvoWC1)!A3pr6k9c@xP!7#+dy=ypL9JK&|LMZ(7T!&`n%V;c_yZ7 zw$(~v>?5el6&*KDaMeGEX=dBC3nEqVlTz) z@Fhd{o$iMC$wWY?D$P7KGVeU~9DMGO9u>|tCH6oD9qegND8ZUIT+(#WWgtc!X&3Wg zB7(T=F z_q_EaZk`Z4(y>RW%=<0F6Sv#dR*sWl)n&=h>;W*!Ng6PFBy$M2Vh$*a%nDCIR7=X?+jQ@R(hN;AB>pFlz?zm*Qt`wCWux)e zeLm6FwYqnn$m%ysnM`UEz)wTP%pb6`R^I|-cg&5Z*XH>Y@K_fTYiBK{N)(UP-!D9B zRh8TES25A+JM%2%0mBo-ptdwvRBMr>{l&%u%b@&m>up0NV%PVFfoz$$m_|p5xtMPAEo|}ADOr6MUi!RX4)0d!FwBBBJe6O@5F-z%<^-g(WslP z+CSBU?d~t=+4<#H!hbtUA3Jl6Xxm7S) z!OE?ZK!R&K0((;Kr%CnqjF@^gj_Ol^M>d~&4s#q3wi)4Jjpv0k7N=GV@}^mt&hQS( zufs;hIiJjv-r66!$Xu7;27JeK=m(j55@LED%0;W9XCA!71EtH-$J`q;Iv9 zmEOqe%%PUW_nZ=)1~N)3k}abey@up~YrUtn7F%nTXt6Y8;o}IwW+!~c>|?9H5En5&6;sM3?-tqhXK{`EIz*AB)8 z37oO$gx?p%os*KiU)AjWE}cV{a49Rr(K4*%5WXaSb5&do538r$#yrz0^gcDBlSDtGm3q`g# zV9iTTTf3e^z0pjV&3fk>LWKR;GT@bQpC4j$HcSu&AoJtGVjuZ3;vwTf=W9(}(N%7FjUeLGaAAzpj!s%?w1-_>lOL5MFT15*MOzKQq$|x2#*|GyzbJiKk0u<4s z{jtR*q+ok5E^~`M@qUr$DkWY@LumcJW;=Sb_?+=O!{r22Yv0bosC06;I9w6NiBIl$ zGKW-d-rq4tki(wM0D)tt=#j1x!YWcpN`Wkc<{x<2;q-U;MDJ8x+mvrzW`XWN-TU_p zx2BK<*V&ViPuAXV3H&c^3QpUeRhGMYKbf7T9X8)FE`AXfsyD4WZi@5#EYiP5*(g29 zVWk?WQ+hnKH5T<;y6IZ;j%qD{r5{{cA)TqI+24NR%e>A<-M;JvZa?z9{PHUdWB;%- zqwTE|XlnFFZTO*8SZCzIX}W={k4aTkY$3HX!n+K3O}`UG&G?WCn#*k*q_N+~#Pn;c8{G;$dWo8h57EQ& z?t?KanzfpxxWzfMz1D8Boi6=BG{x{!x^LI*Svw|<*StckI?VW(8YS60s~UjKo_p4l ztx$G4<~B$tzYb}&0>b8VXTE0Yu}K;S(3zVk75NWyXVMwd1vNo42M!HjjA~)iGds@O zqM#Y`6jg(`Si4`cOuK!?-_=YAetr4MdGA{hI44j`r%%f)^mrz6Y%fv3pDwNaz_L1x*)W@eNN-_#>X-{L`RpeF*)6I2b zHI_1mtJK8st9$cG`{ygpuv17eNrmfN!m4-JaQ*e^C+SZZpBiVf11hqbj$7@@wN3i{ zomuAkL9R4Jp=tz)MTa#dv|~bFUw%leDm;T}z8_We(ttC_Q>tvEN>5<|vf5MobNhx9 z*+Zs@u=IFFP#2Qmkf8sS?kT zvmcyRiNd>4lwoGVjDv}OnO5;}*1f0Lk75tCm#4lXXV^k)ht5UlP}A0MONMc7yp**- zmXibrQD}a}$!>ZzegQyFu}J*mW)G23T@GPAtjCByAsON*Ij%`w)gM&@sHt)r!{U zk+`wOZmGP%fOSMNlSg`yHG2ff$suFO7O- zi}1)*0?tNij0%F|HI45OTs$6B;65&FTX53IMZvi?W0KXvXOfuH7o>bG3X zk@63>pqy`D8r#~l(wEytgetAub+--0nx0^C;>|y&+QPPiRER|$p{!`ciT}EPwhW8BGuA)cfkN|RglUb%O0?=^*)bjSs1AKK z4m#|qK%I5XO)ugDZKc~={gq`RYYaYLm{A}whFpH3ZPSH>FYaOMWu&?p0+@o~xWAX9 zoVUBndzax|Qn5vXv>_nua;C~MLpZK32eS{u$GYTA7=l(SyLgZ>*+1N3x+{GBFoXg0 zV2UT?uLHUv6tr-$beGD^O*&4*MPDJx8@5B?uM(aa|9M~Bt+s96u4;~Dj06Lm@4bYq z3kc^A8nhK?k)zY;ju`>xTH26RO^Lg1!ZVgNX`~ty+LoQghwKZeCWrvh;LkhI(BGZp z^d`PUn(O~ufwls~3n|5GtUI>*&fP|gCSMJI0}g;A8kin~)lh<1zA&K%r`Pmhec8^) z6ah5JKnrM{t5Yjp_Q~=aUgow1c=51>x!c;o3P9UC*h!tUIafw#`o~+ZNRLzd?W})m zY*qcBl;I}Z!c|jUXY!P+EoG@?@O2Px>yObOOWPY?hggPwZB`r)yU70zDW=fOSJuGu z?QY>b{8Fuep#LWLha}^-1mdGY@h^1<^dop(*cd z^7@*D4)ImIQIRU^MzT`|+tqtq$<^oO>-}bivVlc)|06RC*QT5OwF~ItTE4)!_tA5~ zVDlT7-2=A9L%2V#F%Pm4L*Hc&p;AoL=Twf4@{;sW)VW(4cir@{JT@r_54koI>^J$X z5u3>;=g+NDRq$uS1OEhZUm-=Z$HpV7Y-Dl%lkA95H&C$qhT2l`JJKk63XX34!-w0v< zdapfk9pzPU767jbvYq_xX=OT-&}}`fvsYYs@#YVAU1~}`2XLlx>}C;PnuiImYM}H% zt-AF@Q`kDqc=-HsOoB7sn2w87UBJJ|B^>d{%}mQF#i6TAX~0BV%yke#$USa#dpm2_ z@YZP2oWkKef$J0MnQInDxC*ECIjI*WXS_kv9Fok>N{J^Bk6G`LjR2`;e~;>h&HKcd zVo}__q3MNzpK8a(!_A|Ox(Is?LT2A;-k#AcW!zYyxRtZ&6%e|b>_nR}@`$!+wn z4K>Q8^Z^qn5m$@|6tbGO@eZ)N^Jd7OsSehROvBLgd&s05nH^&K^4n!;G{?;Xp8xosN6ZyIHX zow82tgJ67!sLp4YrQjh(@bM_nVlKN~>V({3i!+Ca?ZMW|tEu>P;RO!Xo>w+E zH+VPWdk@v2hQgMe2=a?N`Bsy3-9bkpyFS(ZmB}Df;-32JEl4*d@chy4l2bdlO*Rum zcI|!=1>stqY6%&6kL>G$DGlWx4uLn99mlOb8~nJW#Dsg@ornafw((oI=#ZiI zz?m~ebhpU;jINhH8%K1mEm;$SDa%F0_qc@^Qh8EBijb4Rkh;Yt5+0o;6Pjrh_lt{v zlU;tH5ImC&AsqP_cIA1u4UM-Hae}Qwa`RO%;LkGNt+&zq-rF`m<^=oln)xn(_~fh$Fe(M z^nih&)ap8;tV0n#YL7xo=rpg*^D4zhqLD^w6=t(=%jII?)w-E2{B7OQT;)AwA|Dam7PqeqDzj3bV20~m&x3vN z3CZv6gs`KN~p?iYSHD%5G!LG%_^#6*)_-kZce{_d%mDbB5;5xYM@&gRsczGy2iyQD-@FMiPr zTAS)Vxh`L=nYck{)KP3saj0N^YS0;MB1R!#e|Yt(Hf+H{HS(DTU2o%x>sxxwzdJw-JS|}9VYpB~nRi^H^ABH^Vj_kv&VASn3{54?C z?Hx?d9kW!D{TIo2yj!_j+2azLx3fXrnYW&CwP5iL;c-oPO!)8r5C`hqjSVvyV`Z+r zVof`DGL96}kP4503>fJn9 zMNv>cR*%1AH&ZAAT`zIyC~~3=v}Pq{ovz=EAZpV);#&5i@14+xVKJHA)K%8wElVkq z6dAN+Xle#O{aw%{G0^%F!88lbdCQ&1aDvpv#*HNvPtBHTJglR@I)DXSXz(c(8gemK zF<-&A8fiLL=kfSqU0!Op_%U*4xBSVs+#?T_WApVl1yY|;SOkf?4?&x4x3<*sJFhJI zfV5^t)8R|{CT6S9#iX+GZo4C9G=8y~Fi~-X5w)lU^2eD&7UUlE+^02G@C~tUmJtDT zXeoC4z%d0fwdK(kZKi+wT=)1%f>30P!6VbTPx>QTnM_1HgY2IPOe)i?60a`rNF}3euo1GMssStceCH8L7G{VjE6A6 z z&|0P%j&5QfRSfkGx0w zKnIdujL9TRGFUJl#21{+V%bYDa<5Z6I1sP^B1$X@u-Z60ha7&stzSNH5&^AN7<~88 zP_)-&w0l@o;$h;X>HE&%N1AGM%{IjEdb}0et_t8abF+Dr0a$%1z_q$3@ z?yu#{NL;{R?z-#RKl=5kqUMr3gxm;{zCBw^f{f6}L0rG^5?g3-3l3|L`>4jc*h7jh zXed*+zwk5V`grkLKDDUAtJ~{v?xW6z?M0(YrMvcfXFdUer;=A#zM%)^apKw%;4d?U z?U&ox=+|CV&!#lNyH5MPAa1iL&k_$padHa)rsF9-LNg?WT>0sEt@xA#4hOH5**o<&u~ z^0gPKLl?u#Zr@17qvw%f2GvrmLr#A)hkVc01l48gB$-1Mlc=xJR{Cx2T<5aM-VcDm z_8!+nf!35MT(kHh>7+k=g zPdP0hjkq}36_4_Qw$e*LX2LUZ>H>)y7z7)~yrxXyt%PIQHaX{VO05&{(}Siaw=%Lo zC5O?BSnc0VNgw&=uDuRCNFZbhJbemuMy2ogTn<}Pu_7B3G3Vb3HM58lBzax>WpEv^ z=Xw5=a}cy^;UX8wq%F4_hx5kqL86^D$akDB*!m;)fRJ*|SwdOHs-n88iRZP>ix_tEqM;LYY(ZnJOS~RWoR0-Fa5g?>#eMS*qgU~ABq$Bph7qnF zsGc{sRl6O7OpadWWb&_>GwwO_Rk}#DF#_VNwfUQGzuRm0M(r%#YMnD7-Q6W2!U*Zk0n*)#NGK^tNu!kH=x&(gDCw>NqiZzp?&o=*Py4jv*s<%n z&i?;Sn(S;s&HBOO0ei2JzvmVGKtV{sAkxPP+CV7R!p?{3y#{_V!*0CbK#%(dq1_w| z4By{wx)cI`G*mPJ(!xPGm#E32j3UdmE=vYhe^2Ql5~JPs&p#=gU$HJK`EZ4~2{_zQ z(zTn|wQ@(+7=a~b=c~`X7Qo_Ow<7{WDU^MlL!y$H3#=8LNz|#Uw*wghZChxG5{0%g zln6xOt&)0VmWyW?@mA~Ux7Pz}BnyGq>Ce=JPK0O+>{(W935AeQwCm{|7z zunJQ%0QGADlhVgao)ka1zjkNbo=_WnPrs`+YRgbf;7PSVd{#7>fc|~Gto7zx+_GJS z<1=}ZVwNjig9Q)6UGufLg;)>B_c4*yt>)Kdn zsjr=vW~5h(P5DMsI!`HPYQyzHxWkeJABBa>;Zz{_jOK)|X&HM1>2^MHSl{eQJj*Sh zhKZCdwfev-vq0TAYXZ#I?WBJFn1kkY1V^;UF9vo~dL;Gur_tyBybfrxavqt44jg?! z$m;X8O=xH8T1fupuyFA}M~d-?0RSq$?~Tlu!n_LGu7zzcqY8}qXV3|p9{zZ ztZXV9&$z4KMHQb^Ni#Ea5a{6_tuQ**ruKNufD%|GCZ%av2bEqe>u#74wXPGAk3srd zyQg)gxjfoD(rv?IGS@)@SN5^MB;Z>^nSME1f2X&Uurgqh*DH5Qw_IQZ^OnU{iizPb zv(lwWrDGV*D^J{rY>9p5gqLdE>u)u2S)ZQXtY^Pm1b5!)6dO9Mx+SvD?zYI%)Kq1` zZWm7<_k!^fOJqD&ue)18*>rRQH`kK`0YD}TtMej>Vl`tr?NMCnC9Ln z5}mR0sg>(Lv|k?mFS9r#ZTqcvKNkVTcwGhz8H*+CGk0wkUZsbj&aCfs_MTtgw9n>` zHR}O|uy~n8Ip+(dIMun|a48IYAZPJU9(L8svpe$AKuxk}s28fb?oT<$Q^ zJ^-nfoW)z68V;+>s)Q#;DR4dWiwW+3Kev+jFXdRn&||ZGcpCGr+}3uDGZ;2Z+fAYO zzw~T{GAA%EI5);iLYcu>w&V zT9&3^yha?+`HIgJu*>aYz^q!cVLnFHx~X@}%EZoEbq-CU7@my|_jQJsTK2l~=z|Dv zh(G4Vwc0A?^@9%2snqcLTi<^`i{GE%Q`yo3NMM7jVIwaiENRZ`Vg3sHG{;|?0x!qk zCycq+^EjRMDR|N8XV$jy??dXY>)lK=TG+FBv>bt{R%s*OLxO;BU-c6VM0IPw9hkrg z7fv&Z%5?F8kFpPdrYZ$}zK15LyIlm~Eq-C+=|`~{jb7~9*X6_#Lb62l09ET{r8!mz zn-k`Y_^ZIHWB#B6zRSD;estcN-CfM{oA(T2TZ0TXLydZ9(|F@-XUjZ3d#SI5my?+# zwRxMKh{`4LOXK@c6+F8^0tCH3m+~-kb2e9>9Y`8n;8am=dUl3puh{P^e4V%oRU{r_ zHJe87Xm=U;Uohn5caf+6g#}>zn#9MPj9)Cc79=y#qahGEqLpdFV=;!gT zdgQ9txdMA7O~N%OrSb3ZUl}vYbOCczj3Z6)dSZHaYZ!kV|A;*H~i|28oc`Kil`dZcart~8{F%wS))Xp}hd zEnj>VBxdgA|Em)=gW@o3x`U47s~TIY41meM^w+H3jLMW?Rswxm|L0^_0pWhbeY`0^ z!f7XaY);afl4pae0t?q->nQz?GL;@fmrShBqdGub#j)K6JCOWIwE4@6D;^+ zCSsnIzIVePJAaU{Nt?cUOgTC-^^YO59PJl(aPLEIUxWv72%z<>p5ClK?zim(3A`$Z z2^Xya_3#l83FDS1|5z!dI?4zhZ-lCUIyCrsS;@%ZTo_%TUrg+SUy>B)C5zk?V5hfk z(L6Ij*Z8Th;&%?H>w7>WK3}XQKX?*6e<*^}&K?Xpd9zBar<*8Dw$od7%=_95;Og`# z;dMH?#yi2ZV-EIT`c+?lSzOnHI69UC8u z!L4-|jiRo#@WHnQ@UPP=A>LaeV4h`}5BZ(#0&CEPk_OdgNn($6k$rh@k+=VB1=;SH z4PquBWs=?uPbQI+$`E_nDYOp+z@=KAy^{c}hw+P2q+D=bHXY!^ZQTtJDi=~0txTC_ znfGff>?8|DpS1)LCOWa|hajei2N4R{Z$1xgFIGRE*0!+t?}=j#3R$ScbbtgW;dRKH zO(LWV|ArlFTKV53{cGL6Fhk$?&$SN^xAH(o!<%zT)6)5s#CZT*=K^1y9{%Kw47~r- zy!}=D+hwy)OZ-@UP@OBQb7x(N&JkCtX;9340ZKD+0Qtd3D(0|1!3dza>{_tzT<3$0 zcgEnm1cVdcqb3YpFN(0nX+wSzQibk|v(gHZx!14iW%6!`yTpr6b^A`ztL=%M|NWb$ zR|xN^$M^GIw=pNQoMLa(K|Q5bsOr5Csv)$>!G;P+0?x?lJGaMbf{Ecf4b*T%K76cZ zVgp%5DlH}%pIqvyWzUkR5fjWZ%BWPH)7^}x=ca75Zt)9_0Seq0(tYA7m|}o1x`lie zaG{@^My0KFOjU}(p>j|E{`_W$PXj}#7I0&l^0yV}>c#S)n8}hPgGCvPTkA*omwz$P z8C$Vt(*LIB#_qEY5>FbXrqGXz=c-RPCeDvR0XXFc_T*ysQ|#|qWt31Z$oCBc40^9g zvT%EVAVQPNWf8@JYDweKRPikE;l6=YO2yfg?VJ|_c0A_krY~Yfd~e1&7m+kb1}E0> z=grF?hLGR-idj~?`gqj~Bl<TjU#B^4r>jyA%3?%?vepV~ zaLTrG(pD0$xy2P6_^O{lSWmk&RK_ZV+fytR+D(^{Urc0@(l}_S5V>~cnILHzkkKQm zQUdQdNyY!SnCg_{?(+ArvmYT#MKANnys#(-Z83oVwc-$4!ou?9r0hC@Z*wsIo!^OX z00!*_wgQeB>J=#s3PULyz6Dl6y;WvO+l}jsr)8`bd?W*E_{mzX z#>D?PHrR(8vVixSO7uOt9cM6Mlc)?%^)`F1>LEvJeYB1t=5fG%h{)`G+SVB55hjJ7 zcJ+4d>Yf_-<0qF7Q;?)euPE9ox{M{W6=eI)K|@>=52Qlo#KJxNzjz!u!SB5=5g0b# zS3Phw;){R=#HJw2NXn2624G6$1ZMn-%|Tl(So7aln;CC(k}b z5+nqbl4($Fz{W`my0cvmMw}o*pM?;Vh+y>~WB#h~h)X4SNo_^9|9EFf)0Gy|!VCQj z;-2*ExkuFOc503eJIgaN^M@(=;I$HtR2NSAdHW$#ASl-xQ^$&p;=_=p+i1d+@ zZ~w}$y<4gi8}#&7fmts`mqRGNw`9a2$q54!| z#9iSGJzRcc1^&^P7+*?M#O3lj@0E~jS*3+^4$DQ6#Rssoq+nU37eC%%L5VeqE@%^wDee)Hkk@ zfh_Z>NzV^hajnsrb{c}0iN4SdYZ8-Z#hDq3Y={@(>p|OYC**i5>^1z0`Xy{&qB(C3 zS*ku-ah`ZDUp}bW3b%&X(FdP+`m3&3FaHd;h?q4L0By|WjSKPr7LO^k){@JDzi<~Y zuJfn)^BXujNW%-)j@8OQcfyH`S*RXKu&!`J(nuv0IrnvpQ-TSO}N@)DS}g`VhHM3L7f*tX;O@MACWyu4;_yViAzZ{99-!g}VCy2$ip zr&!h&*wBPI7I8_nx9mUE{FD?~7e?wr0N!}o5K^2m<9vrW55T#H1qFCPG)_yMh(?;xDq~@ z?TvKEq<(VEprDYPD@a|dP)ZmQlyGhR_i&C+mV7BdzAya^z-@Z=qdiwHW%$Q>?RIOryY6YZuoN~c@6*80zsHc<)6!X zh;-BIYj|n9bFv~43jl?EH8G7jJ-H|L7286TS$dt2Md5jmPY;%8`vnwXPF;tS^6{55 z>M?L9sZgEWE@c0X6DR2eH~&LC#`)__uB_(7h3JbM==;dGfz+T}>IZ42gE^pIA&-Wr z&o2;)I&%1p;ZKxGFKMws!-j8&9{4(cKxM*lfQ3dn)VSqBjx|gp5j0&{xvTRf%X9v> z>w&f_bp<;Gck3V)slcD&73VMX%j^P8Cy(kT`r!Mma-(jq;m)B$Fp9 zWA?9rb8kQ##&YshGu1U(<}_XIC&OFbHvzfTAIKpA0$~h!EEyOZ%&h}Kue%@EKg2@` zBHDr}ZHT(Nq+isNL!#;~rM0+)LpvMcBu4*kom`2gLH^l&0AJWO^4u|!jQ56D8GMQmpl-sRW42EJ zBN)9LztGtEb*ks#YI+6DiOR)Hy&t`!6+-@R%Se% zgg;bA*vHES#=|5pb5*x*Lo2vcjvj>fZFXj9MX~vhqa_VeFz{H-JubYf;zD#eBXTto z7p!1{ZZco^f{uc-F!_Wnr{nI(vqwCCZ8y zTy!|$88+lCC2OyieiTAxhDeXcMrG#B=@g89BY%0-xI}6wRxd%#4Vv|Yv?PlX}g5a-9jA#{|9Z@hyaVfks&ecovx7pZrIj+Q1UKqxFF-4Hk$Z zC6+0eV6`+eXx_57t$PrKKij+zJ6>7k?_el9d*r;zVMl0D`{JGe)WM#Ut@HoE`4E9C z-f3YxUWM0yRCAta_$WD!ff3I|`sfRgkXCT>{Mws!J=3UGN7HzZ_gR^Emb+TcEv1mD z@;_{pO#Wn^(@N0|*TZmj2SMY9U^HeLST?hkYjn4|8&iyv}+8rCAg zf4H=M9wXKW26pNxqDi_&UycR1CkZ7o~>`^DI}qNFj-s`jPDIN2;C=2@(xaM}cp` z;d4~4N{}ou11+MUEolBaVlf)FV?Ymc<~j!>bSUYRe0(9WLiLrWeijQLzJ=M0B`wpC zt+nWFP~PR;#v$jDT}4607jE5N!aL(A`5l{Ye)Qn0_q#5CsiIa|jywIn*=Ij?%Uw43 z@w8trwD07CKA$%0=6x2B)Z=MxG|ci~f)UrR-#zJbpUo|Iy7$eg7#@X!a`pm$t9-@E z&1LMXQXXK}Qp3D_*sywYRIEAHDzzKs3KhRQ-xHKt?>6?I2Y)X%Nz#&eIUF74xfSVm zpdvFS-_@iZYLG%NJ_Q+_rReU}=b~PKu^D%zP)fyK&($J=&6;Wk*DkV3qq*QR(njre zjl6?+BWt`^c9BT()m(-jfXY&XcizFUD3BUw-uY`j%e9A$f8U1w%=lN<+m`a zMNAO28r``H;qS}Dm57KOP9#2Ta#)Ep+U+Y5e-|R3)~*GAKNpX;)u4#%)xmAWxhyH% z4(#H#Yg-)LM}#6O`Af<%J+2fJWm#z53$`Tn870JBo;Vy%f=V!o@Ph{r{dekoH%1rI z^%njOHy%sMrkk!!qs>mGOob*m9qeB5My-J@t@DA&NaEYxNu{DQor?&Ol551TM+;(x zJJ{9pv4r!7vG9po_T|?SE|Yg0dTVS8+i1~z_`^RGD<^ahF2?wnqOJIf<~?ts!#GvQ zzE&4(`ne?zO2b`|pn(5;qkO^>by9JD zJ{tC}n%XSPjC>;zd7|T;V30S|jX@;sZf(n6AWt(5d?Yxebz@mup})tD4+2+*t_ z_#qWu=6(SxThV`C=Ty2Z&}w5M9jKQ=$@n@cbVXM_)t#|%sS=|fWub$pbRnI95w;`Zet8b`Dh2Ha3 z5z#OEJ8Yk}a`9~^5-cFgEz~*TliO0T%GUUn*=4*dsp@~QkJMT&Kc{|s^frJlr?;>l z1J4|SG5Mb>LaZDZ^z%s^pk?!7zNy{j-{AL5=?JPL2}j*+U8|0E@TYkq6P_6lgY9>S zjIHPNB7b7^13TnN2h^ z6>lD79y`ZVygYoh?K+S7v)F{O<|z!y$G+3O&ik#y@91(75QAFn-h=OFjx2GveqF*N zfb19M>?a zYV8NNfB3&yfX7w%mL&9Uv=yX9u-7?9D@bWi z1QYe)Hquno((|yr-`t6NZ3JiS?ET~Kz-P^aQ|+(m)TPdXZc*trWN(pPdJ*42eN5zB z*&LZar>s%PZ4&!(YdYb#+@o*_IcH7zSY;5F@+Sdmu`QgpDZBr}<6W zoJZqx>9lP$O_PY=VQf>FZ@+9HM0RI%9c_2^B>t%QEz%=MOFOf;NS-4o6pJ)|eW($AS`w@%QS&Y@#QvRi1jrn)RId!)<4 z{eXjY$K0O%MDR;~r=Nr8O3QRKU3dn^aGqb4#V@xb-?HLFPygcM0sr0goiviAz+&?E zfU0DnUt!zV@x|4Q?>0DXO?fQh(JO`&wmhIBNJf$B`yaT`!7y?*XjSl5dj<+{z>IHD0yit165fHH}x>kEJ z=)V&mkVV)Xm= zV0nEI-K;$?E=tnCO^=H+!9hpTkoH%UiBOoD+yL7OumRP(KqqyweO*LaqfpL zM>BQR2|dR2-NKFbL`|`%(6$F+ne~tuVamtoq+a9sr6o>UBmtJbW6o_4`UA*MrLW!O zTXo)uEpf5LW@J2mqqzKKi|zWX0HuflDtT z=JO?3yTNTRoQCkU|Jpx^s{dCRnpDYJzZ76%t48If;NpW>)p~mM#skGn3`Sciirf%< zSky&}3|TAE9cOw;&s()qZ@|q3Wjf_YY*rL@Z662+j|swjni-dWej=UzbWJg%O&H*M zk#0_JGry`q=oq8ww7YVzstYv2J1hSE&i6&M0>7x=Hd1(P>({#oP24yIprGA5*01De zx85Vsfd>Q5%$ixDSh$wRZH9b<)lT{%dJ!8N_>BoYS*iKjK_25;gTP)j6+J3 zHPnROT-`Vwp1ga|CXd62bzRoN=TC>QEF_w2lQ#X ziBhjO4ykgQ{gk;o1Z=?ESaKg0th6+3*Yg#0Zv9VkQsnjNWSPVMW>QIP)htD(%sbd} zz4OK7?jAmT(8H6t#%SUh*cPH8FK>KJWL-q&Vj*RkUDQ~X$7W`ebhv)&8pu^|4P+i$*u^&?VRZB-1Q zwFY2t{CbM5*DFg0!ZKhy*t7_6g}AGTtNo^4hZnUf9`GXlOwhgMhZN4T1UNGE`Fc9s z@k+l--4su)&ga{|dsD^1zLc(x)}XJlN1+<)3U@U)RJ!aMd6&h!D{&?=RXuWU z1=l}1DxBV)LUz(6DDR}?xoAKFv|2jwC}t$nQ+BjT;7BAE6IVuwDJ7iZI^7>=O zeomcZd6gHUWpc;H`Y^dvVJqUso__0AB04ij>)0$lQ&;h z1g$g=XQ_9O@Koi@GP*3RDJcej!F2#5I3O zonU)8(JJXzM%I3l8@Y!o9KzlF!tICIC0-IGfti3EPb%*`PgF75Dl!Hx0koDtZxH#9h(zQa1fZ8Ue^~pM zz>5%S)JYxb*o%49m1?-lq>uqmpoZLI$ict@wFE;C0nN}#qkEz?=(YMdYP zvUyfRpYw`=b0NB1khVQ8;+jT&e10Z)>)>+c#=b$NHDi`Z+HWWZ0XzF^Af=moO$rH( zc1}qn4wSl~>g;}DyO|_>_e*-~Q{LOLTy3&FZK0-eE}uw?pF7GX8GDo46U|`Om%Q|E zC_lRo>b_KD63btF@MakbWJh{_K8dS04$@=@#5~Y8m56IU6Gt(Y)Nix9)+t0F02z#n zrFZOah@Vz;W`FD4KCu_Tslx+aVXbdioxvH3of8o+e)Ni08LGRZG2E-wmF~!LiVNJ1 zP+9wA$L4*&KJ$=s)GTYDQoMa*d@RVkM_bW_w@8~A?vj=Q(y}cFFr?e#AkC+d7#c+c z$Ei*&T?t&ZiAW6xW?j_l>n~qc>lPurA;nZ{=5jk>bpQmsWa!zKh`y<3Er8ON&BRnQ z`TG=>NofDAVjtRm`teskGVHgC4PtFh>`qZwC9dXk*3e*cX@SwJx%^+i;kwNnYqP&v zlhZP^oF;!>%cc!gsxxx}++WhPMNb1mJDeo0SEmM(e`R^e&QnZc|4p|`4*k}kUns`# z<9%#?*_9X_015{5O5M1rsUei>*sdH`$)?*>gRn}{>YPGA95W~?`O;VBBPe!z8OM? zSbh36DYMZ{=V!g^Qbh0pXaltsB@Tko`ayoS%{~%eW!jjU^=!ng`xztbT|mgQH@uYm zp_AXqB}zD))IKhQwRX*2?`D{nQ?mn74K)~r3l{2Rt!Q(43!kqSKYWMHPf8y_yWG{J znNoqbb-WUVQy6%mZ9)7F3jf^$w2gVy)H2wzYk||_4Z_cLpcIbMb_*r&8&*tZoW_ux z4v8{g@AJG%VwiNAhU8|?=xyFo&!4%mGTpy+5&tyD%*9R@UGOi=Vrj6W=I+xL#inpd zeY&++{Wn=wW8mdF`i*8j*`5K(Bf@wKtA~c(IL0v1Iy`!tygHOy+9XL*ifWZ#I&sunj4O%Hu z*nss#?%rJooooN~x)KVs;9do&td;7eU%3oXEd2QT2m(S$J*hcMX)w^E%rR{Inhf=Xu8qhyTGC3G1yJ3g53DL%!tnO8m4Hm;@ zfRmnnTjjH@Zbg`L9zBKXpqqmu2&u7@ni`{M186SU)4z$}$>(N8Zlk?GJVzx4)PNHk zx11M#jtF4P3!HjiI`0La&7baeL?QwTu8DrbmNm;i0WM&Q?JB%9Nt#{vL}9RJr`gNj z3BJsu$QOsybnXpckw(yuiNb|fwg)2Y^-rcLLXkd8Ph8}r?y7_u&C9JQA$DJ#kD!cHXnFkC^RnuB8OY;i8;0br9McLascKII!uf3taK`9S+w?3ht z49nfoRr7Ss@7mV;ogPvV%y->5^9(qy)sLVVVw2Nlj_ikM?v~4Hp|rKmd`KF`0m*yO zp)T;7k(D4Q^65uToz zw>RZ19nB;i$jkgowLBDO9-S*^93*=fw*0pa&jA{>!uLf>$@CiTbiBBrU&VaYE?r|w zn5gcbPjDYS;PqN(wXzB$IZnBY?7HQC`(eXTO=ym_iCKe<8GyVF&U4fGt?5=^R(Z@l z-+RD3<0yWjk-xAy=upi8nxYS6nf@V^mvStj%*=U)gNKN1bM!FqvE)jr1iaF*vhI4O``BvoOW;mWBH3*E6T}DW?g{xx|^`G-zJi)A-Do7CE z!DDg~60^*J5!*0(XMGg5w+r&|hFf+%WfGY-`36*EEjEK(QFg)ufm&^v&FNaFuMJT_()5JhyY4q4yPGC)uQJZs|q+L%xHqtAyTH zu?j;ArgM+PTp{mSDf%Y7yi9A!BE7*f-u+geU%y==-3dv|GLGkSDvxoUEu_LdDf_A# zbtCx7$z*8_Stdd)F`RfPu6=wI_CZ%5@WBAAYk^-am7HSx91$` zoZ+u5-9Ts6Rk!d9_7}v5hl280bl3ab&v!>&3#GJqanC;qRP5NM5T-=Sc;qbIs2#vh zy&dw`={CBuy&q|%$%_(?lm6aSppJB8sB>1ynALN;b54wB#6JZ4y|9dC$%O2&C%}o9 z@iJZQf~23L;S)eYDdNR!k{pXO07b~qDj_nG-uC_m=JqO_(l_WIKGdqKa!S!^<|ZV* zI(u7ay1Ga%zu93kuzK3z&p+cxn^1G(6vxB6zJE5hUR}EOQ{_Gm+YA8-EoL&L5;^qv z2uslWvh~7T0a9<-eX4T)h{N6QgXRgS>}f!v1NAMFvr5e4r~xiaR<@9ru^0{fK@Sc> zi)>Zk1{BQsYnPF=U?EB5QO~N6$YLnvwNuMj117q+@YNUcNnEr74a=~2AH_`WwtiZ( zu~JX8s^}sqcpc6|pNCVeO7&^NMWo3lOTb@jJ(a~-rj4q6ogV~fXBX0#)e)QF_0z%` z#hhnk7eS#aQIKuKDF{t|Ts`Hv2Vije-)epnYVyd#r}|Q2BlGf~4R|;S+j=q>#w|wu z2)_GMwJx0KK?}z-y2wG9z@DXBj=jp+$LW$KJY0V32_3^csmto+FUjdN5&U&&)C)~% z!I<}m8<%}3=b09du?V#&Kbp~ui-tzSna-eucGOzHTsinb9vZMgJN<`v!|c*SrVuHi zmi?RFDU@Flu9u#nDx`3$*6-@C2|P#0c!T}XF%49R%^voc7EKQA)Y}>wGfx`TIrM>P zG7*1B+KA}`${r>Q;*5e1!dr9Fjs3ljAHS`0JEmec->VP+u$xgfaKEkkpyVO_SPfpm zd0ae+LAybui97ddQ63XGm7|`WOP%^BC&HnFrzD1RC-d2}a~POF_0TvIpfrAgnMpUS zEZ&Iqd7vBFlF;6JYBQAB?35zqmsfEtl%#3|Pk#X%gz>RnDIwb%4k{2$REuq{nW41p zMm?33udzRf>8N7iK%u-|0h6D)zO`3E-mZ!g_q*~_%D`9!*i@9(Vx}Sc8>LL9yIQ~{ zXJ_&2E8{Lf+U^~39Yp8Bfla|p56H4BA?clTUN-Ro8d@Mdu<(0Wb9zk0Yz5_#oANWH zly+SyW5oE>Y3LGRpFTHyIZw+pn$U7MT4J7AK|Pcr%*XEoqdj*pT9$?N14r;IW|%Xd z%EQ;D+vhnPS!kX|Jibxl%`I4mrLgvP$Tar+GM-I$;UrkFj(ge=2Ud6gHfW!}wRn^j zQr&&G!M$AGsKJ=))NG=;WP7VB|5LVMxL9}VdI?KI)bgS@&{OIJ*lNtnYmo63xg2+CR%o`fq*hdXql+}*ThHDb1>E>QzJj zX{H@cmD{Qn_2EX%uVcS`*Q3Og@xx?74{zE-{!lz)v-TF*1?kXi^yeg0RU@3^DOWxT z{Vy+ihh|#Hp7~34Pv9`NNn((}RqdZh1Jg6KaxGRB_LeYMp!j&f<{rYe53I8ocE3EF zB;9($0lLY)uP4`xTHq z=f-IucOtUu1u!`<_q&1eqT^_6ja7S+N=V}QEy=u{CKtFKJZI<+m6|~WkT&O?U~Z&> zcaenhGd5M7o7CCvFxuwVXl~jl{J9_0Opk5N0y*8OdT+=uD;dd)``N*DXu&4Bh#wmN z#zJYod5|NqUW1Ec;!Jx{wB>6JDCvBS;ee=KuQJs~Ez)WLTJ#_saVEn--_YL5Q>+_# ze%zOlbdY6vSPTVFVP~d6KbfbwUVnDaR(c*fhN5@jH}vN@x^CLpQQMIzt}%rl?(I@u<&7ktju{7(-PYF|HGaQM%mzX-P01t))>hq6D^$ zb>*mQ>A>!?nwp}WW5pegffT8QHH0YpMKvo$L40NDp^SL3*;fq4?++Z+{k`J3Gl*O} z2VD+dKl}tVp`$suQPC7G-{z1?=;5oaB!Y=tk*%3Yl^-@f*Hrav=9$%@_+e=rpn0H8 zN@NxJg_JPbL@GE}sm_13=vzAC7YEdxpb{!x^spX!UlFcuHC`LG8^dltQC(86JtJq| z2BXn@c>7l_is-MUNo581@QM%%5iV=KdNFme&pJ&-d?;6H|ZyP z%6&?P%v3f(_okpoYo|oc1mABaC4E+g;w5fY+zkSi7^;-YXb*A?oF~0;2!aB`VQ6c| zXas%i!y?SowHkir+k|OFE+|`#hepGhuer8b9i{0?rbFWq1xf5F(>+oAj!q>{YHz4e zN9)6t*>FsH#_@OCaOO^{yS1j(4yE;*20^eAtgKo7REXkB_;_rAlud%ovc$s`wK3(} z%Y_Ygtmy6Rh&R$w2}WH$6mPgUZYipUlOpHkAvC4M%YRc|4SDTfuX3WB&Mj;aR*CtZ zIE{>_LSJ>9p8Qdf@=iR{ZCm3c87z9UryNPh{S?<`?`Vx^(U67Of$I?SXUSc=QmR4eH~5HO(L$vaL;yW zI2sm!X+ugRW9bC2+*2&%OR)WGnIS(Dlzwp-e{bcLdi&}q71lv92lYp0+%W$PU8)8T zwVljIz@3xE>y)B`ij&IQzsvOIfcuP#SD>PCp zcW+$3tD7ZScpu1ozf-}hvslKTa=}n!MzFy!d(vPHOB?!N!rceQ`S}a`3y3EYjiGXd zl4}4tCu+d7cj+N!6;d|E(ro8;aIF}3?RHBpY>cWQD)tJ;x=nG0)?{V-EfVs|otWk3 zzoJSKP9Rc8&y^$nR zQ0*V->LoEUv}oPrXwiT4pN`X78T6qc@ws;KvfO2qTrztm`6P87fR!)WSxb; zNoSZtgXJ_w*Ex|xqa-PXfNbmB=(BNK44DmLM`K7M=5)Z5z8A;z%6aK;rrf&vyy=3en$aNQX z!=E1(N(A;WRy1oFH9U&u;l=hP*DnD`=XxZu5CzVLDQ!=+Y&4}+%WQ{QFoyT9lNINB z8)){}U~!YndRy*b=oQ-+=?#qKh{$;DMTtxRb#veWu zuhIpPrmBSFJI;DHM%0@3D9z?@su2rd&&(TR!MSY0SpMr0I zC`7N}@m|bwfHg37lcudB6~oASYPMD*QeDyS1W4J>Cn227#T^T;w-mKG!4D7o`;QXK z%R;{$$)ial3At17HPXR?v$6Xki`nl89_A&+T_RVb+C|Nlexto}PN& zbn5*v3sKLybeh(8bQ(`zInpmWpRbXdU{FmrHrpiSed;v732Rxu=vlUqeGfceD1}M}$qfSR(vp zbn;mO39PbwNEfpPj)xkYJ-u?^IJ@b-M)xF`y!Peqq@(PExhRBI6$F(bpb(nI;^^VL z$Z_wIafLJQLYzsWR|3qB5zWpsH;#ib4jg7i@12uP(F4Ggwp=I4PukjEvY1|e8Xdbw zcQ^&2!Z1KdN?tkuo&0P-_*w}tD*k@_Qk+zhkz=pd=(ZwhYWzp7QwLhw4F)-&O(Z70 z8U)}3uW?`JPjC`6hRAcpZ_QEmpu12um_@^w)0>bZ+#-D%LQR}RRx3OIWs!~Gq#(tq zmTC)dJ4KO9a(Ik4voYh4j9R+%WI^oJ0WECg#Vs^um5mvyX%o1*zxru~g=})S9BJ}U zEy=ENdKdyDUcDBNZk`nxT3W`7M-bo0wo3+grSjbYl}1*k@*x<*bDi1-yH!23w~k7# znNB-l*66O&pBw-tK}v=6;dSz*)P3BT^YppU<}w`X?N;|(imaC1urib{Np;PZU-;=+UPqtyCgWrsp6=) zkc=xSe>&R(1{Yftf7hk)#=B~AiwjQi?Z3ZM(=Uv&V>Ee%p4x1O?O-vDM+tF)X#2Vu zmqcegy~?@qiv5uzwa=UAe_dvrJg+ZESG_Wf>yHoCAEc#|l4Yw%Uvh$+-Mv05U0knL z>`as!75g4AI2E&iw7Cqrb4yiS8l-{_;~eIQM95Ah8nj}sO-vaY@0IuJ_0J5sk9E1> z+DZzOHn4WRaxf7pS3OGEnIk-K_Lw|#%jNr<{YMfQxEk(u-mwutmFsh3)*FJ`GQS-To&GnUk@U~a}@ZCtv>qD$(csu zT=6>nEf$v6qDBJ&b~U+o|2GSu5d`2xihYo-DioFwI&af^r90)jH7A!5nlJIC#pjr1 z>=N0y61?vAQSMeKyGZJMZmrARym&ga^^1wKWa%7P3;T_OaYWK&fk|E)TJU0wdwfWm z%nS}!?eqzc?r(oS2uzxM!l=mP!{;WAgsA5u=6K6ZlVUBR@WKeWEN_cDn}oylhHDq( zhCI|lyv6m7E!4d?cY5;NQhd#xDcxaRVWm^ajb}tXlFbiX4y>k&aG9SPOVl^-K40NfH3w3{iflUW=}8u>JI7pzQ~H2`xlLH2)E zcZ#on1l0}q_Y;O=vuRKg59i~4(1#Nnm#SjDzt4T#IhAGF>j0$3944M3XdyqncU(*+ z->2LrpLDnVZaUsAS>6;l+j_r6%{75J65uP3c5@53=5`@gx-qCZ?PqS=C+HHJ4L)k1 z*pme?Yn0cA2@a@PbeAtvLuF^&igg;7)hhkdsNN3a(yB8 ztH#6o6V8s{pPI{2!Z{L9l@;T5H+j?#H4TFCrRSCgO)7iLH*-zsP%vDgT_b*5b;LOT zw0^qjG2CPDYfqE->@CvjfX8ig^$?^BVRyN)O-bq4fzv~%u1&9?`=|XFSnd5VucuC_ zOvoxh=Vkg#YXn?(Qu-;d=7>B!WK?dIqqbzkC`4)5JEi^V^rQB@V?ZXgnSmlw(}E>I zuEOtxcYeTP@X%J5f@W2nQvz^FVQ=z*QCSMZtQRg>BCf{QZ2wSn&387}W1R0a`rWYL zYv@# z{uzrkSJTmiT79lo4?GoL+gi;lwm|A}M6RR5y1GIsYb1h6PJ8~@F2MfQ>d7>vkE#De z*3*EI%iXv-iyP$|Qx~4<`09q_?WxYGp7Gb@cE4(xkn|IR?Qr4b#_-C|>WyE--eQS6 z?b~>{11C>o!X-Wf?{%(r!^w)Z&LQtAge-}Z?z?v6Y%H*KdQtp3m#$1Vyc)`L8Kw)2 zkXq8d4YfGoli(6kLUCxlA4IN$<`F=$4;j$*4D>Z|3Oz`!t&p!7b{V|2P)~7}zReA8 zdXbT@VzxxpXJ&tp&bmL=@w%oEPhV?uM8F38+Q^rSzxKxT!l`hGpS@ib=z+d+d4L!@ zL(b)_4@kT~TK$Gy1e<4+r}Kt+IR}9kzO7zKGOJDI6%KM*`95*0;|3>nCTFBa6utL| z1?{dWyYq&a10X1*I1;{Zf4NvVYN^hyv_5PtbJ4U*8Ien3OsYt1-%(S>tzI-`O!gf)nZPxFaF3tWa-7Fgo! zqG^lufv)WJgaEPV@OlL`*8eU{qIr!8w zjVtdwSlqiBO-}(Rj@AJH`v0j5aHjr$G@bQZlaJTOM~5OM-69|@NK1pHgdk&d=jf1b zDM^v;?uOCb-Q5kNyGA_we6Q>I1NPIs?LOxnufvr&2QKg_8)>J(5vKpQcl(s;c@!5? zt+mk3X&GBn48j+~Y~uO*T64V++q6z+7%JWBaI8s)xr>l60Hg{M_jxD8j(k1>UCCTN zbor}M=eAMS>nDhVoq-bl4vJDTu;WyW|0g^AHU}U@ubTJeM)exS3*lH*>NIvY&4@k< zVJ+R^7W$IE zg{mcTcFn#SdQKiVfE3JU*1Li~)0Uq�w_*vS9s6A~P6TGn&SSwwes6Ew}SpL|K!I znRJjgI?vYYYT_uW{Q-II@-jB`y{cQJIsiBL3H2=|HT{NpY?l?y9+!(=@8ruDt11a= z-f@mEqyry8u-pMuceXuOh)=u?w^Rzf!kP~Qo)l899f*|=@nd31*0c-tke8% zk|;IXFpmCkIB*f--hPNadZ3~A*n$me#NIE0EgTUIi{|Bd-UwBcmKE5-1k_+6E5Xoy z;p-S0{*vCAqaIG04th{CLKD7&Qxrx6@?W|qV2P9Y!%`p6nrVZl)X(|Rv}RV*Pj%cQ z!(RN6+vKekSvC$R33jk1!;TD`WTy5tLWp0x{g9(Y=>t__J21IVx^9{nLc)&o^Jah4 zA7$n-CR~^+U6N`}11lHp`vw<3?Bh`Gi~WH#I4}Mxjge+qOjcK@0$f&j+tkgXW%2Xn z;gi0*3gze!#Adn4%3j&$ngTE04STZ}y*TWT70@}DQ+@`MqOCoubMZ#pAL5s(F-!%XE2OX?aTtybV1AKlf~3dBJ%&G)&j$l=Vt;Os&6J&_^)z zy$->btO`{uy9e;N-|fA~>m#-&?1s1Z$fiARuo@; z&KLbm5N3GN>i1zLuk56;UsY(*HEcYJ71B1NPFR{23oWcLfptOpU!iSBw>Mw3HguBg zC+Uc^ZdTl}(3sz~hoJ<$K0QBZWaKPYHEZ(iEl+$kK+~v-Z~lTL(uVe{{i(Z!k;&s)l6|x&#`9U?!+i4o%n)hrwx&TA zfjH+{)A)l=Bljn818L*ZX#hF@rNy)DlY4r>dVY(+YUBuN#SWuAm3%@>oWorbQp=52 z(TGb@VBI=5rL_u_rRu5x2dc=9O;z6Peqc9Tw#QC9$I zDO`SUmTkrC&^lufXm+=D^`nw~6;$opwKqMz%7RBn5S_g5E-!AGT%{I@x05*>7?Ea* z)b!u$Ca`dn5Yw1D>j3`|XQEIrVDy+H3FKcLxUXdentYzwvy@lhhc(X0yt5$Sp4{uY z)jZ%-j)#WgC^0{lZ%t2Iz;VlkJz3^%}(Zbm<{iRE!#kr{q+W&=pNm- zxwhWFzs*hV!|zI-8@Q8>#>p0p@W)U&Rv4dO<_OiNek!eC8;_D@3)N2`acr$y#J+4@ zSx`#4xJ{QZqUZdyp)Pn?!>9FiIQlKci79}WKVRnLjS`#rAG zAKMCy{n3WDdDK6<4RNVW%%E=pvjqzHnCKnbbrJJ zG8L&kPiWSAX!rzFKLzO$PvlBW8a=_hMv=~A8f9Ho@8=Bzg?trK!Q6HFOiDqrb%p1KcR81# ze+$ej`-E)H$%G?CoBJqv$B;q*BGw`9(6Id?@58s*P3N?&--Zn{bF$osRa4+IpYK05BPT9+L)VMfCJjFK)?9%b za;eFy0r;PwB#h_ca4g^0<4`xvIhkv6Pgmqky<`@q*XvkTnZYHsDsz@3J>F5C@E7)| zRND1XhvXV{SYxpo=rV04=_)wZxYRYusjgO8b2*OWwGDBg+#-u(H@IEcr`&p+)GvP+ zwec6auk-2|skC#;pWVJLA(F9~EV00MwpCKm!^UYcW2sC*%obFFL9wMVEMmr)Ldh*% zoV@Akr1{ME!bn1<(8?jtAr7|DC%|FFlT`m1o)&)m3cWyf=?va1cL&0vc4C2gKQE#T zb={xS1ML~jZkDbB0_$&fv9H5HUQ1nL7z;0VjkUQmpw~2E#ak#;NqvoYaqN6gHlF;2 z;s--3lg5(@?+YUrLqJP9cz3-3|DXA2UQrg7#FYY%Zb!*RE%i^obVPuT7i^`cyxy_A zyFc3zaDLgC&2^orRIR3E5dEaWLb?<1KDSSLEf-bPgjRWHNDq8HKI6DjptU*^38=UIQNPw37heGzP3PodOr2*+vX4@@+9`8v%2GMMo^Ah^)d~KC#-*U~Zx>nhb1y`pHi(w0kLrofEm`tsSqos}LYaK8b zMl6`fsU5x?+sVj!h+CT>THAA(S)}18jkO%E2!arRJiF6nc6l|!`csj+Q=}vOOcv7e zPN&Dy+bnjAN$-&p)kt&X9U%qr7oH&w{{J8vH)RZ(PS@g8 zekOxc^&iO~E9$2|+jL8*lJl7<BjNsKe&b2-xOlGT7C_I?maBNz13$<11aav z`zorK#^KhTab|GsP3aR~zL9f4@=*PDDofz|6Q`1K!C3oR;8O*5 zq^kE06_W2h(Da?_kt5gn-alB?45z>CJRDS_Nuk!;7~?@&2#zk-+ORD(qrS>_xHFPZ z7rEs>s=gpfSKhkHS|$C-vVdDMeW>qRfO5bKpCWm5kFd-{KUoj)Ivyu2ddeBwHkC}d zRLK1`YnXZu|GPxFCeDOufB4KjU;X=INdZd*j}3JUuRQ_6Jt~%sJvPD*#3KKzdt47I zT>U!5L|PlRtxIvND)Z|GMy+}-_MVt{iw}#~i;o{SQ_ZM!50X>^_@x`~T-{v1aLE;{ zer-1pwXS@C9gVsSBwvlUzaae=8LY%6BX^fQend2DZ~u9{GthqLsLY0-vtGw-iiFN_ z{!=F0P19$GBVrGDSY)Fh%Hd7%-yB}{A3Eavicw#j{pOAR4H zyGjN>Dc&+WEW)#n>2I4%i4U_-O6>&EA#D3Cit%wOPUm{vKP0)eX6f<%cbqvw)OgM< zd!9f8t(5)I_Ik|hjw#mbyTr{Tg~j0K3VfOJmGpSqe%*0~Y|JvG?jumW29iig`Coe$ zgbsOCpEGiSd0o|{AJ?=W&eY1Qu0-zIoZozu)h`-1AR}fv|I2sqL|zy!zp$*QcU#MFK=E-E*#ikg3bS;~exwEX-U-C7_KCkS*l z!FnYOmMvL|pLF~&GoJT9XYbEO#&nEUpY-8WKAiv?BcP^Nn82>FS4iBg%8SFI8`t@J z1?o?GChmpIKHTpes4|33nk%JsP3&Fn5r(hL`7INs8UeGbC@0X#O7k}XJxCkmY*V}o z1)AYk=1J8w?A{4uLcAOA>yP@C1xxKaI7|^B;w5WCPlP4)a~zeGEoV(9MoXg3;AaAX zz@RVbXi@S1%k-V2vWL9k@@%(|tA#wp}uIz-K z2%=lNDxnua48&~pIC4GIQ#i7^vX0$#>!{_)+}GLL$u3pkK!e7Kd=E8f1FF?+5-T-3 z0{U$skQJoQaK@f6-piEV!$R{}en|t%mw4TX=otLv|jAp)UvZ|`NoQYvL-6FV!1A*$ODp?&v*n9zP^5kbIw4u^@A z{Jtw4@n@D%3ludUGh9agj~K%Km?)xnS(9MNOBU#20u{5rE#u+<0fRyAue`nYEt*4Z zQ$OK9QW7V&usf)#6XwRuusS;x8$Xa8QbY&}jh}smSDB{GZQ;IyWB}GX&^9ZR6UZnG zi8A|~2Bqy7kC2Djy}jeR)9n&X)s&@ZL3oKsuu0}|!^B1Y_>NMZYPC|7EpoD)xQbi& zSeYJ+wVVW3yz(*JZinYb6Fcf=UQ4T_0&?(7Zgm{yOiG3gH4KsG_c*xP}p z$Jy6fe8=4#rZ-2w`3{fFYbRL~+?i|S7#OdPl-48?+B}5g|9u_CjDGm|2c?Xu(q;N? zs)T;zb8#N}KP|`y(g|7#zIW0xfI8i;F}fO5SLCFCTKBhy4XcaCw)~GcyO>IFFKEE& zk8(mvdG~bl7x`atiBzwc3%MoytZiU&`hKC{D|El5fwxPpJYb3}f;owA zL}5m@uhq7r@}f%$(%iI4pE5LWPM;d1O!;PjWpuiq&c?A{{&5E(2DqfrD@PTwXD%mX z=+VBCe3z72=F5eA`1EB#`2M5grIIE@UxYz;AJ1*~u3^rz#y`DI;AsD^JtJdXu6nYP zj2NF+y?_zF3EA8dGa>Jz`yfcmPp?N8i$pN>c&3r=o1J--f0Z}d?E?vR8I0XFPeo~j z0m_W{2-L@3f)*FEwi85R;)TuD1P#z`AfUT952G^Yu}qvo zSTq{NjUG3aHTrR=SQP@(EC@16BQjHqYL3|~W`5O;|Xe8I%ZY2k|_&4a0Y+ula@_spLl@eQcUiAUf;=Wi?9T10>-W$ z!tDMrjlKPAy}&y+pih6jF-r3GYif5_|KoPvJhOVH_dmQ+%V*5pBsy0~5l0{L$8FBI zHT49?4a_!%=_24+QKrY(Pcoz=Hz^XrO99O$lO&3&P6RTpg)M`a-jwU-RU+3$52Q?q zoRtzX04J+SL+q*ZlSAK>K z5^iG})@6hwTE|riU9+4-o>|V{5ff_;%sbP8=QLCPYOf78j*pLK)v-^u4+`!fEf5cM zCl9UBiB#rQXU|cgHiA7JRmH~L`2;ldU$wBzl*}9-n~d5Rm8)LHLl)dqE&wi5K$E8y zDewvkiTX!i3pMd;M*8(uwc_n9Jf{7_Z(6E@9B~n7u|irZCcSZf zTGUds9ov5aX@-e9+F;aQHs+0HVaGa%dOWOLk;SS9hlX$>XB-%C&}}Z=x#(@IyS#oW z@_B5$hC9W1^LZ9*uWWB}@*Y$Wmo8WL!cUMc7`+T7iwPHY;b37~H}m%1EHF1*K2PBm zRYt+_$1I$5k+6~outLytC?JnA^yvJ<HmhETRZz265>QdrB4A_--eKHkbk$_!$Xm)p9> zd;`0-$sjeks-!*6e*0U4y<)+BnL%h8Ea-*-`-t zr1f!#ug`8!9VguW7&>70y)4Fnu;=D0L`5Oi#O+jhZG23^D=}dk`;oUy@@S>-;Ljvy zIwYB{YuSm4X~ukJwRT#--RNWa9%nGW!~q4;XADcCbp@M>f3{uieLAo59{JuGzpR2~ z*R|54T=dbCN@qIk^9)0UBJYo#&nUgr%ypg=uKGFEV{!kk=`l*Hp9_f>0M0nFT3gVS zGOCkFmW*^|Vy$aB1?V-kQ2W+aT6_M>(0W>=)lu1esT;thnC+LGaP0JToY$vBT3cWD z@)J4r=3#kDY^GHZ?X`ZJxXvd(k5zA5u|bcE97$V?ROo%!sPxrzRcG55ZRL9Dq$KAt zS^_C_C9aWUWb!?o+Q84HWR8u7-=a~3(xvnsNZ)_lhA^8^ffU@{$OksxA=Hkm9Ug#d zPpG3y9T{Q6WPnDGu>T}n@iqUaLCEvg5obfw}IG&uZ)y7QBiA(peX(pnF zW0aQ>Gjti9e$oG8Ijl(6ny0){?BN=nBp!2U)I_yHc+-8>M0n0G1>A=IX6d7>7Hs?aezNDPPv{(lyLs2%r{ z^#|&)aiz;9yE6bEi3=&8{=qiKD53C|vSsfP2;^tjB^mid5`$6e7J)blPvvHbw9FXJ3UJZg+V#~WyPJ9g*Z2DinNn{RgL6e${Wm@;fvXrZ15q( z9mPB+^0}1Y16HB(=F*DfcGS7}A{7c(Sg>EgI|ATBK{K~Kmdr^y+Ymzxg?3*%k}4No zxrd3&%VNRVUlV|h)+Br-RN!MR194Moy*c6`|A&J{{Td0gq-Ny^$(Fd6(2F@3)=lQ! z?>8G0^v=*3^JBiJ%+2fY5Izvj@HYQ*4l24bCb7@4P(2>Sdn9h(4B?(DtWv*=fkC~O zu!>pe6>|9fuk1)Zk>EB(CYX=N4V$fRR1U1Vzxy{HWl!l8g*3A3SgoM7WKyWW;Vd?w z*Xw@u(QWC{V;aEdd6vPtJ@4X?D*c`sT@IbV$uQkgdGLzp#%nP3YuW2~!ru8g6tj^0 zxC*RPiZ>^a>$gAU-cxHaBPDqGXZB@Q^G0_3y|r7K)MXFLuw<3eOv9$4iquq;-*t+I zVqkTg`drOe8#8N#GMz7dResr#bw+J(3KI%E2RL9F@PgLFE zs<{?_7{$c`D>pUu&)d%zfl-3Aq zbAUx0JDA)s-<&C#^ou5UA>hMEInI`2(MBTk6{r#FV7#xPYx;J7@rHGNNoI?O?!v_Q zNq{LpvU4hlu=kX;&dG~X#kPyPKX!$kI0g`ZWC%&?hyor^I|5@69E}~%Bs2>btXmiKGZHiBV=!Sy|K|Dj9=(~Mw-U1XgoatM&7T>b_${3G!uQi3 zmW&8p_iy5c`=@P58`lfSr>_S?Jh+D~Le(VF9Vr4CJH{Z|DZ!D{76%{fWdIErzsB{8GE`gns;7xz9f9pLi1-1zuOoU}+!1fmWEVhdy<81Ai-| zzq@FCjk>aB0_@tQ_pJTFk}bXLey^Q+G!v<4B}vW3*5~w8I!%nzW6Aq7C6SRzokeL* zOvQP~h7&chbt6d$QMQsXUWtBv<`?ypK#&sTN9@_e`?6L}`pt4rDoVSf@2mVJB|h!o zxPw?T3jE(?Z}rET_0|9CEv;-J8gkvwJ>vpC4g#Ggr=qvN?d{W#Ww1pAwp8H!8!f5l z``Ftp;H}G?;BuMs?mIU@DoownF8tgh%&T;v+66O!{QjLV++DixO-Xd(2KA}qe#RRa zewx9g?t&_>T~OBZ6;COV^Z&rV*$m?m1fgKTmiON|#$Gyp>PLEX_%{D_&rOGdfLQy; zv%ju*jAN8e)`?70dpmkh1+b-pD$m^25Hx5ez%6f~Q9qQy7Nj2dgHU*zruAcc3X}cV zDsutAu1=dK@e3CKEzv1re)2WstIr}L>xqY2rkd5Id&zz6$>XAO(|&4|+j`kr2Z5&< zRGY4M=qGC0=2_k;X-}4_xs9MrUVIhG@9M^cFxLCqF{CD;l-Ue2E0qy}ocVrV&TadI z2__5U{U3T_H2ns`VT1z87{8;Y6H_3;O%x6!<4O!t_=jbP1Aa872siT{B_Ox&*HRVB z>~tGYRkJ-IF;}|~a5l49FudRQwk~^r0kl#d>9aizRrm)iN)7S|S#zOIM_X&WdYlJ= zSo{mm+b?$1Qi-w%Sbb?BZ*lI2o(SGF`?BPMS(Nikg3ITAQB+}jjWbwCAG=g9IUCZ3 zb`hQtv3_t_Y;R%rX!;e$bD#U1C;^BbX(Rn?TS=8#ris!uY0$p7ZaoxisFU%q2Z1Cg zRY!`ZhSnj63@^o+B`|EuIPBAeFZ5-nt=(uuSp}$hGOvJ-cAT`n>4OSj15Xph(c~eU z9*c%i3f~3u%R1aqrx8n4!3ZJEjFr7e?-u+o&LE9nS=ak}$lza>Oet#TFxbL>?3jrU z4J0BP^g`39u$f2z%x+vI{cl1u@44Kq^LOFlHhZco>z0+)P@dKEJp}zQOzedZqS^XK@|Xo588^7l3OJ6{&IV!TTBTNaY}d_eUGp#yE_L8c=%aN1nPlpXWsmESA`;t z;03TXg2td>gb%Xt_L1TMbp?L7jz7x=Nn~dppenX!^&jwt#{veS{u-RG(MCrZbF~~M z@B8Uf(+JrWS$R7D8JWUvp4WldJZSd?cf~ULs4SJTtD5dsb}a(k;0U=ICC2@mN&>X( z7eqG+d<8UIMbqt1)Tgw_@tIRGc_!TSB`Mo zHzmpqoU5%41Xv`;3{-I5&E$CoRXp$Oy&Ak1lsGz@J>{mf3-DO!<84vFQPOIHSkjXh zD2F&bxlOwXCI-1izl@GCR3R^hx9|9Po-uQuIW2pt*WH$-a}Zpw%nT_i2^9T1$x`s- z?$Mf;MW6fNOn{&!Q_09y$5VydFV@UD{rq0v>QY(T{$LT4wKiES#sr1iA255)Liri# z!B~r;_$TQh`X(Cx`~vIkq1VJxvv^7RTO2TZXDMiTkrh0{ZqC?#3!l%i1b!}L%5F1) z(@H`w(MK3Ku(Ttw6Xrd18AaBDKH;8_3m3b2f4{Q8ZzT(gWlq*TUCVvQjdSD-)-bfC zh_Y4QPIN`4Hu#*?2V070?XW2!9!#>?`)AEA{ow|hG?{@Wa22e*y*g6RBD5^Bti)>Y ztF>;pV|99k|B0p{6$$RQaPAVSc+2gVpVY@0naU4X4nMj;DrF4Uyt}1An|vTl%aKc< zgcfCO!@OP)9k@csMfjeLb-j^feDNsD7}SJ%MOT>XH#$niZl%&dSdxskgms+^qb?oWlM7BtwP(IPt}C7*!oYZ&_vJ);fRqpi(LOBxLF>Y zCpq{g6IQXspML!X&81b%R{Qu?cm_B@(Ulu7idO9JEd~>!Q`Kz|2`!$mY%Pq$}l&*yxbd&CfZ!yGcjQLBs#GwGDy# z{1eoasBf+jL{^_IDzT_X#4@|30p8v4^B?-Rp(Kkaw_(*e5)}B33TSPB^Xb($PX>2i z04#`Wxo2l>9sj{0PR{uwFP`h=poA>jG*!!PSeQ`~nmS;$2B1OT4dHz!P5FrwV{LNp z8ivue;TJiwY^C&f zJo|TjjEf#-JL1_D91OuM0HHjdxpJHvN}UjK%D7-8jb~nr2&&gM_rpT@`c0VVkh7`x zc`&IJl0F)hQcwlj!F#YDyc-PAkayJ1<>kxN_{?UM%Y6t`hw{q6C@M3XjQPph+Y8t* z^RomaquA()_2fo=m74{Bd_O!+IQi#jF{9pnIRE<_6=6pQ#m>B_vRHLM1vbaIwByS} zQ_cr*t>*rr%7;a{thP|Y_8!kS7W%AiY8kfScjUUdz@JM-z#U>d$?hucm7JchsL`Nu zTB}9_bN)|E8c_>cp70QQN2-+V5~elw8e^x;nk>up2tvoW|ZKhMFpfbNbSg?gSY5N}@G#u_Dk zW&DnF%!NJYX#|p}e!e{ZSn)Ky`Tl1MRb?*%)uwlhdN-aSVuw~sukAhPLgrEkVT&K7 z_U5H29I>fo{jE+nY#&f&Gd@Pq95C>F19{jkKssZ_nkMj+7Eq6Yq|SatLlfL)(r_8i zA;?>$Y1oLyWzB0>_vzDnxe}qDCD(n&#~OYKaKu==n8y(J_pJxsCCg=a-q4-j@YcZa zIMdm+ymj5aAh$T9p0#CkUt0}7m_^5OwAnWKbl%!4lU-HPd4137+>)%7p49DW*sJur z<;Az%-D~)q&sosA@9fR0b#xgsIQPv?Bt?Z9TOPEjVQIRHm=PN%y&fe)>?Ej>ydVVfH4Z z(Yv>Mzzj<&Sx;e$JBGjE$Nc^1*2Rg2dKYf6iGCgWQzyA3f@3wW8i2VrsSy4Cvi_^yio`DA`QJiKV31R;rH?vyxP z0R8Oq_=%C7v-O7dTeg178gyeVyn0>hGtJH3(|)m|xtT;;QSFd#7h44Gcxaxhl>J3q zdXSEydCmK>)Qg1E?)TpvZ$f&3My&0@_i1w)W8+#Y-Sn(SGfn7OJadOSc^(|^u28W} z%Uw4W5=;!=mZ1?{43z4cv*}MowCKgv-2Y>mpS+- zMu&p3YKY<4zx3e%i{})Tm1$*zvcuZyERnDOM^W3+bwZ1bN=?}$OEtj9=kA+Bdt2|b zVKnXO{Ho#S@4fG?+Jb+(q7hUv!=i3~@dft9Hf4M-CH`R<{AZJfBxJm{lg91CNZfXO zc$b^+)~mJpfvWgF@~>uNGBV?=!)VQ?Yn%AwxXK#%~Xw$5&t0Sw8X z%2erpIvaT6@mv>79Mkh5*?6XD{O^_A8WQB^a_Z@kMs)i8ld?u$$+?153n1ougjC`P zT6VlEk4XEd^kG1gx&GJD$I;N$Iiag$$s^9P8HXsEpcr4x56wgHL2Afh=+1U4B!tr=_(fSNu*?x*6 z+f^%3|I>GQd*DV__zUuGyJ=)f9?%;34RT;9#Jf2M*FgaQ4=cQL^t|YuXs4aQDAh|%>Ex=Ds=vE z+%d#JG@-OF3wnW|pI(B^OpP1o=DX@xOZSA1QI@zjXpd=OlK)N!gX2!?OZI-WOG5PC z#q)X)LPIKwWBjw1jnAW34cF-C6J|>RJixc@lyJpZz87aCcY7y%K<_$XJxa%T99J)D zX<6CGr#f@TqTvDAU<&o}4fFX+tV6KQ#Hz17*#MRh81BkF!tzfsQ$hT})nQ zEHEfeW|xO6(K2EpY4~2=;3o@rR#{Ae!T>$RSW=8vlcW;__46Sx?JPLf#B!nsa*l)G zT8V&f^<^-x?$;6DI-6!$!m$XP>uuB&Yks10Xo>YXRpzkl3$j#8RAN;ctQko7$HCvG zSsoe-=EidS8xfd+<;L&kcHrxL-9o${03bxrE1OCC*D*B>5?4O!N4L|}Ufc4pAVt~~ zJ)fvLQr_bg5|-O(#rHM&L-=DSc6Y7d^w73!!;3_GoI|tQZBIq=3u==!cD}Ap9=X@~ z25jadSYmogtL27YGkB-0wZ-(1>y|86Csvng4h>9D$oSTaUtcJh!uk9C_z!64082}J z^|hP%gA%TQAacz3GrgTSV2;23&qZK9Z;!)xggLg%n* z$@_1QgL8d|EYZfLsjI{srru#*PD0rl@Lc z=^Olp+~yE@xTqYu)@pOXSq$La!vb|BMVa4^WfdI_G3v?jEvBWFBzr_|D~u#QNeZML zrJO?PxjYxurDLR@(3(#v!$(X-;9^5a=iHDyf_4J=SGsqxnT-<8Jm512^`i~32?UK^ z{ZBQFi0$c0ni@kKaC9iV?b{A^3W!q*I-qAVlG|~^Rv%F|`Kwww>bMhE^&wTl`Y+N# zJ=2O9p6=Lo*|-9Srr#p=J18ts(D~hlLNb$!b2RC?Bb0niPlC{n+6-lX(wpohq3VKd zykLco)xs=QSh9o{UI3^ucm1GMUmQa>t7Qiz-Hr+bKbmCb_exrHirD&9;BDaXb~yIx zAe7o#v)XP0KiwL<8`CV}|I7ydG_T6ixSd;ixhlJt8B27?; zTTs4^7+487T8#<7;0agXP`dt)G4X>3UB~BbxQ+)B_8e66Fs;kX~C5&95P|3w_VR!tZSB){&X)2)x0RdZLh@HMK zFVb(a>HtR%U!>&UZ?v4w@c7yvRh6^i-nLR>@8r>5^ja$7$SXAhr(-NxKc4KIa10GT92|V08oiqjG@Nx)ccsFk-0IUen_q4HurdIzu$^u1S%|v zP+uhYan81i#bRF3+suvXWp**XV5GhUTo}vw!H(hsVkbw~P_#bZ?Th+klm2)dN7n9S z|3*;aaBH>qoBP{8MRaqSdDs7CQ+FKr=|5vL^0e%p$QAr0%7eu8n?2=Cos*OJu*b2w zvO!DdG&eg&x;ATE1I#~hnzbj1t9At_LT)1)HUE3}@+?Evz>c}Bzf~>d?q#7(@M|Iw z8ot35Sb1|xx%c=Y?V_Ao2UxRxrML1>a+@AFeGpzEhi9!L+yU|BaUFS@LNzxE)56$> zUaZX0{qGB+&xqUwL_x&+k<+0zsUBLa$pr zwlNi|nsp?*w`~8i%ixcyDiQIt6(I1jP-A|6$QpVKY51|M!WM(;h602L1I)^aH$3D$>|Oejw%ZJZ=ZzYfT8O~_<=a_l+1t6v9!8Zm@R{1KNft-UE@wGu`*6? zxeUuV;Rro~5ZYlp@L_LwV&=LP+_GJ;&30nNJ$j2!UDXK#$(3;@1w6C$|0YB*|Tw%w=%+RD+w;Tkn3s%;<9^;9$% zcC69eZUgaW&+%e_Z)2suVo$J_0Z6vPb@uey^k#qiJo6OX+B13`0BtucAJV^jyX~#w zw^~E6Tbw=bQaP0!w`?IYg??P}(+6h!hTJ9A`fVjQT%!iUWDte7gpt;jBB8y`nPgSJ zB!`5giCaB9xfa$`>V;ZSm9w?;@1AUON>NzO@by%gXBydwbS?Kf+q26ywP0Bckm6_y&i}Ab zYkt^#ARdlKHrwpaUM=^q<=J=%uaQ$|G7|aKx89!}Wk(ekr~CG}LRkoiW@Q)fT$pX9 z7+Q$OVT)LyGgMQc&A?V(eHU1I&TC`p`X(zLRdG1X{vD+h^Qkr_$w58p?-(Sg+&YD? z#P<>PtZoE2yy6}{j%&0eYMiZa(bf{PuO`w4DYx`mtKix1XW;E!5K=J&b|WkoI)NDA z0Kk)%p>xc{mHh(o71;y06gw0|FUw`UqPlbtoKLro$5Ebf^pxTA+<(ligfbvJCRRj? z^IgZFLW_iPSy(Im@%E)ZE0rZ)M9Dl^^|87wRqkxK&4&s8_k~QFes5AzPt?V9#jc0? zXHJ*uNU&e!!~UP!mFBzM^w6#e90h|AWFLNYu!6Bafgs4ZZoUuHZk>9`MUh720P+2@ zXStd!9>5JWN7Kpe=M7d4<^_BhJYO#2xD?vxlTx1PM6wYbXKXGDzLY%T0$Nv}hcSqL zx}XKFqZ(bjM4gxlNy2N;!vDnDKAwZ$p#C;%>s$ksLQs>)dVeF zU>9yhB7YyZ7Oku>YI7XVsA;GxwCg~HfzB1{9c4}izrsB4bTr#*kLwHJ=9N>KAVWY> zscfF!!LTgP`Pj6MX+WagqtYvlGy6zl~%OnPU zRB{4lII46pE&X_O+NnkZ7)xqHLtQim)OxZfQU{HgZDi4)bBt9&&97&*F^M3}$#IK^#(#8^ z(up+u4y}y+54dF3Ol9};>{oz9t<}-VFIQnq(eWsn<;g3vxH^g;J{cx9M4LaP1@wYV z$PoxZ7KlC~sJ!9Q!L*husf?(1Q(W~uk@E)?_LBIs94{?2mva%!fAbf`91y2}DW)y` ze-W7NS+&W4-e6{^e&0+_OlRXHlCHdCA(UPBpZ9_(shQHs+ z(qP(`4C!$+r`snQH_5vPU+1^Hu~q5Sz=GeuT9#TBuY8B_0f!WtC?V=07VM*#x=_Ju z8%iIg5jRTVIiYbe^$lxi0Lps7#0+EZYH}}L_D$NBO*v~*+uIodlk9ZGt_AQ6fXDo^ z4M%!EdGIGQH!=bB{%?o_fQt@ATRUu1?77ogx=S*tFai4K3Cz%8POiSSu)I}fD;yEk zc|l43dc~@J4~p^wZ={3#Dbv=>kx8Q|P}vz?6*9>n6K~U+_O`o+9N>$YMe0AhhH`j|e3k$%K|W-9FRW=IHQ4G874w^O#O{1v%7WfW}rwY3^mU6nSIF25BL5eX@)YJMq zi|~fBJAV2iQ^obW^n(6hK64H;?Ne&{Na4Dn_QIR_mUA;~=8wpvpXau>P0 zXrIZAzd8-vU9D6f(cQi8f)9C~1v-Scy{r*)cwj*;HkgS!1U}mMy~6el0Y4 zuR(*|xmz!bB;xGWIBmM6CK)BEX#{t*)Yed?wg9um@9Lwbp^(~{fpQ6i8e<`UU+DZy z^KQ2J&HmVIxs$d$sa>AYX`8_2(u5~IZ?l?az|tyr`0x7t|K*bcrT5vmS0tolR^189LkhAKcnnpeqnOV0XVMu4<8uw!6QJzc04D~I|}Qz z0g7-yZyIHKkO1@s;|%3$DjppW*b;PT)jV7pjakq##rM{t}X zzj}YUsKwo~@-HaFi+FS5?mXAA+a|vujdwvZ)b!t4V8e_2kRb_e2{NwU&*dXVN(?1G zx#!fQSv!m-|5Hx*n+^SjWGL1VHh+*;eq#$ZA%Ku11rLixG-@1S`DyUNorYW6q7q15 z7i$)2zcCc&_LD}Vm#Jlwth#xX8b;Ru+xoXXXd~A*^a2xori;UkRXeU_ex1_1)TnR{ z)^(+%#7U3h;S=Jj{PO5K9AZM$zQ|pGWAP8t&dd5LMc(nrWG}3S7a-t7b=#M&S9iA| z1l{+&fd4GYfMeaTb?UfynLn#K2mh!dkh{Sb$I5 z2u}Y`Tv`Z-95UtX|N zqev^Xcfr7kzda6d$ov+;YW@&kSNf*r)|F3^x&3@Y?qq6?B}eO8mp1*fe~m(f;__(_ zp@T8gPB!HG2Hgi}$aqE>opCE}%T}Xcyk_V<`9U$C&(gKG4B+hdqy0j%tF{@(e0k^A zWh&CDO!+?5CTnfUzZId3h~%YKo+dEL=mpXqD7;`InrBM723mDF_H&IQRCFN0&yeS^ zk>op7Sdift*y8%|`!%Y4*|p~%wlAD*I!*IS)+fR(SyHf%hAobnK%@~mE)!2@1$cHY zn$~h%UY~fN-!MUY&mHpp%|1&WH|dJB%l8vUi4*U4#5xvClc)bOzG#jRu@STU`9A>c zKoh@pO3uGAt)(CW7W zlbX>23?N-gZy-xz`K6>l5Ce5~fXp5CxN&V*0INahF^z+@0w3e391uL?LPl(H>DGH! z_zrW=ps3KiP0E6Hs)eClw@J@esp~_ZIZAA$jc?4iMbKw6^@sx0TE1-nl=X*`wUYBn zdJdq^d;Tn?sr%mz9!%m@7LN@f3-sjF<}Ry>DJej5?_rGQocq|JQIAc}NxA;6=nB5i zK>hd@t7+v1DNf+B?8&BCXIa;*rW<-L-YEyZwVSnQu&7R}8oO4z0k6=;j1fKvMsq1Go|d%! z(~fLF#kY5x9FN zUE7Al{}Z^=U0eXSfaIXCX+aBktz;DqdJkA3mn@e3maH)rd;=l04Cs;@xxP-nM?iuB zZDO>*MWMd;N#5r%slKh1zk{p=orlAEK`f(7D^RC;{&+e@cmIBSQiUf+a~1G>ew}!g z@4|W;SOtp?iRpWz^g;T$>3sy?SI|A3K1lFAb;6gy(ewqQw^*p3V+!BtQeTp;_A`U?$H42Z;S4jR_~`;25Kp-qcC$W zvf^C$r#C*jz>2d~o^my%^>3PT8MrmL{CoB1K>%I)&4bMxF|L$}YF22HV#AKaFg;+a zT!Zs8wbY3x9}B+Jg?`SpjD2Msq%OBoqm9C$RTuhkDp|#!lLh8dB;G{;lrSCy)bNY7 zU?BnxL?9->s>Ny%h$irTvHNKeUk}w6YW#}dB{$4ZcfS}{+nj4N;)(xwv71_;FWj#AIC(B&K(A4>l#_gFOhdDV!_iChItEYaG*<1^5|e(klL5#c>sP zTkUdNMFj_EtZl=~HX0xY;3Dq1+Ir9Xwi!@G!0rKT4vdO#R~`ElU@|kov&>m|2VrfI zJZR?bN3Vlm=m;Ku4O(?Z*;_>ea4L@K)GzJvP@A^2jKdiktm*V_@xEt$Wv8~bJ_hJJ zjcjO*rq2DQ&kAc>l>S392H_}QiL(g2_qd6c zJOM%04OsFEc&p?oG*wW1%A2%Ud4eFB^DxSt&jeE9mQL4IakD<+7-4~Sk^Z|HdIl9$bsHtQncEjH9be`bX`8Hh2A4L8WMkA#d+JQwqV-Q zF8Ln7cjj-U-k6mNOV;n4FI)cj(;+{nO5u$MY;cSF!M3QlU#j@l6qL?B<*f(daPQ}G z3XszN_gpREPkBFo%5(+aGblI3rc68UV5S|`0$A85SL@)&cX-lep#IkVS4t+8qgT7v z_&@wxa!1rwkTB)^sAcgwuYuw}32`l25sMTBN$UgmCh_1JiMS@^R0|Z%*Id!4_>p!21cDwH48}?K|W(-_U zxn4X42)b7hIuV30oAW9jZ4!7c)gun`TLf6%hgmQP5?ZYA79aOqqD#*xJCC?Zvlg>X z>?vv+pM|_q^GZN3GkxpiM)EYgl5?<);3-(ukMa2$gxU|!SLNs-QD((lN-3n{df_A0$ z?^;{;4ly1YX%6W&tnJ;71?Sm1xs6j9QlU$>_;78l?k#=bnArGdnN^YpfKM*wiKA+% zLI|C*aLAH9TU(&ndWUYZBGyW1R9pn5N(DW3!`IfC&;9H_?6-ZMGVjgZ`CaZ^Q+Q{t ze_9D#qB$iN=aN=X+4nFumSrw-uJ`cVEa6w+y_~M#dw`Y-W+F5RU4 z=K!=$ZCk>m#Af6@1S~sjGXkKHcI_vek}P>NhLWl~~yr za}UDecn0&5fKHm?@;yW*3E9F8bj)Hr6xN`}(?4Y?`*aX6pZ6xh_+6P*f$GS^-&iHry+X+19`*3!^707@xy$0S>XUf~$|z6FVThUVO)X=$Y! z_fW#E2HNTw-WlD5t*bR#s-x?Br`nJ@+8VTqrC9oB0jTCXoG0|Nu-r>VuS%_G*I&-1 zKKRsE+BQPFqL5^t`R2nhn>Ljrq5G)ERFubKAXJ~jSZ>769P!#*MeFkr@C|*C1e0~@ z&+vZd=?Ghb(Y~#6TYe77{I=FqJ#w1YYJS|ewmu&3)x2!(b;1qh7+|f;|X8h+DTkG0PU0N15K-dFO> zs_&lUtuN*GFjVr4fVl+bO!6z|YVE=2DK6IE-+h5kcfTl?#GLlK4|eD-HJ3sS^Sr{M zY(og7%U?ZZBB*4Ob2Rdb21!N9U?(If(AD&OYhH~4J#0}fcH_}zQl z!j?E%DIlR&RUplUN`U)mZU2u+1RYihn^Vfl7zWY5jV{GNNGcYrsOxkc<5^i+FuawJ zM2mAVcVBJo4cF0C*~ak>&1XFi#5!v;IWrc!WNpkP*5XsJf4cU!TuESUvt6^6bKraA zej)BxoS}1LE_P`Ge}HhUPVbPt(}0w1AoWVJjR;tvw^kpt>ap~o*8^~WT;8pyBv{|# znBFDTVigXNH(2Lct@N>cPlIPh);DTCmENlbA2JSN?Ve)o6zjJh8<{uK0&|Ls9i4IM z+AY0HuKljFIM}yRx>oa64Xo`wW&Y}R=J48gr4TLg zKmOIh1Atu{TH!ZFQ$yf3IK=!7{r(J*<_9?ih(9}j{Ic{^Ea6wseSW%v??`j$r3ww28Z@EfoN zMO6|{ri}?V_mDmI2)zl8weZ-n%5&-E?oCYiLd%txxsC z;niz_l02JO;yZPwy}y3XHXeEmgofu8*Lr|z2ixD$J$2t@zI5hZQ%D2n&?l+{#^Ia? z-GFzouHfg3eumC{=QaAbr%E|KQ6Yp4P_|<*6xFZ+-7I4k=V&9%kcfbgfbN57AB1>Yx@+_O&X`O%v!S)d=>|?!Q8-puWK&`0I3JM@UPd_xut*;V5m$@YC z&pPKyBy}BI4VLO-wD!`P*iWLRsZ@`6DEqX%K3LtoLW(zoSp(P}`z)}8KKGi_om zeGWk@t;hptA7X;PQub+02W;^cw+SrQXmP+AH+aArO*Z>dPFV{}EPxT3R9OFNQ{`5rf*1=U(Ib^QbzgR4b&0&%gT_5t`*dWyo}xnt%8 zl7?sXBALWa6I68R9}5@J9w$P67sEvQ^@!y@)&oH@a)<%P6Bd*6dTU~K|nAhv9UEHn+Ji>h?|Ay#^mDQEST&! zF?ruNCPtPGAy0z2H#a0Kxe3^L6X&^*OVErB;$rKJ7s(h*0GSuh7#oSi!VZjNd9=)& zt=~VYt83}%K7E!M%}Djtb2NRrtE#K2`*hd$woWbN^R$&ldS&1z=trR^=nB&}UjYiVK)P>p<2 zWdNbHbW1?2!Cj!A1^Q$2YDrj4-)6P2kqciL^h%g*N}}P8J}vrGj`JK#jiIh_KE>*| zPaG?q1KhL(SAkYn3360kVRfJBk%skr z!=|~uY?ruS>O5H6-M`$I>jJ_2Z7JH7^-R~PW1y82^Ho3^y~^LA)Z!@je>YPIUkB#x=3rNjY`##?J3Hww7dnBz)iV-=ynxmZJl)5!rj2p zhS`VYTqL!?`q*^=R9gLfBvg+rpwELD!=RlfhHPK9q4zsqeOm}2TQ%n(PhBwYr!--D zT3vbO^m1n&ove0SJ+16DU9SVKsptwzhvoX-^Eh+xq#{!K0#(WST`FcL~gfkc)5IQp~<@}x(fme2tp>KPfJS+QwwL30$Z!)(x71- zx4*C4-)B3JTFRsbR@aZIg}S1VLO(5qD)Naaf2C>W(Gqq(VpD6Dq_#HP!Hv{?D4(x- zJ5p>Q;WlwrB+b-vt3I0FB^5N&M=9~6D3SClmcK#UT->ecg)lYXR@2yPwquS-QGc88 zrfXmI_DpTBf*l-Em3EU){fHvaY43;7Xj>N_CGVF!TIA5$Z?=`y2Q^+fQX_BQ){UuE=4b1J))`1R~%B{6suywEH&W5<)Rwv@a)&KPI?!j zz+{s6N)jx|f=;;2xl~pFM0#p*j}<6Wqd|c(A{d@4`m}_!UZ~O+k5A?SE<|SQY0;Z5tDO;P-h`c`)vxz^!W;r zBvRBXM#rStxePZZML&{)%aB`nwK3}YDWdB30nQ$ueox5Xgc;>LOVb+~+Xbx+nGVg= zddlPGGfmBxyxa9W4N4zs_QyqTT;w3?Zo8(hJl9vF=dZr0`mM}{RZ&cqTO?F?8 zw7%FRPd6SLviU#BL{j1W6%*e$QkJ3-mL(+BKi!No~5j zZjx-vZ8zz*>nso0bD6Kabiq*~F!?K1)>_%mDt&#LNAulJwc~Z7hsT+KC*Mm1`GQqx z7}S3GFw*@wS1N=iQJT?89giM>$0SHE9x{7wbb^?MXd~- zln2`<_fn@6`v&WQuT-ElJMdLfYosq&k}pA3Uh3RbG+}AFqc^*4Wi4^iE z{j@TvmSj}UO~IHKK`&gRy%R-QpfC#-(&(RZomV1*ekjftg=e z2Bnfl%kp|9Nr&!l3ubyG<%cWhN41|!SY(q8H_d3hfISzW|JD=%FU0$FJ*(1{5?@yc zBXTJNjY*Ac{`8W%#e*JKpq)jsotN1jrOUJ#Ou}HAC+qi4klHKVP+E!~R4;4_)!I~A z*COlvQ)g+dXLAMHvU?v``^`S+KHP3irn%pw(=tR{sGZBL84khG$5!Xo+tA09te++< zF-cfjBAW3x(7WZfsYw|I*b+qg_xKYY0`)Yy6qXQ_k*|}_V2YoF{ZUr*K9)xnUV`}X&sUL zbtK7yy06V7LiH$?g3HxI5_5A==pqR&jZK!uDgR>SOwLDidH?_*07*naRQSEM6Lih} z>`rRG^>TI{y}SyWrGkwqF^OnT>4r=p3nYn*O{~QARlgV4?6wl*+JwzTcwJ(Fq()Tz zT1-Dzy=-XBr%Ig_8gpclUA>lj45rXX*44j>bLD%lngUH_YTfECN+Yi>(rsSLf>ukn zqA=&mywYjCNs_%Jna}8H%L|@-_YnF+ z$PC4k)Sk&@nOu-B&__T>jgVRt@af(iuW#%8-K21mxO(!7alho!DUVNZRwU|1L`^KIUmyAM0_N12~lyEiH_*er|sXayoVdwbyMS2A_qPCw7%G?N8l3uZ$jA*UiC*p`Cmq}fwJ4jZZnbGG%k=NuI@{Gq8L?yMb zY0w20?zZf0`}|5cFY1OV^N^-}PLe#c4OKrciF6Z}tT{~*Pn&R?{SB;g`ukKrV_vw{ zTh=c=Fv5+{9WxmfRO;HDt0Cm7iEj6IIHg_Drp1pfh=fPE2}q zjj>MHTn`>Q617Ypl_wIlNCO2*GO8j`*CC35n~X$#nt|BIxJ(V1|5z^mLJFKZZzaUW(DZE9bI+i0oa6X2} zHA!+}3J7$eiL^Vg15BAvgj>y%dbX%-Jp#NboC%G(+2`qYDYufNy}FiOir|@=R{gK~ zr7DABGpe^OCTcy)wu!XaMn1R%d}jakF{bsyO^#gq_4`b3+cdK_w@lK~iYx|J+4Q!O zNIR!Z+|%PPxaTQJ;#?#&AiKU^!>(@=%(QdcR5)4Q-Cwg-y8A)aKJ%=}vbt!%{6%#J zwPr~>bE|tv-kJJ%_4_w%{_OU$%DAqGtBua)p_l0u+kttXn}Xm*v{sOciGYw!vaZ;; zXU8>MJ$Y~2^$O9N$HU`H!ISR{WNSfML+S$6VoYChDY78{H6y|{Pe0P^I?sbiPXndr zi4}gw#h9pOX~Xq2Pz%vtF$V=o)Y&>Yg>D*bN1_%{prxj`XlQsFBqLGlCc<(_s)(8y ziCToR%8o=Wm#%e9yX=lcJ>ZB$twWhd+vHj7DN&1jnB>TH$m?vISj%fG&5M=Kuq2Kq zAu`)Dzw7stzDH`hh55IN9xSEMGJ%Z{C8LtuC1V(ElctpLX_WH^f*mRY?48c zkBHSsg|a5fusLP z!lsW!!tA@?eHxM^!gXJzwW0s6?5(7qcRpel##g{>tG&5!?{9qv zr4v~F_ho<^5+UTyRu=U- z)mU-_d4AijdfrFeqjQ{-lIY5JY{G6uVUor>uZ@1XB)%7#`XJ1V- z_JDnDTFq5{AxAMxB{#o(MI z-`yZx0w|B$+7Pv16Av6=T3v!jKdFMPxJ<193Xu=EG}8$P4Xx=ZR>$VwQY-5+k1o() zo>lRZTwk2q8e?HX?)C}RqfxtpPssk?QM1zT#q z-!3Fcuf46$ zdy)*;=8YjT`gAiALg>r%tmxB80f6+=76G(EOw)O@o?A;|F8cHP0NaFHwri4fyC-hq zofqvc4ws9`c`t;nCIOdwOzLeeR&|1_5RiP2w5M5h?QM-#8oJOrN7_B??o-;fS=uI+ zZs>F9BAu-XezKjkGD)~dU-o&@+G%~>v^lr$piW3x@-A%M$E^N|w%VUhy>|9@Td1Yl zcRj_-zfJ7BF35Se$+G6VPw%5UW`RyR^(SdwA*PMxCDb%U3g+5Fzb5)RMBc$_ofHzp z5zZy$R%bA0+J(=4^3Jxk-y+bOk9h8}eBsG=$FLtbCc^l^WiKHV0S%DSK}i9Wsdbh9 zmZsLq+*|or3+-fs&|w}eDWyweY^Q-zTI)hoLPf*27ekWt*paAJa4kv1i&`(_Jh&rK zi(6B8fUCIF>5-^quM|mCDkxq0AK396~s^o4}|txAHS_7*83Y8S1L*3b#aW^ z<3^ewK<+n9b=93}>Qdx>r3Ei&B~*`-(Wg}(q-aA=8-~$_JsD>$;> zKFOmd=~mmOIL2OW*}pY+HVX4?p$mv*Jw-^>?^iuf^;KVJj3rw;ekKW@>%Pc-6DL~$ zbET_hM9pF$a^jQg2Yrs)4LI2jikfnu9e5({v6%4Wy9M&Tuym=Q4C-YcGbMwCNV`^y zJ&>CeC{v?BfikU4ttFYQ(idx;>y%?^Qlt@S^;AyTWK?Pq-CHNdx~aJAwJ^m^2Az>F zbs3l}D-t#FNYs3obD;zpb|mUzbVTecV9TaKn(e!yh>N4@WtogbEw^O~E*HtOwY_Q- z=E6yiU0frTb2*s;O3^>P6-5D)=E?f~s1tB~A)w|-U*4K`VKe?Kx6K-m%mr-rRlPEs zxR(`r;5dB@=Di^Ltjx8|MN(4CV$Qf7z|3C!n4SNAD z|EdKZ#y)$|og_bL3y3uGoLmaI?k5}B#QR)ZjI>^us^6ITERnxU^Z5ei)envO?ILit z-wx8AE%veeZKNO5zX#~Quxz14JLsmJ-jLi@=S@4Vp5lt!xy!a%k1Qr}maVj3C+&HX zR$9%2PNdb*(Ad_Wc>2mhzG>a(u+ONT`;tfpD0{px{-*jDYS&FY|6K&!9+f@^y?Lfi zPKJiCvl~kvSC6uKX}`PGjLB=D)}$hWPnAAu1T^Vmp{sn~?FiTk9csiqJbI0DmVEaz z9YY#H*B`|4aV$uzZfY&PVTArrriRL6YONk`dH^q(UMlI=T8+uH-A_nb7n3Eq*=GTvy|pQ(ggSKLGO?3 zzqoRGB=h8=P+t<63v?A2OcK=w`CyY+`?{Owvx$+K4Sk8A=QTH__wL^`QC zI-6|UV{@fj%4$dNkEov%R=Dcepmj5A(8<0!i&{jx37{=xFwd7R08nk(^QP}NzpHboIa5o0 z-G|TgS110KE{xExqa2~Cm51aciM*>!b{p<{LvJ%b@pdhJyTeL0Ik%BVsN&Lsi@nJR z&MtwK{>(WOP|uWZ+Hl{8?z5%WlcG-jdwb{YEjnvIU4WWw-&MoCC*Kw7{d}A$qM{RT z^PMI4+jey-45zDnAw$%w1k{0Mji*H0fzb;=%Ei43_WMu0Us}IedP%^02lvy!eCH?M z#I_Jy&A(}rSfp+!PgjEOD|U4{9PyFvInvaQ+5oB?iZrhi>#CM?F}I|)i%kI*`AAV z%GnZsRh)A<8)o9M^hnf@W+E+LoKi%Q9*J69AJZH^OWW%fVwh&VZYjDh3JI(-s;724 z=6SMG9GL{XX^mgqpVIJLiG$Sqxy`K2c~SRmGA&R#xm06H5^$Tiwrggc*1lP;seMyK zTrQ>5RZkZMxX!JQyS0`q-=aLr2iUz(NGIdTB~p86x6X1V-m-7K&=Tn_1jd$0s$H60 zyH+>n?z|26z1UjN;I6OGYFxTVEV;;c-M>qNe8Pfu>b7&8lB6vEd9vDTXZFq%$+lq< zZ1uJj-z993tP*o8JG1-(bE3#D5Ktl{Df$;HBGoH#{}u=xs}jAGyvLXCb5SCzhx&8D z-cCLW}_Hr0JH_DBILp_+ck~jP=OT zwm-3M9vu+Ui1I1AwCA8+VYX?w?h_oQ`pPJxh^kGz(-)(rz(-zheW@>x>#}!n&%f+qKTx=64-rXYGjXSIG$x2CmUi7D)!+DH->Q#_Zw zzzU6R_n7qGL^jd|4{7I2tDjcRYXk&Z-|H>{ZvIYm1i7zqXZ^9ub<%eG$WK56?SGdz zyBFupOJ_T8Ki^q9gn?&#r1PM;5>UT*o1iBNxNFs@Yt5H4%=f8zU&@uEaypbI=OU1BiJEa8@}wBMA)Lt7 zCmRKtx!u`3JeC^gH2H4F|IdElxMY|%4GN8itgWw9uNj&A3bIVCO%0)}Z@)04iL*`Z zAUi5GC^9bthAB;;qR(0LqZ3|fqOAH?Fv^*8XwC~-@0Hd)(2itBq84Kbj4{ZWCf?2( zhdCd*wl}c)Bgf%xO9)nE8?x=Bk(@2xPb1pN<(GcXsXHt!vZ|Wrz^a2**M+9`n$#El zfweCU`n}*DTk8d)i&)EXr5#uF$L^nLrmxC|MhO?(>EM!-JzE2wHWssgX~?4)OzI($ z{Z1>J-M4HkXRWu6PUC*q?*j9fK$2Ld3AJR2&dnZsyI9xXF71?8$Xhd8E8D9vb>7Zm z6V|Nz$X$Nr!oJsaq&v^LCh>52@s0+S>4F2bt!n2N2AJn`jnXA-NFPfQZaqz&dacfvU*O^4hJGKpkK0#1a2!ed z&E!S9MA=oh)8i((xsS5y=Akhw4e3I}EFyGfkwu=<%5@6;si#&Hy5b=;j>(mZBH9g< z8loAkwCYAVeH9Je%x45~+Q~lNj+pZaNi{w;&iKQgs;(Xb^ zyL`_)eU26JmPuQSQQEOQc;@;~0q}xPyfs((R>+$7#i-}u;esdMJ%&yw^oOtbt`h*a zsWnKMYSExgS*F&u)>)^^fu#wD)*556Pbc?g@SF60WRc14B2k;fD4izST4Mdh*zSYV zCeKoU(ax(dNuuqXmVt2|*ZE~R6ZZU>HS}?t5_w&4VUyK-%iuJk?}AOXlgD*|NS-U? zBHC^;sUO#c5P`N2WK@3_U21iYDX2EgKDI)y7FPL$HH+V`m7?{Q=r-#`9xb?pE$T71 z)0g3`(Yt%d)zX<4;w+uaoxYx2E=bpgtCf~Z^c)y7 zoqjJobN#1cvi*Wjyfr4^Y3QTM0)2VAZ}ew5&8x?`15du&fNP=U(td~9W7mF}>g7!n zbfpC^7Rrj)^w+7ev^@?^=P7CMxr*! zO}6yCX`Dlsn&*S9smJJ(J*u=eY|8?-Z~)A6xy~*3n|tI|^1id%G__>u6lIa7EXtQxb9%O*+Xa1A{k-$HvPea8ePON|^c99qyybBfptTqiaiQ%l(4dcM z?8+z0nNT!d5^MEl6?*X!L(~h`Wd3@VRch$_1IRX*6l^3c9G^# zJEQ)nxAo{QQfMwJP1CA&BT<{=(nZ9?$mJ-dx3+rynvzsgW1BV>)qB-O7D2RO5@K6( z6*|h9ZD;k#H6QM>?LgOV>vLsVW2n+;TH_?l{<>&yXj~z^KUsY>uSwc{l?A)sS;8ZE zTo;DvCA%Te?z81>V=-R(>B5O#_hF?HZyk%N1vkr`JIE`*T26$#o&KE(613cjR~lS% z=o*RZ?X5r2O>=WId8sgIu2V$hkQRFE1|{l9ZL0{xmRtu2y?K*9s?;gcphQ3^(u5bO zQHl-FiJjxr`bq>9Q|~mL%E@r|X=>AsrNbuAuE%@!HA$9F({#J*r4wUw#sXt+Xnoi3 zKVcHro|(0)Z=IM~r)#P^TRq}Dk*d!3a(a+$apF8F_r`! zLi(x3{R#Y=4%w)RJA!kbYY`y)e+$aZuODEnj9QSICEX4ePf9D#P;LVPT3&XVn^afL=(#2>w1 z_NVFi*nQL6vOi`WbFNMOyQ}Z&8Yi!pU8XbQ?V3Zoj@dVTe1UPyT|RlgxW<@uKcvlz zc@0VIYxS|OsT*1QliGRL__K~>mCHLX*?mjzWBPrspFcUrX~-H!9-M8&d&iETXJhJi zZkG~y?(4;wfCK{vIA@8lHSdSZo5We>Vwr8fkM8M>oN4 zXs-d+!rUgEE^^vT)JqbdG!kyUhFk)MB;hk(t2mC^iyYF3>)k4;?W-$nb z`~2+^?R4b5UqspN$91+5ZymiHTYL9$`)zmIm$XH5_rFOG4~2As7{tee7G-tP8WNz? z1Yt~!%hV$hEl72VI^}4)OpP*i2AHRx1^QWtx69O6%L!I{rHWnJ}D-N4w>`tgwzI@rX| zbv(f3A7z_U*`rABjf?mu=es>*OLgOU zI#*UdTs71B*4p5&7dR8IWKWp#p<5sDEZEn;e9Ct(2=?$;IWSi^_KLw?0f?1JQxkIw zBBk5!6(fJ|67`6D3yt>P9ot*>=8cn|qaH1dLkh7LU2KbNG$rcPC`aEF0hj$xU#YoL zT-tLGIQE-w_N?}kZFCB8Cij}d)eA8?k*h~4Wt#D5W$tuoSy_*+4uo7ic`x_wxZ2r^ z7kuKakVEs`Pn81-#~4LvOX;?y~9HKhxA&YIj|lXZw>hvDP)XNsV!u zDQ{@ib@eapV{7qUn%=Z|bN4M6)>$`^bfSWxKgP?VUGy{ygW-x+j(jz0y?n(lmRyW2wgJHOU?xYBeFh=~`o3 zORQ^{buz99voJYd#XPGxm5X=-e16B9D8(Vy>QUe}Wo}-yRv97|dipQd?Eq(vr(JD$ zFSX#kc;?t^6MO9_M_;EzjXr9TUBYPwm}gb);A>gu*T+$c;?lQ^rLrFI@bKijOSC57 zrZ(6naxQ{sn$McVIggpOxsWpnvLedaX4YvWE6ra#i*&n*XBv?SjCwX{Z;#|<5!v=W z?bMUlaB!+cAM=rJIrgmYX=6*CE301X`Rp96&!3-=3-pS_wtFvha&Igp+WCF7i*to^ z>o}K$4c%a9y5ig?KbL)Q+tPQ+V_BeEQWF^4COK6r8R_fYh_u}`niMHf=kq(>)Ykd# z-ElR2R4G%{Rz|vyw@#e(zBG(JN(VGm#znl7B-~!fna~9g>2TN0hx9d*xt`T~p?}wv zKurQ_^u+<~nz1OO*kS|6H~(wcm8jXkCwpLE6eL;^fua! zMx8~>?7rn)gm=4Gw;$9dTqHETk76b|eTkSB2ko}g%{Iu+R}5KfE!IcvH$=e07*naR4%3&`bx&obcNxG-3-l4F*`hJ z9-Emmz7J3AW@dcXQg$yFhNdfVU*#BPN5BNJalQG`WI^b45AUKV?sGp0Gi0?=2glJXxB}uZ_*$GuDt~_ z|F@1TK|_%S4XkORcq`(ZXW`w+;=CI&n2kJyJb8A#ZPz?6 zl~AF5WNWCi(C(Phg)@13mG^wDOP^_qk|mH@u0%Yok4t~gCULG4ZwWaM=Q0T&p4iRM zbcNZGF@`608^>(2EipSh8Xp^;*d3Gb+2PTc~slDeAja(z80%d4&Y&tuuw&fX)6 zVyiLQF?m8nnzg1eLy{8fI()r9AX1OXly6G`;iKOP+(Hr$k4_PUVR-JYA~Mj)OQqGK zKJ7v3s@u)a-0nr-*q6VpUOaHJM(!$+RdT7(`v-2GQFSx#%avR%COVm~Ue8mzTK45Y zs$1c#Cf&F1h8w%kHtw%*;6P|-M5XrEr8R{!r}@=MvQ6S70hRl0QkP01dkjg&Dt znsygZn&zVBXjh_+)O`0*qZmauFVUbxjn$lrJ&W(#aaBj-yJqqp7U-u+A17E7#Yr!- z5SdU{={KTyn?zHNPDTIL4c7Hpa9au5?t4k?wppk38mra&#`WIP?FMaHEw=SMJ1P>q z$f@qWPDL8@Q>8>LiZCzIzV)-fJv**(_U&WAIB$8!b*Y-~t0(VGy-p2ER4K<%0qT_E zyUR}LEA1)dsO>qnXQ-Wb_*wlf^=KPj^PPfD&CelQ1F7q_7Q@uqtsR$VY~5b(2tj&3 z+~;-G>eM_st8Qn=qwUSA*Iu3O`rfV;#!5sl?$fL`vQ7E3&%IQn+9r0LmPx~+E*ADz z#NW%u-1~2j$l`$te0pE9-0izX*&BC>V|si0E6MV%x(6y|S-Gw6yZsiWsl04V^(oqS zS^8Nrp_8_m@m&dGXlpv5Gi|5TQoD$tt+l@F_N(H)&5n#QJ3P9mB(hb1T;|?VvwYbH zw;9{Azj6$cm}ZT?7jU&J`>Mz1nr#{$ z8nu;nJ*kATP1p0n)P5&hm3;}czXHNtz=SPSkg00B4Y~$Urq)r!^G+31ozJPqxel-S zZh_9ts?zIqqUBBclrPl}UO!KMowbf`Zm@1gnU^##habUWUDM@A#9d=uZl=~t0o#1n zrR}qc8JLTHm!{Pw1-h236%q^d15=8GUOpzaZ@fhjUN8wTz(4PEH@?3Dzpzbx|MWi5 z{{BkB6gP$>y*f#jWpzSq*U<^HMA|u)A#_c!P9WueAmL}NlXsiUdYogBzkwTX5#RS$ z%;WOd{z|%#D+8TszFj(6-9TAmKK68t}BMllE>+*LT)Q#skxoEUU%>}RX!{=$?PQ&KikZ#U1q71A5VIS>4aI5 zW!(=}Y7BLaoo$+&2AzEOf;`z8R=H0n`#LG#u_G|G&z+K0d%?egNUw*-IS={!&2Y3X|1G6O-eN4zkO6=|L%U~DaWMlWM*#fR)h}Vs>%DP(#J_w$K-pS{>aq46a~i> zIlyHkZ!s!iFyD;B#EB8e5$j}I2H4F*#AO>`5^(*yJw*@RBMI%s%zC9k_j85TzMoS2=<@H>eN#;_)j~Z(@k*f6uLFfQ(2q#j@Y@57~D*eUf#_R?(5^ie4MZ9!ro?eLGtCIAI?Ib~WkwE!94*_pS1D?k>U+#DL=1aZ5OHiVd z?;;HbB0-5K-yY{8yw7(IbemqIl@D%c{Y^6p%74DrHP0m7P5QU1?<WBlqy|@NnTkMRW5!y#-X%-}63>q=X>d-Q684 zN~eGdl1fT<$D&A=lr%^PA_5{^3)0;kyL9(b%d+r)`Tl%=|9j4!J-d6(p8LA@&df72 z&&-X2`s0*PS@Mp*m5b)fsIGot)&5!Qj(vcUW-o@)u?JqJ-~nX=*uJEg=J21_JUq&u?B z^mQi7Bg*%Nb2=n$)L(VBtPL-GJ}TUP6eM2mH3b*@=jV5e|NTBz^cuQ0$MP$#Js$UEz^Osn|_&*sgt zdU}>k5f+6|hzCPgE-$7?8s=tn)es)^TH|+T|XyvBa{w6g2hjOauv)eG<8n3bq3S$pF6I}M<(gwbw z1l~yHrB5%F6~`L3_nfq|T%s!YD5tXwiCy07GPUlOFSl&$6OJCKWYSzFu;d~8w-_{W zfEbrj1C3jBnze&-`{S_-jD4;A2dyF#$;XszduB0o-RGwDMBXejUzCgG%dUXKW0Xgg zm1)^0i|;OW@8s!qjnvFciWO0>sNBPOVJRfO3&#^s!!qb+-P^)#_Qjd|@bmi{{jGW+c{xkrX zO3}0%ocE}?D^{8nS2d_#U7XtR1ieulLO5>#Ubg6*fBWx^CupqzwHNTltSh6m3TC1# zeKh$S$D{D8jsvVy1p?WlJme=ste$$=N13q+MM+gdU<3^u_O8qdVNs1P4xQeOxPGOJ zP(Dfp<-ruCR>dTbO_rBY@fRu7%1)aDU6sh$15|1o*Z4I0FZQ*$Mg~n>#-mov3uBDT z2v2UBy2xlbJ&~m*qVMXy4TVAx<}@_O*1Mft^QP~YUpMal}GJ2gZvDp zig{DKUt^CaWJ_Rd4;Kad@`jo!p8TmyqkD^%#27Nw_{QG8cXD_XUL2M(w}I*SV^TMl zq?Gy_LpZct#eX52Y+dd0wzV8FV}|{w5V)MLl02x^lZf6NzQRt?g*lI<`+H2j7XEv7 zsQFk`zU_@U$g4A&=^#Yop7~2$i$a%8KZ|&Ir+T5M{>F=pRVrO2kSC#jLR0`k?-~cg&WB224 zwA^JOAfFV=p?^!tbq9uNgmA<{tBc5sWRkLbWXwnCt)Jt6`J1M$pI;i~Z6lpvb z#UouJ$XDkODD`Xdfw_P%fQh5y($5BC#uzpzvR(%HAG0%l7}?P3NI79BNLOfN*b(qZ zIYyD!1tVP=gS3L%ol@!Z=PNvF0{$ImKR!}Z5qI8nCev&N|7%JE4R4j(^Ue5>A=%1U z?J=88xLin2#mf>6VUai@T&h(u=J0vJRt795NBt7f9~S_OnWf}MyUK@G$BwTGRoYnh^FcDLk*boX3b0r--3~*62*NiRDAIDDo47Qs<6mb|aaXV*%qp^-0C(#B;GhFrx{V3yNFPkjF@u<7x@9lo^`dW<# z6ZK-MhJP2G+P9cos?11ug9?_Zsn6 z_c2V+Jg>li>ziXEB_lUDkyIfkexLX1od1PQTA`QuR@5woz0&7OooE?HX+_4Fc}ZD8 zHtNXHu5C0Xz2f&@PM%Hup!hI3 z_S|W?Ez6)9H^7*tT<**Lstof<+S}W!fwouNs`ukhC7KcAo~i zfNQ^fs;tzfp<7?OX+oJw#`=@Cd#{%bVg5}mS48}cXY==OY>5j9IgFfl+Ainx=EYjT2iLavo`@v?{gV|!0f@*8x-HSUdp}U;dvfu|x{$@gh5}{(6B*A>f{AxBoqyUv2lCYil;J z0kz{l@bo1+&~1LEmes@<@CUb>C_0#3(yg_zZ2-kSB4f`EX(3OERTaCDmM8X^rN)vk zTwi`R!pIwb`=qiJhR_Tl54u({o#w7mT(S8gNVgOrIr8N6uK62Fw$x4V?(=3SSe&zX1U z<^J{@i_$we@wvzIb(I?_VO^3MMcn=E1#PjbnvX92h!=rvW62GT%KM7o6FdquH+;YI z!V2wh;muklJxkr(-yxNz%Ug@$fCXA3RCv2Z*2n)ndycZ-){!gr>dh&65PanUo#w5B zif{+k-~Cur;ep=gBfweyuGGd)>P4S?(Y6ZQTfsj8$@n}a{|MG%C2Oer^T)|$|1X8{ z$r!ApGB33xp^_;UwJf}^KHIY&K33B^V4ATjO=0W|ggSj!gTX37yH%o9*fKs4DO_gs z=>rPW2Az_6?z%#(0-o7xaoCzJJ`Ly?@f_fF-4thd{Q8Mb@(}K%UQ^5ZPC6Ox%guwnG*`Q1Hdp_ zyUWCBy33_RJ3ZL|_m{2ZZ*TUGp}j2C5@s=r-=z=EdIUg4^$y_h(v!O3s@Jmbg#Za! zYRGyn$yuOpYo4S|NP<3_+z^r&kCMiw$F$sc`os+WN2q?`MT?p8DGJ=tjbnLM&(B}?#6NhjYib5GdGlj z((yC4B(H+HxoYengohBP^;V&CJZQ*qJjUx^{Z!I|KZx_Kw!F+x>$a?`YJ#q)Y&x7v)rI7CGsnNi zGf`(%9L8YB9y7gHqyl<9>y|8@BbIQoz+ zjgR%Hnh#9TGH#1upb@X-tuHRQzP(fY4+Z-9QBmbccdQ=a#08f|fMcvS+LgUGXE5Ez zMG8b+#)}n`L@x6_bp6%RrXW2dtX&KAb=vudYL#+1dW;-lacX(7A}w0q(-(slkJHp= zqoe$Pq)~V^Xn-BED}vhKO#K;H@5NWe*BLa4bRqJiJa;{#fq)=NxP5~A<%Mj&?U9>1 zYD!sHh!G*puXwqDUcZ2_$6oKCPjn8-5n@?rZ`g6T57^l;dKXGb@6W%*`j8Epr+CSD zN6ZkgR)h9R<(*T&K*avq|3=4trm9gel65%YfnqGNJr-TD_&d8q;Bg|$ch~Gz!BN!} z7Z*3m;%$?4tG|9GY^_hJlPNzGYBegSUh@RM=|0=SN!tFk@F%AXpl#*D&NwRbS`Arm z5ZYVva-*1Xh%2dbCYGExZ%5SMxbxus;TY~>KZDkgx&(mr4}w=(pwDeKWCWx=fJSrf z14)J+$>L{cuFiK952JML?I-y+1xo6!hpBmf|5Fltj0DYby9Nz0k;(3{ z#c6bd#|tsl$$)S4WWn8@i8gru&H~M^HETL+XZkVsM>VDmJ32+feF|cD#^x^St*%X8 zS?S;t_PZTbU;XdHRM1zr>;r{_KPL+jY?Y^bo@kBQ3}M;LUw* zBBS-?1uHQzSX?`X?88%)q{*thI~E%UGaS1VYh(mPvB_9oZro~xD-JR7vA~0uWIw6o z3VGu%4Mv-Ncek2jWRmt~tX}G+&sub2pJhjiYhn#LxEgLQ@%tI0c*tiv1E5cxq?6U% z$hPDDaeS%&QjzS<>URs9y9xSb?>#%ekvi7HyoHh7aW1PDR)-;$l2#3dGUo?Zkk$X2 zC@JWEl)v|Sr_Xh@`=&}%=*;(3q=mB8CMWm!yMxVFsrD^8(JH!P>jGlj`X#;SD0d~# zHC1QZai8~l7!^%*tNL8u!0CGPJ*rB~f+|h(Ey}X@8{ve2d@-~EG#3Uttie}+c)jsV z4xu1XoVB&%eRW&%7)0?0KGJ!2_o+Y+ZJT?t9B>hE@4Z1P#-%51{CA(`=nggtTz&`M65)EcEUDJ-ox0DXc<|#mJU8KX8BN@lLgzS_Ug^0 z5mUJJa{>PoxL>9OIze(!fw7>p&WkxKJX2bKa`t_v(s5Gl#{N%cF|8A^pR?+vlrW9U zRTocfwQRBes9Eo@O_>?k*N3k)A;4-W=*rsoRnPlzYi`jWi4VFz{5xN$S4}`+7X9U) ze5{`r-mm5WYqSP{)tJcs9eKuJ3QN#Q())rY1{xZx{qPpVxN6TeGMBa7XrUpqxOT*eI`wljCXtmU}pR>a7r3SZ=A^7q4EtrZG>)Snl=vfE5az-~AV;R?=CbkraKU5H=e)#Zc zE~eTyF#65njnAiwv@*RDuJxwtlPe<{zw@K&^@%a`u$*`FW7Hu~eK>IG7P*gw@%sSm z+1&Qn=kHUC`rd7{n|IR}>Hc~7(2Qe zkD-EVp08Ig+uFNi$Mo4HQdb~Y1cZxf@PkQh-R4Lh`rT^fYuh_Nf}wrm_ZmS#yB%aN zki5g@3ccG&LqGJ^*&L0&fmoKmM>$az=_+a}aEvsOuRURL7PZbU738>pC{o!s;(r#i z8u5)630IR8U{;;gI6y7vLKj4ga-R^NEgR4$Zef8{1NdaMbm}=1QHgfhzX}Pbx!iN? z^2w2Nz$3LI>~DrSZc1S*Hr-8kVcGYzNXg4;Plp_XA|UlLoao#Z#UJ;Foo=gSm8YI5 zs1skT30yo7sLFijJ<~g1%d}J^>X5HfSu;Fg_M?@g7XqCfmzVo*d=-u$d^KM^q5V0M z@YRom2a%aGi^Ru1%q&n5Vq-;7K|!UE)mw;8ln>-jrP{VfzMKV`7_+ejw_fP^S?^Pl z{x^6@zn{g`5+g@T6?JF6LSbGOenz*;y9^BW03a^1s?|)U#MkGb8!t{hLj$?G#qI3y zE@C3`%A+qnhZt$1M53%3j7q!aKZB)LKv}%nPOt=?RxI2^l zeY9fn4u*qOokt@PR^k0?s}em}s1Cb#k*4WiFe5UuPeTRPO@E=iObiCQ+(~B8LUMZh z$CQjupDXo}PY~wPxY&?Yrs&LRjI;@k{E}<$Yg~z7$d(T^a{3m)tfK!NR5t>6+Nu5V z(9VnHnQJjogii2kaHvG0Ie=qOs@O%jwqqW zMgSz&>mT-0CznJ}T5MQQsDGs>e`_hbz31NwWLx4B^SKPyN- zuNZ-qh_F1q-i>2|y>o!bJ||Od)=|q$FnQ5WheOHJ*yp@_Gp`Xa<%XU=x@90Elqkj zsLx7~UEms!80AQdfu2Zz&7Vw!f?XNq#tWvSK?0Xm~>uYH6*I@BbL81V-t;% zc;H$Er&+)MPlkYqF-@2#j^Ex92*2ZOjaN#-1M8rKaTA#T^VPC5ki^Bvmqb5};*_h= zy?_)JEZ)Qhe}+tC%Xo4L_$tNM<3)yx&iu63;g!*0z5K+L)D-YA(e4tYYog&YJyCvD zfasz5g;bI-Ryi?OpMVoWqG@c^!`P9(*1Q=;(6M-wpls?fNR{8FV4^V#+`c z_bwfG{>o+kT5%%c0s$2-7#_Ri+7ZFInXhG8@HB~_l9i&pwh~$-^kacaUY|2#GaA_Z zPgLaO&_?t9zrgJnFyEP7_@XYtf&%XnSpg!&53$2za${vV-}FdqEIcu>6#q;gtq7BY zQOcHY@ls61O7SwvrIM}VUZvN5)#u*={nRkuQw2zT_)EH(7LICI86tuQ&x-W<%Z;6B z6P*@-5U87*FGt%ifN-eWumU@#^ejyrrpz_r{NC*|BnmMxH~>1-H3R~ zNd$>5gF!w5R~s(nhX^v>hnrAm<;5&b4AinM)!Uj#DuZo)=UpZ;Zp>@W!a)Mkvu}#w z8=&fskzp)LjL4AEsrCO^UiXBxr432=(b+Y+!1x*QSLYr~szhH@Kd(~xW`HOj2r13F;G=w*=!wrOaR}SA{ty%}p(5$*&nHi)zs5u^ z(2j7R0367WH||+jw|=NTaAK3RVh#?DYMIkVP!sMp%h7c>t!u#zzOHCL?lA+3GH?Du zDp*bx_EgJ4s>iIzP*hCbX7jQ#j*Gvca!=tZ`7%zs3oBc)+7VsA&o;E${wBbWAoMb^ zLACYK=)<<2ZtMT)#l_B8PM3`y(uVDCK!tued-~SVJGWyAtZHYKl5OpnS8o?rB|d&# z9|lUH-!C{qT9~_JeK7O1@>y?godb=!xFycT4*U}S=LfP8Lh9`}FXS!W4}o-gka_v# z-PU*f2CmyRwD)1L*t%!anvj86*Diiip(`P>W1+eg#`_zzYcrDbm?o@{OUJOg-S&~5 zzT)kr9r%CYz0*@EgMTrx!zi`P+wL0yCi%f8LKCEOpLWAWInLMPMk@bz_$Uw7Q5Ay{ zhP{G=3%z)e%sGJfeOorEnilA5x-wx@mDw8Uk1h3=<^|j=F*$Q)H+HIahP$WD`K7VQ zh@{_9LuALFGlV%o@?rFK)5ow^H+Q=rcyC$$j{j)vH3($5w#VA?p4Ierg1fQ}pCNco zp!fcLYF}xCu#{A^+O$B3)q`J(js zPAZf7gtN4=vA*pciv_RG*)F%F3U}#9zuSHnY#i05gGKIM!ed((o#__04FQJCr4pLO z_S~`wPQ)0vJ=!%0HFI}S&Jz@9olt$!adId}P!(G3N^b*G^2rijd1W?+at6ENge8sy z{QtAAcOU4kFzu{BBhc18J8e0!`VbJq7#ByqHCYGc>8jH_II6T#k&_Jjbt$oH%qn3g z*n3odxPH6qB@baBhdLI^e)7HZAe;RM}JwPuy1JVSKGUyq$I)Hm@ zetg#&H9PC@p7NB3`+dW*sKIF8W5=?uoZ`+>5vmKtRz}YfV{*rBp>B+YJBT#j) zZJ;SqX)G8bzjhVs^{I9KX5ZPjCT8l_x>)v&K%``FSfAwBX@9&0hEgqD^Xjh$80rN234V;%oflb^**J{1RSn zcCGbX73LJ_j;@S2N>&m9gZQ#l$0ulmuekLvo@bHy1MEwWOS7lP9!mB2dI#Y~7y@3$ zSXSXQXrwa~nA4}a^WlM_(;=qvABX{qv2(fXL#l{)$6HnkP_bGBq;M89G z#?A6}wJ;Vz<7<*pP-{$ZdPqtc@w^=V$vlyjsM{`jcv2mkj6O^{gPM}o@vAwX!@6JUP8H&1(l0&kK{QIHSY z+*yxFZ)Mm&MYYD7V~G_)2e`Jccx0X-f;bK5DwA5ixQfe*Vsv%!25%ir;CtEl9IN}f zx|e9xjY-g1$Ml^9eLisw$uOk96@~^i_G8_JmMa7ZKl^nCIl!a{ zq87`XhebQ+!h+l{z-OAiL0{(RLYR>%C+pYka@0t_u%*7G2uWp-q??x?FRktI4zJ`f zJDNaSuxwvMRa|0KzJKUWM3s^QaYCZ$-;!w1)`28+q&X7@&ClgVV^(?VBKTQr`%`;7 z;ODiA0#=zW#1v64a&|yE~3q zT~G(`XHsJKs!n+~&!!uA3nB9T!18x@TU<4)ATZ{i=EDBDfmVCMqW9)#5PDVRv2;s5 zrZ`+*wA3G@O52;07p?gYO0DGtLb{CN8q-Ey1Is1b5})_{8B2}m^=?Gq7gJH^QIdsf zyW)e@ia}wPTK%-b+^%U31e0&}p%=?V^tIZMG4IYJTo2cY5vyG$1E=@X2$W-k_V26| z0*_Bt*$k^e2{p(>^O0~`-?NH6=Nw6?-VzjfFJULWWZW45p6;d{vrhLY&-=IS7Cb(P z;z%;aEJ20qQedb~j=_V6WapCzldFuRQ5yy~-9PD^wvnpTK(gJ(FZKV}gvhD-d@8VD zy4LdGziedJ1=*w1?wb)nIIG{^h9o37#jBMY=g3L2Kqw!-1qFj^Pw={|#}b~FgA6ay z8;=dsvFBJ66KTq?aB?J3PY-}iEIZ4NxAM@d3kisc<$#X)_QFW>uQ^@8qy~&2!hbun z;UlSxd3V!KF1$ADem@*WN7FvAEQxxz+*ibE@)m?bQ&p{Z*m!IN;_ttX$mG`MdaCj% zjJIy0bL|WiqZZQNyca2@aNayEZ6=9g+8L2cl}Y^1oxsyoVl%zRTAEv8gFSBnI%j+o znsvhw+lv*0vb6i=S{}m8N)xfJjv9ZKLtOHghj3?AUO|TC%6}Nd^fz1}1p1n9RMYn)|(6ys`abjqSjkI#aXsJsJuY!x;`sp+WHQs>!9)7cGGwHJr+gI zF6XsB!cs4Vqpkodqvn^Bf<28^{;Nb0Id{iac`-DDbl&H>FLYCn>rrRVk^j-AO%|eybI?vX9^p9wY z=VtJ-G0CLup4^l-sSvmIF)45Ws87|r@1LjRy3IVA9}>00qKWw*gbC;Dg$?~XJ|CJp ztBDI%$6+Q|N7BEZXW+*BGEefSmnk!k(_Dz^Mq`&tD>LH%kBsKKGFCl+_j>Tv-i{ZU zSA|YA)-C^tukd7017Y(v5a+REl0+z^bhj8JFORN!e`g&VTgZ#<3B=?}lm>6sw*|RQ z85)fVbEsaQ!j43S;8>+oGEuf#LA0@SVYk|Emuwkc+GC-yTB1%f7WLPSA{%9XRv&V2kKVXTtQjol`DCIHmO7=n+B7T)U z6TPk1iSSNR9Ix+qmIY~fm(MC~)tvGC`su5_sc`Cm$Mj7rwYM1rcx*dA?EN^gC)V}q z0-zT!#Bim++XeGZ5A*$L?zE5Gf^P6;N0!F`VS6hHXX=Zz=tGzn9j~pq6RsxFw)amY zO}sicD`sd9$3%S98+EKkAb0>Lr|2KoOc8`npPh5?FQhobwR+6`Ms>5L|GD)iXt7$w zNYu_P^7X&??eRo%P(Jr$aOIb6AGhuPKXUN%W{xZQ^Cu;K;kFU?tIp(a++!BBkqff7 zV|NR=u67yJmAAXGnc3y1lS#pH0Ky(&%wMl`eD9)j0|o)hKc~%Lvr#bT_Ngw&8Sd-v zG1cHVv&Og~S!&+Xa=$i$CI^!2i3Bl?UWZ#mSRm(J%u#9FklQT1fA9Bub?N7yb{K7r z=NU!B9_Y=_Kb>H7=3ISHqLZvGSU_Ffj5uXLKzbHVk;1|*kz_4{jPy_%^yyoYLFCa>TLG0k6+2&p8OvaA^@nJwmPT$err{jiRfUaM zG-n59GoI~#*tx~VHX?M)v!manxn^s3daq}52#rtm)KXCG7U{Ds9-DY9Q4nOzefx2# zDCw#-T3xmw=}oTf%)3C;l2+nwic9MB$D;TzVDR*rHdQ(AtV8|( z70wQMf&i|V-(OB>R>0kV{7F@D4j4;G^99o7!=?!$I1mU>UU1pan>wurOOPJ+p#1qS zTfIXd-&=cS&akCUwnGiwo=i35ejBg@Qf4}TC_>W{xU_fgwaEn*WZ6By7-3;nLEFYR zRg5@ad zg%2k8X1{j64xMV*M|yWIj@O%oxQ{gEjgx%tJyDu_mknGN%%h|vuXI}(Jc4|@^UJ*3v0V7MV3f+;yi@rI_z}{S7NA%g| zml-U~m^-VB7a@jTGMIRnpT)R(k;?hmXEU=$1e;pj!nV z+wUn<%wK%`GR0bD)75R^?r>9TBoB{*2mB-X@EJzc^^(z+l>Xy(_`9%CpI~g(G@xbG zeLbL`9i=$~_-ZK)&v+g&zRNRCHLjSH6TEc6RW8+YKvZQ*KX#S?zL9?Rp=ykl&ISctF%9vHYk_gI6tsJ7Dmdha z5DUr%5xZv6>?BO!_#vm?B)Dd+yFQ%Ppxq&pR{lXAxF>mtR}o7DxE(H&w+28?=DfA= z;p(r3E3Kk+U`pNP-jof=J~k=<>ZM_GyWmjjwkAH&TjA`3y+{c&6{(IaVl_N}rSt>N zbP({lw_aN_MLf-A-mGt?vOJ_Jsq#`Ha05@I=qkHpyTo>y@FZDmWD1$g7V}dpy4jO} zL;3ZZOYtiU_CVpfW}Z&Rcen(@_nItx@Y)hw46hUyGpk>6Xg#n{q2t6QC38d~XE?Qk zn8=sJ$A<=qRpC&(YdS14`;yUg7w++IAEu|Yp<4*eGYfl5>R!DNeB*~16xlckW%Dl* z`dZY&$J_ugsfk+&0Ot3+}H?A5l zQu;Pm6TUJHjUA9|4xI}MydcpT@fC~)O2kZB8h!@%LYMc4!q{FQJ%578WSSTjFt>)k z<+@K7;Y=Z;{?*HBcVnzV=5i~9SW61hHYM)tl=$7BTYT?;J&n@= zgtTf4Gt5chPQ%m5$!rE;{QoNogEHWXVJ6klH{^TF+#jAyzlnve#!;`2LHbGITPK$KK)Th(|QG zch;ha8clkn+SpmBP@ezPhVhkreg|6dUh`zfi;pbcpA{CaDo7VMpPRn;upYkscA0tb z#Kd9w^~Expr@LX)ryH&qSL_a6JE{Mw0mH=n-7Zk9M?!;yAE??PJ^E`Iisl6LiXG$_JotpD*2Wpd~z)BO2mX)cw6f!KkUWwNSh2brB26&@ou2qM_P)sv%&>4Oi|8U zU7UP?qK{miw>MxW;8!(25F*981v=+pVP_#_c&wr?^tE;U(~~O4zHIk=rOibLuY0W9Lijap@DD3Iy2Ey64)6kd=0ph_5e-bil0w;?peM;a4ULNNn)+&fnHs!^VOl~iI`(mV=BOTmBe2QM2gnm7-US^jNsl-{{_H&_a+c}M(>^V4 zhf`RE_#A%(2d9fL0$HQf_S>O0(}3OQdGmKtRZ@2wPBM2I0t$B?SFQ?!xw0^qRIEnN zoh8J<1lT6;_1(=H|Cv4{*S&Z|8Hp*aeqkYV*KB&Nn^XcXvT$4|Ii8EF*Cinn=g5w0 zQ0-`89y(%PnS2qim?|pXYnd;w1;Dz27%AVZ2g*L%Gp+Qt0%B}pwW z9viba{83EdvzM4kme_RswrIYj9!3PJ^VLQkw=_wU{$DE}3(^9|p4 zElY9GVmh+&Tk%b;qwy?0$k{E9)L_(L$qmQRD1PY+Gb zm4dTD>To7l% zy4`Q~j~y=15f&eP#L_B%^ed_d#qf?`;UQ;~^JI=pe)BeDye%2^&i~HA)I*MJCcW4s z>1LRVR^R&OFyi4Fe0?hHd9>NwpY-lCd9fWNI?RN~l6~_t4ko54^Ud+L>w1+0n3OK` ztd6$G90owaN=p-2o}H8HU@t#((hE0Yq_DDXi!_eyeO_UrmTLE&MMCnBIZe{ru%Ih~ zzl5~44VuqKebK%RT#K+kM@}RQoQqqRsJ0RdG{x>cicm(`SDvtJZyN#JYFv+Ocnh+Z zzFiRZfx=tjM&Y3+Q9j)9l;vLFo@Qd}bSQl^zxM>iahly;YTkZM9(j85 zFr>SV(?~eBVGL|P8w9usc#VGyLV@GX5Uh1-Cz;cuJqBTr*1wCSy~nN!yy9@OVgzSAq)l4W3Dh633tqeAZfF!qvyeeh7bB0({;>->j)`FlYli9H|O`ej3uW4nbaEVKSEPg8WLX79V$^ihBrmmCW|W7brt96Q2!w<;l8V0`qggOhKPzjLEfcs^@g`wg zN#K*olftG`A4y9!A%>F2VLsZ|ze< zkatdZ!U{xaH@&Q|&g{H4Vo=1%8k2b^@7ar13UGKJ2p$=q|A4x_m&t2hBQZxE%DUqs z-5GFBfyDL`*PttvyR9eSh)cV7O$P#0B+Zlon^6m!mryw(=*c&c8*6ehsS8f|Qk(nGwXr;eGvLVD05pyntbb zdYz=s5E~bP{v$r88OWS{B;c;Ew(MWR#CS=T8|~-71F=<8ObT2`5f`@-h_(K zQs>W2!8|m0;f7RM&MmNG8IeHfy!ZgZKPeUi zID9_`@i%4B=9$l(LB{Yc_v4F=rkux~w1)(GCm!JbFS%`osK=W~?`!L?i|?d2JPCf-v#tgSQ`Iy!Uw0|KLOv!w5Ct6_PGf*jf&!Nf2U$77fX3 zwdp&U;Eg5uvA{$`bB`N%VY*(>RzBl&W9;Qx?^^2L@%04UDn{ayLCVdq$#QZYqs6&F zI3b1$GOAnax-#)y_xC!Mh2@xWLLK)Nx}P<6A3b_xNOr$@&unhoKJqK}xV3ECWeX1) zsoAX3yAHSgh?)M|K|iK9p|FhXAb!bsvR-*zrG@RwNvN`rVR+cp=O&kSAL6+Z&n6_F zWn9CMjf*EicyrM9Lf`JEh3opEB=&{V-0~+McdSx#t5$q<{D&()&>R#HF?O~GZqoV@ z&oL=R5WhL?4}4HKMh&-nC%n%`G6roE2OYLO5MVgd^l`b}be;4@CkA7wg6;^%GS3s( z7E~Worsp(x8|4J%MRNDQewOwZ|K-`=c_-ewjmJ!OpPbfuHgukl zzg8Yzlu2Ftt?~c300aqyx=bq31neSiMd?)GK4RSJ@^KiUB0X=f>@-pK%fck|>eTNn z)lTGyQ~D&2JFC~+e{e{}SgRTzSLL7y>sv4OSdO{>S!JS}$zI*;O&ZF?QwE9R;*A-cnj`90!ow(}Q$ zVroZrrguAf_TsajW%PT5`JSf@56TVnBQqCv9DYU}m6sgKng=U8n|#o}w#fdfSF@ys zNQ@_Z@U}PGsvk(2(=!}dbUq+A$=|wqaluG^=)NUe_CU05H1n`nx1LO%vgOF2>oUsO z(6+shFCKA(??;~3=RJ#R+7V^1hvGZ6rRNtg=7F3GGbpPqU{xf(!8a71F4ygEuS4%s zt|uW?-q)qK7DSoX?ahN*$6!#vDgW-}1DXA;^Att&eNDNYK?^se{SWL9Dwph=+@z2p%R@# zxhttKUeWT#z09EazPneCerpwPBW7J^e2RR~MpIatLl*myqt+j^94|t?jS%+!9=L`l z=Ws@9QZJl#jNA0L3-z}Xdn{J1S(n}qM_<3wNdhYVU4z>c#z_zFSkT{Ju^v!sSus@w z3%cK*Fr8$3EzR67y|wrJKZf8OVjHKNToGB%L~T=1J3u|73)m)ohPbY4W;};Jq*hV7 z%M+VPD4N&Wq$VCpCRsm#wLa||t0+I&z|ye#()(qzK2-Dc2-1tcva#=&T@e(i z4Sra#F1TIv5jsT>LEZSx-MhTiTyAhTC0hy8UHn)T5VY;_v}3v>;OzYB_OXYZDv)hI zn>3wH&>?TG+Ib=7TlG(+(1(3GG|0nk31_!Px zdZ3|x;!YL*zGiT}$ra2f94uIOk4#<3DIS^m)z+rTZ1bGta+<-`bbZ z-f^ml-4E$8xe{lRu-1vzMYjS}QBys&iF_IU*K;J9MhL3I@m?f^acKGJrF2%O_tGRHi%Kq0Wu z_-gKlh%g?W`yvrE_rm6vnjPh6rVn42x;gQKcF6ZjFTT2Bz?!2$4-u{p)B^9@qs!@A z*A{2zlK7sEY*-Dao7`s|K+$)96rRA9c2a*e?)zwbQ@XA$$RWo2@$2p7L%mZ@QH;V~ z`l78N!#u7S{YnA}+z~5#croDx$L647waL5JpIEBoty%K3z(p4jSr?CQn`&-_HWLjp z#r@9$LXBcuG%LP^`U9<%L*9Sou$MZcivDeoU2PK@kXRZetjI^FJZ`lLW=-w?@@c6% zErM@u4OnHGM1{M@$H-|U0dD)f!3q4>F`f6-ym=tbo3Rj^>R5uuj~~w~)5#%~4?%GD zxLH^CH&<8i?Mwb`t>>6C;bG0;P-k zrm!z-GD@R(^8SuA)}1@GVt^7gU8_N=m{aa@gy`0js-Bw2 zqu$oNvI7cy3$pv2YAE7IJufHbDv4(Thh|ToC2T5ef&*<8;^DXr@gd9HiBpqBkBS;{ zOd_`B;b`2g!TQmEp4-Lw?Ys`>mOENcThDTX^LaFSwI1=fgb&%dRQg9Mc5EuEpS&HK z!vT1uyO|6}-i^Q#cLguHu~{V(3`xwJw_{w3|xcIJ#EN- zP?O>(Kg2BJsigGW2BvbXDEi1ZF`XrHzhv#t*X_5te5s+KxzAV;$24b^tSfiT&8|~t zn-J&N;Of2J325`!n?BVl-;yd1L$RIj%dCF zgo6GJDGr!s>YkbmOQ_$RX!l_C7V7iefke1`(wz8*qzE}EI{ruIVv^#Q^AfDH^T1-e zB)4bM?1v`{I&JnWF+?iajXS98dJZe+)s}n(RUA#U@5|Yq`RR{hx`~9auPN;!L$kkb ze)<`2)f=Lnq3pADrmvNRi-Yx1`Rv?)t`y>VgPAwq=(%l_)ytgXvPV4 z_~V1+cJ)8&ctt{(TImmQRC%t_p@s z%a2+1bK4iLVCt=I?TrHT@2f> za7<{FXg<=&H>2XNV=yFb+S*?gc?i0a4$3G@%*zwZ+LoYneq7aRA$PT`kLPx`!e5on zr_6kL(`zOrCudXfl|3}};H2C4_yKliKyA#xTTK9sK1mL~F znHf!(@$BOx`Ijky_Flfu)UU+iJ7_Cgh_OnT z77%3YKNQKtV`E-Au;e|n7qmoOEa)0==VeSf)#Ngzs|G0GdzXoTCQrs=L6(|ADPjdb}zlwtd=~!~{^)q~Z55K1L4j;ed6AosazY-}& z7l`Spczl%V5%k}%zj>VssIjb*X&9G7WKskU>PbQ@uCqpam*%7HD4#F5pGsg3jKk9#f1&z(7ZLi?8{N^Mt z=;3AXd3XN4b53__Vdi|97Jhjk-uqLE{kZHU=?-iCTR%Z>7X6{pm*cI-96tQ#gisTB zV!y^AdPs%*4 zbu{p6w`1`alS%FijMWJzpXps1eZ&TJR|@s949O`+1&S==zf%|wuQ0W8hnrUK3Q{$H zuAEviCGsGt$BeaKTYq@XecOz^nym4E_gt4NQB2B(%}}9_?F>i9R?X1z#8xOi6yyI) zX6plApH1N)q3f5+)ZN;HCoI7LW06d@7Io^K>^#W`e^Jg8)ga<`GDmaAqS&3TIj%Mq zXQA6e(=tC5E#pBBtU9Xd;!U^DxGk8zrDi-pyiYt26Bii%k z^F~Q+^rkCZ&nDn_*T|Z`m@1>6=JE>g(JCf<%<9GI!vD_x`R!e`U4tEulvM_MZZG2=$2hFFFX}jeF3@&KXub2<2-O?DmEh6DSep#-d#}k#TM0k ziBj{)dVV6o^U4eNh)_sWUgBS>l(oX$Ysyv>{E)G}1}+~EA;fmjbcsP>-^-g3UX~>z z>j9`xX^Q=Pay>7yA)=^@VDI85J#QIB&%|-qb;rVcUp246p?ErX@rF<(>nfgg1%d z3(`nUNGri5Wj0he+_iF8lo`BoEW!zEps3)XnEw)ddJ z5vgR~-=`N+KLvO6H~LK9UPKK}iF}AQ9*Qs#RDzY)*U^Dbg9qp@FKTEgjWwgUM*e@; zSYMSq#7T-L#SbF0&dyPE$HZ^Y>1L~Djnkqm_2A=v+S%(gP$ha`QgY#(GO8&c#sju> z(yYMSuwpo6$^YoFgpArkf@N=yzn>1pPAq>LN{LvK zZYZk#vG-fz($hy>Lx6LL7II%{V#JL@@-qs6qgxqCJyzOj?+$iNY?{g-vyf~cWWB?; z4q~A>c5qED7`{ym8JDb1*c(oRoVS*J2aZ&Jm}&)WE952%pomEZm~vbdt;zBfgVMHz zZdc4fqw{aBeX*|<-vjx&?<_fb;ZkeM8Kr}OS_(7l zqraK3j=C~I=}F;8iEQpfSB@l3!VAG()EjqTYs%=qsZ;Dzra~vvTm!e&3;4HjN3C*u zEA+#_9v$^<^a>(kngS(54_D7ViAspbm{-`|>!}$tR=P|XwX==Jstyp~YlFfsjbwu7 zEyBowRp=amt@c7{$7MmuP}dQy8C4skaG)8>)2dt#kIj9dQM;8F4F^Ns;EgkkP zBlPF~6d&p;N$`Ik)kEXPcsiRF&gbWp4$6Ie_#R}70FMcKpkJ?+?nR@Ho>psvfZl0& zVgEVABg^vq8?ftH{f0ww>JKG%$(UExlERa+fd8IcO)U#401xy54mO~IuC>)R389YK z(;A(Yx4;}dg%T`KOga`T{@!!jTIZIykA!;-rC5` zkZ!=tceW9*5>Rx1k0Xmwdv#Z(4A%)C*Eu6&DIMxt5_*WW{By%DMq?cBX6=maai0b{ zV{b`4h53u9>NJEkcR?eLL$V*Nh(j+E_YH|g+zJ2N7;vUPE=KA8LjaY1*G3i#gZPYo zf*DuY88N5qea=$@?wRRV-MrW`C!*a((>uu&bASjRqMGnK(<>p4<-Mz`Ke#7d^cFWE zpZQ|d8SOctT?w&-i}!%`u2H$8-KaFZ-OR$LyBBIyp{eAMhw4YS$_v~*3c7sxO+@d{3;cA7GN2}g2NEG4YD?5=m^=;GXY2c1%e0miU3u=7L)36SW) zQxy8yqd$8@Ky~391JE_qCFw0r+zFX-kuG!@1e;zbhbH8?LcOPBa<5W zHkpLUZW%R=>D%EZbtae0PlOVY!`aFyr(o|H$C~*`34D8Y4yg@lJI>o5))e@3>QL&| zaVw=wel=QTClN0BGWx?zk`L-Psy1Ioa4vD0F_kkPd88mf

m#%cPeOOHuI^c4KH) z7>7rcHm;AR>I5$Rp>?`P1Vyn*$XVK2ow325%h*N2AjcwNY8E-3LCU>+lXZb+&^ck^ zR-X{*JYiOLm&U8KTXU-IJ2-=A5uBSW5OtF?42IPn>t6Xc0sAHq5UP!nV18RcTKgw! zO!dlb9JXyZvss)k0&@oXze}7xqWobbx;CIh`g(R(4q8jLUcoUJL{Poudz_S#vdpLT zvybp&q+tlPF_YA+PyRA5z8}SpAT5n%OD58%&`NtdV-bKZsNJVnBU`Q*tSi9j>or~p zw|N$^nQ)Ue!U@M6Zz)jBp4tjw*%0=vT=0k2=FNHTDVaDq5xo^Taa_@QpU)(k&_zIa zQ^UCcC}h6tLtub*t#8m;exG?u-6kyeuR3mn)DAI-rJsjrUDxg|Yt~|+YS^!;P$h9= zEO%$_e<3E;R9)}KGFS~^1gAm%5$ykSC8Rr~kqShIUF1f{TqF;_DNWNaaVE z3Z5mnNu>D^&TNfdsw5I`-~x9|CR;DMRFl^#T(6g)d6BC2O-7sjAiq6>^{HB8s}W^> zU1Z54HirD`y#Vn+K#ZyBneb2AODR(h3u^z+T(d8PG zy>acp+f0s%1qa+hLnTJ>k~U=dg^bJha40^)u-dGsKyo*8LNxDl*0OrtSv4y80pNl4QGv2F844 zP9XmxK$qtG+&p)JAEnUIKj4tCDb{k2@!!|X-2X5WMhOqM27UFhbZCdw{2AZ({9QJr zDg6~d#<-v^3Lj0C4XL1hmDN9MmM$$RCcEmaw@sRanmdu%O)g}hte6G( z+1}m_xC&$j=I-eojWWDCg$&S1DTn^;V?u=)z@>fU@e?kl&PO=7shW)#!bOLnib?-! zm$m;%ub6lGm|L??-C4TIkked&hkY%vqUuRPl(b|b60B)*MwPc(-rktOl|E@%i{*x` zEJ59HnXU_xl+m7_Qv{&_V+^X8>87PF^Wl10JbNqf@xz2HA-xi_V>Wn7PyOL$@-C;$ zmzvUf);^z_*+sGV{WY)_i|yg0Q`TQVLPYl7&Fz=*&MR!OXB4o_93*potSHS2gzy28 zdq$r~&{dTF8VkQ@cr^&RFVPs#9!elTlCQGLDv3D=)73OepyjeGXOmhfB|ciXTAJU( z3sQfWMjsDWlak@5o_f3maA})r{W3cLk{82JU-UB@=@&8AP?7bn&^{fb8$@TRFt0U3 z`{R>x8@2Af;*u=1gnE_V%n#FF3g=G*JikafrIAPXL%VsM{D$Z{4q zAG6KhL3TE*pZyR$IaaM; zcvDlvtaMiq)!yi^HEE`=9j7x7IK~aowy9#EN@Apufu5}(9fwSmX(E{b7-Q-Vf#5iG z0fwYq)H!5uY$WX4wFeO}QQBw>xb5B>+r7k7o_U?FB&zYOYy{su)t1zGv z`5p)`-Ocd@Gqu);FG3y`hKi2AB2*k@O3v^^u&5azxGyjclVAh@ZbUq`I&j?XWgKRB zR!ZbzL18qwY#Cf8k&82+H1XoK`GsF`{VL@0Ows>>C%Qb`CA~7T&rrA^`7dBzw@+z2 z7A|!2k||u!>_pRfHlqE}Dsy=L?^Re`xlD9y+VGF-)AyUjjLY}(0@PMf97++x0sJ_^FWnubdS9ZjVpTvcR-kn&*2rda&RUmnY@fF;KlhfiCuT1}fwDw9&| zJ2aKl{;YWTe*O0l#~|E+bB~4)V59Tr4JzlfWyPA)GgokCD z&ujxw>)9htX?jJ3j)$uluN8)>$6`}1SmokUouje`&wkIft^W~Ow__eae5ZbqSspby z2;w#!7Fv4>!Mu!j)VQ;b<%Lq(dt}G{%NRIV_?j4!PD#VX?(+V9GOL{+#p8-8Fm$$^ zQc`vqf7BsxmIP^C`-m-Cfn`|{JK>j28=cV->PjxaPvjsVEBB;up7TlJ30e1-@8U~T zUU}|w7V*F6mDW|xSq0NbxOqWjYFif2l@QUo)Z4^kgs`-I4!3t9Y2}wchEJf_pm@C<$qx~5iMsD z__p|?4jU-wm?oa>r`y%x@7PU>Dc}(g`I1M>f3K{ycN*cB!rL#!&Kn0&ko*~(F4O5I z^SJ#^rH)t(PJh5QJ^l%sH+DMya=QXAb0=hRJD9#02-W6wS<)AktNPSigKA;@J zJi1iiV$Bw**z{F(F)Hb8s(Au6ZUg##akl;8vAgbm;(ER;UThCmZIpFx z{AVuseC(_eMcfB$%tL4fG(6&rSMxGF5$g?J@zJV~PLY}79iM;I(`;yt6h%D@XE~%W z-nof1)-16~*88biU!N<-Q%gZ8=&}puhC+vcl9=>-{?73}uA2FbqsRNCQ`9}zjetMb zplh8jGOLZN_4}2CIcBOL-=eMIOIfo+nC?41Qt(SG>xS}8{v++UWxbH%^{W4=;l8_C zrP~IosgHbWAbnP--#zF`tIwi@#a}`hF%yzU55t_Zr`-r$Xl|m3qdp>%@Uau;4|)4* z*7QNlMe`bmv-Cwdtb*FB{Jaj#33PZCUn`;px0AEafSio^rV)*N8F?aMBLhpd;V z52UPZUYKt5Qok%R>h=y-#`=o3xPidbdL%ZnK7&$9VxVf18>^y~r`z(8ClVAqE zmaDtg2gZA0zBiq&r6fvWOsYG-Nn!V%zXLF5$xH?)Sq`o69>z9}3Z&Wq+;5Mr0V8gv zRL%H^`;dEB0(e;)VVDx_K`<}k8tulv8d9HqGACKD^(DNMTO;i3lx+kS^G zA!2MH9NiLA?4Z@(^I5-RZtIQ%0qYXfve(i`OAH>mIL>_C`gF`HB)F1UroXy|c}8BO zxM;lYr88)kHD9`XLgNyD4l-&*fWQI^8iJYN8=zEBpMFUpcdmscieEdi8bHNw4a}Mh z_zeuRS)i-Oqwj{Ne@pCoL&@YO z$8(&jS7MCHFzVNjzqnJ>f?Vk~$Ry&6^#4B#Fr)hX$0CIlRY4^$31p;S zcRYp-w>NnT16#it87_LUn*8gnpv!tu{xtt$h?b6G_Q@~k4rKGrb(NTeFkY{0HZC+H zihFfHykgS4aWQ(_RA1zoP~WW*jjNXK_O~i)Y2-F;~itxE|a0S_fJ(D zy~_4}=>I#n#0TeZ?+Q;GC5(n@R}ufp?6pN}D$GcSBAR~b8Zz;x$6@=R?M|~1FlB<7@% zuSvIzf~CG}U#+Q^aqR1+Pq_y7c{(jOMD*_?cvBNq86&BuN zSZpwa_d)AKej}n~l(eO3jD3Lvmk35Jj@h6gbb7v+ z@rOGim_>9`qGo5i1LTrc!(feQocnXsHNzu&)XEKTe0aoZ6oPWy?XwB$&{(XtRKEICH2@j-!g6SdC;M!?zCDJ zx`)C5l8hw?8UM9wg=bt71mHkV1K}sqeqyS_CTog@DzPevfh**Ss1|txw-2j1R z+S!7Vg|ZH)y3vM%Nt)kUa=Hi^U3Nf*16FJYoFgo;A7g*eo)>8$Fqljsp|@&Kywn-L z8ht&xO2!n1c=!r2O#GMl(GA-26@)QrT#cP6LFvzYo-euOB=jcw4S>e4iOfvn8!pLv zek-da2KSgPZK}AB)ly!CS5#2KB3D&{y`QBcVtCs6Fk_GCXYA2h6(Ybwvjqd?kKzN0 zJAAvg5b?`eiO!bX1(mYl0fenhDxN>#XZwrN%dX!NrI$Nm)>{*y z=Y9Pv35g>A#<}kCR$?i*nol&01^Gg&+@)jH$%bLMX%$9nZaR8$ls857G z0$050Jh7W`v?BG046DX*?aBV1Yg`^orknz!mK+8jF<+Q(fP)9T7!z($zkjQz9p>Ba zsuVS}R7X%{aIH#osV(-lcmg&n?dxREP}^v|yX=?QiIj9lzK58m(0|4WU8-^&Hc zZ4!)~x}dXB$W@=DtIA_yu7+z#e+;}{v-28ZQF=*zZzSmhi#foNh zlSy;CfZg&ek8p0`Ki2smqxj*;&brNy+e^p=;bGrWcHcc`6X#pE=|hr;V|mdLw)Zf{ zmyOQ|4@x7?Od<1fu2tR+tKcbW8I{9={S{|G!59;@dH}e})X!*7*zEn>wyC%84qJ!i zLlW3%4fODMNtoFkV!NdDPQRNR1van0CkL)7Tk&N5Kb`_+JjidM0bO?GRTz;FT_rz0 z=1etc!VKk8om7G1@huhtPVyCTNl^7#IDK@tt$(fEw;lg3u|lZxd$>P07K!95wVLr` z1;26s{u`j@J+BlNl~n{Q<}I{(qHFy2(0V;&LEP>nT4~C&T{U5og1`@^Wa@7-OOCsRw#Y}R1nmM~|>ROQVj4d~1-tY*uwD-(B^VvAFc zE{)1b9q3)cMP3ueSUd?^@{^%;eXxWHuYY`-dj1{l!go^`HZBoH#n!T*Px^mcPIrVm zftKWc#VaTym>C7PjJ;j{J(teX*Js+hyNnwgQ zN&*C*CMzL@buwHlL8>NqkbXGYuMYjpkQf_5G$9^y#3da{{}H?3q9gX#2&F*-gQ}RY z8UDZjEFie3U+n*tIB=MvCVvb3s6@n{r#I|7CmD;2*ERTR1+AJPe4F(1Z1K09+N}9n z-p$R?pr?qs)_6PO-xdf;5x8%Mma*zDsZ_l^;7PA<(y8G7wgBC1Q?Zz?j0vTQ<59hX zfPWvyy)BY&{=pW0KdepA>4qYfrKEd6WH+=OwtB5_@00Z#pC4jU$BC=1M(Dc#{Y-3m z{$cYM6Hy3eM7WsN-ZCmIi5gbeWSM`jUDcpF)-YI$JPAWU*dNN`-|$bT{auarS&|Yc zXU5Pt-qH?~UPw|mt3q9cG2v0Jfs~&()hziEcE(6^^0k*eg7H-r)_K)zbwy+hJRqn~ zEv656rSxrpJ=Z8madF*BKDPqj8qO%DL|jCv;imjH=Lm@N?%T1>Q+I;2 zq&rSh9R<~FcD1Kek(uFq11wWt^aGKPDOA-pu?iY^I-M{GCesuF;aQ(RiVSGIGxacA~OAhFa zRoY#pTLx%0$?_$SZK(;DTdGq&c8-k#w^=h%GJ`_u>HtVoLDA^@pr`IasMQaUp( z($;OYRJf>MS!}B|>d7A)RE0S>{?j#1IovEB zqy%nR$T+AnpKPc~YDOt=i%Pmnjt=;RJ`1h-UbGkL;@EDOfH%lq4o{j! zOc$c%V|=t4CMkK?qSsoO3&~E`pt=3GOWnBY$`lWE(_}|CiISNz?fmBobH3OIx(N=H zvdPl!wmeR6jsfK+6))w8YQ<=eF&hM&m^Ecq`~Qiu;Y+hUviiyNlRMu#`jsM}+fl@q zA*KesA5wb+hu_rf+I7)b7jvbl&ws3cGmvsEmnt|G%+b*=bn3>Kvfcg&cd+>G5d#)B zb%am70_*q-4`5P4;Zm-#X;-UQ&Mn!SylEl1L%?#>kKl_H7Xe(ur;XQAcL>fbLrgz` z&V{OxM)`Ze8P!XWqbR2kKUaq0^&z90M4Mi9MA2RJH#z=(pi8B(naG&x=~{vl?oWz> z*gl!vbeF_m=8o@8$Z1PVqh^{#)IW>bv9+0zI+`gAGB8VI$NY48;p_pwl|5Z@7T(bF z#%xb+;WA*;^!7+}q|%~poJjb@lN~f!$-^CXniEpk2^gyX=?Z3)VniuRp`OFo)|u!tvm7j{3WaA(D+OZPLx zE?c^eN3iknJAqWlZz(txZvQQ_2sDqJYfSZql(BY!>hw|a<)!qIbH<2w?bzJt+FeHX zW#T_MCR5BKass?q0JW*{PAeF;nc3ZkHJqD17wo*EK?h41J1g}i&g<#wf#Lt@C;^yt zc39a4aAR2@Nx+y#;4RaFIl+q~1JF)!MB%&-vuq(D$6|Q5) zrI>>{pkrWdvDKP`oj#u8BwQ+k#{kSTRg2GPKWKY@RvkHN2^4lCS1tXg=ofi%2c=qt z-(DvWVPb;t4doWig9cgG{VEDYaU@oy=hy4&D}`p~nfbWz^a?Dkh)S#Y-LR`^ZgoxS-PS8?veu zPFl*SJ+}Ax(qCJHv%8=>Yfn`Fj9)kwVb_FcRAW^vn^Oa<#)jK;y!bvmu2OK@ytBFZ zg8^$NqiUn(R37`dx-rAEO9Nc^PjG4G@)*r9-}cS1M{C!u*GVVz&;u^Nsw%&d#6Q?3 zCqD`?@dyAhLrh?;=rHuI34;Ksp3;bb>u|VENNe+H!e$D)0%$+;N&Ue7Hs9yOLp4D* zFYk)}?V}6BbhNnrNbrb4POcC8p`%R!;6C3Y37Z=@nh$V|kVwX=-R9wu_(RtN6MO;lVxAwy<6zHal&1>dh9 zJ$oNqqQY1LMA-lGSBN(W#(%L@c9WAdA&^Qhr-JIj(?uV<@#r<5u2u1>I;Ib?4h-Jp z6n;&()`EPNy#k*+D4Ig!Uv(1gbhyxH2U=EJ8*~AG_q_COOO$xh$&G{Y_|+7g;RvUH zyE3|wz+NGPi0>4pf1@xL|9C+3^V|O;M9P_7QloBfat2Unw3ZB^g0)#JBA`;Y!x~dK zUn*m6!I>xA)Uy5%gt?bv(;&QbXX6C%w5;C-WJMYkX63P*edVq6uCc|3uu(EeF`5~w z1N*3nWhhN_1*?wMJ3rQ==U@-9f|T9@QH)nSl}#>6rc7Rl|nh{y%?#Du-V~MoL{@<0_}15BFijGHhg3` z)&79tr*(U1i?yI}qUGa?benP&s1Z>M3S>CsZ1+wQEl$W2qv&F#uI6Prl4^pq%^<0 zbJ8?PDl;J(v+~g8+q$-wBW#>y-ux}U2CYj>U!vVVm}gmFfuOkJ z9rbAV2Y5dj8#YAvR@gTkZOO6l%U1{B?WrbdOS!3&cjg^_{_xLbtQJ5MmX9W^aO137 z`&k(fnhz#)>e)?Dca8aO9M$&(zmjmuG*V5{#BIW;P%;uuqd=_n%U;ik73W(9{pd37 zwI8kV%wY#R+Io}8^+E)!g$`!LNhN+&RmA5%rIEH_idFl@M2%4>wzZ+WJI+yG;3oTY z7P5P2zyC!xWfwFYZ=drF7*XmeV^ZL;A1%}nPZu%eIatm103|5Kt7v*g(#|C~B_0R7 z7JHSF7_d!rWPbXMHV9^n2EaH(?uY{28FNPLB&1J_TKR+Nq(9i4sVDI4>4Nn6VpWCX z?QsK@fxSIK&89DF7Mma^HHra-3B44n62@rRvi799$m2|aw_oB3weZmmU~h#=cm@N> zTk)PwTzLaNW^MRFlS!tKG<*S2O;hotpMl@mdb{I+h(LjbrP6D4MgaQrPgCNAkJub* zxnuTG28_>7T*knOw1csU@RXJxCR@@NdTge^F%53ZNVd*a<;k%ctY!+e;xS4wDaC*l z_nXnae2;FQsTF+6y9+rCBpK#iYS24$hLlU~Q(nX>@=bw--!e(W>E;sL%u{Zn;Ca8B zrCew7dt`oeOc&I$Q493)`%{0QBF8S?54<|%gV!7 zVW~0Y=)B3VqqRw=7A37jv#Ix|=C{Gl!2x0)e|a_kEY!(C>%F8D1dEa)r;q5Jgji8A z$^!1s(H66ZUj+=j_X+w9vK|mMB&VECm&|ElbyX)?FyK8Ht(vc<=?Z_=&A}9@@MiRe zM{(dnR%%QB;PtZnbbo~JZLqDnaLV_v9xmWyGOMpj`HlB-oN;sU_wmMm*B{PKW2Un+ zR2!?Ndt}iQsISiRQm1)hPlR&xNH^T81;YW$!EiuDOpIJDkHq}j zpV%zG9>B7Yj{R;MQ{}yy04Kg4ja*eeF$ABMy`eXQNS%dCbhAlvVI_beaC~2-fc`fN zwgZwE-{&^-X4kD}@%ur`%hK@oQP@O3Mi0&C!u--D=i4^_^J|_j8{)xqQuzX;_0+wB z*o-;a2{4l*Z(Bv8uz1B$u|K?HVs>HRZAzjyEZgwL7i?ru-F(q_6CzJYAo;n1DQ|7u zry6lR3{N9|O!1o&h9O#P`RY-QSFwGw$UP(=b10W53h zA@<24mF=`NRW$t|t}voOKVleh1mc7>l^X@xI23YMpY*EY5Q5gT3Ut(5x@EY(s}9R` z&u3KGBW;NV*NChM`;N;D;k6!<4k`Xs1%By2 zRX4xz(WhN@|7+vuzLMxjajQ66WV%L^W#3VrQ021vX*!pluFCI{X-)lJ1)0Y@h)~a2 z9PDluZV-%0U6_VOSl)-{m-Hk=`gS@XPU zu~i2N=EjG%3nY`s%}J&QaV2;*os_g$aL3n?HCGoV?PLQWj0YDZXIrzmwtQ}SszrZ$4e49FnWx(-Y{kFL%e(abhH~t^=qtnsyXxq~ASh3lc zXcM{-b~f3cj?$thc&af~orVvB_MWxW&7t5=z0=bf0Y!xYzH`((8Wo=uU4dpOK<9bf z$Vsf>1u~LmIQ(FG zNl;bLbd!e*3oSXAyh8s&YQ;3UMBp%4`F#IhCiRp)6?e3;L}ZG71CtfXTt$T{*$z3< z#uh)^AefxxHk&2auIBV;qg}1MxD&Tkrt!d z-#8u9!&^=>zs%U^i=5H7<9(zz$ES=&bwFj)k-kqFVR)}ntT^nbmSCXf4v$K` zo45E`B61;Haok24#ygM*PDGqn02V7jaTsV6VHG%=LXtk&b*P?8hn~V6g9WKkk=<`f zc==nf{Ex$M?VnrJ(qD|qZlvd0dmOVBneog#v|?chqc@jj32$#BJY9<428F$NEId54 zKs|ia5^H5QE5rjJf3W7rCRi9{rfXxZ2Ly2y>hxMkqgY!|ld&)siqvy@i~Z#ylpO;; z7M&#BXM`W0tN9-fDeZlxB+lVZ_8&U@@K`i{b-HtS*>9fMZ^WvT1X#jPUWv~45?1Kx zeuccU-p5(rN?_uyGpV#4XP7MEh23Ib-9?&eZ=d~OW%bxQm<=?xWTLO#Y2Q_8h*V0+ zL$Lf+#I5RK9RPtK#KqGTj3<4lDvu{LA)v)aa2-PB87q5i2t$CeXkD1akV2XK!#X)E zH7>r1LkV~TwUeMh&IQeGb8hXXfx5A2**--*M#+{1;0I{*AEbTH$)Xw93|b|$=Gf0A zM9C{x!$2GlkQ%CF8!H8_CgpnaNN;0rUm1T8>%1 zdq+?_rSZNF6H=`^{Gt-uH@Q=65NxJaS3s1~`9irP*7FV5tejx|MlYzTnfAA~T9Mba zyZWsaligRKwk&p9L&EQvG6Ho6qnX6cIxMZdLr$skCTDL*l(+gXp8ULsBuky%;nNQ) zUx1_9`(CnIQAIC!t(x5zFeKBXlF99$ZBPm!XJh_Fxsgm52O?TT!Izx0Yx@(Wt?g?B zTjE^ux$HiK`vI+QSDGy;e~lLSFv|$|t{4B@FdBFNQ&1@~~qu z+gTR<7Ko>M0%jG>teQuxzDJHQmo{>T-M7{tU&Jgb)E0T6WMCih1}C9VP~k}y>7;aY zw6nH=g=D?2kD=4Xyo`kD=eE3+Qw7p!013NsqU{ops+n0gpOmLLdQvb?gZ7$=n+n$C*4Tf`q5&soa+}LJtiyL+J)0Hm< z^YQlH>&Ze!vS#fVFry`-&#%&KL^3J)E#1u$VIB&-JWK^BB@o5W2 zc$YP8iTMer{bG}U2m6c?#Kq`5`9I3kS+>fTt_QigQdR)6HarS87U-GEm;KW>6HDg0 zn<=(Y`1fK&!6YqjG+D~$iEYm^J}{8c7VD_k>K+capP@GBjNCqinS2r&U=#nR+CN0C zX2=1!CD!!LopfeV>swWCHSqWevg=>nZP4`BSrLEqL(;&2jPIYJKQi3f9A7bE?DYV% z6a2fVR4KXAqQFxgL4wZkk{A|ADaOOL6#}Y)ijpbpL#SO>*=MK-=qsh^&Hmw)V&})Q zDvWe9v(lNzVK^4-Z`9Npb$x8nx)!8rNtO1o8!-1DZkkcfA2y!FVONh>-UwN$fz zPl^TFVhj7+L0gWBZKKH6J@7K`k}dR;k5xL6T{M4nXM@|$9-|{<%Dt4<)0>ovnvBCV zA@-Ff5h7AVpZNSLpQY}E7p&=$pbASYk--C#w~{J2o*Vxd4urg`V#cb8WZliLv6(EB zpxC0Q2_W@1*JbJKxuDO-RkKzPM+^fLaN~Rjl;WpRsro8XlQJhpV`Q!#=)AhsBGz{& z`TOH+kJYi>ONke3QinNgL^n5#lKqqq3~zpK(s<6@w^)wf_mdQ7e-sLTf`hx{!+d$4 zJzco}gn!17BmE+ycIET;`-KAjflsLNPq8R<(y#*(zP)H=jvm_6Io|I!8ab6Wfc76+ zyzSMY6@`&G&Y#r(5>t*}>lfWa49)V^r{RhMHFr@xW?mJDw(vHksm5WM$zf ztHoo~6dZ)}7}n+AJwXp)g+It*ch==1JB8$pKipm~T z5zAZ1zTg+A(1fdmqm8J2&ZYhhXUc3M(#Ld8Boac0%7X2a&`v1h`j-(l*(Z8`RzBUo zhGWMK*z>0YL&Dq97@uZ+R`x0DWx3Ry+v}jf+1B=Au>XxA9oVp3+!I_Y7i(78JU=Nl z>3)8cZbd(9GyFOK_!lkb4fZ!PST6y}(Eih~<`Acyq=YQXq~s)yUsYM2kAzbNzgq$p zLM<5!?9`#h)DCTb7P74ay@m!t1p1qhda ztFNC%o%+;CnCVQrk;{*fdF#W5NcHLm_Rwy+#Q_;sv3Bm4QD`qjN$GFu<1A+J${bRE zYZ@NF%f>>m7Weq1170iSyv-{IdDRasN6!L%RULRKmK#jOlbXv+Rbq0l*KRrNHF**` zypeD!O;)phi%>ci2)Szq6XzFOXsg&{e=I!@*q$T$|kWa{7-#shZBGPiFv=*JtN&(CXC)%Jj^Wit|Wa{DCg zOWojAMfiM6r3J>klc;a0;yd5X@p4`j#n$Ke!P(*b+2WHE8USUf$D;X;X@EXIv&Mug z5ASHeL3{5;l)z~6fE)K)agGcNLc1K{G3? zL^T^xA2PcmP-wL{I8`rlhA`|R-xnyt_4w^+olH&Jq*D$2+PYfgrDoPwSJz0-8lNrG z4}V`VGu=qK zm~lo+>GW#g;T4e0H<&xFcj0?Qi|K})Cy(U<_%Rqr6eSmi^9plC6ya`~shQ*N+se8* zM=5`<5nRBD|dELFOe;AI%9tgk=(k{OZnK){Bd zzNRlT=eYHFF!b5;@{Cnfm3@(w$H4rF!61B1Arh_X4B2}aJzYND)Mg*qi@a$_6k%^| znVeN-9dPu`T4V!pNthXWMSZ}N=o+wud(_ehZli6qOq6q=Ux>E1x}pGnZX5SHcctT* zgErDxH2i`Z%q0&ek?T!(7jJj?)f|@pdHETUT<4Q?JxT)zSmt{_Pz?s7f0o|2oGoFx zlJ2g-D_N?BEv)`PeJn8!iE38`ucT5Rig{2|4Eyv1J-qIVenm8XOK0DDoOmMv%5?-k zbLe(2GyF1vIr{D=aB-Msk*-wh0dnbW0q+D98G3o|U@)N>b8EZuvfOHEH8Q?#lfj+{ zf2;6&Q zf4W%W)l$SLU@uuFTxQ4S2av}6&coBT(srUdG6}|c7ZrU})uehw&P#k&%)?8iy+f1< z#WkDP#j!K027hYOMqat8D11R7fM;tS2U0}wI!`@cXxe`sW!-U0af0x@_`Q_;wcIn8 zm6`o(Q3;EbVdJ1~YnsBawc-PxhtvaqD>UcUodkkMA&SFzyVSbMKUQhJLMXGI(ft1n z-G38k9f5iCyy>&Ot$#V+bepi$U4-S<^HBOkK=b)6BcKrc_HCHn7$hX!2`$DJ2^Uvadk#RNC{ZnZK5~rI>iQ z_DPz;IPhGJx8Tu=ndDlh=L1%xGmNq=p)lpsFY&n3Yv(FyrzstMxk0VQmqppU6paMVmu%?>yi)Ao2v zj=PvSu;}zS`Nnf+)K!rE?h{_yDwn4Nw0q#5@9h^C;V*=`SV&XjLYrjO?|s_8WpUA@J$phS_|7MhP={SV6zk0j74GkKQxE&E}5p6$WLXCRS&K;d2Wwt<8H$j;Jr}{ z)a=cO^{wbQhXBb+<97XFk_flbxMA9H=|&*?N*H$KqSI6w2Z^v{Y;y^(hblzJMBy^E z(KU*4#-`(Vf^a4OHsdVlYR|eyaH`(~qEzdLE0PFZ|NBK0W>6g4gum!}CY5O)M0x~t z`q>B~G8f`)Z{{@!oBC-dXne{|$<|Uln5fstTll=fh9EI;)gmrUP4+IJa%o1RA#U=N zB>uV`0panlrqJcgQ>j4DZuXtm6JEFUsx_s}3^IrA_ot+{#tR`AQ4e3(xfiKf3qxBT z`6c9M^NXSTgFuW>iYwv+*?V?V*qVFs+h@a9Xla~}@USZ@>o}GtUNy0kT&-qFCeH8UhgOxLGdO7nGJmJnR zRaMp7jQmZZZm9PT^5NHCjRDyb@2}5dz2|tB4kn!|%dz{C1Hfk!OcEPn4*!snh+t!& zT*^O)VOi4;Q|4Ay%8Q2LM^*YgW*EPOGiE4$7dM(xI z&WHJ-aY{LDQ!qqEBg8kBgCjH|)>j^3l{PkA4C(jb z-HpPS%##+4vxt}3_d?>l#Uxa-q-8gTF%%CQSQgO*_An@TPB=OVYx!NLgj!{bE%(is zZeKQ0s?bQ7y8EYlH_a!a1bF$Lxe`0-SLxhFO*n~DYtbk4_?Nd+47!)MA%vbI|P{rEw zZ4e_o3B!SdVu(|BKP5EAJ^%{ql3hBJn<~R_el6%qPVR`5(AEfk0piuxA5Pm;>bkHg zS}eZ~#GqfsW=9owy>8t%ex8j9st2hMQ`$YWVDF>wjufAX@sON3&;&DFkG+@pe*n)w zFuz88k>)z-bsZ$Zk$=~1yP9!icoLIJJHLTh6vvwMQ9%`78z)JSfZZqGoCkjM!sMIC zm?Yl^aB<Pmh02Rt_DF{>7oJnU0Tm68 zbmT_;X2@ZsiiP$}e4qQIbL2**4b&NuA&L{QXYur@`sn;TpMCn2dHKvUr6Jq^aO=nK zz%w8EEUr6q3g_0<=dL@W_P_4zXal-~ch@ci0gTzgi%M^F5d&v;u0D76 zbNI{6e})^keg`kC-HunC{hT4(FRZ;A5r7xh--Q>~-fgW5#d&SZ^y=XqTEPd8!Lb#+`Ex08PFZGB6fA}%SqfN z%kH)=WV!B~by4gE?)c+USM$kp|AoT^?bOsGIM8aPG_a@gLuZ zZ1U!r6+Lw2PUTo%TZ1lJcap=XqeSxQBKbPTu>b0+?| zwZ6HsNqS~hF!EeCMc-3Fxb6P5Q*ft_O#gne%I~O}`yC{d0aq)ALtlc@Y`j_%@pJ1O z6}O-E(h%@#&z#10Ha`pixc2O6L;#*&JA@b3Z^yM~6hVJs{dNE)UUlYkcyayR=2)*f za~dzK-)_ZTc_pOUN&K%r1;=(yk`ppQVcNyU+TN!5XdXqUTNh?tiMevZM^>IT*B)Uz zK}PXa!^`S-Dc2ZVImFIfnj@!L8EfZz+YCmsoT}p=STyA=%$Wheg5=vSK*W!*n}Wf@Rnha88SjA{A=}W+TXe)1}eF;Q}o5-^7J^8-7%{|X70v)h7AZ242QbD-Y zYq#hL=X%?b&UtcGcanTJ$<6_o`K>O+hNOL|aWalf5y=C%fL@Cl7RvxtkDcns!blgQ zWQPcg5sARjd@Z9VZS$A`YMn@Tv0h3&OA<&ciWG>`5m?&I63WE9R%6|diy~HCLK0jS zjVGv!Gy^dCf<(ya8Kx(e$#-T&yww_);T5=G*0;KKO}54KNiZqeEejUbJF@%+W!K_C zA&L|5azR(}?Wa~%;_ZH>j-Jsk&cClqvYGzL7%VAC-Si)sZbS2rny+&+50WB>oPP7# z*lzuru240Z5;MQKdD=|E`({7asUTHM@($Yis7T~?OZ$QqRlXvXb#o=30|>>|0+t1D zt1&{;BO>MCwx`aPh1lK^Z zAHh8}$EVkI6LizW?Rzf}@5>KajQwiJrArlJvNMu}6(V&4gE)&SSM!VqU6g`y4^~lw} zlI#L7PNQ5KdnqCL#3R1#C*mj?TmoYjtcQ*KWEERWYZ$ zX%zr#*EPrm*?{v_GB30Po*jpM6aD65Xi|a2j(H$6s{z2NNC3=L)7`d7b!=^uB-_37 zvOWf2+a)gX_94ub0bS7;`L3IA>_?ch=VX<0j+n3~t}kSm1Cax{U$@`68YA9qB+#?u z+60#Xw~<^2ynNsiN;sRvxn?Z1kFpsRa21= z$A+x5tJE7SMiIc{w4Y&$K>5C3rQ&MerKA4)^Vd%xJ=yHyh0-0~J(?3DIRRHXmJ#)? zi+HmQT>Y#JI`KX}l5I=OC4F=YT~ZwmS!B|Ua#MbEj1ql}7gm!tsTA8lIuXf6D9n7t zbw;Xr+Dgg8ZtK{(PZCltF6TV5EvV)Q$IqpnfZI#DYCGOe2r8j~<-sD~Z6uhqy-L2h z_pNNfLK4gv1qOzED+5&dzoyua3s*!%@wNrGe1y7*4A&u$mFVNr_p8?iPolD$-o&#FwMmlykMX>`S74&f~MtXr|dWktPw6=qAfp zvTJnvQ*C7aZ-PP>yCIS`MTxjkmfWV^#ofclta~n_xfA``C6i3vRAp}>)OLZM!g8F} zS7Y+E?ej^`-MsHWz5}iX>=yBs zu~fNVoxB{Nluceg>@r`rK1}9%+l3}`v&Qtb1Cr8RsOH7I{kj*CnAfdCl)^)GEx3XQ zrvg!ha;45noO@S4BS{wqw=Q*E8gj*!a&=p}?w=!pK)wT(iALGEPi`qu=hd@6CnqMi zG(u_QftM3?WSL$Au%y(kw0f3zut|m;2=>btB)0-!B&Yxrk~Rd|N0Pf>yx`{nXhLLz zXr|1@wdLg`ZzdWiD_Oh6)##YjbF?*|=9PWYiFAQPlR;&k9T`4}9H}uOWTbh76=TSdw2vaqL>g&+=DO_a z`vEAzOa`TtpR4O7$7v6f&JmTP!xO@o0y6Y;1U=Q`N{|62$`K<+p_eDQ&d?a`Eb?5d zsFb639%J+5#xLU7@HkTRQ6k0!J>yJ?^cm^=1#E+x%*O3pyApC&Vjd81wWBNX_G_^Gq+4#I6rI@GUM1OfUN;l*J|^HKA|}~X9fCS+ zP&?kP9W|(5H!#1%e5{MBy6X@{woAkn$vG2lTT4dwh!TNfGS_C}Vt#fkhN)npfLna}1W^+O3p;#YwV{An)uk>|81$)D)d_quc;T z;hMb8zD2N2&egKeI|XEZI!Q0*#p4@y;pp%LR^fw|M$~j_9-IZ~? z48$UZ!F5-~;#pDS;SBkJfPiJePrT)}>T4+_uc}0CdgyAuIFCC5cbBm9y=A8b%I(hP zPT!+l&dG<^6t~Ve8lQE zyKJ>xhefMGDiDN^;BM0U7VaCZq-+aXI2W8$-t8laFTqd$mY&d zr#4?J7~>LRL?WV0k&ReWa&~bL$eGLiUO7snu53{i)rpOxxO4b~9%o`?^h9%QwU=$S zaYUXRCiQ4rdqaLNej}g$E&$=s*-Z?GWiTuQ_7u8E&YPp&O}{yE$k~Zf0CoSdDWEUf zoe1ZejDE{pZ<)r)GkRtUO0MYo67#BlhzlE^Rom&$+ueNw0(JrmlkYCFO^GRbI@huJ zA#Y2H19`su@I{f^s2b$HB*m6ON{S-;>iD|bCc2WeyWJ(ma#EJjGRjeM$qn>T82)V} znI)1;-dousLlUGqEQ=s7evGv8`?eP=DHr2hE!t)me{!?i=orllA;a&1c4f6)(Pj?g zC^wNXAj@vTPyEC;k(b{>6y0PUizMiZWGmmja_Gc5DjFHms3IE_WsR+87KrrsNG4pb zV(8gIV!qe1kWFEoO-3KMk2;$w6!~@w$`zdonfY*H<0y^{pVWrq03~vi7-NJLMArA< z|32hzI!9u1&dH_FcD`wXR2Il5Gew38`ogsH$xfxd!w+NZYQ@zehOZB#BnSuy=nmgX z;=0PE0>zz=0LTst*7Oh)UDb6pN!qjsrpwZ}o%%rE$JUp|#p? zwq`;}&U?nVk=0{uH9`!VxU2h^BQ{b;nK4dz)r+EsslHO1-0~QBEcJ%4FAB9B(Y36F z>qeVtJh_R$SK*T|N?iY`_u)Q~!gNoIF%2-WR4?tHb-!99AmHVSMWfz~(z}mb!PMWp zT^3E_?Y`1q+&YYNy{SFe)F_RJjQ4bLNs4|`2a0(~HvmJtf%$@0Br~T<=G11C+zMk| zxRPB6)pf|#1<;)VXx&T9{h#e1cZoNXY{0HuUN?WXCEi^jpUFVP1ArZroy*8&X>H?a zOZo!?Y%Gf;`v@{nPbTDciXzuVKHX#c$Z~sfX_ElCjibozRTk6^C^Da~663n)HJhtU z+Po$XER zi+)q_tq7#Hp!{pv2E8o?(j-I9{l0CIY| z1=ad`4yMi-G#__`o7+84CG!Firl$Ib>JC9J+Nssmgw=4g4#|RQl7QPbh20jBoZ3xu zmp{1Yi)Q=h%(~ClpKtzoG^FVS06Rp!*?W~++Z1SOQ4tnpI4UpNmDcCmm05SKED5Lr zM3Pj>$guodzLr1y2&IYO`iv}>AiKu`mRAwG3psW{Myw5&V)-Z+BeNnyvx%|)7)k5v zsB=u@+FR>R&~*gK#WD%Tm^vSb?&o5IdYO1`+m!85)zeX(~t7)p|nW(mmY*T?xx!zFzx0IS!T^6=mL;cJ5zkYu6&(*$f zN*=d*%w`wNGUiuToe{|R)rU@2e$_y=^BYUJh9DW9DPrBrHis%+#f2EiR7r7cczo_c zK3#G5@Ucd+EDL;5HEV*5B1htH%4Kw01ySW(+E+%N+~{)MJqE6XirCHMn6PL*^Srst z@?LTkY6aiKK8rwSrtlRXzeHqhD+HNx2@;X)MJDrh1i2YqqI527A}1HO>SF4Ptpfh* zcLiU(57Xber)~Bk-37Cs=@R6Zk1(CQ8I$af(NBOhx(S?rTk7by`nRmyF*-(xLPP=h z`0}|d%qM6+`I??>`~KU?1R3@AUv+i+EW+F+Z_xMMG;O0a68E{`s6Mx}TNH)PC07nm zsnm$9bHcj6>iiS*ks?EmbSVyHig8iRd5Vc~%0T^Z$bD{hij)V#F<`G?5y^R*r`UFX z0dhs-0lswbD8HZf)u^pO!~ zNuXV+Hj!Un@7zrH%B6mY0IWW_R0e~t(MQV2c%{E%EeCX~T^G9gapc+Vi`4x8?7d5` zZP|4m_N~X>``lX;m6&$SGy;gRB#NRa+3};1018Wos9UTYf-Q9g83D|6@@vv!O9Z=a z5!|TaE!ywEc3?@CEGrLpg4lr#LlWzrbM{`3G{*eq7-O!v9{X|bbC1HUv-jHT zG1pvcjyb;ZjWOn_Ao+Ewh<)1eex2VOQ#Z8@P+*w@#$(K%eeS*;Fvntao83+@lw;w& z|9o0b0mypI)6OxTGv!(QbmFtXJAco|Op-N(wI6XjC@ z2XpUK>clB9<#^Fn*gX5(XKVNs=z_r~`k1=;5nf;wvirV>zdS0!$BL{4yTJ|{e2&N1 zV--RdtE5tH8ONUHK<4HUIr1@XvBv$;xsZTFV9A1N8@#|H?6E?N8u!?s1($9UlUkXn zCak~PheAkqaZY=LTdc4@%5eU0`w2eBd%+x+J|f$+i)-n6L)TZeS5|(=D0xPR+pH`d zKNo}XBCms-yTZA5v#FcU>T0_D2o*iY+r|CKY*%PNhPw{c%9-oUrFS>jMZL1Z{^){g z1m4H4*S&X)w&6r!2bSly9mYbZ>>bZ}4kr6FWql}nm;>Ef zMLT6}?Gefv^S9hPlun5`7Ca}p$b~~C<=Mw|WPv{UKlc*nOBa8$;M{)Jcp)z|X4s-7 z;~{0e$xtXDV-~u92Duhk5I47k))LtV_N0w0Zh;DIGKTZdP1oKofS^MQ+@mm+bWf>x z&cZ=HWKy4Ai7qhEg&FTPTC@P#U_#fS=j))Oi-TEk8owoaXVCJW7SglqQW{6GT#oOt zi(KUG6%V|tzp7D^BZ%$_lEu6$KRgceCyyg+bZV3@hbr}fevd? z#U)Z3&Txv|3k}#6@NQr){DdM=B%k(4#>CS%5~24>b@yFc#5u5Qhx4fLpDqt8LU} zp31PsF2yU1Ib+kCII39fvIycW^xU8-pd~=(TmU)eB$@im?`-j09`T&>W-6C?ib?hW z_xQfxdwXiA_BmMSG_?4Xa~vz@Ft}-M$miU|IlPjE)B4`=|DID$LHJmkQ-_K@|I$fw zsq>Lwb?7Xh{_CS@Rsg8ie}aDZD?#re-ick!xA~ME$5BD3=N&q6Xw4vsjaM(HU&2_uUfS2g7#vWI=g;X{_E>h+LgiDDgSoizJnT?jl(xOi3#1R?ua}Y|RlHYCbHe#@@9(3*_gjB{HV( z^5;;)Z2eQtXS-2keE|7eR%=Kjox~IeX^q3q_u#2>KQzw6|^!Pk; zyIj(?r+#<4pKYo9?ULU_o9voD#Q*Vs{!@J8tN#cEx`9rxm21bqw{`X{d7in5gf4j> z)39^REN;WPva+nrRS2Jc51*eD)}4k@-{Nt?u9Ok{GMth9L#|xIWCVxfp>Lc^zbF*!dFup6d1@Goozqv=mr# zWLkYiyLN-SXko5#Z*MMtHPRjPk{3;@7+ zU7f2MT{^S{{Cs~b0Jooy2i^H|zdkzeqJQ5^IRIt(uuG~a4=9vB;lL{m7o_rZbxPssVhEZaBrj@th6berEkm^--L*yY{hwks80AN280RjQ4Bbl_AJ}7=!U*_+8{}77M)n zcKuzys~u?T998H-O$g27rZ!=nqhl(W+x5Cn5!Sg7@GYs3wu<>KI06Zl8G26LX>+@6 z4tM8zPo09&Q>J;qMj;WqqTTDMPF=v2~kTPFa`SsS*VtAahpe7+6< z88{u(J!CHP_%j{?uT$G`P8Ry14C5tjv}0x&knH;iTQx*#>q{C?App|tJe4y56`odPi1@44cbmbqcoT`6pK z4=GN$#})2Ii(}eVBBV{qtuuVOL5=%RV9m12`w-&Dee9|boKM(3Eq2z$d`WBM_TaKT zeVkiteGm32zu9o^J=U?X8XW{;h|1a6Hnu07%UHy-N8#o)h3>k{&{%XA!}7)OUB$3Y zuA|#RD+}jCK<$_s8(;c9T$t~RyvcH&D(6e=TOCQ|VC-{kpEitdje?;gkUGk);eAY) z`8n3>W@JqloR4?GDaboz$T^*oIc8gJOD>05p*LDKb;o;0vY(&wcG2OIcVaIC;i(*R zeeZaGb#l?mueTfszJW0Xr9*3|p!k`FlQlkccuK`b`#skV`zslR6!4~>?R}+#9}vbQ zHOQ8R19K0yBQ?g^E9u!(=@f|)J6>M5ir8|#L-J^)H_owK(5WE#WwOvyZOwz*vGaH^ zudM9Ux#n4F@4&D?T&w*Lfu@%dZSsrf$L+-HQ%i>4aSJ4d0DRh0em(&1uaax=RKL{g zKSs0r`aoYSktOeT9&me|<QJNcV&q-qRm-s<=dz9B zb#;bQP z{JcFx1NlnkxzsWMNayu)XqLkri(@3uvDbe+^y5WOzg}{B>~aw6?NNiDtQJ49Sd9df z(p2D3Y=FpGq(zx>YuBcLKi4L{_!92Nki;P~nu6tA2n;aIB9qz9G4|Y^7DNKZ8Qn2? z(<)+*1EJI9p>vs+h_4!b_ykhGM@8gi8i1$XUhhECF`&N=L7y!=m;=fjxg6sufTzh{ zj<(gVg1}MEb2H(@@|;@0QSYrc_nHeq=e4In__1Qa>)3B;-?44I>6d2rYbfh~g+KfA zKfo`2CWgGmN^0$gbWi|18f z@OcXv3+#V7iW?xFIp?UdMym~Z_eO9L+cN~&dQVH?{a6Dm+5)^{8D9!$QXBIZ4j7U;4_|T~Cg;#a?yFoEV$jQ};~TMgT!4(_q>|!lqfvmm*ON zvZR*)%NixR$)cB*duGVA<)sziDg&(sUTK~%=MAzg%t{v^dXL(LbQf{2JlJKAa4&0c z4#Ox*SfGp8KAp$P@V!TcB1BZ#b>1bqt27WkH=7hE{#z~m*;V*(GWjt>P}%a8}qtfMTj{dRm=&x85@w`DJ72S2FCz|q+DbL4fu4j}nFVek1~ z&v~AgoJHTJ<>FcBJWD**J~G28lYNYOvrM!-$5KYw`{sFUT262pDBDnCy3o86YzXM> zxdDVxu3PLg>Ek~EEqYaTU+7iKs8KxNwIJPIX}CPup#VJxz=sY!y-IIB7s>HCoz+zQHdD|Ri8}g`2XIVoo zHR5cUI=ZkbXh}1cWb1)YxU-6VU&ioo+qb@OW@;{59xHV(>2vHtE7%^1Z4&NVkFtwf z>UcuX`_ixa%=&m&2*9iI zV(JSS@VVs$Q#l9d1_XHTu|kU)ci6f45~6e5Xd|(rH?O4qsq3q!Dwg zt)bAn?PdI3&yj+<)bL-@G7Bt+p0@lTNMFe*7Fq8_zU2mRKXUvb!1;AxkyF1W#RATh zi5d4Hrswbqa45^ba6UXbZNoAa+B$}G8@WRNoGmc*PM2}#!FXN$W$o2|w|;rTDFGh{ zt;>}{kvDUAZVS)Lcu%bDtnil*g+a1yoDho!*20tL_=wzvOhiNlXLT#_S#d!@sZcX=WyO$a1nxWYaxi`b@@7?pE@?hm)0#Nv@J@EE#OqBub%0!h*m7KwA%`V-8pK=Ai(sK=8 zZV#4i?#fb;yUYX4apPU@G?jC($mwA2-EYf|w{5pd(SP@1J&Ot$4;jS%{HYHW?z_LP z3R%+ARG9~-d8Y&0$ala3Q~P_$WFOWJpb8Axl(&`39rf`a8D%+6ST?y21>AXGw4GoT zq!i&eEqciQQFx`#DRs#7C{SbXCVOA8ne4ab04tng%8J(@Jogxgct~(D2EesV)+IO8 zM;cNM?04TlRsS*m?9cxIzxb8^Y2upWzRu) zTC|e)m>OT6Rq;#Gv;$*L-BL8~q;(vN8pTmUiyqAt?zBc@VcOS0SK4R;d(M1EUY&2J z9WxeqYe2nLKu#;3du?2}&+<(6=;5mk7eF|xXf{G^CThXFM|PYj$36Cr42{x5L^1JFf z6y01I?V5AfYoRrp*Dc#peKQZdbGGGh&*@n_1=uMFPPHuClYj2kacz&w-9!HPC41#$ z8Y{e9xh!M$aB@P}dCE9=0G|GCp_3R6WmHHWg60`yz`uYrNR~?O#qUN3o*HOVLV%q2 z+U3qSevTyrGj&Sn-yCbHds~OdlH+sxPAf$PmY!|1_cnir)(qBdd2e;Dp9|N9&Z+dJ zl4qg)w3C-H298j2>R2y17CQC5r(RlwUkM&cw9y18!gH|3KRHKx-n6&MV8W-MiD0CR zFrYW*(`ma3OFj9X(%9sZD6r=m-%NNyVH?<-b!AUf*Ab@L1hGT*q7Vw8Sk{@x4^gtxFCOc(YEh zvfnZm=ol!_V}-qW66~KcoU_kH+wUW%?=H z6kE%SpKH}+*F%d;dN58$9Q6Z3&i8nJ^R3bA*!8+?74uVo_ml0@SkYVncpZvdD)Vh4 zkf?*bv)xw8usYgn=s&T9;1a;{cp{ku%{-Zh0_eeM(p+#=h=3f1#>3 zew%)s$3nG-266fu+mI@aROyaiKLrG1gJ+`X|a!!Hqd8BQ$#%%t+ z)o4@3)wg(#0Zx6U>G{b*k00H~31uwX`Q-GLAc_cf5?>xQ4P_^LVbBbCCd@D%^`21AK2Z zu-}74@9ayRd=DjKp7PhZJ&3}z_e0~n>~S@1n(Z07c}pS)2#^aEMe%DzB{09u}J?gbq4 zyydppz<0|MjknJmc4Iy;HRbPB@tn#G`xZ41@d9vDkTNz~p zM!5iugeJTGuw5Q36^7mlYbW{FO#lYu-1yIeZ{D+=BB&I{jk3#Y+$YZ&=4@pMNw@QW51+0;$7~O>x`egbW^ei_=$Choxs}XntYb}e zT~FJ#t#Nu@-rx=HV`!#;ZP_ks;A$dEYi6|~w6+dol*TsK_^krhw8lQRO~;+yDSK~) z#;{cq%1=|iioko19%~@>7SjL}bdSAt7r=dyw?)pm#F*b=Q(JPsrVclaMdAEPt-`r> zO2~E}SH=7}KF52;DX!p|mCdaykWol!__=~_#Lw&<8)BYXyF(Ce;j{g0p|1ztshwa! zx3#nFu~x<${PLU59x2$in%BC@{aJI4b3eP=`%4|`c`%-L)7w3kignz+O1Y#S9WFFi=gM0JSgZ1$TImWn-ff5?*soKcjSAPF=uUr`NmdmDpN&K z$P%ZX+SFIe%+XW`Zid^v^7NIDhvygzqg6)!v^=!w{E99UDLUSuE8w8T9;}P7eW=d#y<3_&1+4yK>93leK+($zZ&*$ z2#Cj}+5H;o`j7GN|G$5Rzy8<$#{;h;VhsZ;YUFsQ))>1?a7nPs{cI>T;x(0BF44w! zr-<)l6|YSb)h2A@9UPk9&3|l98Q(wVTki)w81A4a3) z9OCwUIR~7%$VFav$?4n_9IB`;w7^lpqm4Hc{Uj^c>`9HNWLYS*&&DK~YorYk~g<$DD=btTeCsR*oIuZ0?@0?T< z0C!9@ocTG8D)B`hd^0b!42+U0aSWL zGK2(6ZDK)suyAG zG_kLw4HY^x(K&F4V<|sAUX^p|A{TktGG^PV<8rvKS{#TvkaKGtR@0uVa{lGt`)$C4 zozIC>FkcPU?4}!ik9D*~sC)HusyPeuSMD;+>jwO?VeFGB;GJ{o*?t=mP($FYKzo>K znSWL`+Edr3NU0*)-7x+DgxEZFdil^EUmMEs)o#79*+T?CUv6ZQ@s<$1l~= z=jFt8zU^=n87ih6(AMwjck_U1>X8-DqHJm~=DlKeKzi?zcNUb%3u~cnISZD4-V3WDY~c_96Q)?nvCBOy(~~L!nyUJ&(tBphq*M`59{Gw1up9zx z3xIQCy|@+b2hVS*@ZQNpPqD;oA#*TotOr4M3Y_zj=c88G#c%mATAgewkfHXBGC_9* z$w6fZEP;s@jnclRmzRAh`C~1(E`1yJCFmg#7sF$h^cP}SFO7hEY|x;_J+93C>2iEh z;)<2kWu#Q-LWsJKXA8ey#w3$_pN3Z*>cn)v{CUQVz*Kilz0+R97K65=jy!#z)Ip@< z%r3l@vddSvAB0l#E#g~Ig*UJby1<4{!+=S3GY$*XS#wZ|pY7wjMOJx@`lz*Tj**dh15w;oiHV~ zy7`=H8Cj9|eM`ahZZIm|xR#=GxLj zf$v!nLi4BIDXS%oE|a_36@h}@Q*N0+V|f-bw&0|w{pFyghOQAaE-^-KgqJvCpBd8Sd*#?5SvCl)*_ZY+kdbDA3LYxrh!moyH8=jva+qS`9*XEh#OWV~Gli`#U z=mX%`IhNQ?%eG4K_&Ef?*llb(`+97ffPAS;{>Xr2#A|cf7jOdz%gFQCJXD6mUg2(% z9RxH7)jBgORPh;j#_@L2;Ghub)Yyl0MoToPP@uzo@apRXY<gMdnV9)qm*#7ChJfbeXfwKN%{K>!m1N_P_e$VWumF=}fX-vS-nPuBxi4oM4#*nbJ&KsS&3$s@iKfGOaw2sv%;j|hUWerLi3Q$6 zhjR+;ZC}d%TAxEB3`_HQY@W2}LUgs>cLxon&oSa6%nK**?p$AV&=r}|w?zTFZ%gVv z&i9kQ2W$HcZTcLY;6EMWWPRB{{KA5JS)B7dR8aDZez(lY7`rnZaF*fp!7u5noSsp` z%#~U2Mw%UvfL(IM%h-}pQ!iwyAlQb~nCG2XK$ZjPfG@U{dJiptvi?h}kSu%al`e}J zd7zSGmjyohCt$_qgBHoLdJkIkgR1ioAwV8uiq#2_0{Q}7V4%wh5WGZk05WBX*)H~% zOdefih&Kjgvvp~Bu7AFM{PZZW4u#7oDO;C{XOua1r4B2B6M=V){UTt%eXh69vBN6d zqde&$<2YSR%F6SbZ-v}eRzatankCsJ*Od$`S7w%XI_I+T;5_%+v62JcV~qC{@J=0O zbDnU2J=JV|^EG_!7r%ydF~*!>fcQSyws>9ac@GaHwbHph>m|_*l%L#u8`s&m~+-H zVZOV-Y&WRGf`w8$gEb)N7L`c9I&1S1eCqyc!N6Iu-g-~T7$n<=`{~}f&nmXmo7zK4 zxM*|}btqe^t}}}>1=1-aUc}!lD^8|-2*#D)RU$@ zHvD=WSm5;99a!~SS?HY1F{ESp%{GWi*73Elp^Tx@HcWa-QjpB^$=z7T1eXiyoTJ17 z;_L16i7WMk@Z8)vP7xMss>ABSEvm>a@_m&s-)0d*ZRPpRbv6XH4k5|M=C%s6F7LDC z^R{ukHed*Ji!OQ7`R*&^9)gQ=fQ>mLDt}DQ2(bX%Gb*`j9RkeL<9Ri8>5!$-J=6AC z6U(y89P^C2V7U1q^8Dr+*V|_((4)dSUd{YNS@6p`J6O#+SEQ?l55YbZu*qwZdLu zerW|=Cm4VW_nwm+_+G;F(HW4Fa{=r*A)sX#uDCzSIAyP}Tg+Of!cgQ#xQ*jPYOn5( zW*nd1Ji#}&KaIvi4rHWq4p4oHQu1O_J4@F__cvyz^f=2 z&p~?6E-UEnqpqu!tB{_$12`@UC zR@le1i=}T}fgbnR%KU`grA&hk9A$ECo2QnH8o%>0UW-LF(j4SIwx}~c&v<79<>?<*5SXQ)u7eg5vnGgTmydO(+3;!Ve1=b_u1Ojx{OsGDrt#2`JJkPH80NWzZO&bH zY}=UlCp{Ei`^&%g+xXr@J3hYo2*0)cY;Z2?T**lZO@X<{Mczdj*WW|%Gqh!gPSFlU z2=4Z_Y~l1|8y%NpvLxgj0BjLgyQpG=RkSPp@?fRY3)Vd;?f3Dg>D|Ko1@b!P7`SBn zvou#P%-sQnu_-+eFU~hT$Jte_6g|}=?+0!8kP=01*D~W>F(}Yr9rxT>Fy5c?pV6JVF`g}@Biob zyuV(Zam_i$9N!t|i)PA$8Ya5GCzNEO9fMYJQr!q=fK9C3r_39W`|ItpZ?e<;=$CzZ zUR=-hxf($;d&9=}e@rFnbk^|Yl8J;z+!^X**;Ua}6s$GZVy_6&2EOd5@ zmbvGRHg2u8D$xXr2RATaA8}iXNcP-DPG(Vf(}4Yg87}+X1|Vn1pu8Y5)b566Umu{= z%_c)pcBnvbS1T%`{-tsZU{dnYm*9-K!7X5)ShF;w*JFN0RH;zI*d}wA*Ud3Uu3@Bs zlNn^DM3h3+mdWaZ?vrXSH?X$emZj*mH=B-QoSQ$_X5G^yk~P>^j0~6B#fEm~<8||n z%2up1U{ix}0YyJ&kdl}0JA9KGF#?7mJ}cPfOl80kZ4*93kBHhYr5!VegJ&k}^f$_U zt3S4fhS@4a^i~jM-&u@!wB;9BH-cT*OiB7@UT_hKA5yck0~hQPCIWlGLJ7^h)&q*e zy3fsDa4;wf$8f!Kv2MQGXIY_eajY%V@-*vL>00k)8J&Atd9(TmtSPm^t{uMC@zXWk z7mb#y95T4}SN5G^6VvpG$ks<|#h(C_`lU4Wlg5CGh%W1bJoo2)b1F9BNRtin8>}XC z{egg#Oq9U-Y*+h+Y?9PZgomWh#PiyqNj`#U{q&jaiGI zd;6aA?2Y0d_QH5eJhE312|b|0RbFl>25iVRhO5Aof6gTLjed3B#dIswyE!*lg z6&Py4`y!!1lN#(hz^W4E^+kLghKbyL9<$WcCp4;xy1&^Ovq{JE$aTUFA_Mb5?*@rB zU#e^09TotWp3gzOdx`_Qu(T3cdT&4BTvzjK&huS&J0;gG_wyOycEN@%JU7m76%E@QtVpyJ=B6BP_4lRj5bwthU^1+a;*$ku^kARx*`r_aizvFoQ4^s6K z{(nXG3Zl3b@(a4iJ!Cc72EE zr=PDa?7YS6ynRQsRWcLfUWym}JYTK*N@vv?lC98cU@c4>{cB%E1P;1%w`HpR;M6&on9TbTjM&X9w zoO-=x0#oOwue4G~i)oHWD0-6&FCoL%_L%Z&q~-?BZPW?dp3mxY460%%K`?U`UBuXy zO(--TVn<@RFX-R=V&eGo2)NkRG1MMQpM?(Acft-Immaqrg-@q?*#t!du!RDhn3;{v z{e%OOC&w*IKW154K}N@n^!7c*B#1c|1nkbNuqi!of>BxwwABXcl8)O)f8?%$B|)_h z%+;?zpVz$ppD!m8RI;avF_tOEQQY?dx~@!Z8Gj~jBYF2`+G+-(F0Zr5&ZdX0WA zfmfFEWGK)nE#v4&tqZN|Tt(a&tNR2eEU~O~?XxNBF{$=oKfonm6vcvL;@yJ4pZQeU z#HG(;_tNa~$t`hPEv7h)&v1F=!3pQ=wN1L`4zAlypac>1!2XJ;Xfo}^EY-&0WWd)g z2XB}zt?n7AB-hW?0YJ%a6z|m1kT~vUoHn9RpWmEG;!TrQkpF$3U|xfBlA|M|o7^+M z-D_%-S&l4~CT|u0t1chwy+W-4$$tLK_&R!hgutZw;g-3_8!I~0-!56?Hr0c=qU%v# zF*{0RU6kpKjh{oR@ESuS<5-P@*lNNNbse78aT|XW$fJ=}DE;Mw~ zibr#Y@@;p&Nk->>`hLf-Il-<4%o!l0UOlQlSMx>#cL?p|Dx$ij}-&V zki($)=66Nm19kWR6y|~0?G6uJvwJ?jc%9f3Y=2ECfRg}zkJgChyO!#+21{JE^u{SB z@k47A#usf_Q$C7V(tphg|8m*Ie8kiwn3TzSC8_!_Jb6OzL8|AJ$cyRoc+8vp}=$Xg6$eG zbWPbyrTZMc$s@!UuDu;O(8Vf#CXgjSuWt-$^u2+Qo^lKOX1^=>KVh;Tc)HUY+d$UE zha!B&Z=Zs5*9~~+gVi2?B-7Jz&EJLC3g&CyFM#2qhgb1{RCZ!L23rxi#PqI(MGD%B zmDzgNH~mw?fH@3R)~2^{+141bY^U6#E5SuHy7gRaqdiv#Zf0x??3sgwbr`HN9PqxX zCZ<0iUHter7Vxf&GXJ!xl4u=isPZzk3+xG%ZtgOg<|B(L%4pU{yaYTg*!H}hjYVb( z^52paOb`%^{&J?m$(nUv=H6C?Th+h8_0%A~RK64u6^S9so;}C`DalcBl$#JNpjEDJ zjvnxQpcY#e?bkCjJVqKNryxaeK}+@H{y2!2y`w9fy~dY>F>V^!y{?#bk8={Qby_UbCSFDxxp!Z<<_}Voj$zCG zAm_sw@VyOB%8DBELg8FT0<5;LX@t0NMU-FvyNvY~MH;on7oqv&u-LZG0LSf)3XaiU z@)NT0Mw3yvX>I{b4wRM&b2hT7zFDaapt|@v36@B8wfSR9MQ^G&fR)<>8EP47`y@x3 z9QJ$=t=w$-oqDBqp}(O%=O|wGK-Uoj%p!F9kgs1F341oIxp-qc;5@@!q1xS;r@1MB zMFe)2?y_5*c>NjEu$O0Zz>A z3>36Uu0$uWd}PLilHI=?xLk-gOcUyo=}t;?vvxr`o2Xar+k&jbv;B`*YraMYAI$Y| zwPz(_V2HAt13Oh42TG9)#;3>%x94Z?f{%{UFb@2@Za#+XQncNUOHX{l8Mo11SoCXz z>~}lcJ?j=XttA0dodZ0}ahxEEM^*HHJm5=gyV1e|s|UmE!H?hs0FsbXdlMunbGNtRJGldrONw+d~)-i)0VMZT+1e5byV)Pxhw3$%pEw1g?Oe@di_3FJ< zDHCkKom3V50bZOJ|E1(bcexT~<4N#hYNk*30kNnK$zNo3{DGwoc9$*qY2VO2=-wTGd^urp z!}S;VKJujI6luaB1oCU+MIB-tP}H}=Ki($D>MF(%}xT#9a|^y zfBlfSQ=x8uN8E+|k~TsE*q}gP-B#w|!!|{Rg-{0&OR_&RW@Yp-kiOzn8_6w}3p1VU zPX@nx3#*a5iUrVj@!KuMn1SA2Zj4eA?)dW*$bC5%k)@tcTz*(0&(b-|>wU}9&nuS0 z1^=K%7G+)o?!n<_<2*$0 zcdzk{WL*MfIMtd#H9>rqYG|1RBi-D267cSVbx-`Y-(D3&z_4HJcrugO!o|Uvs$Kqh z%|Ts$G3Ji;nxie8A$?`&aGArq{PDCIXZLU>`=s2%Q@_gCf( z{vZWp3|vnIj3?9Rnng8XC4nDc=~OC7r}thic-+3f`d99iz=aGWR-AkbaofTsQi~)V zv0U4ypVVbF5PDkAA5S0f!y=paQ=G%*vgY5)@@3B6UpP$0q#BJG9G5rUFOXySMYfN_ z{Tl;pFqilvRiCt%UdL~n`|>zqV{rls!%wASkvafjp4fAf@bl!v6TYImq=V--e8UMS zYYLWX_wR&}1W#+UF}qXubLESx9a%Lbsa?to<_m327x8>`4gZFl%YY^CdI7b-l~!eY>H0 z1H29-zlzTM78qoQ<{rkRP|Pd{3K%%$5MFN0e!dhyxDZjFZmx-R9Dy+-R~q@Cmx`VZ z^q{>JlV{h8Yji9-sU_hkB0&~nk|{%iC|%bGkKmEIdsN%_dtP`Yxw5jQWYgk$ot(ee zyNplG*I~X@Gbhu4>AdjCc^MwYGK9lAvgl;kPOc>h9~Nl(W(CcwRq41B<>K-7hc%Chk!3lMl;(ZxV8TMMOCrKUXlTY}9h<%vKv z+1wIUOZm**y{F-Nl+r%CQ@H!jVQl-)0g<8w)MC61DPhW1M;oN%R6l*nmv7Eu4k!meOZaZ6I!YmD)4N7iAxoC&0G z=Z>M2Lbqsbx_N`__@s4)iOb$51Ov+^6UZZQ7C7#?QFz;6`6^;I`9edvB`D$M{&Qov zFN8RtEuw_fcREe1wZMmJ%P1(Ozxnd*(HCcK*;O08VF8D3 zeWKI~1Wr>pyP-kdaZ0hAi*gM*adcS++o}$_f=W_fGw%G#3+^KVt^_*?$`yWwxd$nJ zCvlt}aXBrDY-Xd3It*ane%y6N%jua)tXe>#AanENSxZ7W9_fjQWox3=4s?rt554(? zGM9x!g$OG=sCeouU(^NIzXdo^`#g|Q%WMgfW*n&McW(vU<@PoV;{T-q%z)~x(Sm&{ zt@U>2Wp$5jc2nQCGJamj$71PfDh56hlHR+aiHb{%QB-zc>LM@(1&OHB;QWB|_}z!D z=iB`9uF1oux1F_2v-!w9#objvR}^LFTOWZcval-&oS(0%prB3ecQiUEpywXoplv_B zg$^awQIE@d(sPJhBHvi>Xe)aldBE|1{Ct(|f7SJSfWB|SG$zGDyD?<0p(AO{yxO&+HiM)e9Rj|A>)~Ro*Cz7;>}f%&aV<7E z6460p>+0Bq(!9XCAhE;O!$sj#xbPs=PuBU)Z-O3X-S|5nGq-O^hq|%3E=_wTW$G0r zc@rtn<3z+Gmbsl2K8FetrdtmM*84-MK^4)JaVRTEw}8XdVqC#N6Be@dwle@+<$=gz zu`e0?gH|`c$VWMOqagUljBD-LjD;F5{l6niGj0hb%-g^V z=paAUme;dSwVtz@>8ca$bgVf>=O96rmkZhql{9Wg2)wzgr8tS3(Hu#V4NIHX1iW~L zTG-fntemh+QL`k%_LiENL`wyzR3@Ew*Ci1Jeoe*2HU>dYGfTE?l>0j1*^!A5{aNXH zGJy8f8}v0!daG_x_n6Y)X?p{C!5_ipSy%u3|9b(Dp7u53YDZ0UOPb2ML#nDl`<+oB z#T(CS(c2bnxYSk_pL!`2_7mEzRjwLmtt4dA!}p?WluYuS#0YH6r(26k=5I5<8a5#s zAD}dc9hUr6L&flB2X*%7Q;b#!Lyf6tS>La11XGg)@6obputY}VpVt>TwOKQ67NcrejS%s z$;R4{)Y{dIlU604AF8)=%W}9CG{>k%%CMRksHOS~yCCM4rmMz>!$0t#)WJvcnWn$U zsn8k%H}yMZZ9jw0$+)+UOn(1%*oDHw^f^X2Vt@ELsvCWera-ASt8_JDvtM=#6)LYD zMECwj?iYr2{(00#Z?^#-BNpu=>q9D@WP-O1oTh8i{sJawXDLN<8~3T=%zVj+;>Hd} zj`q^04>j{??L)$}YF4wO2EPnCDrlS)e*Vz9K;7*3ml zD&lQFmGdcxE+|&53@fgCD%nY(BYQv7$%5Zpp6ZOoOW#~xG?2!kfbEM*M!`bD=r8K| zB(B;Hc_CE zZueF=j$j;CUps-?jEHjodV{aEo@gt0ykv2nTP47H7H;OiKJy!%aq))HIv_hjV}R2- zU#|XJtbN^D7MIz&C5_Hf_C3Xcv#g$wl*|~J*#b=>;sy|Ctgz0RN` zD$&1moXPqQT$J9lYVxVTA_UIPZak+mCo|JJhec{{#UnDJ%`YPE>jhT>81Ed{br>TO}4 zR4??sdEIQp+%IMbf230|+H)baMx5&y$+I2#CHM9~?pQV`cf*GOkjZ!{>6dw5X?d3Y zX#3>J%8XvExV)lrRF^QhGk6VE!$#V)pY^#hL|TON6mJRtwe#F1Lg5_;`Y#2?t;#Zx z845#%znR8=H;^EtOM^53N9(Z9DKb*6U&WshM-G-|pW8`BT(|snh7A3awLuTq=)5k< ziuj{T@t{UZXld~N_QS(k7`@W@C2B1>suGD|i%W^PI3`x2)LozXe+8?`~R=U%4Y^91pVSyA>dZIxL~x;KTgYkfrWwzq0Z{rEro{-A4zC;vi2Sq(J#}G){&uT*ip4Bh2cbY# z%_QpAs)zv!4Nm4y;^(snZekG2dPTbmYez}KbM%Z!TMn`OnCKEZsqb_eR0xp=zv6Hj zvn3-ccn3Hu?!J9&wE^h{jx)*VQjo-(`~+j?QW`nO=PeYRJ9cnl7*567;a@PW3s@LscXebyy3nlSWd^z?rw(N@zmqI%?J zexr}WfC(n>eP3p$mg_Gy(DOG^!WDz;%dBA1Ef&BGTa*1fy-f?7Iegucqo6)E>q-fC$_olF{+u zu)pouq;8&(?*2?^wyK}zHIzyULtjhR!Fj*Fo0^!QH5Kp~2ViUTee{6e$ksl?mHb8* zR;6A7Ay^paxb_HKms?voy@0#^5#dGK6qa&Nb0Rf@ zFsMnnk$5&UBpi43Zn3X{Q4@x|wT~Lf=QSmmJntYwf5A4`8{&FZiKdHBhF01#866@Q z@r`z5WP3)=Pby~K7UkfMxY~6vsT8cXEj21taUsHROkS4{Igu+HKNQVKlS&TBK+M}I zK1qw!H@42%&9v$({40zLEx*T~YV76Vag8|^PPzx1TiKf0o0{96;o=bfoJ5nQMonxv z#@6_cSRY;(4?Kkh1Aw=O;D0p@xZ=!LRQJHgByhf5+H&~4G-~6grJ`WzEb%C8Htidp zdi#pmv}xtBI`e1&B5I_~Xk~uR4f@Q!JMxSj07LnBIqO3%+%wH-9lx{!!bXV(Clbdu zza37@pAA{UX+_@U3YIfMu*R%~Mnd}}^_Z9V&q7GAe%8;a-V@|wZPjyX5rX^0*Q9C* zn01YwnLI6?!U5eymeY)*oOg~MC+4+g0qV&~w%3A?CfS8tbwVwv6lvx18t29DRio~; zUn0D1Xf?eeiR}M!xi5S~@tTWW&Br>g!S1n@`&9owTZ!Q}N-1!?3Uo^j$!P;73mJi; z(k~kdeq|mWDJGYMKq}t+baSajf?1QveG2;G1|m>)YojK&a@XlyBj+7YwPsNavGXgk zw712cw>P9~UNyuQbFDj(lYHnvx?hx-fK3rVMS64mOChXx>CBr^Xh^BdJ~OpdX76SU z8K;N`gT{I0Li@vVQx|a6h<=-5<>$w3)_Os(`?8JGIjA30M2Q`CSp$V zE%!?64SY ztFe&W)Q%;(vpkU~CnMB3cXWvP<1kGvh?`fXmm`}5Dhj?o12k8*v}O=gs&-jSS8uiF z+y+z@+p-mzUsOtPGPz_|?%t5DcdF1L|$(E8KH;fF3@v3(I zkl$WD8UonPkn?ac&qA!b<(-90^zi|tjQ9@3--w8T-Oe}TZRp*KBai!Tq$C03Wx?LA zJQvD7BG#wC^&N&?U$FtU1r*Z!sx=R9H_IAOB$* zh=0g1jlXg8@gtmU>0{U}vd&6pw=D|$%@rqVF8f7HhatAB5Z!*vQo!d#HMU|lj+8?? zE#fhVfQL&wkN#X47{hz-fg|QU<3#|E+1 zL*2?L!zjJtoZOamgTDq7ggXDHw{JhOHhJI&FT3~rsC3INI(zWGK!Jk0+^a*Q!Qw3& zc4h6*;^4I`XU*dCt)Nss1zFV`p9@G({I5Huf|wgulYs4y>D~&IR%mq@J}^a0bQar` zy3A+eZfaig=@MIW4DLZ|aA5h7+_52smHnI6<=j#EUwBsrc6b8k1IJ}j^@%1fmn#1-$Y@?SVt{P1;5n6rfMx_ zg9JSj!DOk3b>$yqImr3AJnbb zA5_r)wS0c*brKo(G$k;%|`5r?nxT}6=Ps}z2lg}XKwT0xR69~fbj}{cfy=Ef2 zEv8l~N+R#tYNN`>bejRG9=tNBR{gt|oQS42VEuISKYp}AUv5B0lyXvh^YmZ7qEe)% zeX5E;iw7E?+?4;lEOFj|sVQfF=*ycZJ`sBTlA5pkdt4+Jc;> zE5Q~K(r+PF#%mi_@0hbb=SeYz~+jWv_v&PE{ujUf>=Uic!GMZ^`;(G%lD%)3P1V>NO05w3eAd;~+ z7_f~AM8UVPMk1aJA~K@fhV(}MW7f^b>4GXDcknyMOaNBnU!$k66G1g=`t|?>pXcAc zHdI~L>DZoW=;*yi)|Rh9hTEoY(L*@`;Mu|T^hJsHh+OK{R(5Z-$rYQE(}O`dEXW0cED!JVQS!O?_`iY#`wWCi{cLUfpR~ z8KbRB>^ir<9^Ga{g@Or!?-P11*|rTZ+6%EPhl=iFG78<0qX(jv@5Zz$LEo{gBI~5B zo*40)qE|ho4)l1!*sq_4$A38P^L9S+BTbePIVE=aV&Z%_uh)iVP#Vy>p-G786c1F( z)45_@u*^F%RquB$z-xkVpKd+Eqm)(B<2aONik3u27qAyw+4IjZJgONt_5@5l=9A8p z4UzCSQ z++Q?xtf(xzWGBgT+l2+Sg+SRoaM-lfmk~dNYUX{ShHTUgk+_8W2 znXOWM@; zyX~jO0!Wx4$ETVuv#hICA;Yaw-u;oB&o6#QzQr`q(XLBq^~D?RUFnzQe_RP$p%8ly z-!-ZHtR#e0TAPN%c}qB`nGXMhTyUJ9A3DazW1j>r_;(FFHVH^MGU^N>9Yqx(@>25* zGA#xl6Sh?xF`=USO*!qYO8dP+<{gp>I;Y@SY!?V#{y-7XJtaUi;3 zlNGFN^`s?(yyb)PF}s6}ldq`&vcU_w(CVFFQ)<%3@sbkQ-3xT;AxKlW-Gj#cNV>5= zZN-W?-;Pj18qo2H{r5xM;l2Lc9GxXWiq}GWY@&u~D~3&Dhrvni+;K=E_w}JBEQSje zCIWXbT&Cl?c|GSj&VhCnyt+qAu|%CN2Zd@32Wks=Sq3u}3fOGL{oxBlB(m&Xhp`#? zfY^*|3$Vn73WIC#ngkNwf##Fr1A|I##10hKb6Hl8+zI?yh&xfCTFu4xwxrNHtQ$g_ zM!2a@V1SrL35)7m9Zwo-qW2xOkD*DyTIdeExC(z9Md0=B}Y02 zKlGovBAP+YY6MB#bxG6*#0x4Hed~O0>l3>fsc0iD`Y17Se_Cf0v&6~4PB=C5>$jc< zCYNVz)1cPjixF~XM)$+19LXrk_;H$%P~0|j#NRZWrl^jExDQrw)JVscErIx$V79uv z&~_D5(c5X4EB$(O+X&u6-?FJK^rqrzLyCnvJv_IL0c=>&USy%U51F;q=!Tb7M=CgO z{ulfg^)#(T*7LumbDxDmo?Nk(MZvppC#$5Z>gCt_?r;z6Vd0|gnNpg^^jz)}_>3Ds z5wa1{$*C32<9uad`>{e!Y?SRmS?n3sIKsl=p1QoTZYf!7dFefyTdJ;ztop6P9k?d( zn9p-v2nf15Hg@t)Ukum~n_Fj^v2t%^%!%&Ey%XdPv9!#2zX6zA4KIH#wXFUfAnCHw zufM{cxu5b`D4<4KBdxWZ^*zm)$(4*k#_ZT7Dd`uokR~vt9`dyA&SBsyndULSR9bgs z*rv75XM}4omMD8kkN9>i-}E4r&n<7I7wBvVyv#V=AwSDMJ?vpo+UO_U8M(z=qOgRS3xrq1BQdJyxq3i;9}7E71lXj zU<=MJ#qf8*rbqQ5U9cL{MjJYmy86H|gJ@5)4Sl>?1|v}T>!K+(NitneQ_K}gJ1BVF z6{*HbW|$-1XgaJKkBM=!53hxxl=%Y|QIoI~**MvrQYi;3eS{G)F08DS@C6YrqoH1{7+uC-cKG389^rx+Q2u9g7^*PrJf^7}V zhE8+EGoT*_WH4}$s1^dd1@SA;7U-y{tS~!R=Bv?J2{!KyjoSTh?B4)>cSNslKH5M< z0~aqL42R)$t2o|HOKBe#8!Qde_=X~B0_c`3rte&+3Y*5c(grs`(u_%GO5Q8fFgZKi z@S$p22fy|^igbivkb793tWZJxnP~OSZd02D_T$sXQ-cZR&)nL(FfMlXqwDvit12Ac zrX!en_u_R+EKAS$^b`Na!2fL{xE*i%VPW-nPT8<;xIvhxq0GF|c0?|10u9c3^(%$d z#mSt~S<7|@mKP5LmG1R$p&nE-7~5ptAS%$A^l=!qQV$M7(E6?36Z{>kV*aC3hi{lO z(Q_1Fdw@^=Y{a>4J7DsC7Z48uXdT5WeAH!57&nvN(D-Z*~Nmdi+*~Wkq7>#Jk`ZrKbRcpwqzIs(*}qG@LfD3A=P;g zM$we;;XWHwC>|>PP+uwr!yg4o_5z>qv*-60`4oDf0>N3cuBu)NQZH&3#dbUO1NgW| zp$NT|4n#8&CTn+vKxez}(rxT7Y?a2C6TZ5OZQ&=strP@0)27p z_k2#YG<(QbOExt)8+*F;w!jt%tTt`z4@jirUkZg2Uw~*5)>>xgigv-O{3laIt~?D| zS}BU(GiTh8MQv@yhSM{=-QyNj6|{DQ8dMKlpeYk|t==DC7O#UTg8M&w>$-8u;sZ~U zm!SgLjnhtLdJurI#(>dihWUw?LcT8}t88PBNO@hn_;bdnD+TR;f8_%YoFAy$u+fZ) zcNy#zrY$Rc2=+%rT+c1$N0|&>8*H+5?G=Rab$6)~YoCFCC#05ITzYld|F+oSutk3I zT@DrY-ewjXbWkuOEqBeE6{#$7Aw*jFCHHrd)>GUM_2#8$LIeerNrjg)(2X#TY4|+^ zua#DSiXdX?R@{(!h*v3a1qIW&zSrBcL-SXpMnUyM8uSDc!s;*A6!pwZ#%}CvKXCZtRzsgC}Avewb)rJ*f<6El>dH?kt=Aa?uGJ#aQSY_)XY*Z|jlYAQO zFeaV8k~Rl*PL)@)7lT~P^3Zz_$Clen6I}94FQEfW>9N#X6n#ADYfrsbeJ8GK?1PpD zJNPmST2Ej0(Hg7J1-k+&Sh2Y$8Nt-=HMMu+Cl9A2lihxz$p#ZNuUE8xRrwq`FFN$9 zH1WQ(>6YBy>nc5>U4#otxNlSNPqZ8*mtDW%iueb&-OhAn8Vk=#N(zOM_1>|D5y|Jq z!Nx#i=lYh+rw4TR_r(amre$&985QGn>%jtFNNyOiSBf#bXK}*miZNQ|xtb$`O#KgC zHAnNgpA4@54kH=ZXTyf=HkoCv%h8+9uDJG3THZKyK3Y6;!u5#%5B-j-KgDWB#x;MM z5U_j5k~2+NSORb<5^egV(Eg=FDmtr4&g6S&9b&z~V!dH@^4@CHiq?FgX?-olvMpFF zjgT66IyrNl2iniag+bzmFKrvxvec*Wq6Mh3%=^gsn^6{heIki8jbgF~4af_3H3NVk zUeUoFI0aVcpI`X~f-XilKAY&N$33oZp}SWl&U6g*4Z~zahls&Ijrna~q*e|lsHPE- zDqd0mf|oK``K88#Eg!zzuS4c>UE4 zQH0kUT&~@4<*B+JV+1)MK2-p8g*)2iq;A`m?knOAi8nwf{0!~FjYs(l1- zhB1O19M{nsC=5QJA3Pnlaf(MoNBKVt|Jv{jzC`sxDfoiO@cJFOf8x*_wDw1BeZZ5aH->o`$m zFi{vWTmW$ohVOizNMiGBt)AEx)*XSO{!zeE`kC4;cLR7o|;fyo$FQvu}aa8<1 zMQwjxR!2P#!?V#d)i_=3eTYX{(mn(-hdvQe@nGwE4QtO`-kj5 zSk1GmlIc2%3(E?B+|U~uScSW7VVwO6bl(3VdC5lh)bE_k?)lG|>NkoYhJCiW`FG8c z1XHagDb*zs|ig8<7=5jV|1PVAAQDW)7(i++;X zzkpNXN7w^ND*O9SkAdJTPltUb#J6se)YIn9y3=7xhG#uf8un|iVW$2CHDSP)s|{b- zTo4)uaP=fh#7cL|?)uoVKOSvg$J4T-)V&-#uyK4=K^5S+F<2l($#M{$kr94hPkSG< z0%xMHm5{pEJv30;`GKx9<OvmN`?U~xGg+#NPOOh%yY=S+=u^%ECu z8W}H%cOIC6ub9Abl##nlzHJfY)?8{u0QNpzwwcW$$}L^ED@P-20RCuz-Noiv1i< zgFA>k!|vQeU$MlId3MEX&07uSaj^#qF=_b|4TfmYh5Ny8AhplK; zbZ}%L91wk_3=uAsWtsC+m^c}@oEAY+$2zF2j_bAp?L_R-$A|7Aa$cbBh*Ok9X9f{J zfWK#Y>*TKJU-+?JC2Pg&#U5PK!%0^lMZo^X+ePu){>E3NPmNj27inzaZ{Ur7-JAi}2p!lMZx%M6C&9fKfMD%;I+!AGZzOcVCrtC(4z#4QV zd5v(mu15@W$XW>X2CnCB<%gLzLTXDF)~Cj;KaMeTi>+HxE%I=(e^Y)D8gWlGZ;*_X z*<6_^&hQo3NMHmS$iZ8{@AEN7`s>W$sMNE4!qKZggE=Jp%xQ#IOf$@p1f8O=PEM!H z8HNGGoZ;%vGQsx6_~>*W;@Aw zm_}SJa#^Eo-5nbfoLCBGsDKF_u$Q|d%+gAxfK?EnZDO9m2&5%Ab`3h)@n-wbLwV9H zA2xolV)OyJ6JmElSRHx-Dr{J#a@$Sen=9rl-6hlXXXbXZRGBbZ4Vr(N z*0RYpL@s}yzY!sAf>@09GzXJ#)5A`(^y;;zQ3SO$)!{hjbFs*E|` zZmNVwF?9~DAB~aqDmjZMXQ?{RbQu5wSj5|%&Gpb7*e;7AYg#aG-rYA33f{_rDASy6 zpQZCNa4#$fBsWzVUU9cx{_WpG$Gvk;#QBo;N#9R+1K}{G$CS0`7?~$a$RUwKF!>$Dmh4mKkz*I$U+0e0XOx#Z!I^i$3x|KoV6B@vJ#Whww-T-BN3bgt<+18RZ zq~|Y1=Z?AxB#&`AAI1Ly%BYdvTS1ibd)SZi=`T$!-~HDFqv#tu?d(L{x?i0knZlb^ zddzph*0fOeFu*70{)I!I9~waFsiK|ppS#vNa4-2({~X+gdBTxEVoyCdMBLj8dt3SH z0I?M{(sP3Wk;KE3J|9yfz8z9x7VUT2-9*NJ{4@}%f|8a#(oHmV>l{2`7CL09Yl>;) zHmc2Z3Tr%w**?LH8HPl&TRxAPj?P0X$5`Rth)WV3RqX=PL=44p zBX;V{PWg#a(ysIOdWjgpcQ|rksubsS&M)4mzwqq+16fwLkthezezP9#|0*093Q5wG z$Z6zgCqPdqmM~l)jkTa*?iYLva|8^2_bRG6D1hw!I3dreP|88tkcB^#C#@m`pO**Yl+~d?~q}cvFpB& zF3bdKb7cqthU)0{XZ+Y-L~tb4b_E3Q(|;qGEX3gyj}&eNin* z5^kZnaD}Z=T$9bpVJaO^;LqpWuaz`Jvu@8dvfym#oV2ji&)b6YzOxUO9prw~eE*#A zVUAOQVxRQq6tAppR+UUYs>O-C0&&$Fmq-a8ZP?;sJYC*h3V8B+^E)80pb}|KMB1V3 zr0n2J)3{o@T@!0*<{1k4^|LUuS-zyp8 zG)x&eMXa-_O7)I+%f|kRH*xm(k4Zh8+I@n0>lyRc>~I+L;BRAEhYN_MT$ic0eT<~E zuUG!4;rdLo_C@!)Xn$RAcRXQ^Q15;pE8nY}-qKd+wbBtJlJdlPpbM;NVDe0yA4F@M z&2!+4{73)!>dEAJjy29w^&kQ5f}6X~LFd2^-Xv+iQ8Y_ATx50uf}#}NQ)e%M5E0po z%i2g8U}4_&6l&V1u@u~I_x-Zkg6wSHxeMa}T`Kvok4y7oWZ_+$20$G$61q1b=j*IW zo&e;2=S#~pnScWF!Ho}_985-L_HYw6*TtMH>6;}~tL{$!SBlBFU%0L8k+Y1*vI6R4q4 zV0oACz}2uLnHJ)DCy6Kar#~s-+J$p6T(Yk@A5-L*J+RH|#)u-=o2LJ*Fp~0v;XIq7 zsWPLeLiI6fi6`mPA%1qo8`geq?~_tDxwETs{!JnAC;eY@s*|%ik1C&u4E$)MkpT9( zujZj_!cOHwTvX`WT9@yxJQ1a&CmV7eUwEXmV^oOEyE=e1lNn!MPSxuyIf?HE=z^5Q z@Vp&XA^`f(Sg&noZ(%<%4UU17wR)7_mhAvZGNu&7 z5)e_cG}*pL8=4M~ldd_k8xi6+Xz|*Oady1c4JJoqtrFidf~^Q5M({1XwuQnau>F_s zLALx6gCetxsOcz2W%d69(LgT0bN$c#a{14xgQP=|jX+M0gQ<&0ikXxK6G z{N`Ku=Juyx$S`}n3dY2-Vx28M5AJxQgwBsE+~IRPhJE+)-qciHZurvhYTj|h>6uJ6 z-)QliBZS4tnRq1E7#)LAHY#UKFKS+#0yA6fBK>Ww$J*ea8{YRkzk;RSU9P;X%YU=OatEI_q$A>U+?Q}%fuj=92p1h{GOF}=Dz zU$V#SqXLLw)(m5xTY@1iqz1g)uq-Zt1Uv?S=(Q|>SYYZ+1Kt!quQl$YLt=Gg&OgPz z+j^a8g&gx*O)lB6t;2IHRr2XE$13g|`)$t*bM7?yLVfZ2t2*T9WoNlWhB5Zxb03e$ zPgfR9i+;*G4iT?6b{zH2)baLvW1>@dt|b6>4un7dzkh;X|LQ+Lx%)*ZlOZV*Hd<%c zE|}g{jo+X{8`6GGl|5F*eLD<+6j1=Y56i=`LWor8=&=gnh{qaHA8tRv=XejS1Hxw~ zK)f=~gl)6j&P6Wr=Ezbz^bo^8&w$%eV;N5V)94;g(ulU18pq%L-QQUhc7Cel^0d?N z@z-6hx6fU)CmC=pamPf;DtS^?{}0_N%6TLHLi|yhnO3%yX5RHIxJ1=iMw|&_bgj!d zY@uGjSEU!*V3;FbMX)Y*)Ge;S2*L_oT-D|tn;4>AqCKk(%IGwH9+Pzbom)L;Ox|`t zeTW>n&bJz#e)~KC*I$MYzs8GE?2<+hJF(^&ou7 zJ?8-KEv`_ZIT_$KsPWCO{15oq?hE)?{clkF=cpqj(3RKgI5%inxaH3`HHI!={UUF+ z>2N|=ue0X!?tQO)B>T&xU7J10vkgD;Uec9PfmE?zF^X4<5+3zq^z>R0A@H^EZ1 zY`0qYT)9K%0Pi+I-0nYly`}`8t&pxT-2R`dEiny_pVg7BMVA$G5aq}3 z%hO`-Lw%)HBs9dW%Ed%U7&c%i(yo+UM=;5JSM@NZ3?5LRfrJ{fz!-p#`#S{2 zRuRZL#Tw>)_5ZW?HZhWAS9;j@ej+lfy2+6x3nC!P&|v79(F|$9fFV;d%o#EVoy|rP zT-aO*AV?T80RsZO_RP_vLQ8)Lu`W;{O-3}`_K(f~tt zS7k=Li08$*-#zEtci&$`WL9QYoJMskuXfojt(_>KzKPdq zV3(dCNFD;gS}2VwLfiZV*ORK7U#wmRzPFiFQTs7UTKG!~bj&X>byxD8;;SDJs=v8TH)4hFTETm18OMVfH)SH|J2K-&|dXoW#U|MkYl=-(-=K zU2=xpdAlsI|Es12zjwiV;f`YAH<;gV8{ldpM1f`VE2i9>4KegAvqlPd2A-v0$d=rM z(CmHL<_2|03n~p0Q<{I;pSs>c89=!FCj|+)7Q1Bm%`u!VSI_YY-oX~K$^(s4W#p^) zJhiXv|NZvd*g45b9-^fBIX9|P9#oD?-H;Y=?~;GIZHpRbSfiR?M@^YKha?BK$)ta~ z{oUR|k+%)JE!f^*5i7N84mKiNOS?N=4wdzd1bCkrXJQ>4ikqNsRqrwpz&|w-QK??D zS=$ty@x0Z}?>vK@ClU8VJW{o76@Q~e!vDA*S1qCa2*6~sa~U&PIYVZCEz3&ATT^7U zh}$BBsBa<5D6~?{q$qyYP&7*Dg5;V8Hjjq33gqRPN7DD&0`W9GjC~ zN6iWky45_=zW@wZ&^V7~0R%Q&UmfmQVTYS=-DSv`PS<2?QN)m5RtO&gyQ#;JiiOKg zo#XnTm+Af0GrY!AY*6C~UQZ5}etC6ql>Cy1E-d_2V~Y(6Y(gILP=Tr25&~;VUv<(U z8Hd|mrsRjE)t4pLwmGPWY;LUutbhj?fEY`RS(zt&9CmKczT%SJsc0RFdJI`@I?Y52 zsb`%_p6Fe2QckazwqE`Y7c)s2P|tSTkaN5GxO}@SfV;*L4HjT@(KhNr&u;ioZ|z+z z&epgPxSO!lBLLJ`&TN8E-HYTZ~rvLYooaFI{WwtE{=U-*Y)vZSRaY)}y z$)O$E--fH(@b$D%+Fb}!0coSMMo|mkHJ(NXq-CX97pMr!E#^}c#d-S*Pa?S1<#kJ_ zO{|N1zDX4X2+Cy`0#8t3>J?_d)qkx$`c zoZ+T7Jl1V;s*ch>dS-I8lNYpwa=r&KK{=~Gn%FfK#nkJX_5Y2}{n{7Mtba3Vby;13^)!?-UqpxKF1GIsH({h` zJGCqh%yGjypP=^!XL0=91h!^}A~G}T_+?>6F@R_cX&O%ht};OftzYY$ZRw^XZ9~B| zwt-Fot~x>IMQe_w`R5t%bhPdFUZnC+4WN_UFWEQeyG!4s`gLbMYq}!q|L}b*u)`9Y zSYY)G*Fg(x@Gd?co!eM!ZD>ADm-$NNP33K;%r;O2eWx{vM2c8z0`MT%E~iCe%ci*5 z+C(;uhPro)GH$n(&vkVj)ooogkatKcaL&)Mxi~UQ0q9)p&*8_I%>h>;P|vrE4hjvb zxAm#I;Jbj5{c|nwHp%&c|cGn^ox7Sl|_&qQL^!I19yyE3Cs`T?;^| zPn~;wg0S}7Y3}KSo$ted_p#r~6j>=?yE$dG)3f-{p`60Ce3Y7+9GFz1vbM1rj8w2= z1N8mXv-qOa69)9Yj5XI~K9Ciqy_j8Wx z&U)$l6w9!(iD00N3}h1u)Kz(>3^`R1KDA(moj{bUtyaF92)-Y|S%fZuG_K1%P5uuU@X6 z$D%rPq;TS^^|N}YK7F1-b6s>*HB4gTw8NytKV|E&d$Zs zTG^`mT1$fWoM*&UlmVCDsh8WJHo$uH(^wQ_5FXq+_ zo>HaJ?lWhSOL??xi2KB5^WHO<4eS1~z znrFL>+bx?n%v$Fs(KuU{vx>%~jj7TZ#j?n}ehaRlQG;m_WqeviV5P0$#G@o~ z#Dj0na%8ia_vqWBQ6B!?P&O!i?n7+CzRbf(PVx|BNU!Dqmeo9b!_uWo`=l=d&ZczT z)zV)UXp2*^z%TGA0M=?AVzzyqiv|lQ1C4kd%P^-Q(<*X3hM9AoZxTJHde!PV?_l(x zuj_2~D8tv5Dq!^+x2KV8X~dXyadMj$Lbh9^zZqKI!sdwc9GVboS#YVGu3_j*Xrenv zo%a&Cv5UdyH;`h|Opl#n+YQ@|wxFmu$@{9%dzL#zX>h&Pb^X7ca`ZC7L&j=96K;Q< zCaDM0zJ@eSgbxu$ybfWL%P=_S09`8Fhn5R{+Xcer0_Z8nQTl$j+ou5CDd$OrYHxuC z>o7?$>+3$sShzYTNdj43uI);)XN3S6^v6INcxhf-JO9}PU4NTiH3??=oT4dP=FII;k|2bSEaA{U`cx@m}g z8iA!or!U7TZBA1i6zmf8vyD>iUZz*k!P^jQ4*0ObjbSR%=fZYtrFmiI*$x^#Ou1km zb>EflxleMEw@dm>{`4)eZ%%_6i%^SaY&N0I^QKn_0c4$M>R1A8tAj0((8p|xuCYK$ z6LtEWeAI2^baN4QHY3^=v9vkfTJEkiZLnN&O3B&w!~NCk+G;KNLeKm)oty1^?q?0n z1!oJiwo4gXq>*iH=oy8zdR+GkEXY=%4UvV~Teh&Yq%bvcCS{0wpG>jAZDbe0KONM* zD!ne%Hs;_3bZ#5o=kYs!J2~H04qf|uOj!+?m)6AA&)&CRpqsNp59L|N|Etj895<75 zb{>;_u=;Q?M;W+Xrgq8;ejkPT%#!Q!4oYnC1lQ4VbDNbVZ$mCtFYpQ84HZV0;a%Cd zeBG%j7|hkR)t7H@h5~KOxs`YBI!+3?x(XbZm#gQv#(8K>jT@Xt@U6_KhTN)`oD;hO zHDwHMC%>pqpLKoie*Yr*uAeRR?Vh^}4*Oe{N}lo8Z8p?7t)XE7Vrg`&_`J2|DW59= zt_F|`u=UF^`eHi@CYSN~65v{=4ngK0{rUfeU;UMTgu3{gGeB&PA=4c+FWi>xv4L_v zAJ6vo8fS3~G0&W(mTcR#ZPIh>w=~-=Z9}?<4);w(*zf{$W?A-08Sx@+Z##FGf^h#n z`0=p+J7MLa=54nKD*yl>07*naRNkHB{>b4u-+BA7h;N1L(~YUp3f)qpVIAGSPw*-P z-fr+|{QO=li%NNa^$ZN(wqd<27;MAGtq!*D_BuGt(>f`3H3cL+DEsJ)&XhB1MgmI; zL8^XZJL}k9bpqsbhE;Rgxn7xvK?}{Tg zWz(&e*C#1h=O&KTr+5`tI6A~m0S0DuNf05c72CarqyB@k;HCa4{(UwVJ>#z9`j^jZILITjp9xpRL+e*b+u z!hJy8LoPLD)Bv!oZVAm+78bb;PeKjZB5W(evngYL+3>ZSumqPDE%VHWHNa?s{KjYh z2RUE;M`)YB2lC#MOTCTzO1lIIx8eVCPrA;kEFDyJo~6zf(pC$bHTMv%oobZIRd!}C z@;{OZSiv&&3?(FE(tTEX@5(@=uIFKPgU@$-%;evnDeuHdPI4b)-x)xGKoeHf9` z#NwiNEest8bh$2|h|3|SI#cte3CtOprpz{Fh}qsH`iKrm*~f!k9u(5iK>Z#J@i+Z#%YfXLS)+;Tbe7n~rA4&5^CC|CHe|RoOu;#>!(P)POr);Di&z}-6`rEN0!?5t zn=p};0agLl!6rf=F4EN|s>}}u>Z$lMY8(9I;XUuEUQ9i~)2=&pKQBJ?&bQQpzqtUH zK#^;fZn5n2fb!0k3)Vnv7DChS*3Vx6&F7*SpiT_|v@I&YHFV? z+F5Qr$28L^q?kzl=sbx)(Axi;je@7FGg<_o`Up`nmcy+JO5OzF`2t+ z-}aN7>R{!YyF-AP+rd-tJknhy9M4hR*1)o6rDDB>CV4>jJO5U>D;VN*U_bGG87S?TjtfGLMXy<8>(F(hmf=M)$BLmvx{<#gw zHh)ZR+v5h_z{H&ILjgE29fa>A_9dyHzOugk`sB94qz^skzQ?~QFYQB>Za%Z9Gls(! zXoLA%<4da_N7(Su)qA7owiD{Ua!9z_8P>7lITb4bRTUgk%##(M%gI3tvT(_eR59A6 z{WR2kUU9;gSHFYH)$<7Sb|^!Y?JD|H0c#>u&@3bSf1R*yLxJ}ha5+!7XH#sBnf>*! zHqOze{cYF2BUh`8tp~V;`AdM?fXk;;23D&X<*(yI(ip}~M@|ZG^*DRKmaq6z~#Y@i-5jJhR;ex#s)4j%v z0uJGc4^|)IukcGT4Y13A`$B7WMz!;)eNMK&{O7~%vxgdT4$LUHb_@Ux+%5>WLU1uh z_5r!~nL)k_FYRLz8&=J{mJJpt(8e4pfQG$+d0Dw>7 z7kk~)hgToqV)epI$5N467)n{cR96Aebt0eO8h~H_c!?@1+O4t023zbUHf2ez`OyWq z6%hYgQSMr%TxC3psuO>2s4FWgGybyEOJg%el2t zKked`H5zQl!IOJ;PN4iGk5N<)bz`FRO|Z;v5%gGzb*O0qAf#|rsP|m?#ya6Sx6(H7 z#l}<@UgNw2UM$nCAXOcfHeZ^RI%K;C+H(99X4@BbwENlqW$KOUHQVm8b8PAi@ZbAD zoM*iAz*~RoK5r{|M{JG}?_R^7*E$^Z?yUy4_ieY@UT%$E&IR53S}e@}O!6Dn9{(Y2xc?90`2G|C;X@Z60h+z6w|6E=O|yUo?{cLd^4;%w^lCz_mbPN zDE3h69Xet;i-@B6*$hL*ASH6K=LOVga# zjE0Hxx$2tSvgA<{oEgh7S&S`jH|BXw%?T?-+-HX^%F%wgZLt%{w6^3YdcViCd*bxg zw|9g?ETvF$H2t(e-=aY7HFcm zsx``Y(O}7qD*yrD%Gn#E2ju;yuAn*I#*l8`!zs&6`0R_~l+a4?)?vqYkl>yXCyd0A zcIwi53^>=)c&#ye>CPx)59Z{U;Ci)cA9NVtN#49njj-I8h~aVaUg#>z+-kK9<4z<3 zrbdAVH#kQV{@bC*+DTT_;m@VJO5=1-*VCrEFCRi~-%~CFmKH?wjJ4gC*3a%P12z|I z@67&)duzOt-H;Mm1&v zYR!wsr6pRk4z|3UEZAiWgm5xp*tVM0@`)gsM!g=VswvGuE|T-C9l+J%DJc)x-7eeK zVaX%<5$)1evTil^79S*wN)?by*AlzX--o>u4HnTrmtGZvd`{SUDt_AKwp}c6wwST* z{g1A`5~3rDn48L{FXN%Vopcg>4a4agIisr2&>8}uL$dF2-SbR6%lJL*16!sXLx+X2P@ zf6{rDI`_40DXXn8izEkAbW)e7)zV`*+jUf!-#XlC1z9>>q# zp6>_V{~veNcjhI(?d@^i9>jbfD-V2%c*UuThyzly-}v$t!E>VlwwtiW0?lNA zd$D>ES>%h=i&;Pg=nu2D-#1}_04eezcWA+KT9AWz8J0!1;nTJ%HD!%YyGqsyT9*+R zZ%l>5B7CNCDBxB@lKhKq15^vg=vc${CafoEK?h$pF@V)Pk?zh0E6OupW8pmYu4w2M6>HglD&-v|BCB5JL zIjny@_p9}^tJ~{X0M{1mBcp6<29(k8W%zU(D|_=h+i9Hxw%ycgzi9qnoL5`?wc_t$ zi5rs+p$xr^m{DU<*T!w(qbjJEsdsi!{}hoi_nZx*K-w5pQil>YO!26(9d!U-uAbuz zH?B}(g$6e`3vHsCLYZ$hN%amq;IQn?n}1hMa+2eVjP%sj$ccwNWq8N7@hlScLK{HD zrk~MH;`^9uizOetr9kkU7Bej}`*~2~H6e`s(q*ZsBl7p`=a5_#^zLzeGn^+(rpOT3 z@3Qd61KxdY;hC(vw|`H5Q*2^e(}m>z7=JAfUF}~RYF-7$w@^P!K$7`*$c~#*Oj_q= z8*QO%Hy!4-%6@ky?zh$2c^H}+>2>>+5B7d;@(1lkEaFs$^*4X1qoiqBb!@e|Ve|zXnHN1k6@;IpMkLu6j3^&*={~TEV9V`M%z`W}m(`@TaFaqf{&ZEwk1qRUzcA0Ap zXo^Q2-)9D$GAC~{+2LhVJ(>W(HRGF(FDAaU&|q5Y2(YG|j)ytG`vlZaavx<1xR(6@ zrEF9idgx3N9Bxr!6BD%bce2tJoTSCnR5P;;_BVjD zN_y^ey8_u96Rzh;xAz0z6!hBO9iGE-fH`$IblZ`Wao|05toXL1XHT!!C6Vko@_@WM zFL&Fi&Rc6oTWV3m&9~9fJtSkm`~B53{2ZSSb&vAJ*1UzQ?~1+ubX?rlyz$V1H*mz9 z@3}1ayqBSWi5zPfc(bt#0Bi?aFoWTIb;zT$m8xwB_a^d!bp-62aEt}UyrNX3R3J^( zSY8xmfm#%FmPcoQ6(tUvBe4%Q^7u>oBV?4v2~b1FZ&`U);qFT>pmH`hX(&1IO;fF?vI`F_hw z%InxX#D{OxoaAB4aUv>*NE~(GD@fG%5W*UH*Q;Owm661-Ik0_pQfeEiOR{U}SRiae z$eU=Rr9fNn(OMi9&~jf}`v`77pgUuA0aIG&t=o_3uQ?#x$AqTs(S1|koo|2N_0sF) zf#6&)?vM4?&h3=~?G()0Ijwt_()YFbT}ROttW3mZT@P8?`*QU>M$zh-OEbgT;%Z&@ zyuT}Se)G=3f@W?d<^rjz*t#quF1-EYdr((+pph6(K2MHLXBMrnbN6bRU*fO6+0gPc>KX`6B{G4DewnCf-xglF%c z;pWQNtE&SbTi?bbfpOE7eMyjT7V~$MApXigeWZPF$q^H;J+dgzmzI{`q>!vKsFZ`Y-t;VFgkIalkm~T@T3jukbj4v;yEcZ4< zNftoDek%x9i@?80x#!fq+oEUt+b8#`+WDB@UA>jwoK!PSYfp>pV5^%G_^fe;1=iT1 zh=xpBgo_53)~#ik9Rg5gcybxSS6@N%Z~q@uRf*z1{`-^K2&ki=3jNRzcKvtG0{mVk z{dS1tmJIaZA4q3WX-jFo-);!`sp9!b?ozsBM&5>03q$QPc{5TQLjTI#E^9F~k&tKu zpw4iFlO_>(nUd?xRgSoN%{Ed&vb?1o>3Jtk z`t170$Vo)*75G+Bh@C1kewN2AtDLrOP^ec%m5q3E)>xnligOo^?W@phK{QM6HzDwq zLESlEZNsbCA}hHt>DC;>Htax;R_ZlGCvPYRa&2J*S#!6H>@opv4j2=-wxNFjA6873 znBFnlF7~=r3^3nPg-d6MK0VJKcYUaS`_Qs+W0SD9K|RKDPHk(~!$%iSY3>);!W#fX z!lD&b7(WFN{fmo`H#@fo+E^j853fGJ#p=jaTj@zaJ+^NESFIF$2YfD*nS!0w-oDg=i zO=>oFK``~X0^KI+t@>~M7x>eE@%#AP*-x?l)aNI+H3hq6)QQs0bOj96f4;pm)DK;Q zHMeA-cUIW8wCIkHG57XKPV)F91?c`a0oa^D6r77SCM>r)+H&bDTKhWm6;r62)Qx5E-`{m9xwC@;@O6Qb)0dT&}zAbakH%D^h&a~qYj+=g+xz{Mr zq6yUo`27%hZ}kyA#yhbtP;35K##_gzjfqQZ6-bMQS`YNQ|EJ1haqhlR@SPicIrG47 z%XvBx21OBh$T9#Tt%klc#*eb8JM7Q}(oHD2Pk$1Ff(cgSDuiHOEQ@R=i*ZG088O7(-a;9&?OqJocZ#p#Yv26Fpof!v&(PPgO6rkKAE}~l zMI2VmAnQLxTKLNB+?Lxfcl4V97~{Y>1>XK`w)+f^rPR>M6{HMHoMDnb?;lxHH9&rw@>%C@$GZ>@%xV*mv8?e*Bow7_gqtSZ69egEPkv` zZPN{w2c3Tw{OR8yGk3UWx3-AVR34GsG!3i=4|Z?oJe%qfOD=**>7G<{Wdid0&1%_F+FT z=2i6N(rZ|-Fhz87>N}?E;nlXZ(FJmdq!U*6_o4AbuwM<{wX%uqUxhWfu^^vzs7>Fq z4O>)LpouLQ%iqb#6o72K@4$HI>1V$Cb$okfnD`Xu0nghf>Bt9UF_$Kzs`Bh!`ulN| z^)Tz*56V(7=3Q(#t)b`Zo=atTe5&(|ePA6#Ey&||4}T7f`_Bq+S$u8ZiJ#T>mBr29 zC)<^GW>~}5>Pmw5!$E2Ox%Z!UYnCdSBLv)IA%dx)&3B{A91V~AW4;?FImvyO7V3ob zjz?=<>1S#XE?`S-DzMvf*bEOJ)-@zG(9u$qepZ{U)0H5mvcz&;ZNo5&Jf;tZ+Lu3L z-+88;zwfMf0lfPpoilIe8XD1?yEbAAGN(b-P%wcvm(5cbySX|i~(yH z`Clvp+<$Kh*6lBLC~plY>}PVx&MLoUbCcU_8$92oe&Zc->U3xFvU7LS_Z$0WYwnX% zUdsI0V{+%)CViE2YV@6t<7g;seN2sWEab1jzeCeW_c?D+;~dwMSTevH?B6NAItXeN z@bf(>@H#AEHzZTQ0ENLyW8t-9?4B*_kpj^Q+k=_)xiSpAbNlOYR#%AF>CErL?Y??^ zcTCIn{z;BgWsZl{v0q}$dBJ-|NOM^vpPLNGFMA9V#(`Q>wcsEXf`y_9Jk-?mJ~ZnQ|SKX`uT}h@XoO zYgwO-3jnMwWyupwWU8rkQGpS8R1kTSIS)Mb1z$APgo=yZ6b{hyn>3iG7Iz|Tz}xwd!NV{L7}QW@gu?6#rN zrT5m)UiJfwe1GaRZWVNw4c=F2_ko2Wuw$>)1ckoOvRzgh)Tq(Kb?ApjrM7Xbt+y{~ znjPm{mOV!N?m@K*-*l!Nc*lqzZ>i2vqfG9hyO0bz`zTOv<2lOcS+^5riCh#=w;lc4 zto-nM-yd`cN%in$@9&4mnEw6r|N2kyAO7?Y@Spzgzdjg_-p4fe?{AMoFqA6X;4DPA z>@QnqbXf+%>e(VZ-!|l{`rqt*_20qCP&&!OlAIlx1K{Z~2)`?ER2Z&ju%KJ^-^L>e z%I){Q>u?X%4e35(?6;S$MVgoVxrdMGv!{mkKU8n@kzm8}rX7lNf%uq)%|GWNL{+iI zl|D@BUFO5l6wK?EyTS_JL^}l_;xbOJA_RC`mIS1|m z_})h>0H@E9Fx@|BtzO9xBA#Izs`&KXama;Z4BMGejZR!P`k8gY*w zdH?_*07*naRQr_YgnOreiBcIa<$m7f{TQ;boNrq^j@Q_to~5u;vH3y3y!@jn`ROUJ zNZ%=mX1RMw{ku8fZGSI2<4l;8ZcvvWlUDruF|1#_^QVnx*7w62fXbp;N!jI`jE(QH zbO;Y>H)h3#>C%LpaS`vz7<-TY#;^W^LExQBfzaPlmz>ox_B~U;d}zc*jV-S6B))U$ zGBD}=dxo#ekmcnt1Lv_BNGEx7a-8%e*-k)c04S zXGy-djh|JOD%-8Yt3O!A8&E^Waks7h4pJ7lA22JU)taqc7TG!ma&54EWR37~$?e7S z`K8Z1DDF-e-Tmh0VdfaOeo$b62cIsz*9wyCYK0#3OqDtS^}Y)2efe3G1~rygN2NuE zj72VvEekZb!5OrOhFt9$=eStCm|bC=`9hMCQHL=)o_{pPc7J&F0e*Y+d)cSbHCFU{ z8B$4d`yC?bdp>T4v~HZGZ)>VQY$g@ZhAQ~>cQ0&BS_sh!S#5PTS@=)Q!a`=_<9=U& zJMIkf=hOCYO&yEwr0!iCx_uKOF_^D*=zGLI%{ zEU=!v_V~r>1+H<9HI``NY86_Qmd~Q^U7;wzILS#Km!x*2Z0pzA{7v77GQJ-cYA6WT zbRBEo=n>OWK5}+jsspD1Z6wD`13yFBewuEW2K@JxDOT9S(_so=Q=7RD`*2LilEFnt zm8}6ZSYwGL)+hpFT?Ct}#Z=N&HGkB-lZ5)nQBGP zd4`YCse5mj@BTsPL0lg&xBJt$qzR+|jJZ7GRk9qVoF^9sWR0pkFt(Di$o==5-_~MU zE@uBZ3Z#=jYOdNg>#O8*D9hLLAZWh4&sa(GS-s?n zC+TRiyqNZv_Y?wEZ@6iWA=@v1XG~bppI6yn8Q!`1ef<9F8D8UQSmk*MX2%_?{hTNy zR%PJ~6VLD=Z1YUH8c_3$gn7VZ43u|Gp%j+cVvp(!(&;X}0}HHpYVcQ@G@+))D?CAg-K@xt`mcV9 zzx>M^eEOIFO8~$o8Yk98qJ@)e8)W&wHjaPZ1?yulyswG9JzXwVFVSET+EW^XsoO4H z=F*O~l(A45a@?NeByU>gvfsl1T(x9tKBu2(P3ny9DIP{V4qJFbZS=OLo;z((D#PG< ztTkybPH+7@J9bW=%%@`RHwep(zv-f6gOZJ^%hlm6j`v-#PHptoD?CMs9lp5wNnFlW zNEe+O$aDiR&Sg4^?ROhhrT3RwKHk#l-cxS-eSeO3A-4*?j~h0m13Tq}_;_{T`*j=3 z_^W_&4OP#xxLr1yXO-<-pzIK_hQ0;(yuRLLxBv9GZn&u5&oaThgBJD<$+YzWWjird z?i-ox6ujv@Umt>xQR?l)x;^^UCWc&C%c2I%X8eyj}d z!MKesDdQAt+o!8A@Vb4@AGx-iR|~ZW$mI$Ltc}qPGq?IkT#hNgeFvZHmAW8~n}sX( zVu51H5&?(|07LO?Ax%U*PY?etF!t@FaSZ^?FMS@HfBOem{^Fk^ZtqY`Ygo5zY7K1yBwI2KCiqw`&+cZ2k^~3u)Kzkn0nFq8F*>A2K1F%^J z^_bYCPljw)YnS`cND@vHM%8*}5omFQTRWh^0#$I+Zo`UC>I7zVRD}&{ti#;4!P4Y< z*O3B9ows(Z=H_Pau=n#x-a&JUz`8fgcTQBXd5@)M$gN7WS>MVFwZT(lhmo?ELtY!L zD(C53yfx}V1iyipPG{&LfTfBA~e zehMOZRz0p?LHT`C7TG?R9PqHyERA(8iKUCkc^2H?dF!szqKL+_1yX67hn^dtVe6D# zV8yNhJi!jl4A4NCQ(c-K&MJh>HfXRz5kbKM8+Ts>18b8X)S$*1XV_pF)az3B z3Yh1FZAY~orIO1n<5@xL&h)X(HRC(OzV8FLbHo;V*%@G)=2-7sk7@7nt&>8Uwv7zK zmdK8q5We2bsBQ2!e)S*V%V8|O#yM`VL=)KkZcbdzI4NSkk#&$Zi6PXW!3H}lu||ak zTeNYx%Jez!P~sZr!N@8@`1&HW!$%EhYE%nb04irZ0rTFMsrx?0(7=;C9vK7Ry4{N< zcL%CYD4R6pG{5a*c7IfqiQwydUL$qd{=+_^HZ z$axyn!Gf&Am0Fa69O3ymZ*Gkh%(+C}|LV;36lEGOntxBGJ7}gq+s8Vu+$-=sWl(ZI z`}n-4MRT~d#y9_8#A^^p*#PqXYw642&C|jSM_YNgFPvA~tbF_~aPe%78lbsa#_2r| zUBR1&X*>H^HV@rBeD7N?-0sVYjNX*aIZXPWb!EW5-kCo~pZAPan}GsNWc;+ccL8N0 z>%e&D)_YF@vcHBhiarls?|O#{^^A3pTNDXH_Ot_rKfL;&_xQ0KTLoD9^Z{8)Pp)4^ zP(bj&J{Ayx2)xy6T7`3v;j2&uP&UVTu)$(5wANR7R$$3~6B+i%-iCNy!;XV=yZ$ck zm}cK|D&%Loz(>x(B@Q4)0(4_6tn)|qAw#@_sC-{Ek~)way>%HB(6KWFaDQv{6FkAI z$;Dm>idz(JO!2wr-5B;BRhvnj0of)kD}ysgr?(OdT&!M1rrEwnQ*z?uujIr@tU%@Z ziH4Al#0qq5&;VLv8CF$oP=tG?DYVXn?`t?dSqU8_-LOD)xTukoAC0#qt5y4G4W*O3 zSvdy#E!+D6IPI^l&h?AYdb?3&Xr@W$D8H?5-@bG8%d|G6%wu|tcP-o{2)`{S`j}oy ze?J6_PXpH)Sz+04J0f9zA?gr&YYXOj^LnzTk*t!`1p6Xqceh}~8^g?XF4;Q!sxoIt z&qPV*=&4Sq6YvJ^8TcNTytmR1V%=hyb8i;wzEd8p9dwr47-p37hB$y|Ao7ehWN-%! zn74o~^)w9)VEd}1Ae&cF6VBgDdc19?a%FNZWq_?B*Q3*ZNWn6hx-l72W+^}xhOTmV zD;~oNI;jZH%zIu2#*ul^De0F4r6@u|HFGl9SwjIRt>~Z+S_rF&^KyNB8&sZT_tJ z{in`oUFUE*Q{>vv?V+JI9V)l2gZ2S%JmwgTc)vrZ?R*x|Ib7*Pb=?#1i0+qJfoYfA z*J2UdjyBA1n&VxYxz9(TdD@_GZ9{VQJ|}N?&NcU=G!!$RDt;uSg1ZgE@{w9_H7&6qGv*6zX)S$G$_zU7JO)8 z6Oc?M&<5~WCQ(_doSY3VaFo0M@kP+as)%m`Sh~hJ$Z9XJMujcTaE%%bDr~X9CUTIL zQ6(5r#m<5q!r-xzdToHj1~p1-(Lk2KNEuqPkI%0zak+YK)) zn>JEl7v6?#cJRbx0eq#a`(8T8BFn5U=_Cez`1;bz8k# z(+k*x*7Zeamn_#wPIB9_ z4*>Ujb#2S;JTZUH7zQrgeeAXOziRimoc(Kwt@MbgZ1{ZuS;t^aZ!ZU~AjsnG;jAiDpM--TOTIt!Hhype|QxtWfZ~1Qt)%hA6 zfbKH1ig`BOpAfzkpdvojSvxYWU56LmS|wSBr`zh70o5!N;rDyN)BGsQ{->R4$k!m+ ztcd6Ar0UaqitrTwDua zuk9L22+kZMMl<}wTbMm?-TgCg7|$=CBc~CYF}fVdYwo=1Bki8j5`~qJJ&Tw)Y82he zZB^>x&?AZ1(bq%lvrsB?CeS`ukV}eF3E!KX@eyu2IN=&D6>ayRc0R`u?=g1LfQ_gIdM7ot~vND5)M3OHRd{nhe$$DW!&kb@BtcfEZMV5?CQ2Otm zBfIPrYaV_5Z77gwlY>F znbYq1zfeY3-m&AHaf-l?2e()RT;7cKz^FwPz4RJo?NLRHVF2KtjfwF*$8wa55wQUdT7TC3z2Jd-%DI@Ezw&%dj#iuq` zNc2ZQ)2}_X<7)Hy1SYg=EAd0Uj+!p`4F?d)T@Ox48|)~zsnpiiz@z@^+6{K~0n z`zEERkbNzLjxcJd?GqW&Wf()u{r$S!ghGh) z0JWPvC=`JJh|q-{)PDC{sANo`*G?JL2nK5Hvt=#k53~^|y}&8VHf2o_<*v)-2$w;F zJt1=^KQH&ycC4pQmGU8Le+4)}Mult!67vq~E&JshSL-~qQ-ab1@%K5~)9FDq?y)cMaBbB227-|_{ovg4)+NsZALp2R((GYZi(T9k^{ykE)#r3Niz~ zK!{Cx&~g(FBi9;!;ItAvdRrmy>wKTUChdljyh5^&k`6Q&2LFz-dsebR`I$mb3hq9( zRzTo;3An$^TZG#4N;5T#2==a&{1Pc^FHM4{_6#nl00R(IN_H#JObuOwI!pR>8>YV^ zpDWaHBuA(RGS(wcOaE&{4}R#%A4YDyA2e8?teNn@zX>?kwFt5$Bsk}966D+3ud)7?h)Xvm=yVSR*L-B= zXC`J1PK)!ox(FT_T?Ue$^q-I~B}FtlNQw-r@Ca9247#wg@R_|wevMZz^~ z5tRlZT8X%68&^%De#Lt8M!M~~1%-t+h{vx?MA5( zf$W6dU>CfoE9lb|TB5U=aAK2FrxjkIXOXf0w6NDRUD2brE-qDcu2ufzdAUIg%nnIeq9W=0;))6bS_~}t$Q(>mwfD^i} zP+LoFiUdGyuLK$@5vP2GNj)^!u6%#NOoYiS@vJ%dW8^>@{J><=n*+<)!pSp@kbhD~^^0xW< zvQx)7N;rUyBSLH=%(-t?fZ18dW1118H=CnfwJUv zTxo})oMdYLuJ<^dJ>GD+2w{6%5!x3C$hwp0vE8vZ4UTUB(brAz^?7zJus@V@J=6+d zSYu>3x?derHg$<@IJn&X6y1mM#JTReByw?h^D5#Y+E;>A)$|tTOF*Bj)sLZg{BaVnrUnVJpA5 zo~X1jKwiEll#J=#4RLxoyQH)ta=E!1MDnEZ!g~R+r0KN_yC#djiY&1NkO-!D4OhQA zfOx_d&NioID?2d{e8>PIgKDer{pb99T4aBw?2l*Ubj&{d@N~>3$v5Gyx{hl{kh+Bv z^k9=)`*C^sA~O+FV0W@~0hg016^Xb0Ox%y7?s8~!!0epu`_g|O5VOo>O}25!pw-B! zAL7=*+scephPsN;g3QUaGtT1I=4>8&12=w zAb~FboJ{uZ`Jx70-Hp7kO1G+Lh~W(HT~y;g{t^O*TdC&v6NL73_i;}tz64fpst3x~ zP6UVa@7cWl&NE>h+jJLi_J_M;*1$NM#9j<1B%rc1<`ZCS01d+FNV>yoih=Frxl26Y zTnWq>?{8vjbw8wqOpPz(TrYX}Lli-Ee&^hLY3^a`Cls}A#Juo9#D_O z-01=>$ zBt8wJoE6f`NY0l}EufdLhVh#k0vBxUoWr?KFpxyUoPA1BuK67#*y$$8Eq-3In>!3% z=doS?XNb^=vl$pa)H`k7L*Z@h(|IhGstGq^`bs*&c#iugYrTbQK5kvOVY$mhK-Pt! zp{UD2ckT`bL?cTuQZ>_^ShMR_w&a3p9+6f_Y_jx%%S;LqBlpUE& ztk%#G!=(P$gx1huiBm>+I&Z!*6Bwe)5W@tj4cSQwA7IGp|9WVEU!x~agwa*gc7nvh zp)7o^j4{@C3KJY^nX*ms$6deK_JHlbgbpP0*rz$Yl1XWv_t$D^7FLS2Q>79MtCX9p8@+HkD~{sqSCU!pE_ZF za;@A@ZqFW8A0q#p-N}4dd@gFBx|Tukt{{$}hc|+ZyJvhyAA@ulTP79L5T1e~HG+0{ z=E=iVnWri)Q~!wOZ($_!1tL<}ZNgwiM zWycIoAX=oO;@`O-`G-js=yiR*2JS0B&23j-d5nr%ayb#*umI?qRf#01cI@nhS{v|* zg@m0!HqAZ$_8ACwH*Sb~6l(p=d@kOur-{x)T*y!+8WTP+R-#rX@QjiMwN^w1tf(bv zFQ?ki8$aayCt)IG7w3+I*76}9yI30zDfV#FDB_JE5%8q;@C*&~8T`xbHhkHrflq=VIgAw^tih^=ItC5EpIE zq2w<;zT{5TE5D!hnLA|@Q1j~HQ3nn(=oKdq4I@C8p8>A-NpWOdVoF4nw^8RQzh*RDtmNA;LELQ_(MCkh*&lYpaa&&zf%^wF2;uBFSHL=Ha z1e9DsRa|nujC_FReZ=H7sY%NID-t|2ul;f*i>g>inO|Y7xp|@RrZW`KUU&Qp?9TVS zYTL}uXUVltK22@V$Oab@Y=WRF4;%j1e*K>D{=;PDMn7t)ozh{qrxs=#z=Sn8SI>x- zb8WHpK!Ht4sq#^lw4N9%P?sM&3f$#Ke|6EGbwAlO-s_(A>+PIL;%gGDrt2B`(T^WV zja<~;zlKXDDstXB6Bd4NUDnlY598bN1G3)_f;!x?N~SU{+HQAtsm~rRcmk@)w=cjs zTbKXc|4Pt1>Zsq*Rds$-j@pp6j#;<~X+MQ%Px~k2CY^!F2(`IS3$+Uiwrd`iV(p(< zD%2cJ`S$cjr@QY%&^Xt@!Y!9G&Omb}nTl9@QfO{R4iw+BH8TA!c+CP@6$j{%4XUuo zgAtncoUv`8^18myHCI&FouJE1kc#md-qx6p`FTcM`$XkBX-LbKR|dhGi23X6Q@x|Q z_?TaXqyDL;=k}yVtw-^8;X;qL2?Q0<-Z5i9uKs@(faX=7D63$2t!Q+v2e;Ba^0}ye zmaGRMj0(@n3AcJ$gXARl`%2O6$y!K6N|-t%Wx{Wt$8L=0R`cA4CKsIw z^i#?p$=f64h`7Tc^e9u{DC{n$c+L7XNrm zCkf+?QIpMOv;iTRpn>VQ;X9+ihp*$jW_{O&u*IPT3Nq-8=Y!vp6%2FfwF!@yp46KfQEzxX>i*L9QjStLqO0!HFj9X|$)rg0io~DG0YbBmlsHjO(%DaXU(1ad zck(h{ODaQI%Ou{b!#F96y3ACu)74nbC~=IC$?K#x_(#uEs+ubmf)v?XsIf9-QSLRx zjf?4j9c?ACe~OCh8E|i>SrrH&4In`izl11hadhz3SQVujLQVVz98XrgS=~NF-hn~3 znGxU{_b^NhZXSq7Ba-1Nq0W(22k%MaE*myqPjglPU2Rsy#n{;+e%72w`%84vIF!D* zUUeoXI>VV>#=_6VXSAj3qe(c#dk2$hu6#&wkCnYgs_H0DX|{zQdUMH-0Nk34oE_!& z9rP>1w>8n2DWxi+d};1ndDUmb{q?HVA=uFETzpkSk|nDaQ;?H(@8W@zQVN2l{GuxJyCK0<0u;Uh(X>V z4Ktfkop4Y;VSl&D7AW83skX54qxCv2Uyqnrw$Nwv4vcBj_5Q$8M6jH?FN6IB&4Snt zO6^eyWSnsXc~R&cL|Nt!NQ*fVke{J30Sawn8o2e66(z?Oxz*aIJ5pgyi9 zn5-jOxvj7VKGsRj#fz^-FhNKX1dgIH?NjYak(xc%er;QPsMG@Ur-ZWB)zC8zTnqO{USs) z*hM59`O(`ywUfKP7x5(ngRcWI?;i-z+caYsl)<*-4-vv32iYhJfu;U?t2vX3_rs01 zMycauszj@@w)wvs-IMc6Kmzr!I*=qo)Us(*6s7?T&X`Z*S@!mX~onE@KE~-9h-`Kk<8($xo@1nEhaA^qRc#% zA# z1uB3A)h|9cTZP-Swu$)Gb@@~7vl+~Ao~xaY+~%W5zZ?$lahP>K@CSc47c2BBQ0Emi1d)rKWwQHtt?Zqk`Bh(&)suZsF6jbo?!kERnn z`q*-`uEj`;7HE4HuYbVtJ2Fm9TgsEJHyNN;BnDHAsqQ?^!`1>@-peH~sBIKQzOi}t zo%7GEG%{k&FR{ba_<)EIs>a;53%D7~}7Z&TTVwDOq?Se_LlM8wx62|Ke@FMIo4 zC6e#sJ-tuQj;6mdN<&22y;)x-{$t+ljoKl3Kop%sXF(h>{HWWkid(WH{D;^vO4FWX zK104BhNbL1;}QMZ?E%N{pw;2eETnw8z0AX(Ieg$vP5}0lahC@AYW}}#DP*xI+)D?o z@V*PGU!Cz~<$OAJAA(8UoHOt9Qq~0RXkc3t>f0)MLkRV$Vh zX#$X6Ms6cIeY4xve@E9jG(S>o<3OM9{D#~aN!vO!ctUMppig}Nj4Pz(^5vO(YBIFq z_o}Apv=a=!Ac9um{#zZ^+~ER=Pt5F&p#M03v8WUH8BO{W*XHma(fK~F60 zllYywnZr*hq*o6=sfbj>%zS{52Umwil3a3jaBx?))gGS= zq81_a9gntAG-qf3yfzFN;t4Hk^bp%`3G-%bnbFgpL{ooP86YhRzMxRwhG0ZSzb5xo zmU#z1Pj^)V+6BU;x3+~sGhxnTEwZwA2`k+vEbUfx{JV$RI31fPN~hCkRP3R(3**Eu z1im71qTL#(R&0mrVAI656+E?9#lvz!1byd%P1qkQ!T zFg%ev-;Vf~3rMiwTO)pIC`k?KVJ9m8C~w`|eVVZ}Pzh5Sb;MGiAJn`-sK?`)hKXUz z)VH<^S*u*FJFokTI47mX4OV<+&;IIN(z3`<7mt%NVtse!Xr9x zaN{(kopQq3Jk8L)enm8xWO-fY9eNp}keuXyc=FHMg>x%)X8{g+H={MdqU~>Jhw@~F zC5D+F=?d`uz7jcVSonc=651HUCCcb-ULJqnOr$~U#pj~%MZ|n++a0;y9`<_7S^$;3 zi=GnufGI#Cs; zwNVqO?@x=4likA*Ftf8?t+EawDhFN;H}Rf*bF2m1nJAKSai(*4;fwEYEo~E++$?qM zQ5{OL&fzrUxn?B3%VE-K%R-~FC~(_ff$Y_#2MeMh?M?^}x3D4r9||iB*jc+9 zQ*oq;h7!AtXv>{%g4*&Wv$4B+(K5_*74b39v@jeF%T6Y@^S6fnWo!Azs*e}Bdo<#( zmzV7m#{uE@%^>*1YAGaKzj$em{0xM@DXro-*#YTT>u`YaYsp@lNO!NRDycS}KFkKR z^xrg@uz&5CqgiJ|+KE^C`FvaTmeQQ@g%Fi8*$+{NcW7cpZyy!z2~wC8iRa5zBq6tK0g%ogPXb|M?uWw;_Xv zUJ3I0wh-Y2FJ_=^9S;HJ58YlD8%=a5+AF_5Em|>9{kOm&*SQGyl3=HvA0f2xb{hzj zPt6eUni`@vl21lpnlF6V1qP9(r8F94CIHujy)b0#~tcw-H07#qU2_9QMq%>~TJ#Q->D z*TA?3zGM7h(-KWMM#>aLnO)ox#^hqPS@%PIY=&Kaln`CEur+b)Gl@2URns%-#E%Px|M z3v|c6IY=nK@K1p&)IKIg<0dflM+tv!a{TS)+y$o|e(c4P(`F~I+HDGh;eBWq$!f~F zx{J9nE*tjkRjHOqp;0MUjlfFt&R-37<3EJ}0-uG~&E)bZ2$4w3ub(Y;A8MsM&YcYZ z193NdB2BtA$>&bsaZ~wb^9EX_o<-db3D}35o%omigadF*R~)9r2dbDw}N7-8{#R< ze&i1;7|6(_){Y3YhI#@ULr%Nky&`94`hEX$H-+_MxbLBMtWG4-)nIpPV4|>-M+CyH z*I?iixA0|T<+NXwoFX-hhg*NmioUKNq)Ox9Ni6>Q{cAEEb_DaUSVAJ+lo@x>*NnJG zf^v&^f?xZRm=+ur(XUbZ`1U5;MYKPB1H8_YPTQ)nS4|H`*%|W41pL1XHU@}>zPWI8 zy{YMXL2nKx`Ji^A$9D%NC4%eY1gh>ULvNIjV;oHmna!j=RHFSBXN$ku5j7uYZ`#oPY6Fu+r=We zach}~kUv@9@6K(&LkR~h@Ee4LNj@$xX|v=`eG(h+hMKhZ3%0#QxlwQ(TL2PD9(CnG z{J198YGU{5;mN&DwYQJ{nKpEpA04z+Un9fyV*13}p)MXKn+z5G_&$nSSm*l2hVdb|- zQw1F+?^|j(TbM@PT6AgA-H%sn^+DdWa!wo9pONkQeQavRJ8}_0(Lxx!(Tn>6{%ANE z1IplEd|$?=v=#blVfSGF5~R!{ejEfmLm0}fPtxtGFN1=5&qKY4Uvu`TUPkL88{A0D zH@%Wi^v2Oo8Bl)!2bOHo)LITr?m3Fz*=+2H?1Zbu#F1TtXrwRea?PQniEx$Xp-+sy zjOK$D>eWQne;n(VSD*)$=ytrl^8J=nY7)PY=*bBLU+>QbU#eF+o4mOk1Hj>mL^`@R zUzx-f;5Z46OyeU*C{k8Tuz;~{Z8W$-^+}}!7GIlFwoQXjzdMaf$a%9??%9V_dQ73< zgaqKBE+OIIYQuXny{YEMO#IGNCa5FI44L}rDr~4kauP+CC%+}5-R5aT5Ld-t;5Rtn zV$|knO`5ya>IW+7XQ5(>>-(hLYmQlwf8nvIpIO~<(Z&BYdz)~QH0kjY&W`S7BP)5K za$A@DvZzyeudZd5V364*+08Y^>O@|&LVrlvo$OR$j)$FU3y#Mow^Ot6o-O8#;~)Rd z<`3lEID`nuvkuvp{LKB{0589=@(DgGY~u+-xkIshv}X6|dCzj|xo?{R8+-iuP#RB* z6>KjDTKOQR|6lE}=?V-wzkImx2+!C)%cPARq!S*My^tt|zI+F_6FH}C$w$`Od_sS+ z%HS%zZK;eDZ`pU_{Nn~;w?sFP=2+jm^-Iy+1w zM$Uc+%WC@3;1_k;8WRDfjCw9-x(`iem}7DeU-9N78Mr5!_pf z8`~G|1&vIEX)h+mAYZ*U1< zB>#!{R^9)hiVSdM$Pjy&18UsR3)wCKy2esDCGder7S&r@aJu&<^3u3340 zheCps-AaBBUXO?mDS(k~!6P*tWww)X{StNozYCckoc$?%&pCkn_AXEr!@AUM< z-F<$q)@-Ig1?hnUdjxMx`+`psAoepESIK!V%`!F0r2qc%=-&Fi%qEQ9IYe{tKAqs@ z=k*8jQNx$dLmO9I{_}0WrNUiP_cy(%shjun9?Gc|V;zD8=9!4BQiX(WlD&n%9vU<; zA%J@glJdr1`12bBmQqAhw%Y1le!;Ksw5tx|zF5rQsohviadvLvH~eM319SeM^|9 zOoA{bhu1Avvl3j*kvwIfZUjOjVt>KXt4$$CFER z(m#+{a)wN9@^nn3{@{Tf6~d^JQIeJq0Jc%ByQ!gqk(y>0-GKPUT}!`TFwx z(Qv0G;9ri}^z`BAwDt4g!gT46WZW+3xV_6%g9F2}WnTB?eXiOv}t9d;NbR zFqG9bp)x>*ix%qxkUO+AVax=#9xkj6BcuN`_l)#uy{ODb0=XfIvpm}7=9VR>El2s5 z$uoykFcG%L@lQvr-@)MU92vR>DeU7#itoyFsxe}LG=Amej8z9yoMzs-wDd^#QNJ8Q zh28QGO$_D6wtX2NR zeZ~Aar$QfS{e)Y{r6ZS<(1E zgU$OcrbAsx$L+94mk3+6`=vpA(|q2l6%=RK}e(Bax6LxP^t&;jFky;`|1 zKIs(1W0VO4NLSITf~7cOsmo~Eyn#?M?!lM1^%mSo52(riHph%+T2$$iueceA*z~%h zP!imz9#;Y#TDvzKi6S(JHc$!MYu>ynRc>FX=mARN-_X8*?HdkjZw4;?$P8Z&cy}zt z050uYaVwSjxWnV4*k6<_k(Y6DTsGP3+)(G@CFeucx|;_=0(z=Crm>GLd)(5MR~?mZ zHW1^+Cp4}V=PLR1Ii_#Ym~Xt*MRSz@w~3q@P?jxi zMFR3PX@w{X&ioE}P1U%&hJtEEFS1GLzrSuw)zM>R_q#AggyxY+#_0d8QQlk-&K3i^ zwzX`(IE|t^W#}d_@cTEzIki_RMN(96JyWS?5Rd63+jN`2eWqglvLBj`@yz@s+bedm z5L(+TYRgbKQrb9(2Vfbr@@byCxh^pc)omk;!WQ>8)LnN!Jv%ZYo#38}oBBvT5Sm{z zzW9X&Wxjb1zW*iEtMt__wn4$wJ4@v0>I4QdI1fR@kiUnkbH^qX{~8$j|MTdPKsMZ# zf;y1Fst#=t&^lF0^Yy1^ODyXM_qXrLPl>XO@V#&D!h+n$sA#xdw_3C{;sw%pjkfR- zRrb0OMmRZ+L?7;w$q~=hWZUioi(pI^-4VJ7Bt^ZG@N;uPW04AL%}{r_x-a8=muOrn zkc6;-_EuM>6BF;xNQROHoSh*dms$iMido5?rsvU0?%7@8j~CHUCYZ*kOW0L9x5CHO zal$%-=gjZI%l;v7r;wNpKB>dlZnJWAQ1Z&q;@5CZm)vu)Z*L1$e9%`63lGNLm|FYv zy^C&U(N5+qM4V(!tV0?MLQ7AQyYl=2r+@yqs$(&g0JkwZFEX;uXKx2)Vv|1Xr=9V> zyt3?n>O35!gxg}!7n$(Eu^uTppo^@C|5q(p$JUX&qdmnD^bP4x4W*1j0pg(Tgg&cQ zzkh{xrea9o_i%4Kp;Rfrp`NG0HV=&HXum3UX3<2;orV^Y8oOE~7d@9?rwkSw^Mt_g z*IOT?z)ry**Kd$>ijvkXyn*;NA$2S`*#fyt z%7!!-pP3=s$qb=l$b}fN6@pD+ng0R9gi)+e5!-dej<1$>4$-3yyi}NUD`j&nq;QDM zP`XVQ6w>ErQFYG<(NL_(Y)lDBjM5+?^FDu|ZLA<}ui~m+@HK9`oympQ+6t6?iq$+( z<{&d<cC zXtS44lLk6?9oO&)P*G56aHt_=Y)uqO67_UF`^RGkM_dtmsysN>7D2w}c{JoH#i9n5A3Al ztlACMK!JoRJhdvlcGVgrd~tR9_iyQu6V8%~a? zA}7I$@))nSUibTrpy=@Z&H*=EObydWm!3^%NG!V+@PjLD5b_Kib2M zt8E$t*@Z!F7Fsu%FDoHat(`yY$Gzo;?y}Zi+8N)N)UUhAUw*H%5F5syUD=$C1ehJu z;YryqvcKSM<)cUc%hQxxZ-acr8tkGhL$)t`18${T4KbW*u(p`Z1XZI1Bf2r|xm9<; z>m?7r-IN{)`T{N=Gz<>z$oE%_o=(a=uX^wET0RsoZ#<%J_3YIu{1FbIq$ zcNo-<3=~GjmBQNoF;j^qZ*~xVpY?4x-1RIx47dG%7QpLX@W0P|qcAyJi+iu{uwS&` zzNDyLH>K@X$|<0_c3kG23c~D0)#xW%j@8kQj-x?H{1~K~nOumXAmtd;qyAU50U@dd z+7lW*{5Ln0Ln4&bN-3uOH_Rn86*lEw%EPP-!6|1UwB8c$A!bgY{V{KMAClAal&!>l zmi6o#P^RqxwOe`NnTJ8)@W}AIok0c8#drjx>Yq--nSs>M(Cp2{S!nISWAX!Fe^m;ZK zS>Jv>EycbUx#=GpC$w@v7Gg&)k&Br030MaC(vbE03+ngsuF?<>o}gaN|&K`~p6#lN!{8ZDxV=22`t`Sf(8d z0B^t7xlk1?iG8YZGXGmk@yDJAOW9DIoAhp@b^)sVj*O~YP-R(2G3*tj6)It~>h2U7 z>IYn=AALAY0XH9cS^M>D@~$4_fRMQyKsI@T<;{5p{g z3_Y|9Yy-UFFHXON<{g2#son~=VrgUXeZix(h@0H1mF#CBHiu)7$1)gF-espSSX}~? zIbawkL|y9ZJ;%Z|y4~!5Ei~r8=V{nN(_s5)KVo})@t`f0uH-_D>8>-(5h))ZrW;{i z_&5RS_loB=y9tA(jY6Y`8DN$|ERp)<hlUGkm7d>I};76jC!mgK5325^-VTT-A#ypaHm( z)mllm0WU@uoGOCiLabKpPXAh)G~L+y-aN@r$~syZ58QI!OWzlz_Y=0GTjh~2&C{7q zMsXuCNeJ%Cxx_HrBpPFn|A}pfe+fAjLgjkxlKN$SO=OiE5EE+%b$EZM&{Kp7EwHIv z35E;^7F2H0MIhkI_ZMf`6(rDXekcC{NUj=g3i~?DpD`i1U_6c;HCzcMYkJT>5dvom zYvX4P`d)Dy`~+r^Mlmx6X#)>E+3Hh9^IE*+5U_+&jdGh9V^YyvX0-oe6S=f)bB{7ffbw;$leRlNjK{Tj3fnq z&uyogjlRJj=T3nygvuWQ51UoX^=AU;FH1jsE`cW!V~NBXFm-^js*z;MbOk$D44hf2 z$RisbrH-6Oxj0txo!4yqqt4pd8sGf3*-0DMrUe8hn7U|{Vl((4bL1=eme28+Iw`;h zgA}1CNbll-9#9`Fl2ZPoK-KTTz(@a}J(|D!Iyy2S#`E=&|M#jMp~H`a;MG8z!sC0C zRj=bO!?hT^S4qw{TV_56pfF$OOZe}aC zQUC*T52j9NCqsY(80_5sgZ$Hm7(#OrRBTR2hKVan{m3{CJ+9{anCQ7_Z`1yHv0A6R z_P*~3t|Cr02_+BqhWo9mE;;y1W|*4%$_y~NlS=PU2c%79qvH0L$D+#tw=)(h2WHB& zP2m9~=NnZ4w~Kt#E#&pD7n1YkGe#+FR(VG+SU$}yN9N8S112TJlEmibYP63knidDj zOAat`lfLMtU=46Yeh-w9NNkizh${VS^F8Ls?KkW&c5n#FWG+@vwh2Idic`{ob;69W zAxvm#O2bK{PwI2-bear-f#5&&^1_fV2Tm`1Q|wgh2H4Ly}wTz zdv8dw{$B!#$bJfXd(|D()kG@FKMrmRqbZ9@np#J@9J9U=!T{KF5OF#y&+lARCtFKg zG$_3{g$s#?ys&X3bQ&;A0RIJ6O}i|mxr863j+}ddjndg6y4Hm311r9 ziX5x8&Eln4zF|i_jK?+Md)N_t9uNMw%JN9q_|g8?{nq#`b_|o15L3hZk7aBU%qh2sW78_Syp5ultbXLHz9M!gJhOM3xwb$|U%La8y7EyQLc|`&qnlBjzmzeDy zogP5p#ltpmieDPx50M$)Fue=B(&0$RxunpLeuCg=dCOR+uDi60IdTJ&=Aj>}d$P8? zMkbqKvrGbE6)GC*+yX6qppXWO)90W9C;r@GCK6(2&vSkyRIa#tb01iS^&ZrQBAF3~ zOk2_F$0cnY)612Xp{tnhlZm}xo@_WYK=v)E?SR8?B>MGRvj(H(mFXC}IH#K-v$X?l z(@ROvaHro1tms9dz@fok--b7$bn^3pu+w7j8gDj6v5h?5Q_ld>iWuN79jy>{BMMi{M7EAiMSW1MLegPI+w<&3PS)! z;y^G2T5r~!I45r2cUY04zLXG-t*{jw4!JJFG*Xh{N!p7=yJ8ZdyqV04-<0d2@g+4H< zH4-(@9JEB1Uv1a$FM3tPqOS^OwSLDMz~Vv&+Uahj3y4Y>Bu1>WPGUd z#IwbbnKy|aB`|M^?7fIkejPFip~^^{$qaMYhY>?eSNux4z2&k@huUWX>*z0llI*ZY z-+nfgH~%0kOEY<_JfTvS=*dOhgMkSJ z!jMV^tSam^2J!95U@O>_6Nl_dy)4&pceS0DLB#iRGknhoQ&gBg=Z6^Dr`~Q?ekXi4 zN9`c+_cX@~%E7q`EEj}rxl~@C?i>0*pzJRq7XM^Zo|c;lm!Q;*XsGJqsn9xJq*fgc zrHOXok)ayBJkGA}>n4<-G6C5nRP-zup2Uu8%bEk4VRa~jdB%>UmutY)i!F>JfqqKb zh&l>kIYFS?1A3g}J8^8zl6Fn^iudRKk?_Z@xKJ{l)G~AK^TD`0Vz=67LIWgXZelKvD8u9E0eb%NPorzIDnPi=zqNh?iOI@m zO_gu{<~hc!MjCqhhju;auyqvLjJFnK1O7~x8X@mvwK7-$y=`o!xkT}FCG7)+m7Tbb z769L;C7s$BXtRu6q3LC75@z<=6wc{9{)>n9pU0Eu{Ht`WHcr2RTMJe;r|pTI_gRjy z1}P}KK7VWU*;Z05(@$k`4!D(^gG#c|$!;cNk)!1a2wn|xZ^);YndvvRlS^`%D&3;j zCOk4olo7XL9848*mfcHzu+9czL{Mglke$X6w(IqjvRvWlGHhS|f_zUQ&6~L?zne59 znlJZ05Tl-KYz8Y3&oqh?6K8-1v2Iokfd7EQB6^zb8!!!G@WqbMH~F(BQV_=NGtW&gax?j!zdo&2I?PPUAlK;FU*c@k-(e3U&IXsoVKWB$JowoHJ^5 zb2C3Gz28X5r1I<`^v?0cBs?R|I~%a}0FdY^pm*v%^(-L|NQ5_OwAkdvt1c2H@;*tL zk0BqY#xF?Kh%bUH#2pX@V-%g>FE822 zMi!x0!|mQ(n+JPPr~S<-j3PC|)7ARA;9u54Co17<$ku!PM>J5IiQe>fCD%7z3b!ub zQJYsRWtvA?<~v11MHZR-jsS;R;A269<0nj)5dQP!ud1?QcCh*nhQqJ zaas*;VB-FA9wegA>vv&j7H>L+jM6>8mdHXL0i#{ec-_O!mJ*H&nyIV>SJ|LJjS`nt z5q5$3;|L5u{@X~&Wjh###z7=XwY*))%%CbLg$W$9I8TfBqN4H4mdXZy$aomIiq) zf1Z(xDK6(mw^U&Px}|BLaT*e9T5zUc3VVe-_ntyeJ;;Xef?fk zPj!fIWaQ67$Bq9+WFoqEc_!jYl+$UeRrB6GmBf$)&tO3E2$FRsg>*NWEe35HzKP9K zmdd)O1GsO#td0~YHfst&HUj++i786iwy5XFpG%`r4Xc_ZN5+8 zdbg%-L<{fsd&z)y7DqKG3{P^&uwh`eO-M4DTdwDS01ZL%zFY$^tB&hM7l%d&tWf#B z-*infbF%VU*t(K|s`+=wvwvuwmT9#RrmVZjBG0p2c8jO@J!jn*yPTG%UCX*o`y8@l zy^rD82HJpo3L8$l__gf^K95~e{#M@J1+;^X*y9&q%u?n$Ixvl?&4SbMi-d0DwWd8_ z$r1(N3;Vsub;ykc-(wZv5V#&Ae93IFFd8+PF$cvYlu{9uFBk^YxP|-M4^cUA$rqOl zcNa*eXD{=nVc`o`SvE2byB5}nm4d@w%XyJZ$!XbdF=yN1=wlU5eBEQE2WLpD z@ysGkWZQHfsVc;!57nOUpNv8B^zF5U7RQ_Vu0^HVz^5`s`3Ww-{BTwRzsi2+@14DY z*R~(H`@pba1qgE`cR2daBaK{ri1c|$c6of*XT-40!KA@C-!)uMP|pmx_4)Ix=gt7BgT zZD=a@WVS-7q2`kX-aIzJtp&RP{P_YhTGji zyIBjJ?oq9Nu{aDDxw&#wioYX=2!`WzypP4^2R}HBWpuQ+GJE|FM0pPQ@h zb8eqe_@_jc&)=tgszT7#Cqo`|KE;ILfPjs-SNRyZ4Cb!uZE1&)#|&)~+ye{5ZO}6r z+`hN53Er91dXfwhLVazemHVesfh}6&vCnNCXqenjW3xIUq$AOIVGqPZhTkXD=NVl+v~Bu?`sKg{!ND*9s_i|1E$F|Ic6lYy4Ng_IrR| z@3Kt%MHX2EnD>TNSRqyMd}v=|a=xXl;~H}uZHI)SvnbmNYm`{ySyUu9H~Pv3kmo32 zS#WVeDp2Pf5ZimQuQ1B1ZM_}8_QfKL49N=#zE#GBo&zzcVhEpb341Vjg>aS%p+e&g zpbWVWtJeJxB-7B0L9+4{aJhLI8f+XRl4A#DgY9|gNXUX0ZXep;Re#sqN^9ENy$%8I zFnpQ{jydIF&1B0B+ls$5Sy>g^=3=S}>=t{iV(9|c@jCTLkliJzJWt)bUPUggkz<3M z|6SOw>fpRB0@tZkNiDFm;Hr;V9@GDGj&bqBcizQYm^OJIL*@YSHlv+hrwzQr^<$vT z?+OOPkZ9_fv@;RVFl++Ka2@MpV}Uap#?AMXVb|0Tu_Hj)`F0*Nk1fFR9F|>9U8T}H zCneUX0_$n;tVH+mT$uM)A!KM{uxqa$I|yhOfzst#mo2cXx>8u^5-Zp4ukjH{a@}(C zuGG-NbD>7Hx!t@jIT~MBk>T(wl-S_HgYuQBXiQun8ACjospCwGi}KBzAcg-sS6~B<$uC{v}7UGqt|ZL18C@` zu&$cn$Z+(qokM8qhtR97fVzN1TIk?V1y>s*P#7g1NtLFU-|R=Og_%TI7Qt2Q8j}^h z;v#c#le{q<3OqMkiianIWvHZQpJiO(4P?U?2osG2jn5^)NPp4lwe@+6qvi zZ3z4csAYVtUO|Al#@2&@ zu%?lGrnQx!K{#vn$)fKTxq5ja!1o-n;VEivsBx#NFZUcr4sF|2qw?X?n%&)oFfmBp zV-3x+WuT21P!*^~X#A?FYDL1V)zq$Bbx0d(ZvXOp5q*w<%~&S}jp6uua!*( zr&`}4eQ$WA+U(b^$8`$FW^*m=vr5-Rm_w)94}RRTA94{2B9+;#JP;R9x%20cqrnL- z{I#i(c_WKeZz&pLSz-_C01zO~1PMDf%YI8pB7uLHS1tYP_k%?R*UmX6qbU9LW{$Wx z(Q-Flpuq~ZntOQP6^zr(y2cJ0>~Ra{SYtOS-}1+2-*nZ3*T?`o#Vvo0>>F&~#;}e( z&qmhxTc7>!QEdLq=YcP>$RfvRHP+8&EA!fRz}pBOr7|k7vFX$tBYku02`+Gf69DYA zQ+m>4N~>FYtWUoCgUOD6Iu#4Ya2l-1_wlPtwnNYLbIjUWU@G1=a!V2#sY;OszqF#sz46RrXddz~NY-4& z+>IlLn0^J+kn3i&G$S(&z{3DiAO#iTrTV@5e)O^7ysE4M9Nq(ltn0{lAG(frC`djA zFe7k{??sr|&ZTMZwPiQ^s({atv6J2jE_|ehj&}aUVZnu!A<)`Y>6{{ExU{xG+kupp z%l2S*C1_ZN0*Lu$L}#I_Btfi(D=X-Z^@<*u*FxZPs(ltmm~NrfICG9BOXc((*Ru{W z3+8xKZBfU3~onb4AZ6dno9R!DJik)*i&KoKxV$xAhwi+oZwy z`u2UN-FdBYXBZOf=E%)8i9_t|J7J4wlAT|noK@)P;n@S+-+qX~6l%--+@aSZeiGEt z95#q7cfX4U8UEkD{@3{1zxI2R$Fs;HiyS6&9A?hh7pE?%rl+&9zc}ic7M|7#ukBu? zivpvNrh@Rfq3Cx1uW#SS-Z>ZPpd|~w0kFf`*j%yR~qFZ<3Jg=Js_#-OGjB#YU`uo{}j${okhNFkoA!(dAq z+G^J4!SQ2u66Sjs(Cz|I>1!K12smlPjJRd&EZ5(liNeLZ90OgFQnGemWA-zY7as3H zBNH-jaCdpHnF~ACdwpz)LxIQi5ii$^hs;WRZOt) z``P_2>2ncQ#Ae>Kvdgwem)-x$6fUDHhx^W3$IYBhAl%kwUbcl6_Y+s}jzb|i4htgJ z*kOgrGs|Q15*gZffBT_>#Va(B;*lCk-T3?6fPHS+fk4lfAXG!X;ombUkXB%YXR}!5 z$0&S0zE)hfEEd5p+eT`Jp>+z_RDuHKL4_8jE3Sh34fZ%k4jPU8aj8ST-Mj=xL;%u%C&><%j~D9qMS+m0xD3};AsBFU`(>nJDnL~x+V0U_wY0RE zxISt88LBZI_Qg$)!Jc_)EOUyd#nahw#D<-U_qsL{=p66$T$!4CHATkceFN~}$EixK zQ^bZ{+vkmd%E}xgXNcJUKl!L)B!@st3bQ*&<apjEru?6-2N+TMym`T(no z+r0{hyT``AZv^g=-Mm8Xk3?;#z?S1ET$+s*Ut|7vIje2WqqA?|{`L`AP$%~~LR@tO znhg|O*I1g%o(U;R#;p!ek$}{Rmfd=&Bhm6 zJjQ!by7oMb&a%Jl%)60d!Baw`^B2GPxA?5d17Bp3MGlwwK)mqjYhz@n$~geMv3(C0 zI5DnZb$T|)vBu8T-^d*gzMh;5Ztah$q3D`k(*W23fUnvi+Ez4a?oz0%{*SLT^o_!y+*0Y&jkBKrDQ=!`d~qS$m}+o<dfVqlDq2tguc+!KOcecF6|XN2l%m4r&07*naROM8cuG0DZ_y6J91H88V01eI^qpP4hyxVQS zE9aSG)e)vSWPlB^GGSy+sQ>6(?5ju71=8QxzL!kN_~g4kz+2z>_N>U2{%}fL2D4xG zyWa(nVPF0PtJRk#j{{f=5G}IEkhD{k#zt15Q-6$=l&)a16P>C6qcs)k=BRLg`v|KE zsWY}?3k$PNsfy0XC<%q%pm8&n%#Wg>HU3juEOwo_y~@ghcUhH-EOI$=W#Id2!pqyD zuT%)H)sV6P+!h53%|8(h|Ku8#H}LFM_V^mY9-5H~k~6bcsuI~o4O%gV+hNx6{&+0= zo1P1Se#pphjo3?@W>*e@Xm%g=Ug$48oA~&4y*x42Ib%3P$o_=@KEC(u^HZNJ@Y?nR zd~o*KLF0(U_vG%F+!#?nPz%5VuqkcAtVnL`U0=PLm7!TpwM&M)^b9jo03Ke?@Y%O- zILtc3PityBVEnVC08O{EZVkQTd`lI0Gg80;?+q?+igORVZR;)ytA^7^>T90`XbUai z9OpRoh7_OL%(1fU?Z6Opxbuh$0_pkjd=3kx&V9i-(Xnfkz8ISxPp@s)or%LVV@5h9 zZ)b0I)*l$N{S+B;2aGXF8E3P0g^@y+P&=w6HHt9>DA%hm9r4T;S>(l%G0`}owAU9s z%-7E3L1T{$NC*_Cx0s*r350w)RVGlT)N+FAK|FK8L+H92c1)R|3AT5_qTB?-T$}Z9_hr z&25<72dIaPK$*4AHBX#iGM$Iq50aJj4FN`*nT^LCn!$wDcDdbO7#10ug4WRN3g?YM zW(q{>K4Ng1J`2kt>)6s^%a*wxqfUGf?WoH%c4 zA6Cv@*$fZYgq2~2VN5|B+d^xP8VyQUJyt5o7AOJNHcP6IQ`@QVeJfF5g}px?-imVpq9hbt(x(~si;Y{ugc38{F{p@{!q6;J!#NC# z<+^oiJN+K-uX{2Wqv{Id?$G_Fxk%oN_`1&xd$sD?g3nlu+wXehJXpgPSPPG#5QRPC z=YriaG9~Y;L52&QqQFy>SmE{U`v5R{BDHl57z(Y&+VjFsxW06EfPVed{rF`w(jJ$+qG>U#w@V4Ggj@m^=WiEP+V`8LSh6)u5 zr`JmNSE94l7-#8)GKC4Z6^=M+Mn|>n)BYlpQ|*C87P$<$H1K_$pu3;_POYz8Y7D^b zcC}w>nQAg#A**hWMUb5~4mpC{A6xrLTOiPVu6CbXHw5CLcTm|kRqX1GRo2>$RQ}ra z`bO0)hq1_UPIl-p=)1?^7|LMl6ayVUL-u=v3_P?aPhXf_w~e7Ke{^ z3<&>qOFH)Dazu4X?D$gVTVqwku-IUS4KA=kb+l)~3M+WC-58I(!rotJUhOLJ9NV*N z%$fBuxno1AE?w9G)14 z*~aX57x1?2i!AVN_n~fI>nu7)dwk0xH^DaP^+M)Im&Pn|>@o-)1+`ztUhfpM9D`_k zPIetG>td%H_hj(?6y|zbiQ9x!SYeNi3)__dV<4N{%Hx380L9PQqpJ)0}#|2pVMG7{U3nn5 zrC5+#J5XuaX1L>}MOa`7F=zIB+z53$4AJ44k8l({g-mA{(`aCsGNW3S3Tvi?WRs&Pg(-U0d^}MHZPX*WTxQj2zRu6#{Tsl48pB zxNR^UL*q682U0+cM-}6(FTMReiOzuckmu1ChBYJ{%amT4fPxW*hi$MkXWRe0+A7ub8rR71)$Jdf zCxIzrN4%B_E~3^e$ISIvuY0c zCawZ0eM4}2hy#g@&Q`7nkkzsw8?MFoG6Qx)S7;bzQn--HDJd1KWx$4SbO@vXE_IZB z`{~{#b7a#_F1*94m{d8K;{o9M@D?77S6~C4P|I7EK6Ea}&Z%kgmw)*$@%hjH!Njc= zS>(l#c{5FF8y4M^&td!zytYxhv+k{OKBmw2iBF~J7MY)<14ixUb^mX&Crpd-x&wVB-ZdDu#t7Jz4o&sMEjfE$OXr@|HE zWqklym8ncYb{tl6)P7_Hs3``%PgX8`OGl~ZX((}sn0#OR0#3>R^EcaOt54Qu49u6l zz=>}uCD*@le53~5TBk){tC7BtvlCqSB3qQ&ffQg`fjWY?42=h1mE#y$W%LS=(EPK4hKG2sGIvK?(tDptWR;b;443rSZ z!3u=C&v47L;5(G~C)1CA#dwge(v&oQS@3}8Ksyg_t@F8XR+4E@! zYKI&05r>i}eT z9an*KypOfJpDGrjDezWM*!X~Gu6N=JQCZNe$L$Vvm+w+3V1ux25|a{+A)I*0a2GD1 zb%Q-viMv3BTR0E4W1A~JAuQg-5HzxImfZ)W-BmmZ#}0%C+lSEnSOK9MWG+{>ao~#A zBR57t+u<`8RHvLthf3SfO6$BKJvcTjZ)hFzup8_=o7#13!Zf<=ax{Sh$1=IVcmU2Y z>Swr(3!FGd)Y=1Xo9o|ZmoxJ|$a5HiUD0zpZ2Woc{dAWFW8nK_pKGl(zw*yA8^Wn( z3{B$(a7;VA3#0L4%fJW&Te)2-2^T)vgnQKU({tOKu~hzz&HZ>qBNoPC5jtx_w=w*( zxsqjH#BSHl17C`*E%LHUJm+_bWx4?Yy;ct>Em8Zwee%|KzKtKg^X}yE?esZterGqI z8gPJI=YHvav3BWFYwW;WaoGm~=i(uCOz5DO7MW`>^^9~y${w~?F`h%((iJ&6&K_9w z-Xc@vMueS@1>SQX?HEF}m-dgxf>)X~WVN+oag|)hf4*7%BL zD5q~sO2H4`dDpkk>N3DmMhGJp+UxRpC$kI}h$vAGw$}NS8U~GHsWrc!74r-KPqnDk zlYp9p%7R$-HwL?vOOM!KhZRbEW&1H$%OE%V;d%tLbRgBpvG<@?^Q+@Tqs*D9joV(F zvg$Sv=_=OKVFCZIi(>;2-TNWdyHA!p@I@AB z%iI};_Ctlj+d+V}E7QW1Goau3s+3VU2S^q3P}pHy>>jN)E}`d2FjZjq{L0&~85-=d z2J^*t*!ZGs(`#L9@YF>k(fQc8F;5_v~7VP)wIcmr`TZ@>Jo;}@^-@FWT*hgB5{54d{itpq&7Sk z8;}!*GG(o?stHN1QpT_BcZMdx0xNT7&rbnSxNPOTqA~cU5X6!}C1|tTNQg5$OQ&Pt z^f260e1ly8inO|OSWlT((Sqm(5(>@j)Lo%llCke&ru*`>u0w3EY4(?1V>fDYB)Gc2 zeS{s>C{W`mZbQpW)n>obyxu=P`zF4&{m4TU!Y?|d1gw-Ov3AcJr+dqS19K+ZE@=nq zj^A$ly8TD^Uh|{DeT-R08PE`@#g)a?g-7myt~r`mjR&l3TgLbOYuk@Jl(wPt44vK? z;0?eVXk>V`6rD9YL)KR7vQv|hHD19sPh-Kg(&-xZkf&~^maI_V0vl-D$I1h5a@jV? zD4r>Je0d^S7*MV;%gNDDRc**tZ(8Ke7O=Bp)3!gM1HeWJ&?Re~1EH~PU9tU+s`xor zWRXSM&egGRN9yfrYqqxRvG$R4hYFpVHMD+)WsV!b*`}FWKl2(4E`g^86OVXa(#4@P z^;)k!bKJtmV?0eA;9}^&^>hQHiIy3 zJZ;vS%lSD5+yoe6$W;z30Buv2VK@aeBr!vV(i>hOZ=M@AN+F?wZ|n9bVt)#)|N%)S;_U#Vr~k&wcrN;50b}7 z>6j;bpQZrhH@5Hj$>6%GmB%ur;F?BmuxID=eB%{L?~q`A7~g{&_3V5vItCg@)%eCu z_X@Vv6{Vi|sXA#cq@E`=Sg0ly{+k8w%w>uu8EC&(t2J^5uH`#HOcN;8P_oy5nezb6P2Wm5RIak{aL0jnT zaDq6xhK|4nnKSmZx_%Xmi;jmF^lA`0jl$e(K3>n2d!FIeERu5t#j^iAzD5XSCghy= zA}ru3GWN|#0rK(EG=GX;{<6SlKC|S3FY@BboT#R7djuK*k%m*Zs0H|zz-Y^uVry?~ z-@`dhy#v&Cmq@YUGCDdPX>|cCYo=X0gs|b6$Q*a#q8n>J&q(CwEzg2)u%ujDyzp3vji*}Jku2yD)@43Kx9_T*CYmy4QOYb*ULory*y@{9#Le#p< zarJN;g2+8sBbO#*?wJq^G8A;M4keA*nANj9j4spjprW*@YlXcrGfQ(WAp;Ev!>jAm zfl&>AhTY2=Ajl)OEu|Q$8MDaBHfuYpkIue6;=W(5+%zT|nAYPnbN6|T5*zIB=7 zJU{A5n_q5YnnL!foBaum&~Y;MJ<75#;xnJg@ad=jC+^+*??&!@kwsoCY0pOr3sd%4 zIp!yyYkxBX@Wo*`qbz?$F{fCIA?PH_Rv<73W_?3v6(=5k{))YxMKYrF}>uKdw6 zHxg0L1l+O~L(@~&Bo3F?aBypKt2wEek-~tV;-ZzutYJy%a8kIjQzcFTr_3Q9+j?h_ zd9uL{7p`EIPVCjFiM>k*l&zzN(I0avU;`3*{`Kugfhj;~`{z}zv%+Z{j>u)H_2jR- zNf$VQ#DIvG|FZhNGk;F1>7V$wp6){}bQb0eQ@hxLVwt(dI|nRt$8{G*ugEh|`0Elf zxatCAu`_)dbECQ9utFeYX@y;u?=>2%UDQMlIN;B?Asagp-9V%V5L_Nj1KetpKbB*kvs+C=`0Pd@o5{2tgj^2rVNbx>|1sdljD8M##1z0U2uE$}|m26L(Qyu?}^S=Sjbqw94vV?b@A^RB` z7yDpM#dthcd+V`ifO1Z;;px_CqLQ_aGRC-^Vt_6ce-~LqL@hRvzUV9~taHM>SdO=^ zp3K-nt0_&x?~>-&c3e}h$SlTaM?J^N*^+d9a*sClQ}W1H&haZ6@d8@pcWiW2X(FpC zw5^Oj2SVzc7g^*wWHR`k%6j)1v15RDAHy|%4B`HoXt^DuM|@*e2OI+tP!e8<-u*xIm|h=nK$c2wZWWPXe)Q-AHQpP zi-m!{>5^(GGQGu!JP-S*|95f-<2CtZ5jey4KK9e?{Psm>O8$87VH8A*eE9htBaGf z)(!@Meb#iTMh3(&PiZDz*&)Uq)zDc5{+k-Gwq|?UsmyWkxru>zn>R~E2E?HI>f}%U zsat*XX&ga>KqthOW9qle%zDa#%bIj(GP<({ zot!x|?S{u-BoIlUI67*FbubUq-ntHJZ|L~Kn1QZ10$Km&q@*qKa>^v|eT;tIl&%o- z5D2HX>jU%pTk56avcA{N2H;taMZK76GSa-#y1c>~uif81qxt^!k>iSh5+#J4DUmw` zl=-kr7(+MA^R{QwR+}Lo6Pk-!D8o7vY#906B3X;1#d@U)j=9W&T$7uj4X{c0&?PeySw$Ex;uLwhwRSSmfvMsm?2CQ3P8EP;KEa{RI2(I~vJc@M*r1hi-$6%L+z~8dYA<*UD%>Q2d zF)?;Y^X27wS)Q7AD-Jo2pQZ4aVY~^VvGF<4-}~5}G+T5GBq}xkbTdDx$MHLh}MAqg#@8i4DzGT^m}v@EWQC8@}q;t+Nx}CS}Y|1}(g5qkY(> zG8G-QH~WZ>GaMadlbbBXq*rsS4!cT+0^NP~Fcw%sB4e8jZ z4$Y@@&W%-1QcP-(!iATUF(&X{4ODOhq)+x5JFJ|+E&E=hMCFZHW!!5Q9-2Dmv}(zq zN-}0u=rjNtpQpZZq30W1U~@o`tmj$A0OS*FeAWz7M$DwG4N*qe4$4KcH%f}MH)xM}83)8VB7Gr4ufW4cg z;Y)*Ou9XXowlIZd<)Z;?nhVF$Aj319qCptK$Ch4U7_~LR2$s350J(kydE}Jnd!^UTUMn?hL&pU78t=n??*iUaWhmr)0p5$e2r|zho3`Bqh|6bd zcZSJ7T6(gthR&F3=PQ(WhFfkP&^@Od+*ZVaEc&K0GX(oMu*QX)lbn^dRIFTdRPJ>1 z%7>bZ4LTGZr5W#g*V#eiP(!C^*Z8en(xv|nktN+`k*RWNIp0%(cMK52W!;8S>NxsR zQ7u@o-Bv1n`?U-*6@?Zt6HvSc!?>9zJq%u%qbWtknC;0b=a#9qd`97bI7_gpN!KM* zIlKm{#x%H;$0}T*wHG1OJZ6O{F^Eh7Zo57AF$Nf0v0%H4-90>9e7e+$C!1~F`dGIi ziFwM1?ddo4a{$bEDkh}f|@>}H$io!9l z;@jV#z{Z;y_HEay+;Z*3KsrenG3gds>>C}2dw1nD>v7YdwgH*e#^()Yt*tpG>#T{v zuAUp9Ohy}k>YYk~UACXmG3(JRSDn6(xw|KYKUT~T#bXLbqccn6#?j`W_Z(Scj}mL6r_|C6 zE#p{6s58;lE#j=F^D~ob;Qz11C8gkSS9Fx>-OOJN{$=zP=c%@}u4C*1Xgxqf zsR1%08fl~KbK|d0`}!%k)ni#^+k(arHd8E&rK=UNz`qXGP%b~bQ#Hcp2hn-Q&zY?r zo?@KCxB!?XHdeqohf{83mDpH}XQlS_2~B;yrfH)xKK4|@b1L)m@Zmqlm%sdnOCIF zzh&kaR*$8kqeAMa9f<_D$F{|PT>ZDO-iyqUOJTlKW<<&?j$gR;KEicF6QV!-Cst?H zWT6R`GS_2;*f$QdPO-IAOb`uF18D-uM_yjTPlE=Wb)00ur<`%QuHMpVGWI z*~bQwJ)N1ry7)LDV9h$#Bd}ISOS^@Z1?V9+9D_T4D*UgRXD_t)PHy6IWUJ5tW3_n* zZ1uZd3j|}b_dGWC;74Owa2>a%_zc}cJ5Dm+G=tmYvFDTp`_QL>E`Zvs*JXgG$E3%x z-Y>^6ye+v(q{4bEpoVQ zx6PuP50pXheT?eneYYrPye-$zu4|i88EH{)O1P~@3%TO)ZG71a~00Q)@8vI78!@R0T{^ z+Fb3iMu|0c*m$4^NTI+ID@f(;ar=C*eTWh(Jj3bis@$n~8T;vYlW@p>0~Tu8C9x-; zy-;Nz1a%DJCQPm!Wbe+23xR0ux+9=X`Ul#>9|sdn9GZ(|XW4G*aw0j}*FY!_W2^uq=2D`vls009}S| zI4+egHoKeEnaXBQk-5=veZaeKzl-6w$aP8VkWG_EsqMOL;l8JNk2N;f_rAaE95N)@ znlN;-0wMq0<-D`P^>hE->be4Kw+L^;5|kJI2s{e)ah&>=0@p*)QQ^GNXCKFO-is%f z8MQpLZ|Z2f-lDfvF1^opm+vVCyP=8G54zi+I0U_RO&VKj08>HG)3$)j!dSq&(v7b%ysb z_ARlxN1Lf+?z`n{Srt}CSb`yX+LKzMRoHflhDyk_#;GSULr}Xgb3jA*xI8p+>~<=a z$rb*>>dlaewkb2QHcJ)HO9B4210cohS`FVGr{!vt71w^{Dd_^XO|-1pWwfq+C+_UqeTz)*)f)56_H{J&Zz1JC{TKAA|6^a}Q~~+~=fh zuQM#i&_9=*)_Yx&IjqonI&@o%KbG!aT?Z_>HLp0_qxUrA5Jd>6y2NfXR$`_jwa3PrR3Rg)K$L)+21)KCW*WzE%Nx$X^0|a?Hu~laV)SFv0>i4CLzPz#p=eI-YyRfFMCebDC6~x zovgZMY`}#Mk1k1p)i~6BUeR|vCXVD+>ip2{nH$$L-O*h#CfECo?R&0WnYIJ9gcO3Khofx# z|Jz_zbz8dTNfWr7?cO<`wDqCYSz#;D5LCy&yGti`Io%J{gD)y@zAAZ{^>;7$p7LO& znOjPeTpqsSvH3+0AdOBnJ}vJOA6t#|ZjTum8GVhdStZA5Gu)xr7kPA8P=~}uZ+IN} zN2p|%%eHyXQI!pEgOiX6vw&)mw7ju>&wsAXbJo}XBi{Z3C&nPxiRJ<)qrvwMo7S?g zY(I8k-z&dg8&X_4M%fCVf3~3zjlpgn?k`*<$v+h;ec(`9VlY{TX^fAgPVw*ywIpALqjcgd2AxX4YA zZkJP47gtxOdCy#UGT2umUUDoGZ%mUq|bCYGkxfY-WG1YdL ze|Ba|>Cn&-tAAt1bKBPM(}hFFTjaXrWr}F(1mA}O@2>S?GY0v-XQQ^uI8$Je$W;DfW*MqLle9%~dR@eHTXmOvT?lq$Hy zapdm_%f#p}YXpP}&vzYX2ld$x04(XC_1{p}+Fm|Qj9%4^#XkZR3g0ki!a%QKw% z`)?y8&T(ptdUans*gkBvXCqK&h*ymqzr<$%#E?aw=s1qyA_1~fQlQ2fyVmksIQLGK z0+ky}fpeS!05;g+!ZXv_QG1P@2hD$U_VwOl-`_q$>Bd~5M1u^41I@YP-EZOCapL>I zXX@eE1H8U{A3%eZtHgbZb3bN**(F4E6&~)zEaMOaojS>?;lS_x##PA1sxvUmk7mDV zY9x04wr#Nh%MPSMq!n=1=o=N+v!Uj)Pinp}mrg$eq4riy6IRn8n-Q`psrkX4oi4M# z#mDS24(-0J$!CGCeP?6FX+GeM-NoS+A?F`H2O$V=65~!u*Ka8YK+4$E-^TCzI%F>J zrYt#zi`+EnvXSHE_GvA#a`QUv-R@b9Vdu8RX-aH`a0_b1Hmp4PGOQ0m_iIYuT3BwQ zqip}4R3t$ADEir=1fCC~W#RVyx^R)3DKCQ#zr;S@l=jON2eY&p?-W0y0g`$28g`9< zYvst1x#DGf8EK~4OvkuYkFxF}!s@BvSo?n(wmp?Oez1M$LV{QROl41*12Wp%m;JzF zMFurc>iM4tsU#P`^=t`nJH%L?33kcJ z=Oh8BQ?kKs&{-k< z@bmthI60OAugtXl0@N@`F}ERTjDa|!?L&hs)HCrp$7Yy*PDvWPwwaFb7~ya6b!h|L zv@0^+S6gDkZ^&8D9-qAe?d{uox=*^n_wYKYbzcT~nV6JCZmJBqgAbQ61=rYCGNiUd zV!a``-YKV|tR2s&p+44i8oxgap0y)*I=V_FtU(l_incR29!o4SDhcH#IUpBNc~PU8 zE~(WRrQ55=7cUI2Q4nm|ZJLMVXhV=53c-Z+jIpvK9IvE2R2$r9E+m#_FvqF}t*wH~ z@LUNLt*}CYYILP&06|6Pue1t3z(nb)ZYuR#9aQ#`B8EFa4t_sQD1LpU~G zQ-y$;zgDrsKq4EepptwFGz`fJE@qFPjPe>g@8FSZ%xfsl7YRMjCPh6wI{StL_myY) z0r=8rE0nXMD9D^M_qq0OhFtL#O6;)?uH)2eIz`ezF9hHzK&3`T*b=LOI(KrjUC1J* zbKl4xNMDR<;P+%INdl$N1_Q*wKce-r+TB1LXGD((TCFEUR z_*(XltD8A)uOB;N+U|+a6)?}Jh)13tNB8>u+uj`ckN@$1#jCIWkI1qw9<-kYgfDUv zB<*lZId1LmVlQn*%>O@p=UsfSBgK&gR%xZE{lZA7bkVg~tlg&0#TZCiM=c`=xvuK# z;n{k~;i=<|L3hfbYkv>-yXb|REH9$|J{WwDHFi@bjV`xfI;=h(7FnwOI+Al5GSqfY zY6x3%h->Cv4P|J2em9}C?SyNU3jvme_V;!tM2n+GqF#7s&}ydC4$OvvQ%&E0lP2_Kn_qU~|TY zWNaS!6tRplL(zGjw$J;VUhfaj9^n4=Lw}D;tZ{-J*4Vc~^2dr4X=8o!3OVvXAH?gH ziKvqhAf{w2Y#k%r06hGiNU1eJWJ9X#Ak2j~wwKfw+=oS2Bs!dQVJaJIl$ z=%w7)O(YxiJggHTi}q)kaG3peY0p^t0C%{&OVvTQy}tE-->5Q??nib)(%AS{8%W>DmY&0Sk3S%3lOc%Iq5c9crDC?XY_%9;@mOy zg}ZJx?_Tpp`||O{$x(qykxG4yy#X8w)Rk#hM+rf)1@=5o%ZPIy7MkR4``RCW_<2v| zh!Y@>jdZvSKs`rdMwyKL+I8%n3zpZ|y8wH6Hu>&Oi3G9o!P#s0`t~FLEQIV~H+0~0 zdKuEseuwMD#)v+P>hmvQ&FTgHR#ar?Vjatz>2c^UEvUj}*n zI1Q2?KYrX=_T)*|x=*m%NqX0_XKTMa&+jDHkC&I#&ruY2P(;fW!nP%~T;|KV^Y>%R z8hhVTlw$2E+Iu=5iDn~NB7eEA>N&1!?bJ3CF2BT}xjQ9bo)IJxv`SK!w z@PnA|l#&?hW6Gje%fdc_EP@?nYHfGlFa%vrMnS7`ySdACkziXfOPc_o3Fv0vb>+g& zYY+5dU~8*LSFT+X^H3|7SF=Ki95ueW{bOXPeZeUDF&Sd54JC4{um=DKLKTA2A&{dE z#!aV4EGI~2Ym8KXXg(tpR`t$NT}jcn>nKcjh&(#`2EMla$TP}-egEdS&+FKOKT58nkuH1x3`{XjQn3=_wwqV+e9956A;K-Wy!~6ZPd~*ZbR7U4 zLE^s4wqK;nPGeALVA&%#=6l@AD|M#xC&O-*JH78V&<*z#vN_XP=c$0ViT-p)u^7THmP`f6yWI|(%_dqmy^p(hL%{pVC!gY#SMK4?oi=d3ckf?w)axP)>hpUo_GJ%N&P;|FsHzOmRxrn>pWe?xtROM*0uKdW6#<8*v96u zS-P(M*>N8$4;*;DjkjaUu~=jPo=M(pHZ6c`B?ifN?%cs{x5J$~cX0RaUBCR^y*AM9 zI{vG#{@ua#Qu33ZG&ngKUN3$=i~J7i>IsVccF+12ddBu@?1beyVog<8;TE2uKsCxn z8ft0F`bViKBcX9B$83jjL#)8lp2>1QLp0Etf_sg1U<|?$EgzDY3hUl>0p3G$6%iI! zagCo>9e&h;YkjYPePv^CsQ4gt653>sRhrL{F9pn>tj>;!dCd(7SAYRfc`IS%N~i-DLjjxp<|_c+~nI4+An zUarDu>pSLu^IQK64Ki#tKgDi$oIG&g=7%uO0mw0vJeEb??RI$l_z8aFH~vm*-98o> z5C$3mUU?(DuS5FT>~4wE*4q1M0_~gof0}A}sIc3Q0&vv}xnsKv zXD>I%T?`_N05c|4=MA{M=^T>#y=seAjYHB{tG1mmR*nI>rylb<>QPE%Va~J_YU|9Gp$A`b6NOV z+AQsTuj37N{y1x&BQ4TETSpZRd{^!=5}21Rqt+HSBip>ezO`Q)c74l$pVEh;SDirk z!S*3a!%!cCL4MxCs27zvBM6Vz>KI50Lp40s0+**1GzUArYYWI zu;4)VR38K8_TL(eWQjp|7!i~SdT&&pYVuk_-*@yWhR;VYH+R+{$kuNbX{g zpBJ&V#4+S~1K^j|=Q}Mi(?jq}W0+yDYF;zXn}GZT7aoMKu?qk$0HYwJH599Hlj)XG zRHy(CY>VKZ?3e5`L%!|)e|+{$2YOdvNW0{fTW~I_O~T|aTpjb$b$c%HM`vF@$`xJM z=@&=FPNK1pk+w{CAL|W-pw|8!VyXK?yyUr?&I>%lEgb5#*SC@-774`LN?ST)7r_$c zoR0ytr%$kU1bH+X>xATWN_{R|_4zL7XxsCpxar)44Ay2XG9Yn?VeR)!t(-aIOwY{KbF5y?gg&vB5*3--{e3p)To)c#5~N zKs;-?rc+_*hrWYvY~RBLPO!$_MUCx^X3q^^);=|?k(7Z2iy2WW+i?7J8-zVNY*dv< zSRFl#5KGM^shOnxj|hYQF^#5%hxWaMLD9}6`hiho6-YrX&rUH^ZeL18EEhfw;*9UwPV9s zRII`pJ8ZDS8au2};ufAR%<>B$pM3WRo#58yMsqz2tW(={{hnGLA3GHW-q-IFkV#fS zZGqA`xmeU}syx^}bdAN<9>izv?JTjv{q3XP_o;863K-Q;P@aIx5iAQQ?$iXGb^aFq zK26eL;!W$bHK+)SZOcPVI%$IKW2Ur$hBFqXK1DpC@tWn(`eav$jm~SQc6KaTt^Q`0?XeAo}iIDJV8)+ddY*|Co32 z>8GF0+V(||J`I=!pTk+JM(!#BP16~#eE(a(sDf(^R<2r4=13`N@5%ydmA7MSF#EeQ z)K(7CTP*#n%|GRv%mb3-sq-}3TXNpec95Ji)H&MSog$oP?9y<(Ec#`U!(>Re4?8=? z--}~KBt8#v3Cwpt&~BT&%3NpOw?-hYz?iw%Avo^us|*15w;uwKzSRv%G+23al4^p@ zzD}_7%=8$b@Z+;@;`QzOuG0Aq8EQPmZ4^$uu&TIq94x^5dZZ65+u!YaU7vyeJZ1ZP z{C8;mG0TVc1@!m(q!*l^*8Z)L2QBi(3gbE$r^5X)I^-D&+}}RJ8oN>N!0X%hvB$>u zy{}!ivi3Z%+;BULJ`QF(6dt6Eq4;QNhhsa8FwEssXCpu7fj-p80j^Vc!^SQ}ur7Z| ztp|5c3g>`f5PIfEV9gv0u;mz;=%$X}_xojy?PdY)L(VZao3rFG zQb$;?z9fG)f9Au{yRJ)JKfz}6cRJfi0l>fcH);0dI+)~CSovkkb+P4l?%cU@N5kE_ zcY1q!TZ!L|ytsq?{;#l3%mF|;v^t!%tY%insgOq+qXdjgDeSUyxb1`OLj$f0Gso^- zdS(sgZcD+p!bLsRfO8Er$WdS)&03iU*RpQzm#`NPX9^3K^^Ff5y79HsG$;9HuW!7J z+s}!?dS2x^;p&)UPjRRog9(2g81SPt!%dxHUoc^t{jtjwgtHA;ff6S!9Q+oZj%Lx; z4osiong6Ucy)D}$%gC&cl^>sd6C3PI{<(~wiev76Unc1ax9$tW{^YwqX#L)|{#3Bs z_jyRBtb0>LY9y?2ffJnL)H|)l$m`qpJxIR5#??GnVUG=V*x($eCh21BB1XF9!S*4Z z;WnP(6c;#g1_Iw&%L&`Cd6laOG4F!;DQ1I#e5xPfuyd>L6nJm2#~M4FV22Z2-~<;= z*Hm7Q@gH?rVRTJ_3a7ZhDK4;a+seNSuTyjH+9>^TWBnX5@F9#Jx=u~czbRrzGqm1i zO8d%;KVE9vsryLn=a@1Ecw3{HBbs+tV~O{X-e+ITip>L$BS5Cgv1;Ee^72Y5VyP`w zmnsNn6WR(ZtX&)0AsMng9-ckGqqA?gxn=KW>*Zo%sPksK6QE5Z_gv>y(vv z8Q6GzmjS-$B%^@hQCc%?9Tj+tnEBV*^DaPG6ZVvL@+8E^Z|1&!mS>m0J=x9+ty z`r$>A0DNDrmmsz8#=KOOdF8qoZ~@12L_KsXA0$KLmmWsukx!MC%Po&RelX^4UkjjP zN?)jS-?~FGH*9+B?~5E)re5y~D@e<{mFqzd0JrhA?MLY9_bxzLCv3h&oLCF@%*W{> zi~#8Z_7AoXVGE~;evphfnXsh?w#qqmoMpT7 z2#Blx6Y#xuT^;1QXb8SW+Hl=CbSp!N0+Q`lI%h`ifwr_ET)8`!ds8ON-it%dLjWF1 zcps+7Wlgeic>0Srna`Cm%#q44keDlZ@XXpHrrb_)L`0wLb~X>Zdtbw{0Psb+WbPBM zj@VFA@6eR@YU;diBS`OWAE7jFNaX;wj3IY(K;gsIY27NHt?*m>aWIEGb9>P>tmC^j zzi{SIV4em453ff$pg9EMZ9Q=uc@Y5ee7!v;-K*O+&@JOneIWcr(%(l5JMWY5#`J|O z+N$I>1GBRQStO&*hlo49OvR$&0)=GW8iMQJA3Q zQ=H=zPjMSNoM4YN&T$LpE)4tvCoWKJjS_30H)aFW7|v!>F1Tzc0_5S@1AL`3l9T`d zAOJ~3K~#M9PjCz8IKf2#PSqi2>vmgbmkm+t(lg^^Y-n|A8<=sW{*oWCsVcU!!v;H- z0C0g*Ji{%V<2IhUl6HF&8^F(%4+&&Q;axnz9X!PyJjHE1!EHRnDb9niLWTrt0~#B8 zu45D@M;++2_H~*smla0ccf3Uo1Kx33!ZAZ9+e~2Ec^`*3+U?e>FX69$c7gTg&stkn zRl7I#7-3%V966+bSzlYSMV@b|uf_}?l(nmQw7~_|C~*f*O!AlhOQk&J!Cz~$m#y_< zUR+74kny*+v+aTuhMH>F|Hk#-RVS7k$4&w*NS39X_=UANDXf9^QBVwtK8`YWi%CmG{ox!2Ru`xx;FK-vtaW(j{+f z-wVDUqpv%qaz;Sq3Z^wEkvTS-lPbNBWWV<&EZmBwjVS94OzR=PLWvp~PH};!$iXHj z@?Y)sMCtVlV3oM`E=`MiQbX_fcu9lv_V<(nl9QKIC||j#o(=ZiNZ~SmRsi4l`%|Gn z;VRPddKadcn+za+lEC zTK)RD0IQ=j938MMcL>?yI2Zd}^+f#sH^FhQN)C;WEZ9|F*P@dg*Tz^QlW$+0+XYoJ;j&J^b;A0nwebT6|WdYeX5 z8J2)dfjAQsd@BH7V~jmCO0K5` z`+D^(u#>av1Kr1*Ko=327mblJR^xT8bkEamrn(&oF-`g%U@;hP5bDKnKeA?D7~>o* zu-!KJo!^IHMwkcpTPo4V^^F7wC7+i@xR?uqaI)l*h%WUt$Id$bX$u{RYoJZokaL(Q~5(Xe# z594F3PEY{X))O}YB;N!?a8=hKrN4RnA^n|_v1C9jHwl1WTfsGeY)m?byNO;ZnuUEJ zb_g7=u*U^XS~u+&Aeq4zw%pMkYpk5-aBlzPMUF4hYHQO1DL@)9TX4)the22jpvqC> ztJ^Bo0oL=})@r?`nW)*D;oel(V ze7c$UO%|5tF}K*@!?Optzx~j&?izls-KZ5Hil`_35LSCgy1+|UNSX!VHbghBbY2J7 z{}#@%8YtE%?PHq3^#Hg^^9@!;^%u?nT4RR>8~>cq2$Hrj1mEpRZ|X!icjCNG8Ed3m z)_EPvNE!#afiB=38^G!P_J<+1kJN_AS@e5oRLAdh7YGko6aZMQeu}^T*?+-jKl6_} z$GFJLBTNNonthOpkV;GFYDZR8<5~U`^Jkw=&T_TOlP=v{dXAIP#{huuH9rC%gw)&F zn|SLx-<}P^U*Eou6JH8+h1%5&5&OMypVgi(v37Mu6kO+K9l~ouZT_`+;W|SQK8K)Q z!CB}SZqH3trt8p~GD{t*|GV_=wEa$VWA-~cQh+<23)=cS+{5!{M_38K_t{x?EwS)i~^FgvLLZwxirC(!-70z*MR{!LiDub;pK79@-afj6@U*FAH!JR-+qV^YXIjscdT>{ zWq8Tx&Xu@WB7>qOEIp3^L3fDlaTT>r2`NCLYDH@`kvC;a3m4IaE0Q}}ZuUAgj)ABO<> z=Rf~B9zTAP%#ZKd2U+s6{5b#x*eND_y}pMO3}{C72oJUiY+kx#6?WRjl&m;D$L3;4 z`XM0P&OfhhKk!a>aoDm=sivPX-AkgZXrq3nLV`r%;CvM=?Fm0Q^ds?>DY4VBF^hdb5FSjzFjpcWY7w< z-Bsg{C5P;J?qq!V&rXV=z1lIfk7s2%=w{^F5Odx?2J7;SKUqhP)y`=Hju9|nNN)(z zZ{PZ_aen@{aC$P&c>Cz12LJS*PTJ&!ml)jcc00c;2FZQJ<9_xt0nm1TU18*R?zETR zyLS)2`m3L7Er0dZ{;=|&{G`EpeQz-QeCqqD%(gzUTqcg=3Sq?(jqB37Dx!tYaq4ZZ zsq=!(3x7L%698rbaciI4-+t(s@C-KnjLmk%Hp*e`B-`IZC^iek^>g87$Skn`vVb+` z+umlvxn4SI<}f*qjy{~p9!epSqomhqV4u3_$CiEc+e4u6#vX{rvt zDWT_=3cgd9jF-Rbf;A8?U*U{twl2zC9Y)z^TE+AG+eg@8gVN=wSRkH5*lsyq?OTS8 z1<8BUKuK#bs~Ia`b>kI6i52c|9|bKQ#>i{i4+0PjXy`9s*+Ka|#gx)(S-G6g9E}f= z2EzMAvl{>ib_tLx4`A62NyAYs@GV?;k`14huz$GgRXBiZ!8rlHT`r@|owrq3yY_D? zT-M%4jSM?%yy}nB9#YCGR^V{wA=h2Pv{|7#&X1OJBI~a0wyq)q;;rv|JGnenAh2*O z>&8{go-)C6Jt@+%a__20hQ?p3l+a1=7W&ghQWH#H2<@DyEw$a4i8j=8;rdzd*Cx2= zM5G)?7dptV(#*DKVCk*E=oZ-Z10=hc^_F#?Kd-?4$A<1_~ zt#4&+0W;vRO6j(M*;p1C06zKTQ|xv-Y&M%wW3lJ;`0*2e+!!R^xpN11@20Qcy?giY z>8GFK)mQ&+^7k=vJ;m)}h&@gSN@{Q20PH^jz!g1{eeS)vewYUMUh|__&iPo@*n2yj z_HE{Bk5tYg&0V9)208XvdmvuAwwCA!N6%fc)h3v0Ea1-lG8p|}nQ+2y{bj12zkZ=D+YYba{~TI49Y!}<-JNofbYJ-{27IdA1OR>s;5)5^y7Iea4b5>OuPH&M z4N3=$YX@8fz>WvUuW#SSGu-w~4=gx_|EwVS2{KeTM>!(Q=fUE4 z#~d55udaqFXU^~q0kZ(ZHj7Nas6Ie?NZCakPQ}UZ7dXLJwjT#okGT)YBU<_8;k}T1 zCLz+YH{P8T^P8c;3OT}8A^cq{I=6pkm{t6o@RKbv!m+Jfb?6ujTSk=2_E^Cx-^Op5 zo2M-ex44|)x#4w^r`$4>WV|^c9TGBrm9oYjd#oYAk73aB7}tkq5Ac=k$KGK!MyyAE zXq*?``6kjNjuIQubC|7hq5vcmo&2-Tbu^}j|7v77F$LHT4b>kbYwTTA2CJo0N9P#l z6>rSh&XcPGzA4uE*vB3hj2CZnY`~p*9;fXq#dgO=oDCqg>&DKdDWZl~2Bw{HjFK7~bo z<&}F_uQx3wd5A@(+`D&g77)IUO6gzvQiebO^WpWnz;#tWL6P4cwQggcWl|ft1D{P` zpTQ9&ZTs;n+mAi@F_p*x+7;4&_|ChNnQ&_(NCc>mTO_k=YF_QmjWi5D7q~zwFT8T| zQSIoM5OimL&Q!iz-NtmYeN2;cO|uy+^UWB(6-y` z_U$O9)L5Rk@blT=`>+rW4HrqViXlMC9FWUhRo)z>12*@!k9t|e2iu3f@;F)I+IiqA z7jDj%HVu+*d5~jSP=*7dvb`n@n#X&yFEB>cw0+(^@K`=MEe*JlV3YmPKX= zZ@lg~PCZw}Tw--+tO8crhFzDAjowGMKXotkmvDLM(gbWiwBB2FYvew@0KxVO&=G-b z?j;mayKHk2nqGT1S;gze`?28Lwy%?WQ<(LJpY0Q0h)i2)-NMrwl~T|z>a5BAGehRJ zKTNz&Xb`Nxu>5f_u1_?oqyV7x8uU!~xBED%z^_h0r=BBq0foyr*~ojj#wng%`uNzJ zd4rw1p54r4$UYt}SIsuhJ?`A6WeyOZcKoq>9RlP1_gw$B*>26ujGav5!FOsj)=<-V z$QpX-VoSP@FoZD%;PElb@(bAQ{|{_7KgDkMg;C?)ZX0~{t51`^rC8)APo5;1q+O-lxg!w`bE=+aiEZpm(>TiwU~w^P>9yY= zE#8~q94FX-Io6qrtkc>z1@eH%nPY#v^8IfC@4P!I0VdAy8PhUfk{AGF`eK7HL_Mn zHgjbj<1W~SM?f+Qq1o{8x)UT{AZvkS<*N#?8fE2+O|T-Q7KXdP30Bzqioyc_H%^JJ zB33yT8JC1f*GRF%dM+U&Y*}fos2zgdv|$!9#atQ#WVS9!K`RByA-hZ#S(R%$d^HvJ zP1*Ytgm$QSip7uj(;#z|IW_x=>!e=Vm@VTIBYE4EON7|t7S2Z%#=1&j!L=?CU$j24 zfP}l*?{h@M?X9uiJ=t)KeG`6MuR#rRVaVj!4DX-9+3tX;Cipf^#!TXAwxeByD&CKc zb?GZu^>+5AuV&jPV+!uY_h*GFc-P0uF+I<7_i`*aKOgXRdF7|=CB3I(on8Na)LaVT zfOQZ7`Yh}7(+1~O`gBUTg*va*B(wH{ePY!Ji=C};ghOb&0cdvE@BhlL^DCeIJbwAh zCjkCaYkaoKH7i?}e*EO1Q0zsnLKvyh z@4V;pYb~rAFm+@Ew6b)sF3+$A9HW~#o3eD)pDdeO2-nUh$0*G9`u2UW5E~;w3B);v zr}Dx}$Mk2;rq%>L5_NLDY*R9pse`l9d3{tf^|!4`$xUFxj{%S~hgtd}Fow>x?>zcl z@}j-fUf27`ryNi%u0We}Ko&-%PV7%PkiYW7#ALHkfA0R7X_9_Ah~ghAqL5rXU)mV?Qr6%r?Z1E^PC89OhigUCAZ)s4g+ z))Gi9>uLzPS}tloiY>ZB4vEyeI$CGLqjunXi$Rsj=kS=W@@1Qxlg-SV`3^!=7T`*`_S(xqu#-7MHX z)WCM85KB4)*7{E9e5c6+X#n1jHjhaJT&7$S^WF9Uwm<6y<>eAKwSwL-RzsA(HV3)z z!L0(i!`x$Kc$J|hNM8HTwxHPF^(K_ZY31|GW01V}`Oq963y_gfS2mg@zc_AQ11bk= zsB}qVwzKOJ{PS9IM7;VbR@ySoF}r0S*zn;^`IltMs9}k4G)i5WFT{lJX&Ma zF@+McFl5tLt@Z6bY{3q0&2!>D;`Vj%m@;=4)v2N3+6Bs^zvx|)UW&;cnjrhYSK7hR zZ&Y*@akIkfvBw%~S2(3l`trVq0HV4L#A#3lzaJ)-0lZ_W{{Qx_rbmwCxW20D?jd(* zL3`1xAuS+aeO<|S34#eqqP(D?ldgvS1N?)0lHsebjg=|v5*FZ_4wkS70fM*(!G_5- zAOXS*$^NSHA@XHJWM+MI^$aG{h6E>8eDF5TavwzD zG^cN48|B!wQ=d`3YpPxu2fY2y9h(pRV^e4XzO>-{-@VE4qNToTHD)mzj4qEv-BlFt)M+p2`R+y|eF%;1>)rC)dMjfu&IMV8^?AIKZXeXoskW0Ke0coSrB>Ue;JAY(o{;xZQH05_()Oii zrwS5YV{0kv@1<7n6yWkaHwM`xn&iAL+>}bfC=$zl_O;ud%hRLxsBHN{`#l01b}~k^tZUbe$snB zRS{Xi=4R~H^GUU~{I288abi)zIj-Nw(oY|KAKzL3%qR|<2*?SsN^7(N6`@`cQl>sj zYad<5FP4Mde4dP7ckJw$A^`d4co3fUAy^tU`zV{zH82YrjC({SsC6&EB@h zxGkQapX2iKa+c+LZl?5m_s-u)0<%+TZdUkH=o{a7fnWXV)Vq{mLOM@vE6R}_Iy4bt z5{`Gl@S_Hn26V0FdfZ`!CAN?dELlCa`pN;*6BMUp>x7>Y6HZ!Uiv|rE>|+vP8y8*& znN@)K0anJQYC=5r#3086Y%D@baF@y;$Iz)D*#hJt8N2UThiU@P94|FCq%825tbF~r zMZbT1sr+of5F*_f$kWBbU7PmuDYaZ%OF7)RKW+eitrA`t1PzJ6az6ycg+#9F8v%sX`S{9?o1AF;hx=hed(P`$Mk+w z&I~WLp?k>HRhnf_uNxv2o*x*zIidcuMg?-OXG5k<)bT% zgWp>^!_&MN>&03H9D89m~R7KUL_k zSp4;b-oK?1ovLVe+NG5QNUX}aEacBt2`GkV= z5}j%^0s3V>q0+f@Z#hjal0J-sirK?Jyn)Mo2l6R6{pBU-JwidwNIL}%A=n^r5UK9itS7N4!d ztrlwSPd`Z35^2_b+>0Py_wVfl)b5DZQkbDX?C)yBm%Nfu`GZ!`(9k05^JVv+zHw`ix=-5H zT5vhnNe0Q$*r3@^DM6* zSRvr-z+6Nk1=mJ$qKqon(jB{n#7p177OMbhMg7g{EWo_PY&JaXhyU>RCtJePxbQtB zBf1#k=t92;^*}3PUGQkihrLBzROGnNQbGU0pxkF z*{~(Xl!Y-OggFv*VR5tP53LS4a&K?z_EW8!E%KVpsZd)Iu;lj^m^5^KANYkiPKASIfcZ7U z_eqr&Xb+))HUC(kG9@$n0rV%)lr;PW zn&7lHw0*oTD|gD+g zb%mp;KvM$sh&!q7T{icy&29p>zv-Ubxe}d2)S0`pFBkjeQ+p3$0ZJr_ja6 z*p}3>Q`I|*#b@~Sum2Zc{pw#$YX6r0_~@8~!~L?aZ{z>BJir>7RJ{ZJ%~?9ib;35cH>6AnmR_z%`U!2-KjFPuq>5Ap5y zaewmO0yZr20PB6nQJG4og5+Z@$mKqW>{(JBrvR5!CGE&}t&D1+a+-WNRg|hy$MaC% zpE{1Sy`Fay14$n0%lLjj>vb&&3bRKnQajFr={8dle9z5zehjJRM1BHwL;!3}M1jP# z%cz?ILEFIy;ko98;(%J0tR;u8=xU!M@R$A!fn+|Fq6S;q&ul3IP!r!)onktSS&)_b zCz^uO&K&D!0#%zDXLlC=Xkt`)F)~U1Em~q?YX>=&aMEV#nN*nb~b#Q&I}rQouExrVHVG z(y_W$yTvgVLj&@%D)2i2!xcJH%Ut@EmQ)0^tl~Cgn18VT1fM?oZf_s%ub<#0?nbNk z7H2WWP9c-39YyS07=E2Y!2Y#T;+i~@1K!fPJ{sajevJ>QEj`dJJ$uN?oGV@W0B|Y( zIKQ90W(;)q0p|REp5LkBxIA)cl1vI+>VKx$PSgt5Vuc-SAXi@*%06mL4PXruqu^#; z(WzFpb%0g%EsAax-lhs^Q&#hS{~_Lg|1N;v0C-#W>n%;ElJUu#p5(JVM|WzG6Bltk z)gUNu0#FmU#k6FHpt7ReD%Q#cc347^#ICT!4mCO~vBhjXwC(@^6-h}%K~w_!2*l@j zSus2MKUaT;ABJP6WJs56?V@hqVHw=$S0cS;I)VkBR(FLt1%PKNTdGHdI?$UVRL4XJ{cxow9*VW-GlF4eR z7m5rheiogX=2295+7FU#D+}=L^QqlY%X$}u1%2zGvDCNfw-W2KbS!c}4%k|f$HkPU zB4{6juzl+jGwt=q03LN9p05}x&6S~cMT5$rqp5{yS_y4{rE@X7B(R}xur2? zHP%-R?_epuCC;$HSbWtSML}sE)Pb2_7nMNOl(yc|=6Rk?2`6K;h@9jQ3aF6Z>>#D= zzO(*WOi+`8Zwe`ZZ0HZxp9BD};j-Ypfe?D4`^ayHUP5| zvjGCanV1d#@~;5qS;Iel^xfDGiBn%-g)KHXgXCCRhIib90FGlupog%hE>4W=ZYFx} z0A&zeg>mP1Qb~C{bgT^ag>R1SksWF*u**0cWrtGEtP(9E@7A4xUIu-}$tvs`{C%46 zE{Bi+TduWvy!6TvoVTCs`Z>;UlGB@TJ-@M-?-CO#lZvF=^67ToL1WM~MgSm)t>RI6 zVi_Q7T(GrDtMEv+NZmR6LRSjgOM71xoUBy{u<^{fpsC_OXO8#^2iMoJ9EO13G2rSH&|jh{rNiv^6sVW#ecNMW8{ZOJyuuym+~xY4 zKk9T0S49!E_5EXK-PTI<@uQFMVEt)!d`wYL2hroYX-uPSg)P4|*m1TwBs7^I6XyWH z9!qp4%QJzFb&V5&q&96@EU|ZODZZ&2pHy>DfWJT+T;8p7e+og_SHN=h6cUz3MyUk6 zbC6a7;rTJI)J@w}v5i-V^n+c_SKqJvseM!xMuktdz%LaZ%45-)@A&&bIk(Y=ttv z7Kc?Ko%^0EC+b2{t=B`Zuwm=FU#+7d3gx{xVpN+<>eKgJ$sI;t1E0a`8sdg z@;$n4i>7%O)W?j;zB;GsI5%|#a@JWZcm?$h)l_SmJecdWHl`+dKJB7Zv`MipO)k6x zVutiPc!e!ixW9ga6?R9vq64`*`rNp1DgYiodWavae*&6b4q<=Xpu@rBhN#fS{i}u4 zM!*rWObU=oAlgz1Xip8X8KPs91>|;Cwi1BscR58<$c}sPE$2!KQvY1eLzaTh)yRvO z5Kj|O@3F)odL{_(79b9AEhyJz#t+N4r=vIL7Y#J&u*^ZyGeYbkAP)v8}w@sfj&jM}d&zJ_WB#O^p*rg3=DD(N0tmwyV za(QNQdYJUb#}CoN^y_r)f+Uu|50q3U?w%w}8fGSGP{Z1ntTh zHMhkuG|Z3WO33tFnU9xOmj%ly`1gN@z^(_~>3varvy$>4eR>XXd|Hzn%H@HHweLHJ8{0)s0xf>C#HkYixxsLfk29{~khu zC3zZSTT`X-9vzmTM;V<=nQ}@K2zvE)N#St{tyZ65yZ!K*?)K+R1jx(fDggJ3aQrfB z+n1UAx4->w{O)(Z$7;25$NLly=jZ3~@3UvmadGh#TwGjWxyx$FR|Nw;f|#+ z!72(X*UqcJ^a`7-(@Mftq1%OhgqCnQD|T=>OPO=K~PWr5pH*Jk-HYlm_@MGC+xGsylZg&3Ar@WKWcm5psqnHrz~*@Dh4yW2dF zoPtRt_v6zvA%XUQf2V@CDdn^Ly-Q+V=bk;4toUuedw?~5M+$N5g^q{Zw@;ChGKEqy zv}0&aQVqI3u?JlgKkL_0lX(uYEJz<6j3r65-=aOuDx3M6+ z#TKh*`7UX?H9n4(aGMaN4iKtNuF*Jf&rfYn(dgr{XA`F;r zLq!9blPm0E(83~oUSc0z(>0R-aE48>pA2(oun%#m6t2t3mJXoGw+?G!7eY5Q)N0E5 zK4uT>qwV%X?DxMw(^LTdJW7*|S&;#?BtL!n`Q&>LAS-xQ%Q-=^{eJJ>z3d*_?H2F9 z|Nblwf#=V^z6HnAw~HQ z8IJmn@%z%ad;9%d0dPNXudu+2c(mjRr=Cllr%qIyG*v2q7s&j3`I&i?=>`x^=o*p|^mb*TEkTDV>c&rp>JbvvG^Pt4r9Ku6GY>%5+@+ zN|ud21)Wzg*64zuBjOS*6it8gk^)^36U)FMnmk zUX?WY=?;~uimd{)%*UU!sqL)_zHfYbb$J__r1@NzKe-w-j` z5-nSMEU*bmwgVQ};LMCE-EEsV9)2tVyEFM6DxF`c%rTvAV?A&SZnxWQ1jff$k?Dq= z(wG$)5bO1J`+HnmloQi^@IgN~K0lXd5(pndsl|IPT}RU4biV0v4~{JP`ImE4ndJ?X zCn(RLx=(TvEWp@va&e&NE31{FtIF?e$I&tClHTeW|*ItO=7{R z0NeyFw7?cC98d>~tg5SrXw1!e3N15tZxp`s7z*uFIcfKdl3bqxTmokTBs)*3RXTB>7N2TXi$zPp}Uh6*{BzySj0k^%cZCxez zzn*E5gM6DjA!W|#_bKssW2}oc6v+(wehU?P<&*s##X>6AX^DejvJA%7E-YQ!w+Y&F zQxa>a7_2e2uW$zq4zucJ-Zr8`=_Vxh+GBwS>re6NqX&c6(bBz3GHBOmu}2$$-W(EO zzrqW=6JwKUOSAcu?F_FXw@B%D1;8Awss%Qj>o$H#zIA4ck*%l&VGy?)*_hgxkS!0( z$oUVmi|Sgmo*4?hHD0cDb2^Rpwmb&zh+S_f0PnIpC^+)K(vDiHAoRSw6c*wY4^+vj zC@RP8#%;wD3&4G!hWeUjhxM9xdzH*X_N#Wsbw|*cycD+U=ai49^|VW5c`iXWK-EkK zRRYN|yW?peq=nSi^%>2V*kXlESoM3{#j9D?F-sP-KU_Z!swxeGX~K>pBP$BH+IWSC z7`KSyGH3l-I_4h7Chh67Aj>%qlAk~S0^9Aj2$YAc$beXq0Rh>m1sMP?F3KR60QsBW zJl?JT^70D1-FB7*`nJ$@7@tb=Z>eobfoWH^<#2#zJ+kUFg;-kcx(!NcLT~b}0~jsd zX3uKkaYU=-5(_W|=Mr1oUq8VaHYa6AfA)|6HmP)Ji7bz?K)i$Sh&Fi9Sh^07eHJX) z9s~;6l3POndWDTslBSr(?oj?(IYxj?fGZNh-rbM)Cr}0u6{vvZ(E-E=!_PNC57&>O zVT`Zv3U`B76ctEKL@W#-vL*)I&FAy+sXY93CtVu_-`C5401G-x!)gWB&Ri=3fCa3n zyH2Su={YY*dcl1zNcN!H-q%i@5-^+^dDg;DMoZKp*(Y1;g$1Y_QEL&OMg#)+Nb4BW z{=lQ9yV#U@8l!3x`J_TP@22muk8hV+#)ppco{e#@;yK&5(qDTY1yW7OwaKJc&1jjY z+fF;I&;@NK0b7eISfg6UyjxUwg}Z1`;RW7_8v%j$A-IvAs-V~fYr1Ap=SM zRbZ%Kz;%%V+L8bXbG`4k{gv!@9mjNZbSEqQ?y9O)(N3>~YbE~{VINrrD>nr{@q5|M z&Ximtn{4SN?xF$9)d%Tuh#0Pya+@8as}vIvxitjMH`i;LMncuummQ>o7yf7@xU z{F`$-3+{YKCZIWzEVLJEw?Z%O8I-FC$~!33sUV3xWzTOSz!v4Zrpu~AJ_d3T`n{ZD zbYK!$W=FT6{1`CK=RaIOhR823gV)Ts!oU1`RW3xPuMLobZ{2@NAe(IfAKuh=>^gaA zAKfJI29$?O(B=|Sxnc=m6Fe_#Q1xrQuk3#25tv_1Y_F^6^?~P8sp`6J5&}C0fDdWn zg}UUpXFdAe3l?5jnhqQ-c|cx*lD-e6R;4S{f?&U=_v#0w=`~ZyLya!DTFYm(&m!uR zQo%fZV(Qvz!L@aHOwR%8>eLkO0n?TiR(YOHNP_7I=a4U|C;*<*}GSQ_5#)%}*v&Y|WhW03Go?gi@HC zp3nJO&RKGcWe(mv47Tgif<3NdA8oDc&sqcRyEL&)zE%MR)Ep}hzAIS3o$|^qc_TXt zZJ}K{ZZ>BG$D+>es(V4c340|5pjqPW9kuWI-7N>S0fz&4{NtK}TJ2|>Tvg`btecub z_$CgPNDnj zC)nZ)J1p=5??e}LD*CoDgn~7~Egw)70>W>z+5I0jyZ^zWc{l!|ZTljQouxF<)^7I& z7K?Y$G+)m8`MvM`1pwgr^Z&xnfBv6%^yr@eD9HZhFF%`YNq+wPIX?K{`1;~>9iQXI z{q*VQvw{1Yc-N;-Kgap``L(|5nC#oOSJ-Sm$KAW~t|cCkOLjS5OBI3n=Pt@XX>N*C zwd#W)TXUYNt*qRoGMioVJXVKz?<#P$CAM*|VVN@Ke>lbKB?57%b$l+dMA;bi<)Ju+ zZW_S;DG-zKUIkfG@&ny5{CgF7x8|a0z`gPqIj*!?r(&yHW%-^%B~6hWw|Y7r$=h2C zineCFWS@?(uP?q|dbj*43!PJ#-w%+>fV=-aa;@1M(47kO)(XPUxj?A^y$PufQj1jj zTWG?HDr>JmOzz$Ur$2kH)Kk@TRiV=GKK9Ql560fULYD#LIl8aui8WFvBcOwp*&W1H z`#bBOfv%aXO-W&}WJLymm$+kuYCA{Nx@4aTsHU`!`5&u6meO1zfS1Z#`H_%cK(ZT4 zxhjMWTBAT0@m(x17}J)2fBjP&P>1Agi#Wa{#-R<7wSMVeIYW!Vbaf))d-%0dQr}g{ z{|K$xQQ31x}Q*_1CzEML@U|WSFT)Wn5Bz2=xI2Zv- z=r`9h?`g+fT6oVHFC6Be*K>`ra)C^eDK3|U?ph;*rL1Trud`>QVAj8>eomE>+6Swo z)uPdvU_dP5yiyk2j z5F)%aJ*fQM!*YIc1U>}6#u|rUKX1`tk18tOg^Qiy{rBFFe-x9k9V@$}^!U+3e6;>J zet!#)-z+_T^bil$pTxavfdh6SE}uJe6?RK1fh~6WQ>6a~E7XPTE>Y9000000NkvXX Hu0mjfxJEp) literal 0 HcmV?d00001 diff --git a/nav2_smac_planner/media/B.png b/nav2_smac_planner/media/B.png new file mode 100644 index 0000000000000000000000000000000000000000..e9098ed5bf20f2aef6d5fa80986dbfba5774329c GIT binary patch literal 213018 zcmXtfWmH>D+jY?5v{2kzpt!qBad$6;;O_1eDDLjX-QC^Yg1fs0=ga-P>&u_4fGQ>VQyBn&kp=*ue%Y5Oa3H0H$@ywpT3 zHG1c!S!SgLE%(sB5#c0)7sOgi&P3Q+d;G~02X_WB+vg|+Xv_JxJ2yrb7Vk+-$lcb*d5q34MH&38LGvCh=_Ml)j`|IWeVs?hrS=LIDoCZ%g!uq zHLunuINtKBAH)XHST@z-krdM56g+!oG0}~p@XcvNKh}re(DgmrL5D8ys4JY* zzNSZtIb#0sc-jeOF?qs4_;42B4Sd}lRGN9W2*K)JG(kOn-drbFi7e}1JFc%J55-sT z(bW=&LeH1qb@O`BNOr(FRhP`(e9qCLOTIPkq4bN7FeJaDF_zq50q<`_7`rSdwrwWPv43H^6fm@ zypI)1R4Tc>rbLG>W}Q~`*&OO&KJc3ql`16P2wIaqc);WHU42VvAC`(y@5q-x1Nv8f zfSxoQTaY(7j2Ate;t0n3=dW@|r&b@0L(4l&^y(wu+_=a;UJkn`vt?>d=BXWMs<-b+ zyutSs0ptLGsUmOE(lKn>Go@S?Kgko*A$M#-l{)l)U!t~f$N7}nT8yHRculRIt!{61 zs!qK>2fUZ;UN4m?bdZ%gi1+taaWz2IR;0%FHYG{ezO9{}aYuAtwk2G)0>bHT81@sS zjA#_OjdytOV0D633N>pnYI>=srh(7PX`vmNcM&9AA5eg+36vm9NsK3)ZPIGy8OxBS}Z_IZQ) zNnK#|^-L>^pXQHMT^d&cX2WedwBe++gZ%EoEn4Jml#Y|UR`OGhXe2zn!`I?#r`r?K zwpXv)USD7P``0aQ&St-6z-dOG&nSL>PH@*{^#j;|q)E{*yy0UNnxc90jFk$@CH@2v zu<7)XHE`A0=@C$rt}z+o8VT7Uc9yD9y%kZ|ut67>4@AM1&ALmURB2RtW=-bk8Qgvh zLnmOnGwyQ;&6-<0a>0gmq4rhOyr8^cm+CH7REhZ$zHI427xi*A%6%!LQ&9UBq8ow4 zW+w5q$L;zEt#Qo`F)EQOn2JHc>Y8sH&16PD1j@oInP0lRy3N@oh-HZfneedF1TP7x z4MEm)hI=l{ceT=}Xt=D5@hW-3mTEeu4}ULUq5RrzZ4RL12WBuS5{^P*w@8Rj+-#$q z;$YO{Q$Ah`VEvTDg1Ph$txm{79;VpPkz+U}4_*-f%5z|niln&Ff*zhGmGFo6EWf%w z;8X>9{%oUA7p%>U}e<=StWv;a4>V=!YEP9CBZTC=MDuj~ZM#qkR17g@# z%UN`Y17nPYly4|MlM)RnGatH8f&uT>XBSLSYhS?D7zKRrFbJH}$ z(cN$u{a0|V4k(gopJHYYiPLt1e~iS~HBGgjOU*%3Y6*#g+fn9n{;0Vf!um8FgbH-S#2s0wJisEqNOJ|H$EHH2DPR~t2-Q^F6-m?0H?j@``Q*XyYyN0jY-ksHKS9P^2Wv>(eaN3 ztG6t;B}A@KU5Bhm|0)#OJCV;~jZsROc=?f7PN!bRGDtbDlN&XyvP?kX2x+8wBTz0r zob+*5!9jzk%_}(%TV-|nYt#YLR>COWR~e0{l^V|oWa}PS!i=)~`{QDq8>v1^xwC+# z;qx&_$!YER$-+nt`RCC+PL2pBR5o=VB_2Y{s$gB>Q%IWzl`ATAelR1W=ST}<(k&+4 zA_b-+W;}APao>RN)KBzz(dRSp8C@h<>go$CqjBb{I}Yk-UG>t2kw_jel@x63o+`uL zIhGBBR-nGgal`?mu^iTNgrf*4vaEi67xiS+!Vy}Vv#|@Um~zqjH-K+xWgmzP;H0YN zSwX!VIbfHbceB4IgjCvrF$C@ukpw^OLh1Fl95-YsbtS z{W@M!6EPP(7sRK2R7XPdCCOO2BYYK}%~tdXgZ1?n`=l^d4aO8FBYa}( z3nd3@PGQ+Fp&O69Qft|b(Jel&s_>dT%qfD-4l40B2B%r<_Lq(J({Cgc3LI5$E`YQn zp+?xxLBBw8{OSO5Z9hhss9JyiZ)GZ?GaNG+PQm;p9Iz`_##|n(L0Di*%*|hh02uV?g^_VxCl=Q+JKEy=tEtI8T~1Jvlj9xKc^DgF+UKzQ5N# zp>pF7{hGnz0^hIXIcagr=u4!Bks#>J!QQC}AZI?TuHCPX+ZyMbnWgm6!^-R8&3lir zU@2o19({57;o49>!*dCs_A~&Iv?YNaIl0xJZhwy&#w!~Ay0#6xje?^ATFTN?h87%8 z=ZYV1>K}Js`BuGiJS}gU=)*Jg14W8;no)@X_BvC5OAiTnO@C^Y1caDKVB$Q9NP{1U ziDwDRE7m=Zo?w#UMqpT%Qt%37dm^!v*ikpWSlnKq zfrZlGS4yi+b!oAqQq)dsM++t>i)49q0rLoV7_!+^~R^*}xEf8gwf1l5Tud zhbjC-29|Ko#Vb7O?%tn(3=#xcz+(+?*TO1ksw3LBCZfOwmOyZ`wd!0~oR?RkWYy?E zIN2C3k-~`f)XRjED)P|A^4r$jSw^L2$?;|jH$#}Gm5|bIN|0zx^{%l-3|^(75HYjVDt*y`q4 zbP==P(0@%L$F&~0ZR)i9M!&x)AE%Cl^~Yxx?7mRcE)@g&*fjVy{8hWWu`OqWll53I zbpu+g3jHPNTyj%ekEV69dzuZkP%5&#No@JEpp#YhbQfC^kWJRQl)Ve42!jt%Yof`* zmE8tZYnhCv=Vwl$T(W~uWWvX37e=eAZCw~lLOd7tHU>^`W86w#i1F|{Lq+YGVd-?r z-vp6~os!E@wEC%LtQ+iVzQAdpRX@mv8Vhs%!tJ`@6+qcBNg=^MHf-}0EqE_L51Soqf*2JbZeDOd1+2V19ZL?$}TR`wSTH=GA>uj zwPR2Z0_yBMWxA5f^n)8+rR!)EA)OH;(SY`~X(VIr*I02W!K>wg-)5y#M(6Xr@E#N93v&WZeu{Jhi7+GOT zg~*pmlr%!nJgXgz5Y;nIm`hha(-!~IA$I~44`IlRUqO?9(Hv%JWl8Y?pxDyhVxmtjjG;(t;HJ!$%7s+e6`u0@^cDdPpT!cIS>VAtXku@rGhg(noh zb+Qi)6VrM%K5_px=>)akb)j2ZJ$c)BVagx~mILXeNCCl!gT9o_aXxqJOOG5c4mTX1K02NWvYIsu7AN?Fe8XY4&bl5V8;O73 zt8hoW;EyL#{I@MCUBmgzQu`?7oSS5*yK5#G>l@Kv$~B)Eob4lGI#iD0IK`)mbT8fD zla2kf0t}ZTCQHnCP3c#2g(79va{7r$wiL>%GwYAWox5HPZ!vVruRjUcRjNfRdg2hC z`e=9*449ZJFVf1?pT`ik`JsT(U$~t%$T$=4FcV*3wsuh--=*1xr#-~H&ev+xLC@eO z2j2Pd>s7%b&^Sbs38jI zes zjBfh1^wb)xw5rqegkStbG+Gs}FZ2m&IShA;koTNEe?O;0Bq$fbgKp}jeb4kQv%2@G zO`T4Z?Tq)`V&5|+@GbY{KkP!|3ATa`oOf)nY2j9B5yg+@ zvW0%;t#Gem^q|gA(%)1)^;+H|s`BI6X7_oSGyaCq;8Ktrxr|K@TiiVM6TJ#vfg3Yl zKI{;kayj7eAWd^wK})&s$AEf%C&kFS_0&GU^0;!TfPtPeB2l@=qG1rf15>VOpbVr3 zYVSd6lY+W&WI=$!2&^5z_uYXxQ*8PD#+H{4RnwwmIEY)YyN(z9Jd~2ISG@D*@NjZ8 zi)JBaVWC#4CNY*K$NAUn7T6@gAauRk%{R&4`UO7P+tX6Lj^k*Py4#U8&RrI7qR_Pp z8?SMa#&S7fniou zQxu?eApjs7irDbp-e%GxUy=m(>A>I&MG*07ea(}Q44L7%@n}h67+w54%jtE+04rH; ziQ7(6t42122~9yPGsQhxjf!_}*f&8In6UpbsCt?}cKj92vC^|V6Ko`F?(mezN^i!J z&Z%j@8!naIhO_k}UB6}s$=1v8lMRb*OGDY!U~-C-T)|Nc$8nuBU*#r_`f)}rlXN(r zCb!9EzT#jic@`#Z_hO>)iOA0xI%SKO@WfA+5<7-?KD{3UvV@{he72tJ%0bZbkSPa^vr;PQR=b$La=8*oHshVjKL0HOq%e zGnNz?t0=DH#gPFT_;(0I`5SmLL5ZPofOt3_3edU(S_`x^=pPJ~nl1J^*YI^S-IMwS znn=1y+Wv(mwhCuBpH2&~atz_FlI~%hu`{#wS*9E_vzZUy?w?Ddgx!5=0Gn1~Jy)8% zfy>V%4mT?D;}$#l$eB-}nFhs7Sw=tqt%-DlCX|;Z_Y&> z@^MY!tD&X-lMj`X?!bz?H^`o9|MBO}n3_aSE#&zi8nJF<%RajR&&7q-B)364&m%Gj%O?<=fatt~Hta1y@qM&53 ziJ*G%229w)@e-<+9<-7_kKaj1nrVe}aa`P&FsER=2=o=5fNMO97X*#QtTIKIa%sgt zgBg9hT=~@*eG$Ey%UF8@#soB%(-B;sra@pw{B$-2|3h7%J9p%i3T0;bEJdYW>y@Bs z3*nR$jy%{fw5Gytx2ah(SNuyqu8R$tj$z`(|3PBq%F5b2+ydqpqhvGb=f$76BBqez(X4iX3GSgPB`|+-2iWw*d(4sreg>Y(C~4JyD(9uGBx@7 zG55Wd6+Fiay-N(EXE$WWQF|u(sg0D$eTxmbmxF?IcP(7>sTH7P`4--)L!sLcw%!^qUWtpc_H8gJ(||I|hUL*=+rC5hgg&!KAgCag_(JRf#{> zk~%8|vPVSmrqkO+m!Kk7TYksB4zWjdv6f*y#<(dmP9|D=6l9!hwl)m-cXVdDl?}E} zdmWz4l>NOEF-rd2l_!q7(ml7!*z`vMg`!Ifc2Q3s!kkJ!E9jM3;M=XhK?mx4?JKP#ftkYM*8z0FqI zYhSX}^&SQfX58UQhjvu8<`336Xn*~?g6HlwsR-9}zp3-N-HZj1W|)w9@vreEJ8aTm zg5^fly>BjpyI4akJd*TbZ@BJ7Eh@_Yt3*af8t)=9T1zG8jtRa8nIkrOL8AXx#qRR|_Z*BhJXk z>LxRR4Nk=}hIzh5JwX`UJg+6$D6{jUIyV$8h#LL=Dk8KW#qDUNp7$QWW942uD%Na< zC>hB8&-t?kMWIGkoXLXrPGJB!GW27IT@9J7it?MNZyl1h*=2n>65dd~jH>=MC2m-D zkt+_C%=_YohC3V^vVczVvfPTog8Xud(#tOzkif#XMfx()Lr`kpSy++=9yT(9%9*sL zDIDD{ij0YPOazI$34A~({9;A<2by8E;aG;)xf8-!?ZA1K#KUqQU*LoHdJJ2J`y-*6 z+<;qemJt-`ri*3PwC&;Nqx=(3O_8}-!q0uC&{nqI9}lab_#v6WmAlnV6GYi$#@nSK z$LH!(2j3iSUaztqxJ5CtSGz*=)Lw>W zeZkoz1od=a>;Q4NoC;u@GfC%)J9UEQ?%V`pJO&0-Yt!s}|4*!kBhpmPZE3(XlhX4B zsdzbqhekP86BZg&q24M^wG;1utAH)6k4P*qRccWRtFoX{uyhe4tbe>6p|lu9tP}4) zNgV*`#A6!YweKh=b1&x-3Cpe;hub}{XHIDkefs z5*z*3waXK%AfL!!?T6SShd+)o0e-6`}+q zw^g_gd%RrOyc#*sNM0jzb!@umQWH{s82;cM(w+?MP0PZ0g>baH|62knNfbcsZ!(mM zDGyn^BvIjA5609Dnfbr*UzmiU=!aW#R`_vnJq`4N%QM;P!$?YR$;=hqIEq**|2*aY zK*+npDy)-&kh5330(Th^CQr3|5xvOf1#_u|&Gd$(M156PUi)2-lZfI+CPR_GU)-lv zwPR+u7lnLk5!w~bv3KE1n`J2LdrQ!uryS~|)M6V648_X(rxgv}4O|L*`Rj%w zX^R`-dLw}NhhKkO=ETVSYbD>jB~FKps6!xQIv%P9`OIk8a$P+4=bFAUYsee#Qs&594?;@!&;=THqNQnm>#*xT?%Z3uyogB z=!Nxhsd%c9?1k9*QfVnzsqZv6O~JBo-qbhj7sDwwCMuT)EYh1e3|AV3o|eacYagoC zjGtajN}n*~x*DbL{T`T7Kr53`AqjVNTZR#ROu zT8T7C?(5+uOKooZA2KzAV5}ZQ%O=Za2f+F*`~r_Yh=o8ba&;5{7Yoa zLz=}8`mKM2OsUh+?W>3uo-G5Ot|pl@VUdzt6rO>Z2H>_=VM^<`R*s!@|Z zAAhS*tHRgkj(pgN(N}sJUDitNt+L@~PMi0gYmlk@r>7f$w$hkrphzcz>|?974sDoM z>(|*UY3#J2UV*Yx`F8OPnS-jzA^z{MGMR@_X43h66@dJ~28#HaD_8RuA{y1=tL1}3 zDNkB=aN9^pFMIeI5^w#my+1+I4^lh}VJW)rKDinjuJ7-@g8T0?$*wXSc zJ2_!NSPZSX+C@l#uzQY&*x~^Qsf^}QEfpE-n#wo}NbKbSmYkFGQetgb3yRkx z0hhbTC+>UjICWL2JB?R6C)^NES8jj*c#8U{H%A8xT&9OI2r}W)r#-ucy&aBDT>XWXSQA{ z1`Kdc8hpx4u4*2_VS+{mL*GzALiGjf4@ytGgY z+I=eKWm>sT&FXHE>_PT?DT8}nO;b-IL~p{7GE5=sBx?}El)**?%J-}Sd#;v{;z3yduc_gKM%i#Jd=QkZ-KifB_MA|z>wHaFN8PP! z)H20tD;eiZ+T~#!u5R?3PuNj=6~A+HmP?kI5JL=nK<_!xQVt>D-TZ&0dgcR$OcO-C zGT2|MASj|RiaEz~(R^_hg|P6zKVPK1Oj{Z5Orun~XTN#>w=|cTcm9ee8H!&TOXDJC zlqHzf6{8r`Uv+`uqfnHE2$49dHCM?#!dBgMvJL4g?EB0(fDy%{RNkW3{A~6p6@VswT%6wiz-%tx%h2dY%BYgaf%%LN1-YN2|48)GIzsCx+|PWy2~g&J5mQ z!YbKkhjQAj=ZS37Pb+^c3S(Hh+IG-jmj+O)8_@+*@YVTdlerGh-(w#UA`Rm#;XRr7 z$8^v%J{G0KHj^wLt~7tsIRO2RGtmS+FgM{Yh8yFq=z>}^X71HhRG3gD5K4i+=c7%4 zt8Bvorq`_D8{99A8{hXW7U7%|1=|kN!D#awoC#h8tGSQ zWWOEJ2A-{H4z1|hmf=?8Sdk2vIYSFaB6aZRsbcc_ZzsZ~MnVOiFD$#NX1_v6I6Q&n z*RaLZf)s5L6vP`aaUxze;Vwk}uxx*$f4jipR>RJLa96SUYZ^OU6^=;DP;eqU7C*9i zzy3n3R5Gvy!EWs@;Jj}@Zi{JBS5>c2dhK~CMJ|f??8VY_VV0y&ps>woflP44(pLl~ zR3>9#>fnH-DKc!*c@xHhrW(S2t69yq{%#(pFw8_M6TEv{=tAu1t0Ilrod^Tfez$fP zIt%co|FA{(kIO4JxaRw+^4jsP(E!nSKT z^rCr_PK{M{m*8dkvSI9v0cP35tl9||w1^t#@^Fe%>`7!A56;%8g@Z6Ag8`UFfbAn0$jOrZ{ES(L7` zE76mt`xa|+B$%LsE1?R!4VjD^Gg)Um3ZlU zMRG~)-`DGQq&PEHM)G7Edga#3r;?VXLrv7D&mTKp!bcJ;MHG$H)CjJKwL2>AJ%fnU zLI0d0fc`7qjqxi?6l-up`mLX&#L=I@9-jbzwv%qiWGsHuBEA=@c6q<01To7 zG8?^JhQlEk5F(%Ulq)|c#2An{#ye1iYZ0CAe#`aNzl=51tQQj%_$2<+uv91%Ug2-T zOx{huwtB$p-?hP#hK-{65YOyT1HvUt->$myZn?B5Ti~JxTZ?=#ojd- z7O%lhTvg?jIGk-hY9_ZrO57LlWa_88%avZ_#pvvDq#2#NU{4%cx&ePzTxQ`=N8F;U zcOa5e%n;T73Tkn`#m52gSk(;1Pn-r?a^%!VtL)k$J`Jq1NNnp~a=Q+{_If8ZZ>AK& zYmkvj6Nuw*XVVFp$AYzk3lkNwVCZ5-12(spp+e=9DNBByLqCAyDRq&iAgXp!CW3UC7HZr{HBR=HSPxW6Q_?c&7|7NC*@c!l1I`Aux&{KQIc1I0 zR-UeDm4`k%$>JCjow?Oo6P8&q$7AtGE^{R@HPrHJHxrjt7fe-l^L?70M^A$o8_v+6 zL^e8{_J7ETh{B#`P>fDLnJ(l|2agg#*?PSq1A*qb1Rg#Zzn8YO#@kU2_~{n^>WMJmNssdqi8qYE)L5xl|@?D`r{aJ1_TH}h(- zbSdRyOsCR6@o?xM7@4L8pDNw6RR~`#3@%tJOE(g9VrGyVkAed z4c5#Nls*Sec|?qYR6yIUb&hqWzZTPe%0*kkclkF4uQ=#j5L~@IY0&_Mjn~^bE;7(= z?|IN4vE+~#0#dq6kq9xuq%x(^4Jdxyu7DGd*|3m_@p$|ep&`~o%Tk2YaDDKF zt4H*e`~#y%UJRqgLv7GtWvqS1i89*wl;5YnO7~wXuYa%%y*HWhG1dP1ZUysz{#cVo z$@u$M86(U8LAJnu@zus?R2*_#db-6Zb|eLklI_WgL76&K^uJ}~qC=p1r}5r^i-;w+ z&gw-uXgcL4OV$i#X|zqY=9!ZmNt674Cv9y5BXxLPt1CA1MCakgM6f9v4dq{@_f>tH zZ-X^c=Lx9(r4T@8BoJu6x`qz=Mf;=~+ZT{+Vo}a+QFiTAHh=+PHtyFc4Fu0&t0jfj zBOTgeO`SeWT})kY(rg%;zPA638SJq++E^ug>{9exZO;?7fm8b<=Gycy&FTr z%wvW$@I}2FP3LHqpJeml~1*W!# zsit_+?cgM{ceb_9Ab#6OXxP;o`eWe>IG<;^{>~{G+x2MNF^h23f)vlE%e?Z~O-qv^ z_CLqg-}r=6J-#od@A`smcs)Na5~hH4$pwF;Q;ln+=NaBu>5p#7)%4qNk9XGKhCVMW z*%b3?6#9`XjZy#!KG0;?ZIuKT)hIf98Khr5Bdqg#wQ~oN+L{bIOtzTTo9J#w$k9Zv zX_L-#G}XoOYD9ASPyGx|*|9L!86$Ek&aE5ENL6)M6HQVt?3IbN*N~^k)!>U~ZLH=R z^mp)cb#UX!sltC!Rx$&)9G6xefFzc=o;o$s_I;>jv5HTUM$sSy+Y%>F9d9?}4rQ|2s0HX~)5RX;+69AM4f`KP z5{uCm7ulcW0hpi6jKA8fn<)Fd6onZBc6Jk>=}*1`RPVa@CiGNW0pZJH}U(<8oMDQ zo+U}9B0?(Ml$St|^48W*ENY%KV5j(W$coCen&Bt8tI3unCj4j6Y*{mC)cA1Mk>a2b zF=355ICd(t496hc*vYUO=}5p*_H84l8{1N~xMpAlMig3}2ILiO6o){`U>AtNu8zrK zk1>qNqy~BcH8qhf@>@qQg1K8szGTEJwMOPs*^2tKdIV2#RzVCJPC%NqA;cU*H`xE1`#E3Csnld=01j@)hw^n*=tC?Wb+;DYZ(ftU#m?$@9176~Z zw9Z&Hb8_d}Spb zg670V{<|7M#hGZTa`tXwL@Iq4#i2HGP&my#nrEo}?s(rHm<5f>V9#2@2;yI??~=(_ zKwTuRjx$!tsRT4TMI2CUj6?H5QY3wK6Jt$Caplwe^rGPqvtnD(vRl`x^!{t(pG(XA zwNfmUlgD$Id;_670qP!eT)QKDo`%pq`%^O2P@*jsa_zaryL+b#Y~24IrO(kNjC+kA z!B0b2Bo^ES%enzQeq2;;sBc(l??YSCepx>IKUeWjgWuQ8EZ&S{YRW)%@8P$zjPL>m zx`7et5si;WUcY1KrZAsT4Sj*=Pa(SwTx=d^&HW~4a!;E+&DN&cp~@nSZ0fGvM7SR= zR6apVh>~A|gY4x+Jx4$e?QBS#!Z3a#_5k%At|aKz9)_G_e;JsFMbN+gje+`c7~Vs> zBL02i|4_~H0mVb{)nEr6rDhCst7~~$>q=sjQfc)NTxB#g-z5^clJp_Gnj4dn$I=Lr zCrP-geh@(-=VWtjFEJ-ogwo)k(4-W|k$CZyVI+q4Qc=ckaiQ@jV0W#8D*B?;^{hTc zjfQW%J&jLeT<(mtoNDf+tVfhX<8bq&dhM|@HcA@bkN~KqdsX;9{Iw@r>#BZ0zxWpn zc;*qxXE~8Dxz8SdlXveJ>LcBPHE^gEfC^0xs-p%lPqV zJ#LY6<|2JI*#TVQ$|akYPSr2f^;CQywdB#Js^URwAEM|+9D9RmyD$1Pu-0Z@%}Fw(#sY|s-*&D zf-f=pniZi2AUpH%Y@z{lC8Z`)v{tvLrdNNS@2hNcsX%9K>_nJQ##1 zs-fT=@FVkKGs_9^pxJU}+61<$u!Og9@EGoi^$S&^IgGg#V}sJS`UO8eY8@6drXIYb z!9aON;iv(CAA4FpFg1lrqEio&5&1oraSC5R#8BPA>dd8{^330Wjx1~!GERZM+)9oI z*092s%0yl1PQ0u9s}@xhKpBdR0v^n>+u+tGJb59@ghDOhU)kB?bvXm=@eWzt3r~fX z+-#P0ZU3jQofS3}R0XC<@T&aCTuo*10`WU?sZ05Ie*nO$TH)10T%F#VjY-RaNM59JbDr8oZlreXwjY{rOPbWKm*w`Jf!%xz4h)bO=Q=GE7 zL_3bm!xs7G4JKgQ~>O%Gx7I5GT z3uO4zCe2xS89dCh(s!7<t&7G$ z9*vs*Q;gbam0JTkR#b$^o(7kjJU8yqWe*}hbG80*)Cx)<9R2O8v42A2Y069=5_bto z>^8yX1A|g|6+S%fOHA+2A7Cs9)krW7?$6RK>D_p`fCn!KNf*SX9mC%wMi^mA)!mq(ZcCcUwOD>MJ4SQ5tTVo{QukKYk^D4t$Fxg>LU zzCyAmt_+9}V)2K8XMx_Wh^Ibr{rcBjtaK!tiaAFN!}ey6sQ>)-NAbnCzg#c3YK$exPFKL}x$bG<-Qji6RuU&5Hndr5#q8 z2r6aWPxK!KUChs6JoG!PE?*#c9l$=2z$8WK4;`jfH7|saBW)8~9TM@vE~~s`I%juu zV{>Y@-FNs~#Ug`!scSM9Dh63HKn5T zWq-T=MW~WkshPk2;4}Bj#9yc7ZWNps(4|> zGhOInx0xCTR6&ly%5;vV%Ox)>C?nQgQ%Igx_68fE*FXH;-0u_7P#Ga9Z*-z5JuVj@ zJc3)730`tbtJvJz)gPvQ;V_duduVaHiHHI>#W=-DkP&XPLGEhfZXMlAY%QaoX!Ly* zO7lQ2W@r6eYQwz9LP;CH)e;M3Tn3L;!qX_0eC&>NP`IMGRD=CF1`>$K+UC2@dCc&J z;MyJ=ST=4#9USwAo}Qu989=$i)k(%ZxNriAcrIxf4jm*JNXG?pQ>Ft?gr-?P$$}h< z>PA-qk{M%ex0ONZ&vC3=`n_4J_FW!F4&$%mpc%K<|B3Yf2~&KPA{qwEv=KFbY0tdN zF+TsuL-59V%e7R@2T_x97T7!e8X)IuxnEgAf`EEdYnL)VQQ0Nnj z1|EUQw5rV~COO|^7wX!}u+;E}V!kS+yw*gw%7o83CA(S|@toyR!v{`F6j)ywcW;`1 z;uj6B6T;*a4xJqxRT2J<4*KJN*oIO(n8G4rlFz~QYu01&6P6H`aKpN3g&SLHbJrd(v+%FlL)S#- z-L-lX(Ul;j6Mx2Sdr8>GXU&vS(gASV%^HVdxQMe^G*ZO42g2{2r-L9367ESC&0Mi4 zOWpR<9U^*2#Id>$pSOHM-ei>4?qR<@DN6agZKvasg}sutoieLyz#I&Tyu^>O4#n?4 zGG`10AB(mL)~q|`;}n}d<#>1B*9t9AWzbK?Fd%+aEACIzQtP`H&+QMpiq8gFLy#fH zLV%dvxh|`fcsghhWZRdpc|FZcntwExMAa>hDn&Qkm~3VsS;cH&%b+U{45f!0b6s!a33 zzKs&*CjKNFQAm{7(6&3abI1-^)wySEJwqqrVYj7nrDkot;nB@tC)jOax?$}gF}^0A z0Q+5an~%fUhFYnO9FtzViMl!JW+hR^1C|e&+9o}%mMrszoe7$%HAWJS4KRsRplMeTi^PB|Srpw;GsNPK$EnFHZoZH6qDkK@mpV4u-+OwX zTgAQgtYnQou_Hg--D!f#@j4^`hL65vFROPhNA3w+S#qZHZhU&u!*NVHQ`*K)uC$>| zZtuLgESDLtENNjB5THaSE40)^<27&UY5zPGoO|lDJGUXr3Z13mv{~&_u52UD=QY9& z^Cz99$k6k}7kCFIYa#Gh`Cn#EYE%zEd-)IL81cJmLP#7^zED3Iw**WM-j^u;nE%GzChvtkV*W{6>(`Z^jxoqT@py?rxYl& z(oWXy;x#XxIvMZU@sK^LD(jev9!Y(TCjEyXl0c%#cp4wmX7e{N5owP0W~(jj0H9X{ zyd`?QW>PngHPC{bwTOFq3Nh4>H=vlX%%+pJk5}~X)2l1eG(IR8T0GQoWuVU^N97O6 z$Jw|YmDu#=H@A&rA&Giy3PYQ{6pWBcgxm;j%IRbIbrvyu<5%q4(UDFZ zZVLdnG|AsAZZUL#v?_!e4T3-$A|;qFBR0uE<37{z|L+9|hj3=hkQlYNKhYv!OIHdv zn(c?wz*{W8^xotIoiV!&QJ;f_&L*6Dt$QS-=L!6NT5Al&qsQ+LA#^S?!&e{^x5l*? z^gDo*3+7d`wFk~({s{12jK53Qo977+k~172;2She&sO@EwZQpb{7dkP45Dq*D;gmm zG7S70Rx>ySt#`nswKIh;4382>dIX4h7j|}u4TTbg9h6$`qngAWi0CG(~efScDt$ZpX>{`pcD!l z_{M$t^qB?Ia9qEw&I^tom>AsLTxm3JTBekK*$0c?GMf;v^t@It++P06FFQCdU{^N|RWJlpJ}iU@#+`PT!HpIsmWORZgnb8b zw`g)9ls+!&)qDRdQU&)0uOY0XpNhRhEo)Dr~<8X=FDaI`#Z3; z&MCjhU8F1a&aLQBo&u*`shQlyy6VwTbZ28OzfG?Fu}L1_!a9hu}Y2BvSw0{PKEe`UU{`W^q-hjE%y1GXH{@`{uF;7aT+;)+kfq4p~UKQ z@=r_)vpY&d@*4<6+%pxhs6=t;H_GfXo@;L)n9c_Op;{Zxtvo?qKmacNf}?+qL?q5s zNp$5ol;4|Y`L|Q1(rC-}zVFK^EbAlIp8ez%qZ^Wo_(uLY2k}H_$uu0=bw}>Vk=CL^ z=Qd`0({>xPyj}td%Z+Xr_4cwB1(5+@nn~1s%CoA^b-=9{BlE5Xm=}~LB$tT zKM?+I{)w%BCOsv3wVwzhYRW#uBbI)7>Opi?@Vv7R9h5u-Y3IwU$>DU2$F)Cp4#Ony zgn&N9sV3b-@{%LY5-Q|wYP?PSfmHxj)!S>~hDQvYha3CQ?BmgoqMoJ|a%G+_09*9} zttSztUK~MWxI) zW4||kX0Q$n2)G#lAM7}>4Ug?%+gsF(w**H9c0B6LcQ~&!xc+)tkwlh&5dBv z?{^9AzybBJSkC$nSnb(P`{(Z&>~|u*!`hq^Cb4XCJZ%GH8Wk7tuf3%Dox;huw}ZQM zf#Aq{#CX+W*O1ZDW$BW0zwN(8EOQoyDdzOlN($6m%@8PsFz^cIn;IW>fp=qb{7)12 zb{@1)*heM|qo44{NfpKiZKVW$i`C^H6maI(V#JR9sX`&UBijHfZ0*Le)#-|`N{8tE zgKBvi7f-dj67DWgFMyOL2I=$vk{ zgWwgg@Ud!DKe`?Xx?pd-FwZOqRk5y!JSH15)@w4hkp81v*|PVz%q8mQuuc?MQS;5R z|8s7LCa}SpTzC@aDEY)UKE6`k7OvXfcxTq|9*ddsGs+gb>zi$=z3=WcI$E#wpiueQ z3+O%a)7p9;B8{c4d!und2!}_wHQd*Y?t%YYDMN%vWrKuCmW2ajauMD7y8dk9K~^=f zhU}FCtr65T@0U6>7D=+@H`QEPvP*iH z5#&ObnGZ$-UYxTYcN3)i))WTj7{1kTy{lx*=wEuKu?#a9?B8jnf0YAbl*EObU%jLt zF?KPyIt9C9gKO?7yZ*KvxF{UMccT;Oq+xSAm(EgUSq0r=Z~+66zfw8YyiLhuiBlYOa;(i)Fw z;r3T11ezK(zq=nA=#c4r0zR}N3KM^&M>iv6Y%@0>?tr+A$tYI3w>T;6bsa4d`m%+n z*^tVLsDleu$RG%Oj$Wg>_S+8ofdN5^pNdm23>9CTZE~suM+LCgxN9L^q~1sFy`Asn zti!a`&U?LU}8vdm<5<9c&Xi1o~@b`08_ zA^41`Zh^@U{EEsn(67a!cv2Rp;Dz0s*z`p zlHgii!R0jgxH>NDZbE_^O4K1zig2rb>3%ixJ;q*_;7CGhU1Bh|##-%kjFUBKBVO#s z6H{u9;v%x*1R>09I)Mb~2rFG$Y+&VOMsa>}Vda#^GiKRI4^$Xr*r88DVAbFAwKsIQ z?*_=LNF`k;-MV9}UEQ}Jdq4^(rAeqqlqtjhE_Q3MU>W+XlQOA@*! zA-4rVVn`r!mMReHf`QBWujI7|?DEFAR0fD!TuUzB)-kTF2}fTe?@&Wbnc0~v&iY$D z*!d1bncMrnRo7pkMO$b&QMmo}nYS7O{kwVj4{X&Ozo}zJLrT?Du7ZaOkEd_Ss&#&*#&)YFa)sgWN2?8=_-e^`fS%d6~0uaQcRd)Ob%;WTz;*V${t=2q6oQ+R zR>R$&NSZe-&Px4EwU*~-%-W*L}iU7xq_>N92 zf)r`LNb0oYyk4IU9VOwOl5Kyn5Pg>xLr;g2#EZJktP`8SvC2U=;+tQ1hXLPDlC+d6 zB9eZDYFkbuf~hOJH9X!_Y3!kaYr}tiffNno!pSEVi)qwEligJ$nWWuo%z`~QCLIMU zeUqPtkm5=S)rZtjggo8H_Cctc7IJBwd=`&vKv}e9@!Hm2#&@zUGfW930p^L_*Yh{` zpc*Gvg*oj8CI8mep6>CB-*w!=u|hn7y1gY`ED8jWW^0`(;8gw5zGMOtqlgIriB?hb zy)p@3WZp#UdM>+L%G!1FM$t$YznwH>*)`8kPW32}z4B0_*G+>WQv1_xJ1S=L_&vUT zu4EY+Q3O-;kJZ+oH)uO{7e@U#_s&r7xf6y}by%20<{Z=c`3NPPIegBiLXpXi``#68 zatId(W|-lv^Q>7)Wmb;t9yHa0t$d8YVO2e)YR)O+FMz*Yx$cL4t{QH(+3tt}EIo ztaSImX^jn_xYN>*FZY6{8i0^hgh%VY6QU7^B&&|UvT^#w)A8*$b?cAo*;ey^#6<_? zh|KnPcraOi)pZB8#+y?F~Ms zaIc?>1eO4Y80n+aYPhH<#7(|t2l2g;Qfzazr8$yM$3p8@tSa^&q4u4~~yiD$}_W<|(HoAtIaYE7R07B3Dj)YDVewz)Ic-SD{ zP@E=G0;Php5O>gP)mpmgSaQB)R}N0xFa*Cp3D8?HUt*@0g7nFmu2`e3-lQMY-+)6> zd+doAu)w{lRbNH2T>j^Mbm_@V{9jCQY%pOi1|ZF5C{s;TB-s&No&TPJyu<02U1lcd zU;F(ZGSNLLAxTCx{sAIYU@BU$ce2 zMP)Lq-3B^*uF2b~%{CVH(rdSov`pd&locV^%(Js6kNfAguj5t!nSuotlucYQlijg{ zd8FzoAL#;@K*$Pij!fo`JYL+xoVw;mQ%`f^5tWsl^Ai`9V;W<60}cIlm)}5cbRT^l zO?NCPOY#}&Mj|EWP=aFohF z*w70Dt`YNLxh$ZlV@8pu(@0`s6vWkXwvtT@b8)i1fx-M{Utkt)fZ}d066cG1gpf<*1ii6L8 zV8rwP*nz&c0I>@VF@c?jmpszfA^VO3OO0^*e`{%2s@gm&{#-Y;^3PlPHe+8_*XXJ0 zbX!Pu_$mgl?T=wv6oM9550BSr?91?V*&A(P=<}9`Yqi1WpxS`6mck>iQ)t&{9{9=G zxP<;u8^rj#Yx&XrjC&<~uet2Sv1|B{$Ek5>>HDZ&$2b9xYG~KT{IxGZXYrivU%eIm z9eYH62UB3YS-$4AEE{(Q1Aa^OoNOI6J5&a3&6hvc-&&8> z9tdP}5iw@V%J4pa#(_vRl=w?-c#!s|7jy4jxSjd_er_yIzX-~F00p1QTT0hi(l_oW zSG$ft2}cc~34y;Ga+?z6)TRTb%09|BbXY_r*F0gafnS<9vk-(_$&|UU+~jYAWH0 zlnovgXyFV+xwOhfYf9FXXDQb#egs$KA*G&1$G^vzKOlI{>|#WX z_{Td}lJ!THi(mqqN{jUP;XI#}%{`E{%~Qr~uqJ;)c{!3-BNDKa{`VQ)^c_Scz;Utp zEspHlW-6^hg301Y#&EsIM3tT~%7-K5h0L@47svb$Ttb}sb3JK6h@8c=eWDffcZMW% z?CcI0WOt?XWqr*K@ENWHBs?cV>U{S8pK|~Ty#Z;W+za`|l1hV@UZ!d&_un1A8&Pku zexn+e1bI+?^o$N8GZg6|ex4Il`g#+1 zomvTNLEUL!>*EHeTxOFB9{7cW)xv5p%4*L$h&cvF7D4z`tZJ;R4HpFJBxy`@CEY75 zDNx0^y$`=DeG15Pn`=1hr1iW zI%8$Og5g5Q-M>z?rIN=i!`m%T-EY8hG=EBS9k>k9k4yHEr;_24TdGa;w?;08K8_Xi zdw;rED@;Bi#A)@RA30f%0<-h_%p|bXte|UUs{~;HkXbS*r2>S-)Y}IHP$Rk?Be@ zd+Wfo^2HHIm?V9-^PG2n2!9=1DGIe4Lwu#Xy}y$~)#;jj8@VLhD0}lQyDpErWVXti zsO#Jb<`Q*yRQH&<=UXM_DEZp9WS>By8v?`J4Y}D7;QQOpg*?$%MUbPa!1x}1SX=-4{lE>~*Clf-hb@4tkJ3~_xeRS)L*Ag(jg z7S2kQSF}+6Nr=lG@^Z%kH{3NvFO5HTE$)umC^e|gF3bOHrT5O`fL?Op-AU#XcVaygAn(L0Aq$s$+JS}UUD zHV{lm=$t;}wR`0N)RQ_9J4(6Oln@s)9nT*5#Jxf|?DwcMv*BxD;v3hL1w=SI9*8*= zl$;82>x(7%K0T-vgmz;1Zp97ep*+hRLy`pt7vo1uXx4pCZ5lB!_~aMMPN$w)+e)X9 zZdm;FA#E$7Z1{n2%rqiO4%)Qmy!Nv_T0%}xrS$Jgkvpg`{pFQ3`gTo}8=v{r4z0zy z((Fr*Lx5En{5oIakBZz&%m<6#I}?}RN3#NrP`~x*kz3hFP<@05P>*t2*pVP8=+315 zMkpZ&<)~Un_<=^+rzJ9Dwe{zDasB49CToD#=j>4@1Tv;;nj?{cZ1z+0)89IW-0E@S z32Mw{QoLs?d^+Wu5tb2_y-{7K=`HCGT@sKF73wAZRRm^7cro{!Q#oo|Ve zFS=jZ4X@fH1GlklP7*+$s*tnOvFE)CY)ta&hyQ8{t1V3cL|E(|t;Ig6Q`Li#ybTfRir zlK~r@KU{(=)m*RnqfYwc3tc0|Tg4>tfH8=+Y}&i87`h2e^Ak!ykvtE`OS>fc7XTKQ zP^5bD-s>x?;z3QU_)jFNDGAf(OgK_{ewlgxPA$F>I{j&1N=0b&b`0_hMXAJuWVD|S zgk!6yGmOusm7Ie4*q286fmyMw@MP&xPh$aTyeUdEL*qw*oabdxRr+?K1BrTE(~b>egc(tfV7-`C>ugsC%nx2Y}(zLBMvsm5@Vch^_I3OD`zqIB1*L*pt3 zxBb9UbiG4gBO>GepACG8aKSfoAATPKdh`pDTzk|f=9LF)CW1wn@C9RS?MIt0^(h!r zIQ9E8a_5AVxt|FF@i~_y{-o~`jD-nZi*uShFFZvlZ;O>}=F)7cPVc-U;I)!co;ih>^a*-8;ak*N| z$FmqVx;8zdVacj<1i@~b@a=IR#bwCRCKs-at-kxJ2a~1$B#EqsMS+_`q%ZVJj#)5E zDAofD9^uGHz|(!n&!mN$i;$PqSte{>g@U>+dy}5fn8pRQP-=l5&SWemApe~#p+-yy zVYm5_)xsw*x*ukHhAv#uRa9IufhXl(MsJK|?V#BT08=?~ah0Fm(L(jyeAq#Y?$Ago zKagxWv6@khG$FaLpOl|cc+n>TP6_WPKBYk_HqdZgP_=c87MFpF`Cov56YXnsmzJJ} z!4+*ZiEe9mNA1$Lqt zv;Ad8!ffwZ7{}(av6l6F7NN392T2ko9fAI3lsVxr{R;u>3Zyp|G{acXrugCQb~=fq zBqj3|u(agPS%CZ7^Y@m;p#;oNbv*VB1pe!I9os*KTl77Et}WBm% z4*#u`f1~N=B88~+iJ0^W>ubZCD%lKYWGKfnyTzoJj-QvsX-evo-+tS+U+v`jhu3Sr z)I<*xGESvoE~}AuI_2u&e?6;(Y3~f%MMMx+?|mVve;r&7O&EH9PX-@I(LO|2<(tPd z8N7|xd71yttY>=CxDy&7)z`VTizg)T+^<8(mDe|Bf#A&%=h1aXvT^_8$xM4f?A|di=gB8P=Giv5LG0y?#4#btr6_k4=|#QwVqB_MF_DC>@+&K9|&RmUFVF zZi{taY$DJ7v?=JiIlqdP=QJ?Bpyd;Sve&ASH%?vb4f78fXD z{gnm~hFsZJw%*14iOt12=8l%BkLiizjIsuX@Z73Ec8M#d|$*tJnDmWUkV7MWv< z6$!bs=ozLUrrB>FXg-)n%~LP_YPt(a^-HI-Ggv1@S`tTIhbgyEegNcfMCTV2&9MGM zL`(1Sxe+FOU7rsgBXO%k(;nh?lQDzIP;?{=Y589?ZZJm|DzPPuqGTy5s^An3H6-0Q zc3%SsYkCwdQ@amdMWQv)`Sa;MXM=pm7lisH_l^pp`WuY`0Q65)OH4xtFli`Z0gw9X zZO!b()vkM8%G6w|VR_8~BCRHeMrG2K=3-H3Led1^zl{p`1ye?cT|!Ec*02VZ4Jueo z&9<4n)smM?E`233bJ}9$tBvWwgxl=dy+2&&x-4573qWi>)tD{b_(DQcDBP}OvR0IpMpt@MLV5ZcOv0}$ejfZ$i1 zwtzesEvPF{8lHVHdd$;alG|7CV+_Uw)=TxgUMXNIoZr+ zfRx-wa;N+2E-pN*&z;q=l&da?LwT<&$S7;YfGk1;VaEDV5Dt_NgL3n~)6aR*UT7Cp zy?;>oGO>Gc`|Pr{*3sn|$*aX!*N^TlZ_YzYLWfWUYq;htC;B_(DjFwCI~%UM z!8C76Zdh~@o4MHBZA?q8ob&FXg=rS$xS5K$& z(&7GG!$O>L9AWxTKd8ra-9#0lkZYONb_1WwOR_i2Er>cwOBD!f6mrxkZTN{UR{#iD zyI|^C7)qZV!+ba67$RAY$wP1H^m5EFE~s@XBoCm+P|0HaPDX__%w!{sEIT(i@JjKq z__BCzz8jbO)HNBvOMj;ghbfU}EW|wqEC=>|%x0_o$jvRi8FjUARar6|C^cxp3T~$@ z`Mb3iQ3LR}470VTmp=&&nhWJ^Hne3zEc=Y0b<^4vcQWpFyjSmfSQ1nbf1_LG&QvBW z3u!Xvw@PxK(e==O2u(2DD7Sc&1OL5bkzU4gym@}pF;W;{xko#Q>@@frOk;uompmSC$u83% zaVOXDG>hG`vW~E==Qf{@V|hiM1zJTp=b=@f^AFGT6$K}RR$&ry=mz|B5gmCL`OM`> zddAo7_Tu&Xe|4`gaBG9=#s9(k!{(cx@KVj!is!jxT0S!MmtpQa&Ez-K9Id8z zP||rJQBlxb3?v}PQB$FNamBL%35mnCY`jOMFuQ@-*tIReQFAlh;Q~m1ns_?B#u^5` z+uKOUwJI*KbB0+Vc60Z#$hbf0nC?M&TfBe3u!)g47eYox0g0?(sZ1st54%V(!|<1L zVn2Z+6$&Tto`=T0*RBO=jB;r z>^ZL*;kC|QLYC(coI2@nGT5M#gXbrVJvEj44CGijRBDPNf4MclH^}hN@C)OMC`(YJ zi)j0Icn{uUS2TB};XNTMljk}X5(1&+9veD}5w34&{A-xvI7ej{q8kqH!FA3kiP(VK zvNsG1rb$65sT371;t`G#==kv!T#(n1m-qfMb2WO&jbPuO<*i;;XYo`fwN@w@bOdz z81?%u&(EOfM%DQ;UMvAKpR_ zFFjw~Usl1Y{1hIcrg_XqELFBFgUkx@*k{$YK{&bqh&YO}s_PcRac=W{%`kPAh=Eb$ zAsg7f96H%I)+(sEdv8>gyXuP20={`*T^c+Mt*|`3_Obj)GPic(LID~{abJH0WRfHj z(tfy3Ua5<~k5h}1RPC4E9inT@8f14n_>Y%prbX|bDBm6?n@Q@fBkq}(2%5@OTs%xD zMF2i6lJdhlH;hM4+9b4 zIwb7a1ubcKkfVC{`$B#(6$~Q8!LG(}GeaQPJwVTE85oS{>V2vrz2 zak<8|;5&r-^w(cKT{8Ltk1pMmGtyM!n<-p~Psi&@Zu>dZ6^M~XF5kXh3YmUMS$GsI zzS2GlWQY;~LZ;zFv8#tDgVryAzJb{RQ83Tjovi&XEZ@3^(Gs}zW*5R#!?1uvVihG^H z5h5qJD4tMHn-Vxal7M^v-WT~ zNKIlqEm>DmvwIkJC?3}(OobD@kI zMli0JOP}oCKB#riAP;(3o1G!PE@uP*M=20o$AJfSlbU)rI`c+;||ti zP)}g={C|mji%%5x;@Z`;M%$#b5=>+c(66>wVK z)Co8et(U`4>FY<7?RWAjbf28SuEs3PR?0D&d)$IiLLCLW9FEJ1)6DC0IGfqFnD(8t z3nby2W6L5dn~4a@^0@Ub0^+yN2@bsTlQ-zhyD|WW{z0{TdWF zSH5ZQ#;AU+9>Qjx@Xe9Mj94Ui0S%(-BNkXFQ8~lp+aZLRUKm@O`Ad>zl6<69U;%tM zY1kknSW}q`ZoUof?xb)z)8Ui8uStmuqCOZXv;J0pYEeE?ZxU`2<)MJ&IGsTdIzD7Q z*zvt6-OM@Sy%Ps6Hg11f87%5GfC0f z`zP~^@VxIJAxQW0V7C%U;g{}*e zoE!M9;K6qLpH}M-LcwOjWWlCC9FQKV_$fb2NVN6o0_d~JK{2x2-a8pL)`7j1wkdC9 zirGT81Xlwh`m`F=Ki3VoojFyN8#QF0gZ%>YhvD$A^iF%J04}9V%rrX2n_Q7nwJ|E& zr^OXH6z?k46QaK984c3QAIeg0N&Q^ShXS<_Sk(vP*Ug1%RNaJZ<)q}UtMzK=zz2z! zl(zf~LtWp9(jSJCCL24q1i_$T;-M!&t0DM9dtro^WBu9^jbFMhN9lfZ4BVNiAi|c1 zs}p5vqw+(8j`~|%7Ii>OiWlx`w@Ld59{2-tM~2Cq9q!6 z2u4PRT{&1uN_4fg-9uAhA`O;H;qgZp`953Rr7O}2CE=%G?uj$w3MPzi83*UDzmV=5 z7}#6{^a(jfdR{NRo|_+EbkE?aqIUdH8&*6w*65;bB(v7Gybkp8rxgZDy$b^o<`#9K zao;uIZ*VgkjHl={t**Q+S`h@INmGX{p_hk4^y(Fbxi zH!Rb;7en|q8)qJTS)jIN*Y40R!vl$ssC`Z2Et<8K+_J8Ba{bfk;H`&hHXuz7yfws7 zrR$q+?if?{!FR))&2j2|wsy<-%9D9QJT@bRkm+~r7m-HED|?fd+y&vkv2@gh2Uk+Q6K?OJ#`X@#!> zvG=;COB?I!Os7m3Bb?dJl?v9IK!8{f#KdRsmHs(@`TdB&W|`GR=4MY25yrzwy}aQy z%-SpeR>R+e?E)Pc0n>@}{R>+_U@Pv+|8a?}QcDSEG9dvsV7+#ae^RXn@-TaG8|FM( zNO5as?zlTTQAu3a>3+Kf$vQs0E}xyhw61N;2R+fep6`A6=L<3KL?&FVa53KQu9Hsb zUeP1lGpj2>Bq)eGNFv}zRzZb}YD}}*SIguIG&bzwVRbnCLleO>*MFQXuYNr-Wq#IA z{IDN9#i@3=Sw-^}yAp(MlZ87@m9PIf{;&@$ ze9$zg78y<^Y;wYP(U|h(%@K{oC8+CV!(!h5$5FCjbdnS7sfe;$J>k>^_Wi`uq*mlT z2H)p}mf@6aIdxp;0k>hTkuXSPIDUde+S%pnS<4-v`s#C&s)jJ|>9;1K)rcSC<#<(X zOdlRuIySmO3c@b{5QCttJ@|mQz#~>#3jDG$9+c%!@=*4K0;`9>_rmA7waKZwe|T4w zKobnTrdYjkVsQP4zh?fmC!Rdt77$S3buiWw``LaST?!O1O%VIpI9`BIey67r!K?9+KHnG)Hk9`o1W=o^~A0gB*CZ%^gC+_L7SZlz6&xH9=GyVy`T zos)Bz^gV|V`^L@eJgl=0yOg@}fjW}B(fA;OQm1c^BqMqCUz?(}qhb>8%(*ge+~WwUYtRSc|Ao6Yz5J`0^qJcdcFiX) z5zRC^Zgg6od(O$q^GK<%_-ijx)da>BayTEnb#&1$r}r#S&2sWKt4Ql((>oSSgrR3* z(<_H>OzY%6VyR@&O#e|OAs+ddoyU!w73VfAU*1li;-*`lA(!4;CgghG+3rh8&m3?x zxJj)qiJtJdWAMv)czLF08R^o$L0Hn{cH*1rQqNeZ7Bk(i(WhU)pmC^+8LzTHaqcZ?-YT>)ob z*~vG@X%vz_1FVSbaH0sli)lrH{2n9W63n9RdUc-uo+ZvPM547hsvv3`+!>Wl{Q9b_ z^da}Xtpf3=O>`?pknDIE_2)d;r6R23i+Z^pGL<7MybIyo9VRtqxce;1-lcU&;m2z7 zyQl{W5abYUiPnjbRX)ISq6a~DEW&axsu_yE8ZQ#}mIhazEh>YY^%(|V&CSYtmvM)T za@00<8p}KzopZE$!B@t!xC`(}vSSmq}YLPzYpi^V#*uyuQ%oH^u?7knkT6W1Ko@J=Ocf#?aHBA^?>>1_dXj zY=k&^y98%!`;Q7cp=|QeBUEDqe%ipr)7nq-q_5CC^+$t9EEj7?#GJ8KXH&L5yo9>c zy+Edf=f#9pmJ5KdN{zMr9Sawq8AGR5C6nU9kbRT2{B#v~cx3+MkydX?k)6-~=j@c= zU5@;9+Z+jaw?vmcm!>>sC%YeLQ^>{5TN6CbEHdsIaj{4GY3<8aD53VgKyy@UMKpJ$ zVNvHo_YgMBvC=7djGN>Igmh|SWgR>9n~yh(=0!`9a+PD%~e=vGJIgDYYwKV`n%XkMMU z*RTpP&3Me9fe){zU{icnWxhIO)ZKVtZ(i88-SKXfG1>_xa8)=-xDLsqj^cNH6`3U! zlxpj!7FM@1)Y#)>aogQ@ zSGDe%CgCDUKh<-3suI?`-wDk%-wv$JKy;N$*rpw)EcMKD-~3fA_KKxw;h4RTsIW6O zRTsL(Uk6Y%5nX#+{w0;=O6RD%ah4TeU$1heJs;9xe^8WvRU#2dSkuc6 zmce#T|EX25H$ZgeW381^$`R?G^x?aWQ-I%w+tC-dH5n$cjM@ zr=e3YJS0Y5*Ev6ifw$aRv5|z)ZkSplKTiK{AYZcV_T=h>%-Hap)2Z$cwmo^><*(-D zpk_W(fEm@wq&#of!PZ;%Oo8xxfI1u7t5KsLXVvzrl`IwoQ{^5Lo={FzjT$7n{972o zt;w%*9-37i9|4xC;%;^Y&H9NnlL{UtKRf%Z5Ik&wC!cx^B;b5WS9 z**r@=p~8_zK-YO1kj@Omt9Sn$bbPiXsxyZ|dj0%g5PE*yZOi|cNDmj*^hrM&o!{HN zDwAfMt!ChqndAMK{esWnSP1=HP-y8BJ?x|RQnGY{lM}Qmu*NS@$qcrFk(itA?Vb>g ztnD6Rhoeu9iq*EitabmPv=?6MhTnpFntMxM))qBw^h=}f6e9dY;904P&I`9a8vqgl zcMQ}E_A%M17$xoBVpa!1M!$WuZ|1%jtOtA5ks^s}V8AQLlh^el+e3c<+ONaw%OR6z zJulcnVvBhlFeQc^tFstv47A`IEmxm`_+_|{+~l|N1EccUX(!{;H9H?OCL~!sQ%J6U znlgCd9ns37DH~>d%91qpX)(VNX%u{?ZuV9V~BnxMgr~=0@8qF6 zE}DmXdH+JjV1+rw$YyLV%$`X5m;~q^5cAfF{C7hfDT0%pDx+O&cEz9Z&01?REWhy5 z0+4A_PeZ`Kp?0AXtMNiVoU^bO6Wje?Q^=-YSl%+PzD$N-q4bnr?UAxP@7-d(R#Dl` z{TIZZO|Kb0oGdmCz{h&2mhnfpE!OtERsDTnJ*{O52>7`32fmaE&zG1M3z5-rz9k5p zl;2m0kzT={R$I|mFxDs!=9Ztk(*X6Anj{>4i&E1ZVRUp3qnOj#2<}2R>m0`$|9!S~ z340Y13_94bY`{hmX_YS{AeV-JY)*+woid`(YqJ!M;&ndd>ss+_)zfKFZX&>=tN|(f zJXJqJg(B1G38Cd$eQN_-?(zc6sg<98S;tnq zo;rT?);osLE5P-K0B&e|wVX)KP?$5;szJSH#*?QQanL*6cjuslzajH_6=~pl*;L&l z$i^5S5v}5doJ?uZO`dD+{Z%1hDwo0m#j$9TXe+to-#n|0?uf6;J z+uLjS$Hi|RH{`}nK?DC~oC2vqMfr#I#(r9lqDPi)JAr4oiR8*yd!o@N4Oxo&Twocp zM{ZeC9S@Ed?fU+ODBWo*a{kLS*+iOZ%jTy1}MHi{t$}T6<@HL_l2l#4- zLnT#|Dj)RjUw==&^UBV#30~Q&unc+dN&ku!CwIj70{i}?{t=`Uq@}M%K1^4#jU+|Dq^Db$oa;5Mu?|aHqQ& z;oBVDKap&Vug2a|r|Y%tVqpZ>0^U2^tI4%5#OpWMI)%3*cG%lCi$2Aa^UxvdN*Ywd zM_`V{&9%~5FiEi(Y6f$1frO5@V-ddROvgWL{X4g#XMm;6%E(%~doIh~Pc>r-zcbtk zp62|fgKWW^tvKd0#6m1>R|dh3cAs^*kRGtPg6t4as%Fszl@fuHj5cCme09+(evN_< zMPA>zcjaY4@D#pmmtV8{FlRl8U|9W?l3VWJqW-T5E_AiB>St0(WT{oUt4ZZM;(@Wm zWw9IGTQBxuw}z}#nPYiHmtSwreC;3=UlNn$f+5#F2~YHTc9OoQ1D9`Wo9cf7@YDGD zcIbH44$fgiU>XhvMd7=$5yuW314GT$By8S@L>{pTyFi8de)*KotzXPw6_7m5Paug= zpgLkjO5257uPb4rD>L;dSGcK9eZUFg8-Lry8_(#cQ?JxWX{8mHGrw4Lu`oJ89Qwe< z7ZO(Hnm^)W9R^!2&QBggnS?znub8B>PIY`WRtDux&+Rc?@HQgGPanKdt4M<3;Qmsb zh?v-kWZ2FqcP|S*8x%=~F~@{SF7%l77UkF8P<7l^JJ%bsMR=3e^f-*gV#xo$79g@D zs3rhkM${2C)jW6gV0{f`5_wcr^sF4*4LLmA~N5v zDdQ-z$|rSvn6Z&esHxHCk%s(XoN)Calkgm8tB%$F=FSsA8Ex1^ohN}R=u@4VFheFHTdL@{@d_xRu%K|j2Jp>m{*d!>gO%&sljTUra-k$ zO?Cl0Iu3RHtMRs7*!F3I@WIV4AMv$*98V#**IMlI^py{Be{PP%ArR!Taft;d2*_7F z>CJ_2!sz-gdEvIINP|J~mKo)ab@i<_7mRu@EI28&)KWw>>P+8kNtRIH#zLiOmL){I z$U-PPe7HShV~WZ6vAb1LW5WY#{*^rnZtBn-SrI@8(zVMuu2$vWTB||Dci()tnX)ww zJ-uppIlS)7dsTaca`~vzPb9RY<<6$=s=LC^1z8V?E{?#41N~UkxI)%iu=XAGPfMeoc=uBNAl> zkUkDrIH$jq#oUr-owE(>JrTpHjNo6_)B65avzTu5U!{}5Yv{>UF8Kz+UaX<%wRn(a z#wmCHLKFQzG@bKXWp5Y8b4{GdHYVGy$+mg2-Q-hEHQBZ&+qOGtvL@T+d%i!sf5Ew~ zv-h)~weIz~@3jbIWl;vSfc#gP)ohQgB)Mst9M@>~T)2Z4g3>XjL@0PPq^FqSzB143 zz!5AQb&BqMQ1LpkGAKC*N7uM0eXV2Dd>*gpMa6CPZyg3O%;fc<_pE%J&F?iEVqL;D zq`VU-U85>NH}u~@xpgEojT=bXY6D0V4YUlIMfC>$J#U692+a}Kt_2(n;mW=lhGD7 z4?-of4NPWJqi~Qr>kA^i=@8g-fwYNV8^jp*#^lEN2lJ#bK@zQ!9|8p8!|i;0#4|v5 z#%&uq!`}ii6!J5TMR?ue3~VxEJPlw6cFU^$^oa2fQ{bVKWQ%hZ@J$nVIvJPpMOBH2 z^u$(d3pA~CJ}#QsR{ZIN(-|=5fU-vK+T+<;kZv!B)-HD5S7fJZpZ%WP1$yJ^Cx@e7 zpH5DSA5R@S#rpZ++hK2f+G&%5tqt=*({R6iA|~NljzMF2nrw!$2C^<^y9TlGuHoj% zjm}gLAvpI<_y78NL-)avvIyJ_c-VQun&xMOY~*drI3;zk3>`Z_I0KNIuK7f5E%iD| zc^v-wQ0zKNL|n-k8(nW?6OftlXKVKUpXW4K> z-qQRwR_5wD2akk*2g~b#kYuGZmLZ6rl@}U2`PZytUGTCk1C%;)&DHTJUqx2-6@Z$n zLhXmnDlo>_5?^fh-G7nP_E6}DO&rkT^gqe^Fw{LXCCL`K6`TZBd4_v8PStxhx$jC&28WZhraXC8kN5 zqOfF4asp4WKa#~(oq(*}S$0cnq;Mxe`p!i>8-owpP0w;S3bM=??uW}O1wI3~h-OEg zh~vDgI7gf54Mwbq@oO6{w3>1SRRFYI&LUt&T!&l#E)h|rk7zExre!h>PQ*1BFGOfo z^YymKtoKv0Nf-Pwg^hBI3vmRbNHlPuzzkk>3vlDCp*Jvi!zL%qSEh?eL`R|b8NznO z)DFR4X3&nYwmRH0Us%u{t-Lb0@m&NNBCYPzY-;KERDNw>nsZFx((};xJ%53|Cw{h$P8x~;6{0#_ReM6E-Cb%{%v6mE|J|sQ@jF#pzge)# z=6)z%irEtLt|D|wXyPE=@ak0`|243{g;Ry4S@IQQHv+3HW zx&lp7Lf(7*7x*)vjYLYT{eZjtFyHs1eOOP$LaHSr1+mLDfN-8KzL2v0<&DHy2Mh0n zY82r(X}^A5DF*!uQJ_|qc{JVFn#0~O>X#a+kT7&^q!!W%-t)c|`dVXF^}-J)bCWH| z%w@b$5*1uT3uooy+r#=NGKR@o4@*c+G^&#NO}^UD(4!ccVd#)0N(5QkXQuX_o6O-< zaBXw8Zlg{vC_XWEOq_z|5%GIAJY_M4W(r+oYml$M((Wcv09c2>3C*`Yglt{y63!jZdgeGd6bn1ho93k`cUp^7n~;RjPthHx6SxXQ3w-jw}l|=MTCSyd{dnw*kls; zruN)DeGH9G6y)Ds%!%KR3>Y_eU8*gx;|8nuU~W?s3U0<-IZqR)dA7^-U+LRsC+6^d zbNnGj`N=!YY3DKzZCncaz%CG^xVqTuxXr|z1=8O@84`kEO54iujj7FBOg7|%m!1Z1 z4dFQa4#khBw{&c_eGlGaDOFYT7kwE4;`tm+Fz~&EnSy$}dFB&BW(HwO9YrJbYprLT1T9wDV9x5RHf_ zGa=`w@U^4|`g0jR<9-`r7PhoQ z1V@;&?{O^<#LV&s%J_va5VmLi!_JlJJi^fYlq1DoQh9T1yPDHHOkiDE@?(ajA{Q%K z>*20l*%+RI0W{8xcv?%P1O2(D`s@-42VJmsR>fO_NO<`8_^QC~#&W%IyH<9{krrCz zR~>&c%`|xq3@ln4%urf%Cip%BMxxMY4{km)t^jrh;0!Z<&IqZsyh}%bqEQ;fE_iq95{P`rhKCgJ=ZB;7 zr_w#i@nx(1_4i%GxEyvgh9RkgyWc+*EC^i2JSe06BZ(Gs&U1)A*J!{piPLW4=3W%T zvn2yTfZyS!R-09x8&g~oAhB_%FhK0|&5m&}tm_LY?S~;6BlV9s6vfwcIg5HOhMGIt z8nXOyJEh3C!5o^#%7dN?^~_RpPJT^n!|Nq$`b%97`chk3B7WUci!Td^WFx3JysPEQ zn`FHlTpp@3L}3IY%{%IK4DoZgRMSAUdh1js@oj?`$VP7|^HwOLM7kOVy#}NuY+cqd zWELNsCEnDr=sK#DW9K365OCC<%g<=)KW*d==X$WD1N0+y5=Obw-d5)k)b#AJiCFqk zidpO;S#1is3H1;C)uenBF*;LC{0cC6&x9uOt_{hwUC;8_*48oRb^Ll27WKhW$!$=g z5}gSu&LG+oaG-5@@#=6)*od|rt$qS&xo&8~(DLu%5MN^PJ@Me_h%1Rgg#I*+VG<^w2FA)s)&fgN)Ae}rMtFv6VkOHa3YwZ~!=1=;y(YMD|E2OCPV=j}@gb;U zwV)zeO{WQL>%VGY5vy}9>nUJNO!5#bV!29mwKs6gSa9*5$yYXR%vDVyo`Tz`*Wpkq z#NTlWg_r^>`|5MT%-g2bXQ7m`&#m%P$42C(+Ha-ukLa*id3qDh;420%dD!wAU7Ea5 zGgg~vW*sqfSo|gGx`f93_SgJ^tSZhykSmaGB4HG_SPfyNQHVEL;vU^>)VmBz>JMoB z7AbT43BUcG%m2*-BE@M4^3TyX>TtabO@|+3v()57dSisPycUwsut-U|(%64|Ns7)8 zmo(s4VR)>&1IH1hTtmid+!7{x1-lx57cAv6SvRyc%6y{rh>K|B3!S#QIO4G$B~4qrcufE2u%wBFOns;&!ZE2=BpBncT;!gWi60%j&e+>-#2n93~btdbN{IDW@A~gk3=%+%lddk7h8w3 zkg-&nvo5fPTqrZyP-@q3H|eOF2|Z6F-bVj2u(dI}+xMvHgv)OOhrtkvGer=y`?g^it>0@-tv)ZT8#kO{6GjS)A z>tb%BB{x0ZRpMW?L0O}q8vVOs@^3t~Dd!T%s|(!6MtMudPF*5{aJshj#JN98oW?RH zGJFZcP%lH>Rf2FuRJ^cj%>(sZFV?@b8s94}=OjRJ?PX(r`y1*jx8N;u2oN`w6D)bN z<4r_3@|$@WEOnd!Qe_@)zx5~ZuCjE30Y4C#pk~GE2^OYBa~$ji>Ckc2H78fxNwUb6 zXLsEnv)rT0!=EX`4KzZ`U8#cz1B58IE&Afa1?;8~{H(hx2yh(635&AKt3pJp6g!3> zyjsc?MXXiamRt)Dk&bOvLu=PY2e2s1hgs>+U(Wov5dY*&%`=-JQppX~<_w;a6#(bT zMCLH}7l~>>b%|Qco%&BdP=HX1C|t{Z$vo=-NH~_#5NKWq1C$JW`b)mX+d~%j%7?DQ zy+!OKH_@ca%5(C~(W=o|eYm;S%r@`|GqVax1{>u}7X$QHuttWME_AVEMmCA%?411W z1eF;5-v3(i;G%0imau~JU~-?qK*!@)lHtA}D=sLgBYb-FT@(=AWk<{zSgPN%=SZ#o1}7dXu^n z>?J0Xco-gMKa4z)qfttTYVM3$#2EOy(%xSeM!UBox^1x9dl2RqZC=rfjbyOW)1wyo z<*!kQ-WAn4d@=Oy+(Ht*KWsndZms^UOrS#)_N8)N4_#{Uha%Y}xu-v#`Q#8DHGSc` zA=fH;{qtwL+Wq(h(1e25!V&5s;9-15y2Yu+8=jeeXRsQ~JLHe5Js!Qko>RVMjue|nmn2t(b#>T3XlxPB*Y8=vFJQps4X8WYs_4Qdg5 zUE&`r5_f9Ujg-{x>*I65$161ET`r&AdHh3D`=oBN;S9LAl);cY7_CYB?(BC_K5*e z=Vp zsF*x&Hq;{}1OD^&GW)^nlfQ@cm1{~N3>G>rlfML%CONFE2njsgzyX20l96!my!#k& z{xbGcWd!PPTopOH=ice?{mQR-0-00WQee!W!A`H(ud~$sz0!L+atiIbO?P&ILOr+U zRiqK=oU43;^-G+MRo;;{L&qahBjG0RA&|;PNCJ4YT(?TLkfCNevgRf*M>e%FTm8`X zZdk(;_2SWETNuvyPkL(@P=pLzbu6ax;8a|4ijXTDSRR**Ha*nrxT2?Z?;nWzB?)SA ztR2DkfsMh1A|EOr@}x6NJ=bppy~XWM2hP!o%(=nVIJ!(UMt0@xZr{tI(7@X{)DA+% zIz?0cM|p6qB4RsH8t-gh_Rk%`?GoEE%x)W}$Oz`&&oLqy3&hXEiWHq3CqBy^yXgR8 z{WzYL*dd#Ae@@;WhX`G)+@-<7sOO4nE?3mWE1Iih4X;o%3w}QDBfP2~kc%6PA&zpb zmK~N&c1qidtv3;-zE8`NXrJ`A^fRymd!SCIv_pr=a3e*jBq=p)&}Ja4zYkMzSCn)X zE=y)N4^=17HWXOO=$IA2@&XuaKAyjfG>&J&lXS+u%9ty}x;0CSz&yqgN}sqYPqqkZ z2;IAf4a2Pc^G_@iO%azDl~-i-(5g+pG}{|~WtR$mHE7Ugd7P!jZbPft7oZK@v@d=M zbuB?WeCYUQQ)=E8%+4b1^0m87@qNQWCmy$UqGbd(T=p@T@G3gc1{L>uuU{C zL2v0TlVjtt$gt!=*sH;?8e+;Y#8Hy}{=C&Z5-3&O0Nt+diQ_SGw`&+xmC!d33(VVL z3S@-#lXWk55Ah3xBmv@beWXnsx;lnKNd;3%AkG0I&s3w?;DTjQf{vf&Q%BLHNaFX_ z=^%=_KN0no58=g!p;x7l1enFa>R$Z-cEQUaY23xpk_8r9))obMj$wjhpsXi!-lllL zVthp8wF&ULE&*PKmP^?0dowH(LwwL`yW4=?SmK;Smh?x+*gADg_sV=sJK&^@ZB zdnnUc`!JDZM)F@B1;)3e{R{q@e0#N9P4VoQ3CNg)m8*lD_v1oMdFptbcqlg4{=plK zb)tV3wW)q?l)wS;dnH|9m!%lZ%_o$yNh*?#>0EA0oJmq_=4moJmG1BO83z4xiVweAzfv8T!+#5KB ziy7cI{+(|%wJR~m+lpQd37yD^nS$K?m^r_W4Xn0DP#vr*&YsXEajfVSSMkHY4s-jQBj74Y$udYbL;KrCD+Q|ap(>>o#mSf#nn zsMK2bt%=|-n^Y}5ch`pGF^;9u$2Lwu*A5b?8-nDwODNa`{_;Mn4Wvg@nmCFFd9r$9W^};gOY+Fvc!#p6 z2zxJPe{x;6SoIWo?s5qxFlW9p1KLex_qUY7sE*3>`-1*791HNmy_H1Fy3tO(Xyp&U zaq}35aC#VLXREI$Xa!~c%X7Q!z#Ox0=dCRgj_m_0t0P*qg(XOqhoZlJYh=3Fsdh1`7~qpl@o zdDOJ7d+iF$i?}FDR`SQEZ*~r7^PHhta;>tJ@3`?BY>kH29$l;Iikv}RifzVEo$iyy zdB(-G1u|Bq8p>_7iQAF+G~Rd?SExtB*`AT1%4@dToZdpT_a(>}^95AZdVFP)EM;kxM{0%^UuK$O20~&QMVYdT_|nhWkpLD2jyS2IrljyJyH-eiWoGOEGwL7Fdxd+6L8G>~YH;Jl)V z^H?WNsr5Lx?L;AUtKM~P7zK3)wXgZ9^Cn}o8l2mgQ&aOFSrv#RG)Rp+@(}V=5VY{9 zB|@1NX*=|g`$!VjvwyX;m<2ZseZGzjRm!F*eENtWkL;k z(hOja-vA)IjC5z~5PLdw8J=-d7Min39ADObC0h`m+i*cE`ls%6=J<(?ssS;$;X-lZ z5Y(p?4jtdAfAMlTD;w%GR$*JwrmGm}QPwrSW*UorM%BQPcBB@M)2I_{TwZ&z3e59M zqf9(7)N!AN!gZJ#AY|hA&?LA!*M_fH=yX(k@!`aBsTx#EAqKktV^~ByWxf{G`3Gcb ztU+`pt_BeyEI=qcA^{Zb;w`daQzPp1cFWH6xD-adLyOaU2|Tz+7T#qg+!s1#|4yew zGAwSPiew2)u=vz0`6%L_z!x*+8W6;b9wYk7)=`(ng@N-`D4aJQ_**cSn`0WRlXH=l z*xOgT2yP$X>5cLzpP0v(m`{_X-oNA}ioySdog14MQu;~eF`ys&;Wm+L%ucyX8Y|AbH4uY_jP1dQ>&B{mB zK{a+vJD2UffnQTk7nJ&!A*D0Aj^o|6+-{$ti&x}tz@xvlZ@@LG0WMW(7|QBqqEI2> zuD?s-6f}ixFq6-LzteZ@0rc7JT8{LPoOo6 zwUr;p+1+<~b4&)$n$5C0d9L#Q)d!ahtSp$$`8$6bR}gMB03NieDJ>j_m=ML^u^rRBSMax8SI+2vc)bA&<^3KJnzP@jhmK z{z{Fgl~#Gklrlj*Ard~Rj(8|9U~9Iu#j;+JwwmTzo6qRv;21N6e%~}@_dr&L zR#`cgbx0@L)JszOQquBp$knJLT-f^^in3n3O6#s@F)xbU(=TW3iG1`1Pc*!v1(1e1 zJmqlQFkLS%HO*-aw#K^*Tc7!g<-03y&!dw7CxpfyX$~Er^jOu&&7w0Q>>joA`_TE( zJn$+(mNf%%Jw_ZtqZ+4yko6@jEH~^^Xj=) zlj#ZC+PcUZx(9sim|BU?crY2S-9zieqx(M#V5)VOk_*tIW2wjs!LW-Zq$i*kF6Qk1 zl^kz-6~kEBm7yZ+yrS(zT@E#o&WcV%#}G^=*MS;NVAQ>V9=sx|Z)=yOFfOGQn6DS# zI>pnFG1#PBl~Rh+avfZ^Jp!ci-}0@gyBV_`K0KKf^&ftBYxZr=xK^n0CE(d~3t;wT zwyPB{6bWI+W_oL2g8IFq+k6#cN3d>ObwZ#jbGVjxzj{wwbqa9>b6Go>KdQF3|BwvD z1!KRPK5FP-6yi_049N#VN2hFi{LWN<^AYy&v8I1`mNOS9$$O4iVt~hsy(Hw;7s7(P zl(!&KCLS`fiGT-9<)@F)>mC*&><~+(`86-(YLn;13>N)Q5ehbk)Z``L0sAsf0cjOx zIu`}I+#MY>x~IS~6Bjs#jsvq){ZoJcPRW)j!JVl_RON>BIRC7v1ujVuGGSP|Na*w_ zZO1Y-tsBr(&qyFv{E@9{!vW^GJ8u``POVsR(UDLU8TX?^ttU~O+E+!ASmV@bE*Z_W zUuqc1Q%Fm$7C4osTcj&%2ROO33;Iw+93ba&i<{JLqQu|c#DTNZT!I)jU^wKuK^`_t zyjmY1=s$+6c8tH`C_fr~f5+or0~x4k1wOJ5sJc_tlbmYc06@1JWU=_=dj=Bj0cHVJcdmykPweX~D{gYgsQwi@r)W%Hbv7 zPU>m{y}=GB7eCszm+80i;EciWNj&p+7_)8qcELfrN3sDl$?n;X}c)*0MlXLC+iX}?5|xAyGkDsbfC zawbVMNisD zPNvjj^{)Mt$>#ZU1uNKW{3*qI)Qd_*gr#*#Fos`-c;`2>1%+K37u_^lM z^zkV~33x#SrrI3aCQ#@^y`VUosd_8-Vu}6iP+g-m(?G$+d{9>MPpq88Z-jg$Db?1f zBCWZ$`z4F;NiO4-F;%l3UhqeR;4ef*+b&w4yC3o(xZLl9f_EgtSuDQpOpMZ#slJ1` zjMO0;N9-uvi9XDkm?MXYH=E43QiqCf1dpr45^PF^)%3z+*oVH`{yj)jAlJ7<5n!dP ztV7!!`I{@S{mnrV@&HZC2&XCfo|c#U_`ack8tAb2^+cprX6Dz-1LDoEk-Lih(w!!S z>Phb7#aYCt#)Mm{x-TQpQ}W=!iX2O;QlrW^6ve-sCh9yCG2KkrTx+4s#tjb~v=j%} z?+PY~HxOY7mT{rWg;{fY?FfS&K>(wD%+Mk4emOh!{bW5w7Xuq*>U#mMF(&tCnF9Oi zLriRyV*Vdxd!h-j*i9-zE+S_M_Rc;Ha-gFU4&g)h)GeN5vhtu~Gw9EPV zA}JdjuNt|&pXZ(sEVPoxV86zb?<+>iCJLtXmPdfxyi$AM#rs2{w4$(RQ&J z(v|+kNL7-70xAo=BRW;szXNTdR-sfD!B%}{B{W3aJ>x9wDYIpr-^Th<@v~!H{`A}Z z5itA8!%0Y?l7EXFsrfdK`z5G$IhnyiyYZ+sO#&jKzg}R7AG)0*U?%id{~WUgr&Za3 z#w=+NMJbqcY;_fe-ai@}?9eKd^{@0zsG>DD0`n_@*0i<8n#+j2kW6*#yK!0Mn=rN4 zV9jcFj<^O1%XXYLfoeT$g(?m<> z$`fxm3qlv_2_3sy{fU^@g5C|>wV}q&c)22a5tKUe41_Hl^HnR?q>wR3Nf`MWA zNqa}o0(5zj39Wh33;VY*CGOeOlXQDH>emMKz8c6P*v-LV-B&6L9YRl6#Ij@wD{0k( zqUe%#6y2rWFeP5CJ>u(x1dD>>L_hatP7ScL|N0RSEX@T-+su}~u7CQsF${s&$o z8kebquakc`zSs)}sd%zB(GVVFEj`{#`D;4C;v0}TmMO7uO9qWg zfXk(wXqZgfbxP7OzaRM;S+eWs1cbE+b*i?Yhp4I=P_tv*FbWu@f$*iShz{U}DRcj6 z0Z;59i^3#f|{FI%7y)O zxB^+Tp5b&+bQifPqC5UflXDzEQb(B=)D)N* zWLC{GX$53)NhF@dJ|}({pK* zu|C~?7^bLOhJy5bOM+{t)8UR^w&9w%v(9U;Nn?DVF?giy$#icHTQgLiJCUBjra&-S z7(Cvi2643Dqvv(ysWmx6TO@fJX#;i&qB3$BhjLXpyIEYUB|&?I9^)#TN7wL57#Zo{ z?qi!--}_dOO&+vGYy9UQ1+$4~zLKkp1j|S116*9?j$f`6)Bn(8d(i;zau$FXhLM-L zH9HPNlU_r2TOb)E8QlcS_#(eDYK7z1w|`?gfpg9w=B~NLq_k);z@MrkOZ0U=AIT1b zTjX1zjG}WNN~6cV3gps>yeIZ4x(NO{EMfNCX7O)cuo0##HI-@H!(o|-`da&Y;|Ie6 z0C_@P2l)47gOgxE8~)YRi)=^u?O92}m@L#2AAh{Q!mr<5q$)ZXf}@pwS5hk;DY-+k zb1&sft|wyJBB{Dau5I+hXVZ;jw1ivEGK_mitQPq+bFm-(8vL``W=+$JiyZ_LReg-X zY_*P?)I^yn(bpaN9o!^DqF?#nLSo?XMyStcMduixxe7BZ%$L!86JUk%M577pW{krL zTI*4gdp=O+W^4DT$roiLggH-LFoi>O!;`&?0C`kQ%x#EG8Z~^Ety@(m^(#o zp>fD&q0g>Abz1AWwr-Fs9&{mY@sY3Gam1-gaD83v4T$zcnze67_UU3UzP@XIpM^6Q ztv5W@MwzJHGy8ra*$l~lfU0d0oS7(4hCTLFcpm9N1^~V&7kjTP@WnwwG{PD=_Wr(z ze~pswyBn%cQURyBqyL8_51(`X6PyTD6D@eOnru}kb&C>}iG=-ASG@FYU)9M*%`u<~ z8E8LKZARsw$pb+@R+I{2YItV^S8|PurHL4R824cR)`gBpsBryXUIBSR3ew+}SoEAub#q zKhJ|zE1^tTnMuX6zi)s4%H@_c+OZ5x{w|K4H}#^L6Kz0`3fDFM7rCEI$2zhIM~Br- zG?jy(HaMiR!mD{c9uXBh9c!;*NXIFOYs3|1GV5Z8JkEO9kPZIhXHaHJbSxeigD6tns|3hIbJsZs zZom^!s6YLUi-v8R+YovE-a9^BKf(`%M_jGR)8(+k7vywMb+)u~?iyVxAs3oDQC{;G zrAA+zh1<_P?@vys48iq#pJhaqtD*xhZz?O#L9xqZ!a>wic&ly+wLHqnoF5aX#j4Ms zZX==AIHjN&uj5HQ9(r&Qowxhq_#9e7<37U&O?u4DCr==FHpBF6ttRyI<36=VN%gn& zO3S@e=PBx$UsSwA?d-r8SJwe#Eo z(L`LWeQ+ID-CDD+o}6NvXm781)m{kio(}&S+TBV$-dq`+2wAXB@wtV5`;Z73g$^*nvF_fhEYeybkXB3R!(|I7a0lxa=XAct7+l1_yU1622%9f3uc z+1Zab0Geh-K(RiRH zy{zhRj^?Tjc+_yC)^?`7P%G>jx~82@kohq!o+1##ZP%H z+KH^u27c~eUb6a3yuU2crm5)9e5t>ep>R;&OoxDtHs@|A@JPh3hypj`25vNIAWfcM zDrIU;wzN7wN)}X1-@=+B7`v7@Ux9VfTtrvkWCcjSf`OeA>!Dpf1B;*(ZxE{6S4!t2RZN`wzDg$ zWl+b1JACm2_Mm%Owk5$Xy7kQe-Vsm)I0|jr@#8_tcm5rKtxR`a`3l+K|OL8+y?n}p6TDUzeJQzy`$U0SUAnF_e$ye)_w zOP_U-PZVsqTt&m9gv3EFT%Zw`Pr$I15az1DGiJ{m@(ianBOp_~PzpHvaS2gFx-`@D z#jboy-^Q69-8HEvO!NC8>N(gnba52jHFe zC71s>?hyhHL)|{DQ!P3-m4afLyY?BwkuzQ zPBiWNOvna=#}@2%RbF>&9+PBU=rjbV0|+9VBL-{lLx;-w`c{;QG$ju{Z2ZdxrZJ?( zg2p>0saPj=?N`b}?n#g$3di`VU9m$cX3!uili?8LX|QJv-*!NCH;;8@Y%=eyDBatF z;j?9bsCtQ`gQrQnprR^Hf_nPw=^yBOrYD1SRWxvJWm6bA-;~SwGgX%ZGgFpMI^AdI z3!;(TR{1*{mz%qVA3-9oWLLoZ{-tPowk>8>yXDoFiCYiD=FaXHeDIYPRm=*rq9IiC z6v3y3 zO1A=vW3t<~_E93=MaKPw&J7>q6`+`MRKz&knp|)@ma=Io(l<5l1VbdTA9k95i7V7+ z5J5@L*#&t}MdtEPAt$w`)p-u>@V(<5e*dT&TnnCXE0O3hwSk5F@Ep!Q*XV6G*Ul1i ze?&%FNe19b2{8kdG=&TS;b4d1ds&7z+pK#M&>BRXIsy15%Q&J7VjhxUPIi{IT#|e2 zKn*HA-GG#8on2YCXYpTh~(RBM@L`zGtZuTP&92fTp1i4`3Wwr@bt`MY+UYx#>8 zFIk!~Op09e#rBn7D%djm^m+9OlxVVbTMpZ((PVG8gF&k@8mY2(J3IH}js+Mr#!e*p zgn6kQ70=PMYlq&^?0N%nDbf z+F~x)P@7{y9SX0yg+my=y%=EIVCR5ZC->(fS+5cNOUG8ge}>F}UD}Umqklv>+eH5R z0iRf#3e7wq=cgjNen2-kL*y4+TcxAYYacXXewd^kZy2En(_LNP4o!`hKoz z!@OXrw#}Iq2BjFFKcRoh8yzsBeZ#Dw|8Hxx^h=E|5o1d|7(MAeJs_gu)+Rs+D_k;n zih8$w$vSmZds%P4J9I8^daN#?#sYgpyOz6At!wP!pe7^!Xw7Pu_)sdmPJ1t@k2Z<7 zXymfrF?;4nd*`Av=c=}WNWZiiOP0kd6!6D4YaLZuRPHHSgjYt&hreORPpA&tCr4@& zUtlSv*b4Cdn~y{eWFc~;fF&P6l7N!-4F({EdFU^Mkb}y8Sc~beo0)>c=ujb>9j)${ z#v34H$};QkfL`HUAWcslPHtJo+T$G>RVmOJ#MRX7aV&_eZjN`z#<0u~S1%M~VDj!j z>9IAcM|)4`EPRjG9$kovEc_21Qzj>&B7l$;Kr^}EQDHxPW)zy4X3wl=gT zQ;>!EohX%@8$>v0Si}{dk2w_usp6%{?wR_wb-_fyF%$Trwwq;2>t1MVQGYeL_CjUx;S(0#s9c0cVr;dvZ|qwqJIo zbYJo^8L-~kyk8q!%A0FVA1itw&T9HN(?c~!;BDrJ6(zkIpof{5obG_PvzA4!q*l0W^mgOiDbUK;8G zsB+@jAs0KZhFGgJ>8AfR;3R1Td=o%EPg-Psk8Tl=mgJ?~*3D>=kUOSaioz$gX4q&r ztj~~%AAQw!?-DzNuF?9U-8`Y;urTN>qey1hixrfNFI!pT(ne~nh&+G}Pg2Wdlc31q zk~=JBP3mc@`NiMC>*yc7K$L{9yw%>UOF4MQz58+9i{;xh?;xCmEs*eb0ZklSi|%ec zAxDqfk3NgUbl>*wP$wFG3L*3j3RNCeTsasBC`AWzH~TfcL-wBIK$k==VPbF5-q3$K za4nml7?8zN8{=ur=u)!v=N?I#Iks8P-1ltZb4r}D>SdNax zA-$>NnWpaH#tT@{*-l{M3V8YoV8+2@ef^$Yu)XsXx3K6!<{TpEf}w&)JI7enr`Cy- z;!dW$Kdy1$C{_5B!P%hU{kPIc>C7@7NY^IT; z$mm}6ykr^(>rgA=S{K3*8-D15?xUAm&Es^&mJIE7%{r-EGy-f!7+&mCjT<$i<6chF z5FO-8D;^nCL>Zy7YemZx3&x+ohz?mpTo%@BM1#;$5Wzedu3BxbS&ni9Bsk zc{#b;gTYq)Gu<={6lz=r`A3f4wq=)3@bAK=_PLk;7ajl{^AiW&5i6MuyAnNJYHl`11vmQ5nwDjdPgP_kh0ad89X|K;#BG)~kvoN*29n&P2IvL%+;o=vR zV8bhSX!_KmkpE$|0SY*v$2nnq9mZGgOy$+GYcP!)ZBmRN4=!~>9=IiDpoDb{nEXO^wbl#)g>TU*g9G#a0HEiuKzxS@tZ8=+HXOL#GBNh$)D9Bx{~D8cOVo)32n1tYySfa ztl!IsMqXR%Cv4v=UR|46xQ$WDiL$PT>qL+`M*s`{MAHTX*_YGKA1L&&FPa~hAB=P&yV?rcGn5@F+Z~#Es1yuK$`i14=20|M|drzx;r1bz~F0 z=ktIah0f)v%^p#7=9S;F+fO!iUTm7x-H-efheq=2#{=(PAAv)By;A-G|Ki%ReF^VI z7V_W+&@_Fvc@4JI&0^~sVLJYjGK+|-OMuOb_!lGZQ#(2&kJuVEE8VBU~e70?HLnS z#R}$e1I$Kgr9~1t6;I4q{Z?^6tk=!(#HN_NsM;za^Z2zTZyrQ13&ZtuWd*tsKsL`N z##T^LHWGRy!KX#7dLE}^?mw5tRb=eIOy9IRA)#Kqn6BeQOjMX7uWQ2(;ZoR`#rS79 zTL$OWCD9Mv9Q!TPuxJzQ(W3L(ez>aGedoF;a8iMQH;Q0Nb~>~+_((s&KupAucicNz zu8w8Z$yDPuMQZXrrKM8ggS}&Q-*e)@>DI8D|E!JWL#O@f{7{BNe0z8ED$ytZZgQ?l zYP3CjM~~>RI3tV^R@#!0I@2sI|AZcga_a(7na$-zi6r_BRn}Pxipsp~T^uix9HO2j z*`=D-j_E@m5FXlSnS@1qEkdV!bje5z>RWKdo0xwHNap?9_<1BSbrUnTu*VAK_FjHT z`E=e&{#pe2bpyf=u$Cmfs3#VN&`&K}OpGJfSmAlHZMS@WLxj6PvdS)YaM2LbgxpPi5P8Vv5`J{NI;W42O!4s2*VIMOBC~`u#@rZ zUv2&Lh6lOm&aMnR2vG;h@>Y!?ae%$UKYwM$QCc!Jh~?|85qg1jT*1Zv)LgjxAKY~s z%l96eRllPmC*u+6&!F|hSe!*FMARd<90E`aMb}o_aO#F*J&aZXMAOlIs6Ytf<;CMLj5d1CgXJzS!DNPeq9EJ-RdYc7cnSd;2eC^z2-5_zKfU$U^GOYeBg1+y8BRc7r>*p`Jy?* z3=^+dny1+FPgB7JuLUeQ_sigIaN%FjM=rwG+a5kkbdFEZsEy0b3Pm;Cyex)&GueqF z$f#{3zqFg!Dm-!3>Ni@?Waf0&#;Uw(LX_kkj&1O3!v|8Pw^t*oexw~&zR~}@Mu60I zCgha4_U_6OcA_ENN<7k*T>zMpbEanyGFt-$5bZ9y#D5{wTC&7~{dNTPJws)j3i~(Y z9M7(^EERtXSGEl^T*+TW0u1hhR5I9(JA0!0!h1`o@r?_iv4I4BXj!$AKRE|{;m{4$ zP8h%Y28w0N*e1uN`HTfUTKOb28?t&Fjk+)xC$}HNgg?jLa`=190)4=OEV#*qvJp?C zuhQbtKM*(tYPjr+Tr26P-SfKYugJzOE!I$>3Q0I@VigYD>9VHMsj?^+V60t5HP7)S zOkJAX^~DVWWg!xMtFaE@-1=Pf`iSXU*m>SobRn}Jte=pvaqDm2ZABMO;znOZ%fe2{I#5)@XPztEq@oD)gHIERfjr(|bx)-ufsQQN zpY{+VTby{;llU8NQh7Se@_tLj&Tu;fcPEpjxyhG;LHCK7U7+*1K||Km=2;g3{i;MZ zZR8(IU?(u6lWnH53J|0iMvpb=8hhe zfDU_`xa>e~%g}w~FD>Bp06P4DSirTO4PyEU-q+^+cmSR9Ul~t@nh5ofZjabYsX5$a z@(uGdV7CE+!=Y9*1e>|JCYkRPyl>dV8B~uz*Ms`Yv1`X02=k$q-h9m<=gI~B5<(>d zDK|N-ou^KlS|f0kH(sKH-M!+cjYbb^ju1t6`#%5$LHfR|UG&TiIsgj~kpadk?Xd(i z#=3EHK;@NNs_&A30P4CD(;?{!QeNAwNdoXRAZWu_g*SZ)DAa(Y1Wa^c)Vn93%bYf( z>Ik2l=)QEoQXH`O#`>i5Q_$7OmeuZK|>JFm-bhpk0D|Y#<3Z5l}krW#UF+MvBloD_Xn5Y$KkZ3isD>V?_j{_5HkWq?V#Src*{m6Pnb$BFevO;#@7#eIi<-0p@9GjpVZOPyZf2BleOb;*hEqp}jy??2o&4Mu_U zx!mc!<350~~6Qvel9 z43LFvAh9|U&(flSKyLo68J1l9jCLPuJ&O@DEc%@Za9BVyD+Dq;|Dcp~StrF!tntiE z8lNOAnmd=kx&>ot*gJZ(Fh(i1_;;#L^?Mc;MV_|lX|q=RV}mFAPK;yreD-?^CfvQr zi}Bf7NV=CQx`%x(_ND9-F)SGpvSl2{G2hdF4bGV=JezhumjpFAL!tE;DB0g`bN?&R z*K&z5a&iv6X-Ei|w2ZMyrIG_2m&h=EtiULii%RB@lOg5c*jGrPGl%72u}p%99Dq2M zkZ_gPA;yxR4JzdLrpIbOA( zLRx_-i~*p=5*->;KK8{iEp$-R3ZI2cRDN5CgWnAvp~NPeV_0rHXaNwy+H=pG11$Ss zNJtqLQ8LM@aG#N9&>+qANk7A4<7bv;W)3}j%wX)XHmm-Sg02CJFj_jY$VM3<+<9?pZazqt7QSBRD7nBN{kVVa#eU!FNLV)domhdw|P*W0=8^@!|gB zHQUf9edonsr3!u0K;UEApRr+2z@Weh%Pp3Hr1P*KTIBtW-|1NGWlln0ohG_Tn-j^(G@AKxZ{-VaX zt&lb#%}fcqvVc||azVBCK^Ujg1V%+Fw~Mj{bUq$MLeLkev7DX$_}Ka|&$n-U?V9my zVgisP4e>QLNx?vIsahz7&?;2o0CRpfin|k0NvWcW5kUYA*9hAu1WX;^$B}c?T!f!4 zm2v}G=XDQKQL-^CV(ni9Ad>I#m|X#AL3h`1?QMgS+t09AC%HKAKW13qffH3|_iT(O z;{EuXwYmQg!@_u&&i7XrDgWuYmAQtyhieDVWnWA2QGKp9F6G^{I5*gDWL`9IsKfm= z5SI9!^c@Mi19h}zgz|e;Yo1x)sU27P+T&n?qk`{C*eyaG4d4XaX_5BIIw8lz#Ye5g zeG&gIVLvK_XC>)m-`Vu7fys~9m1sG~G0Yo`u zw1M6hHJH-u%5AzIoJtrc;)2(m6*+cK z7ow~Hd?qT2WRk?r-JybH z(IoV!l~KW6(?u<{Dt1P$p0Zj3lsFdYu2;5ZcWP7+;OkF^+?O;sa7kcTYfOU&0S&G1 ziw2cXyucZ=Fc5^#I~I&@8J30VFL@W~@9gJ;XGwHV==GgsX68Ww??Y@-eBXXB;l9y;sSBSG%8j$I(pGsJ_26^a=VMER zkCI&~y+(YFFyodfi$UTTNV-d7P|mQOXBW$16^+v0bpOC#tKZLR*U~4GIECaG({oC0 zubH!Fd;&w$<=z1$imtNGRNzx5-m!8{hDMkG`dRB*F$~MKbu#X=FzxeRF(k2jl?FaQ zs>li`a!Lw|NVZWQ9?PzrLgw6?g)OP!g0c^+ReEkiSrXNxK_a z#y~5IRQ-5;E%y;D#}?ZZsKm(v0O62Qrp^6yd@NN<3H)E+VBUm45iP0Wp@ZRtmB~q- zVbKaP)borpESlYscEs7kYIPk#$r=@O-5~A2DJnfdljNmSFNDk4B1=Gu?!H%#5t||U+$T*TJl@v`+sO|rTerSi~S1zFqp`( z#W6gT%z?sS#rKE-Nc{Z$nnnD6V(zH#8ZA;LDt%V_cYL2xkaQR89Sz&ko|xUO!#o}n zt#2J$myx<7>xi8~^qjdZ`2>1yNA4|9qHsB6iqk0*?~>)900TF8PHt`tR9{@s^Zm_g zrqe#NUKE3awd);!x0{1i{3oi-~6l*OrdF?%zsL){%Vo@5e2&Y9YSyZyc0{_Nm9;mDWbF%=mqe-e{$~88i zbz3XD0(#{Q>7aaOsid-L)pE(KMTSWOssonLtbw>8S;ckC?QX6c#pTG5eN!usjNstA z5O$&RvyYZ|UX=+P#^P;w2lvw*eSigaF%y+zSh&6k0CV3^+0DI~lwsjGk+o9VB|x!- zjc1{=V1>>*^U6KP7?v3Hl`t$6o7Gd^SgL5l9LKrJ-!*v3@ll;Rj!Gf{qp*?jv!*>B zCl`pB#v#$?rq7%2D+>nu!9;pRf@*QcD-qiYopfUCyp;RXKyK{$ct6)>{r0Qm*z`*M zPj`Fk84VA%y{!i&tS=_|i(AX5#teV|?RO_B2rsQ}qy6HOd=im+0F+V%z*^G8ip;o% zB@XvGSRX)$yAVZC3J30efHTwAQi;8E5&cP7)UoaORm8J9nffSIncIA@Q^5&TZWrhed=XKgG)8=q@i)ghh(F;KOV_CxwzJU057r2IWjDYC{`^Gghm zIIr~j>-M4+u7tp&0GwnmzH2!p!}LiWj$FX#6d)v4#&qIwUtH8QlJF9}{uk zM6)YYjG5wA?2}?OJ$Ruba{D8u7W#d@eS-s*_<+X>98uw?o1xwK zwNs286B2rzj*CUGkypM?S$pb$1{>U(qQW&E;}?8} z9Pr@t(HhG#kQF+gE;(gn4vJOLu9?EZRDr3X65GM$`EyL#!lwzBS~1-4T)_TP^=q1L zx$?k@u33#zocCCV@flmVbr!Diw8uKONC%`db+TrUguQCRF*b&Q&!Z((^w9JDuw1&^ zgH~BZ5v8K%01`)!%&X3`D+>UP9~pGZ8h1f*Qib=fLD&@0>5_THR{fqn>oCKT0}ljT z?2pd>)MgmV=#(-nDI+u_{jOExEK7g9N)AZqwrR#m7$tXv21xmPw`Md{#m{SjP&_Zw z-}JGiU_zjg)-7VtSMp}aWZL&I#;98G={~jWkUc(?JV44nzZ|cRiQ6?9=e%PRAHQ_B zF(`9I7uDRW*bFM>VwI6hObr}k@Bxo7H#6Wdef50%2G`hNhfNV+(rKR^uwCH>o8VF= z0Fi(|vfs(pXT>S+RQBjdBSG2jZ;9n{E^HedJV0PpoEj}Y-~JSoh9PF>fXBV8jAY+h z`1_GvajtMXtf8}sF*{gnt(HLT%8!kesu8mQ*%i$wNvY2|^o$!vZf@9GG5MmFmf5L& zLCQ81|BO>50~Q#u{eWXYId8d5TE$a~07Uke{#yt7Q@OX`*|x=Q*q1M-WtD^p$^GQF z4Vc+XQf0fps62CB71IPDeV%KZKnl5&mT{|X%CLxKf4u1D7{j9ZBcOs-hO2OXr+TTJ zVL^0$iNZAmX2#FWw?oG)A$*epP8}Q6g=1=SOkaBu9VO4(H-<};`gm;jg9(1$4<4jt zF(bp4r$EnMQO7s&oU|4C8TeDyK}nkuKb<|+em2Gujk8E|K~nx&_IcC4)AuG&Trxt^ z>%px%wNFs=SoQNI$tS?{Np6`@Dz#ALCR~Sj;%QdN4QKkaGv?t2o8nAer6D*s-v)MN=TjiZ>J|S6 z4wTgR&+VH4arn-z@dzy{yu(u*u=I6K79rg;8Kn*aj^t;Y?iSEiQ@u6IxRCU=x(Fs+ z#>lYH+Q-BoWOp3H($DPBT~4zyl%01q(~O4(9t2YEzZMcBA>&vp`;F=gxkemj&z~GA zk~Z79%rzj_)cUbQb|(!+PSY*d5U`^I;%zX0&P`IHTim%~Thzhv`u(NJJ8Wh@&2|A| z;m!qQTZLnoO)8a3WRqgB1nB1zwU5d&nG}w+HjG8aoG_XoW>iYrBG7wkPaVs!W z&MEjMU?OI7av)YeLHg{nV#uze&l#TsG%sjA)vi-)sTef`jOW46R2C_J&Ur+S0h{HI zdoYc6qQ^B20bICB>q{JFszP&s4#lOqF3T*&_?LAc++Lh>U@fPk>yiWWEpG6Lg^xWwi^I!(nTzFlKUH z=?@K}^xtxg7_5~k4)ti1X&%MTI4(gjqX*ZOl}rMtgf@YfX8NgKY#V*qZ4 zVX^TnDPWg&Ph(i@b;c$COk!NT7qf^T)O?1s?YM&ip>~At!0Y=y z*B0qz*B=e)SrF#?Z@-)Dez(HzWU0Z2wbxJb(BuMQlz{PxXRSqUqBS8X-~H~QCjbOj zpBvAzOpTv;zI}stcoMRbjTOkGFss=OHn_nCeVN57bb(#zP$${Nc31~!LpKOXrCEXb z+Z>A~{?C%t?EuELzVScgTNiYSu;Q2nMttzF3gD65Ry2pkJUH?U>cI9d-_^`;}4 z%~H@|<8ERGDJ~i*!TWj>k&T5m^0-!vR=OoN$n_gHLI*kM%BU45%h*T?>Y`A5tSmXET#4IU6V6An$$X8PEED+}!JMefW2s59Sw!N-GTr zPwS59QxL5}+eM!d99n=BgQcNOEUyrjDj4Txlcu;amn$o=0$GP1bg7%9P}k()1eo zz3R6v$J##5Gc!W~XUO#jAoZ;xQO3zA2W8>ERx)>|9!V`UKd)lv8_huBg&nbbd8(I8EEGS3u)J0Px&OD zWK3=yC=G!j_kC&+)i8*%%fe&#n-BFv}SK)(SRba4JaMoF;&j$~%yaXDHKP#a(-aK2{}u zhfwFYSOgGt@PLeLMZAa#=#aF}WR*0F#F{ypQOYR?+77I@9PLIVxw~Ww(@auYD<-uT zYS6>P1-f!i-Yuh2y~sY3XVS1o+aD2KiGYRYy7#PObW(RWgy(f|jBXB7Q@zjX`wRh~J~;&dnlsY#ZB6^i#-F8Zk=w5rpC{`-_c6JKu;Da%#%jQC@p%bjFxw4k%JZ*ChT0mGw18ylEOQB1x~*gt6^UG|#nQu(I)$5HKet>RA_ z6+g)*$;+KHN<$V2Ztk*419rm}`wv}wT)wa+BsOJsWv%oP!tu$NE;$A)k~Bc#Qgl2<=a&}u`@vt|F%yknY{Va0 z06~K`_yV)vW56P?rv)=&Q8Z<(71vf>1HON1&xOSd3;RklByrkjslijLd&FSCD#d`^ zBE_;-`_baEcQIq4gP1L}+YKNpqtq6$V=-lR@-a8@c{v9Uwv=UqIZjd$;KBZoZCuzY zGCTa7kXkFilF~xF=Z7|83p~hrNeW^8p6od?zVvf+;r!v0$2?!Rfxma^nPV0yW(?vs z4d3tfm5ftK9t5T8mb^y|rDT2Oc`26?E8b(OTilxRz8zy&a_oxxJT;>9De(IFhJcg& zbvq1;{yfhfjh`zm%pcd8{)wM$2u$`%o_p(WQ(t?Kv?qT|DpmBmg{k~$f0rv;@FXUl zg*Q{`l|MFYrR{XZ8MwDeOsV*3FnJ0UboxTjkQIYiwpCW^d{U!f@P10s?3=!K+OKvu za6ertAsvC;OwO45ufO~q!0GBJxo5b11KKCK8@Y3!Bw|%vs;zeT#+Kqb02j%q!r;KY zXDi&4WcuS={0ygX?25L>3cEy&*9i(_NlUYuZ9H)5XIOGzr9-U}0SLQ7K*jzbOLBmF ziIN(*_7IBkGuACEy|-&OUE}og4Q0^N0Dz#+y&*@q%SMoY*905~4=DL;@lOjdL}}({ z`ghqz_?=ef9lPSj0{mu`){5z4(Rh!8Pw>EPPg<64PXZn#(_XC1J8+fXc=dgSVabC< z{kJW~dhmv4?6EOD`y_1VYyyH|ZKIu=42~gng0tnS)WttScEai&=)nDF_R+Nl;*% z)huSI_W(ee1Vbkzdh!GiM%V}G{!gb z9N3A$QGEUUdFeItZ620O%yc&(%A2M~Slgy-kZN!!{Fe&zrq`7VE4 z4hV|m4Kib*ZR};o9WTS}8v}a7{W`{MO>a+nhg^I5zt7z-e`IVzLG&{=6zRAmy2~@O zsrXLx8y?+Hx_paEJq@5u*nuk04NuP&F}`YFfT4HOKaS?Sw^K@`+VB3BRiAyo@V(Sv zfrWQ*ER|9wDQ~Fbcf%r(^i!t0k6lg*l#Z_f(to@jwqlWCwiwAL!;E+i3?bBiaarWV zKQ_;>2v8xb6vwS_F@DYmQwJOO<|VsY`J1edB=Lu&aP5 z3GN7js5*F1>x8-X9ce{WXC{;5g_X&@*Up?plVupE7_tBWAOJ~3K~ykvGS94dp)Am1g}vG1++Ah=r{U2ZLzn1I{RRJ<=3B(1 zskNMRHs+susK@7mrm16h$aE%8D(RZIYRliJmmjXa#ftowrip$MKRT1l6*%VZ)r$(=&om$H)zqFxTzX0lvl zSmKRbXBX3;NV6<-uM?GD_XXYiTtaLYhtq+KNnds{QJ>v2HR@UUM*1_uSX-TZvIy^{ zPweu^XOwH{bOV-2s8pM+HIZXQk{0kx_5{;nxBh%GNy4;rSvD#E%-U0YDDEc5jOf3u zS9)JxS>TlijQV$Stg-ss`ESd!lI6A-VXpey%VYD`8@_WXI2t}ay4?K*rx`-`E^iCi{#{$F=8JDVs-qpQQjgzTTX%Fc0jUO7we5 zcPO2(p$n_O?Aol9*M^L23;$VvawNIa#`~U#`~DJ3G}vPq_EOgZa{1!dpiMn7fKB0( zeJ`aj^<3;ouFwB}_TD_sj-$Ny{`T2sM$*W#M#e^7W(?L0*j6BzO|q>sw!t>KqcJyZ z0fK-eFUx!3y&)zW_myRtT$6i)lAD->gw*Q`ql4wp0cO!^zU+XqZU1BOi=>i zrxaCL%24#&3u44*6m2I;?Oj=3pYv44Q*w0}wVIHw3dra((gs+rGbCq-!u@A-vLbzr z%$X;B$R5;bI>ua-t~!LN2l6bs$(@>!*Ht6}&LZndh0_+Pqemz+RT5n-s6WGFA8Vdf zeGfj)CQ2p=3MNS=G0?XM4+VomA4|eyt`(!#Zg59pD?4V#7JjYbSe=xcsMl@z31`st znaR_h z)P#dVl$q;xqdoU1jHugtgNB;slvZQqi8^!*O5Yrsxi?|Q1lLRZ^6d=NbF8M_)OHCo z!kvu3RwbpWM$&LjPC$zNMV4?u^PQv+++Ktx$L zrfQu-HX&t?kf>%-DmTjaMw%l^il^N6!5lc*ii}Ew`(KZuRtsuyrC(8FkUHOp( z=V6yde}-%_Q@`W&lb(9V)T*bTa)sv??cBAn5PXxGQI+ZuCjVeKoD_r++o1gB7t!9s zpx?pdAgrZtmNeCed2jqV&jl6^`Kb^8G*Z>~-L%axdl%JunkrI;0!hl+|GXEWObM+dCLetw# zn1b6GxtvKtQ{kF}O_JIX@h<6>Ek=x5=m=42R#mFC-)<=My+Q?&{zOtyk|aX9Rw|_= zXjVfXd`jOLrA9?jXT%wm-;HUft`GO^YZPhiIWXm{uhJ=#FQo?vLjaRzIp~detM#Ei?;Xr&owt_J)cHvD%vzflxMqjw3DdV_pDZ*J71_b7O0=DcAuj| ztz0BSCdpO%%#hVdFK(__Fyy|GY~6Fqh3T&yyNeQ4*KA$%6D7||CF%C-Dc5#I`3To4 zzhk|zw(1+EGSz#l!_4ub-jhZk12@>^ZYGz{I-AuN0N~3QL%}V$Or9a+&k{ zcFmbJ6jWZl%>Ehw;P9lu<#v4k!y4Z3Yc|Vau9IV*-$vL#-hOhFTBH;vU2n0^AKaw` z{jOD4_0$h_ziV|B!Pgi>bmVrM`1xlKg9lIb30HWzg3#)~x|R|bR*rU&q=kr9$P$FB zOFF_xd-xIc(zk~BR#+Aut%!!GYVCXwr)DNff)F;1*Gf!iV-pq1Nv>yDcKwn4qa85Y>Y$b{j4;(g z6m===JyiR{CS>e&pTx2tNjCy<(xs}6K(3?IZp4ev#t6c^6D9lQ3L;B*-_)R2&8C<- zhSXF1>WXS)lop_$Uk=i3e;~Y^O*JWa&}$Ct%m%9#Sy3UtO|liFuBbCAeMHrTU%d(= zF6vrMMCq=A2e7JU_5A(E){AQ9CtosMxQbwR4*rJSRG1{i)SK^Mb*H}hq5f3VCM01U zQSd-8+F&B+UPS3EgP#9dWo!n`4#A?8A($vOcP>8`lA5HWmEaDw2$M>KnUMV*)M41$h zOT$1YNJ$*mcUm9M`1@_?WT4)=;65dMT%-4KVH1w+gHG@4{!mQ-i*ZYV3@J)fNO0ZQ z?uHhf?IiT_FV^QgM*Gk)>fFd6!#|5H;h#B|zvYXj&lgp+c_JB1K@ZR%*EiBdb@`Fo zWKaYZbxxVY>Bs789;uHkkBnTW0yN0=r|pjv`lUgj9yS7Po4OYL+V#K>pt=BcT-h@& z@PG9D^pC#eUf4&!PLr(Z=Sl>AOP~1Cdl2SL z-Q=4lNdR|_T+dx2*LsokRFAC|y7ez5Zk89{el_9=x-0q=t)J}bbrM`>^(PO)`cnV> zP;G!-(~dVbsgR&ViW!y$tn(O-cK9bXf_6@*v>L%Q#@wT$ic)JcpQf^;&y0v~<}8Z% zUiF#}af}SQkT4p6YDi;Xsygb$HyfScSq9x9Fiar{d)a~%7W-JcTnaK8pq|?NRyAtL zJk}n}>RZC1zlD<)Q8RivI~V)9%x(VP;mVag5Vx=0R(AB%wL5uxZ_u??1MX?9>+m06 zyClsG{)2TX{TTCIsgJO{g5RHZ4xVbCt6te#Da%49NfNT0t*T3K>L@D`&EEf7$JMK& zPLPL%LP!=W{Jo+5yJ~#5Kg#S*k(UZdl5XGzX+qa3((WpbNlLE4T?G|T$0k6IRz~^F z91(%?u~j{st>l<}pT94(P2v=S#yIt%_q*!1y1E3)<6BKI%D96Cy10654|_(gZZO~4 z=ps*njBop?)#AnIBo>S@X7FHC!cSi0Z~4-J9>iN5qvl*hTB)Rjt2+tfn2L6eDC&%V zhTm2df)y5h_BH4l%#V5Ps$R^z{3?*CP?!psc`keACrC|Fu=6$*mLS!|zAmh53R9c( zXCe3*vY#3Mxy|P)c-FKrWheTKYtVJ6I;}kmAAVkY4$($ErK!1D<3`d3t3mZXdR~pG z6sH48YB!?a%eh4}?_HUceUP=Yy}hAh{aZza!@Se?)(#h*cQ?$0Xj`*!VJ^j19>rYfTMGWyc+dT$_mCfQT96LOl?p+bhD zmam>hmCc;4()2rlh^DR*QXOFoouN(Y8UiAyo%#S{L`r(=;H@f8wrYJyx4<@ z2xWTuy0VG1g1 zkh&9;SF3|Pvpi9WOK|!qgu;GSg3ni*)*Z??fL|p^7-#|G%^r; z4*#)H2KVhA{6$e&8Y3)?k_??J1sxle%rttBJB4-29xTM67>~=aMeZMX6_FrK2d#VOhOZ^&e+E^ zGvgYhXeopbw)L(c%(O7dpf=2Brq;l>8I{F<{lVm*9ytoC^YHXRq`NjT@gu4d6Mn8% z$Ym5n?P%tL(6oYBt!NIX8u^RS9xV1}qTYLN_LM=rr)ufsT8dRbdMzg@dEXr>+|fd` zyQoM~CPSVKMbZ?!hWcvZqzlNYa>qixY&Lj4%?#njJd53r+_DJmL$ z#p<6sdu#+)t)jkiReOK)b^vg6d5nrMKnYW=+GLXTt$pi8S}p2Y%SC$OAtmDm9lacOx+vG(dIQo(?MAtlMo2=d!-V-9f;LNf8-1RG@`-Ye+Unl?bUdd6 zL9!7Orqd5mpYwX@YCSUx>0OG_9w{3IWrL!tHezAe1U-~Gvhb*2KPSHR~pu}G_j*+F1^vT@bh$TYMNFi)0H{q2| znhW~P9(Byp9jP2KV$2ohlqfaRVb>x{P@gcVy;W^*{XA>^c0%%K4Yf_i>TNewwxIJh zGb_?q`Y@HH9mBI`>v|z7E6t)^&s#grvlz|a7Sh0OJ`fWofm+YOeAi7-*@DV6SI_do ze`l)3H`CNi?bq9W-4sn8sTfdc8aoXepRy)4G5fCa56N$4t(e;@8XtZ!8-U9%6gUxbc!uJ)LQwQ`J2@7kT` z+?=a@4UwrfHm?-6ntzPB#lj!#%`Fy+`PE#a8HHtRtlCgrb?P~bpI<-1)C;|BH;I$d zTlDm5H9@c!>!^oD0||U<Ij zjX>EROmgs^a5bZf`(19;wWKIyDI8IrMn7q-8uhG7F3Tr_gO}UBhLw&q1xlpcx@0u&o#G1Xd&klhQ9qdrq*VgI<}LfLd|!D6Ywa< z>*$Qi7^4-$1I%bxs7h1V{hKR=CFq>-Gc`YGWl~EK4@D)+LAw51(2h<8a*!(3w??jI z1OY9>{VOT|!hMt%Y$A;k6ZkQp=e@f+Phm%!4q|lO#zhO45YS^g`0dRQ5z- zI~0?umy_eg5;j9(>A@%jN$P~zV;GXIDPxQnwJ>jrQnQ_Nl)-KA>)rSZU*9Jv+Hvhd ztG*_4jVL5(ArOnx)fDYiL_Cmf9#PD`8lB|Q+xd3goA@4|T4*;x4~yz1$c4T(k|IWO z{iH?|jckQdC?*Q6WK+GF4B5alD}6 z^4d#?P!B>ek)%YK=;_Lm^5m9;$v>*_+th?3sP64(gZheuqX^+9_Dha`C9LTs06hcsS`hHrdv2k&pg;-@xg%99~Onu@C=l}S(}O_`KC?omM= z0MeAa1zm+9o}fkvk5EY+$#hmQO%-)poc8DBM}BMnASNbAF*=QS@Es$@>4|#7 z_vlgZRCsD#;h0ZI(sbR}ZqMAViwb$VJmMsjrIhzuYBG9Q@Pww5h!E%r_nH%~VV;bR zSI;lW9AUMy?n@*|X`#V8U-!ZOYGIJk1!J7vn0KNi(X8K+#6pg47GwuJ*ZIeYvDgt4 zqt2kwb~nBcF-}DkNt2=2&@r7{$4B?oxpwR>5>zRYCgGAE5Nj-@ypZ9-Ku@SVU^rj@Eykd73!C7bVc|6*2$7YJ518rtaKud5cU z6-Igq_nUxjp4a%OX)Ytl%DRtYf_KNr8@PIGPh0YhP4Z4pIMr%(!QJ4 zOo{>-$|NbcK2Al=*GUF}P~pWLmsr`0)|#tPnYG=Sx?jo+84B!)SobnKdlZ6t_1GQ? zWH`YRie#9j%Qa%E`S0XoEKD@oz?@3Y zQ70Q$y`C0x9Y-yDGi7e2{ufdm%?ILvL5y1H6j74@4Zsy8CMJ0;u58*L6B6$ zy-Ev2N&c6#qZUz0QDiAIq#LaJs6icqh*F6ZMKUo_icuE}mMBS_?gNY%3(xeZU0AS< z<=%1FmlNM_+$w$p?8~u_4Giwu#?;U-eFw(9L-u|2-nlJf9n6*LwNTZZg@^_FyvLY# zbdD%t41N7XsYsGCUCffC%o1kEP^6b>BNAPskZOkvAr752&AWc=4vM5XNe?B`%+gKX zQ8l}s#r4jqxWoUlt1gKJPSX@gyNXg51yU4Q!b#E;S;ll* z7Cw~&d0lC0W$mR}xPI&oW?150RmLSuU7jgkk&L^Ltun!rD@aLNW1HWB?!%<$Q7c3# zLDkiAik_O6q{K2#kfy+W5sA{%@BNwx&mKX!tEDKFU7}R=>IQf1s+cIn5Li&b9BN^q zIi}Ai=Cdw3Ns{KP@mMqqVeTD=?c3DvedBQB&4L`seQ&->Y`bx5@bTWUu41(P=C%}V z-6w^)#MIC*Q-fLhCUQ({3MfN|(RX0n%Uf5x0Qx3!Obup@?}NLxdEfgca_qZt4^uQ>PfpH(_h)uTmWk?w*Jwl}E$_4TV%elp%3-XgkPlsv_6 zp&*WQ7eivvC`vX?N7A%VgBL6qh2>Pl-f=;I!jztM!}V35pfqw@l;higsllvAKqOgd zm5@kMB>zjY6SX`ttt<~LJQKoN=sPezZ=|lBdB<%+jHvyWJ{Z>(B~S~++KQ4=mXx9- z)eS);3ZB1`^p}y!Qq;f#jY5(ppzWr4*NolGEIkxSGvk`#<$bDB+ESDxeNmwp)H;=T z6vu?ADCs0jo=N3Uc9kUIpOkjZ@4Cp7qC}5t^0(2wnI_UP48?)$-I(8tSFtv zShPe*;#4L~&Av=BG_<{~6M5Cb_|!PVeZv7e#$h;M`(ni2ab>n9A(ftW+1d(EExhR} zb*^?|-LUw-epskU>xR|$4ntRSg0|~KDrgXH6Qg#NM<-ZQgV{MFN>c5T`A!WD3*WB* zvZt3%`iBkf+UD(RSDE_`j0gIk0p2#dY(XZM`mv3Wsd(^k`l1=4Bz{BCfL;7no;T72 zOdqr-J+B=R`XFPN;g#s-Bt0%++CB1y_Fb%nc9W)!W4AL+F9p)fu!J%xX6ZHpJBUSV zlb-Ta(TG4jQ!|Aiq9ob_8TBsdn&K&1trYzz5C`Mc4bEa3#_@)T!qi~$a^dFKvq z|IShIe{`q#zhiVWPjfbpauJ6(mlG`E@alVc&7t$Sh(|exXT0O>VC0>$+qXsc=~*`n|8lS2rzq%r5}j0eZoFBQy?|1cGKk;66X_RozVle% z;rZTmbWQK;NYUyMg?136M#=*930yts1Y>a5HqR`unQO7@Vq(+QmQ5U29T;bgYl7Hl zIl_KRG-}GYklVxW{3hcXqWynLRm_?gLmmOlOa#a4Ke`G?S@8Z)eNs5 zbU!9&&6jC->|P3Fm|-bJgD7RZhZ zKuQ}SNg({UrdjT)Y)hI_lwzWE`eM=eDAj{}=sFSYs$J^LVtO&U$g_l#tl$W%m@-I` zgidr$u#`Mq+`szgOmT!8{`+hA>rXvQ4=36E!te3=UoJO}+j;poJ4c6oWJzKf$J=)? z(yvEGaMKl_^}|B>sTBla@3`p))F_GBHx8@adw=82X1V6T?9IS5RQ~cF5|J&)=eCBX{6FI}TXf7ekQj54vY}y)11O|6)Gn6BJdn;u! z$kKsv1~JVC>-mQ{ROvgAW97s+gS&2Nx*WBBORU?jOqV7$ZLLc-gVgXCF`~lsM{>O1 za&YSay6)uQc>Cq4J9DV$P7cosQ@7mdd&Gz2$#)!z*?={HM zzU{)CX|TbW_Jx4*@+(Om`!>gxyn^L3|8DNIu2X*xbd^Il^O9(EfbUZo3NUr4yR86Z z;8)JYyrBA1-!W5zSuai4@4km}LIs;=*#1`w;hB+T67@OG;lbgCRijQqmai6}i`(VX z3++&pg3Rv#&Gb&hdvn0^Rgwm1DT>Db3X2=Sf3dJ=41rWGJ$nW0C5#(ePNODU0J)?IH(#NTVJ zKJ=$DR+LUXoHB}1qlh2UV0>E)}%2; zj3CJ2yQwD$->*E8fXSZ{Z4)u7A~stOwg%u~~>nfe9Qc$aSQeMI0^f)Wc~@ zlwt%UO@SUx(#tfx9A_yfjQzv=fxcnhKe3IWK`|SAf~EY{k2mt&)lXB_9;pIpl63Kl zXO{9*cMk`iN%QBgc^8{^e%UzZj?us804sQcWgKTI&(Ot5(#Bx^iQLaQKl>u%xV{79 ztaAsb?V2g?=#0Bgj@A#uCvJx9up&#YVxnVq*=y;x2L6F0se$Nq&6=fpM9NhG9IC9@ zwT(wMZDq}_ZA=YinHtK{cfcG3gQ(X>Hf?3)#5jEiG;%Yf2*|{nZldo%j_-YRkCAWR zft+{VM>fIAiE*{vA~45SchNNwQ1%eQqm!gxbzjVqdy^G<;_P2hY?#YK)&M{uZ&soKD2B|qV zJ~mMlNr@nc>#c>z6~ zR`A*_uQ$qeDEBC!=4WOk8_V> z&TG%%$sa$-d6%6Bxp9*;HHsjGN=CE;VTyR;R>lsurglWJA(upGYN&o*GVRKVaURjk zuai;>=8CQZD5dshuq(14a2kJkO#Uj zf?ohkuXqK87xaqrT&kUKftUy`Htf4m5ax9^UNz4pi7{7b#{5ofgP;Xa{p$wlfgSY4 zXe(OSaAlGwLt5)5dP$ccr6{|huBFMIAW$hcqFX0brh0h&*j*fVBj26$LWFmDW_Qx> zN)HikhQ5%292z&hQ-*5(u76WD*^U0EmM7NZ zCPp*8gJ>i)o&Z`rh>6l7Lnov9J+|Y!ES>x*%Q?nHJm&K$`r{9e^JljW8{6LX;kVE~ z`D@(MKf?A(?yXC(<~!Tmyaa% z9T=zkTmQlZvkxtNa^wz*pR8U)&xPmGH<6=yR+htO!qnPfW7d3R#8JT|)@4nfDx3J& ziji(oCvoFewUF%IaY2%_u;i^gJ5dOdNH@2rS1L({YW)U9wDdHGG@WHwTV2ZRPH=a3cWZHXcZw6-Lr$LeT;H$!&dy#lbB=kBu@J*zTvn}n z9%qH_E~e{mcG{$S=y~JI#Xh|FC*0ze(}XF`xx69fA7*Jk*rY711az35yCi!WIT7VG zv+ZL3)dD>7CcMkWatkV|mYi0wbC~FU6sl^|31irOHN5AlV7W19yKcWSPlU>Nt!KGS z(Uc5|4IzmH*NQW|gaL{fm>ETRUIlQX#;cRwa<*RvGDy^d+#uYojWE))h1KmJ4l!B9i#6rx*tO6q zH5fd2rx49~h@b(pJZwvGCdAo1Ga7#$^?_r+sEQ@~#Y#cr70dh@=ISXcQ)Si#ul*rZw+HH4j+l-7!M3%Zx?SfEFviK6{FBKj^{RBg$%RtN@rowO7X3Vr!7SG9 z;G3Fj!KBfkV^`rP{i%afEQJsk6Z*+8+S6h@0OMi+ca2!nFnT+Vn+c);>amR9MwX5j`6=pcKC()eF|Ie*Z?@&4& zd6inm-?#_`T|yF9BEvqup#srP4VwE+rIa8b4aKkTqsA_613*`>PU7WHU2N)XWx#xw zV!8Zs%!T{1Vj`^vVEUluJArfkYC~nVMmI!N?N-_|SSlis@LADN4nUV;&4X+(6#h%g zjF4_5KF%zNE|_lt#W^2`MukUiO#-N%eGIK8<-gVV)5HZvC(31_?U;>2lSwS_rU}>G z5?$@QNq!M17!1_@7~Ohjm=f|Nv{dW~-TDe3li>PcJ9>kP=ve|m6r6*w^&W%vuLF_Z z&y`r<{ew;C_cy>jt=IK&o3gCKC*zQyZ_+MVsSrXE6c$71%X-XPi$(TqD5c2cVR*tI z>aE_=gLJ4x*$P^33hUQjU-8(_SxcDF3E$E1AWi3^05oH2Oh?#MEYrV{#!n2-zK4=; z$|&ykX8&?DW*E5j_qT#Y*C5+$g8xO1x>@b-xHd2b%crSmmj~+etI8U2@?;wyiy&eB zaf_XXDFHypsRPWF+l*O;l*NtCF+{k3C1G7dUNlLwg#+lz^i%>SLr{5|V0RFle-#mv zvYvR|0?|M@kNPwRz>=$qZXtS26QptjZ<(AU$P6BsV^ zXS{Q}SmKwZ2+7MMa;`+p`66Z`GcS=)TJ_Dz-MoUX5M?PCHQfM1bUD62Li>+?3|1lS zKYi#i_%vc7YCJ5$&gPZ7o7v=o%P~CE?(e%o1%Tf(?=&e?~PYTu7eL96$Y7&EW?fDm&PF4_^|S3 z?aSJlox>?Cto934PReu-mY5xxMn0ccy@Ex;Qg=qcy<4W{$rfp-*+D! z9lG)oQO)x}!+gii;wTtq=|rC`P8+IHEo?68Jklu9%@iAya1PGIj{Ph(M(b`r$e1vMn&vaxZ$#QMgd6sm+p|?WEVZ$4rR&dYb>&hMPK1lroNe+KgOm*&)M{Glu zC2uAe7E#;nCu#EJyx>8!i?v%?SeDa&h5LvW!bFJtW^qZBL-zE+kW?F??>OIB*oD*1 zdwUX<{MWgJUs6YTAan9??qStxF2}bt^EbO6et(y~b1X0<)k@7ogf=H7;m#t3WC)?k zsa3w)H_TR46ha=RZ_>TEeWZhK(OAS+u0@{_1qw4QmmU|!SgU-UE7^9(uithMrn1^F z!Wdb%?n|>&+phnu;DT_)8!Hl5XjQ(=Eo!Eyzl1y*s+O%GCl#5r1QjLGO9IV)Tw^1p z(jQku-E9IojfW2TTxGf~LW|X9JVRt&)^We$0m=c4bJ;bt=~|yJbBmVC-p9!Wsq|D5 zzd*xy(S@LDdO~qcK~raJ0o;Hz!x&|k*sL2` zg+-eB@53st-e!_{)t{eBAVX0eUMgR}PHKY8WaOlY>d10JhL6c`vb;4pRBxFT>Sggap<8&V4M2T!K-#s2 z{$j=6Kh}v}iyxp7n6MKsU zF2L9bUgcWE+J$|$=@Fg0O7!pG1A(pj`+v_Y64Ac{?_fnt9*5jueD5!=R^v3D*IvU$ z3DD;jzrpma`ap8HR?DK75bziys~`RY#>Cvt??M3V77coXcCoAAU&AW8hGC9+ZnAoJ_a z*j42i`27KevtMpDY?Nr(G}QWO}_Z~b@vDk4fHdR-e01N|*1iFwylKzITSR=U~?PF3Du8(g!&C+YfyUbWHpQ))t) zbyQ^V>cjEHsdq38B?*3S8$bUJBBFc`y`ka*OLtU$R9 zxUjFK+=2P>aFnK#S^T37XmaAOI0gLC^OkI18BDQYJ5{jtp;vW=H{%-54o;MMR8#6a z&_8~@Nlf{Ix5sxN*R)$Val3NO(5tG~rMA?0^&hiExdNwX75^uu(hU2h@sa=x?)&Rh zHCBM~a+R}6sEAF@x?rw@Vo?%ppsBdlPrGB}ECohLpnfYy`-#%$m3t&jdHTh2me^Qn zrFA5`UhTKI$ty)BIEERE%DgS(XJLV-b(3eQ@@^Bkzu>Rxl(YEhQa@DnE7~L|c3E_p zrf9-N6GMoZrax#^4{V0|gy{8_?O|orxyxd6ZOY4M#Nq)8nE-eSDv1X&2KD>d|UnZeRW9c)y4V5PF-zU+=!HcIRoM%Mz zzFE_a=Z7=T(;05fYHuDMKmWAA?tNd&eVFF~(TAR&GqT9?r zIU@)7*6JTfs?&QFSPmbG9H)3>nj5Y2O@T@|TJOuZT%d>yB}EgReR9%{ptlMXPYbXB zFNY^hVsl3$ zr0%aYLWO3;Kxfm52pLZeNBd%F#AUdDU+d3fQWrFms9)&NRh_l!D}qY9kZ2g>Ra9G` z(6SQPUq};(k6|JS5EpWzl}EBFt>DZZN!o>z`;h<63?k)zUGAN3fG78K}HBXcIsON5*K;}R788~t0QCZuj?$Uqo zNnex-Y1BTLKik0yW#g_^q!>(5$YWHSdRvhWBe0eREJLnTS*-SOndC}o?%XBqag-fH zs?W8Wg-$&;CuD8J_k@6;OmC2aA?}Gl z=_-WRwi0s&$GloG*&VEpNi7RnNdsycVxvvGo?9ZqY`)h z)EuXI24wg8`U&K>+aANmg4p*-S^RaD9v4cD!?}#S{i->Z@VR8*Jn2O4c9h9WqQAPY z$Hn50H*2FBdfe?90*#O{Rs^ye`Ag(h``wDTk7qlHql-TwY^^=yCCd-jJhfwuV6}0= z%U86NNA%nCRdNKQX+*O9$Z0S;jp|z)By}SP%%eqC+mP!7bW*ucYW5Bo>1qFd;cNS? zbW&K_)Ko)B(uP_Ln635m))A+qV*O(LQVX=E-c=N`WFMSWcpGqVdVjjI6PKl{F`O(I zj9uQ7rk`FB(5S0^Tlr7Vex>w$T-t4yaXKWqbd@E|t(Z8Ky6JYr<m*QJEpH?sGqJd);CU*{qwOo_) zg3b)pDK07`0ruBFZq+FE{pWB;+j4|1-XnI+ z$k)r26SUU;-wf@0tmN!_igUG)Z!iD&j~A-Arn<12D?yO_Hy|cs)O>7g{r=8op}7aa zBKo5l0S2RC@5d?*T@XsejR!`5DU9Fuacb0)b4p-tazRi0+^P2vjDP;wN1yi)!P9jX zH`q|P0J1aQ?mMmlWAHOv#%-@FTHQv3&T_m+jn(7K+99WOCsb{EJz5H1z2aFp_54dP zb67QcKDgyRI)wYDN3`kbvL8oKhM6}wJbgVf6AJ9R%^0#V*fj9$Ic`bdUa<33+1C;e|n(TN)*pyLIJ%M7Nb{z)8S)eV6TwoSUn*~ zHIcrUO>1V|cUFp)tAS>#r08`k@~b&3;^M!MW;O52mxVA?dF90|_XNv<<(ss%IR4y< zz@ZW%g#ldGCO#)MD1uq+gER&uaTe-V=7{9D&3>XZhcmCart@VN*HF=lv%_WScQTR^ z1BQw$dkmU~PW7cKU!P+^@o9o1@PbpaB~K$$y?1lxM88F*9rlHnfs!oWGuv;wfilbf45_UO#hlmSL>je`r<|9$5N3 zJDu?9meu3^ zjZU;N;#(OQOsNs}PL%j4Sv6mP>iL~VF>yJmuLsd4cd!BWwaxX_%1D1LP2Nx@;F=&| zu7&h06y7*;@*4juk^T!sRZMv)-^uVAt@(?`V(c?r`knm)aZxH&nH%RiW20WnT*2$? z)4G&^M>5n1cK4uITfBo0IILMts@4nE5ob7=!=3$Cc3)5=qT1S-qM8BK3bDLqH@(}S z&=zu0x-pXE+yRu^8PgXBNRi5Sn8}{L^OxV?Fl^2Umc>G2Q?B`CqY#IP37C18-xv5D z>hn@g;=tB-D{G&KK5MLBS)*@{`Nw>;hVB|XUNN9+%*m}D1%ch0U~Q6+23IK%8wPn> z1|lNu^GTm+72gv!jK3@IaAob)ziUce{J|Vu)wK2WAvGyXG-w6_Rip2QaNe-NCx!!W#61mQ|zm!nEpkCqB=*YW(SQ3Qbm=&6n44quc`>^AcB&zKnf@eswnuzff*GZegB68-t_epq zt%h;1@=9^HgFNU-Z!a2eT+cNB=?sV6+6LV0r}hb8U!NBv3*T<9$lh;Z3F`Mo_~dJ!X!Hf9 zcmMcVzcj*1k&4K~HWFGL>r^fx0(dPEFB?arA!?Od@~VN&f}6RCt6>;)SoFWX^#<;r5DleE?PfvS|YwJ9;GUP z74+5Ss`s1ld6>-omeJhQw@fnA@Z7t&erp`vR^B_7+MXiy<#(okOZ$hcBtNje#kpM^ zK1)p$5mbt~HC2IoQ@hzIFmxT;yy@@_yneo+@O3pOgTsd~$zf&od?MvX6YoD<@}SoZn^l28@SA_dy|R3!N9d!GCmq%QNEH{P+brH|lO z!vd)*QP(Oa_UHK!Z%9j@weF92M8TpkrioJpze))=V`*et*GA5Vb1X-X5#%^N9W8VB zW(jWMj>eZpb%Un~hu_cpG*Cfd0k3mpFy204&;5OzTSiZ&hS>dtp)R1E9Uad$*5Ucz zQC@amyQn=anPy>KO51OzJ}SyW|&5 zrsDyBP_lc0CELD}CiQYy5Axfm91)L}jF1WzkO?W5v*|^1!Btt*!S6g;p0-u2JRUA1 zn-q-OGC9s@thulF`RQd?uy$_4ty;G^^m{gcxLD$wbVxDxXt6<5!;o3#*YzRX;+6^k zc59s7oei~k|LHuKQKj@{^K%pq8lp?QOPR`CGl2_a=ag0MVyO6@VB8mQgov(@;s{{7 zy{3UdmG6mGiu3=4arwqI?$am;|F)&{aCNk5-{mS3Poug0XRw>k0jy3=?)_*F6Kx4e zU~&QNt*^2s75t$=H2i}DE3!M=OyFby0`0&Y)ozU?g|)B?2~83A-Uu**CU5@7r%ZE* zV|Z~aAQOKbCx$;9_zNS*b1y!1>Qn4vcdIOFh*xA<>#Inz-`QlYRj#3q2zozGN90x z`}}ohyEoo0(xi!aOLsY(f4(hJO(`bg<^;8Xk<-}vZYISg|5tMX7yN5f+Udmj%J)Dn z(^beIR0;WM8IZsl=V0N@kJxvm24b% zobUqj`H2tXPRV)ev>G}C{(~wjS`OPo_PL)eyg+P9WNQe0$gwlyO#&|Z3(+V+BF$&B z0bthSPWjH($#THU)vBP>f$h}p$;l#Taq4V90C>7jZ^9w{u$*Y!)lGtqpd?pmRwLvl zN3{s|i@7mta=3%ViAjosh0whiB+Xyk93*HhYeqjOxpkX7tMOT+e*Q?O(t$9_fe$4| zb*}jE1Y=0|23P|uIXE6mQlP%yA?Sz%y2C!nYDh08od{4v9%gee?@*dUigD6uja4SHGJ5ofRfFbX!GVDRyKdTm-d zP5~1CJY>RaN7mENRyDxgFVZ9ok@>+r&Uv3XJW{)3kQ6D7x{R0O5!whI<1Cn-R3rlU z&aq^<5*K>5h6IzkG_%jk-z85BRj%%QdhwsS@zu#oUwBA4cvS>2nN&;hvm7rO5jSSb zc=)U|i^0c##Fqh!CCNA3K2>S$Ht&+lmhvPOzHY;iJ&h#GTXjh9?Oh*6`|ZWDlO6x? z%@*@f_12go&&Z-=fPb?`Y(E(1&1xqV2AW<$%*xjmdW7&WJBaGh3%<{4^=29_amn&J z;(niw6?&UK=YD7NNNUxbkDZ+q9OQ$diF`xOIlFc>YuM)`Te75(y`4wT**@D$eoaUD zV19DR^tGMXL5o#n3Lfl7*`L z4g_}0nNBxS>&W8;c_NQwy*L`IV)}e*_PHlDG-Pbe_PZNou`{ios=%&{*<@-$2dx~# z6mcT(XohO9q=(~@65!SFT6Rm4%zBCLOwR4!JO4}!>W49EJ*C1B{Eu4cXDcct*et8+ z7O|4k2TEEUW&2u?+}Fv@u~0Cnem!YnKImM9*9Yqi_NVHk!7 zR$->TKw+9Tcyu+*iMxIr)0aLWPZ-1L(>&-3&812@e&ROtUZ5Ww-it9?Xg3Dw@M^HL zEJ}At6<|*(=~IPb-$v6Ti(ElazP@c&D3k99#j!ly0jh$Ln6?vtaAcrSotTqMrU^9hADIy_WNCnJW#{scuBTKjv(B24_4eSu;hcW zg=bbHI)9eHvuw?(GatrJa@Kv>T0N$RfJ`de+9LeZNmPBVD;rs8A61H@E=Qp2h8bg5 z(V_7V3#md%obh3IGp6EEm$VRijSp+Hf0jYZLrtTZ2q!Io1CJKmju#AS;CWg?++~RS z1c&w}smKsHqA^30@F|Fz)O?v&?BMJ9I8#o&?tqZ(UmC@|R5D}5j4Z%*X_54&Hwi_3 z`ydWH5E%`FigR{Aae1aGCXUncA4WNiR#a6lHEO_%efbNc&w(U1zxE>`vH>Y@Ls2&o zqrI)jvj%%DK%2>2c872niGx~3W$5+;lMiF&rBcg(K^T53yzZSmp7BxKnob*MES)7` zfV^;V?2S^bxfxUOvsDqUp*5vgX8DG@f0a8!nWmi3COZME)V#s0W!xCt{%f;xy}H?^ zv{IA*SpifyXaPwVTK2Xhx^PiLf# zhq~a`=QG`&iG+6&jXxYdmUk9TzeFZB|6G8^ouohr)907bTWDQ$9(?=Y;UDZ??DLoL zYE#AA)2&{7TF!PChg%O86d;qK_Rq5MtU}*CZ0!G-2H&_=A#C+tm2S)GYh?$?sPJmr zVA$kpq{#Cas`<;9?4WT(Ce$!T^m`CA8XTV#$)!yYVPb{BY`?Q;Ma(7R^6|2^H3t0K z(fg{C={g#BRaov>;;j;{7aF7~Fa{@uiK}67XqcQ=A%ubSn4{74s8g=#4IaIrWtcsz z;HSiGEoY{w;+Ii=7=s$LGAPZFF9|Eiu7Q74NcOF?3MkPn^cp)IEC4Ds0>M77BU0Nf zmBSCplqXo~ecjUN%0;q6o#>*Hl_aFtr&mGLa_f%x5YvVxt67!?YRK}bNN}0FGBQ}u zc&#Uff~atK{SJi2Pl+sw+-mSiz)`?BLxdl9Bz|dax2&v`8jw~mN?gCDoTPHglM%z7 zD3R*iv|60dC;XxzXu%8Wmpd*!T!}%i$f}!EA7hAVdevr}2?ii69BO zQ22Mi7~2?~Dv$0A{W)S4;#}TOzxp0Yt$fp=c}+%x5p=R5hOjq;ER*>DGS3=U1B=iq zghCpg&-8BF1)gVPM0Stwcn1x!icXGQV^N?TS*f(h2tas%)$7afFWm98;xITogZ{%E zLSjiO>6rMkoCTUZG^4_SEb#myb@IU7xk_MP<=VSca`8i@Z2y=_JYkN5bWJ4{2eMAd zR3G_5o)5H?4S{r^P!4>YRs4lg)UpWo0I^#g{|akgu`-hDy*9VL&8^7HO? zy@X5V|2vZI@iY--IQ^8>L4{zNyl!{pjD#k(x?8u8Q=f~oL=TZJS=Zze59o)OeOA33?slr#xB&GPiqJ5N?)_OkW*rUw=Bf@>m6NCK4A9II!?NnY{PTdN?gw zF0~D7@D+N%8j|@DB;6&IM(s1Z3?`wNQgqw(PI+g1;fm37{Q3mQXsaDF7uiLx`x~!) z0zgWncgs7yz>!{tZoCyI|B8Tu@JurkGeekPE^)s9XA05MYtyIT~W0N8tinuDb?(m}ei#B1FD@rT=CjseJcS8qZ^|90&8O zXM`Z(0&c!y%7lP1qd`pmyp3LT`)>j=LFD@K#UBd}f;Q=gzt^|c{9zy1Cq*J-GKiPB zi=#MTlDE$m?b{gDujf{+PrvO=R{G)jd)z_>2|V7uCc!E>j~+<+2JC2c{hRXmX$O7{ zWGob@++fezUw#}=TC)7_r^@tjFnTy6P^J7U4z_IVD&9wFLB?UIAC>EW-cJ@33}L6HpnXxf+S@ z8Ay_6iY_p#>N1*CWsvKrSTGpzpxZE;chyeTk3?3Bzr&48tPK66Rzn6YbX9VR8Im(Q zg1ay0KpC&#+YmWBGiu)aB^k9w?9BtJTim3!Bo)YfR(Wtj$4sT%`J$_FE z@^z!qnj(yG8pA+aOCy5^dK4dG2YWXJrr{%Ik@-c_@_Mv$WT46iD$9*b?Mh!_9(S9^H&2OY%KHLT}I5# z&`BF!NGyYldTpyVdh5=LpJUocTEFwW`FvwA!%q_E+9)6p-A=ZvDAkbkE@aJ9YKP5lsQdFK!+TszBt(hih1am{V*9hOCxYdTU@fmFi}VlC z8pvlQ7j#Q`3vJ=_L#L@DP=m;hG&roS7lKr?c|+u|a>Frq>CJLe2;p94<`J>>sLrfY zni<2r(ev)8nftxv(e59co$AlZQNy428bI9*wu#BED_Mecwc6CIW!%*gM}^1o2Xf@9 zPUoX?eiiSU!UKF<;dK5c$9GxXS}fA~A`tJ6lud7XCUFTh{>%Qgo_uMa6Z#$tasfE=m zP=ga`KFi-93s&Zn#q{AeCB@9B)Im~c|Gdtq?1~C+?3y>Kzbgy@Kne-91(dX2$Qd(s zhy!c%n*>^+Jgws_m=+NW+Sp{K?+J6uSnOD41*Vyvi<-$gUhul?`8E>9<%hYrKz?}@ zS5VssLN+i?!S%E@ne$|YiM58Rpa~rP9W6z zC9Zo}PJCUGjL?)EXpO9^kOOm)eg)5IEpl_^d;X!%aeAk^2nRL@?ebgtyXg0hy34oecUr>-#>Bfsw*(V6fRnE!0 zV4)T8_a}0uAli}S%|ij2PGhVeUv^I!Ol%3BTaqQkq)>3jVvyN$u5whHzyIvKMG&QE zH05Je$|gyNz>`#v5OySzZ?|P~()CP6!fsm}{_(SC)zYo=BR(Jh>n~RdZiXY0W-qs;nxY|k9%oP+y%eInhrZtXCs1fFzvD5)P2ZVn(X^_Grh0y=^YB!kjsk?R*lordFGhDnVo1eyCNjWW#H0yD?^HBb1FaINJil)Dt>|wwX zv+i)*&op-FlKwN7MySb0Kr6R3;pZfYQvBUbHBX;6ln|cAFmI2Cpx3dD&hR4P(a?A^iKvgDl_YdL2bG#5hmoBbo?WI%P5h2@883YkPwnV>Lf-A~E^Y!c^R`$)%oUUf;fl@!nkH zb-Brbjga`wNSm<7+O)ga+{l#8xo_1vP{5a(P9o;=jfp-UlG^5Nj^z$d%PT5MZ6sr- zk2)A6l+$Gop+YF!8QCB1boI|@^EKkw_|zG`EUhG>zukVoJ8v#Oh5ILKoEW~w;t|y2HugvHvA*R|W+mxgi&y)b zKBWRiBeYp=uAY+ywAd>zWLQsHG7p(ZiajnSlrVNc8)VTz0ehPGVYk%J;OH z9Waa>`x9aK*f@pmH2^!q1B3HRZqgl_+C0Q6LboALX|2=aeOlGR#@{TPm9>i7w`30Y z#~7*{?+M?iN7Ca0%863)QVw8#S}CKoyuZ=`9kW^7J`@u`^P~TgYkDs1z z;pNTf2@cv!{;wKeHW_B7M5}Z6m8b^K#)MvA_}iH0>U(4(8&by}oGR`qmx)%E8i$ha zSe04@3UmH36@m`*q2%1v=sF9XfKB8Alyg-GgoVZ6oODj9!)nZVlQMq*Y08&o2(@Ht zD{QJ9COkHV=v}D^`ON+LZo_P@B`r%Ko~w!FFR%Iq`9_=r6qHR{QE?#sq@s#f?v}+j zq7_o3&-m9eTj9UFG&CkcZfb_b?G45JFhW^}HtljNV+N@b5JAGJTrCsdr!pUi+ufcH_x@iCit*;zkQs=1m^!0DW97B|1#$ljv zPNYM@@^SkSdCY@)OsmR~@9x))@8A}dg2+#&$`tnU_J6}wP|8Di`Wh``!SCE+CT<&n zxyausFa^~r5Ri8Lc~r1){RNISP>I|TNm0hAiB@5`r*LDbqs@g)sv|d5>f?S ze+3cmwaG^|zNC6CYgIBNg_NXEl@JzxadQ<3!#L9R&;MlV4;{Z`i)3acNAIWUlWr!6 z;kBLh8kzB)#GhC-^dZS19@!R0+K`GhV|1fe@|VZVZ4H6hHd(At3mMhwsVSsQ9MtTx zZx&N3G~x+~Ey^a>)+41fXsrEjlA!F9qw9_`MZ}|SEes_^O;53 zt}lNpr5xzUQGA+z*?ne`i;m5kxA5X0*c#7kabrh4zkhEN8z8=gS7_6kUB4cxtxXUX zj~h-el8@kG7{iS}`;xItVboIT&;0g^RrsywVC<#?Bk1^atf#;2skT(rNpt{6pDB1u zJ#^0D6o>YhUH{{br8{_5>R)sZvB^kp!^(Xd` z_ybV{)dEy8ngm$u;aeXW@4;fW-(skzcP^(AfC_SgJGx&ikBzv$v=l@tW6y>+|2Z6k zVDpygov@ET5VMzOW(R4&}_%CP^->!9ny)Me*1Omg0WNO zolY>a1GSKB`KVJ~bZar5W?wCqb@U??y*FWIOW;}KIK2dI^Ly!EFa&VQCT?Aiih4H+ z$AW4vZBBVf8ODGcBVpJjDhB%%is~z&*(RA~nc5vP%1|8Lj-<1j3IuGA4+%&J&l3%; zRtchzgZcmQ7YVny`VT}MaRI%}QC4tsme$)pp~g3-2^#CUdSw}vMx2C~>jG8=ThlKy z-E@+eM8*@F5!^OV4M%=n?k_28IVMlVc3C3r>B6>HI}ba591vM7FLSo+a$M8$E>LFC zr|)g}7m?iw_iJ^CC%!G-x5oxqF`Obr>Wy0jp@*Oe`u&c&RoKltsTB4LeuuN$H6&nd zWJrz_HckCpcP=z-LUD41m%8ifk2#O}Pp*~wFH6MOe5)~qZ=~w6-Z5+ME&bZ!mSdik-n)&>?M5o;+oXeF4`SiCy!0o zuE3bqfjH%B1pPJ#qikmg>U}<8aJWuZBr$2uE1ZSDw6vi96BBv?vvRgpV&}!@hGm2D zD}1D{AVs*O|MaWjlW$!b8h*z~wlCZw2QC4xN3vc2l9st7QvLy{PyS=qds&E~F=;Tj zk{S3Y>Ja#j-bB?{iB5IeL!FIdvaW2~!kf#29TQ49^5(S`M4ONNJ)P`*YCxcN8fqG* zAkzS`8c@qK$pD#Z<6XioHz> zK%17^a*6P^JqIQ{iucn>dec!srWAs!ojEjMG`Ou*>2o_9I#p+UDL}tvuy$8awyN?R z7-v`0McRw%_`Vcm+J$d>Y0YApU&#BF|70uirrCc7khcr!>j}6Mc*HcZj_E}}ZNx0r z3f^8BOsNZWi#J<*>d)`eAmhWpSEJ>YP++lF|3jwn=6`Pv`oM%$1^Q_xzhDjES4B(a(uUwHu z(+UAMp45L#EomW|Bjois+;2}$RG23LMHcI@KOezGv?8keYc=T^&wHhfZFE|&#IBF> z6~8y%6#=P5!Aoz;FBAe`Q^PHAA(!HK@9RpG+ z4N*`%B!;5Lw$`Zqrfzigl0$03fesUYky1L?1=U8S(1*0h@C&SxDOM6F=#F=&e`!d}_{Al+;;+h@s~Yj=Lu4NrL(~;a2ZBleB)8T5_Ys}IopBX3DQhylbm6-pu2i? z)D7R1b!7EZAZPzoloa)xd=w9vghT`ff1G|xh5SkT0YmSk{WX6S_hfg~qdv*E10(SO zq~Yu}Iji6}g;bzwG@7gDig0D~f*JQ z$#y%R@GBuf;aYv-KNO3g9Mi~cKmdl1=bCQe*2dTmuED>$-fR~5O%rw{Tw)Q#Cz~-3 zfxW-E=)<$SexquIAph14Z(3$Li9dpRShNhK;dfSheP8c5<>JUcIGVu75^#yxUPr-Y z`IhS+STLraz)YFZCWsL_2W`}#4YF6%KJ~wsUaP*qNQow!hOjg8(9Ih~#5l4{IdV(1 zhQCkhLOS*$vQ|#yzXzuzq(ejcJIhI`3JP_>LJm}Ab-`2^5?@V&@3wJTk8xp44b%)d zLgQ4ROCqKVcwz@17(($o(p&&&7paDxt{2N9O$VuOUF%cB28od(@teH+j2I2_H6z@o8*z z!ms2O@)azpk&E}kwvf{9vB{A=!G7}t_g8qS7NqLvR2;KQ&%g9_QB>3;bz!hDKQcuT z{y5E&M6t)#1(Q%MyH$VRdnsgR;A(C#eD}vWvuQtd^bqO}qw<-Es|)@Z!H|Z`M#=8YeOsH9!5~A8v}}dNigc zJ|3~b?5Ei1Y*L})p1rMnhny!u6YPI+^qgIWH~1GhR#VoUA{p}rs%`kVpYi^AXH}G5 zrP6V=t~T0+zf-bPqAty+;Vfo#`FAVOi|ivwr2Lida{&qcvJx8XAV#zLWbw)5?v{x6 zH%BkF3Tx9jrnnu|o5eu#zC#Smn4Yx#gko=E=R;A@6pSn)1^c;?j%cfFH6~T-{%=Aa z+PtLM=DT+(6o|RgH@|S$bFV1p#?N#+T&n1>f~F`MQi^l4%kTPfp#6~`gCr<`c=*d= zN7nY_%f3-`yQ!&oY36vJzld54n|#-jL1zz%HN!x>EJEWP zUZd>#h&1;jd!RmPo2xqv6jkrPIf*Hrm10D2Rl_}}L<=FC)kB>h+|`PdXO$B(MZgjtD-*1fWHHPEg(vS_cco-i+Ks&oFzq5}{2uzm1!Y8in z0t$Z*On{G}8dkNaFw$1lN5WQbnO3vt&*poSqEBGJkBv6AGxt)pH=l~4I{y*1`I!(K z5y*j}DPHNWA6KMH^K=iu)=!BS0gq_Bed@b)?CBb+^@zTH!n%^fx>_R^cUk+QN0KU7 zTU*j@fBVN-=1YMy?Oc;>14bq_+Hk#9NS9Wz5^8qPwR8@2Gtmk9bBJllRM6{l_Q_AVy%0bH7K^sDRJ9e?nnMyr&NL0qy_M^c4(oY(ct%yAxc426uON4ess`+#M!3 z3@*VX5Zv7z1_%<|-3d<6o%`PIKj^ORQ>Q+uD%0#tj-D4t2I!vI-g8Ryv`g?~?2i9P zdKKOjh4xBT_2FP=v9&uo*L>5j`>pJUuu$<{qk$y$9CFRBcZ!z~T0l&jgH5Nc!QI!mhY0V-c7qhSAYwkzSyO+8Uo2>o)MOfRT-*p+575*>dM1f^?ojxe`kJXMj1*U zR;U8cjGZ?vFg2bN(U4$eN^#s^Gjp0r+PE92s(mV0Dtk?M)q>?qxVV6&k;ycWj09&7 z9!sUadX@TXMQ9Ml5L-vr?zj}`1-|p7!6`iRW_J29Lsdtnt$_Z_H3$afYf+b}%>+MH z*X}~jvPVZ2%?QOXvH6rPyjKfS7v7%+;4P8~`Scg3WM@wMOm>h0?fkmPAPtFW7$MoE zw<6HP4l@W6532L+Xzo1zp}Z6&_j9H{%fCv!SAW|kZ5nmS)ocgKddT$6G5rMqfyY!q zHwP|IA)~+lviIH9?*yWUJPQ+T|78a>kLE~(=l{JOcy#zS^!B81L?(#Ea?l&+%Fz#{ zU5{J62CBiKbZDZ7p&xGPu?$1AL2{O%S6luPp%gvlit~HhDq?_t#z+}5Fw?`@pUf3& zCYrOQ_NXVqjafxk8O7B(hno%je&E$x5q1_Tmh@c?E)3h^9Y73IjTU(rR8b>~5E11h@k?UKXTW5Ddn_<(RYq;p*edFG@45YF>H78KdF}*3F?AOT#+1msRM(1q17GeG zJ}E>wz5zv02Dnz^K6O#JgccY{RybX&<`z|h)vcv9=*uSMzy!nk%>7(nD_sj+&MEL* z&r+p2-@;vtgPv@rUGZgpf#zjFc3tjjH_%WVh=gACH5LfdP)FJcC$j#T%L~OYw_iU^ zouk&U8=!MEBg4ZehZ5Lf*^mH=lXKLIN#aM!isq;Nt&-fgOAB_Ktz01r<5^USkq=p* zqIsZqz-Y62`6*7EIKRFc%v(?Ib_Vn562H_5oOk1M?b09=4K0UTA)nYXCTLs;LT{CY zXM|0DRUX%7ey;X%J%-}UbBDwBl;Pr3z+xCpPTrX$9i$#rC6H(_PQU$e^!L{Y&CL4& zmC(oGBqR4vv|^t_Z?@-^tLppBG>fENv{?%h{BX-Wn+3Ga*P~8$1(K8i_X3zn`l;&z zS(y{a$+6DdMPi|n++|mgIoL_uDP1+#f`E@y7JXE)6A}aj3^dETkh#?8f4`S{Lm<&( zf#rK{es-5ADCt)s9ut@mU+N^JttmUWs{BAnIks>H5wcLf!R`Acm#}5`YY3`AzrrsR z!m>7?1U0aFuo4+qWP-w&i5#ON6j{@E0MJ(EA#x4KQEQlm+3ANT(w#gg6t$chAyEY( zI39>h`ZQ_gRV?ztf+N<*#8m0ZhF z81>>LqT#SiF!CJ_wps;TVXknbRD(1^C(Q>#$|$LMyKYm_EsSasY!Vn^C+0(dR24RD zGoBv2?wH!IF4a<;td*s9Ff2sN9xJ_j=C;%Nki6VSqDf+kpVjP~XAu@~qcb)^p!Lp9 zmz%7ga33;PB<}l3TfXJ1?>vk+23=QXte%?3^BEY7K*Z%>(`R)u$D zkx7LA&k__m9vGC5Nl(+VHp4N3f@vxdooBrN-HjKT%Lr%a@s`i7U|@~?@HG9!_Q3{U z7WwNlMLa6T6s|`%acOLo=59M~<%OLo?xKSycN^kaGd*NjjKhr`8e5iy#dZOFm-4;O zE85-4swdXXPHRsLM(_O}m94$6L#^cKrgl-y<~cHGHvt4hu>WeW$t%|#@L@`kEzZ(~ znisbn^S=?QviGBIUDcNk#-6PCgekIJ&@9i1S^g1N(fSpvY>^5cuZ&k0fG_aiffS44 zjt$34S7?N3Ew+`zdbCak4|&pCb^xAHoP33?5iBpq!L+YQ@z?lrhrGL$97l zPW;_7NCZZ7;poTd#(qlmH#EufKqb9_DlA|_nbZdZRhWqo$Iba#)^0D%54bH;WG>m! z8o2ggrJQd{BdX->4`EV<(evYoPmD15xD}_z*y5pb(qI`dDE=u;gWP=eXB6K2{4hK; zz`0Me2n=x84ie6QilhXD`5V{l=?%`Vq`{C2hd+b@T`X>mQ;_IUU8(CaRjbGBL zeEN-`w##dR2csrH?8*?Tp-DPb6!yyF-DLHcArRJ&^eRY_h8p ze30J}=f5>4Xv$v++ZS5M6Yne7NWCJJrSXcrTt=a`8-b&ZaP7~H1QV%6v=WH_rC?eE z2(XidO4aHgkH2GCo)VTIRB9n2ASld-as;OA2A%H|co(=acatw~AghhDyPXsEuaKd; zBB}CTx|i-j0;1|#;nkB7MRL2?go(v>!79a5F%C0b0DINUdwv1=6C%h*)xSfMtA|a} zzKe;q4tcY>|Bn%V{jkvzZS&DnB#!ePI~Sx}y0$P>3x^sm=c>w7znzQv%{VCf+;~1v zQw}^$tfk$KyOZgmq{)W_+B%b8-s9jXkf12>Y4crKXgPR=dG%zA_JeOfd*`0~ZGsM@ zb7hv=b<{WUtKJbC72)D}0fBdeyH^|Kl5bc&;gB_8*iz7I)un;?MwJYwFz+?Rub|#S z!7Xn6L8^ylYrv+#mJOu07Rg_hX@>uOd9YufV#oi5_d5Jd)dEBH;waf7x%)_jfOh?Ls7k0e7+l34CnZw>N$bfb}=+%J-~+K&?faM{JT z^KA2;%cX~1$W#1b()e{P-}j@$N$Dnjl-jNJXMzsFEV7dOgVvh)PXB=cOrk8 zPmHi7fq&L}U0x(%Rq?A)T*?*z@U+W~lVe%eQKwJ{JF{+2CuEjjS+tNfGM7V-ugn5o zri4LR@q8P_V5^SY36Pgg5hBY!)Z^JyWb?I8wl`S$vf@meK;;uJJW8H-4P!pB9mQ9~6^O$uf@^ z$ISN~x&tX}A)2P-h{4nDs7#QyXQ31?D#Rd4-%Z>s7DzWiOWINjI<-k6qDIx>dU< zHq9H7f=oIOK2W$XJ})pVkZ~d1JgMsDVHX>(Py=hAlHo$&8Eyj2y(6Bdl22{n53!w^ zB?2SI>`oICTb{ZFA+PfTQ5nD(30tCE4K)$3=LQbrzbZm~@%S z7F%T}fVaEUr&g*Ch4F+B$_#8v+cbWD>-`UB1)>4Yw-Eu*cn(pNc(QJDf^0*WqgY0M z@{#G+PT^NJy?4@&9iCw*k5<>AHbE%=ga+t+F{IzGn_HTlx&AO@{ry+kp{n=P^Dyqe zZ%J}dTTyVo4W~q-sz0 z=!Yh;^xFx05vh9^OJP6i!o>|-1kd9g81N^P?nk80ZKb5s+bDol;th#IuNXe@W zZw)&4OH1NO>84Lg3BHM0Vx54(Z`kRhiZA7?hriT(H5=Yll)=&YNE<4c0A)7Wgp!BA z!M(Ll<#$#^DHaj1{2X!Y;w^YT7d}z{*>Rh9kjSXCpA^!;WHoH&=)y;{a9<7QRt)bS zY>(P&eSyzDHNJO{kg;puXcgUzZRxwJm(6G&d#}#rrK-EiTR@HetNKtgx%}JHF?Ch% z<9L|fNTWjEtW(l3jv!gMr;nSiNHtdiE}S7ZKAko=2T*^n=I_Edy0QlzOquUnUUKGBOKlSJ*#dJ&WD>iHwRBp>4l)3lg&fN-6Px@O%LM0|zG*C6S&}cc<7P ztJ)3f)gFs@t%k>!OS4RVLn>>u->Cem-NdYXnh8$-h z6;e3i)F+j50w&YdS&}=bE+Z}RFv?^y6GNeU#h{;+sbys2irLCub zQT;tnJwDIT_16_G=;@z{9yC0@H2#-4hJG@|y>b7{8J(1UPf)}^iZ7`#+^R*OYzhl* z*JmCKWidHRhaCq7UUg|aL@jzODw&g(uaq}cI0TVt*-%6jj;s?SE?>4nWls?`hti!^ zdDO7zBn05HOJ&W_{9c^-PzVa_*MDITm9x3<3BDdbcUJZ4p5Siz+M?o+^#(qlr6Z>2 z1-q6T2*9|$z9nT7QonW3CN;I8R~T8_{5S>lD*KqllOdyIx-kw;vblv+43Xuv)T}v| zwyIN%pw0tbExOs>lFMqed`?E>rh>kIz8xd&EPOxSmH7#5%=xb>XOJ3WgQ7r@r7+AK zmoCdqQIKkJHQ&wc`m}FOw)Q3KAvxf+3h+}o=P9q0wvWoucz&w=VZL3tQ=uph^;DRYtBPjb=#1`0~qXK_U zx7RancThiXz&9vz5Ojg!OLfiK6aON!jHvd^K$sA15$dWrQ6F1e&Be0tUm-%*7Kds< zVusI;z2@k-A3>%G22l*=IXpiHU9klGZ@tSt0&;Q|8pH)S?ro3=YG0Zs$OHXfmi*V= z|J)Ti`Ak~$!B39d{_;5Tw`?4O?eJ_J65y)M7dJ}AU{o{^dDL(@pF5wp&FuMT%b58! z{5$nwVbm^Vg`1`)WSFB?fsVA0aV5p=Gr~EPQWLT@Wq;urp2Yi+n?78?f;TkSH3vLe33@z!V0PmOnC8G79YR;?{(QD;KHq^kqmNpGR=0GixP3w z7_iphEFEXA zbWHUUhO&(_BfXr7H?U2y*=TtD$9qW1CjEg%Bxe6{V!d5YvIgw*M--SMLu77o=leNr z7E%QRZ!5HFzG0Jm4Ps8tIA3ub20O#E5SGdAJcR!H?3_a3Bo-v*2sAS2Ow-JA6JJxz z@~(b5W8F+s?QwYHmH2E0@zp8(WJ`dQ>>0}^OH3InNMbRC4zg?UMCOdS#CmGfw@?Ng z`*>_=1Z(`E7N+?Yo4@|A^z7ExV00IgPv-Y5SV#vGhRpdUl>3|o*D^@8K?ap9^4vhw z4tFKj5F^01Skc~~LN`KW5rjUKyJX)5I%-x+4tdS9*^fbHtArVUkLKSZtYX${h4{0a zO5Ld1z-TS!B?K#@rFumAtkFo48foM1LVYF%`?!Xv&OU@{_Pv5x|7)E^I~IBdE)f=Fn1SvjWghWPrO|Bqxq((G}`{4&a7 zG!oImB-@uji>v?DjJk=`vh)h5-xN>{*+*#xS7QwESO2{H{bV2>|mIQ6f3tYX(0@qGFSy5K^Nhg>-DRS|<+JlTA@b zd#&5l3UuSG4Te^#7p-4XLt*dzuUaw5Kx&TQt^~5!Pfq6_QQ+Mnhug-j+ms~nACg^m zmGdA6&HI>t${3}0@E(fUgbUQjQ+^RVNOf&g|LX7HK!411) zK#jOMo(l8=#B|s)wIG8_NX__}uAm zv(rX4iu930+9+!;uS8ppB;IY(9#Ys(p1?pD#2TL;*?Tg6OF@%Z=Bf7o3K-kW<%0cE zn!%2h((Vf*ZCRTuwxY`u_22l7TfDhw%4y8OZ0Z~{%Wo2g$I6SF5BGOu94N`)ed0&j6mXH&-iaXJM{#;jULz-uJjgK9rh3Nv8O}$k+J}=Acs@ z6NA9`KM-9Sip284m`}fX1b& z&XO&|uIbdQ@hT*F0nvV*b^?e`rT;!{8_y5ftM%B5jlfdn{E1aJO^BYnp&9$c`pLi| zbb^0ceKXS{qMQyRhw6N_WM+uQ1wfz04!F;m1pQ)CJz9Xpu&Cn`rH!9{n`x%EqKC0vQ~l(_2eUN#*Yz`_voH2o1|CE zP-~FHATUW;puS*s@QB>$j=fX$y)LoaF3}_gwT^gqdCwNijMtjST${%BgzZ0kYk%qtWe~SxkG+bW~>~eD`j? z1*FX?{#7vF;MF{M{zJVGoea@}!xU)JD;v(kHCs?30Y#;JCb4#=dn6npinT;%O!|3n zJ7OFdhGS4S`C>7tmvli`sH5o3$KpQ6}Dhlorv1LM?o5UE-LpVd0DMLbYqsLtC;b$0fXq9II~ zbj(Ke9V1kBK^r;cphwJZWM!X&%a0(&yH17w^8$R?%rPN#98BbIK}yDhqV93QDF#}3 z%6WFWxN{S8!YkC2(x&dcm1%5x7Ax+G2#Lg+_#=-NQL0e$Kr2*wOX6wExy8I!j6FvV zL6eEj(9=1)Yj>@2xUKMD5(jA3P~0TNZ9*q-R1k<d2?!y)CaLiX`H`x%wem3cIX0hb%owO*h5f zmhp0Nx`SO{??Fu3f~xIfwUuwQ7Ft{t*f|1Pbot{hTh_AixcIf;0-q2tk2yL(Z`TeN z`Wsi)8S1dttA4o%`p0B$yNS*fORQ4^2k%@bu^q(EEBYS|w5RVUs{46FTsv`qDtLU% zZhB#(YPxIsXohm;g8%`6U*s>?rG0d*Ce`mgN^~ctV9Lft8Op`l=n&a}aK1LjfB@sc z#LH7S%gRzACxCt0$J!9fTZl+4Q@ShthccUFGyz1g_f2j@1~o1M-Ae7vZ&An? znNbw#ZcVW1@bvMZP6Y+DzsRYXX3$1l8w)JrtX8@{hRYo@6PM%;jcuama?(MZ@VQcE z!57QWzG&A&UEym-D-@qlsSI3J&n0x}>&oE7R_pp}N6%!vTGOCUmW;P_!|+E`%X$+q zrrwKsF#>MUV2+Lb1KE6*%^hK=nK|r#UpZKVw0Z4Kk)?_6pHP!$sAmgomRblP6xXi+Qm2Gg z!zkLkN((*FYM`t01KC)GoI)F{Vdrx4!!EN6Q4HM_mBM|SLYsrTx;@dLYyh*MP8G|k zmRs!0dNNf*0}lvlbdm^jRKL*SA(nfeT78V(Y{-Ox=H z`}Qhf)K)dBV3M^hl0u}JAe1fk$DzYr+RWExU*%44!nR#lmPOLBCBA=a7U$`SruAd< zu~xu?qRG1b=a+bYtN+0ZH}l7 zL+1pI0tX#;mlx^clPpLd95#IFJ~(PhADuShL)1d)(yAjDk{hu`yhM=@6%2+d59m`B zIaUENJgO8ve^*Ko;X;--)9FC~dU2Vb4I%Um8ePjy%FCqPLYL$R{4;pEhea!Rx4Z`ziLqqpj$U9jg9$To;g}YB6g;`?lwgJ ztWS5a-4KZd@m|P6NW(zcxM%A0@;{z;~k6hcwGE`WMuf9uqb_MguhKGo>u=wb;hzXb9b~ho zL=#+ZSb}bNzdvm^UQF3R?NHo#6gmxfR%6o;&M`ed?LNFS|A&qqD*kd*SjS9)xa6i4 zMmucBv#?J8h&vuI3$6l?*OS9>*cS%iF*6I>Glrnkkq)a1;>D6Eq@1(Z7@P*8xSi6V z6+5)W8^hp6GX3X>DiUu>r(ko^UYy|#vFIBTza}V<#*VS;f;vADg1|@`-$zTr-XF}I z`YO!JjQzWLziet-`hSidUlino? z!OrGJildo(JMh((9>@HT5M=?n$4yD4XKCI)bEOBEDt}9U1jAW&vacfO--Ifb`^(in zD*khO+U6#*DdBQ1WeaH`sjaT+=u62xl1I8UVwA|;J!{*{T%sr8w$2waH2jD)0?XT1 z{(!%FL4HPOWGcU*GqVY4IdG`<>C&H;heNB2L3!kV@ir}4P>ZQ~F6wGaVV!5MdA0;1KmVq%&dQn&o26b%CkiqITJ7C|*0mu~k&rE=Y|zawbT3v*dHhpkp{I#mp_CY(r5k&Juq5haNoGM$cC)YY$z zcn|r%4;MPy#UIDY>$iXxDeQbnHH@t3ik6e484L)ir)X6j4KC}t2ldicBF(_w*clYJ z27ln@T z-Cgytl;QgEkZ#9a7fvp=dnPz@>alex5|#6uA%R2o^>)5!y-Rk1)vwl$ zFO8A?F5^~_AeDx*PsE7CzomV?u1fcs;1?LoAXD+S_)gPWAXRLT6uRAiJ=6psUnnrr zRIKmSLle58Hih~|lAalIL&O*d#O0=@_NJtXzCkQ(%Q3bVXMZ@z7Bh=5EMx;#t2i#* zPoF}a6WuJ$A9diMl&6mF1*+!i$F2Y{BLC5N(+vtgKd}i1t*t{u-pYDpIsGAu@huT| z>S@mlG>gDK>eh~0qcIBC*LjXkk@FsIK4|S6?-#^}EzbD%(J{!Dn$LtYjJ&|5T)w4v zmV8$xh-5)L8qNKKbk|Y#SZ#jf@NW>Y4^+U2EKGhGyqgg~@#(eUWes)QeAr&inS~7P zgC|zpBzejE+E(xF%kD7_V=o5VmQ&n6h53nwvXJa<172+0bUXG!r>QTl^GXSqB3n&k zI}L+(f(l}S&KriG%C~cRQLak3|-CXN|e_JVtq*xb)S``;~WR8?Z{##n;E z-U-Z(jB4VF4yXjhSt`36qmUi2i{$GHE^8O5=;w8p&JkGVU`T}7$F7i!DZq* za=-u~x=us=S}?DebsO(q|MZJ=SyWBXGQ-PnSb7XQwee)>h0ykIbNtbdW&SDQ;Ktg;@pVXs=)C-u88(2yZ*xTlUJELZ7sCk zE4W06qhfKHI2X#kgB%Di7rXyWxt4!M-2WBk{PQ5e_h0fAE$QjBrJs}k-i9Z~@`@+X z%r^C*e)o7|2|D$;Aw$RDP=a`-4E_wifraLFoMQ;FahHdoM#fwTRsR;yp}qWag)HQG zyhi7bDsdi}ljle2$n>t!$$FE2*P$8o`H%Nx z)ud=`FjPUyOqZXtP}VTMx$$mQd!T)@$?Q06b?*#rl2cuOu{h}Wpq<2(ACYJvqhLl$dNg(SAamsBT6eo zLx;9vs$Bft89}}Z=FbQ!hos!VcP5?`PFf_6%6Na0Tdth-pJ4RkpDr|dkj0t=dTP89 zE7=SGl>BDmgMs&XZNA=@L>`HMGD$0`m&bD6vPbAl@7vqHz{{LC{^!;ZXChYPs?$w% za!IbV3z;8zU|Ow>g|=AO^NhwA1<}syQL-{L(iQyRQl_B0-E>U z{CAYsL7NYx4(L)Wc2qpl4@8 z-H84@5s6T2_Cq|xu@Z-%nSmhtogkeCL1n-=VCqXk62&OGwFA@?1g?_kso73f4_)X) zj;#Ran?mD5y_v*Thbc$Kcz%5;b)A8FVB)pnXyf$$QAP$M^IZ(YVSnb@%R&J@t?3}( z2SttvCW0?=OoY2RgaA(ugP~gbm~WvaUKK`PiDMP-1N=#oc^tOeXp;4|sAbN3I9-?& za6|l>dfN$+)G}7?n}fFbY(kRlY%mRe<3p=Xgi9`V*CDaYQ}|aAxxWCS$B7e^Z)yV_ z_35HvAa0;4NH}@oq)jDYlK);wV;4(@SZ576Ma|=|{=_(kc3ZMqS1t?O#anRFt6~Xn z^fffcDJYqO34qZ;OJz_k;+D81h@SL`L9%`dQcaGpafSHY2x)!7CLeT7B%HJk)8eUMvJKN`T)tG_@gNV8g{K%$h!G+*rhOid6&s8I!7;$wPBV)M46&f|ntLFA zE$`=@`X-B4M?D5w-kJn7)xUL*jQLqX8kjIZX67@Gu$*hDI^lA`;vD*R?B-;T7As-< zL-?PsgifpZovzsH6i|v8)%3s1-$2c|W#!gz|5~DqG|mYkr%v$J2yR+!YgGtf_WL9j z>?sE;m;LEiNcMHyI~pH6@koar!<3Y^*-CJ4C$6$X_DTtD%i4MdM6CH2Qz%nGlijD3 z(-oI^&Hen3R;(o709Sd2_s=;53=}C|(|3Eu<+|^}FQ!cCXJ&(XpU*yEdY>6Tn2StT z@#r|P{C?|(pxcg;aw=5?8|;GN?;^^G_Yi;2+z*j80!2TRzj+)518YXTcKZh~_u zsp@RL!a8-UC_Y{=<0VY}E@U=tv(L<#M@%OZC2|}zFi#n2a8jCcOKOS}Pd@NJ2SB5l z4VCndT`0N9@y7kRk5XE^GdnEZuzG=(Qwo{7h|+4q;;J9V?+6%Jq=hA?Ol#tyyC!7OR48^DzM!|B&(Z~A7d2Ks!?-WWSQ?QNDGCk%7@T0h8Y z7oA-u0fLyXo&|8@HB>nSo?AQOAjJNoe}+8pd=q4mUS^tNV$^#ud9^#@9;7LQ#0Q6x z>`g{kaJNeQv(d{gY5PwRIZs7=`%-ax%bgurEEFx}>AkG^S4}a_56g6j*8d$w5dQwi za&#HEaOvkaBVXR^nDCh8K`9p#zD404Ei2qIgia92A!s5<>8SCB4`R19O<~dgK~%5+ zw{80oi1rQMlyk@~Dq{}88N|ZD1hR0_5b7A;KF3Fy6nrwg-FI|ud`+y+30TjGz!_D* z#S0+-0#j}XZY?UbKC3}Iq}9SA_P)M1fuGK3F~$|@$woY2i+j;P4WPekqKG&C-- zj24~bIAA}A-Lbax%~2?p!am4wouf<&@q~&>I>A0zh(TWIKl4ymB4a45Y8H!->w};mS6(pjQfp zDy^_$^l}YBEJHfy$x+#Y7&{?2X?(>~Llzph&x0#l-)?OIDiua4>E1dRg&;&|bb+53 zS&f4h-g3W8<-t2jk*^OO-M{vvBW-i!WpNq8JlCWvETtIrzZh_CLO9%hR865_tC`Rw zRN@Txj>@m|z9u&6GqXkeTphb;rsKmMj&q-Bk&>>PbEO%GFH^Xa$!ulxGX`yvhYk&R z6MG_H?wlUG(HemcCxHmbkY6?H2*him;2*(9K(p_S*A3^@OjQY;l&5!fYFu}_XP;&9)ki@U0{ z1IS3t8W@7ocB;;!kPRiUK)GCIEO80J)c-cbW)$8O!r|82#c!eHq$7;eVYj~78(DcG z8HZ^Rfn6%F=P~P@Vp*Q}yM2lMa1p&Lkxi$+J!;7qAuo8AD2GD_a-e3La7%+ZyL}R{K5#A2L2IT=9B;gCi?)L5#?YyukL4Q` zLOK_!`QJ7m5?+E&YR6eI6LJEoxrjnQvE#gU7<+cSWo_cokUou>_Z*(i04(v z)*fJXJ^%bM4Y^Dxc8?{bSlMP$4o*wM8Wu*fKeJWZG2Ha z2uW5}g8XTjk#2wl0ivFj(9(Zn?(Y58VC_;s@QH)EhJeru1NE3~G-@smtWwi%K$g@@ zrHQ4t{FVPH)nebz<&G3SDIVJN^BNMJdsu~{_HT?3>ltO~)j@UzF zB7RMFaBa79-(1eabqcIfe(=eF;7+x}E@ncC40k zGR%P!=ROy~5MJecs%i%!rq~Qg`sWNx{N%TBBjcVxYmh%gl%s;;f4HxwX&S<$|K(3{ zVp0$-58aW)T_x}cJX-Bz%iSa}yaFyOtSemslHiCCsL*xvRYs7)-I^Xe8 zj`5Fff2XSWB{f}b3jsJkMS9=mRCA}oJ=(NjO!xB=XzNP!iVv^EgTA=s7v}HTybf@F zpvCyYQD0F`2b01vd}%Qg?7?LNxxy>Vxh@*&qz)Ayn|w<_U> zha~|rqaEpR%m5IS zai-|Pcs{d;XEyRDIAJDLZ1C!vSz|q{a^Lvm4Vfs1=T}%)e0m<&4o-C&UWq;Ux2`&w zDR?v|Ali9{tY&WX*{t>f5leb^NT4Dm3WuPA7%sXcAOTEu0$n!bMyVcGt>L?Ka1;!>(Gt3ucA2*H&>)W*g|JfOAu?$mlQ zx$E?@txx{OmOZ_JLJmtuhX%RqId1yIV{~F4VCB|s{rFWDX6#*fM+Pwc6b#t0@V59$?OL9zQf1m6=iZdw9=O?`bmIWy~0DO5;BYocKNl8bu^{< zlURtyF%)7%a@GYeLMb5%p=MqW&dgo4Jw|2)L$~?1g zFggFpj_^FAbc;*xEx+%!VCB^EgX#GFn)a*`Ai_jug?T*2Tr8-o&z;R6M#84?(r+h% zj`u>N5O)zcNZ@wEJ40?h$_&^KG&k+1`pWl>>c|KfEy!BIzBGpl;>g~cnZ6L>sZ^MT zn72=G|BLx=nPTI`?|DC>a**?>g~SwliS8Wx5P~HMpjaMo2o} zYpY5e`q>HuVBg{&NVr$Ba+`D!sU|gLjKU7b?)rUfwen}`5%A3-4_>Kj>%mT0Y0mXK zyo!yRkRSrY5|bC^$*mkhYl!_XcH91#-GaZJ7gTeEH`p zCsc09{+roZuznzl6H5COVCwm&U%hFkfND8Za@#QzBiX^vObZnG;=Sy$hC`ir%pHmk_c+;4Ud1M|z@aee+h=I1%+=yK4h^e47h&&YA<>zi zi6H=*-Y&f#u(ApNRy`PI1zu}VB54mTE%ln!M$Gi{gr z*2L>xNK=LPTde?TZ_{5G%X`Z(oX3(xV~ z8GDCYd-v!u)JSwB%<;qBYB&lup{(Ia#&ItJffz_pUFp^Hsb7 z1gEm)zstKuv$h>FHkk2LmRj9O*z1((aPX1oyOTHVV6i6qP$@JTT9$jF#R9)DVM!!R zKn{fezr=qOqg^hpT;k=3&~mF{YJsc=LCy%WMy>PQJbE7K{r)-2X)U8oq;{I~O1(<> z+or0coa1g<53c_lLm4SMOT^XY^Zpd0Z?7GAr}@#YS?9Mp6RwYs~O?&b}nM1A9YvNr}>SeJHU{JM|eaU8T*wm$Fu0PYX z_NMAK;N0SGkU?`CVy^M(kgnPKp#N&WVC5c5OX7qOj z$z&}>^pZbTodHzXaD5-!d7(Egi8b24f<=K7EC7bit4QoYkV%#7{^_&?h1M2tp!3kQ zbP^!M-!iibyWMkkKIM#umh*w7D4?WAc*iEoj5~SYeoA&#;s<~`hmb!DrFM(ItQ_-k zg271j%FNjT!yI?aiM)aqSb5S~zBM}Vf=}DDB1ymqDEqK^t$aE-uU%aGKAIQ@i5HxL zQ4vbc0$$-D=?*}aOWrQ(8jO2ey%q@b_J?vq?y6&CPW9Vx{LJc&0YzcU6(Rq4ZrxUo z1Xbz`7JxZ#D|-}2IOF&wKzZ$mnK(FmQFQcExR6U{z1!f5NZ8cyYLH4d8~$w6?8!8n z=L+yQrJ{{$jznM5{%Ly}i>Y<)GB6rofpuFSqvT{HHjhh0;sF&LfQIiGpk(8h?&ALD z7prW~y(;L%io(B@{lmvn04_kfv$qcw;l1NfARuVgl2uP#bO|qJqRB%_$Mj@9pD8iW zSc#)bYfIEL<5DMTJpyXWU?HImNUn!Zn=A>xt zTV+VmT$#qI0KJ{-OM80cwRCo|&O$;zCFs2OeQA@=TL#03ptQ!qW{mkZ|MG4`zhsEh zl3v&}b@|NG@}>9Q>2V`t2%XJq>zQcAk+&Ne$d8?#6A}$X>!GU3R|8RJijs}#)}2o{ zTc_T!>e$4d?kNN^o-t*shPgsdUq5-r&31e~jCP@2HvBSExjH^P%;J=fQNPC=)TAEb z%A3`J>PH~bNR@%YN-n~1k9e~TatdmnMrvm%Sb_ceBRxBZ1=17?LsVddxqO#Rt4&XG zeu}a?)ekP4MMFg*U?UtXy4IpZWMckK9douU!YILI2UD4NWo}&&ul4I=(G$sdjM+~2 zXXO(3ee!YV!|I0Wbz_Tc7eD`BL}0Js&mEU3`J|V2ALN@t;!!&1oSR{VZk5N%Y_k~H zm9QBT;hLY1Y=gL2MkI2~D(4ptRx^mk{`FQVkUlQWleOhRsQ>y|W_$MKD4NaS7z`BU z2+0V+5R%g@dsBvO`v&3#dVHv@ZQg) zc%(NOX)SJI-}xwh`kp4`XrD>)OF#qgpAxMrZVE{0DUFoG%n?T@kW(%sllu+}q9G@! z|8&Ups-=Q#17+dbqBOOKIK#IS{{=az(D!O+> zpoZWyns%y>5di>+^)B9Hb zJC?{33J&$`Xa?C9t&F^A&0}x0XBCA89C+mbWRH04tlR&*Om5t}Iti$V&JW?FlwN%>Dqst^bh= z=!LN@TCjGGZ9?;>S=noM`us(^ufs>s4TaVip~rGIV#eip)~eo>5)bZ52>W}-Ud&N# zUXHP%(OJqJVOx~)+++a2UdtSpO(e&%W;~h{AIzs^ijUB}_<6RfkTolp$DW=kJa5fq z_&v1iP;$~mJ})A9y+uT}(17%JSC}52=kKows`t7-NYG5ys#NV`L#+gevED{oHzCMg zL{PHeGvSs1$C0~-)O>6MkK*=U_a-brzS$v7)4i1{S&xd?!fB7rPqg1nP(P%>N{>!? zKa{HfT?^z`IUfXdHqMxTlLTto+;@f%cPr-~B=;Mhnj_y6HhJFD{ZX?o6HjW9Jh1uR z0OLe;sXDG4@{PNI`s(l2C*S;Ia(Pin{UcQgz-rTan!D>C`I&q%s4Z)6%TVkbwiwvj zJ{EMW!l68)D93?aL&Ym9Z;sX>?qP1!`5`N9w3I!Am*)@~?-$fmlyEtoT(VzLXeZf((jGQoEBRD zA@?yRJ;qGbUJ)Egs?cvIEdKV>Y@7$`JUTx4h1E50fiX!1-oG-^v;H{f z9NRnw{;JO@m!&_y7<%Ae1>>JV z^XHbS{%0|`5W!&U%x%QZF(%V-CW9FRYqxfKcI^wK5x{YP&gX%#8@-Xp$&lA*tMn&g zU<@SWVQxfWh3inoutjp1jDIn;zb7Q!7%XOpoyE!EGmxnHc5|AZ!cjv3rv!?-(|O!G zIVl@sM9;<$4?dWyNA>C@f#cNcGGqQw@^P5B)hNkLdV`vV4>g`d+)-UD+Tc0F(#H!c zqf(pgzqXNp@q83dE}HjOkH%xMyXS?Eu0v1NwuZDNmNkT6nKK?BcQs)G6}<1}uACB` z@5j-YBVKAsCSOw%42;OA{Fdn3A_Av?=Ee6P$E!vBV9qBLg^yf1IO~v$s% zsEIE9(V`%wSY}10=;Q3PQU9EAsqX)Ji@AkvkP%M9kIz@#Bv~=n{hgLM zbus%2U-cbz__f%6MzX?+bN)}$mY*3Kra*SF&MK8&$JXe%s@;k~0~vsAfIw&dJ5P?F zi9UTbN_zfo@@RqFpp=Qqz#CH%0Mb0ZwS10~HHMufOg**6%Vs2FZ~ z0`ZX@84F}}lybtSKRgzr^=SmEuZ;+~iu`6Ihb+l?Qpj3bSWSo1VZk!Nit~zulDc8U!tvJ0SDn^Z|%?b zK@q0a?@AeOkD{&s6*?>=y4`1tB7c`LyG^4qJQf4JkD^9|dnC23qq)jxb>voD>vvy? zTy8e1E0?mI90?4fRVlF}%hfHrwpc6%ZnbJW8T&<4!`J>H%XwvZ7L6;X3B+sRi^qfR zsjb9qprR<6GqvVb>yRUSinVSPfSP_Gj17Jz3>NP7A)98PKOll6TYgu9S4YJ(IfsjF zrcS$FxCQjA5(ICYpw6pp=WBaOkNnO%b2cs!&i!6`hB^7qJ@X(qW-y#Y^bzdB+`ViOssMFoJ1Q&mntr0P>S6$<+wn$9sglCIIh9ZYQ7oQZAQ=ESz`%*3|siEZ1q zJ#i-LIJe(#t^21}{pjx1Rn_NIon3oB8<0#~zPziNH0w>E7bRLZ zz}jE;J2Xf-{)a?`v!*;OvldE1rg_rC{K{kQ!m>W2hDd&4TvZL0%+DLFL3rf>n!~Vw z_tErU;u{0zXBSoAOzw_~B({(_WXy4cgju&g^<9Zv1>+bk>$oo&2@jdQ?_*d`LtBxg z;Nr^Zj($A0B1scY5|Fy@MO-Bez4i^oN>+*`DT^BLCm=aW$GFv-#a_5c^(ga6RS;SsP?bCM}x?bQ@5_emrkCh>TrNYmigP=V&I>S5p+n8I?zakQXh+)tce?zDPY?qWla7(dKoApro} zn0RC)HuUlwHn%Ber(Qj+I=Mg!@kww|S96uU=(@Nn+{6u%ulEeYYeMbb-EcNVL*5BA zawW<>JkngrtFRtL zQovYhrr#h?;{4;$0kxkK^|n>Beb#PLC+oCX&eqEj8J6yR^61t7^%vv{8c8Nln(<1V z!UB_w*Qtq>J1W@wdd**A@r8O%1k2N0u{b?-xcO>tq-&6E9;1B=CS(%UxnKTP95;6s zQcNm7NQI`mFV^llM>HTkg1CQ)F5|w)Iqp^tezuh9Le0WXH0q0E((!9M1t`r@z+MlK z_i8_B6xib2pLt(x>P_3M-dcuM5;GqmdO}4DjTpJ$hD5j}n9HjIiwInSSvpJ$&#uhI zU_zI|9f!r1+87B``d$w(v&EJ-flt@^Q9ODy;m-lIiv9_f%1jd{4YG~azcGLwd!6H9 zO7?MUi7|BRbd00mx^A%|n#UXx0irLR7?e6L%zqOI1;df`(RUZky5#GwxEiML48d#0 ztb+si{NFsi8T_s(jhYmk9{Q>N)q6LLfjnGwtF|R0U}x2A4a>0&*IGmyRRxNj4vSpg z!Q7=SNG_KrKXR((4|8x`XpuQJInmkPuSpvlaVTJu=l5VN6%kmuu9t&QR?W<*QvQiX ztq;B+?i}uSVa?=xHahAqzL6^j?0&Zr?MC$a_!k|9UEOa-#*QYRKVXrJCB9hL^Fm<_ z&Dulhbev-$)FW5+mhX8$xu;AV4KgtUjG zfo)?(k&67oVkWR#8 zLM)u^>oESc5F9M`7jk_<{0Ou_10@Ksze%JvA3mD*@Rs~0<6`Nnu(2zrGtXRb5_N^s z>va7&ZMEy=T1w%$36u8?^>Zj1F+`6z90!ziwDASv??TSyfmX;dMeA&@FuZdJDt~oo zVae#RfiZZ2-mGr-S~=|Y#tEh|lzC((4+pNis_zZK>^`Of6|Qga&9z%Br)?-WR(lww z9?$+@ddjyuW^VG24+nqxq#fSc(4?(&a(wENO(T`zL|J7rwXOZH$lgx9L-oUE4$kSo zu?Id+&oo0h5~(~Ll-;RW{6P6;4BV3Qj zPtlp8A2HE$%1dmoHMac1_tz-FDshoxR#73($)RRN=}0+4_yCy*%+n3wOehHpM1qFE zR1^vZXz`?ks5x`GlczM-y%F6bN{dDLTd@=X^74)swi+Mk@*uk;C}ba&_dbp4|8ITw zDHom^KR|JC^$ejH)Z?)uF=eS8pvt|zP08mLaIukH6ZktW>nf{9`n`M1$?C+_^lKi^ zcl60~qu-WR$;!n0KOb)xGZ^z!tksPW6m6rucQV=CyJ9>jfse0U65#Mvs%sc?=_XS>%fdiCpekqs^E}z4|uB zshJzzmaMQn6MPErg=^LP8-c3Fe&)qJV57wxQk2TVI7Ow&=EwY%MFM&5-{h|DEqk4I zY|_zaksS2P!JSzcoY@!GgNOI?Jn^PLSe?g$G5}u7CM8gcJGv#zesg!hUr+q1I7k0=h*b{ZQ@%hkyNT#<_1977Tc6`>^R{hU!ts&oS4AX2~#%X zCSpkvxlVR&UEGWl^P^bf^><$?)o{BvQc!swELUgP#@{kmVxtNPlOOR#a8hsyPsjf5?-!;|2ZiN)PhviXtMr2rGWoKG~X1<$$Xtlxz`TH zeE?>*A|i2=zOrO)&pbFocaMr8X%}$|;0SN!Z~hyOdqk?LLLIB4SQl=BUS>_fnG zXBr{EqzV_tw=toZwx+6hv?iu716!xGBe|&%94WW1jS7A{xoP;vj`mm_yd&{8U^-un zA#8n2K`uSHT{lch$zXD^{sam%wAwZj;l-yra63R!j1>QT%0A^>FJ^X@1EpVZ-5u9p zi|OHdzK$QjSfaOq7Q@)+A_UmzrcC3}>m!>hMn~18ol`Qx9h|XCo@#=EZ%~5R!gwHi zxa0D~ZBK_E?GEmBJ%$7q*2?IgKl{yh*)_+A7fCc>S7^kquh@Veow}U*(l`0RMuQeB z$=R4m#$zl_DlS&+DE{#Dkx?XlR;WUEaq$%GuIDRVSvGin_+GjxFQq*vNt)+=p?XEq zaS9^j0d{{hJKq`VeVVU#H7$}|Rcin6uXNW$)Pnk1fb_xYcJ+39t~(=Jf01`zrArhW zsFctP-)>3b2oBMjvmrlE|Dg|{Z_;@liCBS~ZzZj*WLd71*f-728Be%p(LK6sC?1@y36N zCg`@`?bYlg_m~9(OA}X5Ra@6AJ2#j#PH&2i>nl8$9ak54f_4$LqncOGXN)a@rS~|0 zIX?5sq&ru&<^|qAx_5_C-0+uk$@-dlHVIK;U09IdB>R~oY~U+I*_>}G%$hx%e#4%$ z{iaTLm(#I5ca(%k&9L(j3R5=$DwfGHJI*QO$@OBO96}i!Dp@2vuun19M|hBVlxQk; z-Ei)%q~uTAsMtqUN)2k*;FLCtVYI)!)g;}@N8?^{g1u+{D8H#e7k+HE&SA2|n@o-K zxLUon_O*NysKP%5x$H*9x>bJ_DEdyLvCZf31(Dqx)!{2?KfQ*iBj;|Y{=lx3cDpRv zn5K)S0=Am3RJdLufrU!-{B~moP&uWQeyZ8Q2)}kINyK+ z<3lcQPnJxY+?ARs>s|e#j_MzEBQ!aNEVG@o?$#J-Yba^H-bc227^N4Z8S*#3qBvtV zFKkeh$UX6N>;9c$-GK+iItkt>J6i3EpiD#$J3fEyFXv&plxplyLx8#3cNAUw^~+|) zR$5eD39A!nxi>fl8j3eK2hu`9V2hJHo+A%PSv4`G>B9q5$QVDL8nM2$Bk}TxjXpb> zrI&aRxg{P{BPIeGV^qPDTL@pHpAbK+^oui45g9v%|1fxDpUMt-M#?H^tS)hN1g5V@ z!Nc$OW(xmOTjIcF|GQpfMRf1bycgGC)@Xjdu^`%VqnqZEqQm_xra!I;KCY9J-G$o@ zW&l|$+%TIPAr@CVXGN58pQ+99g7m1M_~_=n=!M>(wM{N3V~=(kqAeqls#uP__ZH5R z?EbIPC8*5IMl|CPVNA%z{`RvR1FIzLr8Bgu`qgRazbYQXq`R~G9RBo`>(7!#M*y7#g%N|q37 z;77;tqK!)hAT!OcZv?Qi68rV)op=F5}!;x_7e-Db)r*JJZv%HxXLF z>Ezn56wLfD)A*l+2eDN`nDK#NAMw;NH7(NGTM|`d)xfKAdc~r|HdOyVxJjOmRk^MT zYV40FGL=Ka#dM1k0>sqsX?2Fj_N%YO>i?x^lUB``I6l8M;rv@AEJ!gB-m1vmqdJO0I+JrDVvSAW$4^FE%|8-ncj z0e|hT{db=KCmC+o^y4;e*qX8L>HdUDSM$L=V@^bA(=>@Rbx>+ACqa^2A!nm+=-Q(P zVUk8YBz2T4=e`1KnhwE`<k)bE!ehDtf296?Y;gYo$p{H+?jui9Z#k`Ci z2d*IT^eB>IEiwFrFc*@VEG>LZS} z+8lUf*Dw;fD)4}3wV$uZ|7?2iq&Z<_Unv@Pb#J0}B$bOUzK!#YP}=n;I0SP$&uL04 z2EFRaBsg;kJQ6~RnD-_gJN(7b>r=rtyp;VH%Ej(P@U-6-!6NI&o|$s`5GlesdD0_D z1#1~;DAv)bo7k6#J5ePp8p|vrmTm-HCClRTH_JqtXA8ScI#T?|$_^nh!1jFf2k0XD zVq^&}$}!%yn5yq`-I7YQl?M)sW}3d~O?TBbNu*4kc5p`+W;He39ll+Q1>IYk5oG3v zzpg!Qk>^brECM$p@`_WMz=(vTK+^A&3s zm%d?-#)Dczw-%So(FHA2K&Vv9=_Ggc!37_GD2X6bP$JFMArw<%t~IA z>DWp6c0D@oeZs*=qdUx$PbB%vBsq1H{R`V3A<^%ttke%@N@F{xnhJ+4y7D zg*l|7>V(#^;@0v5d@gAMqm#?9oc8^hg-*=`!?dZ=Y*OhSdYu|AWw zslM~~IIaQh^Bq-SwqDB7@hcI7c>x2<=7`QH)+{vvC%daFx(8rHW%%f5^E(?#`P znw#s@t5=mH+K{s2L`Z}!D@mM;NV!@@C$Lto{|X8Mce@g76V3e}zO8@j$}VQ^ zLlLb)t9-GP?qiKsFlADn%pUN@JB(C&76u%Wq! zQM?oE*S~XukNw`<%=7%O%+<>bdtBQCSk`|`|#I)tkkRcs0HcWaV$eRY22_N~rF2qm=?JKVp3RDrNap=2ps2fAT!oOcK%}D-JKn&J!5#!YIq;mA zYyZ2qnpr?*9{Mxyq1vmi7dbM<-`B*SkO~{XT}@p_rQesPXt}7K6L6$<36JtVi>HmH z!`dUC!Jxn}OF=ArmVU8yY)(GPdUk^@!N1r}(-Bxg)gBQGUVpqHS%Xwy%~$v#k=~p7 zP4SHC1C1PHgbcfJnETs8%f`pB)KJFIk>Hoo8$>lvhDStvfD@c=^{oyP5WxE3_CC07 zKo_tNO5dJdSr9`g=}5X$qcU7miXp46e{-&>xs%aDElG2vYF!kszDr^ZsAMfdkn&?k zUn?cDxU89_(zU%twf3nUr3>OfJvXs_8!Ig__7A45AuQTjiG5?pN#3i@qFL=m(KeAu zjTsVxJ$$vmDTM_2m!wcC_=|a~XS>d{6@lDr6VR`h>|oSH_}tD5wz;DbwJcRB1j=5i zqXs+u#TD6kO0^dYwH3UEJhO(hUTwweCw*H8P8x*{j*FVEIctI5<|9(2uNBPNHEJgx zD3CaV_W$n%U>bL|B0|sFI1+uJHXJ4TXDsb17W`jMvu$*^`!aN7wiFqK!R9LSTgo7u1Iw}XgDZls4^2lwAGwJI+qG`9H%I>D3d zqq@iZUCRLh^xn%Ki@?VV4KRwyga7D}4uLi)hjmgDZrSra(aV#1^b7G-#MN!ItH-@! zX0YfOYyAkkTmu-A>Bjb7grG}vl4kVw>G94Rb^76r|5Ghf=6gHP(-J2^_mm9L{59D< zQxY%yUC*-~(QZN}swPk{gg?%)vmCYbh% z3v48;=kuE{)})W%oOhdD?=!bNaB#KuyAyBhGYE?L33m$5(SH(`48Z|Wb4Zon1_Dwh zomKSjoL}=><*q;kiz#OHVBCrcrf>6!9%d5Dmo9`th)xqA8i&O9R^#o&*k6-*LpwLN_FU*04Y@l1tZkrk~=VA>+YPvFAuhNG1XO(_` z{u#zNBYMS6=zsV9PJjCWmxX76gMR?BQGs3BFC>+`@qMT%A|pTeVPYzQq-7K{kWhPC zE31;KCz(C-hEHV_#8t-4_?|8bFaj3G*j?(+?uyK?S(QcY{cQ;%%tO4>{PyY6VLlO1 z{L+{@s%@B3*!t(ZDq8B4r3LoqhCm}?n`Pg^L$<$zXYW}vHL70J?OUYo*_HmqJ;+yf zE08N3%8XQJkp-ckw{KOT1-|>;NEuxyUq7UnIK|>OdIh7Nxbx_-y;a)a(q@!yLjCh> zHkP0*${5u|0jTZ>!XkllD7J#eR)2;d4YH)8Gm99n zbCJJriv)vra`oY?kH~w1#F0y>BhfK&M6yjG#b*!I-?MoXG}e(f{-BXVmwE%L7s*Mv+}SL22xB15T_Rrnwcf&d zQ%KGU%)E#%_Eir|%8)2cH!(GX@2GDiif!(s0&sFW>t^E=kENpbmRm%s`OyO<~aA=CyziB$LBv>+@5C)9V4VU25mfdzU6 zZB!uD-AK%%48i2B4Gh%(0qSb_dr5^k0vb{9iSEg3rbn?Mj&TV*0(_(Aaw?vmlZX2s zi@fc*orcqBCJ^RlyYio?pZ71lb^-l|k|Rg^&785zhz^)%@#dSG5@v{nVlvJCeky4% zD+ZQP`z_i8Vn&3g4F34R^ed6l-J1J> zNuWN0*AKB2A!R*S4iwIY8E@|-H*?bbVDCJrh5;h0KFkKusI?M#+_c3hI>cxd*{T7# z--Z$p38lTQ-GbQM9YkeWXF1LIU>AQozlNJ11VHR7P=5Hg-Vsqza-hFZ$LTltr&Wt& z(7a3^w3j?GMGBVas=&#=;wgLb+xsd4TrT_1ph*CEH+=p!pTw&Xj*|G31S^$`+->7K zW6(T~^aHc{Y;t>{;b49`-7!&a&BrFF5QH2QcU}{XMKxb@vQ@e6sRpB7%2RC=a9TfZ zpUBMIbOWAxd)K=EJkek`&>EMr5+|$Yr@DKaieIB+2&ys%!`7otCZ1syk3|K+s6MdF zI}`iO?UG#+5-!g>qAjuWU3I8;T~PBHs}?c?D^wqb7~G7KQ|qODvrWhW$nNpP%a=U0 zoG#PEM$rU5Tz!x(UEN>CWqt(ceigl8Ck`fD-vYk-R{&6gxzx_xZ=?-o*a}(m;i_nwM zlcOBLOX~4`e|X?mBPMr@T{m^NrsqXg{r>hxg2O1CypfMnyyntpzO3gbD>XP3b-EE8 z3CmsLc<;9pVpuF%RuG=|zlxhJimr1=0{c86;bM9y617yTgZe)Zmbu5+VBHQ%!Fw923JzHVTBTHEG`qtBsrvA!ePy|PIwTiu1~!GAN`y) zwccz3c7Zj0pl1-a4?F@=;~@0UGJZLH!3*5(5btGpd;z|$^S+S70qQ=u=tv&74`n%@7~+D?3+EFQ1Pw} z^XlHCK>>Q^5m9CnS+6iM?NXcgIst`Hjipseeo9vO$(d=epGRv?=SmI?pHc_boGm{m zhFq#9y%`700$LOFlCwTZPB=jr2T1OQmoVW;SPcy`9FyNTE^{bFASNBi{F{1Bj$4ge z`X5c*HZ--bkJBmtGIo;_?h(NRl!4xqoI3aeu$vJdG1_rs_tS#-t`jR|Q8}RTOIbyW z#9b&PslEj~m7wJ88ca@!RJ2$qriL2+V#E{ame&QJ^->G>VC^c5Nh-1ZX}>LZ?(v0x z=xcVT6KdQ^&m!2s+)Ul=P#CRPBK5J(bo{!-9mc1tNh|>aEFJ|6Wu7n=Q5RKqD0DUR zHZr%K+TEPiXGBqkXmY1MjJ5Ib-}M-8=fd}{2jq1@3_bW@6fv}7F{zfOhERe{%WgaE z)GjI^G$D^wR^Vv&F8}GyRMo_v3I8BB978v=V_t_`pB|SUmzkOb-njIwl4&RzLI2qy z!wNaJh>=5zLV3BTLerS>I%=h=PrJ~+)*cX+l92F!!v9LeC-}Mt{Vd}?b;y0?_Jv0- z2nEvz{&gV#ydd&7ed+v{1N}+6g0vHB1MM)&-8i^Ld2RvR%-wOvaa&GdLV1t-M~#VQzXqINg_>drrdg}T$w0HKWp{H|v&;rV(Fx=Ry{Z4RS%0xvzC_m2uszlbp|4>R zuTPBO08<6r4RRDi55*ePhIh0)^yKxNfPYxcz9$rLJ}#d`=eoes2zB1if)%jmMe)>$ z(H0oR($E+3q;+m;=bvaTIvCz0t!Mk|bo7)!zy*R1-3N(9I7~hFp`GcEd19^`s$s#_ zIM-uQfzsq){f}P6v>c9o{noon)f1OSa#;@ou+P8a^_-O*@uE_)u>ky_kiw0pt*yDH zlG0K713)x3X?yQu`j4YJdqS@Z4eACQl-DOB7ie%CAV zC;tj^58*{?4`Q0aM^)#qE*~R7K6zG%y@z`OjymXz@}gfKZ7i6>e!Rj-ScFzA+<*M_ z(JL`a<1Kmf(g2i$6cz1K$+3Jd-^dy|*r)j6)~QL!hZ))Q#fE>NYi~>|m&inNV<7fi z5hb&F9ZRpnhU6xVKra1=v?8$PyA|>%^iv`-;0ZFRZe*gYA~!3K+=w9E?&kKhQbb;A za7tdF8D~i~^ESzYFla@MPFddP|rQbtp~%arR8^{Y|94)h9@87_wy4^Vavq)FfdAR zZID#7357-w4pi(a^*0j=Qj>cm+~zqR2LUrJ7yDaD>GBZgg3NlT zQ`NdgQ($_7XSeynu)l+kL&{x#jS;DDp6v;4@RXh4Vuiw3Ek%5b>nZx~8jHx6GvUhw zu_U?&>M<_bbEt=!>d?-y6Og>HGxRvW*7my1=pv&8|2~;Rt9#HKy)++Ek!+4Z8Wn7< zm{(prRv{$aH6@XLml{_TEa4^l61PVycd#udZ7VirabWXk+tpUvbIdV>lMjz&$(|o- z=B>@KDRwb5`8|KAR_4e@tOUd6Z*xlLw~MSrR168bbbQjJL}cOOe1@gvV|7`wM~2JQ zewU@bxiB7;W~Q6;K(T!;Zkq|o^xh*?k%pp}o#E|Ev+Qvcqro-aIGnnNOVzBrK{XOH zD-WFkR9uxLzk86mY1{%-0}ZLOg(Gc22@Gz@_z3Hl1oCc+!yNXtP~6<5U%pcHC>-#PWX@57+yBjYCqU~dBAW_YrU$aRKtN1jL3lge+XoK)iG zAn!0%@{_ts;K9Gkadf`|3>|F#mvCqDl^m{B;bGs5{!dYS#HC++Y8e)5;Neraida_xJJys zIWi5INoHuw70$jXB%(-U+{-O_>mdL34$35{p8{{;HnaiLr!FwQSqg}Gh@$L zTF4SOA!HV!y zK`6Y`ZNhg0BG619btJJw+VN(sA|@%Wb>SDGL{WnlLK|60kD=$suOL=UdApma1Fft= zRLAyr?nYO^Ydij+t{=oI+5095D9t{8wEvsHm`q)2dbdk)p4fILAd>9XaLUB zu{YsDyy5-Lzxl&9^0&f<1KkEZ$brWligy{VFYWDe_vN2)KI?kI-Q3{v2_yd-2IwzI zKdy;~WyBI{vWpupA|$^oNNA7}?v~=*P(Wkqi z_llH=7MN?|2`1%0XWZP_~_}SO2T2}WpzdO2jLpXAg_GMEgc#G`xxb(G`O|?+G ztVVFf@XmBzX#fDwb#n}a2>Ld#eAlP(@{+fG$N%ifD7??Sw#j)kho8~*bL&MLjX;sA zqK$Q}Lgm7R&QcoUZcSH~=Ts*?5}1n^?tOL_yS}+#{G%qXcX%PD(4yb~q@6OAS+Dpe zHUPO`gx0V22}_Qz>+n6)6>Xo=MH@q|@X%9May!ZCT6+*{ac;iK$O09JRloDb*!FOT zt;ZahNnXo*LG!)}5v9qd2P}@A^e`Sl>u$kwMJ0=W%WFGKzgh#d7`;{FAloTkb^hYv zS^MQSWrBFGC5n!p-uTsKM-Siu_k_y0sH*%PSl=n3`m=4ngUqcCd9@B%vmRTs9<+gN zvu5&DubEn~J@(HHD(Bq<=@&rgDrPnDG;fMk!=fSTXomb`mrzp1fu(K#`hb{`&x}lV zR)Brk3R9N3TA{~+T*g)ZnL_Q%AT^&ewW#JYyR--bd{(YLwPRWJ(rMI#MY%4L$DRm3 zeU#^<&c5@d+Uskor@S$G=KwgGrjXpx0(#v;mmQrGf_sV%#;4>laKyCv6rH?-h%~iV9 z#u;mP9t0FT+#=69Rq?xxhgoD25b1^ok6s@5Aqu0>=Zn zk`=XECWnmV8$kB^#_@@w?Q~-CKue5=6&^2~%6X^mR?s%^h)MQAVd0$Jv1K}6V#m$T z!2>c^m zt#`c;0MNX{tiJdxeZ)@e&q?%t+xbC*-ZCmZ=@S4N=7G2lh`R4VOp>h$Bzim=jYx(k z%tdiNO#B3ID>>%IB4|-ZT#?BV3j9~T{O8vTLT6eRbg$v_Vit>5vQ_T|XEbU|iv(|4 z7q&(gUVzlqiyu&ZG+}@KWKIuB!H7)wuNK@Wxm&Zrq8#gJL?V3Qy=SMK6?f!&Vk4&Q z>4paUJZ?lIPWM!;NVkfXrQHJ4s%8wOHB<_9mSE;lnrL~#v}D>j%AEExUik4bse&72 zC{HbvWr^^^4E7^7<(aJS$tN*a!7C+!hl3i7#4Yrg?3LsyHZ<`e#hP4rS0ddTiz%jb zHrqBw0w2-m!~C3rt2&5s6_)hEkP6KvBq8{8*JOeHNRvJ(dM#(jEf1EW;bCsDlxGLV z%LHh%wgyC+()*D6gu~7S_kXY0B9cu~>%^D5yHA32O<&k!&RjXN&F9zH{N3;(ZA@z= zv(l$x9rJ7$vt*!m#ww0Z*h)A13EmRg^0`*jdjnXkOmi50h4@10Ru%k3gl0?Eh4^L| zsDkZAV4dSJ&#eEUk!_-d0Dh~DvZ?N#J#ELGRNs+Li*XE5Ru@^B9LI7WN}Fo>Gl1n! zj0R`2)%;44DW~dfB6&4+*qw}zc4_SER&2}6dhx{)W;>IYY;=3ZgM6L zM1zGh;kf7xBc^s{=WE8kAuLniSpu?}#vZ9bgQ1kA6px_vDa{$oG=N&S><8zO^ihe1 zk$5LlZ}{>&NA5k8A>QBI(VL=G202Dt2 z!@@I(*)7mrw;~F>cf^3a zguaurrS-aA$IC@?T4(1g^9Y7&-|u$$S9~$P!YX1~qXfkWHUD(Zk*;6A6(OJ$#I(z) zNqp6Gqi;yDl2q*X!Bc;9w?#tnq#$@c>9vRQ&p?>;=@J(2FvS@nuYl(6)7En8DUApy zG_QoL!Zcn;l0!h^6)-rX_Df-6SPokYHwnaOr)!H~m@KWdax9l6>L^RC z<3&l+gVhgV*Z!a-r;IZ(Lw&@Tqc_JAwYd22N0t`^D|Og}OZ7qA5Ao$aq==IAbAIxP zB-G)`DR{41iaoKcc^`a4ZFb|_UJp4em|@=> z4?lZm2{ud?eQ!YbJVe&lM6N%-szaySSb(JUqpZGc-5EQ#V(j#)o)S} zr;H49^iKrXx7G;DeaO@bq+)at-Pt|wM(g;}=J%|zlsEc8l0sj|eFz*Uca<2f&W&L~cQ2Tc!^~MxSWW zeO(lft6q})6z&CM1oAM_HjI>VBIIB^k;Feo()0mnzq~!qsVR_`x<7b7;v|GNhQV%u zkaoZ5$wMhe2u|rOs4B)F?MPgsA@Rby!}E(Hvn|xm-8io?i6g0cT7A|8!p9L2(e-v| zfghc?);f^MI)GKE;Zda|?AG%Fp~hISqr8*q58FhiWm}W(wqf#(ERHl7)i)VD=a*r? zkn}=pM4?|6j5QgWdT;IEk=8{OM6%w}yoON3S!FTu(28e)q`K;ioJwVTs1wy9Xvf#; zMmOqW>^r3hxXyGO4aw+~PkK;EnETy#c6y!4xpfqphz5C{@}nT}(_4WeivF;896_A* zeYQw;m&45ycZ{I3x*xNR=zx}LQRt&|X5M@l=r>`XVQax6A~Sa@6ZK72oh@@3T1L(u zd-Tt>I2OkNhr%ku)1eG)_t<+e3wL#KpZ>5wF^3AE&qet59k{m<8-W$`gWCVTHU9lT zaCEoE7mM@#BCmf7UdOoU|Gfa`r?(}$Z!V{MwX{*}D!{FZ&F}mSvl88mdHuVQj5T)DyU6d5Qaciu@S>5SrsL8u{``-F(K!tUj$EX*wjn`e95GJ z7rpa3&ZAD@$ZXL^#1DHt>nj+QkZrSFm}@Owf$+zQ(9VQ%NGNd2=&(vyCd{IbHf*Ag zX|cH&d?d_97ZEzjI6{NXN_Lh22}4skVe@fR9u-DeP!M{qbcFJS%ODs-NP7)L=3*d4 zU$P8nQ67eI*$PR)P-q^WNr#x*7OqjdK*oNF!>A5pbKO=NPQSTw61TUV`@ow-dxV_F zw$u)L|s3TWhyto{;jr)p$Vqgt+`D+8x|FKdtMz<)~!GS7<$_$)io$_RxVgj$Te*(Brl?@V-)J2bML7^*i2as{_KPGizl2a;Adf^_FhIVa60CG=(!IWa098X zMlRV+(3*I%GCO5#UL`H;?J9?-6o^TUvZKlCbB#M1(}%z}I(7Ou#+*K)pTDki#JJ>% zL0}9X+kqUb1I=*02gfsg+4)ID?9Zox0i!M^b1~Y+falO$v6O}?jH_^_v)c~GNyAHz zYFn`gKd1j>Ue-;7$h)IM;ulM^kpPVMX^TbWCt5o-mF0EJxT#<4j5JJfl`X7W>X)Mh zD_*Nq=DYy(H+E&u-4<{@Kj$+&skvc-mHvs!j@eWOB{Z)Yh7bSS#&GsJUTz3!Xt!C; zoSbOWjxuDmv~)I`=gr%vBYAh{A0dM(QFcm70Pm;Q)rKNmU8LomBptt>7!KGj#tSf11D2Q~kBTXSX*AQ3MuD4F# zjR^hSez}PNEJf7RO4PKpPOdM^g6%{`(N+!g8(SmfYc`}D<~f-cCmhwWkc9v{@!8(> zp3*~(qN&3XS_LQHo>0pdnoiLB?M$6On54*r6Xm?J9)L3LZ}>RCs?|o`3ueCfq$gw8 zfw!zA3Fi(gvz-)i`B71HaZTG=t#Y3FSr)VbIQWL4Vi9oELxmc=2*tzX*C*B+W>_vW z(kEAg{!&C;Hly8P_Q;pIgKy&YvM(c)gvB4~MpVWnJ>_{*WRB011}$@l<-8`HPotP_ z@puLFowB)MhK(|JybUwt?J^xw>XWZ$8f0VoEv9#@nj2R!i@V;Qn$U;Hw#}E2fBM&p z8ESKZEEFh(y|yq}nX1UpJ=p@z0(1!UV)sb@f)Kz=*`*E<>I^DPn=6;T5%^587~SazjFeVlb$+VCC^$&?T+_zfs9_L1WgvDEw~LLTYI2 zkM*OEeNG&DL6KVgHx2}WUCuom9|pUBPw)q5mP5n0>}cHqu+vU<8{H>Pc~E7p=xqhR z2J=`O?s`B7Q4(AJqy?7_WYz#FD2N0K8xU8g(y&)Gr^n_RlvS!~E_E8JRM8k-?;;t+ zUDcjM)6D08Q{1^?GP%m|Z&=saRg`BI1}30yL1W@44p?$%H$3=xBhkZLR1Iyj>)}JZ zA(2hVjE7cjUk=rVC$g|oy2E`Ya_^=MG+GM+ZMA`|M@CFYYrA+hu8*NEF3-yppLnab zt=-nx4BUxV25vcY3v0YPM`5i`hQGY7o;V}p0*K)%GQ&VP2pTg0A#DEQmH-3WD6YDn zSyH&I7p{huoj&`Nmwv(ylKQDg>HumUK@XZ{i85m26(L&Zi?L6N;duUFHxJ8dcexo+ z^^{>P^(ohu8}jJLGjJ@5F{z0Sxf*CvlKtI9nZ|)0VJh5QeFnXWWiD3Zdb(+>+rT24~?EV}l@7br-!Ha??IZNNX+}Or1 ze@$bRh@>b@O*IgqO&R$eyxl*}2H-h#T-8iD_ih&{F8;fz5%co=rann+JKI*ZsyIX5 zNoSyczwdDf(o8NS49txg4oX(%Mgi=+?v+kL|3}kRMa7{7$$=qAaCdiicX#*T?(Po3 z-QC@t;1(>w-GaMA7~I0n+dca+hjZp*KIq%G`&Ly~UqL4xDo~+tRRlcJ-UWP}OT$*o z;Si?HEhN2ZW!fiEG>9)Y7$faiexW^(@pdF-`RYe-dkmhUcHPY`iM%s4n#Wy z6xL>Hizt<-3{H*P6xiUT0AL6-mV&w@)kvyX#(FAEF!Jwt%+!obyuk#*{nSV*f8y^G za^j|d%mO?+YnBFv(CQpFys-@->re(j7FZ#PA~HSqP_u zO%MxaALmU3rT|F3y$m$t4Pe2CI#u^vbqtftuL&@7sc_CleKP{2x`a`4om<@}V{EW) zBCpATh@Xy+nB>_(A?R1EcFZii z6VgvNG#}Sj76S=6o5KWGuZZr^r%l8ZZ zBpVaTxc9AF#;Lx{-Xa0oMRW~sIX#Jt_S8iQL^Nn(IZL@g8+cctqo;U6eKc?GUs{nz zt7I!v(82UyZH6g&%4a5dX(0A|b0`W$I+l;HFv+W1Y;O|3-m5gpYxT? z;xU!^D*3HVZ~eUtW)X8$+=jobiuF8{AJ9n%hV9*Nc^MG;!!t8?F5)~=foFGlI?hqE z#=#+PNForlt(wRp=fO#{KA@{_CVux0hc!;3TEkknf}4Dazom-WC%YO-71CUe5eR9) zn{n=9{yrx(U9b)n%EY@@rxs9~43WVQs8?RJXLY(4V2{+>dEz!_`D6$cK09ywQ5F?cGuuyn3d-8fY+^1peZov(l&JWT=5U{f)NC+@fSZ z%iVIQ$BL&=Cf$PK6NdEuE|pzFF+?Dh?n5NFL@1Kt-EJ>UqB*I0oGOFsL@lbeceBEd zowDr@v*gXDq(My~>ehWxv}awQ36F0qr%ZqKFio6W%}qC!df}i}Fb?Z;x@WI(R{R7^ z?EO#FB8zd%06|OxC9nG{hHE&a_nm?-MUg008G#A^C(@lKmtIWpyi(fF(a-O%=h*Yx zK`<2KrO;|ayk2E8d5rwd@05J2abY>hN&yXKC6uNoDeRPkvM2ko(-T7|?vKg)%2>l% zoL$qgZ1Jgfe0A|k$?bgwZqn%4GOw;Nb2R3KRSW#mD(xmv}~p18Q6ryI8=OWs^JRzd&OKR-Grs`$tAC6-*`~TMoxJL zDFfnTKv+jQ$C*rMUIj174wi&)KGTIPv(??l?`X3y#~$J)zF0Lq8! zY*OWW)nU9xtv~*_EZuiR_&i)RdsWBSPpAl(rpNwUf3%~{N-AE5 z{=qycx$)J806-C2od}EC?Fd(Bg~+zCWPo9~IA``GIGGdWkX9WL(qi|vAvFtZNxzGb zJ>Tm3+p#A$=q@Okkpf}*)FeI+oj?O6xQr_~*Oaf0c0b?tA(3N^Oo$M-Hl?{KZcfEc z3okQq4UbbOFBor4Dftzf9Q~+c`qKliR3nt~K$TsHQ#_Zf{-=UK0HI3P*~e(!nNxFKDMiShJUQ7d(j@gvi}*OS~|n2k}gWaf$h$(h<&x zm({9&GaYq)TEaP0^Aw%ei=9KJ6HZ{4KgxOeC8;}at{2Bfh6=IVn!%{ia56iN7FiJC z{aO9^hCh*K?jGDiY_|CJFEMT3{_fK;_^0W=zHl4NGRqS8`C2y5FscMfRg;jJqo0Ne%BK=BE_;dsLy1dMm2~2J{nE!IUGe;o^;0B1&uesq$i% zc(6+?g0Y%W_63ZDXALTHzRckjxobG?yga)+p=i-&Kl~8C>H&*{Dt-1bBd-PutTWhcmMcb`_p;2}r2alq5U)dJy}!MJ?rnOu zU7hF$M&J#W)AC4ER+A=t11;jhD`>v&Sh1l~dl9ixjxgtO7mcfdnDqJL^q7Rg`H5(` z3$V2U5j*q+5@-8wQny_R1?MK8&+N$0xXxDZ3GL-xK2?U;wg3Xg7{@qQSV`{S-@jN3 zWkTc7`o|3D-QfJ9$hj(8BD?R+ULt!i;yvo?2+%2bUis$pORxs6B;a5@J zPGo{exph%IZ=;bqFrN^Z=Z;V4BJt{$Q&;;rmbBwliKHy{8U6A(h-)F{o{U7f&^sxx z1{E-60`zdV8bz{9NtR8Sw2)geV;v;UzU`k9?0N3yc+)IS1e z*V2!&GqC<+Hu1BhvElfvX&M`G7&sJtlU(@WFkPwGAxJ1k9-g#fu(1-?N)V~2tK&BP zZv~hz=l=Q|oZ8WL+m~TwLwfK zzL{)wYQ3hv%Xf>)dH`NL-?`-+_N;$ziWZ@Pd}BLX;qJb52wQ5AfRe$rjIfakEPE)^ ztE?$dJXkX!B`4KVQQHv}wsT@zN4)PHY4lC=dYKXf=;S9TEaX4UE1VcAIz;$=$4YhK6k`u!zJUJ52+I#E*5 zpd$rID4M13ds2x)*`fIb$6D;{p~|%=F{k^Sh}(nPb5ECEbGvhoTkwl-MuUI!+1dNI zuZ1b3i#C7DUJ$E&k7+4FWsMXM+xT;vKn%W0i*O;cX+A8Utg*C>M(DLN7g}9lkgARrD=!q4ZqaDud;dL(M|WU%MPK($MR3k((`KUd}3O0WbY0MQRLkMwSPK`xZ{hgS7^| zC$|CkE@HhTbBkiW)3E+XSh;6_k@PCa#;cTiOU3gQia)hJU5mbUPb-sn4BYE(p0N1* zBA0ft*<Dy#~d<0+SYO$HaDijQc0?oAAb z)G7d#>ip>~{^L+&d-OI80e>VorVcV4s?jGnJkc1ma?7>)O8 z#@;dJqOr5#3rWb~h6@)s!)WD|FRag%Y2zi!L`oP(?Fc7~w52q{z&JvyS#wqOhS-6%j768jhsE(;F5zLGd{q`^;qxOgDUVv!46Ajk(_Bd4T4`HmUqY``E|*;?v* zfI4xT3u@?031>4}+3AMs2`gU`RWB#J5*U>%j#i>YCYyBeVwfZQn>+@uR@Hej=!K11 zb|iLbs+?@VM0mQ6Epbv0+IAzO#H_%^kiwcZNBnbfkqOI225tQVwL%xUT)UyEtBw|? zAbs*qI0|_2xvuAVcka{sk$m?I0yXZ|P7dV3X8;O4%v?#|wyl>%jMI{&GBb_ZQjg3p z+WaybjR&5T7Hvk>LjfknXt&z7%2Px*tE4h52RG zS2$VrvEsTf>N|;P1t>W0;~eU$eK$P;$5b|QhK2)Fkd-Fe0^Mc?Rt^O&DUa5CBak>3P5}l-y^l_ny5}|T&c~1AuAXL>xTeiM8nfut?NSFw2*0_C}--ChgD4 zU2S|$1LGO__=?c)OsgyGSmNvGJpU5=9}5nJ)>bV6prL)#-X>onW(I<>@W_I{F#=&E zvXf8s@A48dx64OHbOCilwgrM3D=t44ZQRqqskrUu_vJ0$5;i1xuAR(X)$5Olb_jcl zWqWaGIOWhW^FO$MHUF?EV!i(8aL4jKclG9l$K*$&q2g6>PO(i_vlW(QyC64v&4ekA zeOOAcQ~Q4Db+TEEz7>Xzz@RF@)$73N@Tvol6D9{`Id;m4xZ-*GiVW>XweTr zFv~hg;)W#li#3}=$ zY=_f0U$BIVZ564gcKreM%VXLvKDF6U=&y+I3tS$$e;a@fobq?6|A>3FE67L)_=5>g zLmK+d@x)v!?whbl#_X8MIqW#*md$kEdqH+sD6{5Nr52pl47u83{$@M;EM5=n*$$Bx zzx>aNuKQ+tB*APoJ^if2HiS#A*PO;!i$t)R#9GsUg-J+qPW+vE<3s(*X~`a;c(-!4 zT$LZwKi0>FKxjV*ef>`PvsIcC_Bbkw6M}hGGz+%RRj8h&xAbn>+6}Q4sE3@iM%Kx! zT>PILb12&(OiyNyq)E!hDl3rI{2ltbJr)G~9f>$_-CRSJ7X}wOt89&DZ;WJK$}|b@ z?feg3CK9yw|IXpQ1yv3-+2U5l{^coo>ev8`E2Rg@4qMln6O1;6yhM|Wf-&AEM^QC1 ziJhhvSI;w?gpL`gezv=Y>@Ytiw!E)HYsy;Yra0;06#I?5cnlCF(6X|y{AA-VNBK5F zl*<2R_-|-*)K9-NEPcH68$)I zw*Li6;p33`?@&2s?`uRTz&C18?GFRFUg#r9O0CjOMZe)eKswg$JtSL6DLKE76n-u_ z8*wz^NVas*Ucsk5*;MICZ$Dp-#aJb8Bwuhtc}|mON)}CAy{JJ?U`^?-a}K5N*}ZJ# z4}QSj^L_O}F!mA~&#~3wOSEdZF|uj<0-h@UUNUWPcWiIm54zhy;N9i}Vs$~3N#|c1 zS>=fa3UhqqlSpr#m$>oo4o4;rvw)w<#hTyC<6e@%$w1Zv5|u^%CIr_KDf7u zyLyfN!*IbJ6*G1q(u_-4AobZgchmJ0O;fh+9BCM8^>RpMnfAc4ISliQzBE>NnlRZ zx>VPOHMAZBR8GwsB$ZTCQ7F{!4jHL;vgOCqw3uAA5Qw6PN`moaXCkJ`k$C36Wa5x_ z0F=RlNthNX85bOB-D4kEU8;}(Mv6y~FOJV!(O+`mbYc_pe71D^5*(>YhVNF#zE=dF zLK5gA^%VkQw~>oBJ_!Dt6`CpEe;5yZ9V*ZHLX%Un@Z08FweH^l8Sm2nWx#t?xNR^@}b z-TR#@RKroa)5m6RLp#BEiZTHo8|iXa10loAKs08x^91GC|BS&T7(}!)0J3WmMe4OU zT7?)~xN&bNcQTKR;438+q~LdTG(VJ)E|c9^W<{mVIslfk*qU!UIPAYIeY?x|V)B#* z480rXdzp)@_Qz69Jc0HN3=yR8Z~Nt0<@@gP9bN1E$78K87&%c6_?iWMWhxGGr0i^{ zORiTBt#om#OW_Ze+c_tqpx}y2!asSHt1htp}xk3qS zf8=CZKtlb*R$f(sFlU&t?8+Pq;`I$mw@a)Ehj0VCexrR-M=&SZrzQy;7ae2cV# zxvApF)Hfbq3zcVUM8b$kBZ)k14+D+7CXsd3i(np053IH%J$#X-4h^tF&`Qk+_3}#0 zIyj4F1}Sp{>Uyxre_RFu!xT!z7iqUO*c}ojZ+KStV)1-ePG#q%(Sj*`6{ihYClT`# zUsT0@E*1r};X7h!=8RK-%8w$!U0u{$pv`U6S?LmV|EE1{hMK>_OD5^7vhmv>FKn3+ zz8i`i*M2wpA@~hy%prwsSOhWE4gq5J9E?_U^GJ)ju+GslBqA$S3uG=~FrkNUiX#fJ zxn;UE3czA!+PoT6&B{#sBKyzh^y7j&=Z@~xAn?IM;XFWYwqGM4bYtezd`jT)(fV~g zTNNl#aGmKYz-E-5-g21(E(6UWK5dM8Vo%j6K9;-j5AS|l1n8Gqe>qn0rzV(4DJ?q; z-xVrS!PWEn2vThd0zH#!n<=~ECzS=e>%G5`ZddJZlEGt#>HA+^at3c{M~poS*6>nU>Jt@w|wP$6+2rJR}z#0Ai|j z%t2_r?Kne&O3}^SAB)VtV3B6UeHU?`HKkz~=0BoQZ_w#)lG{b;7%F*v`4RIWlMtx3 zmZNPJEn^5)_gwzFiNX3LyR9b7k2u_MSRI0+5M)^EmVC zrcWCoWe661$>q6c*86YJ?2L);40?yrCF8P^fcF#0&2gTmg$| znGYiHp<@b*^Wpw55M%z3(>zbZ6B2z8qMQsUOT;mn7FJ(;BS00vxn>2L`0timYub(^ zS`%1wj?wLA8v}UUM_~CH--NrEYwSfi4V;)gKT8XJt2vRtEON{%n@9{gELGR!p(|yp z_@YqyQ|;0Fc+p5p!W*_@@_YUJ&d2yvrLBzzLv=r7()&sukn=XnT9HtYqdDX_N}oMJ zyV@|54h9VoLVac^_)E0Ni$rfouIKrwank#j$NTMIUV9SJAcoSI6Zt`mF0g`mS)cL9P82qrblCk{Q|ZB=zDN~BOW6NmhDFn$ry3W&qC;UF?*7X502*mz0ss| zB%>``blK#7^*PVotG)K82c0nrH@zYNcJU_%jHMlSB&9qCxKasmH)KM_dFx7y@F_2K zm&8qTt#j?n*zFpI&(oG-@Mz{SD`|(1iLxIkbIL?vdo6^r&>Su|BG&(_(4WAizY*y{ zM}b{?`>jX}aI-^~jDCTVB(y;d^KNlzA4na^?1x-RZy|De768O5)z55b>%#?(7^Cxm0lPEf8&yEhEr`VxTMOq_*88;^(Sthh9@lZTni&MKqw^1YhIY71Nntu^=FhMI zS5n;ko0L2e%fdXNI&%Hq%;v28y^VXyiCKH4x}=?wW9AJgr7D?2GIPgV?^AFYHHeFD z*$=71XLw>@2p>}gGFUj^l!J+p$a8hjZ-_h%LiPpY>YWumA-UH<96Sc3g2Yf-__QZ?gi4tKRXKC5H|GFQ2VTZX<0y*L=zj{ z!-O2~*(!$}@3rK}=7w!ws8Gp{)wP&Ef{|$}EdgEM1peqabXnV?c&;4qu!Ij+sX3n0yK_>S zFvRJNFBwCRL#I@8B{!6NphWa4VeKsyRp%j4b!$=2>NPR3uu`j|yfv5Q-GQoKF59^{ z6PH{P`y1!UFVA|#w%hJQ5AXe@zGsk*)!t+_SjAH3v67E$gP&rrFk9}tg?~ymRK#YB zV&hFESGFO0pMNcze_T8_d>%We4IUbq{>nF1CIgDM+FckT-RymJw|vRf3PgAM_M+I^ z`B!PP?UnX@88o}6Hz^zmq1IGfHGabK4Vqd!pe)En2cw^oH^Lv1I91R}zCAYVc;7B|nmnjKKW6sFa6=FDHF@h8 zbY!UHVuVrzMzlsVlWvGEp1m`+ywa9kmTx}_;m#&TkIprayS&>#i!Com0qtec$bVcr zBKnTlP$tj|ZP=$($6Z!fqwOBiydbCTd?9S1VRg!}?8Ki~*81z*p(bN-R>I2m6d~w? zV*!4lf~#Y3kH_87RZ+4om4UL(p28HolvdeJ@cOIsMK6qq&YK~!_Vqv|Ai9DuY%sc{ znopyp`_JlNU`$8IuksLkgtqpNrGfNh9N<)OJa5~tieHF!e|ommxCn@9xsd^A_g7E? zeTTSZmM>K@DRtOmmG@nil?;Ui+zgd=SuN#s8MI@CE$?Tk9^qjGWIiI$ILi(cHVdXi z?ivI(f;Qvk?!?Uq_P?)**Sxm;7vK%ldBrqg<)^&rBfBnSM4;#bI6tDdtJQMa<#qsX zn@~64C7;>;wqA!*(PV>0<_k0CRGLw1f+8`@%%61qPDiUy3?9Lg9ozB1+S%RF@E(`c z^8G%OqmJ8%^qn#8%$-Oa+7+zrgon`$u$*1Uw%yj^@c1btVD(45v1@?jY1e>lZufbN zJ1I*F0Xex43L4A7;yF%y4X=Z7iG)xToExmi63tD0#=}t5_jY;Hu)Aq|?Lc&HgLe$a zZy(@cEyeSWN%-ReyMz36H9B38Nb(i54fbr6!1PMJoMO z5xp^9#w<&NhyHx?2W)lak5Qs@T`qjylpZ#^91Shc7_&+GW0AVt$O;JAXGr%PRw)6@bgJ5s$@+IRi5Z#*+a>hr+7V)`DOQT-Enj|Z>)E3I2$=~Ip z!<}uuIGNbUdxN8us1Q7V-xo!Ioo6pr!O;2|XXW8Ne_zvst{j3K_B{XN)i@ErT0>6` zZQ)S6N#UdIo)RI8VByaW#sDl7@wO_fWN1M=*zks26?S=Old>66Y=xpjVCo!C#=^eH zcHYm2oi-3Y7Rk%K)WlJEPoG%=q^!?L&1|bojIr|kH#XvMA4O8<-;_50TB51%zRI4dT4J}t^FyZOOuV0cFfyv1LQk+Cyi6YI|G9ZAq9 z*BVp?eji9={I+67kFiwexC$AM5S{*^-%L_zsUCIH>W=Yhvf_Y~dyySr4)K*<#^v`I zjxpig_8{VFW{mQ}?-bJ#ab18Ivr}jPwb<63wQZn|)(!pr)hVo2!QqQ_SDf*Gh2%c+@;)e}?xqbC*i(32d5gOK|8e6&VnVN&XeJJnGbnN_y zZgB|>C^~iCx_p{cRUvqH|3)wi@XdCBBi7%#4a~kSl^ zLniY%&qkQ zR71uSt+2N&fGjC_w=kvwWmMT&g>1hS>_aXgJ2npakKJ%u#xNfCB z5Q8?6d{;W-efBR=%w)#QGX$Cc%><0g?ml~ih*W{TArBPb87xNL1MMGN7lgg7K1mjO zdCyo-5`zvIW&18xXNdbAtD2?GHhvETjc|BF4wu*UfosFqQGH6qR%DqL*ao0C;+_9Y z8bdn&%yH?8d@}Uzi)pJAo)wy^X)B`}u&0VV{H$8s=?eTmfl+a1GsX7MA2tO1MwFD6 zX%6X9faSX%JQe*N`NJecMYRB7mE3n_C=Wj$1=lQ?sSKhlVa}SkS++DJYqKIY}E(7`js!!?I`y$-UKox{@bFg^|O- zWL4zcxPAfcPz;^B3dh)f<@0|hC;n1Vr&Vbou*)fTmi3-W7m`Zg;Y}ec9obexu{I08 zWc38mQC=Jot%kJYa#tU`i z^o?NtY|9&^Ly$#RBl@W)Bmuh`OI@z!@6i!*1gO{=_diYmqG;0((^qsjS)X%l$07Ab z!80SuavU#=Ko6YdKpB_orxkE?e83f(14-Zs!SVH#z4P`(`G9%nU+Z&$@CPy=m>%8> zQpUyMmJoa_aP{?A3V{-xE=R)qW9gq!larq~A~8RQHa45Nuy&4Ts3i~6A6D=<8m*Fv zw^%iqyM$042WS()cVgTz})of86-5 zdE-PoBM2@NOMxTtZ3-y6ZZ>)QaO1Pe^0gOZ`1@ZyA$Yr9o!HCf#2g3CYn1*)QRd^`IhldhZ@_aK0i|+uG`LQ-J7gYrGCd9M zmRx75#Hj;7XP+;ou%d*>*WBNk-4p}+=U7xs8^(!Uzo~{xBFB(%`n(mk?HRyYwynx) z^C#D6E(Fd>kk~mo@H+Jg!yVf)drc=4`qU}9Z#TaD?V$&&KJcP6FDs{fEY!Cq<%lqd zm51twZ_~aA^%JvStYW0ocd@*vtHg+2V`e>xV{jEGZ~N&tX?Ok@TG(BlpT2ijlV0s} z+ruDx65pwud(w-?IO=*qQwka#@+y*}4&!Zyc>AY&)j#e|#VJf^@janQL2rk?+?u__=#ZXyU6cyuqqt>F)JLKiG4k?9b4$}_HX0p6SdLs#i*&> zng6ja5NkTNP#kJ^aN_ege|3lP6J378FVa=`74D%e8npi^iApJKiy>w8{&0A6`G%ua z?0+}WcmNtA?e#ed?QHYr1|v`iY9#8g|9wZG6YvLf-1_|i`qA(odJ#n3fG5%gOVO#@ z4gbZJuwQ^AK(?LM_tnRE(q2;u=7hhjG|z}SmE$?r*hhbmLqX?E$(IU_TI@-6K>%)` z2q=6Me_JZM7*dum(F2T-N|R8PF%2>=R!1b1Xm6K~>sHiJKrM#9rCDVejQApJ0wv}3 zgP26h)P}XYCGr}&z5~|-UVRY67+#@`u{DplqF^qSL-s0#157o2jts82n6O9Vu_ULJ zToB)4x4m~uy8D~SW}*+wAtTW$gSv0`Y4q)6&}c`s9(mpNL45BdYE0-dFmV?hUT!J2 zl(OP#rSR5uRxh`n`+0LP-WE&?CH+2CfL@s1utx5ra?Tk0owYbos}+^90rel!4;aEm zIgwxSM45l4ccnQ?@{ShebmF)n?V*H(3#VYx*G=ibLa8Tzgq?>C_~)6~dL>RGME>Al z&K;BqbfQ)U4-WtRf9z=kv}h(dM3-Q^T{Cv7G-p8UtttWxwf1`sKs{n*dv^o=mrNJAimrK{$uz9#P5w62(yZ{9fE<{ zz_7iyojza~Nc?EzkHyTqeS}*<$^x?S_`AYB`C)f(W2slD^{WcS#x;WNsSPM3B@`tO zANe;U9hr~B-DVF(pt=3u^lYxfA9(OGifa@w$vgy3eOyWQpicV~8nx}fhz~8xz~6u5 zbm?u;95Rr7OQY#nPT=UbJRDfx3gYSDc=cyN#r-n_C#$XAymG-^_U$rhQ0x$jR0|mE z&v6o|3RO)v`*6|mR2WC|S%G+nk>-Bn5b=e*JPgGK_-dDXrKS9Wf214w40wh`!cm z%P=!Cuug0C^3ZIM^C1#>7#i%0cWqi;V6s~A>)si+@<}tfiT9~Z{p+u(r}sCUop-BG zq{e?8pYErx#kU8amNnKZ^Wyl59CHPr%NDWi9%WQIHv5>BY9-H{OjoL0`c$cOP~g+& z&D&%^J&x|SV%%h`*TKcoG27|7wp4rDI^hP<=Qy_D=PTcA*892m&OE$D-so z`s;Q&@;;~}8tFv@cH8Sa$@h{*hEF!|t@1}N0m=DpwNR?Z1*V~|Jt0@SQ0gs%-}$QN z0(=vI8%?CWh5bF$r)}Y$|2d(g? z_TZ+mILVzKFS2Uazh-;Wtp?o~JZ-dRlh=e~-&c)@DsYI#4p}J)r|^zHfne1xA|B6j z$3^PGg4e*s$K4|H*TDm{xiD2ULUTTJyNr&N|x~&5zA6PwEX~>aP5(|<6zf?}O{B-2 z93ffomxz>_6UY@s48nDHjrR|?6Fy#?svb)lPgxlXh)7#QE2WQ3oS_D;7U{`86`XZ>mz5mh9Jcw@gdJHA1eSFPEE6gro#K6c-OiEnEwrEn0)a=7(Yng1$yGx4xo|N$4*66K_ z<-u@wodYiCMkG=(1AGs6oqPM0F2i?)WAZzG*pAPCzFfY&w|2U2!F8NrA15(`YN00ZPCo?aHa44PCeQN#nX`c zx>}8v`QNk>L58;EZbkI$k8MSrQq9lg z&+Nv~$nl56`n>T+c^u6Np!~YWw38a%pQMR1nPpDivuzXZR#;lYZ@u{c#p>!U;zTGO zzu=AI-(!2>u-?Dj0hdXm?gysL=l9Cng?g_pc6k%IRN$auZQ)Qn__KA>2M4AQ!07kR znVe&*4&)JNXzO`9eWxji*fsqK99BdTIS6dZ5(4j;G^tO^gE!~hu1ZRnYD9fLaC&dM z<77JWhk>vCTQS&(j7Z^7GF(hiwhR0G(>q*33p|6XnYHSGw+=u`h{xYtSK(^6jD+(u zUWGNI#I3jc_c^!q9+Pr@S?XkqTylO?3WzVfa{isb8+1Aum^WE_1eh;VMKTOorsb47 z4D;xvQq`6!2x)uhki@LRF^-iQstcjIac^@xsUNSQqJ`8X9Nj3}&gaSubNHV1`oj8^ z$A)NKTn*d`F)8zty?K918H-oe1i4!im>Pa=Hew zp6D@d?`8BO28G*EF&K5t`152Ye$h>@yflfu#hEjR$D`6R$feuScmXkv;8*5dZrURb zi-$u1{Ne5uRunZ>9tjxGB&Sa|Hv7S{yx(kf&-_xSSaPye=wxbje!WW|p-!v{f7gGnyw z^tPuwhp!{xy{Z*lUqqi7Umjrx2HgKT_PWmnS2__6AOM~V(m!!eCBP-#vD;Wa`37bV z!m#(jar6G2{aBszry@inGwRO;?aUxJ7$%{EkkUCdp1*n1(yx=SrvmYZx!Mo_=6j_5 zjIleNUsr3LmC;U&1kiYBgdoEHVahh;iGhB)Ke~nC?Gi z#!GXLetLgvMQDB_DWgl11UUIHs*@M7|(lLTf(`faX>{c zmx87}x9j@jv9cqljY|^vo{NH|=VT+ql5v&BcAITf4kgWWsIsBkRd(ZA=weh3=iTo~ z=H6ubXkxjpMvzgyekcgs^j0a@J~f1-j6a;$dc0rE^x$3pFf1v-p5<|s(nEws%8irP zA}uSXFVBcAm3!^{!*l$q_LIeLRvgfdYj~|W_ zl>N)IZw)Jp^(F1U3HLM4hQiFeN@&S{houmtH-E|w{wj8Ch2P)wNBIg$-AIX#^Y^)< zMSeRmITe=unOaKSoPd-ggQ^YcCj?I=KFtQ2$u;h;`Oib`h zTTS|W-VLIW%ZQDUr%ELL`TJyoWW)%D%_Ymjr+Z(Q^YH9z8==>|jC7ASK)BEing&T}3x=kn-^ji}8g06Dg@+>POF)Wx9-)S_89 zqTf2Z_}VB)@Rm2wRT<`reY6l7rAUu3x_2ka^!7T<=I#b5f2 zoz~R5$MbPXGM-OEa+82&&`?Auf`0;nbL?h0d&vqK!YWryG-MLQe0NUG?|NO6d$C`> zPb94HKu?FGbLwfna#wrvq!X5Jer9~?0)HbzMu za3q%()Dx(uhY^_4F6-W1_ued{&SEUx_@sPtVSSKQ*x@KHjP9*h#+_$s@B{O}Cgc}< zKc=qmJQ48C)+Gd=ryh9ZQM=-#7kvkNsVkmBd1T^#lBLtj9>{O8D$uVHq1CMuIcmcB zVTKpU1mO`*z|nfF{t@h& z9+>9r*4+#z@w(fErIl3$DSQj~wsa^~H_HCg3c3uc(d_T0;Tq`CwQ#7(cS+Ut+v#ws zyiIr^TA$Rf+zM1S7Q9m4ef;Xw3gd2k=lk!)cM5~y~%^|yG@p0Xqa{Q3eLfH@rd@37e)v`RtmtG+%Kp80Fp|q2m`>P-jZl8TO16&cd+yYjHc-f6Wyzd!ys;0w?{MpWm2vOqXzQK zQ2ELHsa~`s)=yg0ZM*;|AHwtjeg?0}q964E$s*hGH|VGD07IfCRB>p>#NeI1ej3x% zDh~FlD-Tjg^dEA)eGtJFS>@r#dRqj3h?X%=ewd4Ei+zP4S67(_(zq1RiK`J0O8I+N zS58H(1m-IZ$W*>$L0!Uj!+&oc*Y)ZT^dMF8ETEjPyQ{#R3i;3?TpftAV_gtBVKn&|m?k0xbEypB`gzVk}lkkfF*8=cz<|(%}2bf&WZ7bCIfjQ*>{!(YA zhZ7B{5^wu+)r^nh&8ibQvn@(oKQZ^#HB7#uT^QVo)#<^RmDw(laeuOBN5g+>ew^;B zsrFFj_wuxsNl62T#38a!)kW#p&3iMQN7&sBqxVK;!QwRzfzyG|6hrD5jxo)yvBH-HmF)3dbkLNb~ zj@=R&(5b~+wC>mi9+V^GU`_lH9l!YBnTQZv0Tj%fLi-Q<5#F8Z4K8Vm1SeB*5n%Xg z_KV%gl9Yy|@Cdzghns1uU%;}N!N>8mSC61uL?wa(<5R#wz*Dkji~4DuWoW)%PQN5s z6-KHZdn7sLnv?6e&QDF1ASz@FgbM?(J?xEVzPDEhHbwvgsjy`LWFc~kkQKb}yT{E5 zP+QRu9mmB^#zYPrOFfKcmDZr;*=Rvf8xhh2st5j0WD}PSV6?|gs&9f>=6qnWLZs$x zg!0(x@c)L_r9^J{CmPF?Va)e=+Q|=#;RMWtC+Eo$8KqAB0Z|{jw;gFha`+F>W1jTr zgmCDY#kXLId={G#Rr!A(3iopE z(qzx(ChZZ(E5B}UHv*ls{JO%@6**x>PzHu%hQGML1GFfPde6NVJ_e-eJTlxUdD^|LW&k- zN2Ez5X<2kft(=ij!R;T;!x*>)X}j!d-pTMgA(HWN!UXQ`uBXS7dD$<77Q~6GNPLSd z$nw}jbb%TD2^-tneDUkF)$)iTha;7Zt$|gatEFspnlEcqmq045;f6| zL;==@j;rMv#_DTF<$dd{679m|8b?vv;zKJV^2}tKHqVcs$S$ z;#2nr)zA=;(L{}8TT4FdIi5YMGH769Ep#VKdBVc)ZEs2r1fM{m&79UTh2d8f4|Ce~ zx8uQB6A-{U&A()jMR=Q!J^fdJ{`{|E?mto0G+NTw!=QZ6nzZt5h$<+k0wC#>DI&hL!8|o(f0!xQM+o-aRqF+|oO@O|i*R%y*@kG&XHFDSnzg#`1Xh^| zdtif_+Dr0#77=1rywh*x+dq;qsxx4k24lu;Op%na!8R@0a7imot7;oLE91rE!~4V> zGdSCtLsNXg1GQvv$^}_G6W^SN!detZf6QrSn55}bGqdUjL^qGU=3)~sT5)i(g_PEza3jmHqpdJLqBwgS8+S4J%n#aS~|JP&=ehjD(9 zvL;B%LG$J2#leY(P`hVsnp7xpMg(%IDCGBtd{O9D;d(lS!Lu=pT3vmDe8PygYt(a)5+OFr4s6YE9>4A*n8K z9COm&!E$!o3EUf$5Si5!A{hY=U7Z{(TJ)3zoy8z)K#cbbpvaQ5gjP+}ty}r+NsQ<< zqF$?#oUgx?2HID6*9T^L+Z&;^5=Sj1KYFABS-?;Ag=4oNo<{Za)nemA7AI-jw|h^7 zDBo;z+?$FWSGwklyofdP{A03F%T%I@FgB3FJR|bLJb(U}9jV`{6nFGVWW&LC!2SCj zLRpMaS^J`=k+;L2zJ}Qb9j;+iwgeL)B;$$iN3QJ60<7D-#~W{T)k|Nn-DzKc&)}jt z&z%fs=R7)b6-&@WO8WD>#=s^h)j6ZVCRi_py1eXc$#Gz=f$1^N+~jr zR;Bl-g^2u)>54U*NWGJdq``@H|MubKLNjmvG3EzGz$*;PD+ zft11_Tuy5;G^`Xfl9&rxUC(ddogprE(XYsTu@R7TffCXu5ZNEOcmHy+`-6epv&BSP zwvD;v#<-XS!AC2j;siZrYW|I-kKe%7EH~v#Nu2j;hC%2T3Z4xLDWNGa8B-wB)EzH| zNVb38$XDziTrYkY@#2WX%6

l3%?|Kg#7YS%yYD$e#@I&Xf7fim$?-Y@P#fFdguv z!J-O_UkWZ7vV$o>*h4h>hXl`?be( z*AA73QfVN=f6l>?%%L}ohrVozIS&4%69Tq(dWe^;VkBg!xh}m6`r2}bIqX%sF|iUU zwsW`=B^c&3$pzE}HW03gZH=`uYBa?mog0T6{{#I%0>AJ17(V`ykK(}!fYP_$^DzL` zM5#U$Edu}^OjoAfSDyG3kLjeyI6&|o`w>@ZC>vwza_s;URl2WrR{6vP*vZ74=2FgB zyaez;3n^z^RlI=SIG>oy&gQ}=*D)>eylLO8q0t#2#EFu+DN+#~KV}2?W?2}~ArQ=q z=)C%tA2HY6_%lSEMM$owoT6d*7!G_wD@Jq}vcx$EJF?{wy zc_Pb9W-?kf2P^?u8z^h!=L4s5$Ib&uvRs?H+Wvxihy8u%-}JG7QM^?{E zX|Qz|Ny@rFUzyP)0Emk&s^~=)f3jJ}=b9JaApHn5@Q773iF6ksjZ98!`{dHQFlUS7 zvXT>XoOJJDt@wN;C?(5@-PtsgJy5P^+397#zx|$%IRKOQy=wXRM?PA~ejZF$@S{KZ z6I1P@%p@BI&nJ=a-N+gW{@;9`B;RoB-x1w!TpJ8pI|->)s$q6)FQ#=@=W!0}n8P~e zZ9k&K6;06p*xO3?qmZZ)DR)INxZx2%X_X*-+=NQgSMjK<`0R7}=cc;O0+<6;cLc(o ztt{GiSHUZ)+s}EdVIJ$4#|E0N9;3Nqtkmb%7$tZXR=lP}W__5$C7fZV8Q(K`Wy>T6 zbCI2sAEzm@t)j92l>tey(kvPzNsl}IPIp}_TryYu+;M41-BY?qY6$DPXjzANUK|-} z-SF=DcP*ba;oEDIN~@JlRHUKocnQbHFdz{=XFrdWi~#*zSGkSd6YW|J-BthibfkZ% zo(*D81NXh}#UQCl*$IHPtk|k|#hwyC<9$D@EYTz_VNH%_3wN{VD?aOa(a6c!NATmd%dZe zbR)Mvq3Doa+;I-2{N8W~t~0XvRKlGnv?BePzUG0=fr{OpBt1OzGs|(R5tjX($xO6N zS_*oU%|!8IB}HqEmSG@Cs`F+m2{R@E=;(t)i0RDAy1ay{1#A6~yiB-5C$hxUG$l`> zBH?{XAyH(0_s>9+)$;B|HFUhKj4=6evuy6aM3z$Zmq1>*yHIyr+pv*ZW`ue7Mtqp* z(3wyhG5z#96tn1F=R%P6QS zz|t_Cz+w_v884bOY&?)c$tYZzvC}{Y9W+o!$0oD-5?0-0545ntoSz(RghoIFq1l<@ z4g&{B%yJVWCy6x#0S18hZ4abrZ`YnrADYT2x++3~u2-Bv7jvMgBn7}Z`I(Xp1`bMZ zI3$08OPAL0+8f^LBIkL%;hJdMeVMVvN~6-qFaaz4nd_8_e&(9R$IR+ZGDbr3O=vvK z=yx;O9GM0z0mJoN{)jCzhONv zU}iVnA~Hk8ZcSM($MFq*JzouT(d)Zd9nHL~Oq#1yw2uFOfG#_Z8v%={n_qOEt5294 zb}WACoK=7H$T?*}k}sPRVcN+O6m!V;<>lXyBD^2|9!8jC|9oj_v`90?US$!R{4&dF zrp&S#dU@bXD)%7d@>Q6{Rhm4y|yqliP5g$qu$PNR*6gY2-z zE&J>MLaxYq14j$r&MHjL0c!T#YL!4X$njS*WfEDablnd;IHLR)L1jfSoAnOML=M^p$@YLH5N<{UbR zY%I%+lGvVoY$sbChZ-R6y#@X57Z5f60&|_$yF5`=8r8j<0HIs=(6@23IudlzK@+CJ zXag)`UcxeLtq{E@9^ z09_ds(9}7f-s*ohHc<9l{TvoKHxmt)qqF5os@4Z2`M%Ow|5ik|3)j!TzUx;97nBFjm;B(U z`DL_uCOlgmvB^f5s!syXmRXhxVJx#uKc|0v{5w4F>ZA;43D+s}_qfYmsZwQwUq946 z{l3UM?t8HXzdR@`Rct%6HNxYXXihID9<%wPx8MZD*f) zsHxHZ@4N@X;gJ20I%6O3WFtuMju-{ohTrq{U;du$HrgF91SpLPEBmv2<@G`(ngE z{D3;MPdq=NA*q#Ckqe{jL|x=9Ejq3y-ECm5O?V8e3|FS8t&AWd%rU1_DeL>@fye;*I8ECZ-rv zGy2_3Hc!TBFj^$zf~NnUy|-zSBfG8ykAFl&0tu9wlzOV>Lko3{$wniVNDXPT6RQZ2 z016f~u4*wG8o8=%&p(+hS4HEN)(aZl08}=JQc0U`nPyt-qO5z>TChh}&~%F}7BZ0$ z;UBYj@4S28^XC!n5uS+z;KwY0j0pb@_xJ9-=iGZ`S=j>D-NrD5L1!}6BI&K1O~o-r zJ4$n`z2oDPD77v#yC0cn026enkfTAR$~%}5u5xQgdjaXc6jr$OpJnYZ#bz9C+5e<{ zeJ+~W7~)WGcb2-BlexWd=Omn*cC++0yPU=LHS1!O;;fUujn@%7L*VVW!#H3PS>+<) zA?ddphgLar(i2FfEJj!>XCCd3m)XIg;q@xxZt)0fEU?02lx;CSf3J8r%C^>+JC;D# z8)9rwLI8Ra8ZR0)RljSWO;}q9%h9f-30_T`xjcYh}jFhn0wKulO zc*7cbrXSlJYaH42X9K0j50>}wi{-a*vb^J}*s=dx8Wd?@Z#Wju$?d)~bu9TmeYV&2 z|9E-N)d$qYA+#f?3#ZGSEDbSb%I;Pwyx!CHgqH=4dh+{OHagS<_jee4PJ^xL0uE-K z+CJACJHxGPmCBW?QiOB~zAjXvm86>kVD68qi#v(O`6+X2+UQNGt%{c`0f0Z+V_h@9b;lli)R z_1jKT?6|j|Ul(3RHVGIgz0(-uboDk$Tw37?tG>4F8ppI zuQpb;Z_KNTd&NULO_-tmcJUZ9Z18CL{@`uhEgrdPW`@mZfd%Hw(7=~sBkWAWY#6^U zg^@h?y=uY%t{t^&exqq=KGs@wFP`62~+F8Q3XPTVT2}9!JD&#UAvz%e9kvE&L?BMpt=E=wg=STSS&< zx9Es#xBPYD`|#h#9i;8sejS`7pa-Kg6hl1u*ph48ZGKEh%)<;Txo04W!L+c(0`nHk zF&cwwjTsswPR8=8qehB5#mS34j0?pEGXQXr^?jTqfKl`kM|h45XzQ@Zf9Q1;gmg?DN~8viUg-gD~PL z&8#c;jWm)j4|0^rP&P;~!x{-@j%hN{Su?h<+WA+A;To^+RUVk>iy8pR|=0|93}~Px!EM32cy)- zNz%*u(GMu2F7)gZ?{Aql6Bi9011qP*&Fw(J=$R8jW^9l$&GXkU$Gce9NPzWKV}!kF1aVOoayD0*f=74zmrii zaZ6^tjO|F?Egs=^@fc?~#u=_#1^&V*?6mKPAx+eHh{*B#f7k9B_;zOOTJC0-!tD&fn2vJH$!L#;ZFyXyu1GuY zXt$HZ<>ktT>x8UU{McVNCkZ$pM@gewOY1vP@#Nrqf(b7cV@J`)EoCEbrrP@u+nV`O|Cv zN~7zW?;!uD&+u;_JjU1mkN>mRG03#qV20A=OHG*YGU75ACXINYT399iuiFhsHO%PZ zJ6CowOZ$|S*KC>pIge5P^}lJeNqzRb`+Rq^Nc-SbaFT$L9HkIiORKf1LKD~OVV0;X z8JmqgtUJZY-qC(aVK$iATo1n&iEf&B9jC4w^9l8fr3FXjviJA{HeU#QPO>$SG)MweKb;dWo67L@JbAZCAbRYcZfB7Hr^^f{FNkBZefc>l{On6ywkq%Q^2qn)d zy#G1+nz1!iy#7ovO7jDpq!^5}n5v%y6)Ic6W@f`?4JteKvzSbU47$y=ZmX_bO z-;XtAx1(LY7QFGMCw5>Lhe;f#6wh&l8A@!ByZ?1hkI)g)`HIXrl4(Px4_$=TFjgWY zW3Ywqr95{iI;dSikFoGzc^~f;pCGd=R_*rLo;1R-vrj{UKE2sAQkZ@z>k-fM^B?{c zKl|}d@L}`wgSNwF-x+F@BPj?bOt?&FWAHGisVy-JAwdT~cy-;6t+FGH-#cl{yhlJ7 zrrX71l&YNy5Le{Lu}P?0kLFU(Rf2xfduhAFqyu>E;Gkxw#+x6**o;doO=S=f#gWPj~-YY)w98JcbpW!BI zq>2GEj?x%SOegFI_UpRrzF0aZsQq0WdICCh$do zF9Z7>6$ca`0~p+HWhhLE7+5)Y=2SUUXU-9?bx6|jiCX6b*3!N%IS4pBA)Y2M4c4iwsE^v+n z&7i6*A;`vELL77y3rxMW&#cmSM@1eIMzz61OP@ zb>y{mmumM{YJ2EVQc+v^MT3nePm3SR2D8pHm5GpDE0MqXrycv( zEM!{?AD;Ii`F0Z~yiC}3mxs*0KLdmT9|@{nME+$ATF!T;IDzDHv)X6kS_5eNhk>jL z(tD`}tK-r6VK%2<9Z$PUI&U?ctGKid?FqMZco1={N_ZM!?$P#TFAj%}y{{UZ1RUrn zh0|NR4t|>+7N*HBX=ysr@8={jf%+M40sxM2x;Nd-hyT6e6QuT`XTi%FuoUwQzy^(F zn<^Vm-?%1kIyT~8iQ49IFq$q8cxpd4|7R$nDfCwX`#3M!If<3La_BFn0ds zHk>T)xV&&9yUvi=Vms!D&6uOxub59M*JjHJkVU;F2Y$N+Vb~{$5@QotB5@urCnND?d9u-nf*efT%<`l)a54ko2)-x-ou^Z z#4#~rXmU*s#meO{Y}_EkTqRg$jLXXdT|=tD01{O-PLg4(=o)EouweccuhCU5I4}g- zdFgU+VhF#}&JefxA{?2E#{J>}zQ9f7D6zuA@i0xx=V+(ovt&}N_`RcvY>=yCFOQv4!0sE#`y3vp~8LAh^XAM zW>mSDmIG2oM=DM6ICQ1ai|7rfd)U?L_wrj#ZYy{{VZzIUu?su+MH|exn+78a{|`q( z23h-HEcL~s<@>l-JhaLIBZHn}ZHw!q2#Y-^5uBjoux4`hO?wG_G~paYyYY`Nx*33!Q)z5@$4&a8Kb2YDPD%^;2fNj#H&05cC}C{@l893S}cDzcEK?`|V?tx`;WbTj|DP*GMy)VU!F-v2xO2D{zYlk{c7bRzY zl^rCax1-c`DPljCFZ>bjUU!jB9ivoYj@9rZk09*NbO_jkgr#gH7FxSKnMW)~t(Ktk z6np$=IHlgh?t>9@DtpaF zt|G=X_fe^gUXAwq{SecC%j6>8Y8f8mp1L=C4XJRK1e3c)1)ZF`?WpM(@%$x6NtWP* zXPzcwu-7Ota}}b-c24dVk6eEz{ag9DI&#fS1t`PloZ)zsV<7GnCpg8ibB=U-1K6Xu zh~98-{J}TS{Fh(ipYp%QqI}yiq0HUXk>W0=$(MLuwg_dygp0v0N!7N{fwrqOSWHUq zCAQoy91^Sy!SREva=X}rnb$<2Al71L-&HQ$CM*=kO|}r1>Uf$xVjv|Z*KIpNhdN8U zFm^RO;-Va%zIYuRB%-s#(BV^)Fi1L%Slfi|+D@9R5;q2NE9)Bz+N?<;pR<`J1%#$A z^<0SyGgknD9S$~_+ht|>HRi2;GKYe)H2$ssf1NO9p3*MdDxP4C1#T5jaJP7L(6)5% z^IeGL`n2EoLoAOeCL!~~Afcp+@(A5IEprAtyL_0!EB=d8G2MMlTB7FeMW&6<7bSOQ zzoBSFm?TQwYNR;FHI&G)8u8iVvGAO0?|*$9%vbdJ=n5I`6ekBC$GzgAlf0RRywZSI zceM+9!<}P+bK4v4kbQsq-~4}=mH#t7FMsX!ukQ_E9L1=Sj(UEM7ZK)uO_=byAa=+5 zqnioP#znuw5at9Qf(Og{_{H+umRpvQ{u<70kEfNgfHtv$aKyJ4-caux0?lg(5 z>AOUpqr>hR|Bg?B&ou+!J4^hWPJ(VPEm?`Vau~!>;Hy+lQ1}uq+HdI^_E4gnPG224 zcE7Ytg%qc_;aUnDg1f~dG)S?=!m@yxO=?T;=opo5%$Q+?1S0Tsmz6W$j#?RjZLT3r+vhRjiUws*)S78i#9i6@r%Yy@A7}&3s5QZrd(rgj>w*$FZWoXDE=_-i>)6=)WQ?9y zC(Aponq#KSNi9|~`9Ksd=<*AMpUZKGoFJ5p#AJAqD}~3s9KN9HkP{U$2Jl(`Q0pEa1QZvvG~| zINvyKNu+)L+{Npp|y2TDBTn(AQ>#_W71%5OM`Fk z4R^bE48IXJrPStEU14sSqq$|1M0#u_l^LG?_HXg!-@A@_{l^|7=sQK4VUjU(4B6eT z#OnzYt{Rw&+6Ow^5N7Cffo#$De(?RR%Y_A<4t1J-vHZ5{y<`f#%0WQFd z118YS(I@<$RaQ9%X~zlhou_c#VtEJOHN6OD3Gf|{tL`+t?&IdjjFLz@`t|4JZ*}eLY4<#>}C3oiL=AlBqDbUz1|M z4E%SCM_{7-7+^t>jb$0Mhz!t~9ODEWVu{9~vlM==ouyrIevyi7pTz0>`FVk{@g$U| za#Bp)M9VeVx8C&cFz#pLCS&Q%w6P9?Ddb|N?hJJ_P;tL_fC{N&ZYZ}i&cWQ}TnVEj z%@gT}G?sJIj+1d@%osx%&AY{?pg#W`N8WL8J0)_QTiKtK-%XvPQo4#$37E^p65+rM zm1X_H-f;RjShj}78=aWvxQ0gUEBwDgir;$NP#%ll<8>P~TDW#((!q`bxkb7wQvHu%UYd8{)m)$v4N z$B>h`j#M(Fj)n5)uvk;|{c%Vj=AsHd?2FgkF$yu7qZBu?{M%ErDl$QiD=!eNaFAb7+BF` zMCb_0k%(}@1T7l)4inc-oTHw^gb4 zm374QwX7j+33B@j<|xr1amSIOv3=#jc&jwZEOB3lF!?|H; z-m!{9XhTEPznPMa=xC@oP%#6Qh8Z7IBYg3lE^R_m7L=lP%|`DP4_%*v3H`83Qa~KS zCTWbBZwIt9Hwc!kznFdTJ>fh5Z6_&w3Yyk;I&EKn-aZEIG4?v z?y;011KhK$j|l)wi^B?uWnq8>B{JkzmS>WPL|oX+hs4pe201m7Lho!iX4pqU)QC?zg0Nh;m7nHyb~kYzJwDBb@|q7Lux1_@?Z zgMFGpr_nIxR2Yr^!L;#wd)E=;Z-A3g&Z3vSYN5kMivF#Wp8N#1FzEk%JXJrCszy%XH;a zd5*%TSxfDh2+X}xpUypn?ptLYCO%)4=Qx?|B=&jd7-jC!OocIoL8B#l;KXn|)U} z#wpmwA#~RG?3w})Y$VBucZLLOd#%}DONwbEXz>63*ME;MefbDk@+Vu3lUUrp9p7l7Ee7{ufV?T_A$Qdh1**Rt)LhQxcB+?yi+ z=c73{XE?S}kNhBq!c63ud+-<)W`eZeys;hgXEa=Ik>AThD)Dkw1T*`poXL^^&iDcv zl$c?GRW!jn2A%Y+AxYZ4qr?BtvDo@+thO}4U16adWwVtqzk)_yX!QO0@>^Ta=b|uX zaP}zdrE3mM7tcU^~6tX%i)F|!PL1&PLMUK)sD3Sr0SO+Mx`!@SsAxDJ;RxWp- zD^Du~3tO0~e>qn6c_%|A8L8$M{_lVHPt7OuzeT-%2W_d{gb5QgVgV$M!=?~S|0m~X zHb3c5Cr7V8hSM~|#{O>tRuta)Yw?q+UarBMc(nUf^y0$vN|DVfoT29G}a>-i%ToX`Zjim+ncN=t&fx+Y*ucIyd)>09;ps#{NIU3>(LuQ)o->D@6l#RSO*z7V?(k+wG{tBrAXs9FpM? zIbvzQ^BXq$-LA~_8Css4W$i0uHpj`xtH~r8#?AaPl;$M>s`Veau`P6!UWSP8gb8Co z=J4H&LDy5TEtq*3IMi99vgA&2;vA&ZO79ZTrZD3HrOSY^kj(#v#g?lmGfFHJ(;j0c zOb{F-z4N7Z`Uce6PjlW86#L9LL`*X0HKJK40|5sE%6w95jHRe-;fETT zU7im(e}fIeq;HMTneo40W8Q0!4zY<==kpC@xh@Gra#W8deS2B(qvX5z-VeUNb24f3 zl|wPysNBXT>Cd&3#NXHd%)HN0dcU=Z(Bz(wE%V+m&&dpHZ~vOL<m!cJ%nE&vaE=*D9N~HI zz)@SW!omuPy*3mmO3s%l*syVq(Hv{!sO8C<;885rF4HG6@4)&>9wo7)`Cm4MdLCHI1?}s={x_}j{# ztcVKxZD<2&8`l4P8e=A0K-D`jy|w;RNYC0D`i*C%G}aL@jTZl`_)9DQ=r&f^;Baj_ z+E>=eF*yjv>}g;sSbekj)I~~lQnof#p4kdkYb$j#%v9#yOT$PyG6{TB2k6RB*~Z-P zdPq|>d2l%hP^QL5IRz`^Nwi)D*VKC-L)@Y1hgj2H|D4(r06PEyzHxI6&%rueeJ2D) zs`USae$T=AXFvW4zK3xt_4IXa#zbG~-S&0+BXp8NU3{pQ7sFemc9hF$uE$8cwERw- zgOHPy=R!KLqqR(GpBtUglcBVqm>>tkGdhE*agNcOHp&C~+%oO*u;Ka>d|ec6>7LH+%Q<0)PxNyMJ@uA{}N*Gu-v1BSR;W$8-pI?B6Ut zg^@BF1E#crvBbNxDNZz>ugcGGdRF6i-uT}J-NSvN!Ba1#2`?M?90R*@mvq>5oPt*S zBAg?~kmIpBp0U3&8vt6h0#j7{=v+vdStR|TZKqC{5XZrelFup$V^VvciiuTOb4m<< zRxUA2lc{hb-Ri$noH%*N3Jd3KeSw=UX_}4_jR784YPpOA4bH9m6jpB1)vH*o${1d` zbC9@wKmO|*u=+u34`4pzTJar+K_*;RC>>X%lcQ_PC`oj@hHpqVfE^rm{bq5~yTtyL z)M8GQFG!T@kt^qjuJkU%oT6~>4d0LH*u02sH88Bo8gt~>IEjIFh4(Wi`!h{?QV!W9 zZS0B!kFE~8_ZWF7nI-don`xBuGA3>_vH`0xHI~ET_0v`NC>AX3HcA{}wRbB3N><)0K7lEvD}^b{m@GA) zLgxrDvcj<{KmsNhQrVm($&F&;2xeva8iYmuC-`rh{|EW}Z?Rdw_nZj#?kcp0%R z7}zIJ*w_(H0u8=JBHh|*H`?sN_kQqwm#1`*hy^kC0mtWC#S@gsTzWxf?H2yeQaiLQ zOOUIUaU_-txr;%XoT}FoTOFm4`rSP>>D!EtvM?sF5({YnDNPtfnQz>i4RXgf`3(*w zCe5B58)st7?D`p4ZkD+*(nOIarkstD>`5OGHgDAX&_fc9ImuT7#Q5+d@Zr@V!huY- zr}LUf{W4;2uG7X|)0hL&M2l}hH zx7D}5lk}sJdoM$+;{BIDX!H5e#=hjbR4#8$3TBJElFU+y3P;u`PlNkcNKzw8!WIo$VmdkLAg~t0gGx#BLUruNF*aVQcOoKLpe&n zG{YU47PtVgan2ztLXlA-=P!5Km@?Rpm-p~)@hOh5LaoMS?dpePW`hL({CB^OYAqQ` zlW{WPDr5ih&0Xv1Fqoh1&Ce_QJn3bmQ(C{OcR%~_PkOh|I22>fpEIm6x1++w=5Nzx zOWajplWfU%)j_qcD?jBzP6)B5)hwR4Hemd3LL!(I>@#QZbHZlIH6tP1mhK-yrh^WI z?jIsrd~v*V)P)QSC0=c5m~4~B#oi}=FOtL>VN$R`jwzHRwVk1uoGJD#vkBzUrqkD0 zm$P<{a1xvi9ie@+%{7FL<2mSK3p1PavRyrWv{4NJ88+@Sn*J5Cm!jvx7!fg|Z`C{P zqU*|Sl(vzv7ZZY5-7Jh)G(_LjS6 zU6-S-osr;|qvm?1E?(x2Ns1?o;~YF$-m)@0^Bm^(xhTQbhzPEsI7l@TC!ISKzgT`7 zw~NQF3Z)qtC7%(9_h0Fgn>7@YpVVMxUA7!0)|g{5MkY)chERTIN`srRR6gGg&S!mt zcHb#Z@UKS*;)KeOeZVp5cJUYuU=uiiOr=}^3}kZ-rJBh|w%KPXEE*GH%2S%K(^1;R zDz(4oW2&i5R$OB8u3>D9p=6Am+E#~>3TaiRb3-#*q;Ztp<#y}L?@8h3L?o?kv5UQ! zpQ&@W_&4QozKJL%p3YE;>4h~!s>f^V{XtI z*LD;tV4;Lv4s=+K8i19p`sJui!2mwdmAw~%8A>d$8r3;q#XOM~N|q)=A6ha4bq)JU zX8In-H9WVD;o358`d*RyN89sDg++gkk zEq&GsL$7 z~ zHm?O%-gXvN?w6^TI7$9@enAIa##SUqq8kp^O4Vo5vqg%Ii}a>;$=#`y9rD`ocyxl8_*+cG_G{Pgt&cZ+&DCD@-#Mg_B@I)JZN`5LIugadSzRag8XIqY^ucHj z*N>9#_BzHPlVuY8KQ4UPM<@f)!c>;NHey&ldFPm6jq5nWUo79`y3<2g1=9*U*?DTQE3SU z^~n_k`rp6Xk58bR4#!ZHU%{sQ8`RCeKWLv5CR{~GhTeAcnGe=Ii#1Vl*GGEyV0j-6 zQk>yB&Tx#|#bewp9`)MKF8nC@?m_FHEbl0bs0l2aFvJ~KON2Nyc)Pz8bHY_bFAE`L zjRX=6;j}9Rd$yqIlyRl4JjG{yDxbN zG{X|+9cg(T+t*Dh)$Ics6n-Lq<9*lu-W&&wu#jnLvxNS4`>;N| zB087qP-rKGfA4Z!t|F5(gyr%Z8V~yw4wVcf!Mg;$9^OwT_Cp}LSOO(obezTpovvHO z6UXC(<*3awtpgc;v5B!k=gcrUBJ%*mG2!1t-=IO?D6HSSz~6R_EO5%U%Ys9UQP?Ct zqr}-!0GQ=p>zEBDOnB9x<@`W+*C*aMtP8^ooh63NktTn9=H~N#dtd5(Q}%ZVyL1Dm z_yVbwFjJirO8@z{&mQ^dB4J7JNg6z13!@Z1h})pE6~ZhAekP6#1u0q?&vGtdU;qFh z07*naRJd#E{$?K|Hj!Psp7lCrJXc~LO6cTOx)@M$K07pdjGZBzh;#DLJrb1 zMWPjAH0q{}S@4><+z8Dm$(5P6cp?9#c{g3@hLR?E=@J*xT+`?6Ugh0?Vgh#$;(fm#3f(BVEz1j^ z0p3GLSPkk6v=5#vZ{Zlv?9*O(_ia0(*nfQ62m03n;Ht`Xqrao_)<+*49EIgxq{^kv zx7>{(293-Msk&4A;|TYAk#gJ#6RsM%@At&}OKc6F#n(B%DYiGKCWcnK<6M1?BRs?;}Nxg{_o2b48-`{1n$dO_;C?9;0-~2bwAOOBu7n(Z031s$BBD4FKG;S?H33c%?=Z?iDvlEg|4<0!Nr+K{!2v3Q{@heM=hvwS3uMVoc(w+}QE)d$=I8A89$j$Td#KQ9{h ziw9S-paid>B)^CEJnz#mizuG6w%aLf8|?m;b>0&1Q<1lcJ!acm91|NXY1kE5+e&s|Uc8Z*qWaebi1gb0k~-t8Jq zd=5-LYv%;b(H2< zQPr5zGp4`?WWv_Pgmp0niGxV=T)K_t{8kG!toEb@AeYd8n9&@#8a zT#xHG#RBK3EPFSW-uXpi?DJS*?yfdPWcofGD@NAMJ9SOuzWL4PL-#16+-`nAU!bA* zczF+Vd(Y-}-`x$3Wqj&`A(Oa_5(eSkDf`{n+)82H$75GDXQmx7Ul^QvW8T<7i~Gd` zS8LF~=_;(^kjq*%Lo zDYI%FqlLLuJn4Nd+whi>4~d`e%7L6PVH*z0VivZjt?CrhE49%;^G)L3apKOD z!{Mt$ef_P^FaazH$?a$YTFQ7EMv3Lbi6m+eNCZ=uBtCZX5c)l1=qSbBhb#{pZ-(ZI zeyqdK618r4tWxwh&e-s((NLs`qJN29m?6yH2#+lG-kjaSI;wt~-uOPB|A=ngsX%@15?~ah0Li`E)V8NR+!tpn}*hN zJGOqa_|(br*5!OaOhU$O(u6jXHO=@i^FpX(>9gX; zAG;)G4X8?mW0Qak;*<$V9d1ES)D-{mT;%xTaZq8gYL^QXvQI>pQxi(^=&Z#Y8yYvJ z$5djQwl=M(Nu{o+I7*tA1Li%F>*Y7}kJ;#eW6PU$40D&bYe7d60FH3pIK`a+Ii$S=l0k1N=?sn9Pu&1ale31WV~^2MONa!mgXL6Go6%A;TGtM{`tilsLyV zHLB{4MzViXHav9(&zRSvf~h=exW&vCwrEg0DfBkSK4iisOn5nQ_}$wMOo?!v&(qpH z>3uLHM@id9gzkkYBYuL7b(kt-xK%vCljW`6`w6jME@b}zVO!EWVL}^jM(n;-b|)FO zGm#|STPw}=^5P`p^t2Py5Hp#dCU#a531IW0z%{d|Eix!BKV zpir-J$DmW~>DV!OJnR8Aa|2o1sS$@k7#Y~V=2*9!6={MSXKWfI$gGhnj#7#CFw%`9 zoO=d}{yq758hKwM!K3B-xL-VQ`+iaRKf@}_Whk*yl!H1@06l2gw!h6erfnHbZ=k%rSm?pMLS182}*1;$Q=Z z?CKe=JLldnwj*veAor{kao?W9)cJk$OC-rx_df0k6J9)q2c~Ez?Gu>Vm#r}Y6=R2R zPNH4ZAi)MRG)Qr~c#Ih~7ajnWE2T$%ekaQy_-?|4UC7(FOJAd=&B+j(8Z5AK z1BGr|8?rc(g(XKJPLw_;?TGkC$9R(LM;tURudDSX_L|Z(YLMXJ1rJXpVvY|N! zM2(stLuzH=sde5qm>nGa*@pYY1AKv-9YL9H=Sa^GJcrPFoiM>NO7RD4*8>-m*(C@a zruYM|9VWwe=;>2>uY?jjIwTsDm{rIv(~`S~1t?M4;tfCzpi%-f@*lpiPrFRMXoY2u zjpH`6{bFXe(iY2pn*s*n;2Hhy+Fj|~EiX=xmicMNEk(1{p<(fW%cv;!GD4Re-G!qO ziVo1Z8SD4py+YZfFIP3DZe{Nt%^~^5r)HJ(5<@3}!#Sx#FeE?7pdF7Tlf(iqIbb8A zGsjOM;3k}*?drk1~cya@((IxoMh5j;! zzI~5X8WSa?jZzv2dS%&@kNBpc`4Q98rq?AUllIb(yw z=4GYUNHIB2Ys^vE%2?8~jxVh>X#ee-fV*XPeNYrMomEs^O|)(a5C{Yb?hssqyIXJx z5Zr0pU4jP-?(Xi=xH~lN+KoeS3GQ(FKj)tJe(14B?Om(Zn%}I+K?X%nt6nMu5~-QF z9e2xovj1klMxrqZ<|SWkP7`m_o84fbObpHmv5L_y%-u$;sgg4W7G;DGSq> zro`_+-oSmOoA*>CekIAY=m!cK(lJ#=rY{=ajLA%ctPI0!#z{BO+#TwiSPVy`mu=iG zvGkM}o!wB&n9@em>npGQ?5vDltEGMH=;1rZ#6N>eBn6yuw}V$N=;+;o*PTynCvT!_ zO;P`ITrso4-&ta&&#L4D6Z_wtPphknq~zA|@vV$^rb@+*vkIc!U?j@3rw_y2L_r=V ze$SAeVIl_~xL&HROvl?9i{PXxhke-OFMe8KWEG#|J5Su{Deh8fuSaTSuJ&q!&&dlb+y!w5blT4E0Q{D|i~7qi0d5Ikd7Pw{U8RwtOW4J0GAzcn3h=Cp+R5{k^ z6{C<1u%y(Y0sWX4L_Fs*QwdS}Tyj;wUMRLOvq(9r0PW#&CuC?z$x`$-nRx`)@_-T; zK#Cbw*YCuP-ga^mGubY(Qwawtt$)r5UB=DhN5|GT`{|Ad#HOrt;k8m`FFGzRc{Uyp zGWJu`CRJhl>u>L~ShufcNR{2tR28U7h5*#;GJ!Ne#n3#5FDeI5!EzsT6!<^%vC7tc zNP$<#pIN-bvi_m^ z&oO4GL`>B->Vp`e-riV9P5`$*)JbNAZe#zdj~>tM?0^>=--|C4a6~z{_BCQ3CZ%yf zTg*>#K6jW}BOXG($=PU%wR)8&4ufUD!dp@qwpS%@5U)+^k8-18;sRc(XS{A>abRSV zh#9*@Anf3oW_C=VYRIo#TfBQPhxT!0uAD}8@DXeK5nM{kFBnq#xyOiftBgWETAOM? zR4)Z_>5D79JoQ)l_U`H&w9TW#v6~{7++|}Y+pjfZXdr^mT#~Oo3UdE2>+IknLyGM6 zxcy7>g42grq^R9b^kCYi><$!SveY!@n;pu)BEQYuNFV23+6}ze|ii0tmn5~ojT;&+-q6bzhm5PF+y@@$X?L3nuruWKy?@2s=H4(n5{v!M)Q@ss=>FQ{qO8^>)MiZj_TRTb_mrzVvO zI9+j${ayMWn9gpR%x`LTBueHpbPv9}MabEv$=OCwa)MqZ=ov#PQ_SZy)hH?z(RCu{ znr_mrs!49Yi%&p#AOM|oZu2VzEfds07+f&x<9AU15z|ewU*d->FS`kHqyk)HD6@7y zF%oaL3B?>tiH_LF0*k z#LG@GHtta=mr}zEGlZyZ?RMAedtVe;N3f>XW<&5e+wp0?btMx0kYCyQhIHU#nZf(n z1hyai(;H9tzau2HI$9|U3CBrg4G%F*>+hr&jZzwuv!>!^t}y%E#4a60@1kPHVu%;~ z8sj=TXE!z2T;UE7kPS%J8a~F}XbBLb8=gThpI9+XvPT)D@?e(>rlyt*b;9WKau4*a zk~=X?8r!mniTkMqn72uUSRy;7xep|LQB_m+lGl{5;HR)*B2E;iRl)la=ZJEOlgJvs z8oDa%5=Muu#OeY7gt#xP;LA{)6wXtkB?vo+elFBTjYx-&x=JwQIZz7ET_}fJk^cS_ z!;B9tJNh{FD$sdur~J5nooWUB_x&qMMz>iO?dn8uq@>`Y*aELzxqjN%Ofv3lkLT16 znQQA&#W`*= zNUq2B%thc^;`n!7!;UY65XFB<~%nER9&DgjfV?|1vF2xF{MPJ4Ui zI-&WL1)MX~nt%S*+c0);{1)u>&|z3GpypTVoTJgzqM-l!;Xb>SfZ{cTgO`CdIPtfa zq4`32JmYn6RcCK4dB!g^weqMCjN&T=aH8jRMkD}&X|LWOD$IpTc;$G z;@;O8y$SMTcFW;j2mj~ghptUsqb@(tvrno77oRFts1cdL0-5(;*?-p^kXI6pq^>8* zH(Sx64rsBfJ3IHYmSd6i)oU0%A($Xa^ka(vD=<~z`uMk zdZKa>prRNRQ{8$4<5NjJ~Ptvpuyr zooNqxMBO;K{iPm?!W9$vHTilL`QI+MWb<`eL_)i}!TaN9JI_w$(EecFVQ%qT8D^Bk zP`^2qEu?*txK7y{QfT$SZObP z*gSY?PC^7l$*D4F`PDFmz3>+0Ty5C}l{#Fk-lr_nR0ePC@^7tM4OjU=6e{`wL)hS$ zaKo+417+?qV2m1W8t%@VtAt_LAf)BpBTM#*vL_X9m1Ku1!V=Dc8TF3*8ChPyKnV?<76tvjK{hYL%15hv^NHaO_Jc7$K9^iuNU~{M)v} zPQiR-rfIHyS#lr$>^%T<3Rropve*vHTs@hQYvq2>FJE@gtg-*|ceTRDRkDn3!8xNE z4O-hsB_p_W2^k%!jIgGST0f<_Agd93ud_36cUZ?GfNRfjR-Xp7qn@3%=QF!+5hxzUpc*7CpNNOiX(C0PMLQOI-(2 zH9jS0>xV4sT~R5dQ6!UFzB}eQoP$R0>}7HJDeD$}j(mB6pH3`a_z+?ov#J0J5gWB4 z{RwPxUnfvOa|^m1&NgGf=le8LZ3z%vI5XUg>$ZEaHr!xuykX9;^7F>hbznC)5Rl*t zN-s(aCBJ(#Lx6w!9ojc;i>=VA7wjQNR$8HP7b(^PONUS|>w5|ZoZ@68&Q%-CNw6@a z^6b~To?pv>gHtp2m#Wv-rDY&?c_o%ss|vl2=T*?Tssu?0#T>#+21gE$6aO3osA(Sy zxn4s4NQFvL60wFWn-qa<dUmW~P@4KG zw9BGp%+|VQ^#?l9$%0r58^6kO9GOf(u&xrbR{Zy5fwxk5}HLzVH(gp6E&agxP;Yn=6lk7nv)xluwK!CF3% z1X8$v7mTqZuivNZ(n!3CUq z#Pr(6OvSln*bP5%grsHW;eh7CcKxaOp{<^`<(~f3o=(vOpWD1M1+@8KiF|2f5gEqZ z^!`sox53fqxzWlx)9%j%cbgoPiOv?_aMds3=JjLIho+5CC0Nugv4@QVjg|Z<*j9B8 zI?uBAA%Nvz;fN^kvKj^ns?UO(6XtWjat+LxQKcb7L>KCKozy%3964{C6=9!~PFOO- zH|N&YP1(huoxOla(?N0zFj#oBR5Sd^RMXGwFGu!4__w#+MwCKIpV}9i%$cahi>1zTP6pIP{F%-v4ebp{MbdYEUu)j#I+=C6$^Z}(Z8lC_cjje+~hw5^6Fxp z=WeBIR2K(Z?Zhu0y5~SbLy46I$Yf(Y@Ddw+4R?1u{O|n{VI~f8n<4~HgEYVYVmJ1; zZTRw}g?`0pm7=?br*SCQkDU40av)Ea^bi5Ookp008f0lsESoJQ8aBvVpGK@mZx1K} zo9G{HHMK!=jD;_T9|J4g1IDCzX)ZbZ(~nlWK6Ntf0%}MK*Q~@LOkZZqH3wG$#$U?G zt$L%dZ4>Jo^C@v4v$YxN{+%zGf4lw)=nJ>l=wj{~1@pViSQ3M8fMnHYi9 z_Xh8?SH93(bKHt-9M~1P5c59iari91xKBc3^j!hPXSWFGC|~i0yDwo9R-)i(4#G1h zkLWlMIRlTRc4a8b-B#IE-r;-wB*xCab7E7aKp&k6V!MDxjlW#evx zM`hRA-xh0wt`YYl2J>22K2nLhm-^a;2rZxIVY4hhmV&L&$kFoseZkNBDefGyzr3&B zc4!yavWmW7jdP04c=|VaMb`v42`FUd1)3hYB6{8rVN3ztCyU*_47QYKYzZ*e64;p6 zX{NBv1(t(}(s#YCDB7;!)P#d--|Z3qysQ-?X@1o7@=+*WCzoeCe)^#*Ke&+0UfbrK z&c0FN(pAK2Bc|{h++?5RrdbhENRPB3%HMU5<#hwcSTOSkN@JNfGwOnMb*SqJ{bRLe{_m8(W^aDnnc3xdAyXQx*&=hi!Tyo_ES(2)( zTtNqcei#ZuqfU{)GF|WV!DtxcT`_K0K~VfRB!TM`wrDwyEQpGj6yhUnfx3D?RPk)2P@Lai4!k6|obdiZ8{)CI;<8oAz=i()FAYW?@YN~g#x zu%B|+=~EU#gQnfCo6y-@i3J?8?Whyi%x>0HEl!wJMKF6yqw8Y{ANMge@@Jux!@P8n zn3i-~kuRHJiW!b=tq}k~P3aZ^H)}!q+|yff$M(RHf+V@)L{vF5Z9Sga=oGI}o6F#f zR;}NIWnBZO2zi?EyYC%*gGb)gtT=Rb9a0Snq18}n+&L$Tn zesy^3tP?uRT(ZR>+nyFMg7E$KFxa8fz0;m8Q8>$#t8z}gvDXlt#G8VV1#)z4<0c?o zuixc=uFG4!aHdI?ugCJvLUwjo{|?QkY^2IYIC%Kmy3F4Aja@l7x@+u2^K`R;y8|mp z#IpbGe7%!iz7N}mrmJBPk`eBuk5G~)*{ZWMq(oSZ19SOT(A@a=2eSDJ+O?t$#YaRJ zFo9nU@O>^pX>qdFu|n$yBHPYRi^Ic7$%on{JT9-NubvK3`h4}}`)&GR#a+}fy4tu_ zyIOQL9+TZ8s(-ot^0WyxCM|r2bfpvzDVM1aQNyfIxB&$H`3A+M!C84DI-n69tPtgH>cc&1Vdmp5 z>s;+)KamuYUAe6A9n*r_K~{=pok+GIE(7mQped|ME9j1@GE%tC*v>2yAGvb3#}zS= zH4G)r(srWLs)66?-#ATQ)B0V)4i2W6oq+5W+jY;I!lxvVtU6biP=pHyh@V?n@@>K`g=&f-p zp^-?V52+icI!Dk%`P8^8p)1D0Cs-8eC78?o9}D2%sud(&Ax@x8BtWIcSm{j}uf22D z30;S#Yy8E`fI3cSjH$}b9=;G-H|l}Py^|h#+0o(uxd8j|1*4A$##Em66k7T58&c=e z?hzEH`IeYlq`MQ%+LzX8DQNDy_sd@_#0xxs<~*Z(^di)7BwES@iR_=xu?VZFAzrv) z&u$hP#7GkkvkVs;Z@jO*pWbXZ5qv5B zdvSgpBM^M~?Uv_f^ZEdukTzT|+1qxmafAJZO_b%edSs5$N{q#{()y-b^-9dKw#{n0 zu$^xTOxcNrOacM!^*e^wFTq1nb1O%C`B+QeijU~Y8;{hjuB_4wL>4J0#)&rDp;W;W z?wF0YWlV9Q@Dm|POCR4XvnqNzh;v&hu|I!7Y6s=ujne23w=N<2{+45layzRLck9#x zdAMb9OIQ`VP{%mdkdCCON$7WC^Ov2~r<*0SFU082#U%2|nRj5Su+9c`3>9{vtU#xU zFaalYvs-I+A`&EACeRG?4|0;O%fn!#uzr?YyP}$5V}9apqCHC26v9E%@*T^6iQukrao-h~bmZVC`Iy%9C_8iYl%8_X`!RdD(YX!eeb#mK04WOGw}Vw9|GJxZs@{0qp}<54*Y{( z^IPm6gO~v4+ksu!{>{%6{o3WU>4R)YtJChvYu9Spb8UrR5NB5))3e1!z16QMCV@L) zj-G!aAoFWgKR!)MQi5Odsx2a8yWhb|@p4W8YlL4CIe@}KU38Cz=Vfb{u z)7B7DC>oITSD+few_x>aJ*${}YQn+qn&_bSW_3842=wrBUFvyK&C@j<8yl-T-u+m@ zbbVs@P6z^lpbr;e!>^;OYS{k)eZR%9`VGsxfhWG?>@NhG)kJL;kOS|f(n2g^RV#N! z>%>Eg=Z3gh}eI^rfw z@9u88<9a*)9u9QBGNh95_~bmQn4kd5&qW}&)@yYzAYED__Ip8gnb34eR<1hHlwl~j zW^S$7)T65wnyk&*C4^4j);eAKPol}FH;2L|r=?fX0#uqm5-)vbf~T!~Xdl2(qGao; zfA?RxQbz8V(dX2U6W@t$ud<`dluw$+VNPuClu|p2oIC#;M+Z! z?sa#H?a=ee!rv2XES&2g)a)cmbByiv%hrxgziWz27sE%&-2lG?9GwW*`TwJ)^S{JI zT*4f^RA{k47{=7j4~(7r^;tM8(XmXJ0~h%|H7Bw$e9}+8dgg1JvcJ@wR0`!bPdpDF z9tzTmvlQltZD<<`)f&dxkg_wdo9sNzo&8{V55|*t4bT&seLFkDpr<8G`~R$0pR4rI z7V^97X*x;sXuMH;R$hD-&TcP0;*vc85_?-wuoUlD4Wvt@vx?x^!%H{rqvbx{k(Ao; z$u(s^D4I?D5ZrH&W#5j#mh_OX5VZ&o(cIIO;%jp0=eWCX^L5-1;tPXZJ_7B{E$+Jk zHm=H&P%BWk!c^U;y$B+G^X7T=aEm8C)X35+_zqtBMusW24$=l|T9;ft9wb^Huh@sI= zRb}0#nE5(HY(q7|CV|v!QucK{mi^?5><1Dg#rPv0Im$Z~lb-g$apNoMnebOZn)PF} zpKjw>1GhCa26}&}gwgN&n)6ie`5^}xmBD(;rDNX`lK>oPUHNMBFf~-XMp0RmRR{vI zgZ~Kvq3XX<-eF|=B`u>+#h=YQ+lxbA4ua=kX)3#KXAvJZ{($B{Z3I|;ny%@jAM+=S z@K3%-kf|iS>GI<|4z;1G4TjG9-RBP0q(YkEe~lLegn2Bzv6t{hwHj&5BhR&VamHv{ zpI$EBxnz4Sa_@&V@IaQ6Wy}jU!gN2aQW+%Lp$*&t&fHbSH%huBH+^k4E$%fsmNvR> z?mVv@2eUKnOS!^*i0r3r#g@XUA3(?-UMl_FB5HlVT{@cwoT+k{bQ$cfHmLbLjvIpM zxf0KW2Xq~}`2Ga`w`MaZ+o>Ho7@*$>{OO!*0|LZK0oPeHQOif?Tsu8%Vg2q%=qt)X zLLm`?YJSH%$(voML2%AxqTqi#Z1|Qdj`xL!lJlT$*q-eC`G;yL#<;{WVeRneY&~vf zNEcCikLM37NXi`&oj!L%5?q~GjbivIrQl{q-iPdrv6S17!7BVkGX2onzFXTTg3x6G zNLaiK?H7DcEs8>$)+O`ZN?D~5nMX@7Fo*DyA>{hM4dm`X(-^WR*O7y-JAIa34sKgt zAMHc`2>?(x^AoYhL>`2f(DmO^Ve96E^PIlxu@5l~Wq)n>Y41Y)-M-&!kVL+>er5kS zjlG^G$EwEAu5=3Df;H;srqPn_RV_S+^Nt)&5EPKPS_f1@HV~li~aG+reUN z>Q4OtYUFxVy8qC_ne7{6)w1Dg`{eCD*$?%1RN1+jW5WHG33G=Xhj-kEU6D7$33HeK z9yu&b=c75#fW&{Fi&EuWw3KYS#3?(-@<|M*kd(Sm zDw}elCBOI#c7XDGTB~|DIJjx~jmTs@)^%v7GEE)W$*4~YMnlGOSE{L871Ul?%92FA zCk4{V#_vQAZ6#---&>0#d)5C|v;+NNYPwuo&0d$&rZ647*#Bk$t>^2nSi=xll_sIy zOX!RR#%M#Le;JX-F@hy727I#bCN(j8=q%U1G^?cihnZH&f2ya2jnlVz9?@4Wzy5v} zA8iWxdiLrVDnv_K(L-ADS(bF<&BTT?b3*_M$)TgN%TD+vy}Q9#&p)JpgO&VUigVvj z7cvf0clN2M(LW;nwZ};jBM?*6emBMZ*sRT&L*LvwQ-_x2A780cu{op^r)z;*+rY=a zBW0u6c7*ZFJ@0PQVN9B$RzBT1)wwW{a0_8Y<5WY6oz?zdb2Rp7U;<8K7! z4R0tDmzQix%C%^W1y1Q8*Tt25;g$0;hs4C@ki~E}W_(`c^cPRF8SX=>+tFCmzP3wf z9Bf!8uMb0mdqG$_1e?H_Gj43eJj#AS#f6ERK%O&cwL&kfPErhmUqJ_P22J4c)R(N} z!Fu;QPU=i@xktXk4|?XSj&{{f!6xU9{~^ZB3Qw~ehf$=G@2Hp)-hy|cqZ24TMf*B1c;>=>c=46GPqNY5%U}QNFiqcg zPPb<@wIfvqgZ-L}{oy9c89P`{<|fpLfA4qfNiKCY32jTZjJ-Qwl0vA;gv$S*jJ|Q6 z;CbZ$OCtd%<%a8nmNqsPlGE#l`6yNauvE8FVql7+2EY%GdNrom8C~L z!$-i;my18v*a`jGb|LnVGtG?0kRNb`y0}0YDI8q7`0bpt11?1*D9{~p#77&U3OT_Ja8!l%F6-wv<+{yLa82VYmkSJ&6MoLH4P8Drc4b)SUsEj>g+ z{|ZzlIRG7UF8`+_wwMavjXX1F&jgI!aklv$nLP?Nn}z-pzApZAMI5$VV-tmc-GmA; zkCiZh+_$~Aos#kZGEyFzxIcmZodZaJzXsvH##xO0A!taA`%U#=mZnEj*N?Y((X0e7 z#SS0dX9&$6Vj0e(g*a-xxtycdoc1jl#Y9(DwDltMF)YiU{U~>!`?$@PqVW{36I%Wo z8<8hUEqcsAqK39=?(SqU1Xyg27rr74iC@8sWX7en=X7sSfMogkqo46w>~vk2-|bxG zASnKa&n>U9Te(A5Dj91ea}SATwe17BXZoHCUI=;Aam}~0hI6gvkD!0))lsPds1~C> z>Sc9(!;=vu);To^7E|I>UOqW5bE3|nFM9aYE+5@xuLx~Z{Xd+QzSKL8v_dTOUCsxZ zVAq!=I3)EG+`3Fxk_M_)Z@u-3FWHu%(Bu|3h*`UB+UY#;;EI1_!T=AY`WMLL4$4*q zp?DoVCquOXu^O(Xp{OuMb}q^NBRpYL!VWmha(Z7lq^K#B5oHTPqxOlGBE4ieY^7L6 zoa;M-pmdQfD|Dm`7q>DdpFG~j8Hl?}ntnOz1KVrR@)mSTzN`^zOkR0Sk&S(xiFF+5 zeE2kSYNDi?HbJV(jb>*V>V5y0pS>I;51QY0SF*TLpV;r|U)2uRersCF2_uA)a8xJA z93Q;AbYdY`&mXBLTCvR`ZA~7KIupL1h3>Nf=ps)rB68i47sh%WQq#%CvxvfY!=#*j zjEUqre3xITy-;0~1vQ4`&kjo5%P|hQf~dWK7Ve*z!RbfC+kn~)|6D*ka4Hw?!NXGz zQfsd8HgZn^>Zq7fWo}tn4DF`raGGxC3YFxfDr-@uR z?tWd#APC@nIJJojDRJ(Y%})!#d=8qFW><~iTN+W>{&ax1Lxo{_0o5VZ1s*NN8- z_i{7qo)gQt(7auK=EU-FinyymI{98N5bl8xue8#wn zMxg!fZ&go^F<_twKj9q-`}I_6C&)B5Wf= z;Anjy-rtGFWU@7r&bT;{w_B0+yZVkMDt3fp-=*qmu0E&GW0XnON3?l&iz9}ueg?{! z7yNmkmzQ2U5(`JoHeb!Q?M1g?Skg-DHdHzen)#zr_KsjOZ@zrr0hAvj$3z@6E>_at zy~6t20KT>Ah^k1IIxuMWq1tzgUzc0FJ>h0EICUf;U5+GvPRL%CW9fKZv>*wx=lCJu z+zFzV7Qu-$wkDt?8QthU}~PO3dWA>Q*FzGmO+)V^~Zo1fV!i|lq&DN36CA^^WdfM_W4*F-4L>rC@ysdj0kMAV~Jrb=Qr@Lvg*9HoxXeui2=l9OUysYEeh|R zEcV@sIg(z!!T{UyAeTg>2>4`PLD-B;ak^g9TK@o(VY_~pFos(+V}Z%~Gzy22P(u}z zU>1wH%3CXd0>TL6ckW_iw$EsZ+_```azDQj7kqYU9mA?@hOQ`9Ih_3!qfjnrh~&%{ zMWPq?BNAcO4gz;`*o%9R2(xCA%*v2#(No@qq|+e=T6WCS82D~Ifu&>?t+V^W)bQ*; zY-h$dZ?zz;kbx^3vn6V<*4JH@EOkvERim;8G`oZTiv->1*UezYf&sPxm;2$(4JU&{ z6rX-+X{lE2@&m~KMX}D-`}JU&Xql(nikohHvlXhka2d%K%6#?M5K_@B74X-br29D% z2bSsPZs2QQl)0~ARiFuf>;#Nm-CRPav*aMC0-_4&IAvs)-HFm(jc`x3l;&wJQem--ERht}bY5)mM?#Cr>pxE=dO}U;#Z?k~ z>}i5}M@_WcOtmW3(%z$DI94m&4F}z5ljO=r9C;S1$@6&;otV^ZLg>5o zGu4q^@%UiSUtj2wX)`re3vt+e`WAxEj}!{`LN4LF+&-|LwS6^ar<;OQZPU|X>iHU5 zde-P6d%k5xX{kw#=W456s2-}eIAYVd-6WTNgEvdh zV|qvMDjFG3|2~mV4u{3gsgE| zUfvw3b-ubo0#`$YQTnJ`Nmfi1Q(5d?CY1k>;%^0Woa-(pSiDeNqXLPs0Xd6q};O5)oRkW0x8 zf+glfJlLDhc^1r37hDNA<}b6%mM zPA)76o~t$Y$Oq0easkT@Xeq!u0OUYc+f&kUv3&fC7btzKW@Dp5`5}_rxAXcU4ZsdNi2z9#V^a#B2cqW01;fiGZS_9F=2hqre&UQvd=wf^9>&ewgr}LkgI<7kM2I# zp7YN2#m}nw7P7txnNp-{;<(q^FEO5EI3f6>*I@{HtGMq{n|KVP(H?`MIJM7WXUUN5XPVLaO*!0IC}Nm(;&AQBBJ0pGYkmAQE?#7PBkd z1cX=Pvgr;JtC@}o*jttq_Z?OF%h99ThVaf(Z_8=Mp_s*P;&)v5O=@boiKb>vWl%#( z5ZT6m0KsmC-Ii6%;!MNsp_e*f>vbnTlkRpetzuduZ5NtVQuM?tJmrgt%LBezP~nBN zbcUDh8PVGGu1S`>(CF|uMG!&(z1E8lcM0(z^N^5^?6&S2ro{H17dsxK1_7ae_ycC4 zT+kQs{BZeBeISl5TS*^hSD}G2JQ=W;Ltm~q#oIoyr8WKWTG9Kn$=7H90e%H&S^pTr zfn5%&Ihob0Ii%eIbz7Kq^0%hE=9zI0EJuHzY2VHAP0JFFl06IvwmD5942>U6tFk-< zHfb}x>k4H&MXBHg4F)@$&7jAN9bbYkb}7&jRw+=~a;Vp-?d3JYu4={AMO-$IrcaI= z-I~U(c(khD)J{D8AIBS(EL_dgEDE#p^-m{$bq%L>-%zi$Iu*8{#6mhP5%;0JWzVOZ z8O$|J^f#=OR%K4LQE&-Ux*e4TpWOILLxDxeTC+4h9)B4RO^0N#mx2@*8oS3d6 zIVw7N^{X+$w^5F(!36|*g@@F_-zjnQKrLdo&a7hBAZ4t_l#AP zQ$-i(B_M6#69xEIMB@@r6e+$-mXYofOVT2Y8d;WTTU_K*Q=qm zLV4qsj}*YQZ zNMmX-=m-}+y9Qe)bvCkH*5CJ;bP;W0@99^O(9-;{=XnWhP=32uC+mkl6*u%UeHVIG z+Nq(;+uf_}@I{BrOgmXgAA%D@9vf|PeY2Av-XM@GuYOMjmgeb|$2;SuGOJiJG6Krg zoSeGo{QO)P{dL)r^M6_$DAC-A=~^{(ZvL5U?SZ5O>9@l&&G@a`O)@_;OaI%1QvXdC zLhCRgzXK1AvdY@VrR>QK$qZ7;ai7uET7TcpMSM@_c82(uWb)uzOlht%0&g*hfg5k! z8>#Jhiyr0#4IgeHX{%a^sU^Z6KGK+yu$`*>GG$%!-OW*~3n^ezcuZmLhUMQ(u(E57n~|q>80(dCLF_&ZAoTVL6zT!4jwTY{TItQd{mq?{bo!^>KEjQK zU+S5j#RTZjHkqdO1_{#Eqts4)ZcP{6h=H%o)0;hD{pWM%e=jhJ(^N-uYnaRdM1{8x zqgVYeoh)ex_NIcOA;i%{NLb_I8I%fkMY*H9#QHWi6G$Ro50cG5t$t^*i*8)+EV%wK zoV`spx%o_+mo?t{xfJ8}bO*;fjs&PWfoIVPymb<%ETn{1q5*6zOPw=hExB#}w0O!@aaQkBhIWRqj-1p{KpDe>tgdRnv(3 zlZU%CNnA>6I}Otz^VdcjVU?;qLo_S09kY>@L!Yn`YS)_@V+#k)bvf5$bu9}zOLib3 z{l+)p5OXEV8)*6<#`&8*BJL#JhXbvz>KF)=nl|rggs7Mu26Usc3-E_08@Jp?ajtw! z+ub+QhTsTJwi4N;KuFKs(9z7F>xAYdxS4i4)dej`V3D$qj=u(YjN^&7|9ZDgZKuGS zI4bam$yXpBx4C{ zHKaAManft0>pO``qFpfBdd=%lRuaBAC|F6>vJ=#db-qj{Kd>8qraSCS;4%m!x5o44 zwlrUV9$Bm?-97!InV8Pk?rH>|dYRwtw7dI_iZ6ENR;Uz>k^9O>4PAC;Tm#J2}s3OLp45~!PQpg-S z%LnXC)iLf6C38+FMFWOq>1CCp5gC=lQI*-tg2bkeB))_vs?~iE@6VIDRP@(YWSPV5 z69y<%cH8fBTw7!OWRAobtk3bE4}HFE*(DQ*&AoVD`a7F$1_}Bs?~XZqwPaXa)LSpc z^}^hIS|c{6zKX#N6h%wv*HX+9> z^Ol55eYo3eLZ5p9oVsw{_;H!;s60^Sbl;o7b3ae7dF*duhrp_FwU_?d#79q#i*57Z z64YJ!%Py1uh=Td8`m9RRn**yQ=c~K}3V({ew4$N303YA5MeZ3|+~V!`q}#~oY~X|Z3(ow^TBtxs54&tWD z1Q0E2!*Z#3sN`b-_>&BHYf%etgzect<129{oQ%+&h0dk2-L<}`z%aWRe9Fo0vUE^a_{}o-0J+ zN)~(Jiww3*oGt;pvaP*?>7W@xzn95(Ks(ZNQX8gxah*V$Wm zyWZ?o8nN$qM&ShaGwzrGwvT>*1ni^XM++Nan@TZdopWDD=cYt z4uu|9CL1{@#Er0pmIGvFxwiDFyC_b{c3OY>sOSCu9rpb+cOBNzWpvRNa(Q{FWa?UL z6Ca{(hofEe0{(S6O9>am|^G?ML{nFH8@r-rPdLXnQDOpJu~ zBzWd%bp5Cn)*5$Y9b0a}5WK7Msj&&Qg7uo%3|J>O}B48L3q?70+qb+C-v z+S@G(xs{*>fg_3V-p;nY-EWhc8p+rkePkP>gP&M_~!{@LIu zR>)bk!A`rk^6R}qVM-$9oCiy#6(K@P-S;2veGI@n6w1=i$-5($a5F&gin^Wdr{X=g zPsBTU^o=#Z0LT{vab@f`j%u@hAm9`%QW#`TQMKOmNt-0*_bEZUdI@5 zTexx}!~_8R>Xq9sE&4M`J|Vsi)jgnm-9q4yIb;Gx_H2e5b%n}49UivHbekKMxLW7Y z1O@v;owH1$F^FTIWV9aLH1X!ONBP4&Ql^`e^Fm%pFE*@XXb@qxC~AknF0(=O;F*f@ z=&-_qw*9Ab_2u94r>roJ32czL7PpZ(*EYr%X48-xcoL2r0T>U7n+x)n30rC(N3Oz! zCLv)I-|;(jz$&L0@Z|0rTOW1^V|;hG8;lKV;x%Su31jO@%6Zysh8(NCJre6!&vuJ z!AlyQojQ@O+EDwQW_;M)pwfN8H9b1H^rjtKd!=dd_G3ngr23145#uigYv^kD5JkE2wBy9&V=Kb08I};;<`h}C7L^c zNGv%uxc!L*0vK>y8QI$jY(L;&!k+@^hA>hkK_$j5rN-%hm|K;dY^@yxd{q=aa6Fl# zO};ZbX;Qfg5>V<1vmt3LJtra3c4D}is@D>oM;<7G=q|e>Q)5o~U0xrxa89_Jy2a5> zaNSm@)4(Yq_Vtfdc1T*jHk~6V>E>v5#vc&R)0KIwyqE#7)WdC^T;8WN&BD6HWSZgh zxEeb=pnOf=#5sL^ll9m=WE;%i)Fj_e;AGiVL*hzV6n2#{Ux88lcvSeS-(9qP~s2g6WmsXo# z6AK}xW@lpk4sq*buflpyu{E6s1CB7DO=&mJXx4%Goa zqCQMqZ@SfvU$xvN|BL%~j(a9I7rloc*Jfc5MpQ)OU`_4i>RDNwAh=%yM={zV(@J)O`-$~+=Tx8-x)GHp?5W5JER-0K?pjNIT|iI$qHiA2#^ZOK$D3MP)%hbR z`&svsV2yQ)c`VxyaVjr745PZRqe0^Yd1oy(pEMRJxh2s6H!77PFW=E0_*3KKG#k9K z4==Jcfw{A$DGsNuQ~aW?aNyn&*lPsWC{?4tRrE_sWZVgCTKh69yi)y2yH!bL!8K4_ znjPrQQX$4b(s`RbT1Q8O8H>QvRk znlL@7%;J^MAzB!YTiE1+waI6&RC*fGV2<%-mM`+%ITP-IJzetlcG0(qZy6vR8G^5D9lL;yG`k zcA>n5zY16(`JezJ*DDJU*>*r_+O&@w%*s38Qs=F4Qdn-#{vS_g85Cz1Z0o@t5+JxHxVvj`cMIkXRDbcGt^F-GjI`-gxCu`>%rHjmvM^Ye_d%-G8x&3$3E(R@Ymqp_&|ng63d@l0kAiZLcW6X8a;|OiH8nz5`(<7%_42e7!9Y)R+#;x=2v4It0N=*?YbeHEumhscG z!>LPEFSasE3;Pa0LFAQiarukdrS!)BHn8<}ik(Aar?7^IjUQi8yUedZd}kn*4X0N4 zv2Ra@WE&eNS${mlyfM?k&hj8)<^B$b8&T?X|NEmG{gcuyC&I(pwe@w}+hJaj?#3c` z=_}g}bY-)1jT+Ml^NGi7dWszB(qV#UXMIA@Fswu%r@VZ^!iMx4huhn*w6wI0RY|3w z@;`gN7LG_+`|ZEakOfy?lf=G$R+Nob>-T4|JZ_?zT#d6bs7jT;Hd$m%_|o4ecfEw} z#pL%pQ3$XB@*-O75^d+Tc?!sRe^}!?U(Xblw$&S1)$Zqf%4y?^>xG+Bb@9K=&@y-Y z(4@%7-la75WzeS7*9LEb5Nl^~R6Is8>ze=ciye?!oqglZ4vx)9BaCfO&NGLKSwnB$ z-%2sf@YavcR-7{DQ);1MSDaT-O(b#DK-J-IzES4Xwp~l@;A_&Bb9cqsz|hYp7p$Cv z-yc4@_`l1Dk~FSD&n>YMytnm(+Glc4j#lV>1*F801AJ7Jzk0gI@a#0i!bNJ4 z5(6e{Qb;~t+AiorZQF>w6Tt69Ay6PyTJJi3*owT!dU^x(>dj@zeC{e9uwZGhO@VK(5ZC~Av8N8hGdPPqA*!=EA zg0Fm@&C^iao9HXW8g(+aUe7LPR02#a=!1a1$M^(nwdi^>5w^)Ik}@ovk)=rR2I@+;LhTd(jA8;g+DFZ7L0G68Rjm#g_V{ z?*R!PsHeuiqa+^={KLkzjE|We;OcfL$%g>55H8x;`0KNa>ktArlMWO%r zF;&fupJC z>n;tJgY9O@oShyR>haHN_q2+>q7>6iKSis56zQ9T!bfuY<2&R!x$EWJL}I*46Dz6I z%+DEbCf3Q5+ALay!sbRk-_29o8@CdQx3$?upxN;Hl5$A98SJv#*cL-)Z1egw7aw=% zX*79(vsTp6+5vKnaAOJi;*lgxi7_-b4lzRa&Kc#jU&v6Zj?p}o0PDl2 zK{&#>Lhs!BH#M6&-HC!#bWsyRSu9?ILtqx6(o(3ub@uWC3+1>|N=9velP-2GwF#HM zJ;vd@T&Inux$k`QimrdDYG?K6lq=UEVj9-1ghN_o0O`a!_fz}+tl_piCl(Y*uPQBf za7o>3F1vrNq#14po)M1%%bWsH55`sy{gf^=hQX(^q6SqjPK8BNE54Xt3j4)k2KZn^ z)fUt8hs+t3nvpjK=Uh&+gHLeLqeVd-$h4tkyO#JvcU_i!+q7 z4A;@a{xUck*~UwBnEom-{Yh9h{BPoW#wu+h7+E#6Ea}phL`cNzfagTn;R1nq`C18% z+O>mNmb}<0LZ1RYuD}ikTO*890zH1{5wODFN-fv!fc1ABr`2i0+5ZY`IKheV4* zINEH6Djr2&Ii0NHpN+PD*at465<2Ct(*I_jzh{8xYn?mL34J3G7jBz_guUhMe%OD5CKemwPDz3X+cmot69+0 z!An2X@BMF3_QK`2)CF-yVXNO?h6SC4<#OTc6??+II;X}@C3c{HlHZk8Yxkce`K@-~ zuif~17=|U2wrdE!KZV{R|0zi6f!f@5GDtQKy?RSXUrnE~0%{{!X}093&Rr_h@W%te z&tfs}xssP|(vc?_-4%WpJ1S&pq9y~eLkm+`exAj@>72A;~`GV3L(VkHVc;Iq`}QUs*4`OHpF(Fxl1_e z5(&(gYG8F$h}Uh!lVGn1$c!;}bVK=?KiF^uLE&ccnV}usOQ^j_W#d0JnygG0r}Bm+ zhoLv?cXd4^pbyD>YysA`T3C_O0GUHAJ{}!?#;g#0zf%aVF@Km?2SK-{O@4M`pnZml zud${q`*1A#_`4tp>5FM?=_K6|v(_ELap~!JP=;bxEbqoD7RYSFfz-=}RKK&a?cMLm zD3#pYnNz_k171M2v|mtQiPDtmEb<8kulo$uVX0sChGv2Mn%ehPLJ=?;otA}2ATf)M zL+$(WvU0yj7jqAi-gtOG$#AW_jkQez!cnulGvrGvoU{NPvNj%Z01r!DY-hc2c7ERm zC>mY;*PIlRZ>ST@lus)>zXH~tI^E#ApVkc)AaD+5Buje8bN4wC z2Af$((y+6*E6?D%>zv8eR0e4{nG*-t8*vk77Qveojp%hOT#Si`7hKyeG{sGxuZ#$z zJz{g^$;J15iShI!{;QuWv2eY!8u`HWT*IAIxEvE-V97ZZX(l1DFX7IG8}bzLL((vu z%LN$jxSxQ7Hvl6Cn`)3!ypP+*Bu98oP?S{eZb6mmAmii?Xx`cMKeBs2XIL5(;4h6uG-C~#n>Bk z56tateC+Epf*^Q=5WENObS>5?6$@9iZBR4)I=nd3&uU-$c~%e48{BCbVaCz#NZ_ZM zlS7?8o*G`*Hjd>0%%FbK1g-BupdnCfhl5z7*??}3`>(s143UVv70Q0m?tKPtkDb00 zc{&I_dL!&|WssYY{Iz3^66hRkJJT{el@2K4DUYl~hCuTl;%`w?oq_&>D~@R9MQ;d> z8q^#kfq4xv z0-umZKH?MUxK&94`;2B0jfdpK47%hkj5?^q+pm(D z*WTS2C-OMOKJk1bG8+;a&^Rgjem8O76bCqBaMY;X&B8>Fc#FgIK+BuE53`5_QcXsq zwVg%zu5%vr|40;ybp|X0pulP{u|CHyD(C22s{*xDe4esyplNA{)nCxAh`}s7%q&f3 zGEHz`%j2(q;z~2m1G~*XnA>_eLf@I(Jwy1`uNt? z5PX7md(XVCx7TIiboJk8NPnwgW{!EdWNedS*H$p4S1?VAMK*GTJ%YbV0O+?!V5yiB zW`iJ(PuSakj}1u1N1oB60kr+0P%>09$My_SRwOl}&69%CB1zGFxngD@08LNa(Q zxVYZsbBHV=&V_+xHboc??B`G9XRn9mO8T69F!rgtFWQXokV7r-_o>+qVGg4rLctqp>JWMl0y zu)(vPZYhZjp63W|Xbk3#NZTe|lZUuA2f>?15YgwY%_w~gManF*VuJyZG75z__8J}Y z2&eTIhCjz&UY_zq`>+Bp%gjl(Q^0Lfc-l?u-&Lz%Q@>J2J&mPXrS|OwbQ$X_CR&R; zSfd*!mhpQeoCB$S;nmSBhE5ykOLXii1KGiQ#`4!Z^vSp@`o{T%SnOg1p*hv=am=8^ z(-m5xn-wMYW=A1yBwEM-4UGKvGTT+Y@+)$MjW%(mmRFajYLx1uWh=jnH-H&*inAD1 zf~k~D)Y0wql}Yj(pCB5z%shmCWcoMmEey+R&h$UtMfEo3<<5o&qz8S1`YQIASeH@) zf}XVJctKR={U24>RVWqiBD~2ZAEOUDa##i_H7?511+}Sod}lHyrgFmiA|IgDxaN?< zp5RemwY?6k2!(Br0U3s@MfNstk}%tG+Q0IcBX4#V%Jmhk z?6G5QkNkSY6$rT+i~+Ntk_YlwYBa_8FEZgMs3(`W>1L?;wUH}7 z73*kMDEZ4Kgt6*IinYF0L1ET>4i5n8Nqkz>)%~cVVA^Eeq?kx6o(7~+@wpp_B}%@m zlP9D0B}~UcP0z=h$K;nEW7biTGm4BfPe)ahK~M;O?{F$=^vMgy?yt; zL1aswVoDA}aWGkwr4Q?SE&uL6?i86Nm`MMsxUkl|{otNneZlJb1AmcX?^BabPGOL< z7r8shCJ8Mad#}Q3Pe}@MN_tznt^f}EZ)&x7t^ri)dVhomW(p}Gf8Rff&FURSQK*k@ zY#M#bwRQOECR@1`b#R!?)>y8Qa0pT86qGlTV(KQx0J)gCRNvH4SSBk~iR130J`@~; zpUB#7qhtxpf`j33A>Y(TPgK?`Jj5)cU^PH;TKA6(XnyGmxb4;O477Y8_)lbcYefFz z$ZWoEX?&95kqFs{d@1QI_8*DA#9hJSB)5d%52;miOV__Ip{@47@*8b`XoBm4B~uF1 zbH^gxqISb=iJbJFs15SI|A2t$5^L_=vEQb2b|K*TR5r%0Pa&bzJz)9dU1f$D%*u^r z4aR4Ehl`DUhG2$I^wb32ouv4Es+!IB%<)`uxvy&8Rx$^Dv(7mVGOuok*82W*y|{j{ zvS+)NBcdKvE0iXy+f=MP=xgj`5GK^XHu~LR7out=+~m8E=}QJ_ofm`q z)u2o{wCP64IZv(P-m@nodTSK1;Te*8*`Tw=i*g3N^v2kmy5wUONK6a%lcDm&kiL6W za-b{;@?u}0`Pr2#a_ka3osy)}L0D#BE7)xouG{9twjYQ?%#w-$kh|pdCk-quV&_&r z2)?AuYoT+Dl<4R{lw0I!!%&is*^^YPJ&dPvv@@JcAP=5$BBRyA^cHcK95gj;SB$CA zLsGTpvxrrU2Tu;GoGxi}Ky3U}@^nlEYG7l}72qK(n=w1C4c2;PmKUPSil#RP6E1M3Ye_!lWUm{EFFB6i*?#bq=ZMp#;kyu~*ALzp z$aS8#uD{$DQpuWNG{7%Zk_l^9)_)UPS5b!fTP9Feyup@Vx0i0;*eX;YDES$I9BVNt zItfevM6t?@-j@|9_VVwnV}yB1%twmemewcZjtq`^eGK}xq)rEGvqoZ1ho&6w}P zQQWybwOEiAhLm z-1Hf^UQ0fPwV?p?ryct+L|PO^eMMk5aFAD2W`q@mU= zii8z`tu9HlHv}(x|=s*oxjj5 z`av9Tcxn0-63@*j%mJlKGXjS_8O2xU%Eoj|J0@@oTXV}5FYUp}{U7l}-Fu5QtMZnG z8g|T=fXHjBe1FS!KRGR zC_%IY#@|3A4+6Dk81h*-16|TYh4vYiR^ofQ37gQ8$xG9RE9kWcu!<{W#s5aR50V8_ zZ$cDBStSm%Xx<*Ub2?EuO^PM;p6fa5Iaj#yDSuJ=;e10MBbaiJot@pd6A={=85|y# zv-dU2*1CxSY(Cu_Fz$VIoPD0-t(3nWVtE>TX!_RgUyZ{_psc*s!m4jEjie#N3ga-1 z)Zk?Yr^2n9P1_HTV5dJ<$~>$v%`)Wa2yyhb!g7iHGUl4!SM*{T?uX>hTKJov$gHv$ zzREu7UZQj({9|3UMkKk75M#v&%-!M)g^bbSc{@w|K;9R`qm}=pdQu7EPNf|R7Xyw0QH9Mr!3=bthY_#_4>)&S6XO0v@`k&^b@l~WmP9?Yjt(O zg+r|dP7vt8=k0}GSw%%~Ib+FJv1~TwH~;Bx_5uS=1qm1z@^*`^h*z@SO18^0Q3(;` z*%vkaM3A+rg)a$?S)$Orh(eAcwPt(+}O&^B|{ zdwJcBuGxS5t1ydhOxi&5Xn^qL!tSsd$!=xA6FY!5&4cNa@{i!%508L~*bZm7zg|DS z#yj}WICh*xTY~?(U@r{E1#C1swT$tEjN!vj-Q9t{&3jmK^!Xee;~ad8&=WG4vCcNp zXwLfpL}46_blRZdAGt(lyM_@%MOCm97x@A~>C9TYXu_dn+-}*V87T_j4dnUi_@W^K?aK&apJV zAE91TH~vqT>g3-b9#7AZKi^}iGCs?pYiP(kGX&i0ZNr3FPv%0~{tuX^Bm|-Rn*61g zcZw@0W)kXRUA#=_xVpJT3k4N5O&rmos?ybu~-{Bic6-5}iG7aMZsMy=?H(Y*{2uAoDz_1B7J75SR#RH>Vc!G+xJYL(=qG3 zS45~!00$VOf14JCeLJpsQ+b)VczFP{iL0e~?x7eqoz;`iO_6D`TiKF=bEs4}6-A2iypA}FUqbcbP!OU+|KwB=JdO}?j8V+J3($m&6 z_0UPZy4(3Y9JW$q)CNY-J%}LeTQvZ`WynQNrm^z%I8Bljip7E(B8d0mR&&;xJ1sfD zS=8>-RgB;=DV>x83{zKrxy(Hs%lvH`U#=5&%+XMEb1&0w?|YFhZpa*|`CjlZJ_`1p zA@+(s_(;c0!P0;B@R3i^{D_7dP<28dRrU6b-*Au4A*E;hjCOpIRQH&Zl)*m8dMr3G z+_O}k_v(D+<$m&W0K(=q^KQ#tb|Mw%YU@3iOZX}{@vW)fxbY8b{6SeKc2yG2JJGw)tgGlwKN^2O5KdW>R@dsfEPXb8{#p{t#4G$%Kqy6j8 zN!JEwU-L!CB|fXe`ygT@oTO$)GH}H(eT{KOIW|W~{q3xf*37-vY4ByZKEeU#w^VJK zo}k+@9?sLXz)hNxIk-nozIpI|fua|lyL`ZS=@&)OwdX;cmt##)-Ip=wO+`g)Q;6au zpHpii37j)@=&09P7Pz4Cfs!igpD@1k!`G;leyj2{fiITP0)4yi!;2A}`CL`;AyG}67DsA+uH~0876|f>s&<< zYy6S?GpHsB3KHl)Omvwg?>-587B3pw>6t&fGL_G6_GrU$Prhqu4uAQjXKf4(fq_AD*!ulaI zPfi1};=7fYHDCqi9uPbb*?Zg`OPr+n7bYX&puvN3>6WaG#9dG&F!fL;clHqYk6tj{)uaPR ztaKo7G%)0+>9-bFj=G}o;VQ1+qw~`@d3i)4@sawAZu{Rbwo~qe!6_e{CYYDxI_(|1 zc=?65|6OMuC#Wu51#R@9%^m5rzk7z`B9xwgXXWffm?f8kt46n|@Ha_ry_xB);mK<3 zUZ^N*897W%UA$aLov%9qIV%;z$m)B`70F46mq#Cc zrB>U5=W4gctO-{zcUVq`pd(l4n3^ld}&|X|D zxD|+|KdEwa%OvF-EBE-)I{t-#GrgEmNd8a(kkkbt65N8r8FQ_zoAdmormar_>hnTP zGNQ~tYnfg#71+3+R(tFhd2Qc4vQW#KJ zg6V8uQ+g6>KAo7QSI<-n$;dUxt))q!G09%fV}7vxsxlC-Y2W<#}r_23joTQybp5rm6z-5>qXy;LZ-a z=693{b|d)QSnRA7*xe+84@22-FaWfZ9!;Rq8BYvMN~@CDf|z>R#~A^nkG7c&Lo?=@ z^JvAk?GKYnK-=>v9j?~JO9>_%(U1bMcgg&NdRImZbFG0u$BN1p0MUMnYuLywc@;1ROb=X@sw46&Nj~Qe=cP=a36(hU! zGi3wx6EQxYJ#h@TW7U%nAU1&_(F7Z_wrLlQ(PD{OAYq!1A0W|D{Fy}b`+PkKNnJ7R z@32UJ%o2>F$TkmGTXxukeL9YI@vS#{d9CwcDUdUFup<(ThtuIfc={KM)G#TC5$R!C z?ZJ(n4%pc@VYuz}C!f*UxyLab?ab>H8YzQ^{aN25Hh`ACTf(G)qEMyTDs3>9T0kf% z)N!7Fg5@t~b>*(*(7fVozS{|ehbxcE>YMFUiRQ6>O+XB|1N%UsA#Sc-?&K31k@}A^ zG&(hTd`@y{`v4u-L@aDE^c$Wg7AB!os_#r^=43pvu?czb1|N$WnRthJnYUr!sa%hZ zd_s}B^718rqJmlg#GEuAE=!We#_rMUl>y#KZY#`HKa)Q02f!#S0!c>~NRok$9%Frp zoYu zpSpXzyZz9dyPmi&ZVX2bjXrsm*9_MH4<_?=VtBU$ssS6z#GDZ*1PsG){yHL>49Hkd*B+bghvA9Ez^?_XKg1PL4-* z22dta3-^pby-iP)d{mz2w_>Dy`a2D0Be)Mk&MK-EABtrkIN)$%=25mJZLTF|R z6tuNz6w%6Bf!ex@6e={kF1J@jW+gEu6YT#em)^gSR{gk#raa&d6cIA)1R58<4#G6L-xf!F8{8cq{9osRljiqo3 zm11-w9WiMyd*>@3smDp)J1%JlHIlzNTAX!1n%~+v40h8H(V@HlI%VjD- z;Mr{NfMD-W(A%XmaGrU1R>7HJ7^gO+FKxG}au>yT3$5!b*dlr%Uvd()vYI&Qz;@Qe z>?0F#EJSivq3bNAjKR0Iq!fAK=xyt-}K{Li~IhXut>A% z9If%sv>tj4T+6Lc@GE2fPq>WOQ$kzGZO1QM#tKYkqM?yQk)GISI(sq=_565#{UaPG z#=L_#%{npz@RIVyV*_H)PMx** zM(zNj)9pOLb+LPf%NyQMdfTQ(wEc2%pLKgTnC)C?*Q4NRJ7{C_7ZO>42xm=%+_4vP zJDeAMa_U-b-B6QNdgHCK%m-clu)XdwI+tGxyL5|DxYaUFJXD(mu05;XwVMO z|2CWO|fTkZMXnMBcf&O_4z!`AX=g@f1#WjwCY#(Y^5ZW|1c`7DwQTT&(W zdwan$Haj-@BxFkV^O8s{FlZcpAP{~3jW_g<*0XVkXuCCWw0!jzfika2ePie((IVb;8QSL#eg0?+$45T1j2iV;>P(g?jhz@edg~> z3!sO!5+{p{+D$QGljZm7BS=T09kC!h^G(hR?&kVJ+Rm|)+zOybTzngnadYGT0(yVU zBMCk-^WjQ|4)<#XOGoGM3p<7-7t&oqCo4i2hwm0(gxecm6L&M5n`SFtd8$M{eE68Q zd-PBNu3lD0u;L(0i6g^W&M9;4#eGNSO{xfY2;9lpU^rpnO=!^3?yUWT!TPX-YN=uun_&QUpwK4cV4N5b+baw$Z7RFV z7M|~KlB8L@?oNyVkM#cgjeWD{7iu zKP_ibn@>5+``0es4!NDC$DDrq^?faAL zHesdjj%G@uYZ8Ucd-YVBrjetfZ(~grGoz^%M)i^6$I7FtyT_2G?Gs_IF0#>2WlD*x zOS=@`mhSXV>Dwk^>=Bfc^k@GGVBCH}CKth&9T;_8Cv05#GoVY%9R59@*Dp24(C4)N z9K(7BOpj>%v4>&K3!njgWs|V_0hB*ijLv}xZr)fJB_do8dYkOlCG1fw)5y-wJ`FJa zsnZLj9ESUW5fwzcKYFd5wCg%N=oiaR9xg?05o<@W!*LKNUquh96)FD(lQ`h_++OoQ zaNXj$*~{Q9#ur6*$l02~70ewv>^=AsI zta-ZfTuE4JTyg|ksp39^k|41FYGn@ktB8lCogCy zZHT_VfPUd&k(X7fZu#6NZ9tNLsUE$a`(bMp96FIIbY7vSp&YpZ*E)BS<>0Uik(V3cHI_8o2 zmoA))QgGgMdG?c?#ksIOX*&m8Ztn$M z2CI!JD-X6JLcWFiCH--&TsoNwvrB^}C&JycJO+s}vbbrxD6A=e*m?ck#tvK$0!V*{ zCGMHOm6})?MxF~Ctbk&%)~tm<<*#j6RA$s7{LGSiSyHGI&d4eUo<}^&pElr=)D8| z-y+@C5KRlczsR`z)9j;h0io#b5~|6tKsQxX4RLH9WYew(B`mj04Y`ER;zt1dB5mxO zO2dKx>3L$=_uti}-$_I<*&ni}DDP)?{leT#pPBr(8PQM_IqhJ9uFL417uB42`3%dM z=HJ4g+E&~!3>W;Aa2ZvYha%$L#3{^#>ui(FX6L^SEn__j${&WAsgC<}syjW}$cmj1 zErlq)xMI0jrp{^h%D*QxG3HsY#fv5Wk1P&g;c_DcIir@w_qKa0^qa`q2KGx}R1Gk8 zE*fm?y=v&?!H&rC;v{^6cIQd{+vWRcGZ+&K!#u$ZRD0a&6s82Ly+tci?@6wOQD`&R zdR=x#$s-w5U4*-O5r0+#JiBAI@G#pj20t%QG(CMh0YgFgYSL?(Z+qz(>!t{p>>x@O z*Ix=Go7gff1MpB#VMuLhQN8X8kOriaGks5ix)erS$@wLiORA~b%Z{n{c?pH}%Qioy z&}wZHm~N7ae~CWyc|qToC}853YSn)KT|goCLro+O=n(HjVF;a$FvzjshQrrG(<0*C zJALuG+&O*U>Cz3WF!wBkvP^sfQF1UpC%M6BTL;C86Rq3j&H^0Pd71P@dd&_J_ai$W zhA-?ga?~&%VWsL2wO-B2Ky3<;nY1qGjM{hB|Gf4;-mN=3J2qM!b!VO?P!X`9!NNnv zP4@5)#t$y@ z^EK}M#~>>%r_@yVu$mh_xV+{HO!+FJx9v+nn+` z0`mMS98$Y}l7`CPxPjAWMOY#v9jCB_P_3wMZTU6j!5wNHLKVD`d++7O-s7DH{q&VT zzj2aH%(`KCn>_7f+P_ERuXhvQZ&0%2n1f(Z1+??@9@2wt>|o~RLRpS9v_mkI`9FQ+ zLLtHaxmc^E-lunfYgJA%CFu5Uv=jvWWd%QjpVW-nE&~yWXuCFCai`v7W#Ol&wB!GY zr^0?gUX$*yL#yFUBEH=CcyrN~9vpmIsC05dbj+Z10UyDiwutj$SCP%e`BnbLd+Ub{ zS`6mTEaDxKK8g&PCA@=tbK+iZZmardPWoQopH;5*vy8z{fi=)k!ryAl!0?Izu`b}> zcAQu%bxvXBA56kW<-Y#J%1;eRJP#V}?frf-C?4$;xD&@fgna)xyU6}x_;s@=t`1|u z3^f1BdJpk_jdiSD4N$2v1DhoU3&YDx{5|Q5t(ff&x+f#*!E=ev@<4A#C4FroBu*@n zYv6{Kv}L4~jO0%Q{zfxl( ze9`?CqV+^XvONRCY?%D@qOu+guPeuT&Q@dZuGkqBO5-daEX!w_b)(2MYL=c1KRy!N zHi;}oU}_;HHeMRvX&M3tXUj_*hcT1~G^s~q+D|6};1rjuQGn*iR6++yC)<2|ODyB} z@kZ>)l9ZxBY=*i!&@%@Q3-q0*nG%U>gbqSJ_no^#nDKazVq$850;Swe>m3vND>6l_ zys0XngTl!)d+RMZvLr->RcTmJ))8yE%@-Lb)7C1{#2*LEQRdwY$WteO8_w+@%NA?Z z=K7eiJavv?R3=DT7Yj`v*fJhW8^szSbJuZ}|Ie53n8}Ba**a}{kiR&FU4)GYfuOQU@ zq?BpB?(~D&8)f`x(N!vP|j}+7Y0VMw`N&7vJ zZ6S$1&Q^+Km+)vOgtO4+T5UuXwp=rWfuSS0H$|L-uPciPwar zozR2;M2g;hrUZPwJmonbBcqcpbURH*7*_kK+8@KKiL zD3TB%0XxB8EkVEfqNecDH=&-zH;Sx2iG7I6*vF~F<(?SZK0ztlI9I3MYBqt&3$SL( z&Lb5lk-_V?<*tU`rzORum;H`1mW2FT(8Kt08JRB49M$9Bcs-ah{tE>X0scJx*hskA zY{Euc3c)$#A6-~q{=L~=cQ(lbq2d7kyZ^njrdxCB2-R^7NoB{+2jLL@)%Hrxk;6f+ z)$ZGpnr$S}586k&yYPAMl|cwEHSeS45IvAta4B7scE3@6d-u%Kla$AkrBdKS1v&)U z<_mMS=?(ESk9_XNVxwNKTwA6I-u@GX=Rn@!c~HvS;2GzrLxIwwo^RoF6EA-jC6GSE zCCF7o9aNASlyj_Ga71?l+nUvZO5)((&o1X1g3dqEMEXZ(ty=y&U*py(C5yKU*I;VO z_eG$s8ZuGHLe;YQ+ydcv6+BCFAL&;8-qJ#<)E_2D{F3@ihG()~X)8>}_D7~?=*@oe z6F*FxTs)zICf#{}A)z(l*a;E&hZJ1nVEfll6g+uEnUKN+1fq=e1k%(Y9auN$j`ekj zGM(f=(;PahV*}O-HthlEM>(%I;R)S3I3e(a3?%u#MC_qQwZokUN~QT8s+0E}4!Huv zLQzjWVQIG%KP@4m!)1UG*J&=~gGn;z5!-x>QIJ2m$kti}J^%}Y>j$*PxT}mBYCb8X ztEd+A%tc~*eo%2k_L&&0zeW7>+{c|}Xr=S1Vjb9NV7h#BgO;6_Cx|F5;(Q<-ZnE$E ze&5~VIKYIc-IgjW9P?0bmb9To{BmwTF%N`x88kCZrtOCJIg3UNk0~7LJ z{6?DuVqqu@v|%UhAYXD)vsiRA;(WGN8AP^upxN?(IEEopUvNp9y|4_teil4I%Q;ld zFAO>N?QdU7&vXB3-BG`3V@FuLdTnE6d$X?j?B{)tj6|nuw(Zva=&xE&4KO_pPC#UU zT`xxFj_>v8&s<{SH1$vvDe+}FkX73RK$Q=>g4`t%B(KxmHxxWhq+H^rAZBi^B9}9x z(Klk&MSC+)8b`dlowuw4KZ+4Il!4zFI=zTrf{X-Lqt72kg%(&Hvn!uA;RG|ISF-*) zamNJiEjj)sMTL&MfLF;AIjee>7P}dJe^%JU*t~h)skz(`X%E?N*pN(hbUuKN#gJ0l zgaRq)%2Hiq_FsuZGyWq~Zf|kR%K8bjp^MpZryUfwvBYlF6z!x~q|sKj-xQG8;f1Mz z!-PK>q_^+fRV^OTaz+k!&k#bj8AVXS7FqM!m6JDcDi8M^)AO$_fh}QyOS8QY{ zmU9u`$ECR2b}@eLcf!NQ|G91;5Jx;u8pidJP(dzkndDKcx$@LkijeHfR;wj!Dt}gH zfe&;YP=XQg04A-*{axt~7`mz1u+0)@C2@DrgUePRA=re3Ch=!%F!=JeJQpSW#Y(KQf2 zkWXdF!@;_t=soi}es`K!HHkth6jc>M>++dvle=P#k4>hX08S5ooT%=!717$_TJkxa zZ}0?Ke}v!{(V_lafmSHWWV%Q?>8%d?-+KeB)*%RAf367h4vL(N=J>w7v_9zN%|%P6 zmSItSnDXE0enOlA{NwHV`TO?`orHuJ4RErM?&=51jDLh3AQl;D`wpWk={Co7>rg>0Yhs^Chi{PQf1A+NYb)%7pzLpxQ8j7;6nb*`U( z*t7SH?E=ze8B^u;`y6q8d`eX+l%Pk~i*X(o`A34pBEYOQI9BIxe^2kRj@&zO(6anZ zC&*Yo|4SY$5?#D$NEo#;qxcduJ2cqtL9KARc(~rGCdbO;Yn}IRR9~*is`}hb4E~SN zg!0Q@q&ia@FaGn$4AK57jFu+jS=B!MO)y5OY-D}trL}Hm0v9$UzI^u%oTBk`p-9e6 zampA-r35g{0q4ATifsZ{lK|obxcl44CQ}&Shv^8*DC=sKIR!{Gr9c8P-9wl98^|?tM#knnKDnOghlBbKtDGZb~tb6wZ2_ zy{|f`p7ZDW5H40v>S&vKJ`2kni)3S;h#h%8mr`WCKN0h>>LUK*^CFJ_ea1V#`+vx2 z)x#49n|okj2=BTNT#s7?VOr4h?U6iSAKJcZsrMJ�$mCh}X-8sXdCp*NT6G@f3-` z5d6JKY_5`qa*l__q>~{Y-hf~A`X;%}J$X#iKKpG&PQ@eg8?do>47z3bdi?h!&6oq| z9U?M_2o;ki2lq{=O!lf*q{q7j{SLEX8{XlNOwxai2e?2y=#IoJ%Ux|lViC!4;s0Tu zO2h=UumJW7(}!Hn%@+3Z`vCAEP$Pozo+2W3aKIs|?;M1zdH;{!h}TsRnDd`lQxuX_ z@T37|+o!6shoS-f(Bpan%wq5ru>Jw4kTzpHJd2|)cl{rlzA+&3HtIXK*>;=l&Dh#D zb8~HWleyWOt7@`w%T)QS(!-GC488E;4pjJd5*WU}Ib}0=BD65`Kpwaw><&#zd;uq;85;=fO z&M7oz$(0mc>NRF9rG^1P`XWV3NS*fKef4 zFUTv5E`ejA*T(9E%1@f1lng@BPGf4oIf0S(>%$(TOpGJg*3ssBnB zDTBz33%aFc2Ns(zoJ+Jy8833G`AB^m_nkuj)TQd<1H$Iniy zh+EHpj>wr4d05+?hjMlY>_>PU6okX&#Nv}{2T0kHBzXd3slj(d%M(BD=iBbDmJR;v zjCj=)ScH1iPBP$QSz5*;Ey3vsQl>$LR8W?N2$71XOnW{!FWx91Jt0ixtEHt@d`^OX*-Z3qo396|ip9C9}czbpB)Fp9(UzL5wx4oe~oDt)(MrTa#z>kYkkgd|>31rU&tD+EW?H^F% zG7uQmx*KIw6YSq0579{I;*(vL>QzaFx`_7a(9VZ#YyfmV9X(mt;&RS-1`FU&5X~;o<>KAq(Fmp?*tZE9G0o%RO-siPK43!L{V6 zAwn{4(TuCn%9Pfs**>2P={F`gBADMknBOc0x<#d-d$=7~v}aJ8!;m2;W0B5~AR6k3 z5AVI5lxj~;iY9LQ8PVmRWhkr)jOvv{ai~PbJ@pkI^;vMlg*wQlt~QuM=2>{J$?#tj z0DQn>&~&HK@lvo<{TKDT0#Jd0b2$jBWGE%xz|N8gWHwEHHS0*f5eIa}%9n5qdLglo zH}f*gn+EYxY9xlyVuRsK%AbpHB5-O+1-QdLxusiFqR2Y7uS_E)B@cRWC`=Vd=FGH+ zJS7+dW-_G~6sMMinM%C5587H21h}wi?Zup~G>mJjD^}6!6nm5w1(TW1b*nwiD&i7w zroT?*1Ix#qA)$ij7<-3_k9LT2VB!oDz$=X@H&d~dB#NnzfsQpv^YUQHr^dOSz^!2n zPR{hc%8Ai4!ywi!Yonbw9hJpzvCOLAo*YKn0G2AKcDClk@~bWs7MPfam2P~CS3EvO zSe9Ue)-zRA%9v#OY6kcU3_r*dPX|0HnP5bV1Jj~UQ}!OVAf+lSrXcBj%|3xzhu|97 z=(Zzn;O3T7B|QUB@34jt;o>*^YSu z*~28X`z8FWT^(t?<15l6684ouu0)6|%LT3{B!lj-F!@{Wa`E5&``;P_ zv;2iE2QB3zBAlT8U6nxT8oR{k3*X^aQp_L`7+y*QBPpfA!bY^=aH5v^3zY;d z94pzv;C_)rg596Abb3M{W7OI6eO!1ZEjML(!2MXx>!W2!+uH9?!l8P_fIy)d)_pf8 z3Q1r_S$p@}KfiT6$js;%o2lf?oU*Z39wCwvLXH$7&l$?>nMy1zBb`*qUR)S>?}-H~ z+oa3qGzGGBr8zYX`VJKsX{^)scOtYqhC}d~ALoLfnu#()v2GNCSMG7K`vMeqc-i#^U|+N*7egbim9~WuiON?QQSHKQopB;eZ_> zXL>YO>N*73HoGg#V-zv@_$A@cp)<*y%s!Yw;6LXr!Ns0*il>-B0a*K@)YNo-<@(Bt z85tk_D2buEbV)m81Kg_5XASAFqH~NGI_VGq2y^pe8bc_}|G#L5+9&4B6%FVFM=}_( zpdvtEZ~p$6Bxusd;;(|cMp8Qy_jMIKn^OQPuiP+BRd1qbDJIKr6a^|rJfpf?AC}~H^RPs-<}ozNH>D8$KP4ZvOS({!?Mm>jY#e zQ~hiEhG`3Majea`B}ddZvVg(eheykDG2nPbv#tU`!F!D1xZF?(NevQ?-l`j`Rw!Ng zjD#jjgZ{Z?2KuuwUBo@{ayUMihjnV^Cn)Ww<0gx1H8fgx1T@D_3aE4jkm*ySSk^w# zP9uoaEv7f{5E8B?6 zx;rr>XFc*-eg%^zSCxdATo>B6`q#X?Bz;>cW`I6l_V1-}buav{4c2qN3?gANkct$3 zRX*n(guParuJ*;g>Y|B5RV>p!DY$@>oh%cUL7Rn| z+R^%+rziM{Nr;{9r+#CNttu|Wbk|&k&@Jvku9c&lM)q!N4LQX5I;yT+;Qnu|lx`j- z6xT%h9*}NBMOupln=d`L&oK2Ct9FjO3yD zzlbfkf4XSjpFl{K6yyq*N9>^-w?@u0DKq z@faHmw_R^eXsMaT2ei;QX*JnA$}n`Ic6Mv-nF~7M*WjfatXMK?+qp;>WU^45M3po{ zUzO1!FemTpH&=1_Smoe+%*Yc~_hUjH&zT+$QRQ31H23-TiiL{@owPZH;Qz3i&y%Iu z;#5Gie$;F!qHOIOO<1cO>dDQXwC>lim)EoA7wGlla%hhK;*&P^ze3`Zn%q_ih$v%_ zWcZfD(6{0M1~0mc?r5piwZf0r)nmVix=MEY7;|wf8G>gOl6188h>cNIOhVR^tV-md z!(*u2mK`#NR?ihoBocBo-wL*)WoHyC;!X2o!xuySX<<-@L$dPRHS(ZR<&*&uyI0qe zJ`(aK>xzX9d=r;&Q3<07an_P%p%0TA{r`oSU4S8n4PI`FbBAE_?2e~B?ZtHU@S#-&JzQPW zbWKIiG{nnCgtNY$O|9hVN?HCIiKmT}9Se(w1VYrh+1lxwzUZQrZY`0HNMi#HV=H~# zozeOrs|p%LXGdZ1tuONAwAU*!Q8$n1&@`3!M51QXHA+sty z^|#QT2)F3UVx(FR2Mn3K8XLzTT-5Z9Bva9_>PnIIyC!uU(HL|$vTgj%!s*ot+OLa= z^Ickdqd+7GZ4kZU>A_;!U5HGyk>MNU?|XmN)cj555$4M&kb9ANSf<#fHrd&nS+%Pt zCZ)y+5+6DYF;bchUrn6in3bjS;nManCG28)GKv=GO5?xKvL z6W|+L#(fh>Tii{IHa&Av45pcVY}MwfR<${bvqi9a*Wj*InAxwt~L-6tCtnaws57rvC?=o&&e+S%Sd3*J&4J(i~5yw=Y;T zh+aAMa6;Joo;26@K2yn37=b*pKwJl(Tt)DI?WD`I>IYxn5Fq=!m;)1{qEOn`&tTJi z&41nFbpTd}pkz%2A5FO_B=75(QDD!&l|pm3R-0tx$x|zA&?kaGJZbB7WY2?!`#5Yi zf>BkPdd4e*G71R-2ioAmzzBQMGIPhZ88{S&ugTbTF!44r<5`d-bTADo;oI&MWAA}T zV3M)rs0^c?fO=|m3i#{6-=VpMi))F}5iFw5Vj&4njL05nC01Hz)~EHEGL_Xc_`?ep zB628HUh5CjxMY+Y$999Olj~? zbdU@OT|?lkwj;hbzZ;w@P6?bi%Hvcy8l#3_>x^9^hJ}#f9Zt~&9KAvIm80U z*LASUp#J;SUTnSd{LG8}UWKi_bogpJkoZrZ8ATVmVw*|Y? zC#XE18eqUI{|(Ure=XReb24)Hc-+N1LXrpH)hUx2?+)G;K;Ih0czKcFnQV77_gQ?* zkb8(mR@4-dvRd?~;C6_&FSN@krZfE2>EGccBX4S*PTasdVQpknjh?=0UN3eWV0+Xr z(@6zbW*qHLUY}-v-;P2F-L{xaF#x9cGVTHC5`{n37d(8i+uOQ&dIO<_9lAwMbDpo$ zHh*(TEb?_3Xc4V-#Xu)&nrkm4M6n7@%nPIBO8>4AdbR5VxWd-tubzfOf`L}L>gBc2 zlLO|{X`k>f9sb;#G04jdq{#joe;WbNtn=#(En|oGDfp@<8(pC78WClne=JNC%K%7| zj=^n)o%{^g$0_*Ji zK)LP$q|qi?7Yw@`oa{5-MkM^QgjPRpQ^H;X<~Z~FV~(vM8QvH(mu(n0i_VogJVs*N z;a>XmQ)}};HS=Dy_&o8Th<{(V8}$Aj7C3?bblc&NB3qpK6veA1vQR8rFkqkn8hSSl z8UMsi5+gb+5G@7_An5Px{&`~F{d17Og~;#O0jJ-`HnOy9Sg1kY$My|6m=FfE65{}E zQ1t`Y0~RpbJg8x_!1_zvCXu+|(1OmYo@bR}+YtASG%R&%V@^p)scTAO=cmSMi0leJ zHx9~}tL#wN=->jZjO2s^OE)VW4EZSUv0IoNo^NiagEF{Ye$^}$h>*-TqERrIPJ81Y z)N%v$kd~k+h`4ipG|c?DI@C198LX{xJtQ(4!G+C)pUKN=g~OwSK;vy&?TZW5@p$+cle?kAxX8N^_)3gC?w}Hdr9k(|vx7GN)9{cBR zPU*PdbH?E?7#Z+Kl1j|(?|dq5)W4x-t+HkuNl3;ytx0AC*-YwyjZNk$UZ zi*PkVJg?8esDlr)1Ts2=CrH{YwNx&oUKG1lDsjv~E z1sPEsKZIz)%wqp6JOn71D+nyCuPpy`{tK1pCH6pFYiy5<(}zN86bR!&O4*HGQ*hpphlIK2WP2H~mLWoDu4k&(7HTY`WnZcLmG85L zxoAuP_Q8$Dg2ZBUJUdQO7V%9+qkwtuJL*})paUrr9tk6&0%ZsHjs0s${*cc|wq5tz zAJ9Zon?juLc1sCS(Pb0);xHu|*`gZHPbld)TNgrs&o>D_m`*Z}_E)?ymlI?f@jC zZ?@gqYgky9p|bNRCHm2$WasW_wZR$@Wy&km_D~%J6T(SvK%C*GkpkF+0-LnxXK>le zM|%T;m~Gz*H~%`CWT!_cmW$Pb;%l_8A6M=--3_kJA?85@BQMc~C2R#KWSbDSBF=sf znfDy0CdFQ8H0wrdq^uEjlej|ND&}H>6*{mDBRRGITf#u4ZEQYT&`RuO{cqjo(CRN@ zvstNox+mDEX3pBplfxbu|CO2rp&&Q!k8=l$8X_J3pD*KN?90UK^AmBCqmU`4oKBlg zUw+|}F?NTC;FrHwz=XWFmr(Bro!!n@*djXTQ-f|V&+s1*fz54HrkJaN+4fzdBHp)t z?ILq=8=O>HHUhAz*h(%4NMPtdVx0KsAtZs2(x29B~&k^}r77s5WHM zP}+UD|LBcbtlPD&*(6tNuQoi@U-h~^t2KT36H75iX5$T?tO+k$Xa1Hszg(Q3VA4KJ84_8Ux@57bA=v=WD%DAy3fVm0!WKt$AF1+Ryy*a zoBLMu1leBu7Ph2v`7KjAT~!pRlCRm(IBE?ha}AmT4gQmf9QZxWW<6BTf2Sw)JYrxG z#epb{-z~8;Sg5Txd7{6H*SB9*4`@Q8sG(F#!<4^1hN(OF+6BBsUoZdTYsjZ?A0IFqr4s>KU|%(;(?D(u;1tl^F<2go6dT_m5HER$)L zYPv53>(`c?cHGERMvs61h=7hmNUYoHjXBcYJ4WlDMT3QD`MPsBKO9@vmg<=0 zVNdW(`xUyTU)H6IB*7nH3WH3UG|hNIck}haQ18wNmjCX#4k7QNYfhT-KcJ+181t`n ze5rj5FG`F>aHpVwK3Jcj=gGQGw3~HLMal4JPf0pxWbD49e6N333PW6)SUlJp z|I&{k&Y*3`*jPoEzA_q$q;20Jj$VGnIAdaJhsum*0&N|_ie^Mqic|M((RYbH2+Qc0 z;0?Xm`~c|kEmwMtMDb=W=Zd%$bQoC)ZDJ)y?=Jn`FPziHJy28bvM<6m#YvK z21r#@y%|st(}{1lW8#%s*%h~XHOij+bq|1nM_1{;4KeN%VucHI*;@jCI{|QZb%KRc zwMJZJ9sadhO%>iax4beH_h>c!#}HonR%+UJOfJCdXP!c&KF|mE8)UOzy|9hsJP9~x zp_gVq#lt)kcMU{qfZ=M7q$k$G_QtI$lGUppdH^!)S(r4|j9SsMCosz3%$y%192pip z7L$JDbitg|;^Vc1p&9Rwr)(Qpv zf1-YqKOd?d+?0|>ZL{TEx(Wy%3@XqMrEaA9K2a!%=zu1Ul?7eW{nyMar{lrG!q?Tq zO&KpPXfc16%9jQ-doY)T|qaZG0Y8H_gyw4x&Fp0wA^>$9H5a;Hi z%MT{bbXgEyaKdZr;7jR^e5Rq~FUShwF@aBxGu{g)zt{MkskxiaCS~^$cpX%&TrhFr%B#>_~Q*V|0H!KnMhyPXP6KMjogdG zOVB@%`IRAnDuRAy0_%Le?2QCgW&Mogd+ai!9{skqNx+jy&sRHB@}nE6$b5R*0iFpsrG1d0V} zqq7mx@3ig5Vb_R@pO$UK6ic_gjX@#0hMYcO!L6^aZ|647*?<~L6%Hrc&dtpzW0k3=e$!@=&8j`) zlC+T%&g7NNiq^pV$7vS+Mn=&cGM$u+ zYab$3Un417JN>%_0s&T)7T;IxFA~={ee)~{o|d2|2(PW)SGe10^7%jawm95;*e%5dlcVoUY@;U6nkwXAG9Q!;{R_Gy4J^-Tse-*fVChyqQzd6>a_p96L=FzDPPiqMp`mIQ9?ffloGN(7I*c$8g4J-`_&odxw>Bhj^Il-;)vzw5ud5gS zk!dUyBCMRGVG$Lw)O*Q3pz|13a{GGyQIPpXhj5m22qW3<;(4MDn(bzZuSb!aRs4(h z483p9cKo?*Dbwmk92=x$oz$vRCJ!dB$T4cA;qyL)etW}JD}9rz#b6*1Y>jK`3nG#+O#=uvrW*P zV9fFXCEgxA5vsDh#2+H&skiH6?2*2UdiPNuat|x1%f}nd4tU2W6)2QVIudDPc$yVw zI~J*9v>RQ%1YI7je`LkZ)0gcQz&0fyj?90T^I9MI`<2(%{TLsS6d(M63)9rN2r^=7 zQv{F$Y~o6KhVbPPtb#kLK-f15`brP1fC$YaR_#a-K~%J&CLy>zUdUnftMR?Lg2U$1 z=o8W_X6*p}U;tiRL{CMOqKUFFEZ2AQ-wr7A+S$6rTLN9YSY}FWM#x?S_lD9A;M=L!B%h3X4FYx_UxKvGCF7kl|JO zn>2D7#o8VszVt0oWZ^&EL%3tv(CZCPF1aa6^>eZ|7P85CpCcdnBAXaL$crumy`unf z?7!}{Z53x{(TQ8YP> z3~iCIzjO<9B+S(P1f$93Uk_6a%rXam4d2u*zlzPdA?tU2bPdB0(;-34JmwQlVUA-; zUA^>&zg3RT&)+TN9YUbkND7_WWjNK;uQv`Mf!+Z_UQq zu3$T5Si1AvpyFHoHq;mMN8GsI)XNKWTwJ!d&3I6EttY%Sp9*IXnEwE++GYTUHC5+@ zw-Nrg8AsDRKh+ogkhn^1hnEqgTt>KK`;%_hUkGfk&E|e^azZTjdfC5F`S0$|Iw;a$UtKUwJ=v5)=30mr zK}Nt`#N48iyLokCu>RBM&kZPgFeV^mT{Z&E%<#Qk2AF(MrE3xBuZ~sM+NFl4>Ek0F=&*_Z=S35^4Zc`*Lq>R-4S{Z>wp1;G27q zzrUq@>?A_1@nJr$MU|+Df{1^BoEvaTnR_PQ1ssjhcIvr!rZ3v~-3ud~$Fc?i1?-VG zwGhg6TZDJi!%GS&s(6+_Ho}(C$$m2ULz}Gjdj9>@IFeL&UEv^u+TJFy_*L!V4F)$Nc!d-rX?^49`t%9~{dbE}`%tksDYR|#Einx1L$ z^%ml=`rmu#7(CXWW(M5W1wWz4j25J-VrbP`xU?FlkSIjEI?(;wRjWCB)1mJ?>f430 zyL*tiFGPPBg)-*+%f0xKCf&fIUa3T<#8{QIiyz0ihl+x0RojOPReO!oGL{1zVYpuS zyI6Hpda5k!7J0{>WAV~;*i5mwuCx-(n$qg4Mi9Q9e8*;t1q;>1agV*SaCE?a=mXtS zL8~yW3#c(lll4d~-po}f)OHMK53GZ~CXBLNd#L`}+^$U3zFz%R#eH?_QVBh?Ou{d2 z@E6u#o8jpAu-{5BgGR@yPAWolrbK$&K#1fQc4JV}P1?9p8@|5qPcU|=L{Ri{5MFF^ z44SR@Zu_d<+CH4?k_#?lXIDAet+=u12&@i*?5#C)k{3`uo$5;gS`mrLAkBIF;Y| zTBg=`?uaDK+g*4qQY9^wv!39auTW}X$6T8jUQs8!tMHJ1x^$`xp_t?jJoqW}xc>Gw z&>$!SgC~h;$kfkmRGP-FY^m=qECa(j))!dJBogm+^CSfA7lCqLgz$xp1c?{k8GCH} zcVto*g1{s-?oG3Hi4(fIc~^qA6JoOctQm@Tyy+(M&ITxAKhM`g1lrVGYPdZBFe(K< zS$kybtJTUDhcl4AsWNRuYK;*M@qdi{Q3=L-$a@!y@wzH9Np93m6RHq|USK2QmQ5)| zqDR24dW%vIU;ReyWT>-+$~@jtI6{M&_Je>q>7n9&*OsFf`JuK4HA)=dC*mIq^UrE| z;oQvo>HL}~=P`M>0c&j@RR38acIPqB8B&5&ISsw|&8YU9YP zcZ|7MBudax&6y-^=+jGC!x>|6XsKHNzloy_&`%dX^RU_oXDtABlJo zBiSNxm|SBUdJT@mHiG!UsSw!Sh0njrY?K@L?5bR6r-t;LsrepQczp)5K~PpZgew2z zGt*y>`tJYk*xX6OxFMJr)ul(w0`OimW0uVRto`BUYq1pB$t`Z}tXb}hPHvQLhyUhq z_^nV0staDj?vC1#zPqi1pLOlE`ZJ-d41=XM`kzele}<-Kfli^ksr)x%?6Y5RjX4jo zbrH4(xN*dbCp*9=r#tRW$f=`aV=!7;@S zIvh@)srD8ePY(QKFgj2_z!9=j3z8C>Uhpc$CP+DJH0Nbnp?d(c0N7`KF zWi-~|3s;XYbP+tC1@GKX#9szW8%DsIQ?%rJcvv`N4VA^l8_b(*K^eodh2U% z$ELmx3Njwq7XaLTfolQ%MUa*2wm;hMcu`T^C`crg1zo1j&T*Ffc>z4D?Q@vi#7u4(rF{(^BaCg3+zNmX>tAwh>BpJ zH#YBpqX5H&a2y9-ity=r1mO)Y@n9y2iF-W6w9?({eLenb4aZ2fSDa4MC}Orh0kHHLDGwE%t6BB4PDGBu6Ew&Z0{kQ z6G3D*6dU8!^7nEJ03+UZ$nE3C`DJy0StO%-fEZ_Oi-pFSVJd(V&X(V!Bmzd7n}xF% z;la_RvFF|L=5U*sU}`=g@X&i;-3R?z`LoU*25UE?9}?7~+f8_OEc^5p!ov`0;-A{a z{!<{x-683|+1j^^+3@_~if%irt%fYRiNI&Pb_ok%~Ef%fo8Q}1Vl^6 z5Deq6iX$x>KoqDZ+Mm5(knPu^1{Jw{)>t=9X7F6-29uq^epQ`8an_|@;nd*K)+=jL z$E0sbrfi6y-E^gaP1|rg4&t4~i;o!LW2o!HB@ugo6+i3Lv=NiGxe}O!X-8hNG&j_= zCU|Hs9ArR)mu)pQ(Tvz6Q#&X{ke0t#ao?R?WJ9Qfl@y=(a^p}ZL4@okC|%w+V=1fW z#b><>t-k#x^i<}Y_2Ki>-02%b)nwViVEZH8#I5oD!mI_g$`)s=CQ~fLwCT0vk=F0- z!T(E{(u4|;AdncIPTM$;d$tYOY|U;j@(0MNOE3BY2G+AX3U%!H-tRjArg7veVi!AD z^DC|paN><&NL>u`FMr;*o`#o`&d7NxJP}IFaGImKmocXZKtuXi-sdg^XHHTrG8YdYn}~(Z?FskQ z4MtNv?_W&y_UqA3^(`U?N%Nly|6;L9M=H<@8|)9qDHj7!6+`Dwe|1_ z|IUn8e!tr<>@}V59rt zf+ZyD<+YLm9JTt@j)Sl{fdA71_-0#LuB=cJK5d8lqphw^!~{UJEyk@r;Wsz_;Zadh zr(K+R%S}BO7-FyBDnr{Xo>|{jz7fLZ3$q_b(nDU7JAP91(YrGj##n^$q+@*<&b!-K zpoaTgSL@FKlyi)dHM->lVS1J!4L9{wdQzCBow?exwb#5~#;n#lh;8kXW0xPFv%nJM z>Nu5kJvv5d0YeRmXbULoaBzOQMF=f3*W5EF9~f_cvdbpwXC5`Xt&A~t1(D?N*mTM5Xa(cfqTp!;hI$el_4$ET(h?!%bHB;J0 ziZ#xk*1+7%Q(<>@$D>da` zA3;yH9FK7T==8IH876t_z|3RNK4zhjcxBi0OJy8Az27jHdk4oVZ2`IDa6o$`l=yn8Yu4PNf>d-R2eJm0$qt%=M$!|Nbt}D7{Fth2chI+_E<1cl?0H`9W zY71S+X;Oi|rrL%_itgI+5Js;5bN)}KwLQk(O^8Z3F=dKNBdljMX2Xgas)s}?bBDaURJTleEnJ|2;v@@TgUHABcPM4Rkl%tj%9KcV; zDY@He(N&h4=r&XL18<=v4kO);2wTD--@tY4f-Uz6o1D8g1cY{;FF~|(OnbFte|2lE z>J4JxtP8P7x8X<$@!e_MR^ay3jm4_@r6O(pNoJ;dzY$NjfGQ)nsQuUhcT=W9yPW>)Gm zLma28L@UEz$bNCIX%4}BAKS-v*x=8b+P5j$KU?+CX8U08dcBT1eQ#aLVDEl~G4#3m zw&T1&AarxN-CsqRSi#(U!C1>=It)?^KH$Bxa z_vpd+WqS~1wiL$4#F*dq<-$I<2_tJhWg5dvF>FGaovnMQ@X2<(b^tlaDyN%lI?8lY z*PVn#HLW5e^`iUZW&!FyRGol;K#%OEylCrP+iVf+!({LNt9z+z{lFp(R(5=#L?nDg z%{DEb;R=cGzd|!<(r6`siT!@FsO|NIQ@R5d+ePouk3=l@xGBo#JJIbAvNRe6oIv&c z?FAzI=2ZPCa&^e)?{&*`;pd6*g-X+w;^}a#dvNlw#t8$(M?4T&Jw7+d6+CwyE&^JG zD&^cWidGZKoExM$&J$^NunTonB3g<3yMEznb9rZlTul~Sq6eP{&1Nils#E|P0Y00N z1aSVa&M?LbdITl_fnx3+4f$LMV=(;wJ7}XxV|+4VJ8m*&-J3x#lm98|-LNZvXgC%^ zxpLTdXrBvSk$KOMYPGBZ1E~W;SFZSZ+3~bZB9U!b95G&SG0)|d>TT_2;lP2E&-~6z zS5gz-076hM^z9?1+QBEl`sMwegpC}JhR>LP8*Bq&C1FCmW@1;XYi)3rFiK{f8SAtA zAJ}*~p}&0RB+(;V8%&S43g+UE75Kd zNa(0vb8}m?iA-Tv$hl#Z6&Y>YO^(IsZp70kowdPQ6?Va8z1dAOQf13Or5Q9TUkUI! z9!kX4{U#fj19vRYmiC@~rPC0~XgA|vh*xH@ta{9$7lNU0Oz#2#M$S?(W z(PeCFdpHwg>$XSRrc9D5%o$HJKXa&+wq+a7Sp z9%0o3{=1+;Eje2BDN{#ks}d^>f`jpdu|-Kobx`c%fCHQD;0>qT{#|9w)sN%$xS({ zR45~s@l1v5Zf{}i3%4ViQyBb&`?){M&{CNB>dnkxe^nO3ETm3k^;XV=1VoNuWT_Xf z*+;whl)(N?%acR2#X4ZPN4pL^GL$O2WKr761XzME>BbR=o^dYvyQEtDpgRU~68-j~ zwIIc_s*IYfx?H3h^Uel)PeInlbR#pZ2$2#R`D;%FEu^Y%tMf6Z`3vCPt94*Bdh)Y) zVw0fERO+2Mo}sd+3MZ7Y->bG}`d`fp`d%F4B_$2!;Mszt% z*2YwN&7p1rAGSz)J7)d#mV^yTA|1ILrKn*^RVd>bIb{N>6PaA__50M`eS+%>H_LbK z>-~l5N8Kgc)VM{tn4N{nL9o+m;!V2E&GWD<+fNbvs?E}FH-9nsR=gMi%c`j>lAt25yth?tzy{T|5mCf#6s0fq0HXZzNh@v(=LE@-B{ry3&1RI*a>FQ784|538t13T&qM*rL@aT%Am_q%`Ceb$`kIP$cYF6^Cr+72 zk)S=aMe92A`$)9Sg~xwx&e^YgS42w_j=Ppk51s)Jj}&QQgB0u(G3Vt@7+N7F9ve=KdXnjB@?)JlKxKePE!0AI!2?MWX%+xB)Z)FwV zth*xARktqGOe15||D|zR9v5aPYZ76pt?{gK@JtaG`q^JLuJ2yG0@5ly*Luw9z4`pR zT&8wQDf@AZ`Fq-JS)qGGBta!h{_3yTJ(s@(Oyedkc^Iyemr9f z@^4?DA?JqT1d_QQ+o6cj&)~IQ!PnAe499;BGewF*uldSarRIBb6bcMgfpNRYn=NI{ zHAxHw>_aGq+2cyyv8`%B?aj40g!s0ez&oh=j+%~nr+Nf3FwP_lTbJHqZ>6wR!Nhk0 zd*d8*t)#?5j(%)g1;`{1W^g&=D~QuG4LVMh9+9M<{HtmdgqNCbyz2Q(Wg694f0{JS zT3I~Mbirr#Bc@ZHYBb7?dYWC`F8^rs7xiE#&9r396|&U{{0FosjS*xM8x{-oGnN(9 zM_;RZDt|xZ`RwTOX?$3E-t$7le71N$n}8n^rC$z}jogp-0|EjZtdMU3FVB#6yjiPm zrka^^!K~%%ZUZqg+x0I1k*`3!M}X~re3rvzSHH5~^+nPq zI&>n?IQ|rv^@n-$xR2~R{YvsiLG$2o7q5)-NPvxS4`Pd;ScU4su0ipD^k6?m8r^fd zL?Eq&9&CwZgj7h1wn-S0<|Bv6P7S1E+%CNlBPz3l)@jdlQ)u{f2#+d3WI9Zl$K!5+ z2iZP&uh!Zf`VBh@rXi$JhlB~EU}=Z2JevZ7%0)on6tr(G&PKm6e6;Y691b>_P#oRB z(Gzt({Vb)%+pq z9~Qm(Vy5+_E?$tOatM{n;Fne6uoHRG}!My-Db}MW=e=H_NXA z8@td8WtUJCD#kI~EP}l%X#*e#$tp_R;Hn2v3CKbds34+9yG?-GgH)$SNa7^56X%^#+sRja>;xXjzRLf7R- zuqrCZv$$$|E*dqr%$NO8jE~@AY89&MyQQ?dPI{6Tv;2Pn1uy#0PO!jPFlp6(Yz1mG zA!ez9cEjLxu-4c7{f_U>r^qyYtTL3TiNVZrxy04gbvE{@4a~fK`wsu}fBvt8wdn#g zv)K%*)e^IrOZ+sX$nP!%e*4BUL=Fp*`s0x7Z#tW>0Hiol((P~E>QWCN38k2LJ&tqK zBmktfkNIAWlFd%9kHgp3?s>({XJspJiWzc=!q*Onx9f5qyGR4@iGe1gtr6^l1wtzC z$|x>*F_1j|3fv_JEI1o~PkmqG@Gk3er(dQ`czJZ@lM+qHdP1ftXC>Xmdir?&3Lo$Q zH@Fu94acT@r#`vD-^~9M&Y?v8Nx8!D1vtfX8UjcPG)DzVyRtrAg@MNcNZZIa^KY@h z3>#E%nSEwzNwwf8R*Yj1Wu=RQ87|r_cC5B`5!z@Avn`EPBD>T8!QHO*OAa9xe=YpN z>r7KKG+1Me37GD6?SaY!8$6!B8Z@sxoxkX1%NN0XHO0oKDBqy+d8`2)7Wb;fx8 z5)C$frQ%hH!BXnv*)4}~(H;#b=b6y}J3k$sYi9#v3RO1QWs zcg>kB16X2)8JPURZNI^N{Cxh}D>3UZ_iAo`i5W`NcshR(e!syz56vq46+iL|U>Sgt zgk)iD9 zAnO5;q!)_Ly2>7J^y;VC~E7O!kbY*L?`1 zBzl2f8+6&;L(lo!x?vxLQOXS=_CB;rV&fNgxs}+*;N4G_2r|%mfep{ZX+%B5Ji8R7^NYyOKj00WM2kptb)i3ocRR)lSn}>ywYB& zw?AEI^xthJnEsJ=ftDuv-Vd7keEWABOTJ|}A`W2Hz^Q})DE+;`MqSyZcMSm$Tpw1L zV2U+XifMB0BbB)$H@^Ox+uohgQ(QP0%{j%!TP39~yMVdW?UJn7X}Vt=N-i!g@Rz^* z#cb>Z47TP| zmE4=s2aw`@v6IIF$C_22{xz!zYvmba^qcLiVAD2R6-n4mW1mUcfTt9P8J*} z0syN6U@8KusEb{5duodo)0w@d-FK_|x_&%zb#;v|zL22*^Ye3DTwG-L{pzdp;HI_> zfVsN5#=Cd#K6^lN>RAT=_y2BiHn0rjE-X?TgVg3~$G>$Px!W!#4;@QRz{Kx#rPG{( zcCRCgG$u%*?7E(=yneXxu5lX(>rsa*K#8wtW9DS{oy`Blb4f*jj0F&?MLn9o#$*eZ z!zc5XxWO5gI2#0J+FYb-?;`Dz|2WcuYtRJi0O*DY`*@FYe|MS0M@mDu^B0{!Vz%t{ z6$7A1tP32&n063Gsmt1%^M%zR%et^^J)m9Tx%WuJ<0f_prFg(+4$Wkq{De}x;|#{y?2 zfKyx;WD*pM9o@vX^)2q6B8T!3w$B)7wD-3S-(gvpA^oSZN;*!d0Iih_1?KWwge9(4 zi%jYJ&@Oo!Z{-9W*m8`LxIV8i3*g0BM6H8_9tD=YDpqeh7isq4fL`U}Or5)Yg-sGq&pxzg!2&a^Fb$tB z!@$(XL5YWfPS=)a=-QdOHaV2h>?p2x>G#;ekzOi|FZlvbeb%`#UaT`LLx9;5Q)sIw z3&(!!i512KAGrx=Y*3@yJ2YS#p1JMw5n%v!E7tsU{sK3+?=4du2m>RM^SSR6@+Nj$p?+=eN4{?-F)Sj(WBZOr5Q8SNEhRQ#xzQ0!OzYsRnc~() zt1x`rQ4<1+nZCD(t^l2AN=U4et|cNiWwKWAiz~uXYVFM8q@z`}ylYFhdMkiX}>acMCMwpbiYwkUnTI0}xoH_SjVo z$9H$GA6t%)9=x4l%3*N*66#nbzJOz7;Q(A5%P)Mj`YG0UkNa5r>t z853-r3UE2Lytw@O=;^_4OLSb(WD7R{#`lqGUwBslo8>H~*ZU_&u~cbBq2JfOOH$<` z1tzh}n?5!_kM&R2?QEHKtBd>2x!@575oED-ITu%F34Y0Q$I_jTNgNnX?40QezlC?m z&a;JIB*p3+ivT4C>Dp4@xdkzGwX;^*^qfC0!$p@|T%6A*IWIcUAf6QP+a_3{#u=tq0g%Y10tmI}c(-WOCm;dDYe2h5^EeB4 z-8rZRpbq^^u*Mowl;H?@PWXgzTniuD%04*GwMyosIm!5Gi&yrchOVv;Oy%yo~LOLhYIlKps$K3BHe&aNTZ|4#1YQ;@PeM_qRV;B7!s8$il& z`I`HO=ORrX1z?R5 z2#FV5|E1@gO6cdSs}JTmq>+rSe}vj>w@F6bZ#dgUc5%Z#U^0ikN|G=Qq3&v9|3 zMZ|LHSD1MByJ3ADE92RzvMyb+!0hN?X)M+eK&S;Y2Ebw3`F(-T8k3!BgSClvnR6}& z;xIAw>FWD3qB-h*8a{QtBRd)96lcIL$oK+fsxKaI%hBz(gV7k*iMABHi{HHP^Y>mrQ-7?n4C^GwRk| z`27)%BW!I#zwm6&Fc)cI$F$FuqX?YG!W4{qDp3Vup;RyjfEk-(pQafGE)TO)&w?R_ zv-~=7NWDZ*@@duG4=!8Y_}k zit}z*c5;jXlHF!OOK#t|UHMzX3%lU4m#)5mcus12P6}wnB|ai$v+`%4`!5Haw}37# z)y`fBltBrq{el;_mm5c0`gmbws$9E%bgqD@#GKyc!=?~i|y9$ zxaNIRj)Xbd)&O)I(k4pK&?ulJslO|%agOU-D;PUOp3GmGgabFY*P3`h+~wqI#-@8) z6HeG8fN?*Zi^=m>e)bh6X&s=1E}~%Foi*Um+34Ic70A=)B<~_E;6-3DK{3}W_5t5- z)zU{yagbSZZPSpZ6UbW+1KZ!&>%gu?vs(d5ZPIuoTYL0sB}JKSGW12Np}8t+86B6q z>X%P34yJ%}-2%pOIqMS^H(UB5X;UnBwqmg@$qZBOoDGhQ4S@#$OfcP=Sz=K*ox<~P z=6}Le`G|8W?|YWMnSYB9xEHeK(A9vSoV)?|MmlO|Pe22!OF}ZfRdRD{k6PYVB>3Uvy@qeBW{eEqJjrLe6?zC&vS_ zm=}Owy4`|ZKx!{F38Q4MYHH}RVA3*!c7)`%aw4prYh|oOaz1ZPo>ltPBsX|&>7=a9f=13fW|+~kfab3e&0gPagCp6Y2q*Z^(Ke!9HbqH zvg;RHVcjJynvK%njO-PC3bu8T<~GNB37}zu2WIChF$sO-#wKod2v93#k*tqcVaBD; zkz?;$3x=*0yRHSd0+ez}Ku*?h#Spc-PMbw@7t4V(DF6T-fJsC_RIyn%G&m9~`LSe! z@*uG%w=Yj1^%tw?&2VLMK&`xWPj+#8<}{D242axaHHjegMLC z2{>%Ka+q|z!Si)XaNI6IRQJL* z6fE7bO8d#7*&zo;R#>ep7}4wuMFScEFMrO0qP8*Twzq+qhYt@|gKB7O(h&8qeXf-4 z0+QtY*REccIg)skN&%$`HSS@N#33CbS;LsINLM(=HO^J?Aq$9di3cRshWa7rwAe(J z6Z#4O+6|90p19mORv*}aMkzNt(omo4!Os3PWC4|LGe6f^V3&81CctC4T%GYWHm=2z z^AfRru%&qIx8N!^nA$V9Jr6aO?KA%$oKZ^IBUvJw?C-Llj(@08;sfrZMC_8cn|ycq zEELajsSL$BUig=%M1uupqx9D$%s95f6p!Yw@%r-7!TZdOVOuNE*YoE9+}-3vvcl9% zMgk0Wb2)o9e;(SPYZ>oXu7Db?KRR<;jUvSN=*(?y>_r$q{gvJ1$=X^~_}8F7g>_(Z zmN>&t=YK-!pCJk-SAviaxNnjixWovqGQkQHRNlsv0;R$yOkmxFBDeuI{=F#Fgu4k7 znfu4&3$f6eqhpa+=SXL%+a@C#d*-6U`=dW&cLhE>wk_Fa7x)~jB6pA=aR{p-%U2Wb zsh-@Wh1j(q1|&KNI=^tFeY+#ez_93R$i-9^OUtSWi=_dPUE(YNils7;WSI4mM|uXL)GAv(HeOGl2L(MlHV`igm+>{9ct8w)@!F+LXKgVxV)T=hhvp&j>~w`L{dyj={OL-j zlQ;;gVo>N>g<$O#M<(|Y9WuT~XB?yTdQ8^k zoB6kBP~dq>dt^~o0|4PS^KZd4k~PWz4unOJ)Q=xx z-C~)XE>;DqS3oieu@#P6Pvj}9L9Rl;N?YJ_zHiH7N#7cX*~N`c8LrO;7O2HJkIa%(V~lRH<=B=LeNtWh2;4P}*1 zS;lgs>jN`y-@e0iI>Xh~RjaF6+|F{j1OR;bWj=N$2WEcqlb>Yw{hYweF(oxB#fB4^ zEBGGASC)Ba(Fb}hDVI}p< zY@>PEUa9`>>cft2D3g>wm*dR)Mbk9BAZ-Xe99tuuq%W%bZbQj5hS!-?7#Qd*77I+U z!F_zd6e~Qy_0E2{c~74G52_xFBOmoY%nMLRb&=Q1|I z8uxL7307N8LeJ*U%|rlLC8_e)Q!-r@Am?I1iKn6v}&A4-@2Nh6rEP+Ej>_T09u86rpMPdSK8}D ziP<)Ny(CaqTZH3fI}MSI*+2G37K`T}yWQlNDBdI8uWnP{$M_lLyToTr*X!W^a<2Ay z(bs;6WpT)YdCIPL-+%w-EZ_jzV`tvH`2iOf7s>V^u`{x7dVE(KcQT&r>UP(rU&-H` zk7Pd3^8`Pg0kg@(AFX`^&pNEp1Wz;La#xSSB8{2uo1P;~!ld2o8g-WRpkQ(&Zr7$G zy*}C*I5v@`N`BiKW@oh+#AS&t9gVzUiYmfUe|JfMvp;{ZFnDcZ1LL9qxD(@ z*z0HK^L93AC{WsW?mq}na^HdYVrr`fAc}=f9!yKd6l;{&VCF3tF2l+ufC!h+csnow zxS)Sp85}^Wu*4Z$ko?qxGoh33`Tp+X0~(Y&yTy^&(X55^J5yj_?fZ1a+Fo8h>5P-& z#K4zX3ZuDez4R_*yskNyGg?tJcv*SZ!?u0x%cd2jBAgc$rxF`~KWUMY&v;x*%+Mfp z3j@;B@U`jJ6+YzzBH4Hv18m{~ZXCY@$?b*GI7YTbfKww)IA9qR%h*U;qHtOlh?vT@ z)-650m`&h4*UEBE=mr@B1TGYM!HAcH*vgeoZkFTGoQGE7*?-&yuZcbv;i>d;WtS{{ z9rOgxYpd^#v}8FIYrcsWkG$&&pfg6L_p~v6OWW<)fJ*;dmFCQK{6K8mBs7_Xcga2z zsR%2xP4O~rH?r^kOUkYC;{!r*{W%Lp{brysii_K;AN2o6J7Gn{99~LhT!~# z5B#@4#r^L5ahDMb;@GS+Uz#lEGWPZSdGZ3r3N&EjSNKwYz~a=^E}6!Q za8055%YleO9Z4`o_c^U1>nF6!D!xXgAWyA+&ByL&1)SC@ryNV#?Lu9xoMJ24VXXSE z73~-_=fC;dZWW2!iF-ZbYgxN`}GqtlS@wpeM z!!?LOqNIV9g-_pe&Qlg@wX<0IKGMZ59lc$!`5XeY4hz`V&m!jqm((K^$HoE;Y;}8yW7F@Nz6ZOoN*_B=x|7dO#@4Ic_jWdk3^=_@SWY$e z;<=CaD3PZ79;;~VA!;H$n!on?9c%balex(1CKEJ}Iz-kmWwq3l?QUn1V$k9~<-46b zEda@Z-<+fXgnQd|^T)=9&bTdUC#Sy->!ZkiZ=x%a{+=7lejo`LXU@OXI!aDCayN#L zkgg<53%2uhcMG*72q?S)JZY^Z!v~+mFISl124~9JFazDgWYMm}i@~vM{EO$n)C^Os zlPqOA!2tO&j>EAP0ywnFvsUUnAH21Hi3{(R$BC>jMn@}N@Y^Xl*DgH~G;pqMR0?U? z&h4ueY5AQ1P_hTgTH z(OE-N8%Tor?*7sSY|-PiX4tka=2uAD7Z4YcXp=n9(jZD=t|Y}y6MnJhCkC_rKH~Fh z14!ND-$uqVj12-xmzPDa^`nVyleQ4Y`vEYQ$f|b?MstC_OB9#_SVMx;Dr^jxpqf;| zr7mt;=xJG42cAKaHV6x3t;bZ9of0+$U1ru^@h>6nZGgnOFc>~nEJbN z8Z`=3{w1fXN^7o`h0pt+w@$~5l64VV!{*WFJ<+YmebPXwz#7vqvDo`ssO>Ttx!>ym zXlT*uVq^puIH06KpME`K5W!z{4lOcKLoNQgP3?N;ls7Ut;`){w7hvlg=!v%oiXyYh zh;qs+YE#8q3m5;kb!ZqaDpk7sBzAAIpj0Sv4O;RxChHt0S0iNta+9Qczw|6%mnIDc zh4EIJSTZfgGM*_`i03GG-D|YP3%X~Zz!WP#7YP&0efYktu?f$M zd#+1Nu)@+OeA%E5&lq_@njYjSmS>DhG!+b93t60Z%Yb*6Cj3rLL59XBX=!5~>^=gP z^lGe)It_}TOK2~iDONc1@!1n>M$NuEb~ZaH3o;A!1-0QjcJWQ4F~v(IHVy*ai3hsb zZXh*vT76gpCaAftF)e6)z~1@1K}bN2?m1_`we6+nr`LIzcXb{-+i$)P-DbPHe*Tzt z18Q3zhn6ESO2QcB6c%}eMBS_Wt&+#cSt_S+z=xMt}Go{AsG=i1i_Yy)^@&`sJhuGrly23;JZzLxH|Ntoos zVv`nd(}09+NuP2Kdi(?rg>t2ImU78x(`E4y03rN`8;it%X~jP$`g-s>@vV_#Vo+0= z@9wx<7M+w?YScElChbL{^H!t$*mIL)Tf45cG-*K!i0UkG$;I8s`zP+94ahz-*PI)1 z9sZISzlneMwR^B+h!X$)++3%PD21QFIJeZ{j`7~v#aJ5_N^{<>U&kg%;*uQu!?9HA z3Rc+Q0j_)9YM#zt46-USK~3q6SsP3+!_vF?)?q$%SDTeO6#bg{qziOP0w~lCor1$S%)#;Gb}>Ftf}|G8AHe-jlm!>9(#>xQWk{XIojdAhGeg$ zaoPeUYj~8u;F?1g1~MtY2X;EG`L5KE)DJvj)o2El}DxAxZ9D${;WF-il9 zC6*`RUu$F2DMvKi{z*Y=? z+%*zqJfDM~N0N~%kt%xxC1fDt7sO848gMXlyf7oS03illn&HtdnYru9@ex?L`?rCE zvwfM{^5fqqg;jnP?gkJhClcOPWR`d6M|i&?UavE1R&Eu?xlm@N?%BE1$H9nTmBiB$=U0b(XQ4op`In@sRP_ z*R~eA@w6KWEwqS1OOqU9+sy-$E|8#gl-$030HewLUGyH;KmX>yQGPt93zC4N#VF~A z#eEkwPnaWND8&9RoPgV|feU@&<7{Rz>(HR^N{F_@(&dKAuz-v@jL40G<04Dcou$k| zfLOuTmI-ae5Jt)Eu{3?PF+v)4SkPx*HVa1dwb5g8N_v{HCEhny{3+tPWvwsb&d5>n zY~=b41zkDt#tG1lQwq3|4U!U{c6_?6-1sGm!u>D21Jq}m#OzGzpC>+Jc^ghF_ITT8 zdMEf!#m{CN1)j5x714L;t;<@)ecIa39ml5$W-kqs<@wi6voWhusiks;<)GL;fN+}i zE}WaK>z~(Jr_j}ob99Akz;wFze0I*<93&Yjo4~F(mphker13o>%vAz_spw*W9|9TduUm(TEQ{v0bzQTcNz{n@bKErBgP0&2D0!sKp1l!xx! za_4?`C!d1Ev#5=@v@|_o5ica^f3)!z!$c6R}YQk#ZbUs-{ z#G^y&XQ>B83XpQfzI4t>xt0{}*mbi&WA+=${^Ug8^`X+X9(T364Op=)v>iV#KsuBR z%6dmRR60u=;UENP9JC$h{nr`DwECSJm4FGGflMb~(2oOc653@fm!&KZgi_Tt77fxQ zh)}2Stj)ENn4y#rieq%*zC{tGJ5f587y{+4qa+cq_Wk%;$CF8{dJlIwvy54r%t=ah=Q>O60NY$khZ2RJd{kR#%y%|a+QakkUgZIg6tr`l#((E!YT&soy)?^fGH zma`_s`?kj><=o83o4U-DF{?s$N3$vfGx{1$d=@udYl92$5|UQ7Rtqwd#W)~h>w@X} zB5Br0iQ{o;4f?ZhI*X|-E-Xye{#iheDLu)M2QI*xebMx*R?mviIvE6f%qS*V2tFffP zBgZaDQpor+_HP%KXj`GOdIy;9!)Qel-`gwG5sOtIVxBpt%d z?(zH;u5s>xk)-$TO80GNm@3Sc)-%L1NEQ_3^qQRBqs6Xw{rm`z>i&J`{5KBU($6Rz zqOZPlJQa`x8~`Y3AmqM_jb9YGG_ixYy)dRl(mL=_CWzqY2Ba^!Uta0da6>aV4VZi& zwx~-`9T#$VrNu$I+K;!5<>+UWtecv=m{i(CX-HWf-EYib<*Xs@e0XLlc(Yaz+1EbQ zLl}n~I1rag9YHe$AlUoT&RoRfY5?^dvBz#u6OTD>xsKb&Tbttc?7sXKPr%$K&)V2= zO8eI65GO|Ho-}eyTs-b=C#zko`{`nDt)`Y+Xb(oFg>;5hFRP*f)Z_UpxSBr*i3p}x zqQ+TxZW;STVB`Xy9YEQ(z6i(mc>XHHCAln`&UJ*YXl~wVf*FLMkZvu}Z$IL9Am0lWiDcXH~|uUgvG&&DV5-6}G3=_bsl`^p#~ z>FNAMVD{hR+%rfnj+3#ZWZ4Op;&k8IA0akt^XzSjjCSK-43ey*^F`l%>egV|MW_M2 zZJ+sS=&?CXdYnGGTH5v84mpP(gi#s>mMFP+B`VlDmzV4%V4~k;tX7J4>fj?U3jgUv z+qv^u08<0zsJ8RhaWm~=RYa=zO}G*%_-kW%1Zb7vT=j_JW8*gBmUH{(CY1Opgyhz!6kKII(dG&qz4l3RQW^+6Yu7?D?oAJ zp~MVJ6#fhV_!RmDm~gv>q@ph%{CkNd3N)BuF-mN~A>`Z3Z}5xx%ZMSY&FpShgE&i6 zp+4{APCjngB`tVPe-eEM{=040noY%@#?2cmuiMmN-rQC+i!>IKvF;&-wzuui{eF5N3D^=S z4XLL@iNR9W?^Xe?K}Ntm_~M!&6NUSg&MI-HuQmlgwk$LdUse5^d+lOifA;8jTm&fk)fUCCtsVB62M4jl z<4Hlt5MX2X%d8dStEA#S_EC^cANg8O(s zcm!j+*;y9pL5S5P7!n4FjFS6Yd56O8bl;jkla(Z=f9X&6Hbwn|E!J2zSu&BPn5k}`X*<_e|p-J(s5L$?DdF` z)on;XWSRY!_GhnGt@_hbv%b&P78a-DD58I5*jICf%wHDw)2QnjgT>nP4|UB8wU1p! z5RFx<>rj0*(b&_8)q+=>rc}36MEl!+dYtjt8#6}z&c)Z*{>vSwuT%P4dtX-K^G-o( z*CJ6QpJF?#eClu6#-IOMP-*Iu0`A)C8DJmLtHzz&$)_&eGi{U1r7_bKueNmCrLk#Zzz7r2K7&am>yc2*&M&oqFgI$DFZP9=Jq)6!HLG(A*g!nla&Sq^ZZF;0#=ZCa2M3?B6V;Q#oKQ}fo-z>h; Q9smFU07*qoM6N<$f&n1i?*IS* literal 0 HcmV?d00001 diff --git a/nav2_smac_planner/package.xml b/nav2_smac_planner/package.xml index 1c9516f16f..af2c8c6952 100644 --- a/nav2_smac_planner/package.xml +++ b/nav2_smac_planner/package.xml @@ -3,7 +3,7 @@ nav2_smac_planner 1.0.6 - Smac global planning plugin + Smac global planning plugin: A*, Hybrid-A*, State Lattice Steve Macenski Apache-2.0 @@ -23,7 +23,6 @@ nav2_costmap_2d nav2_core pluginlib - libceres-dev eigen3_cmake_module eigen ompl diff --git a/nav2_smac_planner/smac_plugin.xml b/nav2_smac_planner/smac_plugin.xml index c28cb32c7f..7b52bb24d7 100644 --- a/nav2_smac_planner/smac_plugin.xml +++ b/nav2_smac_planner/smac_plugin.xml @@ -1,5 +1,5 @@ - - SE2 version of the SMAC planner + + Hybrid-A* SMAC planner diff --git a/nav2_smac_planner/smac_plugin_2d.xml b/nav2_smac_planner/smac_plugin_2d.xml index aab22602e5..5bae687472 100644 --- a/nav2_smac_planner/smac_plugin_2d.xml +++ b/nav2_smac_planner/smac_plugin_2d.xml @@ -1,5 +1,5 @@ - 2D version of the SMAC Planner + 2D A* SMAC Planner diff --git a/nav2_smac_planner/src/a_star.cpp b/nav2_smac_planner/src/a_star.cpp index 4f2f3c35ed..cd09cc7943 100644 --- a/nav2_smac_planner/src/a_star.cpp +++ b/nav2_smac_planner/src/a_star.cpp @@ -48,8 +48,7 @@ AStarAlgorithm::AStarAlgorithm( _goal_coordinates(Coordinates()), _start(nullptr), _goal(nullptr), - _motion_model(motion_model), - _collision_checker(nullptr) + _motion_model(motion_model) { _graph.reserve(100000); } @@ -63,75 +62,59 @@ template void AStarAlgorithm::initialize( const bool & allow_unknown, int & max_iterations, - const int & max_on_approach_iterations) + const int & max_on_approach_iterations, + const float & lookup_table_size, + const unsigned int & dim_3_size) { _traverse_unknown = allow_unknown; _max_iterations = max_iterations; _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; } template<> -void AStarAlgorithm::createGraph( - const unsigned int & x_size, - const unsigned int & y_size, - const unsigned int & dim_3_size, - nav2_costmap_2d::Costmap2D * & costmap) +void AStarAlgorithm::initialize( + const bool & allow_unknown, + int & max_iterations, + const int & max_on_approach_iterations, + const float & /*lookup_table_size*/, + const unsigned int & dim_3_size) { + _traverse_unknown = allow_unknown; + _max_iterations = max_iterations; + _max_on_approach_iterations = max_on_approach_iterations; + if (dim_3_size != 1) { throw std::runtime_error("Node type Node2D cannot be given non-1 dim 3 quantization."); } - _costmap = costmap; - _dim3_size = dim_3_size; // 2D search MUST be 2D, not 3D or SE2. - clearGraph(); - - if (getSizeX() != x_size || getSizeY() != y_size) { - _x_size = x_size; - _y_size = y_size; - Node2D::initNeighborhood(_x_size, _motion_model); - } + _dim3_size = dim_3_size; } -template<> -void AStarAlgorithm::createGraph( - const unsigned int & x_size, - const unsigned int & y_size, - const unsigned int & dim_3_size, - nav2_costmap_2d::Costmap2D * & costmap) +template +void AStarAlgorithm::setCollisionChecker(GridCollisionChecker * collision_checker) { - _costmap = costmap; - _collision_checker = GridCollisionChecker(costmap); - _collision_checker.setFootprint(_footprint, _is_radius_footprint); + _collision_checker = collision_checker; + _costmap = collision_checker->getCostmap(); + unsigned int x_size = _costmap->getSizeInCellsX(); + unsigned int y_size = _costmap->getSizeInCellsY(); - _dim3_size = dim_3_size; - unsigned int index; clearGraph(); if (getSizeX() != x_size || getSizeY() != y_size) { _x_size = x_size; _y_size = y_size; - NodeSE2::initMotionModel(_motion_model, _x_size, _y_size, _dim3_size, _search_info); + NodeT::initMotionModel(_motion_model, _x_size, _y_size, _dim3_size, _search_info); } } template -void AStarAlgorithm::setFootprint(nav2_costmap_2d::Footprint footprint, bool use_radius) -{ - _footprint = footprint; - _is_radius_footprint = use_radius; -} - -template<> -typename AStarAlgorithm::NodePtr AStarAlgorithm::addToGraph( +typename AStarAlgorithm::NodePtr AStarAlgorithm::addToGraph( const unsigned int & index) { - return &(_graph.emplace(index, Node2D(_costmap->getCharMap()[index], index)).first->second); -} - -template<> -typename AStarAlgorithm::NodePtr AStarAlgorithm::addToGraph( - const unsigned int & index) -{ - return &(_graph.emplace(index, NodeSE2(index)).first->second); + // Emplace will only create a new object if it doesn't already exist. + // If an element exists, it will return the existing object, not create a new one. + return &(_graph.emplace(index, NodeT(index)).first->second); } template<> @@ -146,13 +129,13 @@ void AStarAlgorithm::setStart( _start = addToGraph(Node2D::getIndex(mx, my, getSizeX())); } -template<> -void AStarAlgorithm::setStart( +template +void AStarAlgorithm::setStart( const unsigned int & mx, const unsigned int & my, const unsigned int & dim_3) { - _start = addToGraph(NodeSE2::getIndex(mx, my, dim_3, getSizeX(), getSizeDim3())); + _start = addToGraph(NodeT::getIndex(mx, my, dim_3)); _start->setPose( Coordinates( static_cast(mx), @@ -174,24 +157,25 @@ void AStarAlgorithm::setGoal( _goal_coordinates = Node2D::Coordinates(mx, my); } -template<> -void AStarAlgorithm::setGoal( +template +void AStarAlgorithm::setGoal( const unsigned int & mx, const unsigned int & my, const unsigned int & dim_3) { - _goal = addToGraph(NodeSE2::getIndex(mx, my, dim_3, getSizeX(), getSizeDim3())); - _goal_coordinates = NodeSE2::Coordinates( + _goal = addToGraph(NodeT::getIndex(mx, my, dim_3)); + + typename NodeT::Coordinates goal_coords( static_cast(mx), static_cast(my), static_cast(dim_3)); - _goal->setPose(_goal_coordinates); - NodeSE2::computeWavefrontHeuristic( - _costmap, - static_cast(getStart()->pose.x), - static_cast(getStart()->pose.y), - mx, my); + if (!_search_info.cache_obstacle_heuristic || goal_coords != _goal_coordinates) { + NodeT::resetObstacleHeuristic(_costmap, mx, my); + } + + _goal_coordinates = goal_coords; + _goal->setPose(_goal_coordinates); } template @@ -227,7 +211,7 @@ bool AStarAlgorithm::createPath( CoordinateVector & path, int & iterations, const float & tolerance) { - _tolerance = tolerance * NodeT::neutral_cost; + _tolerance = tolerance; _best_heuristic_node = {std::numeric_limits::max(), 0}; clearQueue(); @@ -242,6 +226,7 @@ bool AStarAlgorithm::createPath( // Optimization: preallocate all variables NodePtr current_node = nullptr; NodePtr neighbor = nullptr; + NodePtr expansion_result = nullptr; float g_cost = 0.0; NodeVector neighbors; int approach_iterations = 0; @@ -277,13 +262,12 @@ bool AStarAlgorithm::createPath( // 2) Mark Nbest as visited current_node->visited(); - // 2.a) Use an analytic expansion (if available) to generate a path - // to the goal. - NodePtr result = tryAnalyticExpansion( - current_node, neighborGetter, analytic_iterations, - closest_distance); - if (result != nullptr) { - current_node = result; + // 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); + if (expansion_result != nullptr) { + current_node = expansion_result; } // 3) Check if we're at the goal, backtrace if required @@ -292,18 +276,14 @@ bool AStarAlgorithm::createPath( } else if (_best_heuristic_node.first < getToleranceHeuristic()) { // Optimization: Let us find when in tolerance and refine within reason approach_iterations++; - if (approach_iterations > getOnApproachMaxIterations() || - iterations + 1 == getMaxIterations()) - { - NodePtr node = &_graph.at(_best_heuristic_node.second); - return backtracePath(node, path); + if (approach_iterations >= getOnApproachMaxIterations()) { + return backtracePath(&_graph.at(_best_heuristic_node.second), path); } } // 4) Expand neighbors of Nbest not visited neighbors.clear(); - NodeT::getNeighbors( - current_node, neighborGetter, _collision_checker, _traverse_unknown, neighbors); + current_node->getNeighbors(neighborGetter, _collision_checker, _traverse_unknown, neighbors); for (neighbor_iterator = neighbors.begin(); neighbor_iterator != neighbors.end(); ++neighbor_iterator) @@ -311,15 +291,14 @@ bool AStarAlgorithm::createPath( neighbor = *neighbor_iterator; // 4.1) Compute the cost to go to this node - g_cost = getAccumulatedCost(current_node) + getTraversalCost(current_node, neighbor); + g_cost = current_node->getAccumulatedCost() + current_node->getTraversalCost(neighbor); // 4.2) If this is a lower cost than prior, we set this as the new cost and new approach - if (g_cost < getAccumulatedCost(neighbor)) { + if (g_cost < neighbor->getAccumulatedCost()) { neighbor->setAccumulatedCost(g_cost); neighbor->parent = current_node; - // 4.3) If not in queue or visited, add it, `getNeighbors()` handles - neighbor->queued(); + // 4.3) Add to queue with heuristic cost addNode(g_cost + getHeuristicCost(neighbor), neighbor); } } @@ -335,109 +314,7 @@ bool AStarAlgorithm::isGoal(NodePtr & node) } template<> -AStarAlgorithm::NodePtr AStarAlgorithm::getAnalyticPath( - const NodePtr & node, - const NodeGetter & node_getter) -{ - ompl::base::ScopedState<> from(node->motion_table.state_space), to( - node->motion_table.state_space), s(node->motion_table.state_space); - const NodeSE2::Coordinates & node_coords = node->pose; - from[0] = node_coords.x; - from[1] = node_coords.y; - from[2] = node_coords.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()); - NodePtr prev(node); - // 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); - - using PossibleNode = std::pair; - std::vector possible_nodes; - possible_nodes.reserve(num_intervals - 1); // We won't store this node or the goal - std::vector reals; - // Pre-allocate - unsigned int index = 0; - NodePtr next(nullptr); - float angle = 0.0; - Coordinates proposed_coordinates; - // Don't generate the first point because we are already there! - // And the last point is the goal, so ignore it too! - 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 >= node->motion_table.num_angle_quantization_float) { - angle -= node->motion_table.num_angle_quantization_float; - } - while (angle < 0.0) { - angle += node->motion_table.num_angle_quantization_float; - } - // Turn the pose into a node, and check if it is valid - index = NodeSE2::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); - prev = next; - } else { - next->setPose(initial_node_coords); - for (const auto & node_pose : possible_nodes) { - const auto & n = node_pose.first; - n->setPose(node_pose.second); - } - return NodePtr(nullptr); - } - } else { - // Abort - for (const auto & node_pose : possible_nodes) { - const auto & n = node_pose.first; - n->setPose(node_pose.second); - } - return NodePtr(nullptr); - } - } - // Legitimate path - set the parent relationships - poses already set - prev = node; - for (const auto & node_pose : possible_nodes) { - const auto & n = node_pose.first; - 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->visited(); - prev = n; - } - } - if (_goal != prev) { - _goal->parent = prev; - _goal->visited(); - } - return _goal; -} - -template -typename AStarAlgorithm::NodePtr AStarAlgorithm::getAnalyticPath( - const NodePtr & node, - const NodeGetter & node_getter) -{ - return NodePtr(nullptr); -} - -template<> -bool AStarAlgorithm::backtracePath(NodePtr & node, CoordinateVector & path) +bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path) { if (!node->parent) { return false; @@ -455,8 +332,8 @@ bool AStarAlgorithm::backtracePath(NodePtr & node, CoordinateVector & pa return path.size() > 1; } -template<> -bool AStarAlgorithm::backtracePath(NodePtr & node, CoordinateVector & path) +template +bool AStarAlgorithm::backtracePath(NodePtr node, CoordinateVector & path) { if (!node->parent) { return false; @@ -484,20 +361,23 @@ typename AStarAlgorithm::NodePtr & AStarAlgorithm::getGoal() return _goal; } -template -typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() +template<> +typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() { - NodeBasic node = _queue.top().second; + NodeBasic node = _queue.top().second; _queue.pop(); 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 + // 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; } @@ -505,44 +385,30 @@ typename AStarAlgorithm::NodePtr AStarAlgorithm::getNextNode() return node.graph_node_ptr; } -template -void AStarAlgorithm::addNode(const float cost, NodePtr & node) +template<> +void AStarAlgorithm::addNode(const float & cost, NodePtr & node) { - NodeBasic queued_node(node->getIndex()); + 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) +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; _queue.emplace(cost, queued_node); } -template -float AStarAlgorithm::getTraversalCost( - NodePtr & current_node, - NodePtr & new_node) -{ - return current_node->getTraversalCost(new_node); -} - -template -float & AStarAlgorithm::getAccumulatedCost(NodePtr & node) -{ - return node->getAccumulatedCost(); -} - template float AStarAlgorithm::getHeuristicCost(const NodePtr & node) { const Coordinates node_coords = NodeT::getCoords(node->getIndex(), getSizeX(), getSizeDim3()); float heuristic = NodeT::getHeuristicCost( - node_coords, _goal_coordinates); + node_coords, _goal_coordinates, _costmap); if (heuristic < _best_heuristic_node.first) { _best_heuristic_node = {heuristic, node->getIndex()}; @@ -562,8 +428,8 @@ template void AStarAlgorithm::clearGraph() { Graph g; - g.reserve(100000); std::swap(_graph, g); + _graph.reserve(100000); } template @@ -607,26 +473,24 @@ typename AStarAlgorithm::NodePtr AStarAlgorithm::tryAnalyticExpans const NodePtr & current_node, const NodeGetter & getter, int & analytic_iterations, int & closest_distance) { - if (_motion_model == MotionModel::DUBIN || _motion_model == MotionModel::REEDS_SHEPP) { - // This must be a NodeSE2 node if we are using these motion models - + // 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 = std::min( closest_distance, - static_cast(NodeT::getHeuristicCost( - node_coords, - _goal_coordinates) / NodeT::neutral_cost) - ); + 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)) - ); + 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); @@ -634,18 +498,172 @@ typename AStarAlgorithm::NodePtr AStarAlgorithm::tryAnalyticExpans // 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 + // Reset the counter and try the analytic path expansion analytic_iterations = desired_iterations; - return getAnalyticPath(current_node, getter); + 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; + possible_nodes.reserve(num_intervals - 1); // 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 >= node->motion_table.num_angle_quantization_float) { + angle -= node->motion_table.num_angle_quantization_float; + } + while (angle < 0.0) { + 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; +template class AStarAlgorithm; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/costmap_downsampler.cpp b/nav2_smac_planner/src/costmap_downsampler.cpp index c722523423..32bc05b36a 100644 --- a/nav2_smac_planner/src/costmap_downsampler.cpp +++ b/nav2_smac_planner/src/costmap_downsampler.cpp @@ -48,18 +48,24 @@ void CostmapDownsampler::on_configure( _downsampled_size_x, _downsampled_size_y, _downsampled_resolution, _costmap->getOriginX(), _costmap->getOriginY(), UNKNOWN); - _downsampled_costmap_pub = std::make_unique( - node, _downsampled_costmap.get(), global_frame, topic_name, false); + if (!node.expired()) { + _downsampled_costmap_pub = std::make_unique( + node, _downsampled_costmap.get(), global_frame, topic_name, false); + } } void CostmapDownsampler::on_activate() { - _downsampled_costmap_pub->on_activate(); + if (_downsampled_costmap_pub) { + _downsampled_costmap_pub->on_activate(); + } } void CostmapDownsampler::on_deactivate() { - _downsampled_costmap_pub->on_deactivate(); + if (_downsampled_costmap_pub) { + _downsampled_costmap_pub->on_deactivate(); + } } void CostmapDownsampler::on_cleanup() @@ -90,7 +96,9 @@ nav2_costmap_2d::Costmap2D * CostmapDownsampler::downsample( } } - _downsampled_costmap_pub->publishCostmap(); + if (_downsampled_costmap_pub) { + _downsampled_costmap_pub->publishCostmap(); + } return _downsampled_costmap.get(); } diff --git a/nav2_smac_planner/src/node_2d.cpp b/nav2_smac_planner/src/node_2d.cpp index cd8a223879..a9ed0abf58 100644 --- a/nav2_smac_planner/src/node_2d.cpp +++ b/nav2_smac_planner/src/node_2d.cpp @@ -23,11 +23,11 @@ namespace nav2_smac_planner // defining static member for all instance to share std::vector Node2D::_neighbors_grid_offsets; -double Node2D::neutral_cost = 50.0; +float Node2D::cost_travel_multiplier = 2.0; -Node2D::Node2D(unsigned char & cost_in, const unsigned int index) +Node2D::Node2D(const unsigned int index) : parent(nullptr), - _cell_cost(static_cast(cost_in)), + _cell_cost(std::numeric_limits::quiet_NaN()), _accumulated_cost(std::numeric_limits::max()), _index(index), _was_visited(false), @@ -40,10 +40,10 @@ Node2D::~Node2D() parent = nullptr; } -void Node2D::reset(const unsigned char & cost) +void Node2D::reset() { parent = nullptr; - _cell_cost = static_cast(cost); + _cell_cost = std::numeric_limits::quiet_NaN(); _accumulated_cost = std::numeric_limits::max(); _was_visited = false; _is_queued = false; @@ -51,54 +51,53 @@ void Node2D::reset(const unsigned char & cost) bool Node2D::isNodeValid( const bool & traverse_unknown, - GridCollisionChecker /*collision_checker*/) + GridCollisionChecker * collision_checker) { - // NOTE(stevemacenski): Right now, we do not check if the node has wrapped around - // the regular grid (e.g. your node is on the edge of the costmap and i+1 - // goes to the other side). This check would add compute time and my assertion is - // that if you do wrap around, the heuristic will be so high it'll be added far - // in the queue that it will never be called if a valid path exists. - // This is intentionally un-included to increase speed, but be aware. If this causes - // trouble, please file a ticket and we can address it then. - - auto & cost = this->getCost(); - - // occupied node - if (cost == OCCUPIED || cost == INSCRIBED) { - return false; - } - - // unknown node - if (cost == UNKNOWN && !traverse_unknown) { + if (collision_checker->inCollision(this->getIndex(), traverse_unknown)) { return false; } + _cell_cost = collision_checker->getCost(); return true; } float Node2D::getTraversalCost(const NodePtr & child) { - // cost to travel will be the cost of the cell's code + float normalized_cost = child->getCost() / 252.0; + const Coordinates A = getCoords(child->getIndex()); + const Coordinates B = getCoords(this->getIndex()); + const float & dx = A.x - B.x; + const float & dy = A.y - B.y; + static float sqrt_2 = sqrt(2); + + // If a diagonal move, travel cost is sqrt(2) not 1.0. + if ((dx * dx + dy * dy) > 1.05) { + return sqrt_2 + cost_travel_multiplier * normalized_cost; + } - // neutral_cost is neutral cost for cost just to travel anywhere (50) - // 0.8 is a scale factor to remap costs [0, 252] evenly from [50, 252] - return Node2D::neutral_cost + 0.8 * child->getCost(); + return 1.0 + cost_travel_multiplier * normalized_cost; } float Node2D::getHeuristicCost( const Coordinates & node_coords, - const Coordinates & goal_coordinates) + const Coordinates & goal_coordinates, + const nav2_costmap_2d::Costmap2D * /*costmap*/) { - return hypotf( - goal_coordinates.x - node_coords.x, - goal_coordinates.y - node_coords.y) * Node2D::neutral_cost; + // Using Moore distance as it more accurately represents the distances + // even a Van Neumann neighborhood robot can navigate. + return fabs(goal_coordinates.x - node_coords.x) + + fabs(goal_coordinates.y - node_coords.y); } -void Node2D::initNeighborhood( - const unsigned int & x_size_uint, - const MotionModel & neighborhood) +void Node2D::initMotionModel( + const MotionModel & neighborhood, + unsigned int & x_size_uint, + unsigned int & /*size_y*/, + unsigned int & /*num_angle_quantization*/, + SearchInfo & search_info) { int x_size = static_cast(x_size_uint); + cost_travel_multiplier = search_info.cost_penalty; switch (neighborhood) { case MotionModel::UNKNOWN: throw std::runtime_error("Unknown neighborhood type selected."); @@ -117,15 +116,14 @@ void Node2D::initNeighborhood( } void Node2D::getNeighbors( - NodePtr & node, std::function & NeighborGetter, - GridCollisionChecker collision_checker, + GridCollisionChecker * collision_checker, const bool & traverse_unknown, NodeVector & neighbors) { // NOTE(stevemacenski): Irritatingly, the order here matters. If you start in free // space and then expand 8-connected, the first set of neighbors will be all cost - // _neutral_cost. Then its expansion will all be 2 * _neutral_cost but now multiple + // 1.0. Then its expansion will all be 2 * 1.0 but now multiple // nodes are touching that node so the last cell to update the back pointer wins. // Thusly, the ordering ends with the cardinal directions for both sets such that // behavior is consistent in large free spaces between them. @@ -136,7 +134,7 @@ void Node2D::getNeighbors( // rather than a small inflation around the obstacles int index; NodePtr neighbor; - int node_i = node->getIndex(); + int node_i = this->getIndex(); for (unsigned int i = 0; i != _neighbors_grid_offsets.size(); ++i) { index = node_i + _neighbors_grid_offsets[i]; diff --git a/nav2_smac_planner/src/node_hybrid.cpp b/nav2_smac_planner/src/node_hybrid.cpp new file mode 100644 index 0000000000..059f9f5445 --- /dev/null +++ b/nav2_smac_planner/src/node_hybrid.cpp @@ -0,0 +1,648 @@ +// 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_hybrid.hpp" + +using namespace std::chrono; // NOLINT + +namespace nav2_smac_planner +{ + +// defining static member for all instance to share +LookupTable NodeHybrid::obstacle_heuristic_lookup_table; +std::queue NodeHybrid::obstacle_heuristic_queue; +double NodeHybrid::travel_distance_cost = sqrt(2); +HybridMotionTable NodeHybrid::motion_table; +float NodeHybrid::size_lookup = 25; +LookupTable NodeHybrid::dist_heuristic_lookup_table; +nav2_costmap_2d::Costmap2D * NodeHybrid::sampled_costmap = nullptr; +CostmapDownsampler NodeHybrid::downsampler; + +// 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. + +// http://planning.cs.uiuc.edu/node821.html +// Model for ackermann style vehicle with minimum radius restriction +void HybridMotionTable::initDubin( + unsigned int & size_x_in, + unsigned int & /*size_y_in*/, + unsigned int & num_angle_quantization_in, + SearchInfo & search_info) +{ + 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; + + // if nothing changed, no need to re-compute primitives + if (num_angle_quantization_in == num_angle_quantization && + min_turning_radius == search_info.minimum_turning_radius) + { + return; + } + + num_angle_quantization = num_angle_quantization_in; + num_angle_quantization_float = static_cast(num_angle_quantization); + min_turning_radius = search_info.minimum_turning_radius; + + // angle must meet 3 requirements: + // 1) be increment of quantized bin size + // 2) chord length must be greater than sqrt(2) to leave current cell + // 3) maximum curvature must be respected, represented by minimum turning angle + // Thusly: + // On circle of radius minimum turning angle, we need select motion primatives + // with chord length > sqrt(2) and be an increment of our bin size + // + // chord >= sqrt(2) >= 2 * R * sin (angle / 2); where angle / N = quantized bin size + // Thusly: angle <= 2.0 * asin(sqrt(2) / (2 * R)) + float angle = 2.0 * asin(sqrt(2.0) / (2 * min_turning_radius)); + // Now make sure angle is an increment of the quantized bin size + // And since its based on the minimum chord, we need to make sure its always larger + bin_size = + 2.0f * static_cast(M_PI) / static_cast(num_angle_quantization); + float increments; + if (angle < bin_size) { + increments = 1.0f; + } else { + // Search dimensions are clean multiples of quantization - this prevents + // paths with loops in them + increments = ceil(angle / bin_size); + } + angle = increments * bin_size; + + // find deflections + // If we make a right triangle out of the chord in circle of radius + // min turning angle, we can see that delta X = R * sin (angle) + float delta_x = min_turning_radius * sin(angle); + // Using that same right triangle, we can see that the complement + // to delta Y is R * cos (angle). If we subtract R, we get the actual value + float delta_y = min_turning_radius - (min_turning_radius * cos(angle)); + + projections.clear(); + projections.reserve(3); + projections.emplace_back(hypotf(delta_x, delta_y), 0.0, 0.0); // Forward + projections.emplace_back(delta_x, delta_y, increments); // Left + projections.emplace_back(delta_x, -delta_y, -increments); // Right + + // Create the correct OMPL state space + if (!state_space) { + state_space = std::make_unique(min_turning_radius); + } + + // Precompute projection deltas + delta_xs.resize(projections.size()); + delta_ys.resize(projections.size()); + trig_values.resize(num_angle_quantization); + + for (unsigned int i = 0; i != projections.size(); i++) { + delta_xs[i].resize(num_angle_quantization); + delta_ys[i].resize(num_angle_quantization); + + for (unsigned int j = 0; j != num_angle_quantization; j++) { + double cos_theta = cos(bin_size * j); + double sin_theta = sin(bin_size * j); + if (i == 0) { + // if first iteration, cache the trig values for later + trig_values[j] = {cos_theta, sin_theta}; + } + delta_xs[i][j] = projections[i]._x * cos_theta - projections[i]._y * sin_theta; + delta_ys[i][j] = projections[i]._x * sin_theta + projections[i]._y * cos_theta; + } + } +} + +// http://planning.cs.uiuc.edu/node822.html +// Same as Dubin model but now reverse is valid +// See notes in Dubin for explanation +void HybridMotionTable::initReedsShepp( + unsigned int & size_x_in, + unsigned int & /*size_y_in*/, + unsigned int & num_angle_quantization_in, + SearchInfo & search_info) +{ + 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; + + // if nothing changed, no need to re-compute primitives + if (num_angle_quantization_in == num_angle_quantization && + min_turning_radius == search_info.minimum_turning_radius) + { + return; + } + + num_angle_quantization = num_angle_quantization_in; + num_angle_quantization_float = static_cast(num_angle_quantization); + min_turning_radius = search_info.minimum_turning_radius; + + float angle = 2.0 * asin(sqrt(2.0) / (2 * min_turning_radius)); + bin_size = + 2.0f * static_cast(M_PI) / static_cast(num_angle_quantization); + float increments; + if (angle < bin_size) { + increments = 1.0f; + } else { + increments = ceil(angle / bin_size); + } + angle = increments * bin_size; + + float delta_x = min_turning_radius * sin(angle); + float delta_y = min_turning_radius - (min_turning_radius * cos(angle)); + + projections.clear(); + projections.reserve(6); + projections.emplace_back(hypotf(delta_x, delta_y), 0.0, 0.0); // Forward + projections.emplace_back(delta_x, delta_y, increments); // Forward + Left + projections.emplace_back(delta_x, -delta_y, -increments); // Forward + Right + projections.emplace_back(-hypotf(delta_x, delta_y), 0.0, 0.0); // Backward + projections.emplace_back(-delta_x, delta_y, -increments); // Backward + Left + projections.emplace_back(-delta_x, -delta_y, increments); // Backward + Right + + // Create the correct OMPL state space + if (!state_space) { + state_space = std::make_unique( + min_turning_radius); + } + + // Precompute projection deltas + delta_xs.resize(projections.size()); + delta_ys.resize(projections.size()); + trig_values.resize(num_angle_quantization); + + for (unsigned int i = 0; i != projections.size(); i++) { + delta_xs[i].resize(num_angle_quantization); + delta_ys[i].resize(num_angle_quantization); + + for (unsigned int j = 0; j != num_angle_quantization; j++) { + double cos_theta = cos(bin_size * j); + double sin_theta = sin(bin_size * j); + if (i == 0) { + // if first iteration, cache the trig values for later + trig_values[j] = {cos_theta, sin_theta}; + } + delta_xs[i][j] = projections[i]._x * cos_theta - projections[i]._y * sin_theta; + delta_ys[i][j] = projections[i]._x * sin_theta + projections[i]._y * cos_theta; + } + } +} + +MotionPoses HybridMotionTable::getProjections(const NodeHybrid * node) +{ + MotionPoses projection_list; + projection_list.reserve(projections.size()); + + for (unsigned int i = 0; i != projections.size(); i++) { + const MotionPose & motion_model = projections[i]; + + // normalize theta, I know its overkill, but I've been burned before... + const float & node_heading = node->pose.theta; + float new_heading = node_heading + motion_model._theta; + + if (new_heading >= num_angle_quantization_float) { + new_heading -= num_angle_quantization_float; + } + + if (new_heading < 0.0) { + new_heading += num_angle_quantization_float; + } + + projection_list.emplace_back( + delta_xs[i][node_heading] + node->pose.x, + delta_ys[i][node_heading] + node->pose.y, + new_heading); + } + + return projection_list; +} + +NodeHybrid::NodeHybrid(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), + _motion_primitive_index(std::numeric_limits::max()) +{ +} + +NodeHybrid::~NodeHybrid() +{ + parent = nullptr; +} + +void NodeHybrid::reset() +{ + parent = nullptr; + _cell_cost = std::numeric_limits::quiet_NaN(); + _accumulated_cost = std::numeric_limits::max(); + _was_visited = false; + _motion_primitive_index = std::numeric_limits::max(); + pose.x = 0.0f; + pose.y = 0.0f; + pose.theta = 0.0f; +} + +bool NodeHybrid::isNodeValid( + const bool & traverse_unknown, + GridCollisionChecker * collision_checker) +{ + 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 NodeHybrid::getTraversalCost(const NodePtr & child) +{ + 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 SE2 collision cost!"); + } + + // this is the first node + if (getMotionPrimitiveIndex() == std::numeric_limits::max()) { + 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; + + if (child->getMotionPrimitiveIndex() == 0 || child->getMotionPrimitiveIndex() == 3) { + // New motion is a straight motion, no additional costs to be applied + travel_cost = travel_cost_raw; + } else { + if (getMotionPrimitiveIndex() == child->getMotionPrimitiveIndex()) { + // Turning motion but keeps in same direction: encourages to commit to turning if starting it + travel_cost = travel_cost_raw * motion_table.non_straight_penalty; + } else { + // Turning motion and changing direction: penalizes wiggling + travel_cost = travel_cost_raw * + (motion_table.non_straight_penalty + motion_table.change_penalty); + } + } + + if (getMotionPrimitiveIndex() > 2) { + // reverse direction + travel_cost *= motion_table.reverse_penalty; + } + + return travel_cost; +} + +float NodeHybrid::getHeuristicCost( + const Coordinates & node_coords, + const Coordinates & goal_coords, + const nav2_costmap_2d::Costmap2D * /*costmap*/) +{ + const float obstacle_heuristic = getObstacleHeuristic(node_coords, goal_coords); + const float dist_heuristic = getDistanceHeuristic(node_coords, goal_coords, obstacle_heuristic); + return std::max(obstacle_heuristic, dist_heuristic); +} + +void NodeHybrid::initMotionModel( + const MotionModel & motion_model, + unsigned int & size_x, + unsigned int & size_y, + unsigned int & num_angle_quantization, + SearchInfo & search_info) +{ + // find the motion model selected + switch (motion_model) { + case MotionModel::DUBIN: + motion_table.initDubin(size_x, size_y, num_angle_quantization, search_info); + break; + case MotionModel::REEDS_SHEPP: + motion_table.initReedsShepp(size_x, size_y, num_angle_quantization, search_info); + break; + default: + throw std::runtime_error( + "Invalid motion model for Hybrid A*. Please select between" + " Dubin (Ackermann forward only)," + " Reeds-Shepp (Ackermann forward and back)."); + } + + travel_distance_cost = motion_table.projections[0]._x; +} + +void NodeHybrid::resetObstacleHeuristic( + nav2_costmap_2d::Costmap2D * costmap, + const unsigned int & goal_x, const unsigned int & goal_y) +{ + // Downsample costmap 2x to compute a sparse obstacle heuristic. This speeds up + // the planner considerably to search through 75% less cells with no detectable + // erosion of path quality after even modest smoothing. The error would be no more + // than 0.05 * normalized cost. Since this is just a search prior, there's no loss in generality + std::weak_ptr ptr; + downsampler.on_configure(ptr, "fake_frame", "fake_topic", costmap, 2.0); + downsampler.on_activate(); + sampled_costmap = downsampler.downsample(2.0); + + // Clear lookup table + unsigned int size = sampled_costmap->getSizeInCellsX() * sampled_costmap->getSizeInCellsY(); + if (obstacle_heuristic_lookup_table.size() == size) { + // must reset all values + std::fill( + obstacle_heuristic_lookup_table.begin(), + obstacle_heuristic_lookup_table.end(), 0.0); + } else { + unsigned int obstacle_size = obstacle_heuristic_lookup_table.size(); + obstacle_heuristic_lookup_table.resize(size, 0.0); + // must reset values for non-constructed indices + std::fill_n( + obstacle_heuristic_lookup_table.begin(), obstacle_size, 0.0); + } + + // Set initial goal point to queue from. Divided by 2 due to downsampled costmap. + std::queue q; + std::swap(obstacle_heuristic_queue, q); + obstacle_heuristic_queue.emplace( + ceil(goal_y / 2.0) * sampled_costmap->getSizeInCellsX() + ceil(goal_x / 2.0)); +} + +float NodeHybrid::getObstacleHeuristic( + const Coordinates & node_coords, + const Coordinates & goal_coords) +{ + // If already expanded, return the cost + unsigned int size_x = sampled_costmap->getSizeInCellsX(); + // Divided by 2 due to downsampled costmap. + const unsigned int start_index = ceil(node_coords.y / 2.0) * size_x + ceil(node_coords.x / 2.0); + const float & starting_cost = obstacle_heuristic_lookup_table[start_index]; + if (starting_cost > 0.0) { + // costs are doubled due to downsampling + return 2.0 * starting_cost; + } + + // If not, expand until it is included. This dynamic programming ensures that + // we only expand the MINIMUM spanning set of the costmap per planning request. + // Rather than naively expanding the entire (potentially massive) map for a limited + // path, we only expand to the extent required for the furthest expansion in the + // search-planning request that dynamically updates during search as needed. + const int size_x_int = static_cast(size_x); + const unsigned int size_y = sampled_costmap->getSizeInCellsY(); + const float sqrt_2 = sqrt(2); + unsigned int mx, my, mx_idx, my_idx; + unsigned int idx = 0, new_idx = 0; + float last_accumulated_cost = 0.0, travel_cost = 0.0; + float heuristic_cost = 0.0, current_accumulated_cost = 0.0; + float cost = 0.0, existing_cost = 0.0; + + const std::vector neighborhood = {1, -1, // left right + size_x_int, -size_x_int, // up down + size_x_int + 1, size_x_int - 1, // upper diagonals + -size_x_int + 1, -size_x_int - 1}; // lower diagonals + + while (!obstacle_heuristic_queue.empty()) { + // get next one + idx = obstacle_heuristic_queue.front(); + obstacle_heuristic_queue.pop(); + last_accumulated_cost = obstacle_heuristic_lookup_table[idx]; + + + if (idx == start_index) { + // costs are doubled due to downsampling + return 2.0 * last_accumulated_cost; + } + + my_idx = idx / size_x; + mx_idx = idx - (my_idx * size_x); + + // find neighbors + for (unsigned int i = 0; i != neighborhood.size(); i++) { + 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); + current_accumulated_cost = last_accumulated_cost + travel_cost; + + // if neighbor path is better and non-lethal, set new cost and add to queue + if (new_idx > 0 && new_idx < size_x * size_y && cost < INSCRIBED) { + my = new_idx / size_x; + mx = new_idx - (my * size_x); + + if (mx == 0 && mx_idx >= size_x - 1 || mx >= size_x - 1 && mx_idx == 0) { + continue; + } + if (my == 0 && my_idx >= size_y - 1 || my >= size_y - 1 && my_idx == 0) { + continue; + } + + existing_cost = obstacle_heuristic_lookup_table[new_idx]; + if (existing_cost == 0.0 || existing_cost > current_accumulated_cost) { + obstacle_heuristic_lookup_table[new_idx] = current_accumulated_cost; + obstacle_heuristic_queue.emplace(new_idx); + } + } + } + } + + // costs are doubled due to downsampling + return 2.0 * obstacle_heuristic_lookup_table[start_index]; +} + +float NodeHybrid::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) + + // 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(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 + 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 = dist_heuristic_lookup_table[index]; + } else if (obstacle_heuristic == 0.0) { + // If no obstacle heuristic value, must have some H to use + // In nominal situations, this should never be called. + 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 NodeHybrid::precomputeDistanceHeuristic( + const float & lookup_table_dim, + const MotionModel & motion_model, + const unsigned int & dim_3_size, + const SearchInfo & search_info) +{ + // Dubin or Reeds-Shepp shortest distances + if (motion_model == MotionModel::DUBIN) { + motion_table.state_space = std::make_unique( + search_info.minimum_turning_radius); + } else if (motion_model == MotionModel::REEDS_SHEPP) { + motion_table.state_space = std::make_unique( + search_info.minimum_turning_radius); + } else { + throw std::runtime_error( + "Node attempted to precompute distance heuristics " + "with invalid motion model!"); + } + + 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); + float angular_bin_size = 2 * M_PI / 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] = heading * angular_bin_size; + motion_heuristic = motion_table.state_space->distance(from(), to()); + dist_heuristic_lookup_table[index] = motion_heuristic; + index++; + } + } + } +} + +void NodeHybrid::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 = NodeHybrid::getIndex( + static_cast(motion_projections[i]._x), + static_cast(motion_projections[i]._y), + static_cast(motion_projections[i]._theta), + motion_table.size_x, motion_table.num_angle_quantization); + + if (NeighborGetter(index, neighbor) && !neighbor->wasVisited()) { + // 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_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); + } else { + neighbor->setPose(initial_node_coords); + } + } + } +} + +} // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/node_se2.cpp b/nav2_smac_planner/src/node_se2.cpp deleted file mode 100644 index 96ab084b8a..0000000000 --- a/nav2_smac_planner/src/node_se2.cpp +++ /dev/null @@ -1,462 +0,0 @@ -// 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 "ompl/base/ScopedState.h" -#include "ompl/base/spaces/DubinsStateSpace.h" -#include "ompl/base/spaces/ReedsSheppStateSpace.h" - -#include "nav2_smac_planner/node_se2.hpp" - -using namespace std::chrono; // NOLINT - -namespace nav2_smac_planner -{ - -// defining static member for all instance to share -std::vector NodeSE2::_wavefront_heuristic; -double NodeSE2::neutral_cost = sqrt(2); -MotionTable NodeSE2::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. - -// http://planning.cs.uiuc.edu/node821.html -// Model for ackermann style vehicle with minimum radius restriction -void MotionTable::initDubin( - unsigned int & size_x_in, - unsigned int & /*size_y_in*/, - unsigned int & num_angle_quantization_in, - SearchInfo & search_info) -{ - size_x = size_x_in; - num_angle_quantization = num_angle_quantization_in; - num_angle_quantization_float = static_cast(num_angle_quantization); - 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; - - // angle must meet 3 requirements: - // 1) be increment of quantized bin size - // 2) chord length must be greater than sqrt(2) to leave current cell - // 3) maximum curvature must be respected, represented by minimum turning angle - // Thusly: - // On circle of radius minimum turning angle, we need select motion primatives - // with chord length > sqrt(2) and be an increment of our bin size - // - // chord >= sqrt(2) >= 2 * R * sin (angle / 2); where angle / N = quantized bin size - // Thusly: angle <= 2.0 * asin(sqrt(2) / (2 * R)) - float angle = 2.0 * asin(sqrt(2.0) / (2 * search_info.minimum_turning_radius)); - // Now make sure angle is an increment of the quantized bin size - // And since its based on the minimum chord, we need to make sure its always larger - bin_size = - 2.0f * static_cast(M_PI) / static_cast(num_angle_quantization); - float increments; - if (angle < bin_size) { - increments = 1.0f; - } else { - // Search dimensions are clean multiples of quantization - this prevents - // paths with loops in them - increments = ceil(angle / bin_size); - } - angle = increments * bin_size; - - // find deflections - // If we make a right triangle out of the chord in circle of radius - // min turning angle, we can see that delta X = R * sin (angle) - float delta_x = search_info.minimum_turning_radius * sin(angle); - // Using that same right triangle, we can see that the complement - // to delta Y is R * cos (angle). If we subtract R, we get the actual value - float delta_y = search_info.minimum_turning_radius - - (search_info.minimum_turning_radius * cos(angle)); - - projections.clear(); - projections.reserve(3); - projections.emplace_back(hypotf(delta_x, delta_y), 0.0, 0.0); // Forward - projections.emplace_back(delta_x, delta_y, increments); // Left - projections.emplace_back(delta_x, -delta_y, -increments); // Right - - // Create the correct OMPL state space - state_space = std::make_unique(search_info.minimum_turning_radius); - - // Precompute projection deltas - delta_xs.resize(projections.size()); - delta_ys.resize(projections.size()); - - for (unsigned int i = 0; i != projections.size(); i++) { - delta_xs[i].resize(num_angle_quantization); - delta_ys[i].resize(num_angle_quantization); - - for (unsigned int j = 0; j != num_angle_quantization; j++) { - double cos_theta = cos(bin_size * j); - double sin_theta = sin(bin_size * j); - delta_xs[i][j] = projections[i]._x * cos_theta - projections[i]._y * sin_theta; - delta_ys[i][j] = projections[i]._x * sin_theta + projections[i]._y * cos_theta; - } - } -} - -// http://planning.cs.uiuc.edu/node822.html -// Same as Dubin model but now reverse is valid -// See notes in Dubin for explanation -void MotionTable::initReedsShepp( - unsigned int & size_x_in, - unsigned int & /*size_y_in*/, - unsigned int & num_angle_quantization_in, - SearchInfo & search_info) -{ - size_x = size_x_in; - num_angle_quantization = num_angle_quantization_in; - num_angle_quantization_float = static_cast(num_angle_quantization); - 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; - - float angle = 2.0 * asin(sqrt(2.0) / (2 * search_info.minimum_turning_radius)); - bin_size = - 2.0f * static_cast(M_PI) / static_cast(num_angle_quantization); - float increments; - if (angle < bin_size) { - increments = 1.0f; - } else { - increments = ceil(angle / bin_size); - } - angle = increments * bin_size; - - float delta_x = search_info.minimum_turning_radius * sin(angle); - float delta_y = search_info.minimum_turning_radius - - (search_info.minimum_turning_radius * cos(angle)); - - projections.clear(); - projections.reserve(6); - projections.emplace_back(hypotf(delta_x, delta_y), 0.0, 0.0); // Forward - projections.emplace_back(delta_x, delta_y, increments); // Forward + Left - projections.emplace_back(delta_x, -delta_y, -increments); // Forward + Right - projections.emplace_back(-hypotf(delta_x, delta_y), 0.0, 0.0); // Backward - projections.emplace_back(-delta_x, delta_y, -increments); // Backward + Left - projections.emplace_back(-delta_x, -delta_y, increments); // Backward + Right - - // Create the correct OMPL state space - state_space = std::make_unique( - search_info.minimum_turning_radius); - - // Precompute projection deltas - delta_xs.resize(projections.size()); - delta_ys.resize(projections.size()); - - for (unsigned int i = 0; i != projections.size(); i++) { - delta_xs[i].resize(num_angle_quantization); - delta_ys[i].resize(num_angle_quantization); - - for (unsigned int j = 0; j != num_angle_quantization; j++) { - double cos_theta = cos(bin_size * j); - double sin_theta = sin(bin_size * j); - delta_xs[i][j] = projections[i]._x * cos_theta - projections[i]._y * sin_theta; - delta_ys[i][j] = projections[i]._x * sin_theta + projections[i]._y * cos_theta; - } - } -} - -MotionPoses MotionTable::getProjections(const NodeSE2 * node) -{ - MotionPoses projection_list; - for (unsigned int i = 0; i != projections.size(); i++) { - projection_list.push_back(getProjection(node, i)); - } - - return projection_list; -} - -MotionPose MotionTable::getProjection(const NodeSE2 * node, const unsigned int & motion_index) -{ - const MotionPose & motion_model = projections[motion_index]; - - // normalize theta, I know its overkill, but I've been burned before... - const float & node_heading = node->pose.theta; - float new_heading = node_heading + motion_model._theta; - - while (new_heading >= num_angle_quantization_float) { - new_heading -= num_angle_quantization_float; - } - while (new_heading < 0.0) { - new_heading += num_angle_quantization_float; - } - - return MotionPose( - delta_xs[motion_index][node_heading] + node->pose.x, - delta_ys[motion_index][node_heading] + node->pose.y, - new_heading); -} - -NodeSE2::NodeSE2(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), - _is_queued(false), - _motion_primitive_index(std::numeric_limits::max()) -{ -} - -NodeSE2::~NodeSE2() -{ - parent = nullptr; -} - -void NodeSE2::reset() -{ - parent = nullptr; - _cell_cost = std::numeric_limits::quiet_NaN(); - _accumulated_cost = std::numeric_limits::max(); - _was_visited = false; - _is_queued = false; - _motion_primitive_index = std::numeric_limits::max(); - pose.x = 0.0f; - pose.y = 0.0f; - pose.theta = 0.0f; -} - -bool NodeSE2::isNodeValid(const bool & traverse_unknown, GridCollisionChecker collision_checker) -{ - 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 NodeSE2::getTraversalCost(const NodePtr & child) -{ - 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 SE2 collision cost!"); - } - - // this is the first node - if (getMotionPrimitiveIndex() == std::numeric_limits::max()) { - return NodeSE2::neutral_cost; - } - - float travel_cost = 0.0; - float travel_cost_raw = NodeSE2::neutral_cost + motion_table.cost_penalty * normalized_cost; - - if (child->getMotionPrimitiveIndex() == 0 || child->getMotionPrimitiveIndex() == 3) { - // straight motion, no additional costs to be applied - travel_cost = travel_cost_raw; - } else { - if (getMotionPrimitiveIndex() == child->getMotionPrimitiveIndex()) { - // Turning motion but keeps in same direction: encourages to commit to turning if starting it - travel_cost = travel_cost_raw * motion_table.non_straight_penalty; - } else { - // Turning motion and changing direction: penalizes wiggling - travel_cost = travel_cost_raw * motion_table.change_penalty; - travel_cost += travel_cost_raw * motion_table.non_straight_penalty; - } - } - - if (getMotionPrimitiveIndex() > 2) { - // reverse direction - travel_cost *= motion_table.reverse_penalty; - } - - return travel_cost; -} - -float NodeSE2::getHeuristicCost( - const Coordinates & node_coords, - const Coordinates & goal_coords) -{ - // Dubin or Reeds-Shepp shortest distances - // Create OMPL states for checking - ompl::base::ScopedState<> from(motion_table.state_space), to(motion_table.state_space); - from[0] = node_coords.x; - from[1] = node_coords.y; - from[2] = node_coords.theta * motion_table.bin_size; - to[0] = goal_coords.x; - to[1] = goal_coords.y; - to[2] = goal_coords.theta * motion_table.bin_size; - - const float motion_heuristic = motion_table.state_space->distance(from(), to()); - - const unsigned int & wavefront_idx = static_cast(node_coords.y) * - motion_table.size_x + static_cast(node_coords.x); - const unsigned int & wavefront_value = _wavefront_heuristic[wavefront_idx]; - - // if lethal or didn't visit, use the motion heuristic instead. - if (wavefront_value == 0) { - return NodeSE2::neutral_cost * motion_heuristic; - } - - // -2 because wavefront starts at 2 - const float wavefront_heuristic = static_cast(wavefront_value - 2); - - return NodeSE2::neutral_cost * std::max(wavefront_heuristic, motion_heuristic); -} - -void NodeSE2::initMotionModel( - const MotionModel & motion_model, - unsigned int & size_x, - unsigned int & size_y, - unsigned int & num_angle_quantization, - SearchInfo & search_info) -{ - // find the motion model selected - switch (motion_model) { - case MotionModel::DUBIN: - motion_table.initDubin(size_x, size_y, num_angle_quantization, search_info); - break; - case MotionModel::REEDS_SHEPP: - motion_table.initReedsShepp(size_x, size_y, num_angle_quantization, search_info); - break; - default: - throw std::runtime_error( - "Invalid motion model for SE2 node. Please select between" - " Dubin (Ackermann forward only)," - " Reeds-Shepp (Ackermann forward and back)."); - } -} - -void NodeSE2::computeWavefrontHeuristic( - nav2_costmap_2d::Costmap2D * & costmap, - const unsigned int & start_x, const unsigned int & start_y, - const unsigned int & goal_x, const unsigned int & goal_y) -{ - unsigned int size = costmap->getSizeInCellsX() * costmap->getSizeInCellsY(); - if (_wavefront_heuristic.size() == size) { - // must reset all values - for (unsigned int i = 0; i != _wavefront_heuristic.size(); i++) { - _wavefront_heuristic[i] = 0; - } - } else { - unsigned int wavefront_size = _wavefront_heuristic.size(); - _wavefront_heuristic.resize(size, 0); - // must reset values for non-constructed indices - for (unsigned int i = 0; i != wavefront_size; i++) { - _wavefront_heuristic[i] = 0; - } - } - - const unsigned int & size_x = motion_table.size_x; - const int size_x_int = static_cast(size_x); - const unsigned int size_y = costmap->getSizeInCellsY(); - const unsigned int goal_index = goal_y * size_x + goal_x; - const unsigned int start_index = start_y * size_x + start_x; - unsigned int mx, my, mx_idx, my_idx; - - std::queue q; - q.emplace(goal_index); - - unsigned int idx = goal_index; - _wavefront_heuristic[idx] = 2; - - static const std::vector neighborhood = {1, -1, // left right - size_x_int, -size_x_int, // up down - size_x_int + 1, size_x_int - 1, // upper diagonals - -size_x_int + 1, -size_x_int - 1}; // lower diagonals - - while (!q.empty() || idx == start_index) { - // get next one - idx = q.front(); - q.pop(); - - my_idx = idx / size_x; - mx_idx = idx - (my_idx * size_x); - - // find neighbors - for (unsigned int i = 0; i != neighborhood.size(); i++) { - unsigned int new_idx = static_cast(static_cast(idx) + neighborhood[i]); - unsigned int last_wave_cost = _wavefront_heuristic[idx]; - - // if neighbor is unvisited and non-lethal, set N and add to queue - if (new_idx > 0 && new_idx < size_x * size_y && - _wavefront_heuristic[new_idx] == 0 && - static_cast(costmap->getCost(idx)) < INSCRIBED) - { - my = new_idx / size_x; - mx = new_idx - (my * size_x); - - if (mx == 0 && mx_idx >= size_x - 1 || mx >= size_x - 1 && mx_idx == 0) { - continue; - } - if (my == 0 && my_idx >= size_y - 1 || my >= size_y - 1 && my_idx == 0) { - continue; - } - - _wavefront_heuristic[new_idx] = last_wave_cost + 1; - q.emplace(idx + neighborhood[i]); - } - } - } -} - -void NodeSE2::getNeighbors( - const NodePtr & node, - 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(node); - - for (unsigned int i = 0; i != motion_projections.size(); i++) { - index = NodeSE2::getIndex( - static_cast(motion_projections[i]._x), - static_cast(motion_projections[i]._y), - static_cast(motion_projections[i]._theta), - motion_table.size_x, motion_table.num_angle_quantization); - - if (NeighborGetter(index, neighbor) && !neighbor->wasVisited()) { - // 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_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); - } else { - neighbor->setPose(initial_node_coords); - } - } - } -} - -} // 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 16da85f15e..dfd295bcdf 100644 --- a/nav2_smac_planner/src/smac_planner_2d.cpp +++ b/nav2_smac_planner/src/smac_planner_2d.cpp @@ -28,6 +28,7 @@ using namespace std::chrono; // NOLINT SmacPlanner2D::SmacPlanner2D() : _a_star(nullptr), + _collision_checker(nullptr, 1), _smoother(nullptr), _costmap(nullptr), _costmap_downsampler(nullptr) @@ -56,8 +57,7 @@ void SmacPlanner2D::configure( bool allow_unknown; int max_iterations; int max_on_approach_iterations; - bool smooth_path; - double minimum_turning_radius; + SearchInfo search_info; std::string motion_model_for_search; // General planner params @@ -70,22 +70,19 @@ void SmacPlanner2D::configure( 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 + ".cost_travel_multiplier", rclcpp::ParameterValue(2.0)); + node->get_parameter(name + ".cost_travel_multiplier", search_info.cost_penalty); 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(-1)); + node, name + ".max_iterations", rclcpp::ParameterValue(1000000)); node->get_parameter(name + ".max_iterations", max_iterations); nav2_util::declare_parameter_if_not_declared( node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000)); node->get_parameter(name + ".max_on_approach_iterations", max_on_approach_iterations); - nav2_util::declare_parameter_if_not_declared( - node, name + ".smooth_path", rclcpp::ParameterValue(false)); - node->get_parameter(name + ".smooth_path", smooth_path); - nav2_util::declare_parameter_if_not_declared( - node, name + ".minimum_turning_radius", rclcpp::ParameterValue(0.2)); - node->get_parameter(name + ".minimum_turning_radius", minimum_turning_radius); nav2_util::declare_parameter_if_not_declared( node, name + ".max_planning_time", rclcpp::ParameterValue(1.0)); @@ -117,20 +114,29 @@ void SmacPlanner2D::configure( max_iterations = std::numeric_limits::max(); } - _a_star = std::make_unique>(motion_model, SearchInfo()); + // Initialize collision checker + _collision_checker = GridCollisionChecker(_costmap, 1 /*for 2D, most be 1*/); + _collision_checker.setFootprint( + costmap_ros->getRobotFootprint(), + true /*for 2D, most use radius*/, + 0.0 /*for 2D cost at inscribed isn't relevent*/); + + // Initialize A* template + _a_star = std::make_unique>(motion_model, search_info); _a_star->initialize( allow_unknown, max_iterations, - max_on_approach_iterations); - - if (smooth_path) { - _smoother = std::make_unique(); - _optimizer_params.get(node.get(), name); - _smoother_params.get(node.get(), name); - _smoother_params.max_curvature = 1.0f / minimum_turning_radius; - _smoother->initialize(_optimizer_params); - } + max_on_approach_iterations, + 0.0 /*unused for 2D*/, + 1.0 /*unused for 2D*/); + + // Initialize path smoother + SmootherParams params; + params.get(node, name); + _smoother = std::make_unique(params); + _smoother->initialize(1e-50 /*No valid minimum turning radius for 2D*/); + // Initialize costmap downsampler if (_downsample_costmap && _downsampling_factor > 1) { std::string topic_name = "downsampled_costmap"; _costmap_downsampler = std::make_unique(); @@ -195,14 +201,11 @@ nav_msgs::msg::Path SmacPlanner2D::createPlan( nav2_costmap_2d::Costmap2D * costmap = _costmap; if (_costmap_downsampler) { costmap = _costmap_downsampler->downsample(_downsampling_factor); + _collision_checker.setCostmap(costmap); } - // Set Costmap - _a_star->createGraph( - costmap->getSizeInCellsX(), - costmap->getSizeInCellsY(), - 1, - costmap); + // Set collision checker and costmap information + _a_star->setCollisionChecker(&_collision_checker); // Set starting point unsigned int mx, my; @@ -252,21 +255,10 @@ nav_msgs::msg::Path SmacPlanner2D::createPlan( return plan; } - // Convert to world coordinates and downsample path for smoothing if necesssary - // We're going to downsample by 4x to give terms room to move. - const int downsample_ratio = 4; - std::vector path_world; - path_world.reserve(_smoother ? path.size() / downsample_ratio : path.size()); - plan.poses.reserve(_smoother ? path.size() / downsample_ratio : path.size()); - + // Convert to world coordinates + plan.poses.reserve(path.size()); for (int i = path.size() - 1; i >= 0; --i) { - if (_smoother && i % downsample_ratio != 0) { - continue; - } - - path_world.push_back(getWorldCoords(path[i].x, path[i].y, costmap)); - pose.pose.position.x = path_world.back().x(); - pose.pose.position.y = path_world.back().y(); + pose.pose = getWorldCoords(path[i].x, path[i].y, costmap); plan.poses.push_back(pose); } @@ -275,67 +267,24 @@ nav_msgs::msg::Path SmacPlanner2D::createPlan( _raw_plan_publisher->publish(plan); } - // If not smoothing or too short to smooth, return path - if (!_smoother || path_world.size() < 4) { -#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; -#endif - return 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()); - _smoother_params.max_time = std::min(time_remaining, _optimizer_params.max_time); - - // Smooth plan - if (!_smoother->smooth(path_world, costmap, _smoother_params)) { - RCLCPP_WARN( - _logger, - "%s: failed to smooth plan, Ceres could not find a usable solution to optimize.", - _name.c_str()); - return plan; - } - removeHook(path_world); +#ifdef BENCHMARK_TESTING + std::cout << "It took " << time_span.count() * 1000 << + " milliseconds with " << num_iterations << " iterations." << std::endl; +#endif - // populate final path - for (uint i = 0; i != path_world.size(); i++) { - pose.pose.position.x = path_world[i][0]; - pose.pose.position.y = path_world[i][1]; - plan.poses[i] = pose; + // Smooth plan + if (plan.poses.size() > 6) { + _smoother->smooth(plan, costmap, time_remaining); } return plan; } -void SmacPlanner2D::removeHook(std::vector & path) -{ - // Removes the end "hooking" since goal is locked in place - Eigen::Vector2d interpolated_second_to_last_point; - interpolated_second_to_last_point = (path.end()[-3] + path.end()[-1]) / 2.0; - if ( - squaredDistance(path.end()[-2], path.end()[-1]) > - squaredDistance(interpolated_second_to_last_point, path.end()[-1])) - { - path.end()[-2] = interpolated_second_to_last_point; - } -} - -Eigen::Vector2d SmacPlanner2D::getWorldCoords( - const float & mx, const float & my, const nav2_costmap_2d::Costmap2D * costmap) -{ - float world_x = - static_cast(costmap->getOriginX()) + (mx + 0.5) * costmap->getResolution(); - float world_y = - static_cast(costmap->getOriginY()) + (my + 0.5) * costmap->getResolution(); - return Eigen::Vector2d(world_x, world_y); -} - } // namespace nav2_smac_planner #include "pluginlib/class_list_macros.hpp" diff --git a/nav2_smac_planner/src/smac_planner.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp similarity index 62% rename from nav2_smac_planner/src/smac_planner.cpp rename to nav2_smac_planner/src/smac_planner_hybrid.cpp index 55b4dc15cb..1581bfbedc 100644 --- a/nav2_smac_planner/src/smac_planner.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -19,7 +19,7 @@ #include #include "Eigen/Core" -#include "nav2_smac_planner/smac_planner.hpp" +#include "nav2_smac_planner/smac_planner_hybrid.hpp" // #define BENCHMARK_TESTING @@ -28,22 +28,23 @@ namespace nav2_smac_planner using namespace std::chrono; // NOLINT -SmacPlanner::SmacPlanner() +SmacPlannerHybrid::SmacPlannerHybrid() : _a_star(nullptr), + _collision_checker(nullptr, 1), _smoother(nullptr), _costmap(nullptr), _costmap_downsampler(nullptr) { } -SmacPlanner::~SmacPlanner() +SmacPlannerHybrid::~SmacPlannerHybrid() { RCLCPP_INFO( - _logger, "Destroying plugin %s of type SmacPlanner", + _logger, "Destroying plugin %s of type SmacPlannerHybrid", _name.c_str()); } -void SmacPlanner::configure( +void SmacPlannerHybrid::configure( const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr/*tf*/, std::shared_ptr costmap_ros) @@ -57,16 +58,12 @@ void SmacPlanner::configure( bool allow_unknown; int max_iterations; - int max_on_approach_iterations = std::numeric_limits::max(); int angle_quantizations; + double lookup_table_size; SearchInfo search_info; - bool smooth_path; std::string motion_model_for_search; // General planner params - nav2_util::declare_parameter_if_not_declared( - 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(false)); node->get_parameter(name + ".downsample_costmap", _downsample_costmap); @@ -84,35 +81,37 @@ void SmacPlanner::configure( 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(-1)); + node, name + ".max_iterations", rclcpp::ParameterValue(1000000)); node->get_parameter(name + ".max_iterations", max_iterations); - nav2_util::declare_parameter_if_not_declared( - node, name + ".smooth_path", rclcpp::ParameterValue(false)); - node->get_parameter(name + ".smooth_path", smooth_path); nav2_util::declare_parameter_if_not_declared( - node, name + ".minimum_turning_radius", rclcpp::ParameterValue(0.2)); + node, name + ".minimum_turning_radius", rclcpp::ParameterValue(0.4)); node->get_parameter(name + ".minimum_turning_radius", search_info.minimum_turning_radius); - + 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); 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.5)); + 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.05)); + 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.2)); + 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(2.0)); + 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); nav2_util::declare_parameter_if_not_declared( node, name + ".motion_model_for_search", rclcpp::ParameterValue(std::string("DUBIN"))); @@ -122,17 +121,10 @@ void SmacPlanner::configure( RCLCPP_WARN( _logger, "Unable to get MotionModel search type. Given '%s', " - "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP.", + "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP, STATE_LATTICE.", motion_model_for_search.c_str()); } - if (max_on_approach_iterations <= 0) { - RCLCPP_INFO( - _logger, "On approach iteration selected as <= 0, " - "disabling tolerance and on approach iterations."); - max_on_approach_iterations = std::numeric_limits::max(); - } - if (max_iterations <= 0) { RCLCPP_INFO( _logger, "maximum iteration selected as <= 0, " @@ -144,22 +136,45 @@ void SmacPlanner::configure( const double minimum_turning_radius_global_coords = search_info.minimum_turning_radius; search_info.minimum_turning_radius = search_info.minimum_turning_radius / (_costmap->getResolution() * _downsampling_factor); + float lookup_table_dim = + 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)); - _a_star = std::make_unique>(motion_model, search_info); + // 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 + _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, - max_on_approach_iterations); - _a_star->setFootprint(costmap_ros->getRobotFootprint(), costmap_ros->getUseRadius()); - - if (smooth_path) { - _smoother = std::make_unique(); - _optimizer_params.get(node.get(), name); - _smoother_params.get(node.get(), name); - _smoother_params.max_curvature = 1.0f / minimum_turning_radius_global_coords; - _smoother->initialize(_optimizer_params); - } + 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(minimum_turning_radius_global_coords); + // Initialize costmap downsampler if (_downsample_costmap && _downsampling_factor > 1) { std::string topic_name = "downsampled_costmap"; _costmap_downsampler = std::make_unique(); @@ -170,18 +185,17 @@ void SmacPlanner::configure( _raw_plan_publisher = node->create_publisher("unsmoothed_plan", 1); RCLCPP_INFO( - _logger, "Configured plugin %s of type SmacPlanner with " - "tolerance %.2f, maximum iterations %i, " - "max on approach iterations %i, and %s. Using motion model: %s.", - _name.c_str(), _tolerance, max_iterations, max_on_approach_iterations, + _logger, "Configured plugin %s of type SmacPlannerHybrid with " + "maximum iterations %i, and %s. Using motion model: %s.", + _name.c_str(), max_iterations, allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal", toString(motion_model).c_str()); } -void SmacPlanner::activate() +void SmacPlannerHybrid::activate() { RCLCPP_INFO( - _logger, "Activating plugin %s of type SmacPlanner", + _logger, "Activating plugin %s of type SmacPlannerHybrid", _name.c_str()); _raw_plan_publisher->on_activate(); if (_costmap_downsampler) { @@ -189,10 +203,10 @@ void SmacPlanner::activate() } } -void SmacPlanner::deactivate() +void SmacPlannerHybrid::deactivate() { RCLCPP_INFO( - _logger, "Deactivating plugin %s of type SmacPlanner", + _logger, "Deactivating plugin %s of type SmacPlannerHybrid", _name.c_str()); _raw_plan_publisher->on_deactivate(); if (_costmap_downsampler) { @@ -200,10 +214,10 @@ void SmacPlanner::deactivate() } } -void SmacPlanner::cleanup() +void SmacPlannerHybrid::cleanup() { RCLCPP_INFO( - _logger, "Cleaning up plugin %s of type SmacPlanner", + _logger, "Cleaning up plugin %s of type SmacPlannerHybrid", _name.c_str()); _a_star.reset(); _smoother.reset(); @@ -212,7 +226,7 @@ void SmacPlanner::cleanup() _raw_plan_publisher.reset(); } -nav_msgs::msg::Path SmacPlanner::createPlan( +nav_msgs::msg::Path SmacPlannerHybrid::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal) { @@ -224,14 +238,11 @@ nav_msgs::msg::Path SmacPlanner::createPlan( nav2_costmap_2d::Costmap2D * costmap = _costmap; if (_costmap_downsampler) { costmap = _costmap_downsampler->downsample(_downsampling_factor); + _collision_checker.setCostmap(costmap); } - // Set Costmap - _a_star->createGraph( - costmap->getSizeInCellsX(), - costmap->getSizeInCellsY(), - _angle_quantizations, - costmap); + // Set collision checker and costmap information + _a_star->setCollisionChecker(&_collision_checker); // Set starting point, in A* bin search coordinates unsigned int mx, my; @@ -265,13 +276,11 @@ nav_msgs::msg::Path SmacPlanner::createPlan( pose.pose.orientation.w = 1.0; // Compute plan - NodeSE2::CoordinateVector path; + NodeHybrid::CoordinateVector path; int num_iterations = 0; std::string error; try { - if (!_a_star->createPath( - path, num_iterations, _tolerance / static_cast(costmap->getResolution()))) - { + if (!_a_star->createPath(path, num_iterations, 0.0)) { if (num_iterations < _a_star->getMaxIterations()) { error = std::string("no valid path found"); } else { @@ -291,18 +300,11 @@ nav_msgs::msg::Path SmacPlanner::createPlan( return plan; } - // Convert to world coordinates and downsample path for smoothing if necesssary - // We're going to downsample by 4x to give terms room to move. - const int downsample_ratio = 4; - std::vector path_world; - path_world.reserve(path.size()); + // Convert to world coordinates plan.poses.reserve(path.size()); - for (int i = path.size() - 1; i >= 0; --i) { - path_world.push_back(getWorldCoords(path[i].x, path[i].y, costmap)); - pose.pose.position.x = path_world.back().x(); - pose.pose.position.y = path_world.back().y(); - pose.pose.orientation = getWorldOrientation(path[i].theta); + 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); } @@ -311,78 +313,32 @@ nav_msgs::msg::Path SmacPlanner::createPlan( _raw_plan_publisher->publish(plan); } - // If not smoothing or too short to smooth, return path - if (!_smoother || path_world.size() < 4) { -#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; -#endif - return 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()); - _smoother_params.max_time = std::min(time_remaining, _optimizer_params.max_time); + +#ifdef BENCHMARK_TESTING + std::cout << "It took " << time_span.count() * 1000 << + " milliseconds with " << num_iterations << " iterations." << std::endl; +#endif // Smooth plan - if (!_smoother->smooth(path_world, costmap, _smoother_params)) { - RCLCPP_WARN( - _logger, - "%s: failed to smooth plan, Ceres could not find a usable solution to optimize.", - _name.c_str()); - return plan; + if (num_iterations > 1 && plan.poses.size() > 6) { + _smoother->smooth(plan, costmap, time_remaining); } - removeHook(path_world); - - // populate final path - // TODO(stevemacenski): set orientation to tangent of path - for (uint i = 0; i != path_world.size(); i++) { - pose.pose.position.x = path_world[i][0]; - pose.pose.position.y = path_world[i][1]; - plan.poses[i] = pose; - } +#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; } -void SmacPlanner::removeHook(std::vector & path) -{ - // Removes the end "hooking" since goal is locked in place - Eigen::Vector2d interpolated_second_to_last_point; - interpolated_second_to_last_point = (path.end()[-3] + path.end()[-1]) / 2.0; - if ( - squaredDistance(path.end()[-2], path.end()[-1]) > - squaredDistance(interpolated_second_to_last_point, path.end()[-1])) - { - path.end()[-2] = interpolated_second_to_last_point; - } -} - -Eigen::Vector2d SmacPlanner::getWorldCoords( - const float & mx, const float & my, const nav2_costmap_2d::Costmap2D * costmap) -{ - // mx, my are in continuous grid coordinates, must convert to world coordinates - double world_x = - static_cast(costmap->getOriginX()) + (mx + 0.5) * costmap->getResolution(); - double world_y = - static_cast(costmap->getOriginY()) + (my + 0.5) * costmap->getResolution(); - return Eigen::Vector2d(world_x, world_y); -} - -geometry_msgs::msg::Quaternion SmacPlanner::getWorldOrientation(const float & theta) -{ - // theta is in continuous bin coordinates, must convert to world orientation - tf2::Quaternion q; - q.setEuler(0.0, 0.0, theta * static_cast(_angle_bin_size)); - return tf2::toMsg(q); -} - } // namespace nav2_smac_planner #include "pluginlib/class_list_macros.hpp" -PLUGINLIB_EXPORT_CLASS(nav2_smac_planner::SmacPlanner, nav2_core::GlobalPlanner) +PLUGINLIB_EXPORT_CLASS(nav2_smac_planner::SmacPlannerHybrid, nav2_core::GlobalPlanner) diff --git a/nav2_smac_planner/test/CMakeLists.txt b/nav2_smac_planner/test/CMakeLists.txt index c5ff757d1c..1409c86deb 100644 --- a/nav2_smac_planner/test/CMakeLists.txt +++ b/nav2_smac_planner/test/CMakeLists.txt @@ -20,14 +20,14 @@ target_link_libraries(test_node2d ${library_name} ) -# Test NodeSE2 -ament_add_gtest(test_nodese2 - test_nodese2.cpp +# Test NodeHybrid +ament_add_gtest(test_nodehybrid + test_nodehybrid.cpp ) -ament_target_dependencies(test_nodese2 +ament_target_dependencies(test_nodehybrid ${dependencies} ) -target_link_libraries(test_nodese2 +target_link_libraries(test_nodehybrid ${library_name} ) @@ -64,14 +64,14 @@ target_link_libraries(test_a_star ${library_name} ) -# Test SMAC SE2 -ament_add_gtest(test_smac_se2 - test_smac_se2.cpp +# Test SMAC Hybrid +ament_add_gtest(test_smac_hybrid + test_smac_hybrid.cpp ) -ament_target_dependencies(test_smac_se2 +ament_target_dependencies(test_smac_hybrid ${dependencies} ) -target_link_libraries(test_smac_se2 +target_link_libraries(test_smac_hybrid ${library_name} ) @@ -86,13 +86,3 @@ target_link_libraries(test_smac_2d ${library_name}_2d ) -# Test smoother -ament_add_gtest(test_smoother - test_smoother.cpp -) -ament_target_dependencies(test_smoother - ${dependencies} -) -target_link_libraries(test_smoother - ${library_name}_2d -) diff --git a/nav2_smac_planner/include/nav2_smac_planner/options.hpp b/nav2_smac_planner/test/deprecated/options.hpp similarity index 98% rename from nav2_smac_planner/include/nav2_smac_planner/options.hpp rename to nav2_smac_planner/test/deprecated/options.hpp index 159ab8b53a..5d33223dc4 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/options.hpp +++ b/nav2_smac_planner/test/deprecated/options.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#ifndef NAV2_SMAC_PLANNER__OPTIONS_HPP_ -#define NAV2_SMAC_PLANNER__OPTIONS_HPP_ +#ifndef DEPRECATED__OPTIONS_HPP_ +#define DEPRECATED__OPTIONS_HPP_ #include #include "rclcpp_lifecycle/lifecycle_node.hpp" @@ -204,4 +204,4 @@ struct OptimizerParams } // namespace nav2_smac_planner -#endif // NAV2_SMAC_PLANNER__OPTIONS_HPP_ +#endif // DEPRECATED__OPTIONS_HPP_ diff --git a/nav2_smac_planner/test/deprecated/smoother.hpp b/nav2_smac_planner/test/deprecated/smoother.hpp new file mode 100644 index 0000000000..e523eaea1b --- /dev/null +++ b/nav2_smac_planner/test/deprecated/smoother.hpp @@ -0,0 +1,141 @@ +// 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 DEPRECATED__SMOOTHER_HPP_ +#define DEPRECATED__SMOOTHER_HPP_ + +#include +#include +#include +#include +#include +#include + +#include "nav2_smac_planner/types.hpp" +#include "nav2_smac_planner/smoother_cost_function.hpp" + +#include "ceres/ceres.h" +#include "Eigen/Core" + +namespace nav2_smac_planner +{ + +/** + * @class nav2_smac_planner::Smoother + * @brief A Conjugate Gradient 2D path smoother implementation + */ +class Smoother +{ +public: + /** + * @brief A constructor for nav2_smac_planner::Smoother + */ + Smoother() {} + + /** + * @brief A destructor for nav2_smac_planner::Smoother + */ + ~Smoother() {} + + /** + * @brief Initialization of the smoother + * @param params OptimizerParam struct + */ + void initialize(const OptimizerParams params) + { + _debug = params.debug; + + // General Params + + // 2 most valid options: STEEPEST_DESCENT, NONLINEAR_CONJUGATE_GRADIENT + _options.line_search_direction_type = ceres::NONLINEAR_CONJUGATE_GRADIENT; + _options.line_search_type = ceres::WOLFE; + _options.nonlinear_conjugate_gradient_type = ceres::POLAK_RIBIERE; + _options.line_search_interpolation_type = ceres::CUBIC; + + _options.max_num_iterations = params.max_iterations; + _options.max_solver_time_in_seconds = params.max_time; + + _options.function_tolerance = params.fn_tol; + _options.gradient_tolerance = params.gradient_tol; + _options.parameter_tolerance = params.param_tol; + + _options.min_line_search_step_size = params.advanced.min_line_search_step_size; + _options.max_num_line_search_step_size_iterations = + params.advanced.max_num_line_search_step_size_iterations; + _options.line_search_sufficient_function_decrease = + params.advanced.line_search_sufficient_function_decrease; + _options.max_line_search_step_contraction = params.advanced.max_line_search_step_contraction; + _options.min_line_search_step_contraction = params.advanced.min_line_search_step_contraction; + _options.max_num_line_search_direction_restarts = + params.advanced.max_num_line_search_direction_restarts; + _options.line_search_sufficient_curvature_decrease = + params.advanced.line_search_sufficient_curvature_decrease; + _options.max_line_search_step_expansion = params.advanced.max_line_search_step_expansion; + + if (_debug) { + _options.minimizer_progress_to_stdout = true; + } else { + _options.logging_type = ceres::SILENT; + } + } + + /** + * @brief Smoother method + * @param path Reference to path + * @param costmap Pointer to minimal costmap + * @param smoother parameters weights + * @return If smoothing was successful + */ + bool smooth( + std::vector & path, + nav2_costmap_2d::Costmap2D * costmap, + const SmootherParams & params) + { + _options.max_solver_time_in_seconds = params.max_time; + + double parameters[path.size() * 2]; // NOLINT + for (uint i = 0; i != path.size(); i++) { + parameters[2 * i] = path[i][0]; + parameters[2 * i + 1] = path[i][1]; + } + + ceres::GradientProblemSolver::Summary summary; + ceres::GradientProblem problem(new UnconstrainedSmootherCostFunction(&path, costmap, params)); + ceres::Solve(_options, problem, parameters, &summary); + + if (_debug) { + std::cout << summary.FullReport() << '\n'; + } + + if (!summary.IsSolutionUsable() || summary.initial_cost - summary.final_cost <= 0.0) { + return false; + } + + for (uint i = 0; i != path.size(); i++) { + path[i][0] = parameters[2 * i]; + path[i][1] = parameters[2 * i + 1]; + } + + return true; + } + +private: + bool _debug; + ceres::GradientProblemSolver::Options _options; +}; + +} // namespace nav2_smac_planner + +#endif // DEPRECATED__SMOOTHER_HPP_ diff --git a/nav2_smac_planner/include/nav2_smac_planner/smoother_cost_function.hpp b/nav2_smac_planner/test/deprecated/smoother_cost_function.hpp similarity index 94% rename from nav2_smac_planner/include/nav2_smac_planner/smoother_cost_function.hpp rename to nav2_smac_planner/test/deprecated/smoother_cost_function.hpp index eec8c61b4e..7e5349c894 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smoother_cost_function.hpp +++ b/nav2_smac_planner/test/deprecated/smoother_cost_function.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#ifndef NAV2_SMAC_PLANNER__SMOOTHER_COST_FUNCTION_HPP_ -#define NAV2_SMAC_PLANNER__SMOOTHER_COST_FUNCTION_HPP_ +#ifndef DEPRECATED__SMOOTHER_COST_FUNCTION_HPP_ +#define DEPRECATED__SMOOTHER_COST_FUNCTION_HPP_ #include #include @@ -56,6 +56,22 @@ class UnconstrainedSmootherCostFunction : public ceres::FirstOrderFunction _costmap(costmap), _params(params) { + // int height = costmap->getSizeInCellsX(); + // int width = costmap->getSizeInCellsY(); + // bool** binMap; + // binMap = new bool*[width]; + + // for (int x = 0; x < width; x++) { binMap[x] = new bool[height]; } + + // for (int x = 0; x < width; ++x) { + // for (int y = 0; y < height; ++y) { + // binMap[x][y] = costmap->getCost(x,y) >= 253 ? true : false; + // } + // } + + // voronoiDiagram.initializeMap(width, height, binMap); + // voronoiDiagram.update(); + // voronoiDiagram.visualize(); } /** @@ -138,7 +154,7 @@ class UnconstrainedSmootherCostFunction : public ceres::FirstOrderFunction if (valid_coords = _costmap->worldToMap(xi[0], xi[1], mx, my)) { costmap_cost = _costmap->getCost(mx, my); - addCostResidual(_params.costmap_weight, costmap_cost, cost_raw); + addCostResidual(_params.costmap_weight, costmap_cost, cost_raw, xi); } if (gradient != NULL) { @@ -379,13 +395,23 @@ class UnconstrainedSmootherCostFunction : public ceres::FirstOrderFunction inline void addCostResidual( const double & weight, const double & value, - double & r) const + double & r, + Eigen::Vector2d & xi) const { if (value == FREE) { return; } r += weight * value * value; // objective function value + + + // float obsDst = voronoiDiagram.getDistance((int)xi[0], (int)xi[1]); + + // if (abs(obsDst) > 0.3) { + // return; + // } + + // r += weight * (abs(obsDst) - 0.3) * (abs(obsDst) - 0.3); } /** @@ -508,8 +534,9 @@ class UnconstrainedSmootherCostFunction : public ceres::FirstOrderFunction int _num_params; nav2_costmap_2d::Costmap2D * _costmap{nullptr}; SmootherParams _params; + // DynamicVoronoi voronoiDiagram; }; } // namespace nav2_smac_planner -#endif // NAV2_SMAC_PLANNER__SMOOTHER_COST_FUNCTION_HPP_ +#endif // DEPRECATED__SMOOTHER_COST_FUNCTION_HPP_ diff --git a/nav2_smac_planner/test/deprecated_upsampler/upsampler.hpp b/nav2_smac_planner/test/deprecated/upsampler.hpp similarity index 98% rename from nav2_smac_planner/test/deprecated_upsampler/upsampler.hpp rename to nav2_smac_planner/test/deprecated/upsampler.hpp index 84ba625fa1..90e0f8b464 100644 --- a/nav2_smac_planner/test/deprecated_upsampler/upsampler.hpp +++ b/nav2_smac_planner/test/deprecated/upsampler.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#ifndef DEPRECATED_UPSAMPLER__UPSAMPLER_HPP_ -#define DEPRECATED_UPSAMPLER__UPSAMPLER_HPP_ +#ifndef DEPRECATED__UPSAMPLER_HPP_ +#define DEPRECATED__UPSAMPLER_HPP_ #include #include @@ -210,4 +210,4 @@ class Upsampler } // namespace nav2_smac_planner -#endif // DEPRECATED_UPSAMPLER__UPSAMPLER_HPP_ +#endif // DEPRECATED__UPSAMPLER_HPP_ diff --git a/nav2_smac_planner/test/deprecated_upsampler/upsampler_cost_function.hpp b/nav2_smac_planner/test/deprecated/upsampler_cost_function.hpp similarity index 98% rename from nav2_smac_planner/test/deprecated_upsampler/upsampler_cost_function.hpp rename to nav2_smac_planner/test/deprecated/upsampler_cost_function.hpp index 44df1c3f22..4a89800b5b 100644 --- a/nav2_smac_planner/test/deprecated_upsampler/upsampler_cost_function.hpp +++ b/nav2_smac_planner/test/deprecated/upsampler_cost_function.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#ifndef DEPRECATED_UPSAMPLER__UPSAMPLER_COST_FUNCTION_HPP_ -#define DEPRECATED_UPSAMPLER__UPSAMPLER_COST_FUNCTION_HPP_ +#ifndef DEPRECATED__UPSAMPLER_COST_FUNCTION_HPP_ +#define DEPRECATED__UPSAMPLER_COST_FUNCTION_HPP_ #include #include @@ -363,4 +363,4 @@ class UpsamplerCostFunction : public ceres::FirstOrderFunction } // namespace nav2_smac_planner -#endif // DEPRECATED_UPSAMPLER__UPSAMPLER_COST_FUNCTION_HPP_ +#endif // DEPRECATED__UPSAMPLER_COST_FUNCTION_HPP_ diff --git a/nav2_smac_planner/test/deprecated_upsampler/upsampler_cost_function_nlls.hpp b/nav2_smac_planner/test/deprecated/upsampler_cost_function_nlls.hpp similarity index 98% rename from nav2_smac_planner/test/deprecated_upsampler/upsampler_cost_function_nlls.hpp rename to nav2_smac_planner/test/deprecated/upsampler_cost_function_nlls.hpp index 17204694b1..f1599bcd78 100644 --- a/nav2_smac_planner/test/deprecated_upsampler/upsampler_cost_function_nlls.hpp +++ b/nav2_smac_planner/test/deprecated/upsampler_cost_function_nlls.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. Reserved. -#ifndef DEPRECATED_UPSAMPLER__UPSAMPLER_COST_FUNCTION_NLLS_HPP_ -#define DEPRECATED_UPSAMPLER__UPSAMPLER_COST_FUNCTION_NLLS_HPP_ +#ifndef DEPRECATED__UPSAMPLER_COST_FUNCTION_NLLS_HPP_ +#define DEPRECATED__UPSAMPLER_COST_FUNCTION_NLLS_HPP_ #include #include @@ -331,4 +331,4 @@ class UpsamplerConstrainedCostFunction : public ceres::SizedCostFunction<1, 1, 1 } // namespace nav2_smac_planner -#endif // DEPRECATED_UPSAMPLER__UPSAMPLER_COST_FUNCTION_NLLS_HPP_ +#endif // DEPRECATED__UPSAMPLER_COST_FUNCTION_NLLS_HPP_ diff --git a/nav2_smac_planner/test/test_a_star.cpp b/nav2_smac_planner/test/test_a_star.cpp index 721eee4710..17e10708f2 100644 --- a/nav2_smac_planner/test/test_a_star.cpp +++ b/nav2_smac_planner/test/test_a_star.cpp @@ -22,7 +22,7 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "nav2_util/lifecycle_node.hpp" -#include "nav2_smac_planner/node_se2.hpp" +#include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/a_star.hpp" #include "nav2_smac_planner/collision_checker.hpp" @@ -45,8 +45,7 @@ TEST(AStarTest, test_a_star_2d) int it_on_approach = 10; int num_it = 0; - a_star.initialize(false, max_iterations, it_on_approach); - a_star.setFootprint(nav2_costmap_2d::Footprint(), true); + a_star.initialize(false, max_iterations, it_on_approach, 0.0, 1); nav2_costmap_2d::Costmap2D * costmapA = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0.0, 0.0, 0); @@ -58,12 +57,15 @@ TEST(AStarTest, test_a_star_2d) } // functional case testing - a_star.createGraph(costmapA->getSizeInCellsX(), costmapA->getSizeInCellsY(), 1, costmapA); + std::unique_ptr checker = + std::make_unique(costmapA, 1); + checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0); + a_star.setCollisionChecker(checker.get()); a_star.setStart(20u, 20u, 0); a_star.setGoal(80u, 80u, 0); nav2_smac_planner::Node2D::CoordinateVector path; EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); - EXPECT_EQ(num_it, 556); + EXPECT_EQ(num_it, 102); // check path is the right size and collision free EXPECT_EQ(path.size(), 81u); @@ -72,9 +74,6 @@ TEST(AStarTest, test_a_star_2d) } // setting non-zero dim 3 for 2D search - EXPECT_THROW( - a_star.createGraph( - costmapA->getSizeInCellsX(), costmapA->getSizeInCellsY(), 10, costmapA), std::runtime_error); EXPECT_THROW(a_star.setGoal(0, 0, 10), std::runtime_error); EXPECT_THROW(a_star.setStart(0, 0, 10), std::runtime_error); @@ -82,11 +81,10 @@ TEST(AStarTest, test_a_star_2d) // failure cases with invalid inputs nav2_smac_planner::AStarAlgorithm a_star_2( nav2_smac_planner::MotionModel::VON_NEUMANN, info); - a_star_2.initialize(false, max_iterations, it_on_approach); - a_star_2.setFootprint(nav2_costmap_2d::Footprint(), true); + a_star_2.initialize(false, max_iterations, it_on_approach, 0, 1); num_it = 0; EXPECT_THROW(a_star_2.createPath(path, num_it, tolerance), std::runtime_error); - a_star_2.createGraph(costmapA->getSizeInCellsX(), costmapA->getSizeInCellsY(), 1, costmapA); + a_star_2.setCollisionChecker(checker.get()); num_it = 0; EXPECT_THROW(a_star_2.createPath(path, num_it, tolerance), std::runtime_error); a_star_2.setStart(50, 50, 0); // invalid @@ -102,7 +100,7 @@ TEST(AStarTest, test_a_star_2d) a_star_2.setStart(20, 20, 0); // valid a_star_2.setGoal(50, 50, 0); // invalid EXPECT_TRUE(a_star_2.createPath(path, num_it, some_tolerance)); - EXPECT_EQ(path.size(), 32u); + EXPECT_EQ(path.size(), 42u); for (unsigned int i = 0; i != path.size(); i++) { EXPECT_EQ(costmapA->getCost(path[i].x, path[i].y), 0); } @@ -112,7 +110,7 @@ TEST(AStarTest, test_a_star_2d) EXPECT_EQ(a_star_2.getSizeX(), 100u); EXPECT_EQ(a_star_2.getSizeY(), 100u); EXPECT_EQ(a_star_2.getSizeDim3(), 1u); - EXPECT_EQ(a_star_2.getToleranceHeuristic(), 1000.0); + EXPECT_EQ(a_star_2.getToleranceHeuristic(), 20.0); EXPECT_EQ(a_star_2.getOnApproachMaxIterations(), 10); delete costmapA; @@ -121,20 +119,20 @@ TEST(AStarTest, test_a_star_2d) TEST(AStarTest, test_a_star_se2) { nav2_smac_planner::SearchInfo info; - info.change_penalty = 1.2; - info.non_straight_penalty = 1.4; - info.reverse_penalty = 2.1; - info.minimum_turning_radius = 2.0; // in grid coordinates + info.change_penalty = 0.1; + info.non_straight_penalty = 1.1; + info.reverse_penalty = 2.0; + info.minimum_turning_radius = 8; // in grid coordinates unsigned int size_theta = 72; - nav2_smac_planner::AStarAlgorithm a_star( + info.cost_penalty = 1.7; + nav2_smac_planner::AStarAlgorithm a_star( nav2_smac_planner::MotionModel::DUBIN, info); int max_iterations = 10000; float tolerance = 10.0; int it_on_approach = 10; int num_it = 0; - a_star.initialize(false, max_iterations, it_on_approach); - a_star.setFootprint(nav2_costmap_2d::Footprint(), true); + a_star.initialize(false, max_iterations, it_on_approach, 401, size_theta); nav2_costmap_2d::Costmap2D * costmapA = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0.0, 0.0, 0); @@ -145,17 +143,20 @@ TEST(AStarTest, test_a_star_se2) } } + std::unique_ptr checker = + std::make_unique(costmapA, size_theta); + checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0); + // functional case testing - a_star.createGraph( - costmapA->getSizeInCellsX(), costmapA->getSizeInCellsY(), size_theta, costmapA); + a_star.setCollisionChecker(checker.get()); a_star.setStart(10u, 10u, 0u); a_star.setGoal(80u, 80u, 40u); - nav2_smac_planner::NodeSE2::CoordinateVector path; + nav2_smac_planner::NodeHybrid::CoordinateVector path; EXPECT_TRUE(a_star.createPath(path, num_it, tolerance)); // check path is the right size and collision free - EXPECT_EQ(num_it, 44); - EXPECT_EQ(path.size(), 75u); + EXPECT_EQ(num_it, 351); + 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); } diff --git a/nav2_smac_planner/test/test_collision_checker.cpp b/nav2_smac_planner/test/test_collision_checker.cpp index 68084993b2..40e73c82ad 100644 --- a/nav2_smac_planner/test/test_collision_checker.cpp +++ b/nav2_smac_planner/test/test_collision_checker.cpp @@ -41,8 +41,8 @@ TEST(collision_footprint, test_basic) nav2_costmap_2d::Footprint footprint = {p1, p2, p3, p4}; - nav2_smac_planner::GridCollisionChecker collision_checker(costmap_); - collision_checker.setFootprint(footprint, false /*use footprint*/); + nav2_smac_planner::GridCollisionChecker collision_checker(costmap_, 72); + collision_checker.setFootprint(footprint, false /*use footprint*/, 0.0); collision_checker.inCollision(5.0, 5.0, 0.0, false); float cost = collision_checker.getCost(); EXPECT_NEAR(cost, 0.0, 0.001); @@ -53,9 +53,9 @@ TEST(collision_footprint, test_point_cost) { nav2_costmap_2d::Costmap2D * costmap_ = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0, 0, 0); - nav2_smac_planner::GridCollisionChecker collision_checker(costmap_); + nav2_smac_planner::GridCollisionChecker collision_checker(costmap_, 72); nav2_costmap_2d::Footprint footprint; - collision_checker.setFootprint(footprint, true /*radius / pointcose*/); + collision_checker.setFootprint(footprint, true /*radius / pointcose*/, 0.0); collision_checker.inCollision(5.0, 5.0, 0.0, false); float cost = collision_checker.getCost(); @@ -67,9 +67,9 @@ TEST(collision_footprint, test_world_to_map) { nav2_costmap_2d::Costmap2D * costmap_ = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0, 0, 0); - nav2_smac_planner::GridCollisionChecker collision_checker(costmap_); + nav2_smac_planner::GridCollisionChecker collision_checker(costmap_, 72); nav2_costmap_2d::Footprint footprint; - collision_checker.setFootprint(footprint, true /*radius / point cost*/); + collision_checker.setFootprint(footprint, true /*radius / point cost*/, 0.0); unsigned int x, y; @@ -113,8 +113,8 @@ TEST(collision_footprint, test_footprint_at_pose_with_movement) nav2_costmap_2d::Footprint footprint = {p1, p2, p3, p4}; - nav2_smac_planner::GridCollisionChecker collision_checker(costmap_); - collision_checker.setFootprint(footprint, false /*use footprint*/); + nav2_smac_planner::GridCollisionChecker collision_checker(costmap_, 72); + collision_checker.setFootprint(footprint, false /*use footprint*/, 0.0); collision_checker.inCollision(50, 50, 0.0, false); float cost = collision_checker.getCost(); @@ -153,8 +153,8 @@ TEST(collision_footprint, test_point_and_line_cost) nav2_costmap_2d::Footprint footprint = {p1, p2, p3, p4}; - nav2_smac_planner::GridCollisionChecker collision_checker(costmap_); - collision_checker.setFootprint(footprint, false /*use footprint*/); + nav2_smac_planner::GridCollisionChecker collision_checker(costmap_, 72); + collision_checker.setFootprint(footprint, false /*use footprint*/, 0.0); collision_checker.inCollision(50, 50, 0.0, false); float value = collision_checker.getCost(); diff --git a/nav2_smac_planner/test/test_node2d.cpp b/nav2_smac_planner/test/test_node2d.cpp index 33377254a7..f4520bd496 100644 --- a/nav2_smac_planner/test/test_node2d.cpp +++ b/nav2_smac_planner/test/test_node2d.cpp @@ -35,41 +35,45 @@ RclCppFixture g_rclcppfixture; TEST(Node2DTest, test_node_2d) { nav2_costmap_2d::Costmap2D costmapA(10, 10, 0.05, 0.0, 0.0, 0); - nav2_smac_planner::GridCollisionChecker checker(&costmapA); + std::unique_ptr checker = + std::make_unique(&costmapA, 72); + checker->setFootprint(nav2_costmap_2d::Footprint(), true, 0.0); // test construction unsigned char cost = static_cast(1); - nav2_smac_planner::Node2D testA(cost, 1); - nav2_smac_planner::Node2D testB(cost, 1); + nav2_smac_planner::Node2D testA(1); + testA.setCost(cost); + nav2_smac_planner::Node2D testB(1); + testB.setCost(cost); EXPECT_EQ(testA.getCost(), 1.0f); + nav2_smac_planner::SearchInfo info; + info.cost_penalty = 1.0; + unsigned int size = 10; + nav2_smac_planner::Node2D::initMotionModel( + nav2_smac_planner::MotionModel::MOORE, size, size, size, info); // test reset - testA.reset(10); - EXPECT_EQ(testA.getCost(), 10.0f); - - // Check constants - EXPECT_EQ(testA.neutral_cost, 50.0f); + testA.reset(); + EXPECT_TRUE(std::isnan(testA.getCost())); // check collision checking - EXPECT_EQ(testA.isNodeValid(false, checker), true); - testA.reset(254); - EXPECT_EQ(testA.isNodeValid(false, checker), false); - testA.reset(255); - EXPECT_EQ(testA.isNodeValid(true, checker), true); - EXPECT_EQ(testA.isNodeValid(false, checker), false); - testA.reset(10); + EXPECT_EQ(testA.isNodeValid(false, checker.get()), true); + testA.setCost(255); + EXPECT_EQ(testA.isNodeValid(true, checker.get()), true); + testA.setCost(10); // check traversal cost computation - EXPECT_EQ(testB.getTraversalCost(&testA), 58.0f); + EXPECT_NEAR(testB.getTraversalCost(&testA), 1.03f, 0.1f); // check heuristic cost computation nav2_smac_planner::Node2D::Coordinates A(0.0, 0.0); nav2_smac_planner::Node2D::Coordinates B(10.0, 5.0); - EXPECT_NEAR(testB.getHeuristicCost(A, B), 559.016, 0.01); + EXPECT_NEAR(testB.getHeuristicCost(A, B, nullptr), 15., 0.01); // check operator== works on index unsigned char costC = '2'; - nav2_smac_planner::Node2D testC(costC, 1); + nav2_smac_planner::Node2D testC(1); + testC.setCost(costC); EXPECT_TRUE(testA == testC); // check accumulated costs are set @@ -97,15 +101,24 @@ TEST(Node2DTest, test_node_2d) TEST(Node2DTest, test_node_2d_neighbors) { + nav2_smac_planner::SearchInfo info; + unsigned int size_x = 10u; + unsigned int size_y = 10u; + unsigned int quant = 0u; // test neighborhood computation - nav2_smac_planner::Node2D::initNeighborhood(10u, nav2_smac_planner::MotionModel::VON_NEUMANN); + nav2_smac_planner::Node2D::initMotionModel( + nav2_smac_planner::MotionModel::VON_NEUMANN, size_x, + size_y, quant, info); EXPECT_EQ(nav2_smac_planner::Node2D::_neighbors_grid_offsets.size(), 4u); EXPECT_EQ(nav2_smac_planner::Node2D::_neighbors_grid_offsets[0], -1); EXPECT_EQ(nav2_smac_planner::Node2D::_neighbors_grid_offsets[1], 1); EXPECT_EQ(nav2_smac_planner::Node2D::_neighbors_grid_offsets[2], -10); EXPECT_EQ(nav2_smac_planner::Node2D::_neighbors_grid_offsets[3], 10); - nav2_smac_planner::Node2D::initNeighborhood(100u, nav2_smac_planner::MotionModel::MOORE); + size_x = 100u; + nav2_smac_planner::Node2D::initMotionModel( + nav2_smac_planner::MotionModel::MOORE, size_x, size_y, + quant, info); EXPECT_EQ(nav2_smac_planner::Node2D::_neighbors_grid_offsets.size(), 8u); EXPECT_EQ(nav2_smac_planner::Node2D::_neighbors_grid_offsets[0], -1); EXPECT_EQ(nav2_smac_planner::Node2D::_neighbors_grid_offsets[1], 1); @@ -117,17 +130,19 @@ TEST(Node2DTest, test_node_2d_neighbors) EXPECT_EQ(nav2_smac_planner::Node2D::_neighbors_grid_offsets[7], 101); nav2_costmap_2d::Costmap2D costmapA(10, 10, 0.05, 0.0, 0.0, 0); - nav2_smac_planner::GridCollisionChecker checker(&costmapA); + std::unique_ptr checker = + std::make_unique(&costmapA, 72); unsigned char cost = static_cast(1); - nav2_smac_planner::Node2D * node = new nav2_smac_planner::Node2D(cost, 1); + nav2_smac_planner::Node2D * node = new nav2_smac_planner::Node2D(1); + node->setCost(cost); std::function neighborGetter = [&, this](const unsigned int & index, nav2_smac_planner::Node2D * & neighbor_rtn) -> bool { - return true; + return false; }; nav2_smac_planner::Node2D::NodeVector neighbors; - nav2_smac_planner::Node2D::getNeighbors(node, neighborGetter, checker, false, neighbors); + node->getNeighbors(neighborGetter, checker.get(), false, neighbors); delete node; // should be empty since totally invalid diff --git a/nav2_smac_planner/test/test_nodebasic.cpp b/nav2_smac_planner/test/test_nodebasic.cpp index 23d445ce54..965246d67c 100644 --- a/nav2_smac_planner/test/test_nodebasic.cpp +++ b/nav2_smac_planner/test/test_nodebasic.cpp @@ -24,7 +24,7 @@ #include "nav2_util/lifecycle_node.hpp" #include "nav2_smac_planner/node_basic.hpp" #include "nav2_smac_planner/node_2d.hpp" -#include "nav2_smac_planner/node_se2.hpp" +#include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/collision_checker.hpp" class RclCppFixture @@ -37,7 +37,7 @@ RclCppFixture g_rclcppfixture; TEST(NodeBasicTest, test_node_basic) { - nav2_smac_planner::NodeBasic node(50); + nav2_smac_planner::NodeBasic node(50); EXPECT_EQ(node.index, 50u); EXPECT_EQ(node.graph_node_ptr, nullptr); diff --git a/nav2_smac_planner/test/test_nodehybrid.cpp b/nav2_smac_planner/test/test_nodehybrid.cpp new file mode 100644 index 0000000000..9954a011ef --- /dev/null +++ b/nav2_smac_planner/test/test_nodehybrid.cpp @@ -0,0 +1,219 @@ +// 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. + +#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 "nav2_smac_planner/node_hybrid.hpp" +#include "nav2_smac_planner/collision_checker.hpp" + +class RclCppFixture +{ +public: + RclCppFixture() {rclcpp::init(0, nullptr);} + ~RclCppFixture() {rclcpp::shutdown();} +}; +RclCppFixture g_rclcppfixture; + +TEST(NodeHybridTest, test_node_hybrid) +{ + nav2_smac_planner::SearchInfo info; + info.change_penalty = 0.1; + info.non_straight_penalty = 1.1; + info.reverse_penalty = 2.0; + info.minimum_turning_radius = 8; // 0.4m/5cm resolution costmap + info.cost_penalty = 1.7; + unsigned int size_x = 10; + unsigned int size_y = 10; + unsigned int size_theta = 72; + + // Check defaulted constants + nav2_smac_planner::NodeHybrid testA(49); + EXPECT_EQ(testA.travel_distance_cost, sqrt(2)); + + nav2_smac_planner::NodeHybrid::initMotionModel( + nav2_smac_planner::MotionModel::DUBIN, size_x, size_y, size_theta, info); + + 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 construction + nav2_smac_planner::NodeHybrid testB(49); + EXPECT_TRUE(std::isnan(testA.getCost())); + + // 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); + + // test reset + testA.reset(); + EXPECT_TRUE(std::isnan(testA.getCost())); + + // Check motion-specific constants + EXPECT_NEAR(testA.travel_distance_cost, 2.08842, 0.1); + + // check collision checking + EXPECT_EQ(testA.isNodeValid(false, checker.get()), true); + + // check traversal cost computation + // simulated first node, should return neutral cost + EXPECT_NEAR(testB.getTraversalCost(&testA), 2.088, 0.1); + // now with straight motion, cost is 0, so will be sqrt(2) as well + testB.setMotionPrimitiveIndex(1); + testA.setMotionPrimitiveIndex(0); + EXPECT_NEAR(testB.getTraversalCost(&testA), 2.088, 0.1); + // same direction as parent, testB + testA.setMotionPrimitiveIndex(1); + EXPECT_NEAR(testB.getTraversalCost(&testA), 2.297f, 0.01); + // opposite direction as parent, testB + testA.setMotionPrimitiveIndex(2); + EXPECT_NEAR(testB.getTraversalCost(&testA), 2.506f, 0.01); + + // will throw because never collision checked testB + EXPECT_THROW(testA.getTraversalCost(&testB), std::runtime_error); + + // check motion primitives + EXPECT_EQ(testA.getMotionPrimitiveIndex(), 2u); + + // check operator== works on index + nav2_smac_planner::NodeHybrid testC(49); + EXPECT_TRUE(testA == testC); + + // check accumulated costs are set + testC.setAccumulatedCost(100); + EXPECT_EQ(testC.getAccumulatedCost(), 100.0f); + + // check visiting state + EXPECT_EQ(testC.wasVisited(), false); + testC.visited(); + EXPECT_EQ(testC.wasVisited(), true); + + // check index + EXPECT_EQ(testC.getIndex(), 49u); + + // check set pose and pose + testC.setPose(nav2_smac_planner::NodeHybrid::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); + + // check static index functions + EXPECT_EQ(nav2_smac_planner::NodeHybrid::getIndex(1u, 1u, 4u, 10u, 72u), 796u); + EXPECT_EQ(nav2_smac_planner::NodeHybrid::getCoords(796u, 10u, 72u).x, 1u); + EXPECT_EQ(nav2_smac_planner::NodeHybrid::getCoords(796u, 10u, 72u).y, 1u); + EXPECT_EQ(nav2_smac_planner::NodeHybrid::getCoords(796u, 10u, 72u).theta, 4u); + + delete costmapA; +} + +TEST(NodeHybridTest, test_node_debin_neighbors) +{ + nav2_smac_planner::SearchInfo info; + info.change_penalty = 1.2; + info.non_straight_penalty = 1.4; + info.reverse_penalty = 2.1; + info.minimum_turning_radius = 4; // 0.2 in grid coordinates + unsigned int size_x = 100; + unsigned int size_y = 100; + unsigned int size_theta = 72; + 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); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[0]._y, 0, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[0]._theta, 0, 0.01); + + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[1]._x, 1.69047, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[1]._y, 0.3747, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[1]._theta, 5, 0.01); + + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[2]._x, 1.69047, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[2]._y, -0.3747, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[2]._theta, -5, 0.01); +} + +TEST(NodeHybridTest, test_node_reeds_neighbors) +{ + nav2_smac_planner::SearchInfo info; + info.change_penalty = 1.2; + info.non_straight_penalty = 1.4; + info.reverse_penalty = 2.1; + info.minimum_turning_radius = 8; // 0.4 in grid coordinates + unsigned int size_x = 100; + unsigned int size_y = 100; + unsigned int size_theta = 72; + nav2_smac_planner::NodeHybrid::initMotionModel( + nav2_smac_planner::MotionModel::REEDS_SHEPP, size_x, size_y, size_theta, info); + + EXPECT_EQ(nav2_smac_planner::NodeHybrid::motion_table.projections.size(), 6u); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[0]._x, 2.088, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[0]._y, 0, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[0]._theta, 0, 0.01); + + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[1]._x, 2.070, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[1]._y, 0.272, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[1]._theta, 3, 0.01); + + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[2]._x, 2.070, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[2]._y, -0.272, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[2]._theta, -3, 0.01); + + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[3]._x, -2.088, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[3]._y, 0, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[3]._theta, 0, 0.01); + + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[4]._x, -2.07, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[4]._y, 0.272, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[4]._theta, -3, 0.01); + + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[5]._x, -2.07, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[5]._y, -0.272, 0.01); + EXPECT_NEAR(nav2_smac_planner::NodeHybrid::motion_table.projections[5]._theta, 3, 0.01); + + nav2_costmap_2d::Costmap2D costmapA(100, 100, 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); + nav2_smac_planner::NodeHybrid * node = new nav2_smac_planner::NodeHybrid(49); + std::function neighborGetter = + [&, this](const unsigned int & index, nav2_smac_planner::NodeHybrid * & neighbor_rtn) -> bool + { + // because we don't return a real object + return false; + }; + + nav2_smac_planner::NodeHybrid::NodeVector neighbors; + node->getNeighbors(neighborGetter, checker.get(), false, neighbors); + delete node; + + // should be empty since totally invalid + EXPECT_EQ(neighbors.size(), 0u); +} diff --git a/nav2_smac_planner/test/test_nodese2.cpp b/nav2_smac_planner/test/test_nodese2.cpp deleted file mode 100644 index 39b9aa2dfa..0000000000 --- a/nav2_smac_planner/test/test_nodese2.cpp +++ /dev/null @@ -1,214 +0,0 @@ -// 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. - -#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 "nav2_smac_planner/node_se2.hpp" -#include "nav2_smac_planner/collision_checker.hpp" - -class RclCppFixture -{ -public: - RclCppFixture() {rclcpp::init(0, nullptr);} - ~RclCppFixture() {rclcpp::shutdown();} -}; -RclCppFixture g_rclcppfixture; - -TEST(NodeSE2Test, test_node_se2) -{ - nav2_smac_planner::SearchInfo info; - info.change_penalty = 1.2; - info.non_straight_penalty = 1.4; - info.reverse_penalty = 2.1; - info.minimum_turning_radius = 0.20; - unsigned int size_x = 10; - unsigned int size_y = 10; - unsigned int size_theta = 72; - - nav2_smac_planner::NodeSE2::initMotionModel( - nav2_smac_planner::MotionModel::DUBIN, size_x, size_y, size_theta, info); - - nav2_costmap_2d::Costmap2D * costmapA = new nav2_costmap_2d::Costmap2D( - 10, 10, 0.05, 0.0, 0.0, 0); - nav2_smac_planner::GridCollisionChecker checker(costmapA); - checker.setFootprint(nav2_costmap_2d::Footprint(), true); - - // test construction - nav2_smac_planner::NodeSE2 testA(49); - nav2_smac_planner::NodeSE2 testB(49); - EXPECT_TRUE(std::isnan(testA.getCost())); - - // test node valid and cost - testA.pose.x = 5; - testA.pose.y = 5; - testA.pose.theta = 0; - EXPECT_EQ(testA.isNodeValid(true, checker), true); - EXPECT_EQ(testA.isNodeValid(false, checker), true); - EXPECT_EQ(testA.getCost(), 0.0f); - - // test reset - testA.reset(); - EXPECT_TRUE(std::isnan(testA.getCost())); - - // Check constants - EXPECT_EQ(testA.neutral_cost, sqrt(2)); - - // check collision checking - EXPECT_EQ(testA.isNodeValid(false, checker), true); - - // check traversal cost computation - // simulated first node, should return neutral cost - EXPECT_NEAR(testB.getTraversalCost(&testA), sqrt(2), 0.01); - // now with straight motion, cost is 0, so will be sqrt(2) as well - testB.setMotionPrimitiveIndex(1); - testA.setMotionPrimitiveIndex(0); - EXPECT_NEAR(testB.getTraversalCost(&testA), sqrt(2), 0.01); - // same direction as parent, testB - testA.setMotionPrimitiveIndex(1); - EXPECT_NEAR(testB.getTraversalCost(&testA), 1.9799f, 0.01); - // opposite direction as parent, testB - testA.setMotionPrimitiveIndex(2); - EXPECT_NEAR(testB.getTraversalCost(&testA), 3.67696f, 0.01); - - // will throw because never collision checked testB - EXPECT_THROW(testA.getTraversalCost(&testB), std::runtime_error); - - // check motion primitives - EXPECT_EQ(testA.getMotionPrimitiveIndex(), 2u); - - // check heuristic cost computation - nav2_smac_planner::NodeSE2::computeWavefrontHeuristic( - costmapA, - static_cast(10.0), - static_cast(5.0), - 0.0, 0.0); - nav2_smac_planner::NodeSE2::Coordinates A(0.0, 0.0, 4.2); - nav2_smac_planner::NodeSE2::Coordinates B(10.0, 5.0, 54.1); - EXPECT_NEAR(testB.getHeuristicCost(B, A), 16.723, 0.01); - - // check operator== works on index - nav2_smac_planner::NodeSE2 testC(49); - EXPECT_TRUE(testA == testC); - - // check accumulated costs are set - testC.setAccumulatedCost(100); - EXPECT_EQ(testC.getAccumulatedCost(), 100.0f); - - // check visiting state - EXPECT_EQ(testC.wasVisited(), false); - testC.queued(); - EXPECT_EQ(testC.isQueued(), true); - testC.visited(); - EXPECT_EQ(testC.wasVisited(), true); - EXPECT_EQ(testC.isQueued(), false); - - // check index - EXPECT_EQ(testC.getIndex(), 49u); - - // check set pose and pose - testC.setPose(nav2_smac_planner::NodeSE2::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); - - // check static index functions - EXPECT_EQ(nav2_smac_planner::NodeSE2::getIndex(1u, 1u, 4u, 10u, 72u), 796u); - EXPECT_EQ(nav2_smac_planner::NodeSE2::getCoords(796u, 10u, 72u).x, 1u); - EXPECT_EQ(nav2_smac_planner::NodeSE2::getCoords(796u, 10u, 72u).y, 1u); - EXPECT_EQ(nav2_smac_planner::NodeSE2::getCoords(796u, 10u, 72u).theta, 4u); - - delete costmapA; -} - -TEST(NodeSE2Test, test_node_2d_neighbors) -{ - nav2_smac_planner::SearchInfo info; - info.change_penalty = 1.2; - info.non_straight_penalty = 1.4; - info.reverse_penalty = 2.1; - info.minimum_turning_radius = 4; // 0.2 in grid coordinates - unsigned int size_x = 100; - unsigned int size_y = 100; - unsigned int size_theta = 72; - nav2_smac_planner::NodeSE2::initMotionModel( - nav2_smac_planner::MotionModel::DUBIN, size_x, size_y, size_theta, info); - - - // test neighborhood computation - EXPECT_EQ(nav2_smac_planner::NodeSE2::motion_table.projections.size(), 3u); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[0]._x, 1.731517, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[0]._y, 0, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[0]._theta, 0, 0.01); - - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[1]._x, 1.69047, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[1]._y, 0.3747, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[1]._theta, 5, 0.01); - - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[2]._x, 1.69047, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[2]._y, -0.3747, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[2]._theta, -5, 0.01); - - nav2_smac_planner::NodeSE2::initMotionModel( - nav2_smac_planner::MotionModel::REEDS_SHEPP, size_x, size_y, size_theta, info); - - EXPECT_EQ(nav2_smac_planner::NodeSE2::motion_table.projections.size(), 6u); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[0]._x, 1.731517, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[0]._y, 0, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[0]._theta, 0, 0.01); - - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[1]._x, 1.69047, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[1]._y, 0.3747, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[1]._theta, 5, 0.01); - - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[2]._x, 1.69047, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[2]._y, -0.3747, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[2]._theta, -5, 0.01); - - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[3]._x, -1.731517, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[3]._y, 0, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[3]._theta, 0, 0.01); - - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[4]._x, -1.69047, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[4]._y, 0.3747, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[4]._theta, -5, 0.01); - - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[5]._x, -1.69047, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[5]._y, -0.3747, 0.01); - EXPECT_NEAR(nav2_smac_planner::NodeSE2::motion_table.projections[5]._theta, 5, 0.01); - - nav2_costmap_2d::Costmap2D costmapA(100, 100, 0.05, 0.0, 0.0, 0); - nav2_smac_planner::GridCollisionChecker checker(&costmapA); - nav2_smac_planner::NodeSE2 * node = new nav2_smac_planner::NodeSE2(49); - std::function neighborGetter = - [&, this](const unsigned int & index, nav2_smac_planner::NodeSE2 * & neighbor_rtn) -> bool - { - // because we don't return a real object - return false; - }; - - nav2_smac_planner::NodeSE2::NodeVector neighbors; - nav2_smac_planner::NodeSE2::getNeighbors(node, neighborGetter, checker, false, neighbors); - delete node; - - // should be empty since totally invalid - EXPECT_EQ(neighbors.size(), 0u); -} diff --git a/nav2_smac_planner/test/test_smac_2d.cpp b/nav2_smac_planner/test/test_smac_2d.cpp index 59a31eb17b..f3391d4240 100644 --- a/nav2_smac_planner/test/test_smac_2d.cpp +++ b/nav2_smac_planner/test/test_smac_2d.cpp @@ -23,10 +23,10 @@ #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_se2.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.hpp" +#include "nav2_smac_planner/smac_planner_hybrid.hpp" #include "nav2_smac_planner/smac_planner_2d.hpp" class RclCppFixture diff --git a/nav2_smac_planner/test/test_smac_se2.cpp b/nav2_smac_planner/test/test_smac_hybrid.cpp similarity index 85% rename from nav2_smac_planner/test/test_smac_se2.cpp rename to nav2_smac_planner/test/test_smac_hybrid.cpp index c0a4cf8e8e..9c6d50a0b5 100644 --- a/nav2_smac_planner/test/test_smac_se2.cpp +++ b/nav2_smac_planner/test/test_smac_hybrid.cpp @@ -23,10 +23,10 @@ #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_se2.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.hpp" +#include "nav2_smac_planner/smac_planner_hybrid.hpp" #include "nav2_smac_planner/smac_planner_2d.hpp" class RclCppFixture @@ -50,8 +50,6 @@ TEST(SmacTest, test_smac_se2) std::make_shared("global_costmap"); costmap_ros->on_configure(rclcpp_lifecycle::State()); - nodeSE2->declare_parameter("test.smooth_path", true); - nodeSE2->set_parameter(rclcpp::Parameter("test.smooth_path", true)); nodeSE2->declare_parameter("test.downsample_costmap", true); nodeSE2->set_parameter(rclcpp::Parameter("test.downsample_costmap", true)); nodeSE2->declare_parameter("test.downsampling_factor", 2); @@ -61,8 +59,10 @@ TEST(SmacTest, test_smac_se2) start.pose.position.x = 0.0; start.pose.position.y = 0.0; start.pose.orientation.w = 1.0; - goal = start; - auto planner = std::make_unique(); + 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(nodeSE2, "test", nullptr, costmap_ros); planner->activate(); @@ -79,14 +79,3 @@ TEST(SmacTest, test_smac_se2) costmap_ros.reset(); nodeSE2.reset(); } - -TEST(SmacTestSE2, test_dist) -{ - Eigen::Vector2d p1; - p1[0] = 0.0; - p1[1] = 0.0; - Eigen::Vector2d p2; - p2[0] = 0.0; - p2[1] = 1.0; - EXPECT_NEAR(nav2_smac_planner::squaredDistance(p1, p2), 1.0, 0.001); -} diff --git a/nav2_smac_planner/test/test_smoother.cpp b/nav2_smac_planner/test/test_smoother.cpp deleted file mode 100644 index 41c8280950..0000000000 --- a/nav2_smac_planner/test/test_smoother.cpp +++ /dev/null @@ -1,104 +0,0 @@ -// 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. - -#include -#include -#include -#include - -#include "gtest/gtest.h" -#include "rclcpp/rclcpp.hpp" -#include "nav2_costmap_2d/costmap_2d.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_smac_planner/a_star.hpp" -#include "nav2_smac_planner/smoother.hpp" - -class RclCppFixture -{ -public: - RclCppFixture() {rclcpp::init(0, nullptr);} - ~RclCppFixture() {rclcpp::shutdown();} -}; -RclCppFixture g_rclcppfixture; - -TEST(SmootherTest, test_smoother) -{ - rclcpp_lifecycle::LifecycleNode::SharedPtr node2D = - std::make_shared("SmootherTest"); - - // create and populate costmap - nav2_costmap_2d::Costmap2D * costmap = new nav2_costmap_2d::Costmap2D(100, 100, 0.05, 0, 0, 0); - - for (unsigned int i = 40; i <= 60; ++i) { - for (unsigned int j = 40; j <= 60; ++j) { - costmap->setCost(i, j, 254); - } - } - - // compute path to use - nav2_smac_planner::SearchInfo info; - info.change_penalty = 1.2; - info.non_straight_penalty = 1.4; - info.reverse_penalty = 2.1; - info.minimum_turning_radius = 4.0; // in grid coordinates - unsigned int size_theta = 72; - nav2_smac_planner::AStarAlgorithm a_star( - nav2_smac_planner::MotionModel::DUBIN, info); - int max_iterations = 1000000; - float tolerance = 0.0; - int it_on_approach = 1000000000; - int num_it = 0; - a_star.initialize(false, max_iterations, it_on_approach); - a_star.setFootprint(nav2_costmap_2d::Footprint(), true); - a_star.createGraph(costmap->getSizeInCellsX(), costmap->getSizeInCellsY(), size_theta, costmap); - a_star.setStart(10u, 10u, 0u); - a_star.setGoal(80u, 80u, 40u); - nav2_smac_planner::NodeSE2::CoordinateVector plan; - EXPECT_TRUE(a_star.createPath(plan, num_it, tolerance)); - - // populate our smoothing paths - std::vector path; - std::vector initial_path; - for (unsigned int i = 0; i != plan.size(); i++) { - path.push_back(Eigen::Vector2d(plan[i].x, plan[i].y)); - initial_path.push_back(Eigen::Vector2d(plan[i].x, plan[i].y)); - } - - nav2_smac_planner::OptimizerParams params; - params.debug = true; - params.get(node2D.get(), "test"); - - nav2_smac_planner::SmootherParams smoother_params; - smoother_params.get(node2D.get(), "test"); - smoother_params.max_curvature = 5.0; - smoother_params.curvature_weight = 30.0; - smoother_params.distance_weight = 0.0; - smoother_params.smooth_weight = 00.0; - smoother_params.costmap_weight = 0.025; - - nav2_smac_planner::Smoother smoother; - smoother.initialize(params); - smoother.smooth(path, costmap, smoother_params); - - // kept at the right size - EXPECT_EQ(path.size(), 73u); - - for (unsigned int i = 1; i != path.size() - 1; i++) { - // check distance between points is in a good range - EXPECT_NEAR( - hypot(path[i][0] - path[i + 1][0], path[i][1] - path[i + 1][1]), 1.407170, 0.5); - } - - delete costmap; -}