From 4dfadb0eb1312d89808f28cdc30367b83e3c1d0f Mon Sep 17 00:00:00 2001 From: jcobano Date: Wed, 24 Jul 2024 13:14:04 +0200 Subject: [PATCH] semantic planners added --- CMakeLists.txt | 12 +- include/Planners/AStarSemantic.hpp | 66 ++++ include/Planners/AStarSemanticCost.hpp | 66 ++++ include/Planners/LazyThetaStarSemantic.hpp | 89 +++++ .../Planners/LazyThetaStarSemanticCost.hpp | 91 +++++ include/Planners/ThetaStarSemantic.hpp | 95 +++++ include/Planners/ThetaStarSemanticCost.hpp | 95 +++++ launch/simulator_atlas.launch | 2 +- resources/3dmaps/Atlas_8_puertas_02.bt | Bin 0 -> 868740 bytes src/Planners/AStarSemantic.cpp | 148 ++++++++ src/Planners/AStarSemanticCost.cpp | 148 ++++++++ src/Planners/LazyThetaStarSemantic.cpp | 297 +++++++++++++++ src/Planners/LazyThetaStarSemanticCost.cpp | 332 +++++++++++++++++ src/Planners/ThetaStarSemantic.cpp | 276 ++++++++++++++ src/Planners/ThetaStarSemanticCost.cpp | 345 ++++++++++++++++++ src/ROS/planner_ros_node.cpp | 25 ++ 16 files changed, 2083 insertions(+), 4 deletions(-) create mode 100755 include/Planners/AStarSemantic.hpp create mode 100755 include/Planners/AStarSemanticCost.hpp create mode 100755 include/Planners/LazyThetaStarSemantic.hpp create mode 100755 include/Planners/LazyThetaStarSemanticCost.hpp create mode 100755 include/Planners/ThetaStarSemantic.hpp create mode 100755 include/Planners/ThetaStarSemanticCost.hpp create mode 100644 resources/3dmaps/Atlas_8_puertas_02.bt create mode 100644 src/Planners/AStarSemantic.cpp create mode 100644 src/Planners/AStarSemanticCost.cpp create mode 100644 src/Planners/LazyThetaStarSemantic.cpp create mode 100644 src/Planners/LazyThetaStarSemanticCost.cpp create mode 100644 src/Planners/ThetaStarSemantic.cpp create mode 100644 src/Planners/ThetaStarSemanticCost.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 54e266b..ec85f6d 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -100,7 +100,7 @@ generate_messages( ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( INCLUDE_DIRS include - LIBRARIES AlgorithmBase AStar AStar_Gradient AStar_EDF AStarM1 AStarM2 ThetaStar ThetaStarM1 ThetaStarM2 LazyThetaStar LazyThetaStarM1 LazyThetaStarM1Mod LazyThetaStarM2 LazyThetaStar_Gradient LazyThetaStar_EDF + LIBRARIES AlgorithmBase AStar AStarSemantic AStarSemanticCost AStar_Gradient AStar_EDF AStarM1 AStarM2 ThetaStar ThetaStarSemantic ThetaStarSemanticCost ThetaStarM1 ThetaStarM2 LazyThetaStar LazyThetaStarSemantic LazyThetaStarSemanticCost LazyThetaStarM1 LazyThetaStarM1Mod LazyThetaStarM2 LazyThetaStar_Gradient LazyThetaStar_EDF # CATKIN_DEPENDS std_msgs visualization_msgs geometry_msgs nav_msgs roscpp message_runtime costmap_2d grid_message # DEPENDS system_lib @@ -156,12 +156,18 @@ add_library(AStar src/Planners/AStar.cpp add_library(AStar_Gradient src/Planners/AStar_Gradient.cpp ) add_library(AStar_EDF src/Planners/AStar_EDF.cpp ) +add_library(AStarSemantic src/Planners/AStarSemantic.cpp ) +add_library(AStarSemanticCost src/Planners/AStarSemanticCost.cpp ) add_library(AStarM1 src/Planners/AStarM1.cpp ) add_library(AStarM2 src/Planners/AStarM2.cpp ) add_library(ThetaStar src/Planners/ThetaStar.cpp ) +add_library(ThetaStarSemantic src/Planners/ThetaStarSemantic.cpp ) +add_library(ThetaStarSemanticCost src/Planners/ThetaStarSemanticCost.cpp ) add_library(ThetaStarM1 src/Planners/ThetaStarM1.cpp ) add_library(ThetaStarM2 src/Planners/ThetaStarM2.cpp ) add_library(LazyThetaStar src/Planners/LazyThetaStar.cpp ) +add_library(LazyThetaStarSemantic src/Planners/LazyThetaStarSemantic.cpp ) +add_library(LazyThetaStarSemanticCost src/Planners/LazyThetaStarSemanticCost.cpp ) add_library(LazyThetaStarM1 src/Planners/LazyThetaStarM1.cpp ) add_library(LazyThetaStarM1Mod src/Planners/LazyThetaStarM1Mod.cpp ) add_library(LazyThetaStarM2 src/Planners/LazyThetaStarM2.cpp ) @@ -170,7 +176,7 @@ add_library(LazyThetaStar_EDF src/Planners/LazyThetaStar_EDF.cpp ) -list(APPEND ${PROJECT_NAME}_LIBRARIES AlgorithmBase AStar AStar_Gradient AStar_EDF AStarM1 AStarM2 ThetaStar ThetaStarM1 ThetaStarM2 LazyThetaStar LazyThetaStarM1 LazyThetaStarM1Mod LazyThetaStarM2 LazyThetaStar_Gradient LazyThetaStar_EDF) +list(APPEND ${PROJECT_NAME}_LIBRARIES AlgorithmBase AStar AStarSemantic AStarSemanticCost AStar_Gradient AStar_EDF AStarM1 AStarM2 ThetaStar ThetaStarSemantic ThetaStarSemanticCost ThetaStarM1 ThetaStarM2 LazyThetaStar LazyThetaStarSemantic LazyThetaStarSemanticCost LazyThetaStarM1 LazyThetaStarM1Mod LazyThetaStarM2 LazyThetaStar_Gradient LazyThetaStar_EDF) target_link_libraries(${${PROJECT_NAME}_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) add_dependencies( ${${PROJECT_NAME}_LIBRARIES} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) list(APPEND ${PROJECT_NAME}_TARGETS ${${PROJECT_NAME}_LIBRARIES}) @@ -232,4 +238,4 @@ else() ) endif() -unset(BUILD_ROS_SUPPORT CACHE) +unset(BUILD_ROS_SUPPORT CACHE) \ No newline at end of file diff --git a/include/Planners/AStarSemantic.hpp b/include/Planners/AStarSemantic.hpp new file mode 100755 index 0000000..689a18e --- /dev/null +++ b/include/Planners/AStarSemantic.hpp @@ -0,0 +1,66 @@ +#ifndef ASTARSemantic_HPP +#define ASTARSemantic_HPP +/** + * @file AStarSemantic.hpp + * @author Jose Antonio Cobano (jacobsua@upo.es) + * + * @brief This algorithm is a variation of the A*. The only + * difference is that it reimplements the computeG method adding the + * following cost term to the resturned result: + * + * auto cost_term = static_cast(cost_weight_ * _suc * dist_scale_factor_reduced_); + * + * @version 0.1 + * @date 2024-01-23 + * + * @copyright Copyright (c) 2021 + * + */ +#include + +namespace Planners{ + + /** + * @brief + * + */ + class AStarSemantic : public AStar + { + + public: + /** + * @brief Construct a new AStarSemantic object + * @param _use_3d This parameter allows the user to choose between + * planning on a plane (8 directions possibles) + * or in the 3D full space (26 directions) + * @param _name Algorithm name stored internally + * + */ + AStarSemantic(bool _use_3d, std::string _name ); + + /** + * @brief Construct a new Cost Aware A Star M1 object + * + * @param _use_3d + */ + AStarSemantic(bool _use_3d); + + protected: + + /** + * @brief Overrided ComputeG function. + * + * @param _current Pointer to the current node + * @param _suc Pointer to the successor node + * @param _n_i The index of the direction in the directions vector. + * Depending on this index, the distance wi + * @param _dirs Number of directions used (to distinguish between 2D and 3D) + * @return unsigned int The G Value calculated by the function + */ + inline virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override; + + }; + +} + +#endif diff --git a/include/Planners/AStarSemanticCost.hpp b/include/Planners/AStarSemanticCost.hpp new file mode 100755 index 0000000..48b3be1 --- /dev/null +++ b/include/Planners/AStarSemanticCost.hpp @@ -0,0 +1,66 @@ +#ifndef ASTARSemanticCost_HPP +#define ASTARSemanticCost_HPP +/** + * @file AStarSemantic.hpp + * @author Jose Antonio Cobano (jacobsua@upo.es) + * + * @brief This algorithm is a variation of the A*. The only + * difference is that it reimplements the computeG method adding the + * following cost term to the resturned result: + * + * auto cost_term = static_cast(cost_weight_ * _suc * dist_scale_factor_reduced_); + * + * @version 0.1 + * @date 2024-01-23 + * + * @copyright Copyright (c) 2021 + * + */ +#include + +namespace Planners{ + + /** + * @brief + * + */ + class AStarSemanticCost : public AStar + { + + public: + /** + * @brief Construct a new AStarSemantic object + * @param _use_3d This parameter allows the user to choose between + * planning on a plane (8 directions possibles) + * or in the 3D full space (26 directions) + * @param _name Algorithm name stored internally + * + */ + AStarSemanticCost(bool _use_3d, std::string _name ); + + /** + * @brief Construct a new Cost Aware A Star M1 object + * + * @param _use_3d + */ + AStarSemanticCost(bool _use_3d); + + protected: + + /** + * @brief Overrided ComputeG function. + * + * @param _current Pointer to the current node + * @param _suc Pointer to the successor node + * @param _n_i The index of the direction in the directions vector. + * Depending on this index, the distance wi + * @param _dirs Number of directions used (to distinguish between 2D and 3D) + * @return unsigned int The G Value calculated by the function + */ + inline virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override; + + }; + +} + +#endif diff --git a/include/Planners/LazyThetaStarSemantic.hpp b/include/Planners/LazyThetaStarSemantic.hpp new file mode 100755 index 0000000..bd4202d --- /dev/null +++ b/include/Planners/LazyThetaStarSemantic.hpp @@ -0,0 +1,89 @@ +#ifndef LAZYTHETASTARSEMANTIC_HPP +#define LAZYTHETASTARSEMANTIC_HPP +/** + * @file LazyThetaStarSemantic.hpp + * @author Jose Antonio Cobano (jacobsua@upo.es) + * @brief + * @version 0.1 + * @date 2024-01-23 + * + * @copyright Copyright (c) 2024 + * + */ +#include + +namespace Planners +{ + /** + * @brief Lazy Theta* Algorithm Class + * + */ + class LazyThetaStarSemantic : public ThetaStarSemantic + { + + public: + + /** + * @brief Construct a new Semantic Lazy Theta Star object + * + * @param _use_3d This parameter allows the user to choose between planning on a plane + * (8 directions possibles) or in the 3D full space (26 directions) + * @param _name Algorithm name stored internally + * + */ + LazyThetaStarSemantic(bool _use_3d, std::string _name ); + + /** + * @brief Construct a new Semantic Lazy Theta Star object + * + * @param _use_3d + */ + LazyThetaStarSemantic(bool _use_3d); + + /** + * @brief + * + * @param _source + * @param _target + * @return PathData + */ + virtual PathData findPath(const Vec3i &_source, const Vec3i &_target) override; + + protected: + + /** + * @brief Compute cost function of the Lazy version of the algorithm + * + * @param _s_aux Pointer to first node + * @param _s2_aux Pointer to second node + */ + inline virtual void ComputeCost(Node *_s_aux, Node *_s2_aux) override; + + /** + * @brief SetVertex function + * Line of sight is checked inside this function + * @param _s_aux + */ + virtual void SetVertex(Node *_s_aux); + + /** + * @brief + * + * @param _current + * @param _suc + * @param _n_i + * @param _dirs + * @return unsigned int + */ + inline virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override; + + // Variable to ensure that the los is true between the parent of the current and one neighbour, so SetVertex function should not be executed + bool los_neighbour_{false}; /*!< TODO Comment */ + int coef=3; + + + }; + +} + +#endif diff --git a/include/Planners/LazyThetaStarSemanticCost.hpp b/include/Planners/LazyThetaStarSemanticCost.hpp new file mode 100755 index 0000000..64e7778 --- /dev/null +++ b/include/Planners/LazyThetaStarSemanticCost.hpp @@ -0,0 +1,91 @@ +#ifndef LAZYTHETASTARSEMANTICCOST_HPP +#define LAZYTHETASTARSEMANTICCOST_HPP +/** + * @file LazyThetaStarSemantic.hpp + * @author Jose Antonio Cobano (jacobsua@upo.es) + * @brief + * @version 0.1 + * @date 2024-01-23 + * + * @copyright Copyright (c) 2024 + * + */ +#include +// #include + +namespace Planners +{ + /** + * @brief Lazy Theta* Algorithm Class + * + */ + class LazyThetaStarSemanticCost : public ThetaStarSemanticCost + // class LazyThetaStarSemanticCost : public ThetaStarSemantic + { + + public: + + /** + * @brief Construct a new Semantic Lazy Theta Star object + * + * @param _use_3d This parameter allows the user to choose between planning on a plane + * (8 directions possibles) or in the 3D full space (26 directions) + * @param _name Algorithm name stored internally + * + */ + LazyThetaStarSemanticCost(bool _use_3d, std::string _name ); + + /** + * @brief Construct a new Semantic Lazy Theta Star object + * + * @param _use_3d + */ + LazyThetaStarSemanticCost(bool _use_3d); + + /** + * @brief + * + * @param _source + * @param _target + * @return PathData + */ + virtual PathData findPath(const Vec3i &_source, const Vec3i &_target) override; + + protected: + + /** + * @brief Compute cost function of the Lazy version of the algorithm + * + * @param _s_aux Pointer to first node + * @param _s2_aux Pointer to second node + */ + inline virtual void ComputeCost(Node *_s_aux, Node *_s2_aux) override; + + /** + * @brief SetVertex function + * Line of sight is checked inside this function + * @param _s_aux + */ + virtual void SetVertex(Node *_s_aux); + + /** + * @brief + * + * @param _current + * @param _suc + * @param _n_i + * @param _dirs + * @return unsigned int + */ + inline virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override; + + // Variable to ensure that the los is true between the parent of the current and one neighbour, so SetVertex function should not be executed + bool los_neighbour_{false}; /*!< TODO Comment */ + int coef=3; + + + }; + +} + +#endif diff --git a/include/Planners/ThetaStarSemantic.hpp b/include/Planners/ThetaStarSemantic.hpp new file mode 100755 index 0000000..6e12c1f --- /dev/null +++ b/include/Planners/ThetaStarSemantic.hpp @@ -0,0 +1,95 @@ +#ifndef THETASTARSEMANTIC_HPP +#define THETASTARSEMANTIC_HPP +/** + * @file ThetaStarSemantic.hpp + * @author Jose Antonio Cobano (jacobsua@upo.es) + * + * @brief This header declares the functions and class + * associated to the Semantic Theta* Algorithm. It inherits + * from the original Theta* algorithm and override two functions: + * 1. ComputeCost + * 2. ComputeG + * + * @version 0.1 + * @date 2024-01-23 + * + * @copyright Copyright (c) 2021 + * + */ +#include + +namespace Planners +{ + + /** + * @brief Theta* Algorithm Class + * + */ + class ThetaStarSemantic : public ThetaStar + { + + public: + + /** + * @brief Construct a new Semantic Theta Star object + * + * @param _use_3d This parameter allows the user to choose between planning on + * a plane (8 directions possibles) or in the 3D full space (26 directions) + * @param _name Algorithm name stored internally + * + */ + ThetaStarSemantic(bool _use_3d, std::string _name ); + + /** + * @brief Construct a new Semantic Theta Star object + * + * @param _use_3d + */ + ThetaStarSemantic(bool _use_3d); + + + protected: + + /** + * @brief Compute cost algorithm function + * + * @param _s_aux Pointer to first node + * @param _s2_aux Pointer to the second node + */ + inline virtual void ComputeCost(Node *_s_aux, Node *_s2_aux) override; + + /** + * @brief Compute edge distance + * + * @param _checked_nodes + * @param _s + * @param _s2 + * @return unsigned int + */ + virtual unsigned int ComputeSemanticEdgeCost(const utils::CoordinateListPtr _checked_nodes, const Node* _s, const Node* _s2); + + + /** + * @brief This functions implements the algorithm G function. The difference + * with the original A* function is that the returned G value here is composed of three terms: + * 1. Dist between the current and successor (1, sqrt(2) or sqrt(3)) + * 2. The G value of the current node (How does it cost to reach to the current) + * 3. The edge_neighbour cost which is calculated as the averaged between the _current and _suc cost + * scaled with the value dist_scale_factor_reduced_ + * + * + * @param _current Pointer to the current node + * @param _suc Pointer to the successor node + * @param _n_i The index of the direction in the directions vector. + * Depending on this index, the distance wi + * @param _dirs Number of directions used (to distinguish between 2D and 3D) + * @return unsigned int The G Value calculated by the function + */ + virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override; + int coef=10; + + }; + +} + +#endif diff --git a/include/Planners/ThetaStarSemanticCost.hpp b/include/Planners/ThetaStarSemanticCost.hpp new file mode 100755 index 0000000..21b2cdf --- /dev/null +++ b/include/Planners/ThetaStarSemanticCost.hpp @@ -0,0 +1,95 @@ +#ifndef THETASTARSEMANTICCOST_HPP +#define THETASTARSEMANTICCOST_HPP +/** + * @file ThetaStarSemantic.hpp + * @author Jose Antonio Cobano (jacobsua@upo.es) + * + * @brief This header declares the functions and class + * associated to the Semantic Theta* Algorithm. It inherits + * from the original Theta* algorithm and override two functions: + * 1. ComputeCost + * 2. ComputeG + * + * @version 0.1 + * @date 2024-01-23 + * + * @copyright Copyright (c) 2021 + * + */ +#include + +namespace Planners +{ + + /** + * @brief Theta* Algorithm Class + * + */ + class ThetaStarSemanticCost : public ThetaStar + { + + public: + + /** + * @brief Construct a new Semantic Theta Star object + * + * @param _use_3d This parameter allows the user to choose between planning on + * a plane (8 directions possibles) or in the 3D full space (26 directions) + * @param _name Algorithm name stored internally + * + */ + ThetaStarSemanticCost(bool _use_3d, std::string _name ); + + /** + * @brief Construct a new Semantic Theta Star object + * + * @param _use_3d + */ + ThetaStarSemanticCost(bool _use_3d); + + + protected: + + /** + * @brief Compute cost algorithm function + * + * @param _s_aux Pointer to first node + * @param _s2_aux Pointer to the second node + */ + inline virtual void ComputeCost(Node *_s_aux, Node *_s2_aux) override; + + /** + * @brief Compute edge distance + * + * @param _checked_nodes + * @param _s + * @param _s2 + * @return unsigned int + */ + virtual unsigned int ComputeSemanticEdgeCost(const utils::CoordinateListPtr _checked_nodes, const Node* _s, const Node* _s2); + + + /** + * @brief This functions implements the algorithm G function. The difference + * with the original A* function is that the returned G value here is composed of three terms: + * 1. Dist between the current and successor (1, sqrt(2) or sqrt(3)) + * 2. The G value of the current node (How does it cost to reach to the current) + * 3. The edge_neighbour cost which is calculated as the averaged between the _current and _suc cost + * scaled with the value dist_scale_factor_reduced_ + * + * + * @param _current Pointer to the current node + * @param _suc Pointer to the successor node + * @param _n_i The index of the direction in the directions vector. + * Depending on this index, the distance wi + * @param _dirs Number of directions used (to distinguish between 2D and 3D) + * @return unsigned int The G Value calculated by the function + */ + virtual unsigned int computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs) override; + int coef=10; + + }; + +} + +#endif diff --git a/launch/simulator_atlas.launch b/launch/simulator_atlas.launch index 5339339..2dc8792 100755 --- a/launch/simulator_atlas.launch +++ b/launch/simulator_atlas.launch @@ -49,7 +49,7 @@ - + diff --git a/resources/3dmaps/Atlas_8_puertas_02.bt b/resources/3dmaps/Atlas_8_puertas_02.bt new file mode 100644 index 0000000000000000000000000000000000000000..b323c08596ac955e841b62dd904cc45f7b76e388 GIT binary patch literal 868740 zcmeFaPmg8kapspzvH-b3qgOOwuiBi=h%jtoI0MX1y)f6VMOP0hF-C(ks`TW+j7E@T z1NKIOS7WaR19ZVvE1EzRRQW0R0R(Vmc&V?@fY8uJa{B$9=SDu~W=2M4WY^17HBVhs zX59GmJQ4B6`Frop`;R{TAO7{9{ri9Si$5N}KmU^#FFyTO=YRBzKlxujJv;xmFFyW9 zpZ?>s7cc(pr)L=c?B9R-i$DCsPyf45|MkE5#UK4oFFyU(|Nh_oyBB}-XMg(NeEP5c z=Rf=O-@f?8|1y03&5IHFCx1Ggpa0Q|Pk-^JpPv8Or{{nAU;qBc|LEiMKRi%;{HN#t z+lx>C$v^$+&wlz(|M|y%^5RcF{po-EPd@&`U;NoGKK`q}I{E40@%72g$J3K%CzmIm zo$wp!*F*k#eRjEOq~&MWe?6?=e7^cCj>yZQM~7_xOuEbNm|u^4$ma8v@$c5Wz!wja ztlJ74Z3#bW{JZfJZJq%YC?>aW@hsQUT}Y0mgML;^kL#&bIqoPE@po&NKOc2ueau!b zs}dwu-2QjXrD4y zbv3IX(>-?gADchxNv4aVfcMVqB|lsDl5sW>adC8DFUm1k`!=6Lyq|rXjz8?D^W#q( z`^9$qSwLic*Gk-FHxBh5AJxc}EVt(}_NTX;hlP*NtnNC~F~*!hs7({(UAz8P1hn}fOUtFvBbx=#N)z8P1hn}azAHOoKKb=dbw%{rLr zdR@&BGF=BXi_df&%#LrymFebSGO2Trvl=p8hrQ#Qab>zWm~&9G{4-sLz2lp4Wx6?- z`=n;Q&UBsrcYHIhOg9H}4r-Qvrt7fplbUrf)AhQVA!ND^Y8IdAI+z{bj4RX4!Q3Y` z>vg8PrTH4?Hq08%x+!B^Fz5y#_IrDP3|q~{S5q$HO*_zweFOqc;z}< zZ@&`b6?3Ge`?GaCJHF1PmgZp2L9HvX_5SR7l_|D4z1pSMnRriz?_CErws?if^OkMh z5wXo>D`$4=*ekJLQhu6qPuy|7IqKc-OPcZSqdXVaW$D8@gXq-d8f$3|<{Z?z5?ed$ z9bYrl(j3e=sC6Z_cGy3xt;#jlQl|qolC2%gj;|SNX%6Nb)VdN|JM4O`Uq>>Ia{0M1 z=U_g%nkgi`FF;319VO%4uUPVT*07D-JhJDx=h|T3TDRw+Lf={)k!x+YG{^IPS31h# zt_<$7KdhEHsLrL9I_w?an$^}hm~&8_buD$+_aj){OIv$gbzCiVP-`SxJD43`Gt|-? zOpaMPe&ttE*%2+vlcOK+?~LPIb^SSO>zLD_tlCW1Vej~6T$yeT=H=Cj-i3dc-8s+k zoP+ADYpKKD@vT{Hor5_C)mhh4hke#QrOwdSUapR-r4DM1WNQbr<7{q|+Cgm1BEsLr~UI_$s2Nqze4bLIWb`mU6m`C$9evnTS!t5c7n zZu?ZFtt;mGPN9wT2oR;UIU*^iB4tvKpmd+wWQGu<4_IjC9wnXbb=bKgCxE+*yr zdELo3>!kku)j4I>+09v9dVc4ayO_T`?7g!}WV`aXgK5iYxt5CT4tY5~%P`mFS|eHN zcy@fvP)l<#^RE8&XY1M7(OF{3@3T0rf)3|%spq;zRJgTn<-4lSe82gKsBaGIf6ap$ zVhj0^(DQ1q#pP%RZI-4|ln{j2jIhb=$v-~q% zhkc*atb>`Z*VPOm({)g@_)OQq?D%F}nQjgylR5`Et0B{M*gL)%SEieTIR`b%Kht&C zJH8oLrkjJgPiofdOxNju$2a53baOE0pl11Jx(@q3saXdzU9YPdLZ<7WX7QP>gW2)T zxH8=w%zaX`UT3;a|2w`JSEieTIR`b%Kht&CnbeMd#+T{lV9r6!^3QY~_Kt7HmFebS z&Oy!c&vYI3eNwXyX1ZQiGlWdnLCxYbT?ez{n{j2j0`s%OYmCl{@hbe)KJ~iA zuYy}T`Ey=L9Is4%saF(jSzpT}=UH#5(iI_p~MuwU&p*Y&?E@-Dmcn&UYK)mhh4hrQ!lv)Yu=? zGXBEUkgm{tR=8FqhIKkq%T=5ajxx&Z)@^gQHj_G@9p8*A)6K!0gPP@^={oEk-;68M z&B6TbZS#5lxi+uAVY$$lr0)U$Ej^8TB`c z)jR&`dGs&)dyCm1BEsLr~UI_w?an$^}BnCxxhZ@Fjl%D$87 z-F|<8_f>gDxz=@9>UidV#n4!mI;f7SrTb%YG>GGhj>_(9#&Q2+q>eK_F8Qc+bB%JQ zOq=QMUv2N4A>+z)9sVpn(|uT(&gnqbmrU1T@Azh1nQji|9MmlTOxI!W_-0(0ZVu*$ zwN+(($#ipil`&b#JVSpme&Q=1ws$={AIQNIncxlM#UVTFZx1py<;>61@js$p4k=`E zz*9(M7yL*t3RBslQw2z`)=WXZIC-;r;(NYkemQ=thRb1F4mw4X$>oY;R4^{rEXB(6 z;D0kDdDWor!djI9BZYT@J3Qs)h9e+jbD!(zCP6R)rgA9)rHG-{okJatMU6U zhK)FW9<#hkjfR>zm=l>Z3awvFI*NzF0lP>^gaV zdGdVxl*G0otgR<&B>U-=#PenRk9uH~ybOM(@a6cgDI`~Qk@bvBg&;kg%ZOTrr#y&R z#&m#+)mkjfgSHXYo0!wpQ+^;xf@@i2&8TEBiD9)OXJslT>C^{&d3fJZOONgO*!*>O zY~6e6Uer=&MZf!9&5q_@jjb8|L#t>12FAA2;$ctnP}KLgsx^|W56$$|x;JGHX{=Xc z|Ee>bt=9HT+IqekM**#gJvrk-ubytb?UPB5?fKaJSx++EL)SmUvTjcGb5NaiEp^zx z`(1rC&a-tM?yhP3|91P-=j%S%m^>HH??O+hmHxSY_NUTqwYF!{)|1%l>-2nR0#o}{ zp7G!;mh*0oVLa!2oO9{8GT|ILWX_9qzKg`;a`+!AF2sC zu1mP~L<@HGA+AKk&sAnzONEEf0yQ$_N^`m5icV>bh){N9wG3Hys)AoRfy8R@40iPq zS?ez;x}&REdE#+;h?6~hg~d-@KjFEo53!yeG6_~PLXLIPH7L^or+TZ6#feg)Z#yDl1~J5+_N~Vw22IP5&~a^MfaAM+`_ItNYx2 zz!ob3wk9PQv_kF>=S?wx?iFm#>hvf-EV6IZw(Gu0UY#swj0A#(b^llsqM! z4<_o+{X%#HQ`7FRz+!x66&(*sF2ms-UlzQ zgCuP!VGkrS7bZU?DHp9i>#P_bk44txOjY2}lUc0FkzB9Op*vmVoQ#Eq^}hw|1@Syf9*PmX&^HDE1=^D_M2tb6yf;j3e2q@+y^|D5f?{V5ZI>hLn2e=LaPrF8a$SPsZ8IUyjVRnKk_A-{(}z|G5G7=F;?Y- zo%*no$J-Gl2`;R$MQEmpL#qe*aqMN=_KI=uT<=lUt5Lkt#4BR)idptv#;>nl9jm@w z`ugi?yqfjd;Z-=DU2o5)w{mvwZQXr6_1>K9-Lif!jovT1{bp~X^je|&kuz@JCFSfg zY5VP)=FUAcZKlg}`nH~PP_wKuU5B0Niq~jk3R$`|#D&p6j+wa@XKgPP@^={oEk z-;68M&B5gCB4f*RkL~%`{8>*j-QLrzE19mdqI*}f4raPuS2Ki6*FnwVGhGL>##Ga9si6k)6K!0gPP@^={oEk-;68M&B2_5 zn&qGAI_&$TW*y9Qy{={mnXZGH#b>$>X2&<<%5-xu_esrqo#{IL@Azh1nQji|9MmlT zOxI!GCpGI}rt5VzL&$U;)GR*Jbuc@=8CRy8gUQ{{_zV{JD0!u6`$|jBy1jFnO^?m*PSnzewfcKkwVHSJ;V!#p;=@{h=Uq#k`fDUxJDBl_XO4N< z`y}#Xy}2xPSRGYM`=#IjGLMmOAWAYRA83wsj8X z98_mrOC9!(Z_R4!9LzbW&bpR5?E9qFy|lI0Rmas*2en4BwS(F5HA5}U!Q3ac?z*j= z{&#%MP)l<#=b+Y=*xF&=C)ItcrCwKSEL%IMj;f^&X2-W?wRH|AlR5|4nb%T>z2jT6 z+Byew4yv=Rr4Dm1BEsLr~UI_&$T*1fc~*Hy>WQU|q0vbBTR@ijv& z&B5F!weGsDo&I-x%}`5oFz2AwmDt*0XHq-bP3!pw>vXb}&1>W~ik(m`v&%h=u;lBK4tz%?!dnSKy@Okp= zqi3H;W)<_U?lYYCg^peCTE{c-{aTYWP?@CTXZfDw*yrm%*HjXJa_N<|l&|q8mrU=E znB4Kuvvqo|*SFf&Nl9nf+mNL^@3D=2rv82Q?09P$d9T?7|N87BCiO(rG1){ zxyz^G7H!twbQ*4npTnPJmFYgLOdq>fSqC%Sht<`rf=u_=-G6NUtS6aH`_vC9+pLOA z_t-Th{KrSj!@1{=bndwx!P9MVoF(#C9L7=p^Ysk%##v&*^d9!#SE#?{??tQ~9_P#7 ztkRQ{^{Bo*H@S8;b96RjKT9LSD~3Czj^`}gY{oKOFV_qq({)g@_)OQpytcYuY97|} z%`v~XoqhUD($XDgh>e^ghr6dIt_nG~KHdiN*khl|zaD4ipP#JTDO+G3bBp#{_I;pE z>B#+i*YMmk)oS0>hr8^anGb9AJ9W9nTAG772eq!m)((5e*9^5Z2XhW;U5Tw7cDAYy zYs+$-wbbcCjbv*Fv*T-qTAG772eq!m)(-nVsqR}X^}1SP+1f#MR4sKdJH9omt#dH< zNp**7snh?CZ_R4!9LzbW&bpR5?E9qFy|lI0Rmas*2en4BwS(F5HA5}U!DLeBAlKE{ z+F|ebnxU5FV9r6UE3vi1-tjd(i)|J@WVc#d!eXFHj zS8FU=JE)GTr4DAtw`R3<4(2|o?r<%2`rq-bS#6zzIS18Q*HVX_N$vR8%(lKK%<&3l ze8bWD4!hr8w%1-eJ$hw4&ti>OJMi?`=g<7wDc)DFz_0HSJ${z=|Jdi~6?k{q(tGOn zQ7)bLGyeT}#c|Ze>yF2-6(1o^&X-O%Uiox3wUl6bbuH!WepQ-xH~SgyH(etV^joU< zR-VVq>#O5bJ>Efmcy&BMKc2zkXXJjo(#Owc)bJiKlPcc>YCS);cG!Pwv-}?F@6_dP z)Y2TxIjD6dwszP%zGkSUIhgyT)?K%?)BldI8ER<`<{Z?z5?ed$Olrs9ET#18tM^)- zT>A{k_LzD6$)D={(r0^?*32j5K0d*6__nd}`Ij%_>}ed!pPl^Z?so|KJ$l#A`{Hci z>Qf|BIzMAI*G`w~9bNhd;5ntM*UlBcTtDwNI>I^Y_b*RA+SGs5r{kEv{oB>&M^B#} z-XVSEw~76hx&NALvK9BUvDG~t|9GbJ>TkZ`o!5M#$x=Qmw*Rwl4wdCw*|*F#XTL?8 zcPrCox(_SUyxVzQnKskS!JLDd<)7&~>>b~XE7Q%voP(O>pXoa6AJ$ftRh#KL9mwJ{ zT?ez{n{j2jIhb=$v-~q%hn-2)BSXq`9rP?d({(UAz8P1hn}azAHOoKKb=W(;8CRy8 zgSqcnvtDPqPX9Z;8CRy8gEE>YW zlbZE9({=ja@y)n0-5kt0s9FA*uEV~csdl=Rbvx7T+ke)TOxNlD-qoywnXcE>3?b8X zP_y_<*TL-gW?Y$W4(2|oS+6r)r~e(_j4RX4!JLDd<)7&~?E9o<9n5sSu4V|Cu7jGz zXSxn%$2a53baOD7)H%pm4VkXP-to=2GTj`^IjC9wnXbd$@y)n0-5kt)QnOxXx=#N) zz8P1hn}azAHOoKKb=dbw%{rLrdR@&BGF=BXi_df&%#LrymFebS?vtAJI@5Lf-|@}3 zGTj`^IjC9wnXbdmq;~u>zDzdvg8<^uObqab>zWm~&9G{4-sLeV^2;mFebS&Oy!c&vYI3@BXAdKUq#*om?DU zJ@Q<-POseSS10Eu@2+8fH8ihI-u_N({qCQ8qCTsBYinuS{Z}WiZ>-Z-W9^==ectz} z+g{zjt9N~_3gLZr?O9eeQiG-`|jU`o>Kq2YxT2F zME9^s<#_b^+HvaD$?3pcR!r?x&xhB=>h*4LE$cDtV*I{XCFwYRUJk5fJje&Tj-W*9 zScr5nj*NJ|U3Emke>(mvMxJ2vz?0uRzZ^d!4_Ot1by+>}xHx&UJ_Cnbg->3WgIRHb zs>N+bq zqFYwpz%l>ZfhFy-b{h7x15f0P{mo%bSOKStXuJCoJWn?FdiX-CuP* zRtgWT1ZzQ^^Z*%lZS`j>k}3d`^Hb%4ZdpCGO|j(#zWCYeME8y}m7Ns^0d8#xcnJqB z*(g5v>8Et`V;TR+blG@fN2~0KR-W?Qb_G9ds@nXDS60D~?#=4Cj11@*ny8;l&(=)Y zvJ|h01YLgON7kGzt3KFyCQn(l{_jq{IMk@Bv?l=J`S6A-yfqzxp{&1HC*3+EtrS@V z+j5W;b9R-L>~F_jSN(B}X69n7*ozehRIJO|0VFb%PLi@0KP#@jEo=5Kho|=Q$1A;! zr>9^@_vV1ESqOIJ4>k`xiHMa#ub#?&zIw!3dHcYM7GGICzkwC_c%q9;?Rj>H7LpJH zGxp&v0 zQ<&-lwX@3GuHy4{%%-w_ckBU4Q=PMV|>#?G)e;InT!q*Cg?tFA4j=pTq=+!^P@bkJ(c6E~6FUGb`_4pk} z)78^ei=JbvxHu2hdED9ftva?V4UVz2Pj#Kl39Mjp457o915x`qbzD~D<=}aK6$86C zwY@DPIv(}aoUIQ#TXuXVbuc@=8CRy8gE&Gee^xN)J>7RKxQ{C=UD9Ydzs?qtI-5xxd2fNw@WspV%W;kX4^DB`)}v zA;(qw>5WVkNiWV0Tx7bvrwPt6KZsFtbQQkvTvn{(82nfX-49t-Ogz9+EvgnB_uTMM zP0U1Kf$)6o3S8Px;Hila>g&;a?PI8o|J!X&jPit;YK5*fIUO3+q~ApI&`R)(wG9s; zpkq5#{j9F;DTbQp1eXPPa>#W_On%jT}KRM3deGUfJekf zPP%`^GqPe1CE1hvl;9}q7wbxBk0nnc=mV>|tkHPJnt;P`P|@cHbYiHEhxc%3rB^ig zL~G`SATGLsk0w=XZcaRxgPq(#RWxyuP7nM#A_z&xVU7r~$0kxS%2oXdjAe8Nw79Re ztXxb|tlM&6)4C|@m^3oP6AoucXVGml(3FB?9IW@o4@Xkt$R=1i(2Ze=-$=3 zm$vr0>bP3!pw>vXb}&1>W~ik(nERyGUAMK<|BkO2YH1GU9MrlJTRZIgq`Ggl)az=E zWorl3QMJ^;?D*EKw$8z1Qs*E$^IGb#cYJGBTjyZTL3P%()M4-V)~vS9!Q3a+9j>KL z|2w`ltF3b|=b$?4TI#UxlUn!E)?QZ~S4$n#8p+lUX2;hIwKNBFpVYeRws!j8@ijv& zm6*T2{Oq&M{l>)i_c1EOMHv^mi72qp2PPqKlqTEj)ep`LieAAnE6-xAW*Zrt;|4!ZCbMNZ?dv$-$yJp!)kL~%`{O&|8F{d9=u5~rGK6Xuy&F@as(ucMB z`?SuPt2wCk+yOQykmGbym-F* zJ@uzYUBCLQPbpYiOWU5(&ztKMx_zIz?bZFedY9)M)Elh-a=hxsD;U1_k)P4ozDnaR z$apPr&f0%@v`28pR~`9!yz;A8UdVi0pZ|#K@+X^DYz~=SMcjgzU_X-Q!!p(9{Q2~j zE8#Q#@i#fGt)=7m*s>j?J;?c?tJc@j7Pa&|epT)GneVw(<53hEA zet50?$v1RCKfgt$`r9eXwVoc1N=J7!SH4d!e>A4=M^~?kfBEGY&8OVU{BpcHIR3qQ z`tI4QXBWr!XAaL^J)zgyGizJYr?m9h#vt(pUtu)9HR9p zulQsbpHMR<5*B^_H9l>oPrKnF>YJ$dx_} z0ppW%cNhdUN>R=aOdg=WJpBEks85w}bdK&`3=gbm(D5KzsOkh*TIcvQUt~(0 zWMa<8f1=OUzn6xjcwwH7=d$zLQeaBQUyq2WW%a{zD@j(S$`ya&K#02ZDN8ic;Te(A z5<^aOPB`%yV%A=mnn~HIG}a7+=+v9TC#d;rPpUlJ2r@+|%WAsv%meFjUq<$$Vg z6C-`t@qB&q`-ho9OZKoXtAu@7vFQWbQ}9cR9o;WaeljF%vcEm~)ykx!REURLjI&xC{L%VAY_gv#G& z6aw23pTbpi%s)NA6EATo6ST{!S%!oqP{pNq^hjXxpE{T*?SDYxf%fbWkDopP3}0Z1 zUzySoMPa2Hbw@gRvQydLD_uqa5e)M5Q ze|Cxe+4AhokY0@67tfCDYj-0L{nZmP6zk~4cn9IhTGQyjIP2h?a{NVsr^{1(Hn|O6 zxGxT8CIjQ?>!;7Jo{gM|_+~v5Ad4Tpe)8@cUO{|9eox+xqr9p=8z_N0X6xWHs(f;x zh;e#D#KlMQJBM{dtn8~qUOZ=yNUi!?L4nU2#T281i#11nzWzqydGvwx(l(98TE%QV z>A`ZqR6m47j!4Q8iHQ*AF_&4Dm8_guk*V?&)~^PNGi9RQocyPuiA=Gg)s%XBm87gy zJzF1Jkvk}>(4#l_3JZpV#~)vQ{uIuq=g%&luK6)*UtgYlee&OrGtI9#+Z^81A9Kkb z0pFn+zOViz^L6nV^5A>Iw4Pxb(pd8~PWvC^E8c_W+R<@#`D~nBE>Fmx^;X87@*$0k z{_bRbAKI`#y^^*S(}mZEE$rRcu3kQSclGS`$m;dL*v39RSB-m6Kr%SoK^o{#C*o`T63d90|~E3WVE{OHM(*JIxGmn}xz`cOA` zhD2Yrj~aQVXVO>a-|MPqW%#*DM4XIGE1qXQ8{NIHTSjj8$L#ptA9aT3o~gQeS0C=O zdu`adI^K?~r8$@nL)E_BRO3$w|cW?(qnr*jGuc0TxV~i z-IJ|0tJ%7(=ksx-d$nH0+YaVe-otKI&_0>8#m(&2&GDRr>a1(2!`|_&S#6zzIS18Q z*HVZ5p?j70mqCqW>q9eT`@gyWi+y6JSI&jIB{wnI&uBmWFjV7b(j3f(p;G(J`nitM z8D^G$rrWaXp7HhLRIDAV&%@W+I>*Id5?3AM#6zB(^Nus>RjaEh&gYla&N;OH4lD8K zjC3sV7c1lVtE=>7ABxE8=uR~f=We>Qad*8NsuZ6i}`QS~w;^_FuPIufCsNwiIeQRv&+h$dwSSa z30x6Ht-6l{o3h7~b&C3xDOwo)JwICKWz{lgfqFi?z~Z+g>Wi)gs``eVdu*&M__~i7 z*>V2>Ss8?u7^2Ar9aSPpEBw=;F{ksu*O?N#Ma56P%ixSmwN;7>&XCA~wTkQl$y*=j z%9MS_vflSr_o-9Y(2AyiXGa~Q>g$<`UHn8NX*+=_CQNp1m(nR`N2_a^C{LYU;Sna= zre|7A>`h#~=A7r!Iahh}Qyt`IAdrJr6*lc3(8N7W{K(*R{9INk=2KM#8~0-63A!d; z{g3S=w60pQ>c4!o|J-_rce|3&LE^|rdsD($F!x z!aPPL=6Jqf5fZbe{ff3|b@U`x5Xf7TY}}BRVF#7pAP|EunAT~Xvwc2 z&Xc4S)^hN~Uopx9}U_Plt}9ASFagH!TRygYeLDK z>R+#~m{J8C%lI#JO`~4hrCV6Y3s2sqAY^{Z)321EV@B0OV#LKPqQ%Z5q&O?sYRN0k zoA6{}6$9$&`V3Th_Hx}Dsj3%4M?PeQr!b>qLXcJbzZ}R&@>HhuQCj*FG3P^P%;=8o z7BtF-kr6V+;^up<$vs)QPG=#;4>;gbtd${*jYLZ^mC&~Y zYi}xk@y6;ALoU{SJaB}>svz;4*ZT2{IAPHTJoqVTdxRy92UCMpSV+szEvp787-WYF zbZzzMTpcxQdsoc)2J>{qAy(TFS;4`xXXAJ5tzvaSMGk)D_wMBX8aidd-G<0%IiOV;{%TAtv&`%=(LY{g=32cDKS!wVu!Sya09RTh z{u9k_No;>eTTFVu6@_#WLxi>p)*$vP++&4(89&4Gbl7#|3shfE!lhLYe%Rm#M_Ii* z`M-w`{2<~Tdl-4*B~S0a@x(V6zZjBa;h&Cu?%R|9xa#6~A{4S0Kl>06VAQs(S%7s} zHNk(jvTd_67BTS(u;R4`AP?fV-H(dJsiPb*s#$$nu41&;jtY6U-GazjnZk2Atm>aw zmr=hY<)KV||DY45zDvn9;}5EEw5O719A&Xb&z1AV$;V@+*%!wI^P4&Tbo`h6{dEuh zvo%BYUVTtbFv5vW73uCCR&_6!VAo{1x4bWp?NIwXFzC{9=%{)RI-p&O#n@BfDPOV5L!F>wNM2=R{G^S$2gLB7?!kj3OzM}U)e$;6x}=J=WyG~9(;{?m z=o1s}o(e%8Se6xkS$Tsq_+O6xQLD1!+zL$XZ#b_)R;KigtoW&#H6_tKt+VXx(Kt){ z$?*Njke2bB|Dc1(9+^Ecll%Q4>o@Frz{(@C369fMCtj?wFB?y^u3x<-Yk4Yui_Ti8 zDt(WMJgJdAuD;Jl?64>!ub^vY|S6FnyzP+1}I3kj`|B>kVGL;uz42_8P`8+ZMJ zhfJ3hQ8l?zV$RnX)n1R)Xg`_v6Z)TEbIvPbYr0&KiE&rqJoQ6Y<(sIIufmo$ln`tygjQpX7KS`>q7mW4tTsLSVo2stxRDj6RsSHM@vqzb(5E- zgZt|4j#mN?FqiRPQp`hiGW4gz4nAGNUvn78EAB(+?#ac;|33K13V%f}>(MIs$s|~p zgG8Uf_EqW!Q8S z#EVDtjA&(z&vxSJ6WL0~-cgx?N|oqY+hs^FidE?7uGjx=^icZ?9T}NyWwK?ZN}+Rh z!rjNf(Y`@e*xgfevNHVF9LE{N&&Cl?*LPg=#d(IR*`kB9jQ`TXjwBv+iOj^!x@c<; z9ht=%N#>e&o8|dcG;64O;M2Sa=eRO@9djRms#l%=Y3O*c*W;m_sXMY?hO~_5REFo-kaeJSc<8?#k6(@l zKmTI9LlW)B2&mnXj-wog{PPfmVsXo&VJ$IDmGpItoX{m&O)|IOe!9qU2&x$b|xNE z^6gj4lP51PUcY%Z-iv&BdH&V;8ShSh_wMw~lh;qklk;KnbI#iH^R1`om=)F;PrRhn z+-M5e4@C5OtoxdKh#4%RA$ty9uk*@{Xf+6!`Cw5*t_i3y^spu*3wLwRdmwi8Bu+Vdz=zCTZK-cN}W zEWPtXSIcJHR3JxBj14}6A&|*ic;}Wd!NB1K8h$mBQiqUUHlLgV&QSoM_m+_nbv5ywN zR_(af?RFyuFt-yGT1^RFoFh%b<7vg$W*+s{N&TMUYGEDGXhorMrr)@|G;ObZ@ zNoQb@y|#FHYNeRiSK~Ml{B-Q?*o$-Rs!U_`o!@p9qPp!waQ+4^>&+f_SM3hN z2ZI#}du&BI_Y}WoGICZ7{W-mc>ip;p&jNipNUug!U~0>!Yg)aq(<|mhomQqo3M}|1o%!dwT+|!Y_4#B>8k&4X z^GtH>%}RcAU=l;v%@~^Nc*p*lAxF*0bw>Srrq@@N70-3KHk*)HE0u9&x?ZLo?~Eyyq_Fxp`VN+3tQ~%NXPy^9OpI>aeEB8 zZmnB6t0Q!AJUQm{8OrTAKR;q5OU{|LkyVWk&36{&?REY`%9Pborq{cF-1%7D>s1{` zv0_igis7yEo9q79Yd7w<^SsV$+)9eG7DvZf7G3#v8RgNrHp{W&+40S|GTj`^IjC9w znXbd$@y)n0-5kt)QnOxXx=#N)z8P1hn}azAHOoKKb=dbw%{rLrdR@&BGF=BXi_df& z%#LrymFebS?vtAJI@5Lf-|@}3GTj`^IjC9wnXbdmq;~u>zDzdvg8<^uObqab>zW zm~&9G{4-sLeV^2w)lD7m z((voh5u0)3x?FpcC*Q`l+a z-+<5fS@*MyZtC)P+wfkW-`?u^H8JwjYcQ^@mh`%sURk?|<98|j_NvMA&9yhz=#IjGLMmOAYFq}IK(wbxb0)lvtw zMzXbo+3__)EzQB)C$;Xnt)2dNe9cfxb1>(i)|J@WVP{f1{${DAIhb=$>q>0xuy=gT zP)l<#=b+Y=*xF&=C)ItcrCwKSEL%IMj;f^&X2-W?wRH~WKB?|-Ep__e@vT{Hor5_C z)mhh4hkc*ax|g>0y6U)E>Y&z0wstT(zGkSUIhai99OSwhTRZF>Uo+Iw9LzbWbtSfT z*gL*vsHHiW`=r)gx3$y%j;|SNX%6Nb)VdN|JM8uQZssotGpYNu*8Q}#*ICEaQU|q0vbBTR@ijv&&B5F! zweGsDo&I-x%}`5oFz2AwmDt*0-zU|5tEFC7Yb;wksE(?o4ra%$==02(Ja4mKE z-|?+kZJmQT2h~~EQiq*M?fBQsw$8zvgX*knsl(p!tyyiIgEbP3!pw>vXb}&1>W~ik(nERyGUAMK<|BkO2YH1GU9MrlJTRZIgq`Ggl)az=EWorl3 zQMJ^;?D*EKw$8z1Qs*E$^IGb#cYJGBTjyZTL3P%()M4-V)~vS9!Q3a+9j>KL|2w`l ztF3b|=b$?4TI#UxlUn!E)?QZ~S4$n#8p+lUX2;hIwKNBFpVYeRws!j8@ijv&&B2_5 zT32Fghn-37_?xAc=3vf2tt+v$!`|^VLoLn0oP%0dVrz$epH%m)mU>;Sv25+2I;xgB zm>u7m)z&$f`=q+Vwbbc<$G2v+bq?knRA*gF9rk@v>t5R0>#E~wse@W0+1kPE_?n@X z-an?lLE?67{Uv;7cDpA&w%+`vY3#>nH@}P8Jhfz=yQJIg$GO~pi{*PJlsP%-JDG20 z>+e5~Z*9Ik6QZ})t$Y)CYu(E4&vOoHou928_KvR^D(U9;ZQt~cznzWcxBU$%dBwT* zX6E{qlq~<7zQr#O<_0d%D+G5{bx0!fAO7S zx{j#6jpjae^KBbHzdC=Lk?$m1B|Qr+QN>h!j`+HaGUfSC0s^e;@gIXim+QIDjnxU5FVD6Jzciq-b|2w{BsHHiWb5QF_ zZ0)e`lj^?JQm?BumaQFBN7YgXv*TN{+WP)6;}x7a$Yg%}jnVPC{Ox?l{%l3J`+~o< zZe@2Zlit54cd1n!_q&CET#LRdx~j*oW|1>^epT!JXIy3SZ94nAoN285@k)9fvspyP ztAE?R&03q=_#e97yyGa|QAQ0vSZ80A9M^RH{c^WuavZhA_IuH`ow^N26+O1+WAoSD zvGqflH}d?Ddio*d>S?H@$FAwI`Rnf3x=(7hQrF*G?0(hKhtf?Q51)+VAocJ&&s^_m zz$e~?Th|{}-W%of%81Q5vi?85XP#Bmx3zBN%x>Kr&pD{hI;3nx!**8=kH4Px%arRQ zZ5ub=-FMqI66eh@JQ@G*U+ZtKuAPYGoO1haIdJZe_4uB5&45?nu{|G~-<_zX$6wPr zKU?=noikH&P`z%o)M4-V)~vS9!ThkcDtDun=JcxOv~};Pdr?cBb=tdH_tMs0R~=VN z9n>1h)(&RJ*9^5Z2XjCE&+2Qvnzqj2H-0UBSbM6+?p57OTR*I>I`3L~?Cw7{f88Bh z_kHS|m70Um1BEsLr~UI_&#iwbQM-@3!vS zzk5+jo$l{lt$S%}ud9x$r4DM1WNQbr<7yW7P#slE9n6kz&1&l$OeS>>vNNxx4tvM9X0>$=<{VUKT}vJIj&IFs z>m1B|Qr+QN>h!R@(!YgSw5VD6LZ4%bqr z{~h0&)z&$fb5NaiEp^!UNv(TnYp<)0tECQVjbv*Fv*T-qTAG8oPiozDTRZ*l_?n@X z=3vf2tt+v$!_K63{LNBJb1>(i)|J@WVej~wp_b-g&Oxm!v9-g#PpbP?OTDhvShjXh z9aT#m%#Lr(YU>=#eNx@wTI%$_<6E=ZItOzOsq>0xuy=gTP)l<#_erh0ZfmFi9bYrl(j3e= zsC6Z_cG&kxb>C{K*VP)!)()zpYN>ssotcYJGBTjyZTL3P%()M4KzweF>@y{a0P>w`R3<4(1$GXI)Dj_I*<8UfSC0s^e;@gIXim+QIDjnxU5FVD6Jzciq-b z|2w{BsHHiWb5QF_Z0)e`lj^?JQm?BumaQFBN7YgXv*TN{+Byf5Nu7i2%xkH`-tnzj zZJmQT2h~~EQir|cTeI3a2XmiPces{1{qOkJthUapj;)Y2TxeNyYL+uG@W$JY$CGzW7IYF&w~9d;(Q<8PK)nu9q9wXVe04tvMf z47D@|a}H`eNx@GTIzMR#Zn@kV0L_KR$J#_?vv^c*HWkd9p9SO);XAS zP@Q!xb=dbwt$S%}ud9x$r4DM1WNQbr<7m1B|Qr+QN>h!R@(!YgSw5VD6LZ4%bqr z{~h0&)z&$fb5NaiEp^zL)Q*46Z0j7%IjGLMmOAVm-@y{zq7{UrYOzRrkl%&N_8`%}`5oF!%MZyKZZz{~cd5)Y2TxIjD6dwszR} zNp;_9sn^vS%hnF6qiU&x+3~GeZJmR;PpUgyOP&6Ad}~%)=U~o3b=I}iVP{f1{x!3$ zb1>(iI_p~Muy=fGR$J#_&Ovq7wbWtXC$;XSt-Y=~u9iBeHIl6z%#N=aYH1GUKB;xr zZSC~G<7{q|+Cgm1BEsLr~UI_&$T*1fc~*Hy>W zQU|q0vbBTR@ijv&&B5F!weGsDo&I-x%}`5oFz2AwmDt*0XHq-bP3!pw>vXb}&1>W~ik(m`v(Et##*Z?W{q^*9^5Z2XhW; zU5Tw7_V50rzB;)$c|QJcyYhNGNB_|3iG6kQ`Uq3HWyRcbd0jH;u{|HguUg+G^*_9) zU!^^LcePFrU8}6?);+9#$7j->Y1WlY*Xe%8H{;55b1=XA>(9RL)ycbS+dtc?_J3Kg zGu^iTuTI_`wsm{H9vrcs-ul`jlOEgiVf@;sUhnDqI8L!9?$hycidnr_A9!7ib$z$4 z;l=okKCDQ{?{3(^3s0iM^Wx-emER4_x8o5==R?Bl>;&m@SYZ{@>CkahB_c5Sy{w+% z$NO?<(1UuuqTzvtN7NLk#t-|;)sN`FBx<=rdb{S%TD%(^FRn0e_5{SYK&-> zMqbM0^}tosKBD-VRACsSZjP(J)b6WU6?oM(a6|W?4P8&Sp|gZx4L{S?Hh& z_jK4UM;&2NSKW)q06kh5zFMY%G=~(N? zG`0mi*aq;0mHxSEA%MG;*vg1I_B>m4XpOYh5yAQjN%d*#Qw(`kPY|GjrmqY!Uxj>R#*##!`iT(AMDSKLy=j+iqc^*%y`@=RDsH*RBozn9) zjxEXC%(7u3Ml~(#d}HH*?)ktx&V((ROz7Iy(=oB$(N*<;Zf~b~i+j3eK%Sb4H>-3$ zw4QEp$rHbbr~YNlHF&_lBi2;w12=l@-6W}Z@?^WDgFGXe$%~an(pIZpsRQ9DE@kv) zc!I5KqHTxZdO7sk=f7Jgg-CqKR5@#=PS+lbUE9=grs@y;=PQCTSvJ`#C)Qux5EdT6 zB+p62C|AYdBM&5b9P4teJdbl>YSr4O8;)$KOsGfLbBy=$a zCS0Hs5i!fk2{u!Sr)DjD13@u2QSl=`Z}W;+hE6d^nrSTJ5A?I4arfn^czGf-schwn zemnA9R-C9xdUTT1r-&C5v&fpl1*bf>QsArmffSz9sO=CfuDTH5wc@y9*2?suW9_wUvF^W3h$`$MgfZ0)dje9cfxb1=XA+rM7_U|V;8 zx7(_|ocD5707l$ZLdQeb7rH{0228G=6$AdVUQd9@br^#M|-~hCK_z%uqzuXB^pmzPgm*r zs#m6Xia}Sv_`g*6r6zKdWlP%`5;s{;2Zmswd z#Uu2~K@uyLWn_S-R)_Ud1TjolL}Qnybaiy<*-*#beLYTszN}bf67(8;tE+SA=cykx4f{b>h0Yl=c*1Xuh6O|%41n`Ql^|=>JAe% z>spkx)vA&^4}AH3y2|9MI}y)U&2q46Cgi!Sp4{hEuZd<0l2uy|^7)}=FqiTF`pmL! zktuytS3pM(W~>Do`ASl)$gt`@*NYYZx+nH!jTR<7V?OAIa>kA%JH3&_Z#?M>QIRQk z^soD}V!9_q74jusaac76JeMRMc`8Pj*pDTx__FfLik*zLPUvE7BRX=WKQWcY^;(^+ zT(NH8Qf+v$X2-eUsmvor=u}FEs+bsL-J!Ye8JP5f82PF*5k=pZVOJ*VfKbIAtin=% zu`5EJr=u%kP|k3XWndD^-ASTUH4@uPAVsEZ5zHnJwn`n7gv4E0U3|T{Pra<3yoRJB0X@~e@$F_Jq7RWPXheb;vxH8QU~lZ=b=Te1WyGo% zI(|h4j)}dSG?A;YV2?bO!(BU_CoIDfnQG;(cSt#Lzg`kYC8CIBaRyylvwe;AY zkIi3q$5u_NpV!i3SM}KZb$4vtC)K^ErOt}(U9Ed*Yp<)0tECQVjbv*Fv*T-qTAG8o zPiozDTRZ*l_?n@X=3vf2tt+v$!@eK?JKb`RYiZy9>;Bl<>HgkT_pO$CU9GWf?VviU zmO7Xn-3_$!X0>$=<{VUKT}vJIeNyXQ+S==?<7%mcS|i!o!R+{& zp_b-gGO2Tr>uPN6uy=gTP)l<#=b+Y=*xF(5_?n@X=3wrVT6f*nPX9Z;W~ik(m~&9; zN^I@0@004j)l#pkHI}U%R7cfP2eac_v)VcbbDvaqxRyHo@A%fNw$8zvgX*knsl(2s zcKmB*TjyZTL3P%()M4-V)~vS9!JLEYtZS*mzE5i1OIv$gbzCiVP-`SxJD43`Gt|-? z%zaYpuG`w_f5+DhwKNBF4r*PAtsVA#Qr)*&>UFiovbBTis9Ne^c6@7ATjyXhsr$6L z%eB;5gN|>_YU>=#IjGLMmOAX;{YlOKRv(|Z(5JIHy>i!iPrcq(ztzRx8Tei3X;y#e z-e*t2)F*|$`(5=cWzxgCnju-Y_td?prB3(1`(4fUe|#25`@~MK-1Q8TeYZY8^xf|% zb?TUO+!Osh$cOcmPxI;XVaJ$p?4zrf>*uzX!LCnf#b>Ydi7b8EjL%Tx$>+7=6N2Ez zry=#pEq&?>9iI&28J`jJC%e$-vv&9^COCtA8G3Z_SwTK8`^AbQ{>X|?kcDqx={NC# z3jgU9m-3?$Bt?g(SeKzaKZ@2T)PzZdK8ww7f09?9%F`$DzNGnds9-J6x0I`vS8$iTfKJ0ieR zq;TaCxyT+FEGsTLA?a@!@kveX!OjO353)uhPemWEq(1+S-7%n2sj8KJ89Hf%8dl{; z-f)q#R*2tXg8g(@wJOh7Pmq-rKbKV}4LD%J3X-;$Kw1tu)>oeRA}_;NpP-fR&F(4F zm}Gt{)9{2zpR~r4oM3QPk|GmXxAtX?0rR-J@RYA6T%U>spT9@!&(|(1r#wLkNt39o zLWebEeLnoF4HEN@mA^nJPgZBUCaQ$b7L)VK&8Lq8SDBNO|5^au4%V|FNmkx;k}lE# zy0NU%+0ZxxttuL6k0ouL${RGH+f$zfR}6Use|TsOwmB^;&sSHT>MB36=CEPehT zEZNzwAZZ0ulNj_jZ|G+HbFs`=St{_jtLLNq<oAuJV@Z|jM`PhHx z{Oj4croe~$VIe&P6$Eo-(p`4PbUZu0W~ik(nA)py?#el@?h8rM`7Em`Tbx%fV@>e9 zekThZXYXgLRZ+Uu;)(_|-MtbzKXnF;r>^BVuhtb1y2wbeMDsw;LudQTDp{v9eP?P< zN&HmyLSL?7GJm?O$8W{(Th|A=mhu(K`O2{@Fc(GfPi-U{Ve$UsvMas8MI`l zzZnR3{4KJ$W4OJ;0M9ZaiQ!Iwu0_zQdUBJDOuhjcuwvLfU%QvGS`?^Xs)| zcX{TRZ$|8kHQsh~oU2gNc2A@JQ5D-U{(6;9lDeX*)jignm6M$NOxXu$qMRvf z#MQ4dWd*c9P%f;nwr{V6?%!cQ8T5EDu49}(0s!HZ3_(U(`|LKt4jeR9D8DQrj zPDwCp@5OegJn&@?CJ%m}uTk1Uos(vTUT&vOcA}g~@PjWcb%b54A|+O@6x1 zdU5ib^`U$pwjFr-GbzLT&B@QlHu!^)1rf;bXVICi=bIs9x(Ut5RW zVXeROuBADhsyS`lCv{H$=b(DsYN^BC@vT{HorAe=|L$-tb^71&tyyiIgEfhx)_wbTFKVgN{k^MoFKz90)p51dL9LN&?O=9%%}`5oF!xEVyKZZz{~cd5 z)Y2TxIjD6dwszR}Np;_9sn^vS%hnF6qiU&x+3~GeZGHckykkHQv((c2&!M-aJT`yb zov`XoyWh_dcd*0mD&l=1Si;NJyQI79!ACwn7!2~)Yhzh#ys}1Ic=gsN7&G*(ZY$R@ z9nX$$&1&l$%sHsex|TZZ9p9SO*7uL8_k>=b-+0fWnM3j`yl8m!Pw#x3vo|C=IJWN} zy>D*hM{e79L%#q1&DzTMOf_+L_2Dji%GrKL>q@4(?~3y7FP%lkX9d_k6@5I@ zaiw@WvaSpxn|QCLwuR8%9*xKS*Ee!J=8W_F+gXnNsoZDavDMx`i^uo8y;AkleSd7v z$L4n@YU%OUw9d~~&8wf+(qs4kvH9!n*!p3uzw@r8$L{{#)p~tw?W|PC*9^5Z2XhW; zU5Tw7_I*;_w_56TwZ^iwgX*YS>R@(!YgSw5VD88NS$*}&)zTdPn$y+~Yftsqy>j1b z>BH)3U5l-c-TlYrcPDCT->1%5sX3_iTH4xS@A#UbmgZpYd#bwYws!j8@ijv&&B2_5 zT32Fghkf6xcDm&r*V4ZI*Zr}z)BU}x?prPOx>{q|+Cg$==02(Ja4mKE-|?+kZJmQT2h~~EQiq*M-KVwgr>(utI23AXlWkY-?x{TV-GF&dg$eG%kom5> z*XuW6Ivc)~@VxbDv19fZBbLWDqgUhk%kgb}k?B|C`4_9li}77_l5R!`f$vG=JIwTb zgHF!_|KruiD!aaa4o@)O zj+s)XeBT`3N2zbiTj>~97!qqo{>bv-`ht}xQM6|yDP)Nd; zCu{BR_XK@8u#tw?-h z<+diiRZ`!T=>rqevr_d-%lR6>74MoWe~^sT*;tP5XZ zxkLErTc4L9(Q7#II2SD9{CmH3yV3&btMn+&u~ z5f^B}1s};rJ))(PC*Ot6RH)l{hU7}{L<K>3~t? zsdYwXkFGr}ePaIsCW!XbH`RiuOVH*kE#%sWW^$x!a@b z0-cR-qnB|eE}omHWDsZgpmN?0nmptFm#zS?zZ#FT@jtHbh!z*wY+1RE0!zB!N5eJd z_Wl9rWW9|BmHUgzPj;?5bcKMVI+2KbG5&)fEfSTeCs<^~Q}@M?z@pOg(F2%{`H8?o zcc0{GB&u6hEBr`!i~sF<1!-Tf)g2g~kN?Zc6$sdQs5)h`tppp@5Y07}c~m{viaH&V za$bg{oFx&h2X=5&t>Vx`R+91Mo{gqlI%N=ccUnkaU18!OoqED^T?>X5`*9xU>q;zZ z7R#{m5EH&sue!Mo*Zm!=aR)}8xXqq_fqNOzG1yp1~MBV_ODGF+#PBjYlxCBEpoX?Ra^Tm*GXuY}2uwswy#Ixm>r0 zWz9%^7A77s|EwPz$Mw5YFvb-;8Q{rJ;-Y)vKV9{*gBYHgM4q$FtEU{HuxonA^lUue zdZN>VsyGJ0-&yy+DERL`}&YC6t_Zdt9Yg60nm5Bji-I3!TWf7=_a zKeg~53)vtMO#`gDpMf^ zYUJ$xVHYY~{11G(s(r6?=fj31J6jw5RfZ80GpUYjR}JiC{0~o}@j5+VqNhS-3MvwJ zA;gLejNq4yj=YE_MiRe~;xz-flqd08C40vDM}2fut0x>h*@vok=10E_&*&+$8fy~# z{0=+U(iX8C8j z`?9OEApCs%cNE_rvHhF28OO~i{tEDMoDuJm?y@@rd0x-=u5WzL@tMKgVm?cc?fKaJ z?nEu^J+1p=>wQ<0zcJ0$sy?NAiH_r7M0IN_DxmpQYF!sZM6P2 zx3=r7JGm~`X1sGe=b&c!XSxo1$2a53baOE0pl11Jx(<83P2>o<_S%b)2u6* zuCq=Z-;68M&B5H)KkId-yKnz}1`dj&;#(-t#xX79xvArLsEBQ>k?)f3vYRpU^i>0X zI!n*|a-ELbW~ikcBa4~iIR`b%Kht&CJH8oLrkjH~2Q|w-)7_Vyb8&s=4cEIjXI|IA zw@vd+|NHM(^}SValK+#<9wWZ}>b^DHpELKonL+NC<)hwlH6xU`?x3bPn+HvgY^5?? z#+2)F?YG68gPLWP={oEk-;68M&B2_5n&qGAI_&qK{>S(1)aAbL`ikB)XC3#n(Lc1N zS68n&Y%${eKd*>$}?zHP+OD%0N9>epo z`Rkf(edt;lA(Q4*KL<6-Kht&Czx!R)cFDHxUg_P*+E%TtrQ`T`ABSUj7hUXAw!Zer zq{sGr7{7YTYoV^mecozq&!nxV`)5yK>NQX8Re9x>S3G&;Q}1^`(nAuj-Qs(!)jMSL zt`9}WYpwAbE7PDD-nVcz7hSgC-~Tx*kygK zIyxmg>`2&OtgO6t9q)RPm0ZyBYB&7k`sSeHT?J7S7_y(OeQ?c+!75)~!46++fr|9{ z>U}<}A2pq>+NchHMUxZ%!8{wkg~U2)9rzvZ83~=<6(CO#-;A>|*q2pS9Y6i4ebld8YiPAfbko11J@Z_Cd$`mH? zYcGYbdM96X1z)^Q$A7qxg$gg7WOCkIWr`M0bpdHvHPT^QhK?v=(1Hk;Dv{lJC|CIL zlaKdr@oo`pST9F^mX%Sw?1Q2zvc@a+e=sRZ(RlJ)+oV?lt#S-|PD4>5Wd} zdA=T{)N^lBL?}}#zFspN%%yUcRsB_^!oj`_KfR|;t8g}Sdcc5{tkpxjwKYa1%j%1l zR*>I3u(MBBeW6p-*=lExBTs&F)YSXzqznAhBP}-BEs^UowET}Ku*jZ@G%G&-aja4= zS)YhehqN8T8S77n#HC4H4rdJN$ocBY9^d^}9`X}AHXSF(1vKTy`IaQ!`-vngQDW6h zQ;EA9?^sn<$JMh+KKiRp^5GGfZ$_?B)A95@8#yRCe2K+3wr(M@O)Q68gI^3}N)CaK zbUL2Ps#(;LMt;~eS&CVPXUud&q2r+aZE^;GYs+4@?p zBwk}6Hom9+7-xH*yh7P_a4Xj_w|n}vMG&gGWjD|7!sO|iko}zNM)!Q(BDY%GGimF| zdCm2EgyPY*zxBT zsXWQcnf!2U@w{^WgRAOzwza>HciA$LRBT-S1{hr9D7Cwx6%Af7|t?z zU&8hG2OCfKyy*Q8PX1uc>-W|yz}LBjj+4vS7S6{pk|QRcXSmf&kp9XUDP`zWjPS)DuLug|z*_t}t+w`9s^V3##3pPL9(nQ(5StrjeK zVpnzgjVI4fR~*%ckMh@<8PU?=sc7uf4nD}|<3G~r70>IdJ_##OmlZ8^I^O}G^BuID z*Dfnouo9_go%6z^_?L&(;cVJxPRH5n%#F;5Ay3)q89c&{b3kfkA4n}slk-#ja)^(( z;0o03N|8UAib-7RwW4MBI>dP`QN(EC&WEg?D^pXNcf~s{Qlc-7ERiD5L zB<$|taX;t-2T*~m>@C6Ca$W?jKb^NvW zR?qkhoukz&>|o(bBsnV=bXpC0Vh2@B#K0Ijre8Ik4xRGnr>-}#YWqO5tXqU?<~f*b z{YZ3X>-l;d+r%GPMSj0o^W#`XN53~7@>>SRGUT%r@nRhFK>qmf`}eN!(89j4rq$(snW#2$NFWVHO|KN80kZ_V3y zwC8I?#L$meq2L5*8CvxUPdKzH(aq~u?|ATtD4`M)GlcbY*q8B}end@7#r4(H6+hAB zf|WZk#6%P_NHIZ@u~Pf#VVyW5QH6N&P&_N}2kY~X513yZ>Vq?me;4a|;`er}lO_os z^@&Mi#(%RuXC1-+y{kzIKeWs6ql(wV3L_}LH>B^M{A_(tmmYZYz=th;84~gQ7elNA zS%HWr_7?}cqP72{-$Z>e{tMGtv7HE$$<@|}mpu9Ta-Cz&J;f=TJXHgqH&uS&!79Pz zoa0E%LCVThMeR{)kq&7@?%Dn5$Nv*`p?GHe*fgB zW0INPpPqa={{MK52Scxrz(%iwjSS&XhQY>Gjx0ZT*%vE@>p)4^SwS!*Er*!XRky4* ztk}gst>Rv%;^_5H))?}^BeHi*SkPki%xg`l11Tzr zc=XX7#gN&rR!{lLg9-HUjrV8;Kk*@xi~10+#F77Y{pE?zHipc_!&bnA3X|`DJLzo1hQ z8EB9D{dIo7H)i)|V}if8PBpX4Y=1hu;{i7HiwT*@_P!}zv0#ry_VgK^SbOplJ4i^% z)4k^!Touz3&Ij>>5$&>~2BwhCRtBtrj<4_oOPR_}l&s?4{*?f@gsSc-6Y0dN>gBf# zr1Ld`I;9gPxy0Xn{mB8-?Ch16%{&K}|Msb{$XyWO1gT!5lzfiUNwPbq8ZEt+bKtci ztZd6ENElJOl>F1I}{)NdQ{aY=PbQ;@7Ei9}K zou`zJG7XV6;c{!&r)mkO#!Fde=btI`v_s@n?mh3)R zafQbhvSeAdOQBEKpZK3yE%72+GdOcQbe;t%{*>;s{ytZ^-jkT7h=FQ7chuw>rT(tr;ngGm@sg zeN{uHt~EhBSFZKuYKUX^sKVDsmE*Z;nOR+1eKv9`{JyRv%?rQ#Bc+o5oPNZWuqq|3 zNuzm7L`d~Bmp;loCdcVS{fd%H{~t+-AH7_^j>qL!+F`u~1?zOZmaHy9&J0p`1f%ju zUw+?9m8+M^g+~yMQ@zT)oR>O&!78QxsqzVF_Y;msJnQB7qgH02mbBxXIJ9#bBV*^z z@yBwP?biXP^peU&OBj9COrBNN=r~o+Em@d;YmiC0-;%ernBniRT#tt3algfW<%1Oy zE6(^0={!1Cty$1Z!X`?hrBc1bf%dQ5{*omL&h@KLj~rsHs41_n@)=$r+LR=XkixIp zJ~l~q$?A4GvsBco<8u2Ih8gtpyl5#-twKw`rCj5bpq$e!@<%_cT(<>%yZw4J<2)%x zJjeRN@9pR1(p1CyYbxb-q?B|jk2)bGDEE}2=_!3L1AS3)Of&mdedSDf zE2XqJ$@{tBy^hP4w6C^tsp3fE5HoUz)N%SrQt>CcQC6knJV&@ZI*!^GS1yy_gi~DT z6@8D>PxxieUM_ujG$K97-qLD?tT?w`$0@1YB1K>A zQFWeOqpI&Yj$Jx%JuBC1c^yIe9&ehnJ9S~uh(8OsR5RLl8Sx(Kvq&sn0y+ zF~rRBRLk2&{D~92BX&{DrI)-ji$R=cuPxk;Q?R~n=e0y5))y|>Mbwluk+@1!m78<# zY4>A-ckSwXXpkDG98aX=G&RP!CTF4C+e@WUDnGj*iZL?L3|0`@?eUbbPAFHd{6XR` z`WsRI+kjJWT8GuQmpk^vlS-Y_+(#-tbe%e+a7KUp_jp}jYx}F|UonxQYDM3y`uJq}<@xthk8jJD> zV^-%!2*(xsiPy?4QCtdN)UL1M{yN~1{?v++)HT_}nx({z4* zYmkDN@fI#wuKK$2WOK>-g~_o-3~rTqo_LyBotP`@6dvJ^c`@bdWy+Pr4k@@qb7pmf zRT4XWX;7RF`Hq|@M_5(ccl%tYQU2f7lO2)^;wxl3 zy^eDw4kM(f3o7;*jSUma6UL}(wVU^}S%7w}M!5wm4f$$W?kVIc#kpQC)6D#}WS*Lg zqMyc9wTU2IBT?6}zJLFga&ITmOc97%g;R5>B7e>L!mo1ClBRu5+4f1Q>oR$5)$)|M zQp$BM&*{&Y6)!U@QA&Iaft*;%YY#0g>XARSg($hy!W!3(m7|^@NSCp~(*C`93+Kjpkd;UW-s)`* z1R2{}^IK6--mH$yl%qVy8GER3N3F*?$`P-Ej8@~d9j9A}~5C9LAuI@g2q;_Gz6=Qvg7DaCdFjMjxyu-@yu zmincqBK>GH(zNo#i*Uu>Hw}4-XD`opPK7h|AN7VPlUgZiKl10CN;{t8()*Q5IHQ)2 zdg9%A%IT+i&T-_~A@!;CH%XspxxEY+keGwLKr*P}F%^76FoC2}Iz*he%M67^JnNU8Mh zwPo8%MZfBravC1DJAacvS27Q+KQ4)OfNUj++x`^{I1Q&cKyPJ3ov-!Y0uX(6XBZk#v4dn>wJs^h%*xZ$~} zU&LOinVcY}^q(0NT=Plas@J9O=wWmwOk8PC&8=LV`2L!5U6wdfdfN#urktiINMpjJ zPsgs>!mm=bhRdXHms$Fb(&woNse0l{SOw>_ynf7!u(BHOdCG~9vw&ZvZdbzT9#W~8 ztG14Hw0a~xM;jLZqVDwt=RAAt;xaj|s6XLVzUpW;;_c{iG^3K=AfLRh*YG<3#Fcwu z)o@J7G83eacurrru@5+eaC$AJw0gYAVhWFmwaTWrLhEpnS1;9(gw9jEhdAQ&(nQm3 zb4ne_n#(o?Y~d412%>!`)L z^gbis+f@*X&Q&X6b(+E|NWD}Z^{(q>@E&=&@?D$4>UEUkV@L92+uk4Q@|Ee#twtlD zS}4wQW`U~Ps>iOLIqM_)Iz()aByN>o}jP z?d{;Wh0|BCRPGYFMpLb+)lj+179j;8*+s#jBQ0S_e$Hu%J84fiA_ngf-UC%fcBd;r zI-e0T)$!Dna!)ze9>KVcXwB41Ra=&$d_QF?>QVlPL4EAkc#_{)*{_YdB$`ssF-ba= z3eL5lGq#S=?KVQ{%56j#y|$ms_4JHhCf)qju>H=gNjPOQI^*rLr)UpxHOp+q9p2yd z?mAv4cDq==r*GXjcHQd(<+;t9xnlWs@1%d%d*3@fJ?ovENZ}{F(@-0jKJTOarY^4E zDnHM=hR)sf$;s*ITjS~b$CDH1;H)}5b!_71{hjBJs(%0EByw3);PY3V5+8RxL4D7s zN~@muE3V%P^6Ng=v6iJi^pTXD>u~E_jj0QJ%A@XI6w)yL&i=QdA`3D1kSyNe|FG(QcpYF{i{ND zaEgWO^eM|T?Ys+?Zr^+H{zP5*aCz6eyGAd}dgPBkw);%``U4pHc7v_P4EdC{$7x@W zMtMKV)50Ln{m7?l;Lbcu?vZq(uzEpmJ9%35I<#kbqw2>WcYNMm^akFqN2A=+<>^Pb z!#}>wxk=Q%$8Vi6(&2%=a{BvnRmp4hiZ|xH0`Jmd+jq9FN28}&O=B)z7jLRj*Ssp8 z&wNMk5|8U`=%1pKyqc#+j0Oec!r9qq6tzRD?_&iv1GW>i@&1mQaC}zj+I4}Skp3sZ^HU&+ED&Qu_^YbTYy$->0hzZ*J`UrppvbI z6un_owfj@J#x}oyWGMA^Fv+dOYaN_bZsB=rJ+F7-qAIfhxIH~>X_lC%g~Qu{Pix;w z_MtwTLy50;US1w(H0oq|m0R*IPKyR>dBK>cT`!$DEn2wC`}$6lX&!WR+3thy@gC|c zDZ(i(3i;)IY4?G@Aa;4j=UcvsD)g`djr6X+Ozv(8`UW8^Z+V?RLHnpv7hWsUCXPvw z#fx;sjmOH!sur z9D(n=MPzlaI*RkoJyw!%3}|sMS0#PbbK(RAntM9C;mUrB+^E-i0aV zX>96%ZO?&?e~SuE6iZliU=&+*-wJOlPj&lNmv|!7Jt1Y3yYwNbwu~J(yXcVTdY3il zb-L)}<)W!qSKbpk>VyrE6PQd#$HLf!vpX;9m2YWCHQTe4;2~P|YrjE0v4N~E>+4?< zX;d1$e<^%B(umJa{TO7W2=14nEnWW7_|&%1|K}|tYinCzUM{Jhk~~^)y9Ws0JKi~- zJpCNbJuTS$W5a^6-zO}%-%Z;r7~74O?3BCoAz9iocH``l%zJrTAHw%qoO|jB3et$l zhjyZzJH5Q`a9zAp$9i|FYu0XoEAAeq4`LVtX;`Ba$0GM@^m z(ddc!R6nkmp7AFf{wXYd&2M>oO0%Lvv1rxA*G&}dr!{3UGII? zaQdpt+x44f^y0oT`^naNDSPj$0cnoYo&~*BTO3lG`J+}O^4dMFCB1ZEYr}7u_p&xT z;(bcL)oeMf28DiOx$2P>wY+C``?8O{H;iaDlky(W`@mIxz2ix``cKF^47NBf{tbN% zFK@glRN5 zTmLG{IfQD?ZJs^^hwO&G9e-e2#^atA$wxf1ItdE5svN$JL!RMj9G903-+xm3{$Q`C zMY30o1-6ojwaPl-Q8vLl!vVF3n~vCt3_cxhi?CX2_~G~@8*$?5p!zZ8>WREjt$FgU zo>`lm&fWBZWJQI#5K zN*KR4_(GC$jV6OfYQk#`TK?ulv`=ka-rAw*DdO0`xPk92j`$WZcC;TOE|DJm856$1=>+X7u8eg|-_=>OZPqn@J?)6TN`B|O3k$>G|z7r+9 z7N0&gYV2;+1*^>;*nzHRH?bytOg`CX54*NNOqW^62h;d26gHYcrSg>0URiTQ4_8DG zVa%yKC&bHP)rwKdqWpv@rHblaBNCB-ZMl9mlcJvh)akcUq@4FKCXs zSYRBLeXp?(FP*yu7d@Aem44S-ho|rI{`4NzIQ4op1grhT=#u(nJR0fci-qTePg@l} zu%341JigQn=pQdK>#(ZK*U{_Z8-(w?ilipH8Pi!(M8I*Lrtaw%v!!ZW8vCGA+p( zTua_tpVCt2UXIb~W7Wqs4%N3_s6G|u!}7!ReAqlY-aMZVcX{-9icdZ<`W3@N*Fzf`_7VrY+C?B7E=~ar?J+Dw?vya+9QK%i7oaC2iU4ET^8Q+ni>6UVLq>@-noy zezX*gQEKzIwXHovqt=SXb5ZhImzFx&lfL86>nBY6+rdRK3LFP6bk-(6!BF#>>8O?0 z2Sbc(ddzd(viFfc)w&3yb6v}NM|~v<_L7XPREVh*Sux+=yWUY&PqA#o%xR+-Pqib3 z_VvzKZJebMI;DzgH+K3GY==-bE=~)1Fs;`gqd!uIV4#*>_)${*;MuS-Us3v{<|#$B z8^8Xm>L|oMmqFGJ9a*1Gt(sDGEQV%NeaiQn8;IiD3!fYGinCYtAk8ae#mq|ZqijJJxH|;%TBz#+Y=74#kNIs+2A4gI$__!d3dE% zfPCu_1#@RrS|7LubZ%_{w{TFu%?+(!l2Plv)m>I=dz#`G)%MWWnKOez#7i+^$p`SNr-9T!+EJO`kV18t3_#(dNB#Ob^sf8Pkbj zYU#nLl8?5UnxD)063KS!Y8^^rRZZ8Zc4@dPZ*NWY1LP4{cwb60+8f=aCWr<%i7q@I zo34SW`9)7|O$jcf@Ow2>BSr3=t-mFEZk%4BJe53~GW-c5t9J+v!y=71mmjn;Q(rYx z*WvEg-)WsJKkov3&Br0M^LoWybMi`H@ZLXD<|`1fDHr<(~4It#ZTW<(x{&6OH*3->)aPod&A~fk&<&v zi3-=cPi$XY{T%X~8TF-ei+2QPrITL?x3u#nyUyz-sIF8zl_CwK^8M>mXJ3gLkU2Fp z!wHqw;W+F5l68-pHD$|7qWj)eeG3cSds=`&Bvu-)M=(&-a7L-rD(ThrL!na zi}{jMUQxeE-u+uolBIgjrwsDQJ=QrbouIjTrNv};%HjNSQ;SvMVLvUf30=~9Bs+k*L%?k{7Wl}$CD%< zZQu5_T0exg(UiQrpVd=eFp0xF^`Lmwc1Ck-Zco$-Qa+Iice@3ilP}DCAXroWvne3I zF**qa))~)mtJy^R|TB)@k9d0TT%BE|xH;gbdF z{6M1YQS-T-N>91ZruN}Sc3FJ9ORbxwe1*YUBFhzLU3vfNv!c!@?)=p;F4{_SPugCX zq?>f-swCGdNpITQ$xY=c6}6-2ILnpx_o@$E8`f;3tA0^^wkMIbBi!>tBHRYOv&K9E zO@+CqxQhHgpQ>$9y-H`lECPQ;eQB$vnM>b^>*=)=jep`I$5p3OZdd9d;~*>dzRB~H z;`)&HEuFb&-yf9t-f2~{hE$$X(SoG!EVpeHPu8c--mrGZLJO0%`u;Pd2DLNqONP;` zQuC#c{{?I2sHx>#-}ffPc|#(g572GG29`K;1gl?Zr`(_BSU;tJQ`mQRIwj0Km?xIY z31KpIf2HNBJlyfwxBG>-*O8ON;oc$LAp&q==Zd*+QzdqG+fEdzfs?D z*>e$$I)~Byo}*sms8D{m4+$K)7uWAD@%vZ-%XlWu^&QJ_q&P7zilPq3U?I)nbxyx? zx07*o^47kTmC*VDrFAkHJqvV$E+XeWc`fe zwVtA8tY*YTuX9{Hqar-jSp7;kId=~py>)U;C-sG{uqPnOvdl*Mb;_)*VK?`TDPM8t zsMa?eI>BhfetULdTBT9#9su3LuKV20uGI#T)*bOKqY z<>OOG9_{(9>Wh*H$@#kTCxkZI8no)W5EMH z0uQ}~o(Xc68whQIhFw~VU{1DhFJ;LWws>Cu{`qqj_&6DZL%V3 zZAk)Imt0mNJ;H@_39Gus%FwUiVb9@Raxce9RbICa^}$gD$teLF@WyRV6kK;d{)pA% z;kdsM3znSf83j27clQ_{rtzo)$u2sAwO(Od)_Ux_|2S0{5Tfb$)VG?NRIicFbT3kD znMlR?M02O%*$DV@^Z40_5uZ3<^??+va6ghbG;KtDPd^z%9H`e~C$fhy;)EQtZn!Wx zF8%4ZwLet9^|teSk^&xS9b2$kXh4`GX?}l`o+UvOK8ZN~Pm`BAUdwAdrJojL z7fw-xj$R|RFVFE-D>N~Z=i@R^i6UuM*xvMt|NASnL;lyca#=~M$@UDsjtkS6ZHuDeWE(6Z4(u@ZHB91EHL>kg}Ruvp+(%Z&IPC6eHC4 za%&U=0@@+kwff{)%bXg=*oIqi&eFpVDQN^2 zdnf%6eX{o&ax8w7^*J7Zqion@9UYT)jN(Y#OS|yMpU>~8C3ygA=tB_`O(Dpj4aovF zL5o*xha6zw)^mbJ4L_zPjlf&asqsrS7B^hejq3RB@q@?O)+W|E){lVrz?i5}ktd+o zQ{m+G!c*bGxFKm!H*adAAH9o9yHn}3xG8wLSMs0FrwlTzWxfP?)>BW=n8YZgXJEsl zo^9u|8Ci(U8<-t2e@2cw8+%5TexCuA;C;}idR&1)ng@q(zJ=$w_gzT&*l~;m@D^S# zrS$XxwT9XmGB>^iM?=ol=Hm3 zrBZmQ$8t-lCEI!Zz;zSSx#`H;!TAiNSvyhJc~2`A(#;{Y?T+hy@!)%L@E>d?$#f95 zU0M1Glcl7IekE@G`Sw|Fg_7A5pVl|++9dCKrgiZ<@4?=W-VlNP3hRB&9<)Q4<9rTQ zJS5nnx->rUXmD?Lq-qta1(V>PPwh|F@X%|-d9&xGb6|;9(q5A@hd?)(MCARK+#63W zrSHCW2<5^3PyX4)xq8Jz-rC2R5YvR2cpAqPMOswcBc=(ltU?=Mlt0$nR=`1pm$sa+ zCQeRR^$4rKtPeLri_qLLPG|&!_u*E#Y z-c%_JqeUzEZh_>{TNtH%(-pPfLtXTxtsXRLZVcN=(bQP~#5LxzijBXL6a+4*D7el} zY`xtg3X5&DJ|mqG3ZXNCEhtIX0h4$u7~72(!$m;GEJymMsAm)`B|vahm9V)DD1P#| z0Wh>eE;&G>UrUiKt>jT^Gs^t*DaZ}Y$GboD%EfTF8MWHz!T%X+i zyr8`I6Q2X1th6kFE*Fb=$=cfYiUn-d44$~6cf>2BW-WvT2+sgK%i-_=JYW(s(FBWh z0J-AlpMUBth9&fti-EXW%*9vuFNubjgP299nL|6`XX+7R_!M_5a+Nh`jgIzLtOd;; zA}UH&j4NA@Tg;JXhiH%ZXUwQVm*enFOTx_H}a;?UuR2|E)l!_3@ zaZBpo(_wxnBh+{4tc7Yw8| zn^x4#Oew_a!A7W5oc?_GQ;!B4s@1GD=Ewt^#bU8iyU8=5R&43pp6p~9;7Zuz?Xnlp z`;qQ|=9&3mR9wLcS0nk5;xyQa^#oCrr5MFa&_JqO$WG=9*)ARce-fZ%yRu5`5hDSt z5Xo}KN~qx$5ZhZ8pgAgvF`wvug_V3LxK#*3Z}nm3Qt#mx&ZBL4T&`NhX|xjLjjadU z!AeX6vI1JFTx>$yn_|eFQfIqZdfSrrwk=nrA|y$2K?80tFO@LJ`AUc)WJwx}fK240 z2#_1VWSN>zsrBVOG(P=k^DwiCo{d+;*C*`A^{|=dxP-&Bb=rdGj}h6O6m}0Ffc&AK zlj~mZ#5^XLZH$r0(e7Lpnyv85u3Up%<0tbnjWMtw=toMJ$!V>M`I@i#3d(+i#8$9= zr#gzES}~iTl*{LlqWwC`)5>h{jx%G3LN}!_lrpvCG6`8y@fui=Y+ZS+1jxp>_758=80g6|DMs5Va;*p zX;IUwBag`JoOoR8s8~D}yF?%Sx$RQIZ^0MIa(HpEUT!zT z<#ciPD2ShW`nh4iQz*g6ylFApWVtKVNicY~`%17i7KKm?XXS&kgBdbQ95+zA3n)(ZLJvC77 zK+xZ+OpJZ{^fO-ASmfj9pGouQpSQQu>EvowUacaQVhFU=6{g$U*?2XXO|IsmXgE;m z-5ugk47NxIZ5T~2fTrOS3Me`+j`j9-GFZKYZThHc z{ABgi;+|3-^syL49lA1pO$A^cuFB!n3fc+U%Yh$UTolW3SuQt=Xi-;{W1eJeUlM$zV`hGZ2aX#l>VY7*8g}0KNl3S zQM93WHl7S7<4Gnv^sKQ|dQl8uXFL!+*^f0*gcXL^bA-$De{Zd&Hf>r~HWU@vX)9GMRtj5@uQx}&tuCl78aIn4_3})j=QNS$g zsW&{#y|}->DYUkFuFuo+o8tam@m+EA1FMCn_tnk)n}XEwIk|7Nd#Y13-)X(*zM%5S zNTu&&JCBdwns1G^Y3>i{E-p+xW7E#J;tDwaD*S_SN{;;SxKN8uu>9PDz3qB`P>q-` zrBzU)Hg&yk$&MT^SxIj2(mI3jxWJNB^6j^L)a8Tn;vB0TkFlfJR~^gaqscLF8*n{} zZpg2DAnk}>l*e$n;gQzzKWhmQ#iVM#3d>kj^nu@+2Cz3l5uxx|Rm0hMEE_3@6Kn;& z1)QQ^exSC9YRSi!K(s65)tL;EKgg<8ruVJGwIbbswkpSJll+^}mHXVrScsd=A*MrIA=BD7Eg?j$J!z_xM;@$my@fqVP&h-A_w4nI% z{`{S+=FQDNaD|nfk$YeKfH@U6gh%(qA7yAog<%Qq*iG&qFg)hkM8`UhHV_kmYm)pk z3N5G8#c;JjDz1@!J6zsX>d=_VPs7=eh-XNYJtTe^Z;LfC)Qq@iSS)b~p#>zr)i0$z zG-s_#?D6ezTN2}_9K2iV67$%rDpsEQUGMLDzqa?^_x_gDH^lOP#kW5H8or_8^+6G> zm1OYg--=&GF}G*Zvp{1C_L|zKgkxY9iw>yCAHIBouP+(Ry;c7pK3%SFl@`7w60eKR zEp3P0D{nU6CO-cfZa>2Bui^I*rHStk_N`SvUceVqusA=88ih0Jfw+?LjX`dTNpWTA zRKDd}8h5>~EhS9KQ?7E>b-Q?;K7~QlH>AAQ6**ft@j70sZB=XgDsn3t^mDZQ+QVD#z1_XO#OC!3kQSXUB0D_m$atrr&POMR2m+!;^jaTqV9&ZC4VcF!4iI7C~cMuqQ2RMdo7~5 zfm?<+bJ@iwuWxKdVwW>##m z<=}tRn@xHlVYNV>Wqw6Kf$uKX_#cnTek$q1v5uqw7kH#?c}+s6VlXadlkIvtnf}V` z_^+_%YwLr5Z8rTIZ2GUXnypq^S$jB^nYE5vi)&Qvxh%#8DH@{Wyl*J+9x$#`UPt_t zz?GrgbJwO()z)={bX$_$x$b9Hu0AxZA(yo^%OazdxxKH@s9PgFI;7kRMbBxi;79mp zfvTjS4&yq$R6aStIUcuqw^doeB9y{kRo&bG{qE)*&-|TMo!K*e^RBq5zAFs3OXbo@ zQm42+$BPHuZEq{B!}!c{tBGZtnZ`M$rkJdll`3Kae|!7zz|so~M_QSgv;Mm&wSq!1 zv(bkKrRFv-RT*_kWhmEaP>Gx{`z6;f3scCWP&90Pk7X(Tz@k59%37u}3MJIZD&{I< zaY293a5<)SDa(UF0D(g2lBN9MSw(3PiZ|;kR^zgP#{-Ha;!!ZJi2SCAAO}W+Hu&lEzutLV60eL1s9xCBEgug;uRt z#^cj8MN)shvN|ux=1<&~bt>gqmLz=eT2ZIcrvE)W2-=oz_=JKdS;$UOkOasyQbHJc zhSZV#?GiV?k=lRxOUihN?kB zsLQ2N;ZHhuh9!&iDm4HEA*WF2k}I{Umx%|L!wipN@k}QDCt)^ghF%f40SthkUx0(0 zmQtAzxNb=B=a@F350D4hfE^x#7PU0$xd7DVtP|y0bXd%KBgv(L#g)~Xdt1@3EHh}F zGEiY3bJmTFtTLz_y^0XbO&?5wNul?Q^Q7IfG=A0BoJXUgeq?mHDj*bSsF_RP9%LtT zy)%ugWnJTd*dLgwkN8+Q8JLG?@L?WF5|;+IvfT~?RSGEtY;_F4brbDF+SZ?y=P3v| zqH zT||qbPgGnoG}}7yFsvGDomg?N>Qj@?x5bfq3b1qx+b6^SnaM?rtT2O`xRI~rC0H>% z86sf;G0AIm!CpW(x$+tNbbTHNef}9VYx>e*)F5p=_L#QZE4zM7Tg2VEB7Y-EiQJ?u zaan7-lm<|edcSpLR`p$71zyeT3xENISTglf?EPK4Cy=M7c)2yzR%Lok7FHdRR$tBS zPBz@`hXIeZN>{nzXy6egIQ6jh3P@>)B7uY>&@TeUt zdqr4-RIZ*D6`r9Yh|uosey!_fUeIQa&nYzM2C6mQ9Ui*s{L(o4)ipMAj`s9hTfU!D zvd=+`;{8X!az?Qs;A047dCE|7V+@8c))5Y zD;X$NdvjUM6=iG|Y`(}2_1xaSj`Oaz{QbPuGwqE?pV$dAR)L;?`K9$H9;G+;PqlxO zbRO-@b!Gr*>2t^_Kjd0OZ<2IPZS{4pANJ8!D?vy9XnNNe&a7>NZbB=Rj;&(n_5A$e z;{1HPn$OS9*qmFOpRZQM`0Q*m-%M399~Y~$GeRIMnUf|UEN^aZZ*OkqtNHkcAGTMM z)y>VSSgn5eVKrH=y<|nnU_Ds_HCKAgqW$^#B^ar+Lh3hXqcM)SIEBV)48_HCvoeZY zLVq)!o}Yshikg!-MWlnuWV~htP-qfG1Q7l8`U+kU0jSk#Qt@|rd2@pb%lmuQ<@hUD zzmksir;_=C68>hCT1hDlUS5*BoRT-0shnj4{!$+Z2ZPvB<`}7IY1=Pnf3D%og#b&*kou`UEFqtgoE*nGOf8s}jx&c3!md`rnbR?zLh% zoDEE+tOvpmDrN=}SRJFk&x7S``mR_4bN?XyeW%4CbO`-1nt+!H91bQA_mnIrIxiw! zYpDlt;1=V_9F3V2=&!17KQCYfIW2l;O&Go>gHN9Xw_w*nQ%0@B^J1m?^XGCQO7s<4 zL%bm_8b*)Ek9vS7f)G6E$wYcY3u-y^3~%!>G~skmF3_x+#B>zP(JYN5twCTw%h1;1 zmW3R8*8M$#U=3w?{~);wEtQA#n?gd8UzX*mY31TU_H(sl$#;3X7;KhHT`#wTlIvSm znOKt>uCeGK-&$jE;@@lNPGh4&wb}24b zE5V)$c8mGVCY#ZSl{7Y3w8J7P_+#0v`fN7C#hVjJ|8QTtQIQ&(^eK7DrroRR1Uc!E z6V71pJ>C9rb5az?x3{as`k%J5;o^s)V7;G;OY}86zXALWd(7MAYCBkO3l@!}C5!|m zm5d+TE4G#gTSP37U#-5N%=CmkNKSNA@@CFD+s@c)ThC@#f~;SvQZK|tXkb|(8emz! z+|HJ><#usj;nBu)hwsoBt-yhY&2q9}hh%j%9<0`r@u&X>*vWJ|-EJoL_v88aZ%{9| zQQ+okxY>?ISL~)uuG9|VTg=fs%*n?Sc_lv4i?tgfiElXJZyb6jMh`6eZSq!QKAF!V z4%xDL%s{&~6V6Lu-Q&p;IP7>3dYkn%X}x48M!m7bzo=&d&F64A8zPrHocTc*vA&7d zpgT-tCG?^(yNvK>b50f{D>k3UwE5s_y_!?Q_$<+`m954roG?9iwPMG_ycf1PVD)XV zz($vBbIQ+7@Jtg7YC`Xup!JP>*>F7G;Lq4@SI@M*T8zv2fL=a;W3{<-SF)lukS2y> zGb`&GXwJQ?e1`Q6wJo}Sc$k=mfu#mGUl;Q`0-jUeW=qk>RqyCn8KhHbujw5M#d}TXJ}f@w`)0PG_qQ;t0j$WS9B%w z!Z$bgkU6n{5YDu^3>u?!QPI$JMLyZhP|Q%Wn~F3kijprVtBcKmARizOP+-9pElqJL z8r?8Y^*8zhK16+jZagcuNU42&gM zK47#XIxF!s^lxnLVm2m>o-mBy8Psp)bGov6{}RtRM^N8=niktjyaEvh^Onh$X4Ou` zfZe#O0*N=PEj@8N*sO4(Ks~_!iXuwDF25@;!Z($!*dD`OqLt>{C%M}ndcK?}pLXn!;*pyZgNCnW^+Th_rTG=ky+h>o7Ml6eRg@tX` z%xJ#5|34uhi@v4Jw$z+mO_%h^Tcp5qujcHYmCMUN(e2@VBTEMh7Rh`J?aj&=d#&gK z%al=1Dx#7JmA2GgEdF%4ovkF_nrM(Rri61WUqK6Yxt-u5Fh6b85~2JF5c(4F&a~X# zf2JukQnR{sThZg$6`nDN+-^pnboOE;>l{}9yUY}<+s$T;55gm8h#vDzga_8!SwUD@ zNW{&w8nK;^PS)sLr$NvhI{VJ8Nc*va)57CB%@vMuEmAO1AhG@_J>SR9>f!$X8WI5& zr{(Yl_}kkn>4wSbA33SPg@B-|CaAZNn|MHfh0zt|h(2+OSb#(3D=Wcq2bfaJMQ658=ngIWHrIq!3pPFlW#- z!`%?)E?J+zkCql$Ylds<2jWU&P9?89M8}Fbn3-EVt~oaGI1wdwV?OqCr8rQr$^42? zi1lQ=Kb?r!7CXAF(20zOfx2YnNj;1F4PIzneb$kJ?O@BUvF<0qb_cWxMLIxN-O{ie zbTdkLP3>v(cEoC7~nvyl>+iG*g^Ki@;v!6I!KQF0d?u0BmwtuIUxSO^Lsz+j6Rr zodR;~Yz&jdV#?vnb#=@6?!}ZhW-_lHX82^>8Ih#=tN2)yj4AZ|Ii(yNp>xxRfqLzE@1%Vuigtr-8;)!FCIo9%G;Zn)9x zX?V+8z#F9hBNKG)(>c=`MDgx(HQ7)&AlhBye9J1VgKn>u%osFKou8Li%O$Iw=u4}T z%wiT?(I;82v@}3NUzMDVhr=I!P=CF-;mGxjl~2;QtdPzI(~=UR?wcDN3v&SV#`{8t zUSZ^%PtGG2Kb)Z#9djwZ^YvIvq;%Tn=iL27TGYhH6)ksmCQovHj&FxUN$GrOC=ssz6H6aAjp0gGPm;8-J)h7Vgus@_O9$%3Ko(gs0xcDxakFtf1pMomO zS(=Tpvdk<*5b|x3Jb1z20Tpq>B_lFEkrh?qct!@s2v#NVsc4M28vkW53>(T}zDthy zl&Ls(@XYL$G*pe#a*ig@II)yC9W#=vEww_;ng!=+xv_weY0h09I+e{DG`)i{42gt8 zV;GS}i32dJ#2ccUiTPw0qTA4quxXTN^F@stvR*o2ohRolIQ2I3rf0>?J4RJ$WwoF~ z+8T&f)Gp3s^U}m>%{B&X~d8* zP{ix&C-f${Am}4Gen8`%yct6c;~U=D7^UYG0`$2qnRHjd(WOlu<;XW+(KiM6fT_)y zd-KOZxDAY!!et!da|x?9u!USxdeTs3;vQbb{d6`M577?Xi%H&$jSyf?$w-LZ!oGOt zbomXV9P=ZrhKOdYT?y=nwZ(VJnUCkI`_HUx0z`ynaO5-I+|ci|0?8f%yB%ZJKlxyH zVZ74(eZy!o+fHXAX$sxyvh3F%=&12Rth_C8hEl z=*v=kVbqdGZN>U9oU&s1Y8MS!KC_9F~+04;r(6EAp($3OI4M)0WEL0ciH^yjaiIGPILMP0Xfv!_PjN7h-<}PenO9l(+zoREa34 zXC7=uJ!5K#g%XkiE_94 zrnfP;s^0*=pu)o$8HojnX35@_O!fN25>FkSEnAZ9)H)Max{_ zz~%+QiI3YY!VwboCkZ|jff7RzuMxsxSG4C9y=}&) znurh*6?saFQnCbQEXDd034%n+&~X%I9000FA)O!59)eGDt>gjA`DQ-ldwHg{t07>T z;V?%rB#H%DCQ?kw8r^V#6I_gC;P9uQ5Z;lR6S&A?TW>jGCJ_7Mh(IpvXk)MLyu&)@@x z_CgrQ(5`w9YQ={a^gcQmxyn=4e=jdUJg8n){%;qTT6P`$P4RA0{KG#G7QK0glVK&{ zoM?%&EuTi{3ZF8hW7E;+@`%=z&v+7^q{II*0qSS8;u5n9eRSMW~Dp!n5vIUmlp3;FBGX2y!quo|&& z!>G7MYF{QAIf_t1ha~+yKM^1X9b$ukJs?HZw>( z*W$dwG}IrM-TAz8i@U%uCN`dl-&MsJL`Smz5c-xB;j=TH$KQZe{cQ$*IuI(7zE{eU zFV}FO$s>-Alol{l*!a?bVQ4G5kfGc_UQVC2`NK9<#4yR-gC@1kE=H@P?$pM~0+9GYC`K})m(`u|33zx~NRfv04~OH?CxPLl%zFqIfAncv0%eRcPoSZ3!s)5MgB5uy@n!kOu5|ut8_!>f zzH*(vndw1zL@n2}%C%tUI9+F6M?Fg^r<5d}1)S1_x{+fQ-+INC-$ z+vyMytFDAgwUrWQN;`d4n~W<_RZB)acpV?u6Q`alJf6~EE&dYEqNJ-?z~miClEgYz zTW13OgpTb3vG&NK3I34*l_+Pfo z6TLE+7uykYC`DEL6TIj3&TIV-j7B`ZQ(EEG*@ zzi7H#5sodFtT=}KA|jQNL7%ulVF7*ib47fqFrVWSM3?NIt>KqlCdNnj;|?yxoLX6& z!^<4bZOo?x%VQmmb#!QGR@qk9BQ`30S4_Gj4 zp`}YSOd;!2?9AL2-+iYT>53&oj@{_gi%z@9_oE%8H|;`Sy^%VzV!5W@a2kduqmXOX zp~!-j1(eM_H2;>JA*5q!kN+$cc$FS!nXbmS@IkCCj?nVu|F>EaP@oHBol(a4j%KZl zC>k6Jh=~Vj(f{y?`_I|nxLPxQv+AN5o%XAzQ#ScGpFZi7%e#U@ACu$a(|;1>(WsM&}j_nE=XjQg&u($P!QE!XipiQs2i}gS9$OGB9B0?>qhO-%1x}9q= zTi05IoyXCk7R(2W#*~UxiJr=<2gX8m3rVRqvDpD~Q99#J1C7QU1Y$QG=u50d^O*(f z?nD~wa|{`+;`|efU^hV)!KxDbkFp=^YCvSgp)BE^s>Kzh%)pPlloz%?LAV9}C0pO} zGV)xrk;znwQ|4aUJ0%_|*8}D{3~5?bre!pT*=Sa?=0twZ&-! z^)n%?6Dyk5YO%%Ud{_*R&1nT#>$C)=6ZK!S-DSyZ$UICoCo0l3tw2yAtJBIlt-ut4 zki_O;7ii|6*|=k_3g+30MSaD+)vBBVeT9_|xAnb$%v5fxA)9T4G%AgLhqPIZOa?E3 z1_?1ZF2rn?Z`%iFdau95gXCa^LbG{!L*|aM4$coVx42>-fb%CSHt6Xa@U0q1K^vO4 zl(cGD=slo+jzIjgVpP_Vr})j{A6V6W!{-}%vP!3{E)UA_ma{KBi^i-$qpU_WS%vV* zgQ5xek1>n-^^CXsCU5gJ=BwY!D`|Ye#(Bvmgv%j?a{~<4>$!?qFqbP^*B+i%HbX!< zO2vhC!iiZhW7Txb;>gP*X2B{)Tx-cf>6l0O`YZ0%{X>jdyiBFOA~Fkg73#*3RC(>_ z#`$mJhM#lRnOL(IeR1bhXM8J$_q^z9;ahPF@vN`zvCFSx?Ba6xNG*D*=iknQdtjGCmM%zdIhCVTYaefEZ>6Xaug|yz7b;h6 z&(nNgHX%&XwM(Xy`liQb(xTv5chFr8b|sr~PMw2Xx3VYUbx758PL*=1itat-E$=d= z@{|%M%{rna>f*{vRj#~9M=9OYOmEWPJq~15Q`e* zlXY?zzkJ3oTUYYTTG^LRCU%H&zzaCY*PgMw&;tKwx-zQj6?mbz55PV=Tyl0bNN0MW zSFnXkj@rU`Lzg4@UFI+9_vM`EgGr~YO5n+DRf4q{=9yKwShKPu=&7vj1J4cktmA8X4o}`=WlxN)dM1eK zFb;?})#jy@Di%)J`jj8~fWH2gUaLFpx!3##x6gV5ie|AHvDOF`^1iv1qYndd0c} zLSZI4w>R6&rt8gkc>5>C%{iH=WoB z%aa=PltMlCP*1AV(;dI(DWH8lb&q>1^(4ypi&7CL&k?+?_2f|frde^yFV+ZGvnEeW zZB|eD?T2egAPlOd z=QX+>EDtQ{X~ZM{4W>{l$G~17zx|`<%u5Oo)W4P#u<*S3GoECqyXNer`>k|WSZ~A= z=fzW|7yCU5p3&$}IJ{tWxIg;Zd6ZNQNu6)nD)B8Yd$nvimy%nNz*~IE5ziuVTM)}C4xq4b<(dx|J6!!=Kv%;9r9UN^u}=agso^2Kjd(5iZl?}_AT*N*LxC`TLe zXOo8Zz=;h?61CX~4Z~S@_9nd~X#0|<{itUE6J)R_c*Z9c7t(3{bZ4_1 zf3h*y1>cXqvBonzv1Qqbo{-GdNc5ER$gjJ|YF$sXximz9>{HVAc&jh=yf4O_?`bAl z+pXR|9nT51^(<-C<=^lKhpzoO$NK$`Cf+6jcq*rU<4V8akbbGbbsh9T8-o=rqOICd54pdIens*W*i(~#d=F1(Jw4Iy zT&P9$>s8R;SE6F8TFRdFZ@-8{yA?ft7ufDXzR+(jyw$H8N(X3@kGi#Zrn!D!!TVyu z_YIieP;$(-XbGx8%dWceJ^-mZYIT>ZKP%o-U9eqwOsDpyl|v%sQLd4A-9@82FXd8~ z`^Ya{V*R#MUn6sP!nS!Q|IO6ssZ@qy%{J0+5y@LB*DXsH8=k)ZdBYS8#5a0#=jy0362q{<=z#emDB=b;@}umC7C0 z2;Td41i*V=Dt{@J%7sZflqU6xT&A3tQmH)FO}H4Bi|el$>yMzZSF3*wB(DH#?QS{v z8tmAvjn4yGEO?t_Ljh0lzKQ>5Q~PmmF-C)Xv$bpTjs9UYX%~KXk(WJ>$1vsT19Z?~ zwf&$+)3<2YwNYc{pl{6_@~5lE_RS%?YNxye8SBO}zrNOfsQ;E^gT6!Mv=gSP_yljd z3Hk!-I?n3(^KcH(N~12(OY8bAlRS%4U3-tTtJ*;CJM(_}m#sX zpDFLzl#TQTk^CUhmwe1S=_cFwJvcciY-o7fUo`?H!KA!`Jq^%g#@x9fQ4g-(bA@?>v9B$XalRa2)4_=4pHdWdHhl z3Ul~nS534|zJIUv+idmA*1CL76@DR1vnZ{k@u#&JTRETxb(kq>KF;i(zdNEY!}uc? z^q@E|i*=YK35TukIF6@&=T`GCaTRBL`LDW)ny6%J(we;q+SadGtKeE(`E~XSw_vrp zVck}%z?t0QnpHoo)=3Uuk&jZiCVb5VDZmuwxTN$8M!qT$Y9V{Y@5Lc2b`VyR75(?S zT8XyTqu|epvnpQ`1M-qL^UhHfe({#IlO&&J$vrZ5B+}J*uAY zh8D+CgpuF1x=yw7bpES%g7g*6utH$Gxg`eM2mjENnVHLsGM>|$Y;qA0Y*6b@| zw*Dx)p-^iNj!)8LI%(`UuoCL9JzxJ4-#zT!HCDhEYhkP?Bq_Blby|S%y*LoJJy4i_ zEE0QE?7-{Net|q{RBKsUy*9$IZS}aKq&U%9qx4Iz{a(0YNaxCYsbaiN|Ih8TvgkMWTK8pSb?%W> zDXp+n#mDw9b?O)5KREXG*kJV&mXsheW zsYVXTc*v_R>tE{nEn}y1xc@kjApMD&t!pTxoM%%F$Q+kqr8Bt8YBylBe92_5IuFRt z!QVaDcRmZf1Qw5Z5VjgK^HtGG*AI3r|LQ!bqpG|r9%U!*n0sp9;@zRP_R-_ikBURg z=H3cJ+d7OUl7v@EiGy_Ye2QCOtUk7-eUr@Ete!>}^!GfDRGLG!?5!89ml>w|lDIy& zFQHXEH`x8zo8Y%>7IXlIIgg3+uG9{sG{guj-W7A6*~r_fDNmJpS(Y+v_^7)49jQ#; zQ9sqSelw8W6+FDgsXUId_`zZ#ZSJWwj^5ghQE87lb=2hbBfLd1VQhy&`c?M#-)mIT z@A84L@4wOBv$!Wl0zR(z?u)31vme2$T|3*IJNZ$TZ!6l`ClP07z$t2#ytKK0H&fWD zk4%cU1@V=ys(g^Al@)i^>cYfqlOGpU$%l7`*4>|qAc^X2{=hDe?VcRM|AzT7t2SD> z%sqBaEl=n4_TlkqxevpNeZgV0gZ*1hRH%!MUh{rD^_c9C`b|Dx>RG<-%o@=Wg0n}I#4^bA)_r+^3Yh+v7Mr6TU4~#E{tx&5s!Z>uSq*%NacFQ zw%cwKau-vo(}e88X_9|nm0i0qecn31)932QqZo~RO)O8*Q~aDDFHNI;>vvz#@6La* zsHhz!?a!f06t&aFW7iECqBQN+H4H$0!rRHKoFiX^^*OLwN;%isz2Mv1_qB1!YwKZC za2a0Dr*>hsSR&9*4FVk|3_mKw6R>X@7Leh0RZwUvG^A=3H!fIZx(fmpYPmrx!vPy1H->E4*jR>ODjSeNb0tK@4# zpOV#CT$kBuYMZW<=KG4wwEy(cB=MQXpTXw(rj5uMzGftPZ#jczzlcFZf6VnO=j$e0 z%YH9~-+k9>eU8mcpe9dh68gm-?)Zp3_CAE3c?V;;Vm#k4oieS+CRTYpg~u zzwWd`D-9W*X*MYh9hveJWZ{8Os@!RciwSCp2qF&nqAnMkfN*lIb_1w z%y*dXyk>591lGqNcX9fZ+%LzTj;~4kB`%pg*lhWgEpKrSIOGRgdV7iTbLCzZafVrj z&iWh^C-^BZ%|Q;LY5hpCf~=g+{rT;((C4^swm^65|MGSk>Fh6;&ySC6Hgo)p-KW-g zKJ~KP7A5I)kKWpQ#N%qDYu4=2?e&r62H2fbTV{ucNRFrS(cEd9UBHL%SbA?$c@MtUtk^JTCn5LdJLvso&G*e4CcOS@S*NUrTRcLX<>$d(#uRwXTD$xFmsv#y z^%CY(9`R|0#!sTd+o>X@FT&+q$1{-o+N;&dtu?e(vfM+sB9g#M+j&204UZ4f`MeY7cD@fL2hxN0)?e%#plV!+Cy2oBPHT?=lp3+{oqVBHK zk4Iqpa*K7Yqm{MWvv0I>jv~AuPk4#HXzj7gdjoSc&C;wjzxeFam!6$cE5b>5y_8Dj z%!ko)>$?AHT$~QNHy+My9MLNljm7TE0lSa(t7=M3+VNccnB9Uxuov%j!*GTD6QSJ?zR%6M7N7R2`#<@$FM2*D$i1Oi(@Bw)cs3sg z27Q~iXpjAYuOxRPl_D!e`b1``DiI6zO;69iXFz=1rD(C8WVSR&7bR$35-B&ZXx`s}%DXOX03rM|Y zE^oEu={%x7Qg63Dz_;k8k@SUB%~=<>Szh3}o`Z<8+E4brKRu%s?-R3=g@@EN*u!H& z*>5~wpCSR)Ob?-*X|#QQrG5Px4%L!PJbk;?zW)m?NKJbI`9O@MwDzC#vnvmlo98Ij z;?%wDCZ0|A2p22~-!rLrUgh93?fdr?Bv0I2iWfg66u6@A>6O7G=&n=_`QUZ4)98k+ zk5(RaMue3z?wyrJ{6q~sZGSp;?(5He=L`~@a$c=>FG(^vOmbNPtD;?6=*r6>FNM!{ z4V2<#IerF5827iv1lhFgVCj3|>WhO0WU}QrTRhk3C!6Ga8s`oAsjMT_ zfb5hy!>vB}+EYy*x@RWJ3!gRFG_en_uCuJH0+7p`f6k@63# z@7L>v(_ZSey3bE{B6&~F`A?E`rJ$V2+69sFa>z?@-tbQJPrdNDsm7D3K9C(+9@)rs z#%J|Gobht3FZV)0`dJd26UZ_Ss2%It2%nz2bR^v#g6BYf?Mxc9?Wtsk(4kJa=Zy0> z2l04m@*Kvew}I;5CvB#dw@S?0ALj#YuO4wvEZH2RZC?VrI_IU^SEZBv@$N#l&yO9> zYZGUz-9;i+IiTU>csRE9xOposjUA%OV~%V*EUbJ7~bT7 z20aT}?t7n*&G~6^>?@1hQzdVuXC}QNqSv`G{P{DS7JzRYf)vawxG`_MXS$>jXSyRFp6cI8&Rx3Q1uM1r46 z@HBXmGtVF!Gpwv;I~tOe+kL+=#y$-*k-bJtZ`V3{@_qsR@OnN4<$XqF$JK^Z ze3Hf67u`^n+r>pr`N8XEC&Vw6qv$={QLWgQ`%mo-6n}P?`I|ORPgAQkWSZH(-j`^| z?uNWKp6qkK7|3DRD^1qWq(a=Sx$CiTwOhmRgEhQTs;FYb?IXCa zEcpHWipLV<^C|K0JVYwZA$NO{!C7C;;p*C~(sxNQvRwO=)#>~(IhVeRAzi(;KT%IT z*FQTsl2wIQO1)Me?v)arFY!`_#m4c3ug-fLe%UU!q9{jqo^qL)SR_T56^KFSHAGb zLn$_TEzYN-urrIC6iXh4J+9tp&2l#;i}ZeJe)r|`+H5S^7j19;5PLn)<{tY#L$EXb zw1Hk&1D}U!%WHaDdb(RP%B|PeZS~_2I>wt@?18=O%kM+!w`{Z90{W)Gr(~B+$!EuT zj#@j{T*BGRe@UaMTo~F|)wgzMBdN}As!2U^<#67{N5bj%qWIhckITqdF@k)+2H)DJ zp7hxA$%dmV?;9YszT)>XODk^=s4Y5OSiAE+Y1YG@;k}KU-7wv`;!Cf*G*5@}_ULUI zblqs}$ThS-$4RHE{Zzd$7PNTl;I09YBL`sl}(|R2id}01&DM9sx zuSI7^#|gJV`Z`B_9xzJY>P?0vnI1Gb`Wm7{ZqU~%_K?0>ql0YRpN89H~9G1*<7D`&)Hn0UTXx3 zQCCjC3nJy^^~hB}Y4@G|Z7xXM!Wrr(nt={{?$@sxH3N-1vyb#lyl)tPwNvRQ7F!&I zI$e17(p8_DXr+bKX0Z>7oOnvly=e4zV4kJi;73|&Yrdx2qWl!r>u^^h&qlQ|nsrEO z)_tg*(tIQ384WOm$hMA0p2J`g)cAL#4`&*?xhI!1jr2*6q=1c-ntVBjZEp~CcP($6 zWOykh4)=%OfmC~RQrm&F7V6-p-wD|VQsW`d7_l9C=9E?MT%x+fhq@B*XU&hau z;FLBxS5x6Lyo_fatESeAef13-yI1tw1iPCmex-hmjf6SBEF;IR>vmp*6*hzI*C}%H z`teDBK!xYY=eQ#`JNQ~yQl0%FtqwAor8ju$dh#fo1o@l%C(4b~-mv>)-3zi0ci2PC zOaIa|Rh-;QziJEFw@LeFuw^0~DAc~lQh_7Uv{zjUq|YkTlQHYE8i#x15AoSj7g`s5 zhqph|s@R`F0@F-Qy)DbG1Wk_nO$ig8N@vitH+aEYGZ8$lWHJeUm!5F$d#lIxTMn@m zkDVu{O%3(fW`6@)uw%tp=(UDbN~2ICFIh)3zfsF@{6!&+XE=~ddw8k4@Jnn#Lw2(E z8UC9Zgw`{#(nZqXo{$<#x^TAR3)gx@3}g4;-rH|PBx)%oY#yyCdas{;u+wT@qbZ+a zyrWmlxkNE>@KUOyye;ipbV*(ZWLI8)2U7KWBgx$VqiIYK@kwC5Pn(`nt7i=EU@(1k z(f^C+Nb(@1q|(b$ea~yeMu*M|CRY1s{B-RUYftveYl2kuaxJUvv+|Ne{#8yb1H; z^h*v&qy4I9Tr-zE*US>#rJkss)gBQ|dgp}C@Oq}@cV?2$zzQ1@#@AmI5|L@io+2 zSchRT+Zt;f{5LKi<5E=MZ5$u!+UBX$xlGU=sRPUiZ-unU3=cU|i0_>L3DZ5)><^J6 zPuv{1J?52Fd$@hFO!_o=K#m8vl*?-n%i$8di?r>g**4M_@JWr>;B0~~*dY#v!tE0f zfCB>z3>2B`L<+zoNsewdMX)#FKNN`g#wH+?@+SBJFZc%(=q`qwIbmUiTqI6KdTJB% z4){fmz*Me@7qkg!XuSYHol%ixz=E>dGtA9q5$|7r$Zj)nwj2zPs%cAeH=Du`K&gTn z^37Io%Al!-P0lAHCeO?#SMrVWnUg;fhO`6O6+`O?G>K2LX>}v+DXt)G8+8P0fkX32 z8Fg60PzQAr;=jpRo;X1wt($5IbkI>LA)B>85c-sAHtWEv7kU>J$g5O$D#HUgPqyFw zN^*f}oV6QDSfx1QQwv<6qQQ~Ve9E1aM|krbxXSAMuxZZ_=F25qfcpWTvbNm=uYR+o z;BS27FaNfAK9t*U4yJ)SA`fzu8`G>{;7XL0LX$`ML=KW|T&g281OGFaKf)oO?Tcy= zMVgxNB8@sm+DSZ|=|Sdrjt_Al=*OJJP3W{~bFym$3%&r+jlm zSID3uK^K!`!-pjjt}JFdr2mkf2<=5O>+lw`nq$lWrst`76lwZpaeKC@Vq2&J= z4o}&^eNTU@-}jbpdfM-8ZqmPs8hrR&z)Acf=N%`g^f@OWNaZw3@PO=-Ko3Vl_isfu^%XD}?U${nKJ` zf4^L|&7o}CeZE|l?S5Z2`+3Bc`+dWI)7!o2$K%7p<73$#c5TyCkB@CxwOP5VjBVT9 zv~1h;<73n8)@57mj!)S!&b?iAOh(*dq$d16U<9&bm+^4jb)E{5k%jQxLq=@(aLleI*;8hT+ibwS} zus>|uZB1OhUmtdd&1|+>QQx8Dvt3u^YzBUy)3#sz_5M&*L|4Qa!N>OxQeWF+?svu}kZrr7_A&evp-EN}p-)R$ik3~2ura#r`Ov;Np*jBNayhN4X<1F- zCJL>$hXhq+RZgeVk~lh8wb(d_o>tSxN3yB>##KKhx|(L)BAR+aje!ld+J*p5nC_{V zXY!U04}D)k+EbO-nN@P?Fz1xK(6{z z3*9@Ut!dWlDR^aVnKkQ5r73s2s(e<+j@KDdepDaO2!)Q<{$|e$73KE99v+Rj&K`XJ zciod2j#+k#UZ632t33}+d1ebBE$)!nY%>7X%GGR5#?gNu+a^FJ9T{gMzvO7q~vK0mS zeaa|(v;2yO$aVi9b^VF9->m2P9@_K^=h?idcH7-{i_V|`+wHzM^uNOQ*^;`SAF6G^ ze8mCH-Rz2epB33IW1NO1AhBrHyKPVAmdtDT)&GWvLsn-8tZY@+)UxBb&35f!UK}>X zoR})FvT3%hFbkW*_R#le*Jd@Czy1`E0gtcd9;dhh~=<(t>P? zZM`mX?Z&n_fHWG=6h*N<9P0n$v8LknVK)0}wcVp`C01;(7J|aAm0K+s3GslOqBiZidVY|-!CbSZ1K|Fb>p=@YW%zQ;@;7i6fjN4|54 zr;99wJ99GZfz(j@(XC`Ok zILur&gLYlpstw1`M@H-fTCCKs+#;yr%NrR{pUrMv~tRmD9Qd|o|3#FtX^%iFoCg#ipsYOjZ z5ug?MUeRXV6P9-Z$M3SQsGC<6V}pNY3oK5w$TiP2BG0!EHq_k`Z|qPM)AgpvGpzJ# zx!z`XMX_Dy1vwUOe54<_2P!VzM7w_5ee=*|cXovIGy#${IyQWS`_nSt=0$e9-4+G) zO^{$9G2>P|3F%sB$0PmRHTIg`GH|uayn?WabpQ~T!+g&(OTdWex#&IPJ(gU1;$FrE)=WM3_=0%3ySgYan)rb8yeO~|(`UTgNk(sdbxSVV@PWQs%;{lQ&<7@+QXRZm zTxZ>L2X;S$%4g8A<9vWClwC~7DVfjDkB?PZ~t=lQfqoXH-j zaW>1kfV2XlQ&6*L6gy}pSwQUpa*q5>GJWGMEn#agpNWfv@y{cc2SyggZi$7v{i9`M zmh8CaFY%zF_PQ+egW(3D>4JROwfrfnVrmS%EonRzv_jv1WB(0mdK13u63#*ubl+#$ zL~gBSv_f?4aKZNY7<50}QD8#t9d+Mi`r%WI4kl}QJgN>|N8`h%DR^g^qjHKl$W6(n zhv}i?vn@6_q{X!B=F_?W`Mk@DU9n3!W{V?o3O2OxLf$HUi0dYUbRj)hw|=QU|Le4K-JF-7db>eg2S-9qtc2K7v8XV-B5A)8F_ z>W<)#h-arI!AXa|d5u5$RhC^DuXhPNU^XgKBQ(0_V9dcr*M1dk-M&>NJDSdby<`yjWd$}1C>MhUA>)y zCthhp1dX{ts_ME;yPfZ_cJ|g0m(ONhcgUNv*zLDy0|sh4-&e%#^F8Cy9dXqbudYb+ zQKjPMC=+dTnuKLUxr4{LoU>P z;5S3R6N$DwcG{lI@k=+M61Qg@pB>t$jZaT z^9LgH1xPQKUmE1o{qj)nkTm^L;{G7J{-XLFMw(F}>3x5s55O%^571{!$K9&eUSt!Z zZlaErlxPLD*YtMRHzYoMmEB$w^ZdM8ei5229r9gAiB;>qoQg$uQ+}DL;`d%&B?AfGqmSE#VrEO>fJhE&p})bO9Md=mk1b zFjV6Kn$0mq_~|_9aS^A_n)9c7R`L4`B8(T8$P4X^5658PtdBYVpyLq+DagoXQ%?`9 zM&e85{X(=33=ot*s%u>MGAk#B9PZ9K<34&Dvk6a7=* z2mF3M2UB{bc}-86Ge~nZf3dqgvyrysdSC4>e*A{fyu&r(n+jVp_6@ndvn1+;4^S|f zHkDpEP1Se5shJJnu{g9{pEHIB(!Aau#&P{NFAhxe!G|q8B_}Q!CUrhfRfk+1u_Sj0tS-7|Ay7?V!y6y=fmRD1pIZgXY5oL42<`rr6k*Y4;{Aq z7zZ64txXKmvKU`otl$AcRcV{1bH>`Ku55>mEz0#lxhV2Iw){|FrmOk3?0-X#J1-Bd z^P2nJ;fW$^>awUZMjLbt%YAYpu+nTE0A3~KFD?QTj+lh|Mu>3QSK_`tSL*U z&dkCWj9Xz8V{;@7;?@$wd{5obj- zf0mjlGZGCm68pA?);ilU{o)889*vTuHA}`u)Kr^9p-kGQSqEpY9AfT*t;~=?0aIT= zRYR;+^;xeuy5n)aBhO?0S2v!7>@jcLEhX+>FyW>AWI2pxe!&R`=6>KZu}(S=yI57( z7v(ixxE8Ram)X$r?*53T1n47Xi1PfSr-@06>Gb)Th!Vlfot_{s9T2c9`aL`WRx$q= zGFcTUMNhKRj~_Kc+ywsi`Gtw*`mNq8UZ7EYNWhlkgP_7h=7#$vHp_Vyq<}u45mNJihTdtd|KxVPo z#4}q$DRD_y?OnC|U&d8CIqILO3Qr1+wGSmoP3dD!f5#TP#Np3JPJ8-G>=>$txWsMi zQP!pM1#VG~B@(|4vEChd6HX(3WBt_tRVd~bYLW!Q#wD6kyBe2j6nkk(*cckiU+^=h z+)FuyZh5^9+ixtBT3%_{E7MC_YtfW-r<+h zM`gQNALbq00SV__y*U$#deF zIdy|a{#jzIS8S5(nf^M~{PWOigR;o{x5rdY9-VE0d1@y z{igPoOD$e#bFUuGf(-iBkA*cKkCMhPtG$zq!u9Va7F)l3I zS*q*E@md02;wrZi+!RU}BzOrc@iHVYic^|db>RQW$lo~+hKk@fNVyRCf9&1E;@{@b zG24k$fNN0~JPq>^NDrZ5vLI@U{FhLaD}X_%V(SyKR^uKsm#QB8A(AwBR!U03xeo40 zQL-y?K`!}s(K5rA*b8q4oD+_&VQh=VLc+X5Xjy4IXzjyd^A&mls#(-rH{;H00kIX{gV&>4Z8k^p)L9fbdL_g(kLtj zagV+IWAu3L*E(y-V{cY_!AMIjNjQ83}tz+umjsNBZZlO)}4)VB!eNjXBgmp{Bx|zA0C41pZEr>2!KzHXK~1( z%YA7v+yOV%vlFgxB!?$CBT_~rcF$TbDUx&Ir9IHcw`E32NP6wMB{LG%n}dzxA_gxY zQ!%Q^7{hJm8_13El7lEJ03SFSOW}J*9@FwKr{dx;@VRetcXegEd{?r>p1c^bVSw1e z9p)|r1M>5iaIw8ctPBn9_Xt*g+_~;nKlcO;+w};EtDh4iaF-dmm#QmT|rBqA(Rg}BhoUads@OUE0cUhh~NAi z@)U>9eo{`LQ*g}b2@D>^Bp>6P_aC6<<~^}H5-w)Kh&&?LEKkt}gwY_lEs*#yF*0CG zS>tn~Wd*WKC}0lo<1t!}IfS`s7<~fPjJYF6lc8nYypRm7#lcB$52J8ZEbxCbMr+T4&<3Ll^uc*Cf|Sn(*Zr#Ur02BjZME5dFw?!0?nav~a$`b2w%Uju1oPoZaU^xesTq zlPO6vb07dqT+hj3d_m5{Sx?j?Sf=Drhao=s5Kkr8i-Ef)BucDXOirgc-^|ePVUNuj z6KW@U%`qa*)-f|T>?I{v$WCs4b4MUT#*Ez0JtVR@{cpg;#27#1C7M%VNK9$9o056j zmryL#=DE3Z)1zFQXdPRCNKiU0ZDHhr{zwSYBJB9#0lo(Rb3R+lH$Y!PUFBBb=Dyt0 zfg<@0r%!6h6hGPyQ;erjROgI5T&4!~k8gD&Clmh%?t^2-(*^E8g@j54`0h75k3q44 zbg-Huk2d=X#F{zU-uJ+PW8yQf;Sqg1PlVXuxtV*uaNdhM8B$yJSYSixNy<`{Baal( zmK|bZmNYm{>osgC=Cfv1z`I@j`EnZ(JLd0xP{K)ZxqK>HWZ`EkI*WlG=YcNO2Z zwfoh58}f?NBDd+BPLht0E##-kJP(Fv)GJJSeLU?>JyL4_kI#X=xNrR)2n%;@rzQN0JTB%zO%!J8_eC_y)9qjQmH;d%0i5jrA_I8LzBG))V(pOLG7E+|FCN z0>jrQ;MBA`PuhKoYl`C*mQOWW%wN;@{|W6}ffuJd*g~XUxo59P-$l|ttedClnUr{cnn38t5 zXy_&@k=rU-^o`WK#`l%A`&Z04@Xc)(o})=RI&^!{OYc4LzS-=`K{KJXK{HRrMsdsQ~iL_oc9nM~Q;DCTnW*@Ak+c=buCw9%umdgbnhQ7^W;Q;oY4-N*i#GEW> zO>-`sGzPS$VK*CcFq(UOI`Ux{*znEpw`UK_Ca+n~DvIal{f>E&f@Q>QQTGhN!J7X| zm-JJR$L{F%3N|1-@7OPJ*z9)BsXRg)nU6JU zbLT@lt#%I&?zoCN@->tlrYGvD4tZ;(>}}fq@|ZP6_S_wsYFEz>bzMHt#n5-)g$9if z2^W|G2pU;5yT8Y+gl=M45C|?L-sGk+lRkfZg#4pxz{evc!3At~Rr~NT-L*T@<7U7_^gchV>= zfi0z>MXZ@pBJUKA-13~SW+Y9s8#nN<+{@8!Nt=L&N z#USjnZ|==gv3?Irf(0vP=3o$V88dU@%=~V)teBZ#pJu+>8bf}hb(B?Ihyyn3rL6Y7 zSW7cF7WemVMw-q3%*`VpbaT#&!SkJ1pC%k5}DO9DpWjW8_A8x83uQ{Uxh5112`eG+L6} zfl2(pb!&=NrB#rQXihO{SXg7>=ZuMQy9Rk?c1pg$#|kw=+ke>|)^)XCqkmXvj;0|~ z`|bMBou<`hmzC^s+?l^-13<$r0%~MDvOa8UcWbdZk_~Whj&m`nX{8R?Px$S=+iyF! z7p~po#dgISEmam!xg9AOkNtKw`@cGxXM+u3*8yin$Ui+`lGs^yWakPcx7(UgGOK&t ziE|WlHXO0F4hlHkS#J03udpK=0bx|q;6-LtePHJXWYlbQIv&~F&E`E!AbL$Dzyt4H zQL*!wnLoBn)D0QCj)OWJl{tVZ6mvpu%@|6$OKRNiO5#~6V~>w?uS+%&u~5oh;W*@VH;hG(!%&&I~wuO{)Qhy1J4BU{~9UF$)Ir}Vs>4M(&AYY&o3nmWLls;nmZN~wQ zgOWmA+2(b-2E#cku%3XSb(zy`@N8p1+yIALI ztUEksy&Wm`4C0zq-fxN9&>Jnjq89dua8_rU!K3c^uw~NmX3vR0Ox@YmA#n)UG+$sL zN_PHf|1e+(;1v7EYC=f1VytYVZ`wAJu@VH?qh%;mgb=2hsmJLNh2-1^+Vb>3kD@SV zN-_%1hu(yVPJ0^EB}&NuR`~qiwc8KigGI9!o6N$m}lAKn2J!wM`*dPRlTRYd4uM@5zQ;q?drbbZOD2MFS#m zjEu0>iw@e6Lo5#B$c%nDi~L1?VrPlRjLd(7b>Bt}NgA(AuMzwDa*n%a8mLVz>~)zn>mIVO^ZKvt#<%Mdsw>x1h%*YsKa zM9(qTFwk|Sb?{jR%W+pY_><$9Ob(Z|Y|MHh%BDyQFfO#(G;FPLi-3Dbp$ebfokfT4 zxvl3s+xlIo#fJpI4BJirK<~h=3VP@DmL(l5 zDwdc|wZ^HZAHnnCBq%b4rEaTc$8iL0_O@o?gAl%S!PJ{Fhsmc?qUR4t?A^CVU?cBt zUPm9o>CCl#*LGjgOH!6FExAKz$#*z3U_pp8;B$O+AXc0`=4g1~?sa_ty1wwL*bK?8 z(t1uDB3vK#^hOQ@EZzN*&7pKq-_k2_7;{grHa*N+F|GET4lOx_;K~;Y#+SS1Vr9$y z_32~W@Ud2WzZ%~Uyit~Rv)fR|oD+P=6J7yKVB2Bjt2RKFH@i7%7#_!V-Oy(p=-Kd6 z=%&}ZRCfaJnwR!A_V!0qnXm}dl02;8&tgH7N1NNK7kS{!6KN=AN~7}#iOJKrsb<6M z@mS531O4YIzp?M&h*;h!75FSjMa9-+bI?`st5o$N6*R?x|I*X$IQc7Y86={-wknen%yLq)0^eUW7ShMZB zAdfK^T>Ne8bdR#T!Ptqq^XTlf-U)^y(0rRTM<>UwsYVwCfOS%}t}%o9I)2qTieHog7r+PH!Wu-)RWD!nj(`I z+kG>ycRMAs)kl*noXAH0TllxeZX>TD`BQd&!MH`-s zs@#HKwtE9>;j^h!19tOQfnew$4ZEoc5nomNG*u2{uRra1O*v!|Eo zL|3QDU_>V9Q_);l(fBbNH!>Gek%;mrTenY+K!KD${GR ztM|k*VTlt`x8Hud!`&S9Rh1m=!Zd|M;~b|?wpxAl6)XN&cY6RlJUoI2_V{K^p84dt z^ZtYt!neZ&bEa=5`R2*BA0XnnHSsIV`5e}8h{80mH?5i8GGt)vnQ^`e##U461TuCD$iPJbqlVSW zmfh6!P@xrTPTSK*p*tlG3Ii}&8()Y{qoJl>c4)#h$6`6)VSH9FnkRov|00w%{l&cI zmVsxeq{TUJ4pupPv^UHG@PEpGc5QbLEFxjNLOcpq1*s3{1=inj(Frx)aJ(7m zN7gW~HOD59zjj}3*PF(?H9J|S^j*j=wX>OY*L}+Yx~x$;cN}q`$a49No^W9ehrOu_ z9K@>9^YjUcP&qv0mw~WW4Wo8g&+WMxzio9km!5)>NiZT#rV;eSSLlt~^wk!JQGCMdx$3$_ z=eg3m3^#~lW5lL!4tPbq2X3UmVnVmJl$$H4ZN6Ev$&|R_Ft2Ew;<@vT@l7U9FqF+f za&`*t`)&WNXPge46l&+sGWE6?5xjIW3%du>?*JY&2-** z0-_lRua;jeLJL(ov|A?vUBo)wL$4B9u~RAZ7Ewpz&^vuNl$CtCfk~%B8_6A(a+q*J z2^~@nr@Jt$4%z4>!=uFsXJu;1SWS>1XKcQ4^;iFw!J5N)5`?HEpjlH$-sS75gBcxc zhc<@ji`_4Tl6t}mB`%pswJI~EgC(g?wbyeidEc43XF39byZGoDV$8!6DShlb!# zljEYWf=l(acUriYCw47k88`hZj&zmu<6mUgVjc8)UBP_jc#erUh8vzlN&OT8zu}$H&Vz2UlHDQ$}fUL?wJjbIOJ_$;iSeWx_;U zv#28V%L`z>}&N_2{;wR7~U)PwQVGmp6YH5bMnP91Y8Sl4Rnsc7MCqHnkv)xisTsjj4uh9AT&WjJ1YPrT8WM$8j>_N4yz~6F~nM<*ePmQFLlTi6Y}n!9*Q< zR&)47jI!WRCY9TrL+o=^XsOk6oe3wYH%ASWR7)zAVAsYy^sEZ)u<;2Z^7qhB;Y08* zSyOqSkxXT`Uvq-#Z+I8XPdtU?dhA$o#Mpc(PTOqla>qDh<;n$rW0TUn4kd9;kZQ`* zQO15R-2^1el=_n6DNc$tMHM+*MX~Q0cTi~NE-jk0&S{zi|5ARWRtVyIDU;;JoT*Hz zzlgeOzWp0%O7b$sy@ol)TD$xi<;5Kgf4rhq@-!#Rys?weX-@c|$DtVTne}AgC@(9q zsZPEJsZWx}$!GeYm}qu3J9*ix?)A|vF>hhHS&xHJxc{4{I;d42Y$1D7+6#@CmD!gS zr{~#M%LP-?n)o9BF4P*DM;SwjZ}W4`OPNG%k_2|0|0wpHi>spx#~Tb}z>)yRk?G%~ zBsbsrD`e}m^tt69`#9G>={l@itbdVa>x>j>3zIAdw2l*1%&^xP6H;(&lwh6-3%d?Z zIBb{KNrH)g07uqXx$h$S(}dAx#(Al#WI-i8k8N)`sR!CmKKwpskJwqCv_*Xq4|7`P zqQi!gesdZmTTIfvWbH~#O5h&&2vy6V%sBm!Xt2HN2&bHh8ZDHiO-Wp{jxnd&k#I?6 z#6aq4`Lk}v(*Pkk3#kQ0nN4*j&dq}w{jXG)btWGAZ1}Ymut!b!rJM=p6izwE+T~Sh zMO#*XL@lo^KlTaPW}6e6up1$fd(p3>wV7HrHlH;Sef8f77ILtl+K80v6(mM11*?8}%8WMxw* zTmiGGH+Tw6EtANASDfsTZ6~P)5^FqMh+vo*F`gI`2HuBVbD=&-yS=q(S~-6cAI6Xn z#jGA`sfUp1`oqEiLZWca5DAnH-7mM?H!+vK)P5sOdgQLhd$08tm{&V+4@0U6t1ERl zxlAwV=d)`BPja8?9kJ2B0V4F|NHC+H7QO(H0WBK9BsZ3Plx52(5hHc#iQGx;4c?Ee zB{&{sKyx0?x>Q51XkkxBkVcsQiMR4N_RcVZC71t4jf+{NRCcsudg7kkiTNq>2J9p$ zVp+n=#LpykDc!o%NLvrleEbVW7 z@xidiN#7EOQXYAo%8eWxU>#{EuGTDBo34f$M%oy0r>?g1EaYsI&b^nA%_DAU5kK#sXWvZO+ z*IaVJ95AzQhbK>XkjOJooKW7ZYsP16r(l;rSdo{~ zZSHON8}8cB!MT>H8^ti=z8AePbXg5xORn!ajd@=pV7szUk6;$&RJG!Tq~S zne(^hu1OoW7mlZBBQ#1JgIa%A=7}Z%PjMS^hPQ z#M>Xk-oMgelU+-Vj=#2`lhCVrZ=&c`uI*9c&-w}o7tF0F(OQEuj7gu zzKfnkoMCtgJHq4pSb28<&+IaO`?dk3n7G$x1yae6v;}GZ_z`)ttoh>aJ44@vqoo7( z`Hds-^fmQ(RwCZ6`MH|J{B`Z*{aTHRwvV@Jehz|p-_kisomwTm-wXS|IjHM(Z9b>CH+X#{_TxKo z!S^@u1B45#ODJ+C+2@<5@6@DAYLr8^lRo+`Xv==85tkB|&`9;-VjsT#u{b6S2;F~R zu<)uSfc{T`HShmGFa1kz5dnu(cf=Y0f`aR4y_a!;cY1^MPt>iHd-A5-d$7cM%pd75 z>iIPPCpkZUuFNMn#pM+hBlI7V6AmueO&_qnC*FbKCv_;vAJ`i;-aktZ@JXJiCHHY~xd8Ojj(*WbWxc>|}KfVuh zm9X%gkO|x0*FQ@VuNPtH>N_!iO(jsEQoHs#{yi#*`(Ye;=?{$f#_vl$|3H|Zlz$)7 z?$reS zS-9oE`5T>1*12icXR&f8!9YAzlHvF$;VrM$Y$;ujH#R7qL1Op0O3qAHhYv= zW6zd*kVq-J3j`L{rQS0X>YssCf}eXN~!TqW3dUHqo+C_|p{Jnb78^gfQI z0#f=O;qi2d??X4$?3Z!xV);792>CNm$9gYN|8v0{eO5W){gO^dUHtf;2=l`%VDinlwa3@|{dm^r^mMeN zNqwz1HAkNJ;$HgoKcw7$5^n}R{EPDDJqpkKPLwa=oa%dAco`RAyhX4ZMv)_)FYTH3 zC~VT%ZbrGU8JES$TE_t?|L@Quq@DA9cj)`K+>rC@@RE~v`~A=KG6Ee(khc2gak6K> zq*|vEqaI#*oXA7I;DGtx4gH!}b9#dR*O5yY&Vc+dn!mf2m#HtqVD*vzqehN>=Z{^j z|D^u0_X{jvQ*(-OMfRbKv^O3`Q+q*U^qQ@Kw) zPS-G1%R5VW70<)beSJs%To7YP?4B>OOlBP^ybgjV&ybU2l9ANuX5Slk&ndGBJE<1g z3}F1+nV;fUgtG_!U!~T&)c)O}cd7XJri@bYS$a*2zYD!1?Px8yn(AwZhOxpW6zvdY zqy5h1-_-s&=*Ev_-hH?1yR==(ya;`g^CPg|^Na_nUpThro`pf~2JcI|`I07J#NQ<@ zduJ?1sn2+C?^^87`$h#eVk|i4|fHb*_#H* z!awupT&kEtk?)+7xP5cJ4F*{5l^6a#3cEvo0Phi6;-UsYwVQRSf$)G480VLJ#D=@i zyap*1C@a1*LP`FN|EWyoO265hyWem~~i=84)!j|6I!KK`dNV@`kN zPQ*q9h6wPFkTJP1hdb9ex9@#Qad4BJ_GBx_Au`-@$eW@l%XUAmPbW6og{_zz^?_-| za64bm=^swhv73PH)2xj9RuK}pS5LURmbWjk_nI>=p3BMv)wnaQUa`TYaTRY-;GH1Q%6UHa zCTuu^v*G1wV#y|Q=mo%lGpvrMfm?^540d==4G`FoL57N(8=!R>WjKNm)Oo&vyX>H* z_Trmp#U!-}OQO!VW65%*i0$Zk%9#%Yy_OuZLHQ^d&E{Fs;9u~l*>aWoV>d^yX1MsjS={+6Y-ob*MDLu>jYaPzQj~*HurP zEHMK)M%=tGGqj|&=D^=fsRl#)BmQ%z&wM3K=G{vGw+!yR`4uTZkjNj!A|8-{<*Njj zBjs-&pT$I8_=az3_7hYDFyM1whiAnoAM`p`Krh5I!L%{3aUB+-%Z#XK@~3zx0rZWrb}ReUIMQFmp8avE+}H));G! zdFYwPzWpVhvE$#!Hz)L#bOAp-6a1s|UHUHMox#SPb`SCS{uS&a0;th|q*{k@(l@I+- z@Z^__CGTRej=!30-h7`UsOU`-{hd;Q)Mew{a`tode0mc(X-FPUGJBEKX%~6s~W#&PB8V(%#YA3 z4->`7{GRp7Q{1vh(UI1f6T}oF|1&&8ukl&A~{(B@4Wq( zbeL>>Uh*wBLcY-oYBbfb-xY|o#}g+m77O}q{Bo~|GDOGCz3j&FhB13_T7e{xYPhxK z@zHw+Ipf^&y=y7K*)V$Gm}M0;Qzsbv z4(W<(^1L^3wc^lv!YS(HZSmB}o_~*F*Lq{}Gm$pj2=jU`f1INS1;~t?1gV{&{kkfx ziCQ>|N=;%F*%$#yIY&;pL$Bq!72oy^pS*vDPs&Gt+agko^(NlFtfS(bI#>pWgjajF zqm-L9>S&vSJ0M!vD93q~yC--(Ma*96?QY6l2m2i{?v+L+s=VIv5{J6~4QI5tH-=-* zaj#J1a8G&8Rr*E2-7kHHTNz+1?4cdDm@m1E$Oh7eDY7!S1-@PYCbS#Tled+zJx z1S@YA^c(?wcI{WnzTpThlu?`Ky13Gf0|EzLK~{TgA|2K0 zL6zgT)M6%&D~!i)xQrv!=4tziq&nx+Ox(}nVPtUMZn;vesnD`CON@tn zv0I#E;Z*Zxo3^r7WHhq}hpjOOE!afJ%O&T8l0LSmSHqZquRRy!v^}F0U>1QaXI?lN z%pq%H1jH`?H8lW*)&W0Uh z3PSry<~Sk_k@cD*McSDL&E)n~&O+53Sd>!1U>Q~%5aD(%XhJJ1-t#(Kh1YZVgL`id zMYYDlaSY|9z59=!+E`8~qv&Y9T929G6ZVciVZ04D`8j8yZ=1D4IA`O1PeM~u5V?K3UVFh+#N@eNy>NrCZSbMqUv(ECOZP5P*EuP$lukO&UO@!Bd{n(T5?=*qBvGOHH#z{30Z z&?9M-=^z6B?R>pY+Kw=0T<8&cBKxs=^?IFSoq2Omi0zycgqU6hNYe?wmOBbm97gko z66s^IPfC&Wg3LVei5fYP$6tZ)a;9p32>cbWJx4I-+=5_?^l;J*#@AB>ni%hwK+)#~ z^WNNuAXn|Ls2LnIklF>W;*$MRYkxp1<0(-NW}q*=7I*LYJ^Ft52L(w=HJ;qFR_-^& zju7N6vu;Licu+m3k0NW0-?Bh=4a!{_Y7#Ld#)8g2sV|4^1GM8p_J3_;+{W*$NJ zL^|c;SfqFHkcfol1+Uy{JUcH(@qIZjyW8>J+qfl`BJsJ@OF7`e>M770fl`jQ#{vj- zXi5~BI~EysW$UEOYRZGL=An8fSRcvW2D9{H)-79{~*l_j{~@Y8(o)fP=HS>z>|NFdLO z>#C|R=@M^c)N00f=!$XR&$63yi)P66m)VW)kRE*GAol5TmU6R~;^`@4wZ7S8cgV$t z8yy%b9lec>NA7;xY?^EC1lEQC=S$yp{be=dzLV@KY6;$Z7mS~2HOXeD$>i$#Hjr7a zj4g@f=HVym{Bd^creDg(ya}_r*0Z_qMEz&kth>FvxpRXD7?_Y#F*W;{R&jsAg|_hd zQ`@Dj#AtR{IPWB#@P_NB$GeOg=pnhKzN1>^>mR;i0G;!jWmiv+H&=JgkI`yQwOw=1 z8~n!7i8mVm<@HTj9q&oHfqwZIlyD2)Lw0wSO>S08Z=6W@F{eLSovMG6eTe7Z&90%6 zRdQ}9qb^noj+{}qeJ1z!oUOcje!Ok&ppg}bCgn)q!JC^WuIp<44({A;8qa{Db6grx zFfEVtpjXZpIKo4^GQ?H2LLwS&Gv^Y*0!buAn~f48x%ecA4|%xRW++F&$QANOCSW6x z@vDb!h}-IN zJn9ryhO4@%(R==S?)*oVqT^wd7?N34H?&^%4RUfjjvK4;6uGhq?f7N?q}2Eqcf4Ia zKR#L@+?QV*o})7m)^vdr1glTj8Yx%I%kz9 z$q-krJxsFUiJt4}2?)-oUG0C(e)&8&z!8_``viIF$aO#U{_X?2E* z2k?cx+aHB&(q~E#viajv)SF#ddy>B8>8HrOI(vl%VGW?D*Q8|G?_?h&m(WKjxP9jC z7auojGe{r+*-|>gMhJ1Nzl;&K9kF*qPj0Sn|nV4Qhq&zTa;R2Sp$`f0!wN0^t*fCGo*+G`a;LL}&(i9Ycr_$GOY)Z(rXGCTV&CCC zOz3&ZOkdEIR}AABL&OtKh%OGJIPRx=J$?dZB~bX>m&<)poPM?pj*rEY8>tKHkZ8&` zSFrRQux~&HA^ZhT|MLyWEtgI4NuH<$bdDT90iyRLJs<9qr?u@?#qdJ`Fw(>8v$@@k z>%E{E9R~ioIZ&>qughA7z&SS~KLe^w+)TanFWR4{o*k^qD#cmfbC+^~emP24^!(3K zgevkKQt*qRwf>=}L@HCl`RDE?YhhyB{?*_G1h>y~M*4nXRk4&2CKAv|1jv7bB`Y)gEiX;0Fc^sNCs?Xlcgf ztUef=B_-Kj5VqZ+0ImgWdjI~*Kht_S24L=~y6@3U#%2mr$PH78-Z7#uM=ajGw}3MS z`OEAEPn3+HdK2S=@TeJ?!0!I&^=ordC(zCv7vAOIpk?|^pIy_NDyZmSh%GXjwGVi{ zjJ5U?B|a-Bhbx`^{&9YFxW>JYCHB6v=1o>yYa07!;5Q6Hud~fHc0+CcDHaD|y;Wct z#wu^PjrVU)cJ2*~ZDXZ1u-7&#O zs18`F%b$}b?F=8u4qqtPuNK^8drkk%M%z2Aq*gb4TlV5!$Bmk0Hk;hWJ)=q!|NH0c zo~^n^?0inHTl|&{o(gY%(q{lFPTE!W_!Z!LjV_+Bl)2)>g}xtrU^p31VvBb89!{X)XJ8BPoCPIkpRTquXN4zCISg1(-X zkgc*kjq)6?D{MuicV>=}YE=z&vITWUb1!kgM*5Sc$A2E%}b z%9%-B=Vh@Kg_c_pRiED@;>WRGZwwSf> z)nVoVvEBK;n4{<7zz2hPz|b&%`afo0klkYcHQ(qCH8MF@(j7RG3k$4;q5zkzz#t&z z+<-*iP3!a>UaejjVr^eR&j3MK6Z|-BIQ2C(ejX+$#>XiJd%|ch`E-=RWpiYMonrod z@V}^tOi)N45xqt!P+&t67LNNh!)js?B@(`d71LkE#KBe(AP+Lyhv3t;Xt{#GoC<`p zlj;wYLZ#Ctt!DJCP^6yc?!{onnO=-}4Ya23YBWsygdw?d29)p@yDP^fZU|TC=GX8r zNs(-<9^eKBM}gobw2aY-A&ejI*a#ayH+;vWll`?bCT(V({+U;hu<(Ofv?BwxGOn3tmV*zX$)Tz9GMFWDWjc8NSA*Og7h6tTO8dlZ?^<^PP99S9(Ku)heGd;=Q-BEydlI*gK2o0LMeNHTm@r)}e|NAMUw%1z2#@gU zd8MzI^HvZnHoRIK2~5J4JT&;k+*LWdyS=))zQRRJmg)-@d}ij2XGuMKj7Y~~xOF+~ zl^S#QZ^R%JoinX~l9q<-ObzOeS4mL&}3-)WF zHO0o2AKpNat+&ng1;H`(H*gpW;lk( zL#$7c9(1KtDG!*bSAf$4aC1hlHr&@9>E3wF4S&OjkcJ2SO>rn@JERg!IgJ})36?`T z!3bd$2xeWfA*-+?*%gl+O_ODdo2^QMJ4N zs*7_zGpAFCKYtG^nhp^#Hrzhvi%ilStcGt-Uo++UIz|i3p6_|v5p%@z68DZC3#+BO zvsrUpUY?iv6F{8Dwwu%QXUM>Npqc(J80Dj6n!o}}W6v3-wTLB`T`|MlZi&%5#Xzwx z?;BJ0&&JfuFf#|u1n(|#*u8s?7VkY{<&6iY|5G3Dh(kkbM^W?N)P^|hTB<9dRfZGLBym-Y+O<6mzHoGMqkXYT~o8eg0XZKQT z)UA&mg=`g9k+ERg2;D>$1$mjZmV+TiWbJeTH}du1SZ)IR~hUcjyq z-RDWKMk?`(B1LSpVOx6H4c^0Ysr{O6;C5QQkf*SN&CT3#Rxr+ifbe5kYh*#OlJ7A< zWUYF7V8(q;-y8(7WU;G!iw!%esU=-=_XIXBP}r6ZFXX&!TJslFI{}XaR&otu$$e_W zn3W=QVAiFp3<16`!1u15eSlm~{~35Xb&j{;GX1sB7wZ$fleq5hWc5U0}ccBh9fj@mq zoVG-t!i8hQt@Ml~;_V;WZhCV5y8;G!;xuI%0GSzAXYhi3UDLSc1OHevS|Mm~5z^l=xBC&V5#-tWfdH1|zoIq=MVoc*UE9Gi7meo4ys3DlO{#&N`0T7h zGiE*hFzYyMGDZZ`tbz<4r*r-T_3>(p*3~u4KlL%kz!RfZpL+I0DVi2wNJvQ0b+s!{ zjTjJDt46tIR7xf(%Bj+oK&4-?28ceF;_u*5l1IN@a?N6@V++O$F0jJ`qO=lLIjSD^ z4@A_bBI}-`X9z=%MQ6qqrnL(?xL5H;LQ#J@()TXtcT9~!P2@A3UR&?=@|;2?2`sts z0Y44Lfh(7>p0O6IJz~2_jvnCV@8NcIGwj;N9i**UnDTv88_9eD} z{{H{OFdr++hdK~P8#HRfPSDn@Iz`&WBgPm}uSQdosh=I_5~CuwD}L1Nl&R)P>Iy1W zJkkUQslrogBv9L|2q;O4Gi}d(#}he2{M?4eVwo{kB!~6Yauu0raV(cu!Z%cyH+*pR zmiD2!O9+XUg7tbv{MfWF+V%OFS&eveN6Z<&XyLE}VH5gQ=@ZMLz)&z%%16eJFi8YKSW2#csQNLI%B@qn)1!YC7AH- zeRdu=;j%$DZjQY2%S-pwpG&;~3_P*{FBaFRE8!uAMZEbULN98c`Cg2OWVOH?a^2&#Gls30P5-j|!sRu*S@JN z9*R03fWKy3aAld!o3feQ~%DN!DGnLtZ{zQXWzxsyW zp?%3ls&S(Z4%$dEdv44x4ewan$ZsxTI2l5Sb-E+)7mA-XQyR?E_o7d6#|0249X8yB zB2GzsoXudwjW}M$2@UuJNI=hKSu*y<@$BdMlrahl9E>RmmB#a)U8+p+(l~_3GV9VA z|M>RJMAXTsz%@uhrV>U-#Uo+dr>2__5Bo3%Ju8}sh^x$1MSFG>q^=l0G5Q#5jgeG% z7*%zAxI&`e%hUG{9gC(y$gKGVrUNbP5a2D**+QElaev1;K;$a_fv4FsBN~QQ%G{Aw zg-Zalow>F^u#@|hsn<#7uE}aMLTMv@3W4m>jOt*^$9Wh1HIw)0iugYiX`0Heba4hv)(6i7q`Qf_y!^Q)1`` z8P>rHbQ3{=hFEJ#eHU1fk{1i*;bDS=@f2(ua*>AIAQEbj+PkEs=)-7en%7~Ce$8gp zyAmwcSM0Hx-~%H1cUSAHnpDP<4%A4Eb>iQH^)Rd7xvLBpuKKC{TgHku9w2K+yU;Fe z#dD8H`@~w1vVgC23!C)Fs$+k9d(G&QcxL95W{CT{+rtgsC_XOL>ZBDkiW9A|GBDfT zG{5@unnQP^MELpKK*8zn2R`I!I%K2yW8$4JC zq5+Y$abDg|Jx$Yh>ci%C?Yj3(-xaJW)VG)%pY$>8()sEZMorkU^Sjm0Lgy;%8gVzb z^wZ3hUWGt0ZnRG3V^@}(>T^u9UaJt6kA)*8=ikxT9!L3@&AO-x*iTP}vWDVdhPg68 zTgaeUoO`h+z}ygjWLDMRzi&?8`0h8>Cr+^h1Wvb;8JQ zi@YGja5R`i}NN_ty9(NwHEWUlw{Gz*`~(1RN>u6nu)+m>${ zeZ`(sb}sYoZWdySrzn3#E8eh%LC5#;ijT6fVAYYIBXB_j%qH}c3+2;R?f{S9`=G!o zCn{HJ@2m?+6O##hqnN9;r1rjerOfmiKz8f9q(xTrk z)OVI_KQx@};gtK2da$sKDfEE#fwk0fa~R<5TiUy%@qe-Zs~F2FC)yZ|K86XNY45eD zv)R_|-Yi^o&&QxNNIe3R9$S8N{Sj(yjgexTfH1P3Vp!#c*YFJQPfH!&^i%NjM(4sG zo+cFga2uUFi^0V7axGMgmgEFiDt9hz8bvL=au~!DTwfi#yYM!gpNHc%%;YpO^Wv${Upa(>Z6=4 zg5^wA8cw4K*EBsJC+&Xl3@aU5qm(G=C0VRC(TiQ)ekxGPlj4_V!)2x77w4Z zR~#H*p_jinLn#h+StGYnNNN%e39D^jTSwk8XTnyl8=q(?B9y|L2v>ZkoKE$m(12^e zOl@8d<(-|gw4IwU#e=^A)0(jVQ;yWGn!#`^(SGx8eaj1tVymPPFHICJgv)99*d=Zs zZ!09pupF&JM*h*uCoGa|ii`C*S#HfWe~CwikSgnoDyWf`p~*{lj1ynZnWl)c&X)yz zW=aTAM}jFt{0SwBqjizS+-jWTePTT>)@7RZ7hU(4b}&D0e?HU%J+U7t;5JNDo}X&^ zw}hpzV^%zzla0$#DmZHS7<-y^B3b?i3FT#(R|bL;m1j?4o0SqK(1E+d07}_zap?bX*}Jdij(rBuRq}pl6r49J26r5~+|%C# z+{9m-o>>1c^bD;Dd3+j7H1kWY9J9gj@nO^aSCbe;DX-+h&ttwT@iRtImgVo^dE-GW z`k+;k{5agriJf3)ZsmU*Q|un z*J1tHL3Dk`To{c<)%-iRGy9k5@WHC)Z;fx_zAgWF9}l?ej?yk)^ZuQ`;oT}37kGDBRkCS4RF15-UlrM3|-CeMsVknoSP8-F$VQ6U@p8<+H=@bIJsM7OY zybGHYSY_Ljm(mx>WqiOM6n2gvBS<)#6Ob&jvz9~Svl3C^!aqkxiWk^7zigG6@#EqDfE&FyG_YHrOT{8!`xV<54+4xKE zO+>!nJtdK!*h;4a_H3oozOk2tu|UcGy-?)k3LK`4$JmvBww60;ANh%7+Ltk$5L57r z+M?yW$BGHKT*+p37ja@?H(5ckp)X_KtphM-6>di>NPio;;2sllH3#3Y`EQY?@eFzL zF<9y;HdunFO>cZo$XcOg*>7zyO8cL9d1F1PmzCNyIu~30_+-%ynU>0oJ$0hfcrmQ` zwI9|Sv9xiCyNPmp2J?(LQ$3d6|M7=E;hk{jQ}E_XIjye_e)_B(PreRVrvA%@n2vLo z*dWpqp0rgolCmI_b33Q~K-&2seoT=X>w1+t;KdTO-bGr`bDx=eLSjB2=^S8F(o>e0 zS&pFvck4(Am}mJ23)6q-=oi!xKjAUss-OenBDWI0fy-3PZj#~l(h@u zGjrB59)KbY{f&_}%aO0N*JEIupzsbarWANi?G*m|P{NwWR!+EBjuyo>x_T-6kO}zc zAN4d5!tynZQh>ZAD#gv+bHliRr=gCaT$FFmbOr2TM5=Y5R+eMJLc{5at1dv&;6RW) zs(vMJk{c;4*qNJV%Yjb|qsv;tc#9`g4Up=T*7Z2&j36*6xajaAI6lBi(ne1Hq}5-z z3N}k@OnfNGj+B#Fuy+a z$3FFJL!xIKXaOhUmEO_2eSvL2xlpAQpeIOkUK)ZlqI2*CEe>;}=+@af>~bAajO@fb z*X5m#1BFNYpU_jDXZksQSYGlSbp{xP0f$f02J)Dmvw;&V=%cPC@IH+<@Eiz-)F?NM zd&5`CZed~hl_NoS?ymkkc$7`>G}xcZ{4#P8t8Maz{~cpeCid;ssAJ#{Ps%}XLd@&F zrvspLH@m%d&c_*&8$E`b<8#x{i{CWOqG!3l+{vO@9!Z=*F(spap5Q^Vu9V%H3+Z37 z=gpa##{~eH)w%c0gpo$N^C9XFZ*XIJeu(XQrizj$1XjLf85c;OLiprK`zD!F28%^M zxdBE^7>TCXWQ4*Sy?TbmO#5WFUHCos_##8EnrYn8xW4lUV?U!5<^LEc75L+W5Med5HQK3G1(G|ejWtIFA$vFi^TCx1YJg)`$FE3bZs{QrVEh7u=e|xhnFAHkbB&kXFDIrTT+GND z?z6+i9d5?k$6cDR79ZW@hS|CXmxWL)OuKJ}o9MiUGj3r@OT^ygk`wdtRu^vwFa{Tz z&)-u^gn7z&K2iTBzqvKdI{1zt0|Qo`-@+3+;;fYaW9oME%{S1yfFH+bbj|`s!$lNv zF$4GX4F3#q#>t(isUmNRvcjtjNPSD!70c3f~ zP2-c@K0QYj%qiv(yT1;EkdW@s}Q&;YlN_Q zdbE8J2U;@Se}$L0rZVr|$;m4aFUFhqCx0652QZTL75I!xmG0ZigVU5CfX~bSb=+CR z4O(%VmN)Ey;3jV9+vMKE$=s@Es=4v8ZEfE@SaOvica{~~p$%mh0BL(dQ+D8)duV%d zlN9Yca+7?p!n=g{W(LXT$(txoPUHD*9v`0*r6h(=%-Pc`MhD`~O=;xegg#}ZjsH1k zCTK^t#6grKocRP#U^4JVxNhZJu0*G4(Hyh4&u`Ls-INfQ>G{loVPxzVZ z|KaU@dK}4;1J9_e31LzYpjHDeAau%2pbIOV5~wdw4Ty)G6QdDMu5%FbQem9{c_-qO zV9x>rY|SZiAScp!s%|uiB`j-B3oMRTxLBp zNayqS$DTcV_RQ?rGk+Y7NF#v`nbT+BBzlbVb3x4$qZ1L=(@f`d>Kf6;IA$;Oc?lhJ zQkLoMY{%NnoDL2|tSQdzbx`YeGIJuXi8D$IVzem4F~JJZ=GIMxf2VVes7u`R&%qx) z>OEvYz;j?h3$fs1AAoP?K$%+*uHhlXxS~~pija{IxHFS3!6UCH+VAHT8g<> zNYTyIz5i^}t&OosXg+8RY=*)6XB}Sb%Bq?(f|+>X=X-A%jxZ$R1zJ@`gBHj7VW^_OGa^b>#1t@ajlpfs?z$4CE_C zs^AHFi?m+=qmZT9ZHWiU?RKtxjN&{QoX%%XfX8L%xlf_zAQNqt~UVfuB5igt%|*=HmLF zK^m?9F{Dp0M~u*TgVr3 zzcD8`F=E}np#@}6=asaVrqAOlC%JGvbUS8&bITQT9kK6BFYsP84QKXcz-b&p%vsd= zx93&DS^Bv86-`sQDn&D~`eJoC?8>53d!J;9z2%n>w2v1d1-s_ufZ43tox}n zaY;Wd@&7u1zj{{csr-3fI$u+&caEy*Ib(ImFs^?m{3z z9)3VKco{jHU2K_OkPYrnXn)StWru(e>wB>`x^{4Z0TADb^M0LVw&$+CA*oVPQ{d<0 zdR$N$s~F`HE!TamfA)M2;Gel$i3q3t8>&(u^o5|`K^)Lc_lpcae#}&H<1K5S$Mp=TP)ne7>|i0 z*l>ayNrZcbX?eG3H<)jRdETmFlRDeg?PBv?KHOCNLQq51y;nyn$1LF)Jvyi}8E@nM zcsQ^PQQh8Rc-$aw4-N-5L-Fyz>OVS9b1f19wNXNgUy~I(0Tk2i3cthgcz&oJul|1o+shn9dFlxwG zH13?SvP;_L9$OPy!NZY;(-S{c>myJ9NvnspO(~gen73`cO?UBZV6CZy@SLA{cR6HP zeH-2>=?Qj}{D7Sy>_@{Py{59|LylE!XntZ52}oLywKud8Q{+a^me6b3hrBh1pH58g z0-nWXer&sd%evAXIW=ndH^kmyK|Hv~rs<;OaO5SULbK_UKA7WloqD$fHvv-QIQf}{ zhfbeQYht@tm?b{|hZw)+GqVx^;DL9`d;Pik9<}BM^BHwOQ0iy5t$h>T%Q%(%fDedc z4qmX=Pyq%%Te3ci>X1wa-P58A_Q_QZ^OT?6U7s&<>sFNLEOms^^j{?O}?PTFqAL@M+}Nc!Q?v_S`P~0gQX@8L;2oL;)k(XLAY!ah|3%^0J5wTpGe9vb5YBFhCIz`WliTq^OwC#FL zKe3mlCq5jH(Ix7#Bt;bP(Y9j7%Us;^zis1T+$E0#cQwww2RV1K&5_c46n8$a+|fum zxvBax7592WuwBcY)Iops_M6ZZt*w|YKvl9Y>YtbPyIA9-2L7!l6HhaCZJflzY|n)i zWbaYbCRE76A{=0HOYuC0VD=+31Ujr}gK!DdJK-M8W5LFCbgSoHL=J#(h~5A`Mnn!6 z8O=CirxN|fdiB)<&?V>Dw(0!QYNZzs_34>oPZI2A^^jm9s>&;>2mXD$jb*q^m9Z1(pwEbo*)= z>5NaW$We$t?Xc$@XZkWnoaxrpgIzbvRiv>G7tq~v*XSk?k`cdP2&zjOBUBZo|CjXsBB1( zH-%#q{*7GJ?pMbzBSW!K0XOLD6|zLrXApukBTY#4#Q_mEoBEsT*86@^$e2^jY_Am_ zwT6*EM`h_ZCd!Gse0cqEm8G9v+$E+%Jfw4KA5-aBPWSJkp2+(cXD03DI0SnCZF-z? z(l>CQhK5Pu^e;e*(@1AB*|8{dd(}I~QRo8;vlv7v!O$UTj_Za>on;rRq5IOX2FuA{ zzyzldK@QTBTfb>rs}T3hJ?3S#b6&a28BTZujyX~mgx!iMFym!}ENzxwDE;n+azpoox2mNb?QIhUiVpRwcbZ?CwEr_A5j zOaFqChn^(hiG$76&*9N8z8T(}=d&JDQ6JCY+2>P{gTQ;|IRN7)Ucb176L*pOI(TQsX!NM2G>N=gn`H%f&LU?0S3Z&tC0*VO@N=*zIBJT>r1=MMZ z?ODvdU1TJp-yGuLB6xmiAq&oIp{`Y}0k|s?>wq6efbF~K*ZEtjK=O5rz(BM>cfo`` ze(LKM5_R>3xWJFmP@pvXSR*+P{3V?{jS85$b5xGJalrj7;YU6p#33`V4cb5>;2F_+ zHoIv>lwo4Ue`@q?)ILyGEiT*pd zyX!2Z6ARAAnsz$|Ok||870jfGnck1DwcdPW#wCoRr_r9zPwlNRqK{{fd81r(Dtd8K z9!vXuVHu7hfFY@g3|xLv8(iVoGNj}HQ+&3x#b@G%Rv7(-t)kU2!CmZ;WZ3sd!;du( znP99hkeZS5fzng>zb5yRIW9sj!b(a=Hsdt`Hx(#cBNeEa^_*r&HUoGzFf2HapbK`K zQpO)&Uz%!qTBd#jB78KhJqn(OoKaRHGE4x`D!D`QanyQgMcf$!Vnpil?*D#R!zYoQiHjTjFJ|X>2^Jl+>bwH_hLLbuHzw3_(N=H@ zc{?m%y11<#u_(8%s%5!cjPMxq#LT#5&>ce)P52d9t=a<|iEnwY=ODg;2i5Rn zlrz$%@E17t^mv#r2O6kNo{|AgueNgLCa^| zU-=TB8a1xDjnj-c5<_&M=xN;7zz_Fhj;Bc_k7tBPt`@Xii+=ZsTt5K6T~*7Lh)!9#Ll zcF=oQRq6W@ivOk}O2ikSe>z^c{yp4%QHAFsDGnxcuZ_6F%zp3=hDzoo|85xFL3g@4 zkP+HH9O&3EX!MIL8UuR9Eb*B1x$NNPa3UUC!@?WkOP}N!;3JefyYE`(P2|G*<@en| z7fbFadpV5GkNu*TOkQ9 zF4MnUK#Brc9wHH&T4se*iwofJ#63T5O6`8omRY+fZ<(jNG&%W1LVtKzEa>5|jeL|5 zZn&;(KF88q*JdEdJ?TZO;IS35l*j0yw53)-UHn_{`;^wF)UbK;)0Y#TOHS$fjle_$T3Sc zLvR_bOJc+n1yNpB<1u<*v0M^oh`0P;(=Jx)e_zh48G(l487K70a<=i6H2V$u9#NL| z(>Zs%YG=3ST@dBp?RRtDxMUk!0tru6Ti#GKX~?^q^LEhEJ$U^ z4*GOHn*o8*Mr?%uT>I&2;Hct-jpnRML0Q@Tso+dAXFB*v{~0X%&k3RX==C5ZT_yRS(LegZih0nAT~jsPxSC$p zFGqjk+JyRFjHZ5zi6}>$UQ)$4e+K@qB_=zBMKtw-(WUc3Spy8X=XUrgI)>k^}k4W z-*C5MM6ivGDo52(7em_e?1D9g$IVU}B`@W;E$ab&8b8ugZbcMa)= zvB7Q-IuS54Zb}(cXx%%8z*+SLG>a6(6Cn8$xLnXJ1ByIrOP(=@lljs5dF~N&3%@4m z?h7fR{sps*nMta(1AoD}A!)OoR`2Ss%~LR+cxHRvBX_h>cYG#3o<8$7aXwdaLhM2L zyrpf=sykWD|3I`fmf!7^7nH4Lyz8jLFsAK?7cgxnJNO6lUpo^ z)e}v9?h0&?opo8)uv1J<=d`Z-122 z+2ZRJt!Y!Mj{^z`H zO>FMxnoJ#a1mD|kg1s7gqY4LJ5fln}P#7b?8w(UO2AWj{H4Fj~4yW_c9IL2j>zrkb zlEUaHcQI@r4(4=2Y>sC4ClC*&nsw~100Fr;9zCsDrRjCEXRX;+Ul6WwzQV(kXd}{0 z18Tq*dn+XX!YcZ)yxSK{C;eh;_gxGdAy3k#6*E{F8{qq2O_1C4!4r}`b{~IV}oTBH2KCUE|I1Y7erz01$2hYbbUG$`k5DeO^|x{oTU4B*CxU; z+#P6U zc%(tO0!k3Conv5-jX5&kUIh^ zZ^y)E)fSz&b0$GCWi9DqZl|q6DK)gdXvJL$vnO1%T=x9m@z?M7Vw`u!4itcw2ec&~ znT1sHM#w%RznfyNbf=B}oCY3`fjg!dw6ejqhL;KQM!0`u=5j(C`C$b;352`~$(#4g zv8J;cuBTPOny}uFwyX7s-AeqQ*)vssaqh-Y06Ct?1tVE7*m(A&aid4PTvnKZ5o@$!p&ExKtEp7W>1-T%mG`?;Ivg;gsQSz32`au0bh43ua0iMWl zV&}CG!|tncdVo<)czqht^R93Bewt;16v3C&6G)%1bMqkXxY)NzC9Nt_!5i&o@RL4H zn)?8bmDkgmLbxP+kx*T+_wy{$;pl<7)49oCe1XOcUjpO2aVy4yD2D9wATxTxEgvPl zXt5Z)BlTY$KW+r4RY_7+WabXJy_hh1}}PbVJ(U9%&nXSP^gpiG!8bi9OO-ztpFj{Cvo8Nsh~C;-)R_w)bGkM#TW{)n?yn5ce3<+Obv&{y)QMS3dvs)En=H)&uxf zl|FfgRvL+RHbdcMMB4?9W_XNt0WEh4t}z4Cx;Hs1rtS+ySI{p%!H8B5aEkTgI$xI0 zab;?c!@zgf9Zumbb_;f&Wn|@V1G-i~L(0#3c#o#ve3DzuCOQHb-bJ%Coreq*a6QXSO}*{v(;l6FVFq9<^3DpQ)~CB?wY0a-ay&~1l9b&=xS$VM?tPNQb`gJkoU$<~q zo3$h2xv}mKLoOTdN3O+W9?7QNDwrVMqx~~6`Gjr2r@oFT3Q%LvOux&J_)WAR%U-pK zGiU}5VIttMZ3P_JFOqRV#_$Rt)0DqCy3CX`0Zr>!$fDZxF7xTaxfIr7==Fy9n($Iu z{pO1)ljf0zBC0w_KgxPLDAlDsI6;Y#?LW`+C|~4*kC?gg8+v$s&wj}SnBX{%yc5?h z=4vtjW{RkXg)-O>5VlB#60D|wU*LY z=iM(;&TEsxkp>6WR~f_A7au;gb?jD5~ee?g+d6Fw&yLPZvpr8!~d)8at=tyT0Lf`%^HqwA4R zmbAX6EX;}&XE5?bi@iz%(<4>B$Ek* z!;3a1(4Jx?Jd$emlv(PTm5}?7( zb-~)0D1D?amIF1|$GBhU(VOj?i_b6i7u}yN#TJ<2uh+NWi27gFsQjq(ZO0Rp7hcPq z`iUjheiEiOPDD51a7u4mVNlf(gT%A~S7KiMF02x~)r)z!!D7tkirZ?tf)jVhSYnRa zC!Cc~h>v)9I24hZ`aZ)Pk*rf%n#6QKb(ogZ!b( z1bo)YzlSd6MwjIj=_7Vfi@;UHHvy25&;-62DLkO>s$UT2=nE2APQh?2@$dt{3I!-u zYe!b<0m~76gE|;to=^TO=Uu)dTG9WOP9~+krA69td+P5wO*Kj!$ateI`k+yR=TNG& z)AuIsRORMKmJ98JU|z&d(w#aIdC(>)A@l5M?w`dbQPDz|wBEMsYoVgJ3*S0shT|X5 zKg<9y8C)Da#&NG7_)VMVGaRu4J7B$eWF>O6F1R_SK+Vl4g6a=>G7># zLk@lSNM#m-gR~G>Z=^FW>}7*%XdjpbiNF3X=^f_PHk?c&;5Q&IFwVpne2NjcYOo&P zTL2imQJFU{C)~y?Nfc6vTl+)}Lf2En{1Fdgg`P_()WYaVE%GY7T-qwu8J0LW8>==x zgHtr8>--!?4p`5<1nXn!;5T*iFDdnb@1A$Utx5G6|N2NRX|!DLQ@SIN?$)i^!{xYT z1(6w_jkMO>Q(T|->?UkEVxJ}1|FEF7e*Gd}!oYb{=Z~DoG6~z<$#-7BcS`CA&i$6| zyJ;;&N>vHAB2Ao^*`MEU_=(VEeDxiWYH0DgR(}u>U&H*W7a-4-7IVA z$N7_ZtegA#S0mAmifxp{$IO+5f3(gMXnoVL+L2Pi?|SKiJ)PL@VamzQeM4qo7lg%v12@5OJ9jYZstFmaiT$$Z7rPM(JMLgWE7=k*0%DZ} z_Q(g~&5IRXy!X4uK#f$vxW(A;>*xs7{NuuQI6A+rL5Us+adSeuP9xyT#dc0a;qx6` zspgIV_j44UekBuP|CAd3Q^YvzE|mV#nl?$YEk9VT(@3JG9nK?(*;>hJ;#$q>^C+Rx zR{C|8WY4yBmb1~KFU@F5*OYXWsD~J<_8i&PUo5FojuIfbr2jL|5<UGSQS#OBshg3gTrXZ``MYcA@KCv!fhap&(en#^+U*#SyRHY_|# z5`cCFN}DT{2K$e9)*=M<9*qk=(Ppe#JxsRa`W*Qqn%g5sCOy^iC@oNS5pYhT_S6Gg zw0`OA+`9M;DPdZ0jB1W=DbgDD=4*QI8YV2{Zad!htmT7OO-|7YA6NP4rFLpl*gCad zSD=<2pOsbahnLhf6NBO~)-7`;e9xne)D~%-rCD$sqeDx*+NU4zmF4?czv=PguY?sx zCHl)K880vH|0{g;*GLfmRw?R&5jg-TW`{NnjSE{FtJ?xvNK`01&NBOc9{Y4hoBSh| zUhA4XJS`~AH~mR;WA5j7W%_dlBY%M0rfp8n|7gwntCNopma z5KQX1comJZy=xE7^)lHg!!w|ZPoc6>t{)QIZv3+28Z~&!l}fMwbOeL zegA_`#HM@q2?y!d_df#58eENRf$GwJa%cQ6ma&Uf{<0~E8TI3juk7pO;+2rmC$JT8 z5j~3V4MgE+=*QYPEp_vmCyrKJ2%lzk7O-Qts*~g7ME@VCIk?efk=Goge<9Wb(cTFSt+l(rRGjS5(ASvUI zjly`lA4zzg+zKo)B8~;WuIc}`@AJ~M<9!x5CAlWZNLlGcs8rMAHO3a zyLr+lb3oY<3hn3c56;Iwo|_%@J(cpLC3Ay(rUlo4uG5v$t*iKin>?Ru-47REr54V7 zLp!7s|A!w_D?W85Cg_S0jYkVV{P60+b}qg%_j%63Q=a#*`>{LMe(_85{rKa>FN-4P zYj6YxNBWT?z(H^$uQ3Js-N;{43ltl5Kx4b>b+pb*FPfr&m$17+e#W4wgZD57&-yny z!}SCqJxg2=0N}5d(uy$APddwfZ_^B^s2PpdzyoWwC ztM|q1?@c)zpeiOdbG&7?vR%NOhl`9$C@y1XAKKHF&Wu>*C+8|D_k2Q)8B@;BHs{M2 zB$wS=T>#vEAyJ2XEfUuYKF&L5)QYi$46PNrW6rE$bAqU^{N=2epHUSvhFI{x8Q0U@ zEhV%3c*+Oq$sm766h<35kvnEO4-N-r87xK?csw4MasAT|JdD*Lm2S<%+Y8-oG- zk58F1lwv;z=FYboWpc6W{H^nwlZ0<`K1m~co<9WVMG^^o)BdTW4~0FvdS5j8fkC)$ zoYqjO(R+pcTYtV>My<38pE(`D3K3fUyK27t^39tsKY#P)^~H-9Z;%(?ym|5Brx%}p z{^sJR+>?0mr5Cm+?%uq(c*XVk=PzEpxVU)p>eZV!pMU=P)deX$xOnsB8)kvGlq8=| zNg#=5(F)~XBcQy#Fvp9F7qk;?ym|9ee%a9HU;gxhC$HapNrkUoy|xD1x_Cw90mkP( zA;$%^lAqjfE`)$=uWZ&-Xy0gtM!uVpGP#S-vR!g)1?>jE8zP+*jOu@<_R7zsMz^e=r+RcjhIB&13U9*#}b zzFpzpGC;qkSKWnH%Pju{htIV>;ZL@(&(Td2DO_A`u^4`& z1tje8!6Uc5Y@bSQ$Tue+|H4X`BxR*-ZIJwWNN15LnUAyl&@r>r3X?=WH%AYj8dcKR z0_N`G)GcWBqr45-=cAkej}ahAZJ;&!{#44OTGUc!J|jJ2_E|4l){y{F{Jvq$m;W@` zpnlJ6tz-5Uz^Q%#_WSo@YDL1M@H`}zF>O^)kr$!SUY zY|jp$>_BseHeZm|!pwXZT$Y5h15wGaeAam>qVcdB{2V52T3sUq(Y$ZUvJi zx8R9-2YLIzejxRyr<@O}eB70+S+w3V<{{s*ZiUZDz;k*4s++}vW-^v58(>`owwnXF zD8s@<4`Mvd9R1Le2X@}Fa@6J+k`F*xodmnJ4AJ%d^;Q0^>sTwSH>2Z2dXZJ%)iqCU zDr^%mZLWbh2h@rhP&>!8);?%^r5tA2v=atTzBjs=0Z56*2=WmOCESg|F_7Edm!its5-yZe%M@xWKXZ z8o1qfhb`2nycssn2X%frH4R?5T$`$B;ui%`x(L+Z88ucdP8|@PuHgXJPML$Twai8+ zNV5#%U2W=uFZzsLRBUR>P?jJCL}x$H5`E>Z2H;hh{(20y7tp~e2QjRxVDd9GneJl? zxS6@Yj#B&}<^`>c=^=Tq?`iw$s!`JZmT?5Jr+a>V)x5J0)EgMB-vb=$ds}95 zp3$V{Ok7EG3}6ke0Nm|=>AP*gOvN8Kq?={|2ggIsCIx-Vkr!CO?Q`@$dJZZ#^q(p^ z-eE5m>3H2-fdS-$JaFY6xKElMbD+v1;EJ61?e8#sr;>~cmy1Qgj92sI;)662ynLFj zW9gn}((k$RRb5=PnfZ%_jg^Kwti-7DMXEQJp=Wi3epgr@_1aj0tmICVGXMb+J?EN# z)QQ{)_Th$ia@%K`4^UbjFl$T1ufpHl^|DyE6b>N4U>$b_w&Iai%EepP6L-dYUt;dy z|8{1SAB-0Nq=BAm&I5kT1c4Wu67aGcAAr;?sX$WphsTnDMSvAQwB(@aGY)`*o-zuc{CLdK z6q*n5*+{osA1L!}y!}1sKYsvXIhfij-l(_C6tr+;N=Sr@K3yucIv2b`(!O^DPGH^k zl{P8$$VXnHO#nj>Mm{Nzj=hKn*QFBjbq=LVA@-3c+<_CNpZvgFY4MrHN>Cnsr5gPm z-5|Rw-89W#PQK-n(!=|s7)S1g6#aK0ZJnMlOU0 z0tGttTgXZo1OfY=mYJnJmXhZFHUlx%@bb!jLs3ziwuh&AfE3@M6VRuH1AQ}Q#Nn@S zMTn7cXRX!m19!EM8DNm?-02H+%?j#qr^x}o9<0uF?i+{QTieWd;Ji-16d+_5F4~-6 z;!{(;A`x41p~DeYV1?C5^yopQt+Sif4F#2_?5MUwk^Hg)80};Ya|u*xvFd zl9cb*n{vq^jdR1Bgd4*X?5b@w0~^(buzVci$9@{##RMk+sVrU`B&^sMaRuUyro@|UeqGNvDRi_IJ#u|(JRq`z zNc25cKe@Jhi{0%k+t+^$1Wnx?aXE_kf}Swr6fJVaB}l&I59+;vm7`sZAbri3sk=JsJCLJfex zOHF5{5a-MkwrM%aW#j^;j(cHihK-|fYkDQt_!pxQvvy$G{2CT;nGm(UUL)Uizc&;s zS=q!NtvoHo!QIemP+{-{r7k&$N8@(${eHFK92_ZID09`Ii}R`pPy8|Za*5GRcfZSw zt+_6wV2WnNfCZlZuZQ~&RvhUx>`3Jtv}S>tVR)#mmA(@8hx4X;&LLyzlkx@(04L}< z56x-2f6CXHhvsIs3I&6xGolpwv_;v*L~u#lSTQ+=^8)%zZWNjx)*BZ(nCu z^mMo16YI9?2GeV?0reMiIQ|a&pzW)9jyAY<#+=&^1iib5TAM98V(KX>=ukzMp571+ zL&GB%TK2-wAI6g*CNT8y88iS_XP+~JYw@vwvJq*C9d)l(@$LJjfdAxQWnsOF+Lfcj zS`N?RI!k!)f`>6=mn~R92KifSLlU9(>(i0iinEkL$`Ia`u5ZUY?szYG1;l6!s)-OQ@~dtX`#5J}DH|CQ9U*u-?6WV!x`r0~dDz#m zSfLivMzX45r=mfuTYRH2lZ9_BXM(|}aJ~7GieF=r`|<@sP^2b|j9&JbvP z3)`5`2CPDR@!}QMHOjq8^#>@nFF46Mht-Y7X}O0O&;vSbgZ98WUSPW;HMI1z{9Ulp zfKf)qD<7jl9=$_GDgxL2lhQCa1B5)T(S-XOZop`J}~beifqw{h=i; zk#cGSj=)dXwGXD>Sc)@`zMn<8*iSG(y!~WZGTw$cg!y!Of6fI<0Y9A3LMmp378%3* z0|MTic7aTe&K=r@a-G<8S3r!NP6e#b67=om?QOwzJQi*@P`95S57aT0>;)T~f3a(PblTc! z@2}QZe4-5uTB?~S9bMaNw~bD-70E@@$H zyeZ51lm%$DUzH`n2XX%rYag+HIHX23|$kBRTA zUr^72-RH8|<0e#Luo|=<~B6oE2xVeF@5>es#q4YO^qnq5a|h7bU(|-S$=qsztH?OeO>Jl zrFJ`MXgyyM!~lIeYKUF(cfl!}V>zQ^gz(+$x5s16o4MXKNJPl3hqv$tnA!a?;29(> z9MPH}4Ey=-7jm5?w+ySz&gq9${hhYa|_DYSradD1%`GYb^?` z)*F-^Bc)RWF-iO?qM;Eg<=6^Rqq`-944V-U0qN-m$(5A#W<-fmNLX{^JcMY7gHsM$ zWK{$+V?yqCt9>!r?((ixQZt+cisz0W|OXH=}<@ zXrvcpKn(2DA$2sgmGArl1TqzU9~1@y@h6UY@n z?g#}!N&%1@GhWXK6*LR|W&-F~BIksAVnXcIEjUL-tPsM65ay&?I9UwyBc*6*!D^hd zu|McakD^Lg5>9u(j!RW*Mj+Y_KgeRYUCrq!J^wAUVOM~O9lAELKCpuos<|Wi5lGo~ zzhx|(`+E?E541HJ+i728G&==CR*ZYILYnDrQOhXKZfJo8hMCRSAYTL>NN3*#IZ3P7 zh$@)I39jb7SJ%2jl_;*-961{AJg`J|6Qg;$&fi^uGjNQ(hc(f9T~}TfMtHUkcd3*s zYHUJjBo6S~;F1a&-{$38ekZ*LndOL`VW78xW!7}#WwW9$Z;{jTjE%*k@`@e#kfQJHmNFPVP$PBu>7BFhQ8?4v;7y zLs^-eSQ?u%rw7;u=nEF<)RzMEGf&{VhLM zNxmQsz|u&7Mc}T6(u044u`0!tirOPqV7zCO_k=Oa1~EG-a>=EiG&d50v7hUJ!?$^6 zswg<8vew2m&}f0d4h$nUvSPs#!92816gpP0_4*ILcbOy<(+mSKYupN!NDh~L>^F00 zd5d?cVUX-ClwGVR+K1_B(VdhgYH)2_Q`Wp&L*yV$1cf<%F$D0X0^YeD!MiG2gKHO~ zzu9jqB2~_jqG3t0=W6!{c0lvhOSt*oFrZkFkrpPdqqdEw)e)oAn(4t9HS2HRb+@or zIyi?vV3}b_7+tU5IbL=ihKC((0IS^aYFuMCDWd1q4MHHoE5bZ^WQpAZsrvXL%F zL7DR{K@c&a@0>TT8Okuy8v+6J7C%_6?7wp?nbCwaT5iDmBqw$%Z{3}-m(g8UAHeFn z#upRd8|!MNm5<`{IU(7QA5Xu9Ng#@|nC*#d)jDg9*H_u<3E72ryShJI!A+e`(mk!+ zE59K{T|q=eiIx(?&EA<57>c8`DE=VJ^2mpYBUs-8x@Di@NSXB1JtZ|uX8<3`b|AxS zO47YXlk7&lF!H$XgcP9`!+ykN^B*E-mncxEy{jrw^$=?Y5(!t=Dw#8P%~HYZ@z%|6 zPry7F#hL;jfz4>1v+v)VJ^J$0O9aDR<2;ge+E!kcs+tizj*Do|H zg~du24QxZ2oWhcYfk)4c(ncaS&@hGKc&7mpJO_D^SO4h3+!RIacNA# zmX_-06YG>d9$2bgX(`i2#Xl@q+PAblz0&rCO-dV>DYW_uFR%;1)C-KCmZIU5BP?0M z^5O#Dv4BeJl(0}18y9{gdYe&-7J=wo7bdZ=pxJMpUC<^ul2y;NR}|wM0cR5PrRz0x zF#Zaw0D2B02Sg>OPWptr!n--2OvQLA-{vivYN(~E3#E}2%_I4nM`>i9ugfm@q7%kR zV$E_IY5ySo<=2Z=7XkJ>`KfCOd6>lf^PG%l5F-BqZ8XXP0r!s{J`detdQmfVy#Y@FSy*&xG=};f*{A>z_oZ&bqNqKGEv>k8$YN*jeX678ELihx zMNTDUc{4HmfwmA6L@=m!@2}X7BCM$r<@cPy`z6Hq8u}T72SDtyyoX?WtLJ90%SUL1 z%u$Vz#J^|3h~a7L=qC)pC#8*ff+o`BjBd(Wiho)_^ra1L`M_7Al7tatr>NUBN1XE~ z@)v%Y&RCr&i?BfXORV$<+rMtdrZHv-kHGjyA3-5;x)yv`!$E^Eb)18GF1u zSvYToF;0=6GM|o<7&wm@FonNC8i?j_E9GK`2&+OtDrKE5wA)Kx?qRShL^`R@sD}Fn zKfm#9&OD$wr|AQi6trqeXT1VyTk#uSF0yG5X2G1+{zN=YE z+pemSoxnwfjN{2kM8Y|}h-EurUA#QB!`vl?rN}jmGMm3gTW9y0(u^@n`1*Mq5isF` z?2@dNBJe3jd4o6&&`PlY(+|jzwU!95)H=oUr?Z>&oKaVVU`+GbU5B~CF_&XF5Bvm9 z`6lzL)TS*pr@hB`o~YBDb0K_!BKWBNv;6O{ow>?Z_QVJw=}Mj`im>53P?1}42YhYN z_xOe2QA@$roN8CyAl>>{$GIxBY4{C(Xle+&9rrEc$omx zA4V`ljz$A$YNymKQmgU~_PpY+3jNs*;5}-Fu7wX{IKSgf^YBFUOSTB9caFW=T8M`m zw7%9u_?IlYui|`ioc3mIRqIgSaNi=dj$Q@}eIo4E%MOjhnhe>-PKj%_b z!}i3uJFLXDl4v2>2k;SjsErp0gqI2X(mkaBYr*3fv4B@%9MHMvXWTNKE zco5!_Z^mqt)|kmTdV-YKQv`(PF@cTMRxk{hdWMPQtglT+IpUMXW5x^3`nrZ(MqYxuI$>%y^&vK?MS(Q@e0w{y@BU@xgjU+DV zEp8})*`1oM5Y6C3a1wV!IH{(eA9eGr_~ed6QO!)rP9=0RpmyAiNW#5?>T2r+7PJvp z3HaKAwe*nT@taya)4Fs|cZnGo5DvyI^}zi5b%o6564Zf_HT|+r?a7*WFArCD;+-Q1 z$g!)1S0iJa)+HI&6)4o%XFRV{W|vdDi*+(&AaNm-JxB;O#|MAdzI7)PWZ## zf)rS9gM)*VpEWPRk<=d-`AEbN!5#!g9+XwUKx*9mhCE}mz++HdzZc%IVHSMG4=8rY z+@n?c4MN^&N<2N}mvpU4wxct&&+$R8b0VVMhfIA16T;?~tlifze8$wCzuSEW^;bJ~ z1QVR@2U9Q2Fh4pxgI$fV2gY~nPOqNwL-h3fd(4P#=`+^)b;$rXU}?5%KByhDdU3%U z3+;&bdI3V$)tjbHe#Fg{-d#x=OnEQyJF_+vnpRmpt%7+ARU$2ececa_`2oTP8)>Dw z$p4mczeH9s*CnY?SV*U!EWXS9B9pSgqWTi}yeV&8{SjYJl){s{uWOivbU?eM5^vjP zZ!9vfTCB|l8*R7!|v6CYj5UCS+!X8f$v@}QaEZW8xm+G(hsg{{mOXUZ9 z>Fz+yod!>g&Ryvap`ry&+>;J@LPtOLB$3ht!g~!1tlDI!3by4Mu1nxS@?`Xp3;T;f zz90{_`gPRWu>d?|O8`uCedDKtc_32BkUhqM4s1F3id<77~* z@FV;!9d~||B$6>8Nt%Kt8Q50XlNKk&X2!1~ zc7-NpK!(lz6%LVs#xxa!GNJ;iVBeGZ>RhX8>a3Y3Ri4%ymT9KW`?EF7iGrnuIms0> zdk!|Sm9N(*zl`acEwZj-6Sl$GlBo$Y$l2w8ne8tpL#E07>Y{l^7p$N;KC}xhY58CY zImH^Z2)=qf4!(pe0=0Er$qK#$(*2ZWAQGBmKZ6MR2G*IbR0U;NK| zP7mkL$Xj;Mj>N|GNKd_f!Zojj20l98ZjJ5CPwF zQm6VKkWu4(El%hBldX13Xao;ixFt3So|K5zwTw#11RJ6)$PUii2caA1iGyNC;ZFSo z{w!_iqU)}fTqL+5Z~4XPp2C&2@h+b&@6@To)1DIr9jmsxd-JfEqS#OcFlXJhkh0IYXT_JE|wzkk!*DHx7t-NNiKLuOe8r> zdEMRd6qxxyPFXICJ{PAM$c1Paxe!51jycAClw};MjrJ47o8ygw7QpkQvH z-(*w^nw2+8>$G&;6#8mOO_=*mm&$NNQzlz&*2G6u>?L|QQptJ^gI>s$k+-g4*vu(@ zXUHfRF}cEe>*;L3BiV1W zSypj^WQExsN>q}1c|vBF*D**^0qFehS0$9R+57|d`A4ExW{0;onX9Tfd~&83GE`uD z$)N!pwUbNU)Qn8yDU}|_%glj;-i}8om7Tl9a}Q7*-0da(q%kM2|Fk>DzFMIl zt@rB3Ty^Z8q42*(Ye%JL2g`q<;m7U~drj$xf2&{#QAEQX7eq)zqK#`qrjvc zF)a^YevXj>qeEDnX-f-)@e;@?R9tUJaxaY(GM;zUlGTEg*j3}3eL5`B{(c>8>SfN3 zT-rzcqdmLWxr?>qkYkfqi)dSB|MlAggW{+i_=8`Sop%dXQM6`8!jpUEYav&-S&X69 zJaV8d+=h4eEp&GeJ#!8~qRu{&3);@d3uq2gvOX~wKQ8m@vy#pl$;kF4Y3AeKXM~as^^GGDfQa4sd}!!g{XWi&D>y5U?L*P_(&`&s_+sE*@W3-9Tn2Y=V?|B2j%zph^E z_%`9*&`Wl$G}S(Eq-#FpF#HsIPPHv&d#t3Vj>$mee6^Zu8VhuR8BHJy$Uk~`5^C`k zP*Q@knDl#0?^>uTA2J_7Xhwg)F_3phDx$jflx5dB&*)dY`+|NR4q&-%oo+wp@7lJh z-cjO-a-=&^7tR7|?(V(gmG9Itpbr~d*@0wR(TD98d4Ik)iUBQ*fg#J=6WbP>8{C%n zyq9AN9yT~GBKKpZ0lquRUM^3zXK(G*Z7Fz|iH`D@Bx`#v0Cz?E&|5X+_4!gTnG4-b zenltDg`MTYnJ%Q92j*dpO>WCEyY*a5?`P{@&w1Z$eoEauQ(xQS%7}Wto|7B17soi) z*e24t3mq#Jo!UHGea)G~-FE(4wq3uyMDcD2+Ph1%d)5q`8t{qBHCBQ=+fRSvZp(Z8 z|FO`&BznExod-q>u9HzEy>0pX3|=RLD<1+8*nSwo(ms>-QfsXv!0b*|UD{|DjKzRw zr%UR+$ltjlUN`R`2j08PJY=>TCv1X+4Me$L4cfYu^wlIzlnxyGu;6X;^dWkoBD^LJ zWlkSfxgxDCs=LsSeKWmWH*?3TMvgx0uPcOHy{?nx3RA+P<;t_A-_laqIhxd<50PstxgTng2-v+H`bO!5l^A&hBY@k}oQpqc8E-aiUaFch&p%fmJXoZrc;O zEYys?I_fnE(vuJ1`6N-C_6dzQX%6ZdWoZN)%PQ@O#Wr@aocU_U=aWN^@ruRsqknf@ z9Domyp^C9=(`Rp4s!r_i^mmXoDBL1?{pAcu@rRitM*@4bp%sjfQMYD}SmMN#Sf z&N}#q00!;ds>sjszXpREe?IU;vXz2V#HslsNwc13PSLpv8ea04BebR#&Gm{@?53V~ zt@Hnw{{mEU<~IMU=GXaJwh)jPJY)9U(=yrVQbBqdr@z7wm(GDX?HtweAT8wsQiIwi zP?00S4_1-5k97DE-+xMV*h$uU=?xhNq#b$VQ4aqP@1YvndMwX*JNLN7YJbk`y#fy0 zy;BE9@(pT22vs7?WZ2^aKNM9Z8N{IeWF>U@Oh$W&ECI;_H6o{N2p8uK2B>K~xr zD@Q8E$|1lxHF$+H8cSQrEQbEHtT=5?%xEZ;^B^_KXo30LnE>61M@-e1-2;8*r~sA@ zTluV8Pzi&*0&8+vCWAcAfAvDnp$e{-oO2+xqOGGM1Ba=b*XD*K`^-VwS&FQ zn|yf4jKR%y;#2gRv|I3ll+Xe~_c) zAE8(~bGiSPv2R$hLHv{|paJ>nW&R&v&yWm!)lrm-0R~)$Vd9GalW5=$K$yVoV z*b;d3^a5>W+slG}1Jz(ZOcF!HX>+BayNPFp^$Lj!3(gIZ1nk*rPG9UBNA!M07dShh zOt~Fw>us?vc=-V>x)$yJ9zmAlYwV8iSmW2U$(svVQdk#2eDuGF9dKr9OWgJgxJkz6 z@W8U@h9HPuz^7W}bM*;QIJpbRE~F4XvfsDh>B3We`2x$#{SZm{N~9Lp5K$`JrSxYn z_hC&ZXRqT*FOX2pNud!?LwC|E7=yZ;g>?nKunMVbGXkx1isuwDCwQzuH~oYh@j4Hp zg=V4k1+Zf{Vx{7`#+|_tfNG^*@_S-On|gc~!1GqA;CM{yEKv-A7s%jFBkG6l>)1te z7ky{sXRTcMU#(xFlOZx)4^Q+^-Ge`b|72gng2b783@uuL!m8q}Q8Y2&T!giT&+t1T zU2l}L_qMsTy}bG<7N8V8fFEIAB43ojbc2^679Z_CT738pk8Es3xL#}j;RDAO?xGb^ zljpU5hXBQ+@Vv$X6t*S3S!e_}g;l74w$BkBij>x7rR6KENxe5VjTq6OZ$;0T*Z9Un z>#xty0YpG&uK`Y&d)Qy~e%eVwWFU~(GT!y)-2ggKiqlVw-;ir9S65DP9hv%GvPe%+ zV4T9H@1$fD7PzTP@Yx4|a?V*rTURwDdWDyH+~fVmyxkSC?j_GQ&d3yri$3l7^>QqH za|ukzvn_n&de64PEm7(Q;+hU{57e$kr1`IO4+#2Ga(T7~qy$_{IE0e&@K7JQC=n8x zstUgjaG|J&U)}Fc9m0kC_RP{d`+3tQE~N%Qi5CAaa9}MkIk-wejj~oT7v8YU&| zDj|6(djK^TF_6wH|Jm{!J%L?_#gG!^P0+kn4V1VpdKQqgr{(S`{UjnAa4qy(W2s`g z1q3~=c)@mv!i*LMc_k3M;@o#)&yNGzLdZR<3Af(;I zf{2!C7|Jh}qo7&OyLJ zeQBo$Uln_Vpj&oC{0bioo}oYWdlQ~3WF=j83h6CK)}x0pNP2&?9{qC$oo8-(CsU$( z`g$a4mpZ+1w-SWUmHAm-fwnr>^)Ax}MMY(_=9BElg6r8Jt*t zj&C?gSmxPK2xIYH_vr>?W; zNgqOHOdViWB|i=3m=Mh$-y_6aXP(Z3R*cr^2+7ap^aF}3@%)Ub4*%-!nCB7yM0LP9 z2sJr>?KfYE{Q=1~R zAh;pth9_I*BTHZk+9HWZAC@kAQdnd-5p#CS8EH34ez z9chnm@GKf&8$K*~9JWF=sMGi|hD!a(mK@DO2$MjL%JpD6$H;3^dGf3!u+@fK-YSUR zv(EVM4j`cg;c?s8)jnynXZnF#Mg4O=vEV2lx@(EL$*NJo-$P@<4v3r62sG3@NFGAi z4T+Y)M5YAkF{gsRPmnnfMQh_?*31z`j<*j&$cY=J{?If2ajuNKRaFyDHF-xv6{OUg zT!MqG;g>zh<$%h;?>ESuBOD<(-8z9YBIhE(76m*%yuh`PvdSyV*x$!daQzzR*hCIL zLHB~!Avs?li=&akvj=*K`)}UA6UowvvnMFUf4ZBWy5l{OQ(|!3x6)?9o(a)B}La_{AX4S!C2pxe7$AJB4K5}(Or%dnlDqZO>qo?%7w$NlN z2I(pX&#A4@j9#wM5IA#-sBoKyNA7^Ji_4K^Oc({!Ia(Y+F`fb;?|&u=2r|u@H9BH+ zi$Q2h{r4qh;rskLpA=G_PJZP-WvBHswt^#Kw(@+O33_$$7xEF zv=PX@)eX0U2R@j}NT#2ZPK7_MvB0!aH+gSJ)?dvU~ zGQAwK|0K^R31*LWY444!`QZu;uu$swz)Vk(qqL&H87g*ATkURPugjE@nE_WH(HXIU z@POQK67q%RK(8KPLe66!`mIBep8~R0ei`e0ep4y+p7h4dO(cIx6=AyNXp~G%&>`>y*91DEQVc`~_@5o3e_q)90 z1-G{h6usoMAHcl1c;X*obR(~!_W1w~5i>4C&08V55ogy(b@ZYWStS;8cg zLqiI!xW(Mk0?rWE0Dc0k#e&`P!Vh6$Ds@m+Ei{#H3{K4 zTAax1VN7*eC0EJiSu=pb3ns-DN$>@9LW)=~sJ*?oNRaU5Rp(FCz}t@kYEla%w|IvW zAicfKoKx2)X##3K-tv9Pi1UcQudvOti9Y57GJ!hO*le3izns7lcrpVzVR}a5cV!um zw2-p@%s=UCczlNaBOEe3fB1}DQuIl`xvt7%YU1mSc02OLF2`{5-A)PkG^Q@6l+hip zqJ%OKwEYph=Yu<_BX^hdvc;6cG;W!+hGY!(@=4M znS*U7Y)-c8$s0~H-#72v5%Dteg_tnxi`dA6ei-!|C@0G<6Fyj=5>45u3fhNzm^<|` z`7|L*Y<4)#jt^imqRU%irDq`^R~Rs@}JV((+ZJO{3SVaJ0%{h-ruCC zgRoUdY!1SX5NS?J*4#9r6%#9@5;A3o3EL7Yq5$uA^b7+x{{#(VI^PrS6kx+f9@!P% z*^^+`Gg&YB9%Dme&j;0M>wwNVgGE%4$*x-0c-wmwXjXOFZ+Q4WOu(W{Dq7s0trubo zx2%h-R(O){@CB&n+hRIjRi%^(`7wVkqfYFgQ=(2mor4*%npTt9>W<4Ay*{}sAgyzn zOF;w8E-*AO-<5W~=o)^u8}@35dWG8nDRWLUGy1F1ww`OZ7Hd=O4y&5bDoyY8E*|ke zS+6jJ7y8oA$OQGVZ{r3l+1Y(%A9e`ljYUM%6Z|+Xp^5d3;91eO?f_60uOpssh*{G8 z9=d??u=wJxZ*&#Vja{CoV57}+H4T4%D5oM9lYk&tXYm_4Bv#9>o4>r~1w3%Ue>zP* zn-7WUb2BHd;(s~qhXhK&Q(c=q^e%N{(V47J>g+MQFl-deSNk0@KQkuH#M$M3M$9C_ zGfGSDZm^}yw$^O7ozZd?XrY%ugGj~Px$&w=O|&Y`v#Sy~mf~~vCJ0xyTi4wmh<%`y zf)kT$+8WmjVjm_q7koizZU1uSuI+rozS)F+aw?&wNW~a-#|j60=eK9ZoE=iE?hWjB z@SITyOD_BJSX~BaBE-sp;y3Kg8O2O4i4k!Hmmk7w;c@s0;RQlWZ0K&!TM@T&d%S=b z9+4+(Bb`a&eBCwB?DOH2^VM*^f>j7MV>IOakPUmDdNmjlIrKyzw_QfW9pbv5$W!TP z;_00Bu#lExRfCGJ`NjUm?MVX701jOb35eO!uz0y|5&L$mS6o*}al}upmEBVBcj0WC zo|+@@?chMw?u;XBuvHG~{F9zU)f8@n43hK(d{Z9KL^Ae5nTSpE9r0ug3dl|+D+fN% z?A^iHz__T8;(Q9WiG|JM&~@>ZujM%3X>Viz2>eJq?n;g$?}pAX&0t5JO`$#s1kR4K zGAr;4m&A80X#%&|A)G_35_eu@_oZ@MP^BumS1xt zK_0mTSzK#Wki&+T(cox!v(QCHA_TtSYC6PI%mWWDc~#WlQQ0HeREUm%3rbNE6)}Ij z!Q)b%6ge??6eLX}GR^ex;&Cxkm`{ zSl*1nP8|$}7vR)8H+~vQ+`h++OOPe1q>fRETx!TDa-x`nx|lM)IGJ)Q)CJ}0C)?r; zhd<8`FBqnxAH;eo={g!sdmHEie3)g12k-#r#c&un_fbK-fc?04JoJ06G{%b}@rU9q ztOeswwu%wob%o?`*VQmPuSpIy8-HDfY^)j1+Tskr^0>YUbhlwIu-gtP0l%@i(A+Xh z^fwE%TTJ!Y*{V*mW)G*_PXNew*&p8POj*hpg(5htZu2zYb6OW0vT_kg*DNfQq0E`ISUsS+F+&q29eVK5rkQN?r(Zm-n33^<9z6Gn+4U1H1~^e8?w z019x5Cq3GuQTR;N3;Y%?bh%dEzTKcN!a6P&8}953|CUyW7n(M)r_Na*%iBBc0Tv=qZhA!PmbW42y*EZZ zZvjlo@LBM`1WlWrZcr=Z=4h3^0u;U7Lf_CxyyhUf0a3q9R9dVcTpnw0GFXP8dIOv= zMA@~qg$wa;|u<})5TV47yojhRWH#>Q-$(k!kkG1ydcUrMv%33Q9AXattEBBG@ z>}Rb&aazLFApyl|r8Zfy)j0!Jc_&F>UrrgWV%5dK=lb;Rt)R;mptKTEL5nzr!L`2x-$2v419NYG;h9mY1ar%o9# zz|b|+|liK`KRrs0cAIKcHNe6i>dTgf3V zO#W&8*j~h?GlZbcLyE7!Q;(r(A#fy4b;|%DHT>opVP`C1W{rZ`o)N?)XgU?1p!|gu z@?2Madgyj>(z49afj{_U4MlSH&VOh4-)InF2MjnWrwGsueb6FC?wg*VYXPc9KVyEb z9>F(CiWOcw*tm6hMb~J^dM&FW(^nfT?T*L0C)kZ>kbrXH&<&PS@A>3Z5ahXyuH-dm z-Xm`=G_w1tGg{NdHrlUuayiu+D}D0!>HJtcin-aag?Sh)d(~{s}->RX>4SVfR`mdgLQ(bOZQ}T*$BqXPWI{ z1z$b0Tl3{di8&XDANZ5SIClNSx|z6d$k~Q>x_jfZU7RiAvV5hI$qgPyYNzDfzn;U8 z9W_i)FKlg$S;4e3HIV7Fi{;FLe@ zg^YW8TU8x920qGj)nYcmmCO@%4ZtTP5uX%%!hYvw;6bDvMvMt;Rin3wCbm;cRyyk1 z@TCC|@#X8UkB)X-8Z>~@CX&ELLp`F=`06VtTs`K*+0hZ(5IUkx-{RWtZlj@YYPo)` z6m$S5e3Jc9jo^PH1}yj4$KDy87?oqa8;-B3WOLPYjc)JaU>o90cF1}-_q=$V-v<9`|OGY|;ZXIJ1&O+@>aLSG1 zme|n>ME7Wn+<}eG(2Jt|jwljcUwx&4S${`Ip59@rn{vV3{YG7zL5%KW_`{zxJD%#6 z1WvmkbT3!$Tx>^z{U$QQ7_Bk{H@&8n7GUH?SNpw6Hi}b%V%SD|(!4hvfyN46Wv6G4 z{vzmf1|&q@Fb>_5I+>j2Z&Kk7nnOlt*)r%BETX@kNKz52&iZ;3X?IzjKYHA*e%XIQ zH)WgLJqC+Ty?&3kgGyg34NcQ&CV~ZT8ei1+ z_g5cDQZS4=Hd%9@BlC(OGfrliGMF`gO?;8E?fa|>ax*?k2Gxl>4=Ieghr0*+^34I? zPJ(=i9dCBSQ1d`J11I>*nTx76%wf%=N4vNdxlVu>3};Mny{?MBb#cL4uGr54FmC%8 zj>p*Db|)9}Qm)y>Rn#9xU5tIY0A3k}r^xQ&*vFRUp(DSHHgRI*@9j3GykF{&7N?dY znf&gP1Uc=?IpF3#S@3eF4CC1~du`-B(CKw1Ha3$+qjOS2lL2PtFHoLPHx4?;vLrId=AT)u4s;(5#vW{%Q1;$DMdBwPT4uoO12oAjAA?V}Ui4PRF8ibtBbf6*f>|*EBF| zBe=hrEd$kob^<28@}6SP!!gy;Nbf4?&5 zX5pF0?~R#);($2sA0i>_?~^Zt_nW~*G!b?V7qq~t6Wn@JuHENNj!e|{H5a4XFybOX zBoEEDV{X`myW8?*s=so&oMzGVIhI+mn_U9BT^S6{g#pS8f8F?yLv0s~lK;FveZ*82 zMB;#M|tX!}5zhw@}P0`p0xaD@Ib(wC`!@R3k7F26G;*P)l?G|rioN1;i8S5}^ zAyXq}nLye-(VH5nQPMm90w)Y|GnUV8yT8-_Yv#NCUA(1ZdwT|Avcr6Ra-jE#bnxZZ zCv_&)_-=ds&KcX6qk&|nhgf2D%ux3bW^+@(Yu_>(I%abJYa5wtCF&h_`pD;y`7Aw|K0AR2gkpj9MW#`XF|O=kHvS`8Gp-qf@~x4 zX{J`_d2Q?&mrIxhTFjcL8%YxJq}yI0S$ZaJ*u4P^)NG)wS%uqm*aI3VC9u1~`>0Di zy+tw}U15*eE}Nh;rq&;3LA%4o6IlRX*a|A98oS^aXm+=?S7I0G=!|XkN_H+QxHCl8 z@}HOt3rdKrQo#|jiqvbpG6<1byqjId5=JZDJ*%EZLB3_+?>awn6DIzQTZZD2FXHAE5>xy1CRBMn6?a)v*%O#hOnm^rh1w743 z@kZivGoO8bj8~nmIF-Sz_&W9y*%U}NJs3gv{n=;5ROj`2}7^GHMUPTJ|gq+|M+btJ7N*^yZ0DC9x- zhP1@N7_)^<&G;rs#Wy`2c91~o9q)7yHtOYu4~^*Km^O@oZA>5u4hFF1%&0cRgZ1}% z=UXlzGfPb)qpUAYjNJ+|Z6!+$CC?9g^I)FYwVJVe9%&a@ag3p6)yY!R2&-`cOO3YJ z-Ppi(<(Ue0v68uW^o#w@7oX`&oG{XD#dUg<+!WklIAdow)@kot{^bzO*r;D$b1egm zPDyY1+pmLnznD@r^C0Uk9>H#2}E&v(tcn3U--$Cgg=beLz-Vs zzCm1KcnNDizPn#LeqMWg+BRR?<9F{KpYnA2n6n@2>uYPZ`>U(>@2{_~uHC=C#(#Oz z9+T@i`Hzp4OWwnG@7k0|N_|!*?`JAiU%OxPQaT0l`0@SNbLXc&bccWKKJ^+Z+MA4z zPB){-PY4O-!Gjoi2%(HWYGcRpyC0uZ+x^Yczrmv^k0SV}?xg-TFy`dmhOL z0F_p;QmM83_twCiQmar6=DOpbkuqL=>D%qtBr>cFHMAtA?DYDNC|Az(v+KB{8MWTDN;;Ok&UEb^X_kPL@9h0R4fQ%R zSH`Cc&9gLYaH|70*A6BLFYypeI%W)A;}dJ1s74Jrs8-h1qg~c_>EIY>hwN$g^&{b& zgs?x+VnhH1yFZ7g?SK~kjHSUoV^G5ema&CrAgS81aALKE7VKyrblXNJha@~O=X7f} zxl#SHWRg8@=xrwQEr?=$pZPO0=)=kGc7rwk5w+RCd49kEhMEEjqhI(()~hx4F?eci zmp2?T!14Yub}?HoZ46gCXmECX{1ua?KGoG3ji>)aE1}Cc{m&hBj4`(BMeCLfj`5ra z<%WVg3;%il5QlQoI+g^4aU}Su}))s$HjLP_@Jz3LC`Ldx9 zI1X8!ClsMHpS|-2%|)6^DUqU)1)h)>MKf;lq;no>XKJ-H87RhW!v+sd9mT1o6v1WZ zl0Y-Mwsh-&!lDn!# z>4P22sNZ`LbreN;U~w)9*_WI%;)xbKQs*6|@wsM)DU?aZdD2ao&*(LK;3)e+825xb zjwm6_PWo+n*N)+aVRQxF+L>gSLi0`3W{tEbI{JbxFAr4lJS0^+_r+f$RZvv{f3sPg z&cQrZBMH@rgW`(aaL+U*V2C)^J>0t*Y;9(*mX(jZs7~(z#23XJmj|OdE&Z!kl;N3Qz4$)y-GI zHoi*Wi74Y36Cyn9vN*MuU-GP7`%-tw-hSDsI8hjKWzdp-J~o`J#||-4NDmtTxVogj zs2wq@@C>%(aiSs2cZ}2Q=U|2p4GGEW!EZ!tA6zG^u~Y>;F2UfHKSOBYO*M?aCdJUI zb1e*jD022Yv;LzsrpL8=tTkyQQ7q34ft(4nea{Ri3?h7K40`;KF)+S`TPs?&E_Cny zFaPX55MsT5G(uSUW2V*#m}x<_%oLm1(?+8XePLUpgUxc7-0CC=J^^{%@DfQ5OpBuD zp$U28bVb5N&WUup@<61pHSBkg-iCP<_PN@U^5VYyde~jOu?~sRdtKVZTbl9Cdf}1v zE^}meXjR>+=MQ$e5nO?!vB*jgjxiezi}C2S0sAAj1M>Maf*U;`TlK+reqb>xAf zz76XQdP6U~IQwh(@k12M&;ZwH07Mn)G~JQTMc2&KlWcU|>64<4tv4hHZ}CRF#Jd0H zhB-&0)6w`$%>hW_&*;3AkC(ZKPA~K4eoyD5QQp6TFQZ{+^o4PP))6mxd15`*^}6?- zw_QztX(tAy@qdP(uVIZyk0Ox*JDTnN75(h`njLr}Hqa3><`yJ;L?d2Zdf|GX`7^CL zWCAhZd^fdd0%~dO%IZrdc+Ktf|BP&`g(vc6gizBC2K*;TS7u$K$3_czi)Co{&~d_7 zGZ4;0z$a^4&H(*0TMBu6O3Q46#x68|yBGrx-F^usCAgQacLS7v(3^(}+? zX!;ti{;c+n&u@6|#5+{Qui>zG{57iKH~g;i|7WOFlq4!Cd5#{O4#R@><*@)+ILH#qaJAAK$?*DcmjiCl0P5 zvp<8c`gU!t)%n_=J>0aD=xFR%Q?uKEOq*umn_d1K#eJ$TZ9z!vbe?@qa{qqa?DSR5 zPCjFPU~Q;90_r1Q)qec(tFP2kqG)&;oXSPZpvGoKyi5^?fzFw15fk(@!~9{78xI=2 z1KNhcmh>UF1aKt?!~S`n*HC*5d|;flTPlLRy@TFCk5RwwzR}6(`Ez*E8BLm}Qf};v zJAQbI7Mh%%9@qAFw^rrxy}3NYwK_dLn{F{TXO-wwD_4`@>8aK?qNsU#{A<=(`=`yv z$NRgF_d^@|weI=k?D6U9)^rQImU9%>QLo38eiD2cv~c|P!<*^BKKo@llf&s=sD6tk zeO9-8I6<}e&=~gRiT_$HQH8ep)%o#(I8W2`5i=ki_kIs|cGY?aW^ldN zI}m*bP!mNXc&H5(Yzsd{+R1<1hN~$4Q>L(;&f1h)PSER@SE#jVP~ZF(pIkHzex^roEs?TZK_)yekh&tH;Ya zfgf6}aN_1_Iwm}3!u5D_9NmcG3tk1iz0KxcvojwbAC9*sJ3D7*;|totZdttfZ)|wn z*?KiS!T)y7jo{%~xYM1ll^gw{;e@ zCa>_ZTuj%xGsSX}f;rySeT0p7gx{wJT*Hf#m*=N^2ihn2tLHs7|DB&7MZNz1K73-X zchKV?LYG#;w9w5ly)T3M#aXX+uUBKD!Jf59u+N9jd(B3h-&1b0v2q7=*ZtmsY&KM# zwek%!*z@PTp3VMvfrjRs8>_?fCtIWGY4Di0!b`%mt|Q;*E3Adp{k12X@QpfZe~SpV z>+RO>5Mg54o5#aoYupYV{~QQwSMs&nI3r*C{{GpxUSE5%|DVo|*#X$yLuwCt!Jdw` zz|h7I0fTn?#h&E9cW`B6g4RPq5d-%oKW_z_WBTZHi`%V)uWV_0*#48%v#nQKU1h}O zt~2c8$7h?cYq&prZz*t8J{`L2#@G+ z9c_}1u-foSZP(kdu5*3;w|E<17HkFmGZpXk=W zrqXb`-EON7_j+P z^LxKvWyp$^8W}y(YXEd+l*D)O5+kuP#mz92~IQ+!Z5^9N>+q zqqQJ2xWtCRh~W?I&*}x<^6B$aSh*kl5ieA2fBy;3=oL;Mpf4Ke$?;C3{~P)M{bCKN znlfrI>hAvm?FBhtd3yZ#n7v6Sr^lzqyBt5DMRtOQY7;MzfYx-YGx>6Ji*uP>G;#}- zLjSk|lO5#>>VM>{Yp{Jd`qlHD9rjG44Ej*;35-h)3kmz&f2&b{%g(UUWISJ_L#QU~Ks@JD2Ua|x3*Y$Hj6MvC*}{X^t{ z@uA<}g`b*zGUM`_bP%eey)VCP)my>AuC1zSY(ZrAcadQmBm~3m-s$wvA`-(Fd%xh_ ztOo}-$cH|vXEdojXF%DX{6U=6n9e|P8tkubogN><^Q|*_W_zc7_1}UWuJ1&D)2>fW zo6Oi5U7kOegwsB!k00;vK3U@z$=DiqaVF@D9;_KZI%6e6_tU{!yc+Dvopq@HSCWXb?*FRCNfTP2&a{X&;phb1V6zOp{OZY6BkZfw zGgeE2`pE%TxgyDbM1xJ%u-LawCVw*xuePB;6r(K|!lw5R&w}>fPbR;xHIs`&u;ASx z|GgcYZcX+dO}0+8dzUc*?bJJ94@{%0eK5KUWRJaiM+^lAgc$~~?-2|v3YPeU9~L~) zr~5pkXvQ8JMg7C&=4kqaOZGy+xV$=>ygCaSXKSyU`hK~R7-Q5n7M;9r=vwSy;HyZe9hYA1LiO@-+$v*7$Wd*Y%e%#qH{INQqryu}Tp zas-H9C`U#IbnHLwch1mc_jr3VBYPx!hN{7jF`Sm`&WzV}yHFCoMzNlv=)n)6MrJjz zhLLuA)`ihL>im4r*jyW7SH2nt#A+rQw9ihb_jiIbdhPUa7^)mw@6fj3y&1H%!*T00 zs6Y9;0sbJB0ei03o30`sYc#+JC5#SDN(z+mg3pGq$wb zN38YIlUo{j(OcMavhju&Oc<&9;?_8hH%Cs72o8*0I$fkwwK5j;FN_(v}Po6t5Tct#Yjv|8Y)&?jlhuu`5DRYp;mLRSiO;6&Q|@+gNwdOzGU;~5>=_ze z930YTcV@^kx?XQUd~|gr-nXPZ`vT$-hMLLV&B~9+2!Tg^ceD`yNo9cY*^3TbFK_l59?e^`m?J#t)m+g z(6~S$yz`&CC_iRH;?=azF~w2$n>NFyu(a7t>+7%omAf3F_+Ec>fJeGs|MRb>YuZI{ z@1E$k={h=UeBNhuxL)VXC1)RN^}qajmmD2t7&Xi1IVHaa*P&y@N=xZaCzcrdHN5;e*T_p)B-AH#}Xg8$nL}mf(P~8r~ z8?w^_tyCypdQc(SU{8(P3bch4+G5sU z#qtOKY~*1!#?~M0?`C#|*zWhC|69*;bi~_`*uyYo{YUTbWCN5kjIN$B+f#E}=Lszs z&g`ef?f@j!<1}_jF!$u;)Y!|EdH z(z(Vek9{?L_wMS7cO~(nj05(3;9dAvtsZOV1m4~+M&BM?o#2~q1e4wA1v{>=LxvaH z(>pysnXYwKN7U7oE$osK9yzB`p5hq{N00C6oQWt`5A~3qf-Wd%oHvg-dXYGrX|=NV zy>&*Sh9j8lqPpnAd$b0JLaB9nf%$+3wX3(@T(D$wC`u0Ws+|r?MUci>v-e3RPTdt&$u&4QvCR8I5*!cJNZ}kiNs-QAL_WydWdC*^%amVA*633SMc_ z^u>qK02@ZVRlc*E%dItRm(9a7c7p_>O$0{Jd-jUa1M6q9x_O2)(ob&wfm!m->DlIZ za6}y%DwyT3AsK6H!S?jY7Pde)>f=inH}MzZ)9z1jW3%M~4`_c7?*IY`?&$?0-o!S$ zd9J#D+dtpmVtMyu8eN@mT>0;Cqw07WJ$r!ryFC@&-NWD&1rBOpkDjA#x!cEd7(Ge9 zfBAK1RJ+F>m1#|TT-adFW{(qgeX#aBCVg^pz;Dg90_}}3wo3*(QW^4Lt{Bm>riW#vW(KgKLxjkPat>%T(SF!a9I+s^# z<0n`)xJ$9_|Ft`1q-FNQlJHR%>-<1t2fq0k?HvjyT3~;S8|A!DRp3geJ)E$+F$nA1 z7z4;sjgPp=tI!xv>UFIcIyd`_2nT&e)_6paw8Hh1i^I|AUY!l~7kHN7=JarlQG-Ut zUm(8guXYUONP{@26_Xt{+v*8UYO5{V61%!Fqj!!^-*1FqOA~tx(Jy3Y-dI0DrYU63 z=`L$b{wGTok--vW;mSu8RX5%kqjN`i^SJW~ryV*M2LjE1aUhH!h&Qwy9Sx^rY*~a8 zuME6kv}H79-H%~|-iu6!hOfTc9;Qv`bzof&qh~W{Y3~j6JsU_4Ud+@Fc=ujNVdNn& zuK_mFjJ|gy>7WJ7N6@{*(1*Y1Bf-<@0>Fm|vhb<8FKPU`6JC~nkY)a~_84y8f%FD@86{_!8Nd^;2V z;|*XZFIpB6nVjI8oIFbFZbYmBap1ple9ZSD7J)k z7%IpVp{)@6NytKHqEB9;OXEB5xRa+rA;loGwr+(!Bzru@Y-oqHu?1kBt5IKNn9-Or z!h62EJ3eIm*zfn))rRHCeG0(^FR1*_SCD{k1dVr$DJ+z+lak#SqfYRz*iK-s4J;S@ zBIm=&$vGDP>XgwFL_5*H9LPh1{^qI$xN&6@A@=gM!EDxUu=Z)zhqcBLvB($Wj$(;2 z$%sS`Bfz&>f$N513m2MXXR3hhV@_@?oxvF!QN)SW5jW_vF7fBto>Jko&o*x&seMPCks z^FCW!F}LLFV)nzV89x;_b`wL7>0Ebv2TkPRpvTxsTT7xP9rBpG>~UNHRncNQxTLQ) zJjW}-zEC_f%-=eDKj6FAZ3W>oUVcO=X{5=dDL+Us`R+OE6Y|C$o1f}z>-70C>mK9r zks5))_2%;NKJymdT{`_gC^tH70vd~zTsBX`&xIdl%=7W_7r|%KP&UA}lmNcZ$##2- zQT&t_qam|hfn?-p(BsXb*|xDw5tI zhGcldy%~SA!}jkJ#|NH6M^u>4!uPZyf*c`w0b?qlLCJS9Zu^y&% zM3%N{Z)-oYYe!E%lD1a+L+y<{y<_c4tB|@C_9x<|gx}Rp$@>%O|53Yq_}hE2%K%9y z2>ncx4V{7AD#LG18o_U- zk2w8xzBSo+^rSzXVNcy$p5kv}{c8H^%e_!tPBS$ObDYhajGp50x&6aigO#KcnnHt7 z3IDx(H1fD~I&zhEk7#r`K=2Agl&c44a{7OH&T5d}D??+P|L(kj3oz)(d*9jp>mGv) z{$+XOwTD0}NX#CY%WLn*nY1ZpQty0giyXKMfW8r3t?j?m?EP$ix4*eL4zGK-X6itd z=YrQvV_H3-MZesT00YlENh{Rj9TS!><5HqqMV zI_;s=VePMsY<>8RwXxP6-}3)Ae15D&KY=kqOAj(FrJlzSchsxzG!%koHdonh@Ka~( zV+fQ7K`BA68zRZZbnF1LkDdQ#8;_=sHpkO%exM0q9OK|WY@KcWe0s<=Vl3xqmW}<{ zp8S2i{n;ZtAk&}g{l-|-XVdB0cx%jlC&opNsj=4@?ark^ay*WON;l%-iZS;iX|?^L z8?j8t*m7VY*Eweye~R7tmnYMEwP2juNvvUu|BqQgeglVpYwO5o^oDif#Qm?~ z_9_3@X`SEJqV+2lsanBowhgy+F1o`+q0_l!{y~IjVNc0*WWBy+PqMDH_dvheYtdo< zMxWggJlQ;SC|hB5^k0w8+3ASWe6owBz^;JidfaOs%l&!JL)KfbF$8fBJ z8OY{KK|(iKyUhmbZJ`<~uv(Ss`!@Uh!e^Si4KCVY)2Eb%YVKVz(@pyC2Qm8QNM7Yu zL;V(O%Aoo8Oyj;FQs+&y-LRziS^Fp2INy~P*Qo<8{nxC={~8(n3jX~Ter_Sp?39J8 zNc6f!cP=nu<@=mjFARXn1McBvml?ZIC#s3vFdg<$%EiFbxkmZ(eJ)1XKwn~DV#{#v zmaNPRJV>1{MyprRA%<3mHHa}o6Q}1Q_9_fDzVnJ<&bjH9&H?TosB1GH-=0CI>@ba0 z?UrcfK{sDOiD^7h#9;%tCyJ3leRvX^J*NXFoGj4}aU1uKoa+)46L~e7`f}BdayErNIH)u^9F32MOim&)u33R zd%E$kPQ3EWfU4T?_Hw=mAFo==ce1i#IQr%peCINZt1GNW+JG%g{QWSaPPWzDT#oF9 zkkRqWjb}I72PQ~Y*eS|&XwRHc8UzEVz=8w|M*Pg`<8*LCSX^ECU4qOm`NP(1CHAhz zYf(gRXpRpSqc^XNZw*x!4EFRL3YJ+F16eHaoqd)wk!YAgmEUs7K}%{Fb~slO9ZpOy z9*$mWXL3eA+xBqva9(%_{X_O{K>zun=gf+03*S zvUMfg@CqfC@v3&C(OdNXr??zjwz0D;C}wn-{HY;cEZWHg8l zh*v$TaYhoIfj+~7NtDkvt#2x)?#Xm1qk?3XI(q3oO>m

+hPX1G zBo=aR>|0u3CjJ23^uP6N%?UF~gFWVaM)wA=UjQv=LA`lXMgBGCC*c}~k)X(umOn!E z$5>p)2`U%_p)$=#jSK_jy9@(lLSo`;a?h?>gn43BFVnY@G{v@qfzpf?G_=L2mAc4M z9X`*13(c)4Gz7S_v=M}0L=lz63(-|7)$%VumTsiTu$8DX_eC1TYe`?0 zChI_A7(m8VKsGEyNs4O;qcP;b8+uB34+2gFi!%0i;Ts_)bl}Q3@W^Q^p92mD3miF%V*UP7g?0jT*F$8$c^~t zzP-3zBBhxAeP(N&QV8&o#Spq|AWtEbh&cr7H_i;}h>>v9 zr$Kx0>)%*CJb0TTYNLU=YfhKbrxS_<4=GfSL7JM!#|}ZVp+2VABPs-2)c{^z)HTeJ ztxlT`f*_%BMP~{c4e_cTUDom6*=UXfIFm4G3COwP zr?)aEp;*h?KpfLMdo^erujY!@+L8mpx&BUHX%9i`!R(CHte*he7RS zU~n#PT=&afQGabn$7!q6HRbTZ>wT@leT5~+?u@vG>=3~u61i0f8bXVq5_{77dUH06 zcCQPy7Kv^lnH2=DRSwi*ykR79;s%}{8?CG+o39CXYa06RM*MCry&{VvDZJ;M?aMWt zQe^&$)sIJzX@HJoCZ{y@rgb7XjZ!0|9OTtxmotyNW8H31;|=P-;P49WL>+hW(~-K- z%ujo2_Mwf^9Q3raEdF*c%Gjw-z4^=G*#2rxVG6#@MnEpc?3arDN^j~S?JH`t_jd8E zTK(*#-t(o}-Lt84nqb1a>l4hZHl44*IpQa4?0l!6`GjO}AVs*5g&dZXGpRN9H_*P< z=KGgGw~_7in+d}+TAtRB#!2IMy5Te0c@K?;rXi8uNE?~Tq6Y_|B%^D6J&BcGpiTKg zl4tye{IBI;dQ6)bq=il!Y6aYKDNdqlPzQu{t+Yf#wRlKRd3Sdl}R8Gjwfqbm_K0u*Vz&NUUwQsf?1E6*C@jWbJA2&QJ-mUN%NrYY??uMT1SkZhKNhvEoOoosQrgUAxAxb_(^a zkK@&~Iy_y`P630^z;pSmP*A`L=-7{mZX3>KpdYA(T&FUP9od_N3o8+ldlL^A5|ovw z(kHlX`7f3Nc4$09@w}xnq2>4Q7)4=gbog`f?eZUghen=qWuZY=W2Ds>kFE%J%mzbe z#&@WYowLM3P)##~C^&+ahe)%+7d{RHV+aSNmAQl@tckS5Ac0}|F*Q^Qe?b@(BqI`d z)c{^eD4~w$WYm$4rtL!kVHB}H)9Wf_I$JG+M(0nu8~iBkBbJY|3}qRAWW=%Re{+R| zcMMoMPtj_c>T)`*H!#mo9`%Nf0`fCC{mfs1Wc>5*OFy^F{9pNU{b!K358}Kr9g?vK zCydXo)PZO(Y&eN*dXztr=wRJ%4eB9 zD!A&}%=R93m)RevFH-nwhnGUG5zupvLiAYOO5&w%cY_9ta(lBD`38Wbf>0xHL+lx- z22w(4$spu`Z@v&PeP1z70R4unJk1OONi)k4=ZUVntj!W50RRVtPHaNuf|)`ydKjMZ zJlqgXpd$KYI>BWK3W;vejQVBQDExFS;B#r7>FiKSeV%8JnH8P;%6a17p~3cV-xUD{ zHsg~YPaY$TDE3ouL-&o|ce*>4Byshk-I61`@UF5;QZl>2DMQK3?1v$h`prBn4(o3` zsy(~G3BDoXucG}&vbXj>8?8!Gqwdj6@kULkkUfQh9;$WKNP+R?A>ZHw4VDjn?p#5m zr2VD$nn7aKs#^E`sYEJ8&|p%uq4ZEp3kK8|Yjxe#Gjgr2TR1PlnGE{R4ML1!9r@qZ z*jc2Wfz&dm)LNzFS2s%PcQm$f3}WF+M>$69-lPDtGO%as2z^g9X=&scblF>zLBTA3 zWJmKR8Xc&>#Rw!{g1zen2}@3|qbV>MVrzND-r_nFMaCD`1jglPX7*}i@*<9Ap{~Ut zeeHp*U1TYdX(8jk1o4Xh`ds_3b}3Mm5xlw4KOO(E|N8q;9l^SOfS zgwX`ztMybKgYI5~2g9CNpMCK(P#$|~J!85_t)WWu*$HhI;@%~{JbN@a0|qIwnO%-+ zEEd2dFUf>D4jDZP7yW6q3~VcC2UFR9qiP3 zE4<~uVGM}pZJoIojSF68C$^MWq0n3>uX(-H0BsW5C=|5eGVLlpDv*3%2b#h#5f!ufM8baO=r9FX7+vs7uhZRhv^MBzHs`8U0b-lY8M zB{p;0$gq|jpYKI+nany$=15rnnoTfIN#7RCY=eo3=1iIw@zG48#(oKIu+hQ^d2Kf1 zvlhN}i8K=wrPzPwF`7&HjK%J%78qt!xNf=8 z19*@-on?`xdkDHw7w;V{>rLH4YP811Nq0iNx~COQTfrngJy*@BO*d%;rgmqP9`IkO zRwjPerI$*}#HHDB$a~Icb9^plSxC+XT^m3H%flH7tKV1KE@EhQ9-MT$bzkeoNH0Z^ zUas$IsHCmo#jBB8Tju@~;&q)PkZhM*%kbkgc=RCPFsV8S8pG?^kLPpo3TKS1*8lA8 zHA=FQC|@0(y$Fw7Yt`NiBF`k=ORO=xm*C5oqwg;VO=P}LTTy_CU%2^ z?gIjsuCKVqvetE~fS^<$hHBMN+K-hy<)_w!x^oK&A~yg?ixIMqbPo8NJR;M0e@InH zQmH{8B^O?U?l~|RKr@W=-qo9EhKHY0E#VI(m&jhj;E3*idbft^)Bd6sOu9$dAb^dA zD5Y^giu7WHP}OwL3Vt8cZ%MnN;}R*5w2L125%0lPm^S5x9^Z-ujXa+`V+9YXXjn;h z%koKJ_`VOxn7FT7opis4WaRvsDG_bUD2kP^t>r^{GyJ_WeFHqJS$CvpmPH9Yk7Ft8 z+fycUk_YZ~mP`gxnr(cel3N@#k}H=aZhzLO2JvXNlr!4D83iAJ@MhC1V9{GGI- z?|HF48Q<|?c!!Z$eS*&OWo~sovrY7#dD_6XGuKT|w|7{PnjCXi3VZMzf?A0GlH8`| z^C)bv+xpS&`AF|hseJ>NMX|=h*cRq>EGj#|4=fzut#;)olUfLv_9PBi`_T^_f_-Zh zju!FSokru6wUW2J+Do#^jW6#1Lr4Y!kFDKfG@!&2$ekq1HoVYOHmt zy-U$@uIa_VG!%-~meUQ4ghK8VqD|F`YLhh9S7UCl%#&4Z`m1p;)|0Ns)4oZIx7AmC zTkT%P#9QK_<=q7v*NPQTT3tIO>$?sEcBF;Pb=b@ zS)B05)vXdM4{G%l&+(_4riZ#uhq$`krDYhV7`=H~Ybxf=3cndt3%zO9o+|D2Q&NcW zQCBf{hW_W~6h9KGMX_jW(iUNDWu?^$9z2B;>kkxG3;bK)`nDEERu^@zsBKbit*?8% zty}87t(>>t=j&{O0j9U&9Of%fx{}ppA;mRK_EH?u9L+S8VMu=G*c&i!qOn(ue-A7y z`IxI!@|Km)Ld4JI1(UhF!Z58>^}V4klgQT|@;VJGm3I7Y4Kd-iwEsCdMRBQq(O1UV z;<&uOhNgTP)a+L$Z>q{RtKh|DDU+0~sQDA|NE$%@^LXqS?0noD?zh%{3#Mf{RlZrE z^C`phJdZ429ycqeSn=1&@Vg^EyT%?w<}jAit4Z zst;U~+T!m4`eS9~`|r^q(jzN_2OjUeM*5|kL#6+JF3I9oK?-6{dn-MSC0Vw1bt}aq zQUS_SE=E@?)%^Qy?K;YH_)mXI+rY-SterJp`nX3smitW=rWUtO!w90oWkdvq@TrTg zDkxPrqhs?phfyA8hG7=U)svP*CZE##ZCplP_;X2WwZbq7twSTvHg4Ub^B2aJ|AWqFfuc2c; z7J4mrWc8QeDbDm$zFa;W*H-~obs5YuU6uS>5N14P7IViVK!M(-J-rBC*r@P=e$)~^ zg*?K&SrJ#G)C(kP$G)EiZ{8qTD>i=XjDcBpWmr`>IB#AsCwpp;J_3UW)GiA`-!TvJ zoHu*ZXq%_d(!7P0quiQmopK9R@?;)z+QKWsr8+&s@_p%X&N<1I)Xu|KFRcXy+5Oa% zRmv%~ekivpWw%*DnmrB+F3?hx!%AC|QxODvmMH$|Pk4#cDPwBQ_65aUV*LFiJ+5GEBwiRwz+ z%|rW%yOcf|jl0lkaE{5c&VEE8(p z7pmaJYqPwKE3tlk9cz8jUQxT%mDad;?c@aaV(H*bOMUYLp!v){jH+f?s)Lyp^Z3|9 zDEK~qD$L6UgO&Qqisu}>CMb!G=Rqc~DPBH@D92@Z-yI4g_dK{C!eJHpAYa7_SeHB* zx%w@?xK|OU*=D|m#H*NxX8pH3UuYJwNMXCxrP<0Jy{cSFSd{T7T3xak&FYhn#b*m) zl=H2a$0e;T2kZN{=6?bH3cSF#O9-wv%?cDgHY36nW8ND3uDyL*hFtK};MK|d9|jM? zu$;gAteKYPIZb}$_i=B4zE|qse;<1q@?HlECzMKt#ObxN|j3Zd98PsR>@O?oSN)U2-C%3_uBTaW9i8h^@^zpg`FfF2j70jobynrVsB zGdZ%fJ457rSJHUs?_$j2&$%j(@K_{o-EM#jtPK)KsVfm19Mr|6mI0ob_k7ki9 zWagk^C#tt&CWEQHF)&;G|%Ca#|sxyx}5^h?+Bp%G<#m)GUg;E|emVf@aJoFi^ z{)~neMJu!hJx<~ailU{P%Fihm*LGz-!jma$$KOWXx&`@(bJ+b zLe5YS;1is&-czEkR+iA~bfqf_-YVs;*#r<1d3BhAa$D%9r{)#RmB3e4 z^#3dcZ@%W&jD7R5ii_svMPO5$%PduQX;w7{ePO=5cw_Yzv8Kgt;o=MSK&y3?Uv0dc zcP1;9Kv@`1v{P2vL%s)F;jGo~!rb?f7O!TARZ6Pbq* z%=(aI&?Xr!w}xVQfM<149*P$A6MA16{|5!?7J?pg#%pH`%yH*qZN=s57kzmQMCGk~ zDd)}Q%)@|h?Bf86(iiJ3&4PSxFIi4)Bk9)B@?e^b)=)dEl36!MVKjmpoo62I!+uxY9R{+)@>{ z7R9<5=M;4QUkg&(bUb~k+JevfAQ!I3F#0$4HwgD!%cUH0Zur;cZFP2q_TBp)u=i!xe7rB%@6>H4m?+o2)UlpM_4o!4~pt&@3EwnhF@?|q9*1ED_t`PRJ#q=yL2g&MH zN--{*mCyH$a$hO)-0LaAOXB8f`Cw=-UW4=Eb-T1Bc=)fVuEsM<_mD>5EN3P&I#Za8 z(D@u$-eRa}{1z_RT*S5FV*5%Ro64T!GApZBR(Rt3kK&UEciF0zH>Nn#`qiPbo%q%) z>-?Cu479ntE8dR?SzK8v%g=M|Z7oy{f4RKi&~!Wunxu>Wb1;zHB5htqaiMSl zhLsmA3rD<9$E~Rh%a5U|TvpJxu?#clb2tmHLb{$kZn?aa5&cbr=3_)%;e6c=`S$uq z7jGR#8m{QcF@^6a!%pL;e2|WT7*=d(^?Bvl`_wPaV1OL zGp}m)e0L~Mmr7>2;TUiK;Q7;V<);ktJ4TI%Ig0Z*WVvn$m3h+?2dnZL)cDSld=9A8 z<;HPaZJF1_Rb zzXykoG{Wn4pj>Mhjn+dFNzACJ3gsz;A4N^HV*Ih*_J&obybW5mkd_&rWla@N=)5%< z&BI>?US-~96}8-!r#5c72Quam)>b8i99Q$OEUdA?%JKV@HUO$%l)2)R7WWzFVZ|8S zQj@qM4^Y0uL!Q01tZY6#i>(UH(FqNC>B&R7)<~46^7a{J0Yl0(9jZYSr@W5D-(h+w zUz6v!xFvi)A{G0VmekRAg;`#*|(RWnA#W_2!ydA^)uB%G>3 zS?q08W;t#RJ#@P!OE*}xuEt@FmH0yE@W1L}P~O(b zVyi;3=3123f9Zs6;3;e$T45gcEpZFyjrV2)IfF!>`!sVVZUzD>GvtJZtd8Y)lF

pNxUwh;(8K9v6#EQan#(TNoryk9`x8Nv)kcG}zfZGv8`isarx-vfx-- zU0Eq!*ypux4}A8=Twb{AY4IBKIVD3m_@X-29)c^%+Sc!Kd8)8gx%iWXf;X}&#B<+q zldm_+bxWwKmYn^Ql}e#*E7vMbo=`If&U)$N zr^s6T`H86f*(sg*TB+wwL)mi}=I=wxhp8=-+ccCrxt&XYkvrqW`6`{@wsTYU738m3 zX9v$f`=0RaSPd(G`kwP@E&dDc1MRsKC4SZ`cjH^`95#5aw^}uw`%iCNd+UGXZx|vyJb0C2T-e>%2Ay$PYFpDiZN-+74l^zvXJkxDne7w%f~DOtuk*jt1k$`23T;WMboWAbQZwUURa_Y6Vh1bi%H`gLx%=^e zI(Lra7y8Zs$C6=RdjgKvEutb18LC@f#y_H-hrXLz&1Sp_Sr|6-SZ*jrW|j zCAGy#QfvjNDDS(7*R8C_s*G~@ubr>uX?`#JTk#T`Jjpo^wFs%0b8ZidcBi%SH7^G* zkA>G;tPf4(8UTDh?fx8U{&Xi8D)*AD6j~%t*9-3HSMR3(@$HgTZriF>P)_Xy%St7C z+ZQSA5c8!SPStL*yKuj@UZEXmG49%jBQ2in)o0B*(k&r6;cTaz3pc*Tv4vYg-hW4k z)mGw3T*pdFC#h9OGLlkjZDqjObOsyxR{8X?xcEJ(^v2hGyTn>gDfEkvJA+d0DYo|! zACkD1(2);kv2!825+%EVh4I=g22uBxzcPJ{xLmYT6)XLdjPu|BiP3(AdwThkPV(<6 zXaK8!&$y1JE}Y7Cn_>`s|EE?U2nE_=DmbZ4nlyy*IgTyVS$n~|aqLs3yjcY?m4EF% z_En(y-H;Bciof&nkC#?5lH4gFO7dYi_9qM$;#v?=iD$7@6DnSSo%&I(r+oi55BX1= z#g{Cg;}cAq)(W-3HMQ|)@$$CsSYF2QmhI!zIj-bXjPCsLTXV7z-b1pq^7lN*T0{HS z)y8+*4;iHDdn+8Otct+y+EA#~`ZQ1_XL+cuRr34%%4-hg=jD7|$w{`%q7Xd!dXk>H z9K3wF3_>B))Kd)AHEr!ivoYvSA%2|9L2el-kkO8%8=ob<^8C&l4{L7J@;( zLe8f765?5m*0PE#E@dhgsw2kCIg;PuSBAa}wB_~f&UN#+Ww~-?mxANm&*0n{DnOS1HdiY)p2@>|Xt=gg@{ts4k|aFEQ%pakmb66+ zH5N;F9>oa{-vt<#(>v9OlQ;ghGFfR0;WwzrX_&lruLkg5Kd@OivD`GTI+yi#=F7=~ zH24PTy`hEk=Aj-5Hlt<+9Xj>-AZT8;42$P?ewHvl{w`5N&JXQy^1WwqINtIoeCz7Oeb@hF9Scj!IXa0jZq5SnQM^J7E;zU^?_?yaOi2)B0%L0AX>AL zM+#ppu8+?@mq$S1l{D;LT>p;q)jeMr)|thv;3!DS<@3t#;qm@me0uv=wk!Nu@REYESr1@1P&Bd#4QAu5z}5ZF(s1bUPwzcX)1)1SE6eyA|td&%q!Vv;tZb=h26h zq%=As#x2idJo6Q?#93^n(dVpV(zDb%LnTPLa?8LlC^<=y)NsF~-CZgls{4XH7qNj- zdEz$SyhR;+_%5y--qf8^yf_VhU#oj)a~{MM4=WX~dd_RP5~s)`H&-goXQf(&mDmTk zIa$M!-%x(SMam|5Rf|fP?xC!t9^T4tjQ>|}8iQIS!Mr6Y2lPfwc{Y)A@9k+y#-*xI zysBIaSs+H$QrcDu86)R->iw_+F1lWpy?kzI>Rf4)nk+pHX;({HDh_Sits`E-*3T=j zxecDiv-m_q26tg>R64`P?JLb!a=6%t9FO}NwLMjQUwo|AxbOS?vvD6eiD6l73tK6o zEyXYgp%m9FLxoaK3)#5uw(KHML}j5qprGNix_IXOhCF|?&6w>IGu~2fw)$PhBCG$F z&?2Vnxk?1*qH%q^gNIL17XEjOQfd$}ch zy!x!o$FklF$FrWChKypgsCG|?PRe01w2J*cLYrBeXRRhJ9CJ%$Q|-+Ab>n!a5UUS4 zT90kh#3F36+Nbu`N-la(R; z(T_fAuqg9EeQJPyIMQ5$vqyU$Jl9CHuKJW9f=xl+BpPEO9Iao5Z!_N4 zTl0K!9!XLbhq)k+TrcFf8ShnkXtOcKRIgjK-W`f_x*p5rh0msX+P-uL~V&}9629kR7#ZY8vdk~{~B^C`)h_n`T`5mjwfcsqL2 zq%_yMJ~A9>l}=+bTm~ojsTzcjb{RNVnSjtDQXM|$sjC-YDazO9ACrYt>zO8uef3pZ z5nSVaFLlkZtejy-n4KK*uckR9hgC32aoKxbV;Jt~DdiHZN@#|Wr+WHpUvsM}Z+YK2 zB*Qd@8dIS1MNZsWtL4imjxk@B`iz??b5YfZ*G0=4E>>qw(rlm4EqL2o6|FWqo9S8`O)d*$S-kV-Bi~AjmVqFBp_9C#S7qg! zQF%RkC~Kv=Ly1HR%Dr)eEVc!qXaCHTs*JHOO?f>p=KKL)MD>PQyMItVUpDb z#DRE?1eMBF;g#C3mN)L9z+j(T;&)9jyt~&?KG$c&QS})^IS~$pN~t|JQEF3;K>q@ zK0;>QE=#bxT{_CVXqr?cILfQzWwV*mzlY3LVI?`vxa?SU&F{2FPb&Bd5}RfP`hE15 z?yej=MNRz4hqT8<`+o#Mttg8>S?iJnE)MG>#{ZT0B)Z|p7|z^s@p|()j|73)U^j!r zj+ul@PLIBqqb#vM#oKqenWOlbuRYJ#d0u}2f6Rt~AO4mKqseA(x7kNvGhc5WLtvTh zndEX_OWvwWCi$||IH$kA6X_LCT;_5zn@Mj)$YA}%)*i?8jiipaik#JP87_B+3{xzL zhhC3aHZeVB(=Ai0)s(XdB|p|n7RK78P&7NY1VR7vt#da$MJX1P<;ve8f4Nz1zWyWN z^J(oNF!rkh#pi5r+&v$2#RiVg3ds z^eQ+eUyV3cNKMOB!67b7H#p70GaS36cVdlZIkQmQKVuI;@Xl-tp7bHtg7Rwc42F&D zOU@)>9FjWi*J{s)UQ2@cxaLXqiB|E{OP0dbE$)~~-@zohmxW_>&f9@a$J4$I<0NGH zWB;7J?+OoHj>FfMPwStHb3MzMy{AWY$~sBv#sbLkE-P_YNWDBuk1?~iZP?pQ3#nPY zicleEhEo|wtm*_u>V2E{z9w(((n$cMYw?liLr)OQk8Vxz5=!Dv7BXz&7CrL*ob533 z60H3(9xsk{F6Xt^SKN`KIBqZyH(Ig(HFhs7V|tZTr`wMu%pppvfy%bTiILvTk-pvYN5*Icmx0C^A>jmt3np5;tDy-@_FPC3waW_U`(oi z(omXHG9hR>T@d@0c$R&Z6Zr256>^s8E50the)k*&=VYpn6Z02b-S*>-AmOXvPd}%M=gV0X0$NpV=9)6X4 zkGVEFWHFRDWbsvT`J74VEZ>pJiQiRklf7fd0$k*iU-^hn595>E5to$ixGMa<5O++t z74lTNZJDy~haG!FVyM(4?I|ojq$Xb_5k0PjgEt0kag23qLpgWT_)|@ZzhiTUaa{VT zm`Acv^duD1o$L9yd{`E({#VD9ah!+cG4rie1$8B^saV%tbVo+7^sp#rhHpGloeJ4_ zL}*zo6C0G@jIuxoTC)RkfVX zw4p| z?;MP2aB9j{hQ(4>@?pG}cGo*imzu?RYsOGAc%@J?c6WkWL98?%~8y^CGbzICdN`L&0TuHi*LCY z2wqiB^m-~Jl(JcDSq|;FkR!=k)({4toJS@R8u2trB)Po~jT%`TbMKW8?~RLNnx`+t zr$Cd#x-!h$rZvi=bzvT&QHb*K=kAc^A?knckX7C6F25n4#mg_&59gpBDW)(7@t(O% z%_Yhtxyk$)=t&LU6Qy02?nmY+@p7L)H?5TLE%Jo^(N#?O=GZ22$YfR7s<^qFCex*y z;?z#%Y(yBm*8H1a|0q;$ ztD4)WhC6s-wdZljhh>LV<2X;va&)VFneM0Th}h%5H1u*9>ntw!Gg|v12OlyoF_|}6 zl6Ea&w>WLe`P!r~PhC=8H2W-_^#-v0DbdDD)CYv7dF&7_N1;3EE_<+dIbL9N>}U4F}yD~;1E+6|+5hko_ZDic~*dc0WEo7AUM zj28x0B8axpu_n9e4l>eMMXj5sv;@z}-5Qt9&6o4c%wc_NEpg7Yo~3Z z)6m2PURuo+Jgne_^k9}VIp-mGnmK8wi0c@q(rc-!J#wY8@(~u9^97cIaR(a^#*gG)h#>qFeeG_tGVs` z2W@C2-bsdocRTtn@6)0!V$FOTmQI0Ee@XdlkCpjt5^d@|q{NY1X`iFxww%7ZTYSoP zljU*9OHz@WRS+!)S~+*SfyuFAmVoq8lA{)F-omGhf+KRx>)?c@uBG~SdQTJ*^7Mt? zBj7!151H|mmkjD{p%sIda6oTtw0Cr*J?m4RxY16xHxH0Yc^T!qD|(2ulk1_q<4WzM zeO$>(iJtTO3}}V;Qx!^fJ9(-2E(^-XWBL-1G-_1UP#u@W(iY{NBJg<*mgM0U_`q^s zl6GU{))WmgGV}&brco%l&&S`OBZ%3S;JzB-sb)?v0rL zxAisWbS~AY8wXKQw65ys^I?0~3=j1&t#o;9d}FawM-Im{ z#l{NT6Om6fN&FCrdVmbB@VQMI)O+>cd1P38U~e=C(sO0WX?k2%!}~%N=~cc3Y-LfE z?A+6xxz1rfL#>u`%A(qTAgoUXVv(S;Gn|)?o`^{>2p?*;4$pdsqmR=Pq^?H*`@uOOTGaPcEyfmw%I7{5N zaaf^-#j2)(=`rxMPadCAk4;N>PUHVvJ)~J&5#Kyif75%C&tSQIpTZ)ybXod*X9&#~ z=gllR$|gOHvWvm-`m%CA#`?oz%&J-#($cv5+ywp#YjNhIu}6D@zuB0};U07T{XA&4P~V8HjMXnAYt;+&>T-8@Y(6$|6;y)B(9sZQ(b(4k+W zW8qqj_N*K*K1A{j_k26WG&yJI+B3`Pvx52OEJmT`9E1%1H%PlyMkPl{tj|{pCqmM+ zELU|Xi=D@}m!p*Ref5Fq`Ps(gr=BnuUQ=K8L}K$Il4VDJS~g z#yvHypSTP{Rp?DR`}6ZWg0gt&1$hF@;{JBy$IlHEpfs@>&n3Gju z^$uHCC+I|%IFk3gxPD4&AXmcMs?fZ46u&BQt%URuJet==&4uc1I*&4HoZm-2N2%|L zYxDirxR8~}Le|r>8x|VB? z?n-74s`xza0F4#oG5>1}q7Um{s9V|Amp7-!{xm(2Mj-R0G|Bu_=jRCY5dUP|Ag zu{F!wqyN2r%P6MZCdBO#r#%baBA>io=>6m{?Tx}Ozm_-&$s6w{&y`=AVym@?f$(r# zlF$+@lCzKJ|Eg?)FH#rpb}c0X$Tt)$oG z)A7wiGC47Dyh4xP9j4 z_0EBOPKO6{*UkkfNgB}9fAv3~E?r)ZGfq{(uZ}Cms_oF%eEUZs#Wf9TKDJ5hN-1Yj zM)KxXtIGyl;-eF(-b=LCWwCvRM^ z&H#)P4EBPCpL)>_qc`kn&_{cXUSoAjF3{WHVBb}B&c)rCQ~XP?Y8G-P)>o36<&(6Q zcSv0u|7cOt5~^hp%Pv++KeHBL&!ko!wLVg)E2*QI;*zV4oL2_jPaHo?;mekBZp_hq z3!J2${Oti=HpQQs9>`;%KH~2=1D48xvBv(gJ)nH*8DN=w-Z_m4rOBR(BwcUdl(xy0 z@b-+$XYo~`k00wBbM-6(Gk9Bk!=C8ZTn-*AY+LvnMYe6OgDjYbsKtyY=Fk#w7Oaz# zE7du#yv}4**iK`VxNb9)Qk<8PtV_?>I&PMOSbc2gA+edv-5Dz6%=-+~L+!bcL$Geu zJmgGz?+ZqY{M;!ISy)#0!%D0R^&e4Iv}ZIahQ40N_5V@#Hb0JJ$$@9iDnnQ`3g|ve z9Hf)5Ko_t&3E1l%;!rUMog#&F2HXcB))dCMpx-H;3KSL?V4;(CF;0LyX%-+c&D!OsRMU2wstmAm+ zX7c%2sbl$L=u}R7NpgPDzfWX~e&~~`T!SBM7th{Z{+POgGr4<<8h%&K*rLy9da_aI2!p+F?hhmQT-(KG@K9~ryt{f z|2gl`nC>~a;PZ7@j|;+Y`PUDU>$}%TfjeB?7x@E}4SWge%zMQB)1k=Ox6nyWH^KaAoeV1yXYyp!M=J!%6-_-X?NMr(v$Uh)P1LI$=lql>49~uI0W|0 zmPq|El&AFk+I`~4MeZ>i;QbglN6LRFWO{lKhVLI!4`rgC#yk$1KfmlE@_rh-JYnNF z{8Bz=F;_9iNJ;!u`=6FKoSN)D#^Rg<4Xv2=!3A(nYkfz~H&NHm!lU`FxTQzjq_y$_ zb{8+i$(@{eiNRNW59*&W9BUC`a*FAvDSDh!9qlaZw2X0I{V*2BzDZ>Qa-MGN12U+0KBP{8RC>wclG$ep+Q zgnS*nme{ZI=XhWE6R8e}$GCt!ocZfds|*r*%=J>}fwGTc*z+ycZKEE&L*Qq>cnRW5 zCwZdWuN?_~hDHyFq0##tbxF-fp!M|!uTlbEha6gez>U(M4xN_!e@*T#!2G426jE}e z>eHbobiE|Y(jPF>Ymm=TzKWUg8GTKE#E+p_UcIKor}xCag!N~&hg^ByazWQ2<~{lO zS+J!1IV@vezreT1`6RxFAe@AC3`NfG)W0>&8jaAD}dBJE?vsebe0(#V!AM z>BN1gH)=80#Y5-`x5$~c&C7RgMY(6tp1?Tb@mV>0nCRzgtd`iH(1%~b{P$AV5yOv$ zUZyl+dERi`QG<0J-ysFAFgwOb1N%Vwk@%-+-Q>tS*e}ivv7zG)hdvP^jl4NNKbEf- zOFf{HxAtL^Toc|bAM>zql5zOp@&E4f;<;b;(8nEN$lstd?}|edpVlBYNA&)2PTdxpKS$9aJ>C1ZHj*Em{%NTPxXMXyvpxzvtLaC=d{+LY+9M7OKE{L8T@SeS z8qMFw-uW@SVw{VdLwRa@u~)o=+3z`LFGYP#!<=E5tv#MI1eVUNy!&lf?|BKwm*c*} zqRvu}_tm)z=j9S7{CQ}#AD8zLgp(edEybsC7oQFDxjp<9<@@JOjKz_DdYpR>GjihN zeM;r?u`aDyS3^HFXMIU}J{$jm(*q~6eWB_RhJEUj*k=?R%RI^1^YobBhv3bR#`L?R zjW|$#s`H-51uo1l2V3~#bH4$Qm%>!W}uQ4E+nAw(sB%`WSXEjT0Zs`@FVi zIWH3XM>*|PQ1pb(CwQNxo`!o!aQ6{R>*;$XR=U4(hr zag^(CVSC;C%cJLnkA<|8vWdrIcthOBI52zc$?CBVT+^@r2-|@6$r^`}p?^;3d|L83 zosQ6fHRF)ZGBtj_X)G-5jLQ^XMIwdPt-kf?s;7oPwIb+m2;;olcC;vNNe<8 z2Y0ajPOEk14Bb8J;c#a9eq2hN>mvX8$J;nipygAOC#^>!I^5dA7&>zZD3;aL7 zb};?uOi`Mi(lyBOkydhif>!e%^Zp+Bl3wfBxBRUBLEfI>|LAEFXOHlD$oo6>$*B2> z^bb6I-cR7%z~f^`9zBb7#2UxDR~z638^&y3EV$uPVhK6@uFqMiUM!%Gm$rHp~v_h zF+YaL@!3>R>a+8{ob#Y9b@r|EKXy4DvG{c8^K*8uK6LNnb>FR4tCIg!(fZkSt6jZW zt*UC(`aLR%S+xa8Wf^&jRd>Hy^?8V`M(^Lx=eyM&FzsqS-wS5FB1Ach5n5BeB<}tD z?mnQjWuMq}yVa&%ud2~%wQ1L@QDuGLV$rr0DKXd;m(h1yqZFfqW-$ZK4N41k^Ky9f`kBAt9@4LFf%&Imk;HLfa+Kc@CMrKU7C zswAE7a^0T9t;MwaCurZ27bdQ^Ev?b+>Kdp8Klkf(wU_sMpk<4!T7ORp;%KkcI@+SM zvemu-MlqUqS!2<_!&L_ce8oR)&9A*>i#3_vzrVL6JTLhGLVJHNGmr$ZuBwof71_(E z`y|yoL8q-sIq0-f8jKK)#*0v8i|~pT=?s;-V!z%M>v{a@F`kOml4_Khz>#dLRb$1r z(2#cm5j%fT)wo52g6t2s}4-mYvbp%hSt;DsDGi1&{pO3!9;cS+% zvIvz_THdmRflr-14bnvG$?Ia*mZZwXvY=nAcdI2Wfeg1WFVae+yDaB(vPDw_ZYg&g zF*5oTqd9%XSGl?>tR-8(T8tBtAzp3t9RLIdCCHeT0v&Xbg+6WnATcVk>>%;R`I43_ zCo1##RBxU8aTnl$B*4Lllo= zEp7Jaoj6!aDU6y=bie|QpvItujZhYOsgu+qa>00%hqzE*whkd;%c9+_=nZAa9T7Y6 zD{4z^`Pslc>ZFClciF5~(}GN}0DQ^A3%R94<1d8ts*o zM@QJpc4}%synip|4JCFv%ZVek^C896J~Ye3_|jP7rOmRwQeN8DMsMjo85{9CA|hMS zrY&~u==h3H<{Du|;ce@=QhdYPV{ z6Ppsd;z^tq0XVU%@*uwFQQt!yq%hyh^oM$$&voOh%v1cd;FHQA=8QyBL>2__qQV&QoUu6+5^v>n_uzCEfdk#%9K1u0s*6o(7L=GRhPxS zA5~Ki?7zTE^>?rSdo5l#-SglvpN>=>Lw~@WV48bYPidAZt15eDDFdJx;u*HK<*wNB z%a=6oi;D91AsM~DLau2=_=EXK8QXLHu`K^^-~CwMe%zm|5j>m?X4{>#8}a&B^n1{QAKD&&b>Ml@*4Cw7 zc*sM@dIE?;g8OnfqPt~JUzQ{iqmQMNYhK9&&(Np z*i~9RUi3Ie8GCM7`b9^J@o&QjzgtbTF@r~{rAE)j#hmvC*z2V&%WQj4PA91rH-mo zXAG+ewh<#~X_(O#`W%G`Zeg2!ueSnvZmBz8!!z{fah%Q2X7|7?tOhLyO2;71ECK_! z<24@N-_Pfp&2G0TR-3M?H=9jaR@J6%>rv&baZ_*Vq8wG2hQ+8HmGgPQz+P`!>@(u( zYE)onWGTu6fZ`L6EJRpct_O;KTwMJ_Up0KFMiq>b%<`585~HpbN34`bL8st6(Ih78khGB!#?I$fxb%RtrLMJr$@g57@G>~_2L5}vQt^uoQ;JgU|^ zNRj7TTYM+)nPn2QqX#0jj94(XsARzeDn?LbYb>Shu!Z7vwYJ*QHrep2Zxgw;2?jRr zyUl-Sw?$L$i^*2j?%`O)rwmgfwjDg0z|0M}?CWK_pKP|13EgnAoOFklc(L=<&G&TV z{RB|FqHRQCA1y)xr~!ml2Wr$%fhqtp3i%`v<;J&^*cm{K5CbxF?XtCvVzx-M_)!%h z8*bW%>;O~Cn2pv3r%BO_5W0FYxd)0;N-P97=rJ+1)gZwZvZZY+!qJjJS+uW-BXtsb z1r4~Jj3%ht(RMSWR>+3Xe9=!QHMy3Xk!oeK-3DCLXH_od-;A!J-pRxfF-z2w2!Z1$ zLlY6sRCLsYCbQM#TnlUNAY&O^klqbUlMC{pH?zq(l3_I8TQUh`3e=q(^(!QcEKA;*E%l9!VUMDKSlYqtSmI>G_Co|FY7-eI z^y-e5q>9WL8u6=(>a%Z##!?cJZe>z@q;d@;tF)FW`%tH(z#%iJ08%TBh)&2zJ|Wqq zOxW|7QOGOdO-M{8DNA;wJN_rdUU+;3@+H|tKq&IIB_tO^5R+oTn?cQ!Qi&!9K;k?F zG7#-acD!!Bols!tDFFvHK>UQb?F2Mzb0JG(%KHjtsP;t6mXZe+B8SYdWiv{q$b5By z6xhFPJGdak&^QsTpsVSH(N~THTIjd z6y^&It;yHK43-EU(l2|9R~uZpY|;WWS!xN04JbLy6IhlbTK92chQ>e;5zH zj&bgqL}PzAg-nfCT^I#zyKmaIsc_TwI1KSqER_bGo#oKoSa9p*r2fbHilKZ`XFk-- z`p?RrFj|UdRc))E@DAU@6}p5%n<~u_r9L7PfmdY`7(8eLEI0SBnZf^;<%}?64`m@6U`Wk*U z>P9TCVhg5P!IN!WqxF8W{;TRwsy{g#VgQ6Ja$$QSBMd2ZF+n?;#)?C)b8|F#f2Viv zENBq>1zuTyF?CzjH7$vC1*LydK*trMCG)R)KUd7ZAmwhX;Z=+~Kc&Fqu;ZKfb=F<; zeI*27goP&EiwM0%1j4GDdvbuXvxMZ8E5#ZA{=Dp1(}I^}aJd}4S(UL;1%7y9c@?Ak z1&P6F$MW<}tX4n2GHsma4EwW@!PfJ`?bR7?;9rVNc)Q-;0ksvPR9aUDPvizekCt&; z9Hc9K(#2WZ{=@33Uf}O6f+MTd-8gN|!>zQwDQ=KYY)@}d$oG|%Ng4Ayi&%~zp>;|5+*q_#Cwj>y}d|nRi)E0kAdq&DzYAMBd z{I0maj8-TP=Vxb#oGzKZ=b*Lc9hScOshLbwX6P_SgB)iZX;kiKpFc0e@K2wm2>l-i2^N=-Ud{bN@6=cqQXthH^=&6sd1AUo(O|JNUi2JiX z&e;HuZ)QYchFovA+Br;RLGo~qGAq$y7@uhyjiyzV5<=hqhvMs{x~zrW;C?v#37U=< zc~K5wZ#j-Adc2T6_1TsEMm?45FCi_&Ts`Dty{hB1Pv3E*npb|(p=HdB|AT@2M1`rj z(9TtLb6vcl{4I%6TUDvc;PG}lfi8HwO)Vv&RTZ`zR<*V`Gwd3Bc*Iw+-7rQ*ZRKO# zoYsH&{zI=NS~Lc)Ge%dx?a^rC&QEo7fq!L$+@I4)Gu9mRC34<@w|Lq!GNcA5BCZ(Q zsSC7Q*f`o@+DHn0nEx@tZxB5u@x-@@G#llOg&8vWPo_!WpLl60%8?A)&|| zvWFn~kCfJo(uAWoXiwx!&Q7MeqcJ89n)F&1m?k1-57;4(r^ZrA@&W+bl+-ulXJ4DP zfz=ItVluggW^Goxj7fAHNA&pRw*`7F-NI4yr@Bo|_I2n|_|1xOauuC~hVmt!7u~@- z6wZosdI{f1`Q@SbH@L>qeTi_{Ffk6Kq_(VnT6TakLR#kwK=FFT*TV|bYH(zI)@5q% zZx3is5GSfcjCcSd4nGE#JF>H*L{0?UV!QO_*?5aGOB-4oI-{YAgTn@Nk(;__GxGvZ;>pqB$3Q2Rcoi$`JifD5 z5wH{^1uPG)$v3zy%+gr%nbYrcL zcFi!QH$&y6rBR~W3^|~0`0X(7*soWvBC>RZ2N#mnp-u6dF?*K?mF>Rl#`~sPt1g!l zJwKFIC8`irz)m;SnOh*|WLwC%LafeA8as*1wD=XUL}ELw*4^Lin|-5|vz`XjH5JFC z4LD8`8wzT*tbr!R+A8636BjGjosjchr`(?@a5D+CM-3blJ8OlN;vv|78^Zt{3|Dp zfH|1rr;yh;RDvg6*G%>eegFnIY&m@6z}@ZFBT-yUx7~b=N3Fr5pW_+O0wZ68=`Gso64;Ef6|^7B2s6jXlgua z_(Q5iQ%wC;YoubT$Vvt2g0;C9ROs5Pt$ zRG1OdhQ$W73>(lWvf49-d@1FQ<&%2auzG;;+myKO$+fH2(`~(<4pzZP4+Qo|mKb6O zyB&`7_JbL^MNfOmvJGxOkYUju_>_tAW%R4@ZX2dl-AqFYSfpmkJDoDGaF$^&IVmPj zbzY^12CWZN;Tp=U7NTBZ;rS&IZnXSb@3(Szy={SPp-B|f?;Sp|?x3}e?!w_up@Sa! z4fPGOp4%Wc~LX~xU3b~a=1X!|}dB63Mbm@KUc$=+;l#Fp?R_|Fb3tb+Z>w!z1* zVsJC0oMRY+7MszYQ)S8Qhoj&^HPr-__Mt7W1WIHH+F0T6$i&1?wEE#4Zi;1{DHB+3I+=DYzNdZK!% zPF1RY=BxtRu2kPZ!-z;snEqf`|(+X9KF8KGPPFKzL?rzMewHa-(6|?tF z9_GIj@=sU0O|u;_7WApZTpSN#^!YyeKKzfxhM%n5&gUfSJfGa(2R<9;5y*LW&C59q zW)!QTg!r7`Neru%u)nE`82pV`GwD@h84}IYuKKxJ%WwTpW%2Xymyk*lV(l+2Xn)p) z8jh{CvCcS|^3575{MC-}{Saa-Xw+*ifgv2|^J^!xIi>x#V1U2L`AOL2*h;jyUc9jS zog0ssf8hM;eJQ<9C~SS^$sHCHbB*+;JV3oVbP=`|Z27S0S@q0WDIOVsoy<_#DN)7@ z3F_PdK>fbXm`~Mp>Ty(`?Lb{Z20TxdL6LQ*?S!o7Lo z+1aIDD0TwmFA?KxlbAXK1hWFaHI^5m|DD@ch|Ek<|WK5E}dS%yjwp( z!a3c|Idl8QdR0HAz;HyG-j z)W`L8crC=*|KuWF??13=z0&7pEFL^Q@9&D)m99q6JS55wp>vql$H~51cmGDKQx4hF zBLFj*{k1_oGQciLpcl296Ov=|hgsgcyQBs?SWgx9x^{GW*PO}ln~?=d7HxaxgqB$| z`*)E#f~!kt(-Y%Nn%bbFpY76&c<#D!a_a27_qmF&YXU5syPpYPUU7*9PrKan)A^}9 z1Cw*17eD8Jbd)vff(|{9LRY#;qt5hI-`|a6_6-o`;T{4z9K;=x>TBksx3id^YPmy{ zW568ifnLoZ&awrA9;#~4{`xc=pd1^t0kGZsbq!h@?h>WWG($hsMkrkwy_e#e-S2ut zuzd8^jlLv^bcAkojKLbFP({s}U5*hBgT|#%#mKy*mb5p+L=0sd#s{&cy2#h!iN$4t z1CXv9+{N92IHIYnoEjhWvb*PN+NQ}_f3aJWA5eLk$oSa!XGnTc5E;oM7@os&1h0x zp#*d!zP&^i!Q&FSppNV}z`g1(rtSST3W|_(sSk}pZzCT0XP)#P zzs?n_18A{cFF`Syseq@9F^Gv)jvi+v%=K4AN9!iz9M74`55Eh0C+z(qHrp06G58XO8^T z(Xpn2-|zgY?RCiloi=)#?e7q&4q|OXH(U7Ga&1Yyig3PV46_kKuF`4qw$NMWN`(qK z_PC+Bc$I3lV@uaX-_rIYTbg?Eb%$Q2aC#Ka^uIs_l$=C{enTENbuT@L2(RMJy>+$d zWO^n#GUQ5&#Qryo&!Iuj?z{0JWH5UK^&OC#;_5&(SC^qL!`~cvW+)f>iaVgx!#}TA z?HhFdRe{!zI;C@EWLQaby9>X_ zsx%TF@r&|!sC@O12vOGYfd8?h03L#oTASSF%(6nVltPOCQCsQw8S4TR7QXxt1p+ zhh!C1(l|ihL{6;;@*qPB;2u{-K)dHS{3@kc;Ov$SaaqzE@|4cus`VC zur`7Vs5EfWaA@Qg90L-(QS(a;?|Em-%R~Mh8y+AM%36|UaWJHF3V7CsLF3E0Q2&ZD zF(1^XA~Ne6IL$mV>Z@%ZY%OTz&e3i@%T-I-4$%^NopO=&XX%ET4KZg9+{IL!d=Ho! z%62km=G)G?Ucn^I`fn^L-zq{0!IF-NwqZgRwmBWMp4O4P*mqyt(hFG={43T8ZHqE; z8q&M-sFW+FYhW~g?Ut0FNA@n|HYfz5-Ewc&oImaKx ztUvl4+#33IuZ{T4@zzCH#MnhOvph!^ZF65meKYLs0>gRtpN#}tPgDfGA#aWk3?sC| z3i|1pG5a{&g{BU*Jr0W{Kl^f8$YMOuu3O4*av3VVK!5%DtN-oTBf%gz?)Ne0Y3rv< znoE~OLOSLgaQ54JOdrAt)ArOM*F?HdNWX<1M>W!n$u#>#hLi(iO_hSCdxg9+)_E|% z5z|?k=V4cWDp$#8ez00}na)`rPp2g1Q71FimQf!s3@OCO(ctAZSj5dSaslj0>$H0PRPtsQCJXlXG` z9$Lz_%=Swo@?L(fMiBZ_a?B%+w{{47Yvd16q?XsF~an*4umQ}rKNqu;_2N;CL zzgkcBOX7hu?wWOjo3;u59hfQN_}MM_(=$BTPp0dJI>pTXEDxe@jk_&Qc5Ne zcRX%3>(!=OH+Zo)%F&iP0-%Zg3X$BkloM{*lN7(o;F5xP6f+bwru->EmD-rapO%pJaYG>$%)C*{d z?$sSQvgy8AEtjM5->jPTcDr|$G49&!v_W{yzeYYe#Zd3yQf^&zaIu^}*Zm&bk^#(c^C0Lzw(*pS>yAl4Wapxlks8tS5`yGrr>!~@% zDDhLHcaHgBO_-Tk@z)Rd#+fxovA{=2)+bkDH2Arb+aA;V?sj}xh}rdlc9AHj!RA+^ zu5LThgplo-p(fHJ?0BCiQpq_3@2qKPfv7X$hM9n+GWCH6q&E*Ws3Gjxnaa3611>Y- zQ<)Y9c}QW?Rm=m-pAx0iB@V(g*0Fw&oUA!(Xu9vPqTpd0b5`fKjJ2=^53ZjHh4yD; z=Y^MvdQWU9e$nn_jID&r_&tM*&UkNbozh}EDar$-gLR{B7~)uAfx|A$AjR*y^xtOt z+P2zt&aqpJJ*dr6P^!e8X%oN+@rsn_ZD9wL;K}-FjU?XQfdjMaw@$tAB(wz@4@>h} zJ0#m;D4l#tK4O~`dLoeT4WsvWJSXAr=riy8+g!AdFe>?P%PBjY;s79=G#+GqmF|3s z5Ff76csGE*yKadqW53dK=#2=T*fYK)ou05TY3;93iMMV6^+lWu1hOZk^OZQP zIKuCdP0#iVVYtH}^8gPg0dPiT)KywnnHf#P$;ZY6JU-UR9-IS6Ldo*_LOF&>+o(rc8?|&6ENFv?f&%AGcZ5wwx`7TyQ4_$!*eQxsZ;w zBoZ3h73=m~=fSTPZ5*^qP#g6HoRZBwB;uto6OfP&Ts|ATU6uSS`xfiEa#bwB8{5GX zs?~&*1^SbP-~;D+!FVl|$_c(=Bw#~`iE~*7&EzJdB{-3~;#?E^fs{-sXs4_FF8D+z zb$ys4QR0e4rwLf#NYZO#N{+QsLhr&r}2`j#Ae=%3oryzem6Duxj+va z4Y*V1{+?zjlUpfikb}yl-+FYoQdZzJO~;=peXndw-qb=>WnYUx=uc5|#HFkQ&--0M z(%dK4!w~@`HDYQyRoogy7ccUT2cU=6p_*tN%Fzn+u!>$X%*6;b>S6mF9OU94askxe zyG_~Jf7EsG=zd3Az!~hV(BJ58Zc$+-gskqi=j11EuD}6hS4wQ(azcc#a#h;v)MG#e zcYl>3TITQ3|N(=k4zOpXZC4r2|iIMGDMjDbNQhKadzV!|j?pug^A-vPz`(Lh|} zIlYY`y&lKg3gRvl%04RXT`-qV;v!GRMVY7R!%cZdEW~jZ_q^oiF(u-?$zrJEJ8y1@ zTk=k5$a`8I@*HzNxu*rVzl>b@`NbK}$Qf>lNVue)z!md|e~3$dp5_U7*7%U;QK(}> z^jYM|#g6rR*O~>>;#BCAxEE%1F!J)XI{jr5p_oj@XR#JD-+vrmrANfN3 z@|GrkVzctk7IxlBhwxsd9xNkwXf1@j;3plqbS;Ci!#>rZB(|n2oAwDdigK9X4}NRJ zMc*DT@iAvKeqQo?N~yl!9e2wn)ldPuLeJ2_7-1M)d0~q~fA6L3LSN99B)C!=CngT zGuC`xF+1fyX|^BJALmm?RP2YoH)=i8fAiN4zk&Tacy@*a&%8ZGoyG!o8#)c!ZNv>J zfa=WvZM$fRDNeW5h8r-dn01E+5FT?}Tq?}g-MP1CN%;DjcH<5PS6RHbm`Y06!{P>a zpDg;;m@toGj~(+Eb~VyI?8;$Gid$1kPCyvL?j2*>3HPaZ!b>uk`P5~J@0fdHIGl5{ z`>-{gW4vimtQop~`;mDp>UV$m+ZQ^bk z%0&yXV^hC*+&N?ZkfX`SJ7L7CM2^5JykW$!`=$j$S}uGC>CN_M{3;O)7Doa%sWD zQ$z?cq1JRHpolnQ*q}??;jqQ~J3()`n@<_3H;4ag$G+Xd7_#$)}gK zq=QOC-rr;Uf3RiXDlH_n>@jBE3rC@rz5gFrfq@T0I();_9>GKI-DxMW^Hpgf4pS$} zvIc5JHALHP9Op0|=*+-qH@Hf7RK|dSH#WRg@S%-1h1awIHN(q#gfrzb&skvl*`COj7vlG7nM#5lCQ2hPzm)8%Y5NdWP|0+=_EyTEPx$ zapU$C?n6@2>@`XN{#NLqmB?&E0% z5wu+VCb;ED&z@U#qEtOa1ru1<0v6(buX7RvijlSpXqk#0f+6D7*VX*le6AT+4XI2V_gBA z*szSos^6&T{<-De8*aiOhSL|#0{qfw|1cg zjiD~)z-X}A#I0TSF7*Q4n6ae- z3LTYkOC8>}q!`1C0j*Rkln_P?xzYQjJ%OAtULj(PrfB+_+;RVxdICjNSe^tRA&ZU% zD1+JdZtvL#`-A~xx=fbT^II>gm)UB*cGLJ9rA`O|uVzuRYZ*RH{8Cf&Rn^>k4%S&4n z9a=TmZYeXpB>}dh>caYz? z(N@1g=3<=*DVk2zeI5~_qqp2IM!!>Dx5_0ajr@s9AVxXinAwI#=P21;_F7CvqeywH z`8;ZsI?3NmtZ6UG8lcp*lXO!u1GtE8tiH1il4>nG|Qe!F8=35^=yU)!RgIbXL?BIz9Ld*`eq zdXziRiIKi7cNT0>u!A;UwSd_*Tz}UcWMqA3{!?YZ|Pc_ea-Vbb~&I?CQm7P`ifUHKD16F z9>#O;lE!P#Ny%(Dn!8=H=no|zi$<(DW!3DboDfq0b}d5)+ZVQuJd9b~-o|h|+HdM+ zvcHE^_w6spr~ui5qG(&H9hH`#!eP@a**2;MGvFsJrnl@S2^KIZ8irt6!F~jC&_Qn( zZXk=dbIMXYOZX&{&^T)&7%xM1(bO8!IqU@CCPXyLG2Q(E*xj-DuNiaNdzMX?ewTd+5a4jaS~an${$i1|hRO;9l@ZqJby z?BAH_*s}`e9`Gsjq82D}hb5}DJ*q$4u>WQY765e>`Vg!8`8ghYLa*I2qXHr9VP|!m zk|(ZoMuiRR%#eAW)^zQSMakLLwnVS5wepd()i-}!?Z4(uF1i@nMhIbHGiSppuJ7IN zdr1qvb;k@+%{p}Ko49w|TkM!myz*vV>~rT{l#Ktom~Uc@uSVZUk+dhDVtznfV1kv; z+#zPI+>kN)Fore;DQy(6vNAreu5OFsd@)|Kxw1HuDcyV95D7)ujlSGKJ^X{FKOX(& z!(Qb_6GWH9%KMsq(4>JG$IGd+Ozto@b{5QuA!nDUW-a}1oCS>7>NAtp*a5)z_(nwD z6nA6y2Dl|av`Ap=xWvIyym53*nL$u`87JUQUyqYK#Cgk!ninw~c{ZXhuCFPV;(9Dc z-%$SPr?eMm+s2rwo~Gsnv{84jB%6l4!0hfQliCW|uWF8M(-V>DzV+>mNWtvjdAVXT zJ5Xs2?z77theY(D7TPQ3>%kYS$=0(Jwj!U-(MGHG=YNeAY78QZDdJqsc^5Iv;Mu0a z{K;7uQqH|P+-FkEimSuBVB8hQJmB#e0`}&TSr;r-qHb{Z9H~RxagIEZ;U;_^d~5b0@_?PR#o??t(H7QrA<447m^! z2RIP7$w5%owlFAKSx3m|Iiv^c?&y=*{+zDP^96y8i8WyxpP+(Ta!)h+ZE+U4#$z zlg!N~B7EV`_DD0TPV=?h2g{BNFKa zvtaNUV%)dqFX$r{KA;`Ocgzn*^yeDN#-0Mawwg;%X^j`CW)8GW>Pr}+7M|0Eu40c? z;DLbKn@if6I)YXlMo);6YdeVEo#FisAG;g$gNT4IugS>t7??M7;Pvm7!NZIRj>6S;_2oCH1a%VHDfO0?lQz;Veg4ue8hY>$ z94fA1TmcWMiIg+Pva*FcjA2n9?o(QazSy=))||kEQ9Q;n2$t5QhybA}V;M>#JhsL} zDw)j5$gOC^ScZwnOP`tE5JIRATo{J%jP-HYv-&|ICmGFax~oNHd2Ja2<8hRvOhUBm zh_EHekr3ktW#JhA0TFn3R05(d7JhQ05m!Etm5{3q{1@X+sKizH{;Kgcx(5j46e8uX zxs8j4iB%ZO+}!xtmkFh44(k=qpjPO(7L9WSL^SSUF^5tf{Ss^?4k$Fd3ghjZlf^rgZ_JVkRKhVVW*Xa+$01@{_-g*#faCuq8bv-kJKHOtW4cq6Uh*Tr`RY-x?(;=o`J55!9D#mX7O zzxATffCb0E%WTy^m4XS-w20RYB3N|G}WZdJ#2^pEinM)KRUI68} z;*ux_8C2yqbSvtOkVfGe3zeI@9D`^-l%&Tq$jFU9INk_@Bsab}HlRTHRfE&Gqlq~s zgtr=J-*_PpIPc)_q*`{cs|cxe@ozb3FNv`FHQ)NMy73P9I&)wc@M)R09BR|D6-GKQ zwQ=)0e`E4INjl)P0xmUstyZ(1n7PaPlEw3TC!Jq;JvJO)`4XAWMk)Z zZilCM+J;o^FWZ-!oTxE4BzLf7ZfIN9qDp?r86B!JAe#=CpivrQRJXw4!=#y^HP)qV zQ`*rQcrCa&1a!kc7Vu@KMIEj+UT7GASc~jlfhg$M@J)!2){Y^w>0dHA$9(D=+LXCk zM2opLlMvU4gIS%C(b7(XtYqox0_N9b@)yoru*a&lJW z?QZCsH}gf5{knLIT^gPX5Im20phd{o9fGF~q>LDVDO^*xG>v9o4Hc*B+#R*^O=6rhOh9e%S0)FM%68+ATIC%L1m)!uW4 zjwc^F*@ar}LUjZ}oNN0B^hvElE$GEg2K17Qv@6PM9*<5^ew&1sop~7MkZIu1rtJrL~6-hRw zvDvUOUrIgOA~$BRfcnGscHzd*n!-$N?g)fSffWP#C&%2KvuF3^41hh0Y%#k>I&Bwq zjCA0(3I0KIj$>twl8{pKuok2ZBiCpkWQ9>LOa(_;7@6aG?O0mYELf-QLm#s}N3eM3 z$irQ?R>ydq^^$9(WnxRv){`wej;fNckOFhFJ*TL*c=;Eho|x}P-zpFY@W%pqsq9vs#%m}?W0! z@0o#WD|0XNhhla^W_uHj9X1k*ll&EH^tQRJOiw~kV02A;(+}XM_7gXux${h(_?pkK zYf+9k#bz6ByIVG#+h7s9VsXi|E$&86P%uC=tLX%4uJI>WFAWQi!y?n}%G)|x&;Tg2 zWNXqpQq!v>ujM6LN=_KJ>J9ims%B^<7>)$^l%xF`9R)V%5}qqO!F$X`uO%IEJ^$Ns zyRGWx?hZ~lNxb)RHD?Yu`-|IKTaU6^WQw{`_t1^_AnMNJz-G(NG4MYx-eVNgOf*LE z)^a4WJjyx?<@8PwLzK_F0DHE(7{l#-9qqZK=ew&!1ID`x?a$$_2u-eGL|k{R4W|8t zR1%>oNqu17PDRp0=ZBB>ea$}=yV^g!jB17~qzyIoNjNHs98uIa&WO}7q9Ho2n??a4 z3N6$K1yn{Tj;N)HT2klm1P_&vxShkt?%FX$1BAWj;Y(#-b@BJbe*rS^g=%7IKbN^3 z|E)=dWe6t*b+P&=6g)G0qFDLtzBNHZ1fSOxYjwqcE&dOF=ZQr+5L_zgMLZ}2JZ#Iw z_&{D9hVhAi)Q5AkK`fRW{fNpSMhm%_<)1@E$Ii_(1ylqddmlhUylI+D0?7C*!LuG z0eUWLi`HP{I%lC{bTiCbn?`Bl`#%vWaWYa7PUAhgf=^_UZF1UvWtp z>(O#%rcZ?7iao&Q#qdE}Vy~ba$y?5_ZqZz$#X>8IRdy`<21QQwntd2Y>6_uO9J7H{zrf5_&}kF-;4{y2POJc(5+GlO_si+`1UaA*UaxvYQ$9@48wPt6LA>{w)EW7(D=a>K~@uDjQepkrP#mZE9r z_Qv9p)xBF|`FFLCb%O(I>GVu=Fe{%2%iue`MSgUlVy_fucl1~(nK9doTk*I>KS$8* zazu@csbPb_SS&|ZEg4%KW#c{v_9(XOTcdCnuGTNp$UmZXfZeFQ=X*67UCPj35%$*FDVqM8f+=F0QiHr(;BveG~P2q z4CU2yq?5;+*}|5=o>I24qX}s5(1Qt)xmN0X=t33mnB@mfT>gTVz}-^x9NwH%GE2gj)IK2}ePGZO0_Z}7=GLfBDe=MW;w#5pI< zU8oqDE~$xq4?uGnW4EivQv zmlfNhDP!pz1cG{Rhgj z_+ERni~O^%sqv)3P>%lMPn%c=p@A=^+Zy(;fv2Wt`@;1@jA+>Wmr+K_>^-K#iHNh7 zCPIPfZFh@`d-!c0OKI;XCv5YqA1)tncVRUN?a%rVD@yKYa%IZ(b7Ebwu2(qRdsx)d z4QsjVSmgF4CH#RVA${XXnF%|Ik;n<0cdeQ2RctB(w;5X6+|i52&bGMC2MEU&gvy%^ zJ6Rf|<%Bu<68jEK?5eUOjcb0crWGr8bdSLib!nUPyy?=$A*cx4T=#YW8ayx8n+B!oyBRYS}J}F}2-W4q+=tCaPfma2N zn#cpqRq(fBIh0=K&JI*^?Dq&=BJVMCLt4OZTep<+ISf61rVm_c?qY=)oz9EZ(wZ-z zv0B=oNSU4Uqyb{!(Ub)bpY*^>JT@46KoK{j_|Q$JqgXv~v*UNE7vp}oSQ)@OQd-wFR~O(xmkl?R4mlkb3{K*d;aUALYRjfqRmutZt`R z_rOV*m{v{Tt2VOL2TlyJk@rFNQa-XxfiY9UXagLwNB*6J)GNcyaKT5$*9RO^6UD}C z>TakV&h?b;951~IPyRruIY^&U~YX z#l*#a5Tl2qisNEK{Zg+FBe8c*X{_Avo!o@_Ve}BN|%o-i%e=>~o%BE$r7V(oGn%WtsHE+mRM-I58t>5O{-;}I-7#$hc7xV*#gnfLj zl46~>CW-}(y}}F!!?MDEsGnTHTIsRIxkVf?L!LESZF)2KbSN3(S~pV3Z~SW z(n2eR?T8W2*+1HYud-WE6_%E3${TEKup!0yTpS7k9x+8r8GPheTi(1I5amPCA^mIZ ziT`u3C#*I3Bp(|-Am=0k79&quk}Bqm*!FBOZn*SZ%o^(5_Be`pd3S_f z!UNWBJ&B6LSq|YUWRM-ayLfzC#wJEbrr>B?R!C?I>S3pva{+EW)DC~(-nv-wgmSvI zo18gIf#&%hi|p^>j6YTih6&!l5huFjq}chH{W`HUj-IFl-ZF-T6_N7gcyY8kmCoc~ z6D_c3zaz7&+l~@iJH8Wo))N-wLmUf1NbxP>?Cf%|Q>Z2G`V=?X_quyqL>=Na^bKy9 z#iBi&V+!eSi})sT*$b>QX-bSAdhoYsN&Qy*!GHpHR@Pxl(~`{PN0zjn&o6Vu7<}uvCuH7Vpd&fy{+DB|Jchvq z$n_Ak@|>b)?MG>~T*fuxPdSFrg&%{3Xb!P*ExAdI<%Mg3p+8)aK@$eG^D4zZEusS zHJilQ1Q`~s+)v50MVf%8-f5tinnF)=!f7;N2@-!u-W>P$j+@+8;Vly1Gge&i`4#WD zRieM?f%H#=zVAzXPuU++&Kh2T{Q8Bs%z1&U3d3zIE?<2#*C#MNEpr+c9{*2kHja9J z4SiDf%YgjrSFgFjf~q7WxWkuYVtWdasr#W9Itxq@* z)IEtaC#CNq4NtM(-o5j)`?w#acy%!5^4OBsabwB@lQ_9?r?TgClSK#|gB=icO!LdJD#{zEeI3@6wefl3zc8QVMV>RytnbT@<%8V6 zF#W8TR=LCPzOR`Q?-NOW9v3x!{}t^*+84^=spLP;e@uObZPfOJ0`&*)KJWJz*-t-N z%atV_a0Xu9o%U;QZ6fWbar;t#Bh=?(o1^FF=l|@Sjz|yKK7?LBgicZ;r_K#s8w;qs z!0dQl7VgYnVVC-NZnwg}nt7{`r!cmq7)0a`n=HJtHOCCI><_S+|o6PYzz6<_5=c zhxD(I^WtTg3&-}K6>s_Wjm^yGM`(&W14%zpk$Elo!#t$akE6f8)ARn7M;gyh@>wF` zX4yA^@e$6`(0QbvLOq5*9eN7M+%Lz8DH`B1`0B>0NBJJgyd}?Tq|W!*Z0Hj|O}o@G zk@Gu#Glzmt|MLYiDdGlQ^DKmxIEfo_hUI!JlUN^rA4A-p3n$~ZmZkO2g_tF>cRZnG zVJdNa>rA`qsd+mKYKYbOb5^{%A)Wv8V;crfzK@=M#Nhj96afEL*wT$9J>Vx!#rFle zGVy(jgz2eJj>u!~{{2N*b;hYZe@TjWq?(#`k0HwmAuWU8b)+Bl&=b6){An%6`hJ_7 zZ+m>tqt*fQ-wx(4@L|1Xekdo?*Ye|Lg~O=xYf9_q`2t9T=jO-Jc8dQanlAix;9o20 zrChU+wU^Ug%Ks#1>hrH&$Qku@uLda%xm6!3pE)9l6*xuNuLwVqcX|Uix1Pd14Hw^s zTp`W!o;RKoBLLnV}*1Yw}{^tAITSY1+X&>Tf1|v$BnPWcY1kgORdXmwh6z4 z@zYu!aEN;PQ8REq#pQ9Xgz+pr`2JZrA5$7~n-=&``U3osv+tnir{QJjx!~Q*UqLGm zjSU!I;maT9hW&g`EdC{18w@*i#$~Vnq6DeH>fgsu@kRP_KW1U6L46-fh|!~8FXiat ze#e}Tdgg#TNA?mr{U+kDeh9^=eAGfk_e*r$Rqr>Vc zJi-`4nX~^j$R(vyj}iY6_pzJ@#L4R~hku_fM&mokwKMrac?URGQPfEBy z)fLLj{}sJSuEbpl#XIy7GV`y4^(lYO@Va%&{ z=`G@3h!gsaJE;vH5;8PT$wBI4XlDZRUF6rMY7@f)wc* z)_N{`S+Z{a;vSmKmr>t2eoMn*KcJ z-o4WVM`--@ekhhJevX)jv^XnU5XHr!0U6YuO2hoQn(>j%g1sQ10WR^}EinQI_tmj~hPV}*Fip24X(j?WXd}L_gUr@TG6|8> z0RO_VlyJztiZd8|`(ke#HAI?VTkFWOKBS4;0ih{g5n5MSbLKDmTKL5ieay*onkXe^ zr5OqFMa;vKx`a94OE94iFq5vV9b5uZR{lU^#3gK>uhi$|K{|boQnp(wv zrf5kT2AWG_x&F`Q=gA>~$C`^%+_5AYLmF_bLtw-v=D`?CM67W(dNuGo=q;&(5>!kD zGPvY?h(LUqW>i`BX+g;YE#xq72vBg{sjwTNOa_sa1;w?P5;RZMiLg{Uii@epIAp0x{(SSApO1#4kPrD!WaCqZ^^@ct!%i zz1z(?y`zfrzwBR)r(;oX%Sk6Q`m!}RX=Y93NsT2H*fsd*_0<%avl*yb#@@zDqQi{%Q9${wQ?8QbZwLI{F1al@jku&1545{$M()mhEQ!Hp# zpa0@(m%O1eD!#W5W=ntr`i7IyFri)T;n2S43@joOY*!yeTNK$+MH`$8bVyGsM7}(2 z`&Hi>K4b79p8KPSkJfmA8Lg5q6KlZOA3UuMQp$nfKE*9i3W-U(XBN8|_;mhuVsp%$ zU0^Gca(0@+XmXM(XTDD@m$%puF;<@Dd>8?<{L|T`vx;Z4(I^ilSh*)SxT>4>E%O~x zKlYp&_E=m26HNZ)XW=oT=79LPo=5Z?u{?(Q+4Bho)UTZsGoc3>dpq*s_YcDbV!nT< z%nzj>;e2LJS}~s~^P2BVpO6xxyW;0)$0z^n?&Je~#wjQM;}_#cK4B)xD0k z`QyMnvc|J%2JJ*|hg+!Dc+j2vfo<}qlv~oe=7Jn4hD&-Pd^Xig* z<5e=A0fnRrD3l|eRFX~SPO^d>s9&5uW9ky9_JQcDr})pJN0Z_+a8CN{)BbDUecFGO z>!)$SN9Bw@r1$!z{{6H+BtGB}SUzB<-^wT4T`D=?$>&3w7BJ6zyR@eCh^NQ;r~Hn( ztz+=PMchf*Ba}y>@XkHPEz=*<`2V~9yFhyN7%ElKgB{X(`y={q^k7T^E|XW9*g0y3 z5-H;DzkEWH&!_S!RlQ7?kzue@EFXY46Rqs=j47*N&#S+FZ#~#vn7uYvSwFuAe+b!r z#ZlLDG763-JT<=)VTy94KqW;1s2u7SosR?Cv-cL3Yi)sm}M z`OQ6&W@wTcw61 zc7dB-aUT%r*!u79xCC_0BV~Aw!kXvoa;Ia>g9f(6Eh_MDdCpMTETNTK(st}$<{sX~ zlnaSh6ZY*imr4PQPEC<2&?UZ>^Q#U;LWwO5J?vCPoPO<%RyK0;1KcY|9 zT=CCwadNR8ddYKTyd0AplMNM5Dl*SuCzm8QEqpoWUXf;1uejz!?ymN05Fl>ET^~H0 z_x=tVZ@De++CBKi>@B~}3+~juWl#9ry9~Tf_nrJbOQ+Lqf#d1=7Tk-sGwy0qBc%AbF(+Kc^5yIpb(;Fo>emCpO)m_O7HQcRL!HD+Z|&(_cHU~hDC@3`}(^G;6>46qG;@{{V1ky+-?z>RYR(;5l#)HJ6- zBNumRMv7x4b#dW=59WzlSG(mBZgIXU$w{sq#vs`VtGhn|TEt?Ho zX?NTn)2xY`uBW@@l>1|NttZtK>lyi4B7%Fm0qLBU=E(}>{BPSO2dUW8KVKkj++cgo zQ+|-kbKtIj7?dzdy4uf|1Gu1Z@`CCpp)co>f-h{Y3B@~ZR@(6+#U$~i` z*%kj5@VIRrc;bi+p{587^0L;73|@u+K0b$HQhYP{##^OEV8Fdw-ZSU2v{TazckD;K(PyoVI=Or) zd+%SX;x7SBYcq(Q?D4Q1T${{?C zgnV-;54{1uLz=m)g@YoH92QSN_#W+trzm+01{7eIdyD@Ih&(GkEIt~@bRq5zB>4b(EK)SBs#B^2tbsV1L z(Awzmq3aF^w8#7pvl=dPuk?(IT=;c+%e@kD%k=Fn(e;A!m<-1}InmDzCp$eI#B0P8 zCwcIDXDYX@6lZ)hC3r~ZnU6bEvLnryb6FPg+*^bKLLWzTA7bpkrdRQQc6*!n_z5;( zC9Yz`&FbC4^RwXM=g%4S#$$>GTGwMn+a0`}o#O*CmOEYe+;D4~w}ELwjITFb^)wZ; zv&1Y38Zh&w;)vmcI1BN5S5VQL8K<}4-9fI^MZvS{+Q1J^fgS9s4*D&hpf4kX#evS%CYSsyY9&xU7O>IwMgnE+WfPaNf9L3!Wj=QOq!p=o^_!9D~N@_6Bc!WL zit3uS#RLU6ap6Df7As}V*x+4Ax)6LNtf!%#P~i8NpsrGu7`%9GsB5zw9a~vUKq&Dn zz|-dqISM&uVtdEvm=hh!y*fo)Xah9X{L=)Q=iBO+*y+4sdPPQqe;U!wmV z2{7NW+0PL7OM3+B!}HhNNKkNAn?v2hZ^9h-_Y}NTZvqXi&3cQWAO#}Ii;#~BVB|(m zMq8`O&%jc6D;cRt{Z7*)NN6)J*cQ`)AyqSEX-2>(e zF%ff~c7s%TN|ioRfcxl;_lkUb4iaN}T{ZeEKI-~z>>1bMjW>9`1GhJfm$Pff&Uf5` zDXz1bGl96yZ#0`bVxAX=d*pT&G@Tb`AKnM{U`=mhE;r`3>q+pM=fEK290LazYzP?q z{}A`aJdPztqHaOA3fd<$&@xod9tgODi?syk2i!8I*6v=^VZXygiHpS}1s>;GR2dH% z3TrLadj<)RmUaOWO9Btq64qMWafEROXsa-W(4aLKa|T%OmLZkS`@V>CNLDqwr&_y< zCA*8~kZ|R`+T2o*^`*w@^!W1nDgVS8}Xlrx#p z(ei0kfg0`0lER`tUmANW#zu8k$dBgk^Uzo>#V=8Ei(OqUUyDfA8j)|%Agw>@dUKC9 z#9D88ps)a@MahN3kd=6H&BZC<8I!WzZ`f-B}W&t8$hcDqTChq(0S0p{UGFfS=@3qA)Ixi&It5Z>b=T} zbM80%{}J4nrB%m+>lm&BU?|5z=Q&GCnOu%=y&Rk*h6Rz-g%;I^OQR?Bqq(-xahIsa9|Zr1v+woO?`b=DP!t$o)eIR6 zVH<-?a89ru{E@b(hJoxL-^oK-G}tC%ZnZ+ShK+G*_B3YAjyo?3+-qA|jF@jHlq&$E5P;M<%jXKBCkQcD4Ug)G)xeyf0Lt%Z|}o6fr3;SxX0 zHyneCOBl=sloCJwb1u)EQ#IhWIET`{@kzFglaHEfQ>1-cTjCy1(F$%j%4#vMR;9iN z=lx|loUi6o;=oCqT8Awg$>bX_AogvOUAYtTeA7y`I~PaB)nmh`%`^|lx| zHrlk7ACfMnHjo3B{g5Nl=kvNb?_@gysWar@R(w&iP?8g$9o&5l`ZIS=ISYiM=ss6C z&2f_euHRUNRYF|n+G#K;)cL(M8%RUb@f@0!%i<;OTMUAmnzfXby~zEZI#8IygqBOv>HAD~q=K1qAKEvb z@W9-s?fHC2f)OYEcp3{Q-&v~SFW);#vEJgryX!GC<`uG0p;qOCvS^qP+tn`3BNyu^!zGIDhVjf`A(IjYebqt1epQRpSKt-xZ} z7q3h;2mCRE~)Hwm{s$oWxl}%_tzc*e$TmZ?hMj9qnHi^Ku8>OQeYK~H?G3jVM&ZxPw#?~-cg}vhS@VoJ#kCwki*gT-xzJK!a@c8EiEPNk)#Q* zM*DWrM#vTI@^mV^Gf0ajXTnBh4eBO+Xam#>swg=E@22&EcY2coQ}DKpR6Hf zrmb6$LmoifnU-7*tg zdLkT)lhlYjtO5&bSnW=VTXV8zOLc2$bsD)=YPt%N&nvE7hcXvfjIqK~o?g8bcf<{DZ=|-G9pwU>Tu4dU2B$mAZfc@x;CG=NXBdFF9;Mw#678^s*6jEc8|nue z`71GWO!{PQWYk|O_b#1G$Jeew2=~jLz&$-X%1GN*j@X`EtFARgg;N!)4QI3gD&LvU zw;9aqxp0X~yDoP)PM{6;%GP2%W)qNSP9$ceGqk0|e8`m;c%3z8tHg;k-lk$*4j%Ve zazW;z_818jZRMP5o;RA2niieTN4u7Ihf8^5-^ccUQxgzLha+M+OZW*JE*RInu|mL) zmTl|HG-|plC7GTaZN#-0Ql6j9m-G1S*On4Fb9FsYSl<*+2~*y*CVR>@97+e}ZUyc3 z8nXG5PWFdwt@tm#!+^wW3~kT3H)j=3Qhr;miqxc$9PU+1#VW2^X!%sr)m-5520x`f zvI)`&f7k?bZ`nzC6SKm$X4h`c_{K-Iob-hv#vh+@0vdP2&yaI}cXF`vpB*c1KGW9l z*S!P$xc{1~(hV$p^!vI!*NrQzwEB=dku&zPf8aZ=gZ;H*fCl=I;9~B1_5p1MvY)d3V>%8}i{B z;0Zr`N*)F_(P~%!Bbg`Bu4rwxuq4eI{0$stWx^?~5-{wNHam3VXHr^6QMyg4CIn4sa<0|+6dl|dN-Am5{F)vNzPn3_F7Uo1MMZU~wMn9xB z+ryjE0ke!}<`im!ih21==>AA!C%#;=&r6#{umIxReZ|_P?hRuf3(q=|!+6>d8JdglEH+d%6nB4C88uir?{4_K?F~}w+w1FWi9O)Q`eOTZ zTLYIS{$w~JL) zGU~}^|5LOqDq!uyUv_&%TC`~Y)H)~l?twRBYdTpMs}gvC10EiDJ{^2?I`hp#_%8BL z@sK=-x?a@DCNJu2YNdvf5wTi99X?SPSGzs!5Ybu-PFf9!D{JLX)LOV+N8KLW8MP8` z5g_J)CVleQKJuVQ8CvRLOX=(Aly|li4`{ZOt^Fm`V?8*c%t|+|&?i~9NURn^XaRL2 zl5E+F_^{n>W9zf;^Ui&)7tCZ2_I$pI9qh3ewB0%Q*+u#X+%xJIi5q)8^Lm%cKGgiS z}}k-C-=~3w!9mm_+V~1=Dr-k@!?2XNRv$WaTkL7!~e|G0f$vRtD-aUq&X~$EKmHv0n ziFM_^^{dc@V$W+x7yh*43ptfLubKJXYw5mDgqL^f0+znu>#p@EU&iPR>FUtoV+lW5 z0vmo_#@z%BsIl&jwe>LV0@`_k*|GL()&CHc%>2i594nPM<((6jGV=FGzSylkCXc*` zzSoRZ#idfg_mhyQw$P+#VY4fkJ2u2Yp%Jvc(*gK@|+4%j9Re6 zh5Y%g&vsYjdtu&qQr~`7T-grahy9Ve^FL$s?^^k!F+K*;3;N_ZR~iRM-qoAFgZubO znzd=r%bd-d=WuO<>Ao%PRdB5%Qd0$=mt4z~6|C3JWxH`X;Vf>}RoIITGrNx+ML?Z; z8#Rr9@en&l`&G>IITOL9%}ZuwL?Cw#cag0uO6DTg>fmi65fMHf>lc6G`udkdz3CJ$ z$cIOv`xl+=7jXBlIgR1Z!Z#JI-1SP^rWT8!!v5()+?qapT!wonmp$E{eq+D-MtL(k z)aNa~H@y+LA3@*Cd9aX^?^>*)h8C+{P;QI7c-h!7dpH`eyVFf5EnmBhLMef1iM#K< zxW>L@Z$)v9wcER9S2Vk)ZpjI+Yyj4N}!Ts0^iEox1|9BNU&xlD1f^EB7_AA)b2Y z!|5EQZ@K;2d(N*XZCG{t%lT^B>)qe8F&HB8myhR$N5oHESnTX6JNLva<3Wc#MfjIE z?VdyLQM6G07GPAe6H?Fc=r;Ti^x186C;kXdMhNEuQTXr?uo==-O`Hz&C(Z-aI8`YVpK5*jf?f!D-bXIl#6jucx(J5dyEG3|}ty6(k!1T^3!{Rwh#*_L0q^HR>E zO(X7H}(g}|BK?bcW#^54|vXA8b#xX{4Z(jrTIuH-teD{#rZEsie*{KX{fl% zek(@oVxYD54iOMoErvg6b$y3J0o$qHf!1@Qqm~n5$+(^{8~hDYkA1rnI)YXf(52xb zn5<9d4*Z>$mWs$VGeQN;2G|9IkMC=Ve61XZVQz0g2&Y%9t`k|VxQFjq6)NDk+*QVL z_0#om)8mo@$sddqq>S+nnmkzf2}#OGC- zZFPClOa{%OUvG89R0N-pFDZY%4NqDfJ{OYLaYgL0#rhWL{AX7T`zCmkqpIcuS~i)p z0yJRhFW$c3bqtp0@fgtVb;WBZv}|R|y47&D;vE#?;;e?t)u2P0CTk+juIKDE?Xc;5 zNM>8dz7}@u&lknzd|13-t#H}4?uy-%>}_(jkrl*wH7yyX?8NMJ*j(0=LsV6^x1N)P zMbuB1K>;3` z@BaQ4!61F=Z{%d&Fe4ZZ6F?WeiQ&e6H3BQMTMIdj%p0zaP`g-yhrESSHOFxXUo#?* ze8>XoBxAob@8VTP1Vl^~2E~Gvnl5@l3>5yl*01-KT!@=RRq{F&BD_FyD#81cDFxiP zh`QC$?drm=uFDw+loT96%L2hD=H#0&(;M}MIq(<1=q{#WOtrHmsU)++?tED>%7+!Z zYNTJs}nb0;qb+Y>;a>ZJB1_3XC;yI7XA60?Lz3mGxr(kWp-r{>Nw_N9wHt7 zvbUJ1N`l(ZL?Rf`4|j}Cd)Rlvy4Kn(icr^j!V)(!Y8G72Zm9a&xG|6|eBEt7TVw3@ z3smjI%E;8VgB4uVOc&~PRNEfi>9U2Rea=BbxwpypEEpLZ=l;b+u0;$i_`zqpTrx0- z!aZYQ{jM$vJ_nYQSctImp|g1w^tVt{v&_Im0VZ zp=2>Btl5TjS9e*kA1a%8muR`ZgX`za7;9eP`i9vd`leb!y<$TX7%eoxU6a$IyQQJA zw~M$WtJ$_*5mB5*B7^442g%X)>VSfTC*o@9;Nq_4m$Ak5c&w~0SQ+u%p*4KA;yoQC zx%>4-$Q5v2O~HZ?^T>F_VoLd54bfm+I{EnxV{+A5i;-_CeT_F8-E+b&^=952jXLzz-PaZBC(*6e%!IL) z((AE0;V|pFkD5-jI(Jn2iL|&PQ66px!Y%@NwDU0|sE?HA0F%yg%bph^%d?8L;%&Y9 zo05K38WZ!5)ua2M9SbkKS;$U2-eoi}o`If)LDFivd^Q_!)Hr;GW38&?oo6% zBCeRdK&8l!`^ zRwNKvyLg*%+S|6ta*Xl zymqwxin`Eqge>8Fcgyt!aqMaBD#O4IxyCa`P@l1j{{v`IFW6l(`#Z0jYf%)mgR27i zF3K5oMiY4B%KV1tr4{2b^j;I#aA|wR%}?y zAG2gmuEbD0{aDKiTa~w(+vhyVS^xw;@LDY0cvzaJE)Qcdr36u)x237|08Z1RRIXJ$ z9xpjrgB{W{^qIkUyh5Ot6>2jQR4KQr*ki}uAuP?+l8Bf?-aM!Gu^37)TB73&d9zbE z3v7srH?8~gDRK|JoBc+tudKQ$E$1tS-;^>4-Y(iZ>uKoIODtVh@OZ1bzr-rpZ0_#b zeFnBn9+PdkWEHK~!?nb=wITKlIf?AWdnHI?-Z>@9 ziXJEEIj9oR>*p13gEQ`~L)z+}fK?yXxtwG2K;XaX87;k{y;SC_4N+s4iDM1#@|WGn zRo5D+nl)YDoSE>}^I*}f;2x;u9QbqI-C^V5(i$BR)CW} z8h3J?gQxQqJUL{{Z?{;O^klrl1tf-xBT=UX^BeF+Fc*M=)AhzN4wX}k|Dv~v5z$4> zn(-V)>!SwB3FxC7Wu)wIjKzu+emP-d`C}#rp5Ta$00uB8pV&PBRFHu7=4A~FN+?^f zDr`>y^MPzW1xH6NKaAc+W-zwxiF8K*>`$BIDs0=tu zpPg7U*vTuc@*xA<5c-Pd`iz-(wE{hM*jL+3vxwJ5+O&GqR=xd zg%fLa)$y%uc4d}BEOC6uRkfPWSL~N!#}Ye{7$!{UXmRc%${lp{D`!wt^X_c!6;=_q zyv>4f#Vfwe1dl?%9D}AM|sPdqWp;E1mfJ*VR9f{ z%=NHNBOyZaD2poKtr_JgbxZsjAtO>O^?JM|G^?;`kxFY$HJDFAMxYrZBNljKP+6GT zl_9(^kGU}Cyac4ll-}q4K;=V6?+GJ8?rWtvJOF3O4}Jc76@!>7XQ4icn+>U%7|+c& zS^VN=xL8dWb4CSxWSV9Dbw(MoL1jIupwd27DDgOQa>YnBt#4vKYVnGXWil_k0O!s7 zLvo6b6~t4s^_ek-%lWc1AJq5PnD%-^ifj~#xemn70HPjmRhl^6RO zbG*gl#67C?xs~_Z+PNTSLRl=XIeJ8c9?KI?jBg|FaNI$Tk!-E}Z=Wj1+UwAB3ZC<6 z)B0TXW4>K5*Ew$b9L&K>Na**7p9+6ijv+>fBm3)r<{lMo8e@zBTVa(rvKS4_ZvC5I z%oZinWu(M(7c((X*zAt~i(dvNzBtAQlxGsG*cftmw_r6E=NzJ;jJcb-mbem}GxZo61On@13y6+8r?WzMMP75rm1OoxmxM29BpM1CryNgIJbf#Ho>U`=%sTB^{oLCjkRxQRjDx&K2cW9G2pDxn#!6`U-!bC&i zc()5`X`$I?nrzNV2z83s2B(|c-zlwl{~@U$oxGBi)@*huGv+GnSmB8Zw7}=Lo)6d` zxr{xMnvb?&_0P;nbKgKg9Uee?CoDN35y_VyCy>)(X`kD7+VfbA(kYJGS7;-ea&r%=O;J+qR}_hzZv_DN5PELlvfwJxEd88?J4#rM<)(RF1^Kh8$DD~t6 zd$S^SZ3x$Cue-)ZzA$^rcK4ce_A8|%se{U^_ugR<%QDbY_EiGKPOC6hfO`prnLOg?rzFb!g_e6ENQW`9eJIsDC<~5V(Rr_>BLI5 z%G4Y|51|j^spZ@D?VsDSik9tQ)<5AoTjiA4wy%YsluTY1lYE}|9gYDdm(n)-0SOc9 z|LC-IVVC#4>?d}(2Hk|o=tmdtB1Od}+vrS@)X1SC4qcupwG!W?hJX3~l-S$9Vn_DD zJD9fDo)O}J|2a+_vzE8lvJLid_ObaAsyGSvkVBlC!}f^sLiKsV@ydHR=M6hT%d&D0 z10T|-!Hw+fuk2H5W@MY&9+_R&xaK%U&U$nI%d_S^Ox{%Bor?x;wpyH|LDrS@Gi~3J z#KGq|pL*3|>ZCyJOo^=B^d}f`EIzSfgZ+mcuv`s0)2_XiEyrKXC|nHZB^wUrC$i@5XWyxsOWI;CKq?qV;pm@Kl6~&uQu9aXYSBoX*8M2-%1`cIl zvv5{cK(~$Hzg27Li|J(DpRv1U&u8{Lbc%0#)s7vpZpV(jn>0$wIGQOHZ}%lVc=rPt z4x+kCLDv-$yg+^SDSX^#M*^#iw1cHc{Lr0pf;f&8G)&sc8VMRqmpx3b0$q}umI0qL z2gRYm(DM3(Sudeo__C=V3&#aTajPPq)NcDH`%wtlLgWVLaB-3z$NsVM%#7-hdc(DS z)a1DNrkZk8n|I08UNKiNN1;)!M{r`m&#Q%Rqx3n6v1Gwrzjb)<)k~BKbJi{}waCxfMMtXGLR4*6 zE^zvZA#lDR`p(~-{CKx_uKu=Zl~9!9E^MR>Np7=!*}81MP}^3wSDDlP^osw^;;std zO>h?1%4Xy^JL8bU4ae+^cw##5e5IK|iK@HkLKCNRYGA_>yOea;`RTFR<*!hc26Bh= zU7r&BUE1e!ImRpHY0j+Tk?Lrc z@h@LzKCD|k(K;geKl*0rlPdB@9&@oEivxc54z%exmuG+PbLZ@3ZE`^?Ybs~If8q>+ z@4*9`FPJw*#Y=sAI^%gEe#v2ut8wjWCC6P)x@^iQF4WN-!+7HHJb3nF!OcxQTjJaM zadA5NadE*3vcpxU^N+>VZ1LI2e}`g!ck+*%6<|%@6O4d89ap_itBNy0*TogyJ`Olr-_>RtCIW5a2Z&*qP zTV2JKJu~n9Y{8a??)v7B3k-1=9+z6?9oY$!m*b; zB$f#w)6AP!t?tpvd+W}eiBX0kBM;$kF%56zq)07qR zxX;XSC@XxH6iCf@b{lWiH@Op9mTECbY<6xMP@!FB`_z>YnIy#hW)8 zVyrSN`;}9ay{#v)>#JZBLZk-0I0uBRmiE80I0P{ofU?-@h1MAY7-{Xw3_6~dN_AFD zp)wjASeR2R78s+^eN- z9SQoh$=8fA_O!=)QuXdF5b|7-$N%Ks<$uCez-Zv?ub&L#`N^(_PR`CgfBoCvg7VpO z-s8ID;F3+g+uzy?mzM=^Ub$1>nteNKOMq6oy=m)*wc|lg0LT9M{PnS( z+`hJUsYwkxDmA@F+9jhoyU7zg zSit{q?qRF9wcN&DSjUDj2tWBgvXAStyU!l9^7Q$$6Gk04DMi8S`(Wp9(?;ag<2Htz zrOaW=eGjeW9wR_IKK*Z8=!^+uRMhO@ct>h?-SoPg_f}fQU(Q(P32hJeSpH*axV(?T zK9;x1>04vIMRs-=^OO72cg0wK53FbtWqF@=pDSS%#DhGf)Q7jtnbT;H##M|rWvT5D z;=acBUmc-Q(BOEfd*7#nvtG6D=sjrT@iK4s?P0G3eGVed27TiFxFgW=UEZiO-nDA3 zYy-6r$DD5yUHO7*|MO%gb>4qP&ex6@cr{8~3XL@G`92*^gH2m1eh;w?Txm%_Pt5<2 zxRMfae?A!RZ1d{|=4&xOY{k=YPhBi!S^KyBMd+amDSaPGg~#_HJqqQSQYv+m(TIeC z6h!LhpR1!Nm7fTUdfPgjMJ*XP36BZjw@R(z^lW=4JS1JCMIK&nw|SSkM5{?MTcee! zMIaa51pt=c4WrQ@qo(a|)g8bmv;ZlT)M`h!ypz%|`!xDKdj7kvjHCR+gAx5aqCwSa zK%ui8j-mI%Ix@oFgFyr9qKSC*$z8tv+Po?J{+bS-?yrxIaAvQk_I?qZbhhIpsT}+O zCpk~r_s`H5=}YL9^*WCC7%+i{v~*Miheuyu7T?*|4=jQ`XSKC7av`YM*5}yU)qHW7 zGbCI44DBoEa>0B~&%O>AXFP4`&C@Gd&NFoS)639|c5quLhjksKH4>JHrBB2wrAs5Do(|)Ea&Qz}wQo=4eIR|ME#F;Sz^B(6P;)M5=7gu0g^!v~>R^X9 z;of3PE#Dm5?XlG3X{3g<37A@h$Q`U6pj@8)DG;su`_EIy9&MF`a2Xqcr0v@GeX>MM#v_ZU%C~JA{^mdYewqo?TM7X%Q{{02<{eKErf| zKFJ-7Yv~+xI>o2f4EY9(k=*c?PGwNRD$H zJ#myg7hf@X9W_zj5qzvP{R}Qzi>F%W)<@3Bs|N7I`X1zr6C@5w-o<#4YJVCuTfZ+k z=B_OM}5NsK?UY%J~U(9caW+ z#x&Y}to*UGw{q&iXhxL15@qaPY59e*=#4QS^8N$rNF7BwUpDir{I7-*-w%NF7QXMa zL5g}S^wSYG+M||78{dKyxID^v96!rHrh5Z3pzgWueOKw_$r?OK$E!{JeHnM2PV&C; z2Tvm>QaDPFu)Fr<67K$9S|8j+32Q!*_8{kDIC1|V#}Np7sJonw^cGfPY}8xB_*wp$ z{-walkqN(PvF6_o=r79Y`TGwVix-I>Eo#1T72|H~nJq{%ew8)8wEZww+#O46a-Iou z#Q#Tm9Dz~@c*aq_B*!08=hErKm~x&V_38BmjdCml`|0KWE%HkKyxO;H49+=s?9<+P z72|w|=MNhS1zom!UCw&a{;K{$D)AMz-{7hpPaUSV&&jO?B?XH=gdXb^I`L&t^bxGK zRQ^65H(y+4uY7Ug?_)gPSN0*s$8rMmv`sfR=Me?Ae^Om9vc2^W+jcbmix0y3CR+I2 zm>*)@UK>YTkJrP}a)@aUQ!R5S(+;1G8E@^p{)rqAWs_U-Y_5cNSSE3J+;=Tz4|6)M zAJ;AP<5)f&rsWUu*u#97-ePr_w@ouAT%a^4zK96u$0+wMoT4lv<0t4llva8?!l|w2 zU3KrD@6OhH(5CizU7$OMF3XuoyBt_vaX!`4+Y6qj4bNXW7M_mpyEygY9WCw!mSWcO zRC{vPmb8$>yLNmR{tutaPmlZFG%0$lS|1m#jpKv}7<43CI-1Vd8 z%BRt4SAX>3yU_6&UuPayvS0Jr*?X9Dq@T9;+!9yNB39 zXdzh!iuonBpIpX2>kEmd=^@C*oA>N$hFzvTWYee?AC>P^6p^COjqX!QXp z_+k`ihwUN1|LU;Tu~31rFVUtbtNbvQkZ<`newB!k=2ONH_dGofzGp-^CS#|IV=vYk z4%ZzX?vP=fn-L4g=Pn9Ly#72^MHmOJX*{L8zR9df|75!-#kG;}3dV?PcVg^Q4t6hi>_}OBefzRfW1nY#bv#uX#d;DWIVs5M&*#Vx8k4O)q?9vE z?EIm|X1CDU=g&U>t+FEXpPr@7g|*h~s@eDG{wni?97}F$ceI4Rep}OTTR_rc@DERK z`h3rjHkYh=wX}Fhy*Blbul98wyLv09cGJN~k22xqVV4cw((FzD`hUOXK&cDv*3&L}yNkWe+;Dr_UAux{P_P7;0e8aM&p0MCPq@HLia`RhP^ou`SVYhye z4*f1Y_+7Ml*sc%LGM^6f;!)qW^*pA`MexN#oRY?ey6Y)^m$U-UBL66Q_jsvy^-v2{ zUH!Pe{z>W^BV?K5H&#Dlt${n3-;`#><>7vz{f;E0Xh=`j9(MVQy@V^;JxKsyOuAl? zYZ3>$nn+d#XF7TqQdJ#`ul_{;iPC*HGvw;jrRyk>R!BLd4)|w+o z_2Pp(Ne_2;jnoJ5?1&}1zqq5%k=%*Jqfr-mMz0|ZSCrb1n16q%(T=Kp9p7~|j+rMZ zq)nbSG(E!C)25SKzY9vVkrIz3ON-C``F`a8sW307=a{Ac$roWiYZbRvG^@#~Gw3sF zc(La%^rOZaX6Ie%MDFD?hkNlN1unu)Vs~L{Z8b316Pr1d2$aA~iam>GN(wD` zay}19LEF_OKYZWfC7-m70y`i#Iwe|^GLV`JSe)wL4V%YkpJ7ez+8SfyE!aY1^a3p? z(X=!7`rK`cQS2Uq?GLr!yyoq+R>utt)%{3d(E(DNq1^#j?XKPJ(eBwv{m{EJN*q4* z{!nLrFZICr0mk&i+bx7#vZ9Vw9GZ76k)S)}cL)KXR-3HB>+e1iQ- z`GWGzD$|P?;h$jHd@`y@Wef#```oz~?R8j;v{B;jxXs1%@JFc?aCsEE_t4}Rw&Lep*j--*V7b`{^@i}cGEQHqLjAPnSSjXU# z_NWGBnrn>BH?A&Pn67rez=l3WgZu<3(C#eKR(Vt=${$N>DU^G{kL5U?_VgOw%Bj46 z+$P(3@m5Z;CY8T$;oqdTu`h&ao1H_r+Iq!`@llB8Yrb*y8D40^DH0&(eiZnjKC)Z|i&i)swJ&fa@pT#hTLlYIz`2_O0KQd%I1E=i_pY z!_R`#K4c8~E~aa9j^K-C?^{~av0l;Ay`_5mzH3~6FopI|k8xe|G`L`&^F3Eba$Y=2 zlasN^+i{h0>*;t~?t-tH#nVff^AR5JYQ=GBbn#1N*jewyndHf^9@mN|hStAxY$t}V zLMraCWu(+6nKp`*3MRa{(&>R66AXFsLC;t>&NdZ*Y2v{Lwzz8@M|38 zeU@)W2rpnh!t(K$0yjJX@%IlGwCzXHvh(OYQXiF$d~Nn)^H$Yvyt0>Uzni07 zJ8&hz^@JDE$_6h|swdkWTlD`72ez&b)+4UtjE%#p0rOJEmO`4DDQ>vq;@CV zLyCVE{dX9vF4{w#M`~+Zfu_#$7foMtjTL;!UHe>&kCor2iLE2+jGXDY5szql)c^jg zz1`(5v!|Cc=ldb=o?g6_v*Cnj8#8L;H0|jy$+@+4XT6AYxvMK-si(lb`%%^Ib^QaB z)gpQeqjyqD%8Hq9IsAuF=xuzY1}(5=zdH*3TgK#jVP;*Uhqh+cyT_opioA@d2D9Mq zr;IA{e{q_e&bk>;qGV_mk4DJDw6}Wevlun+#t!=s%^crS$k0b?-EF;MzaK@%t`6FX z@8?6tWIJyjgL*9Oy*RnMen+3Ta>lsXKi^-GGcDC$qD|!*QuJ8lXhvITf9hJ=WuBo3 zP2Z|vU+U4-e|AoAR-5Imrc-xaV3Egtwt>DqJRc!?8~p3wzlZvne2{tNVp`RF|DE-= zy;orezpcso+w1pVJv}FI-eD_dd!JZe(B@cPX{CMo0N?+Bb{uW-#e-T~+BNoS^DN)w zYN);qt5xpi>25UbuHNM<*+k1TN-}E|#RVlApE>-7$9xCjJFY$?C!;dPV(|1;*k@N- zYp3tR{%GA#s`0}1{hM>P?=mK}c-v)^ULLJWM`+>=md8C5skt0-Qd(lZd3t&BugY@2 zl#Y2JG0rp~oAz)#+aCV!a=h>AKQ|{>x;ZgCIN8GY;ks{A<~>FY%RiQ4Pi`YC_xn2b zSDU0{?r{s7=Xkz-iTzc?CRZOj9fjva{QT~7)F-#K=VEU*<@JELDy!vW%@Nuh^=-uX z6-TpqI@|U2uv~KL+JvLh2?i1yOx@NJ2T=Y_6|~n^D#El!vnk#~~8bjVDEu z2Qb&y3(hAe%HU!ll+v^3h1Nou%`zs%jOg@WFuS?qoNj(+oc;?gfl5hS*b-Qry~%0t zp5;wkII|Gqr3Bb)X56PdrQCDMCluxwNpkqi=umONt>;RXtJ3yOjAh2zuv~INDs}l| z5z}X$^XX62R3eUWxtS2(hIg=jT*Mlh-l^hvK$jh?03u<#r9v}N_IIYJVdpnof^bF8wQQ#`A zIhk)>bFwDU6la9NB1YH5{%W2}X?lXwCV4uY&8>OJ8K>ex;OK|!iK~;!<#aY>M2{1^ZO>0xu#Q(FafJVeq3s!TWau^_&1qT1pjq&XB20mA#upVyo8@aER8inOrujTzV zFx;z{DVD}2P>;xUSxRxLMJw?w8#&o242+rq^ziB7 zbwYjke4oZ!U5)(xE{i{4M&9>Amo`$n!F_Y7=8~F6rfuPVr<{T zy+jbmJJD&PhnMas% zTH7JEv`D`^@rlqfq|`&G7d$(Cl;$|OfP!izJ<2pO*^^HkbzuoP!XCm>lhI}}Rj%e6 zxa~2HlNTRT#NG@JK7__~oT+hA{AVd4gX=K$legd;jJ%7c2Dw(AKB()Uepdx^Wzy&L z1K(yv(pnF4zE#(Qr%%jz_Zj2I`V3kxX7bhzUwiqkxZwAS8513%{^NAL=pwo~G202k zIiU=>etpe!$&59b8dfsD3XZnrF_&fwjcRZf z*d5salyBe4{12cC{BgtB(Ed1$I9kz;(1SuBTF^Ysy>_1C++pKVM08}dplB`gaM19Q zUcP~bm(I>fi)ob#Q^^U!l#axhxxE=eQRhd_;}>+o@)Y$N%`mhC&QTw7R4(cOp@NLU zKv3c-aplnEx<&|`bJ*@`LJZ4p`SY7KmCa*LuLvJF<;-B>-Oq{6vLXZ(QCuj^S=*dA zKl}P_*r)S2H+euLz&~>C@2Vos0VnjX=G`taDh&=mSj@WSAYmHU<%n%!e{!(z%?;7$ z&^4w;5BtTkGnh`Og~N_loRmD}uw+jPN5fhZiQw*z7%~KPBeLJ355~Qo(GV6ybtr&F zz#>j>Cxy7Ro*2x}#NdxmE(1k$`-=t9rHmvV5hOSw*bujz8%!S3JWsgOopZ?WswAGC z5rYWdOzf}gYt+Hnt5=*TuGUAG%d$&sWynqNA5L2DcoaD?FX7{|Af~c~wtTwiZIgM2 zSY3u8C0r3v$tJ`+Bg_O*Z#bmABKF~YyZx8@Vltddvnj15LIlAPI)i&s(fr^EbVq9G z6JAttKxqF~;$XlaVJAqorq?hb!7Y zoAik*!12kn#U}HQwlF$r3rzzS@pB78#siD;+2#oQ4Q&WiQM`IZwtlpEg=H{X+GhHc zD05Ik#^@5=bi18(r>jMGK-{K(xrf&YOf(&KZ5zO7bKf@4i8wcz3?nXOKRz9J%26~U z%4xS_6i7l>L0cnD8Wna0cN)*IoG&>^{>_`auUAAiBtQnSA2~l7t}t4_-5rlP^uI!# zEQ}#w&_ljLp3bINFh;*4(tQW2N1Q^qjaXYZH(dgea>9HU$ae&+V*ql9{mO`>MhPIC z2XQ=>L=}V07#r4ULKKqH0zH z0y%SbJzd7x_C_y_)2}%to35ni;32x*V&gHn?5&C{g<#L#-xKkODB?7Pb z(HbHrO=yOAl?F96M6`H83**H`E2(c{Uij2l4z#!Gke4&io4mF`{=L61X#{bb0l9EA zGO8dO*npUH2OqJ^HXv50e1*kF7DkF~r3nD*Hu+Kl3J!yg!_x`(v+gnr(YJ&MTp>?L z>(7yZMs@8Ha}QY6oT;gr$|LjPn(iG|$Ux$R6UTrUWivRii+Cd7;SwGoJXJ@7dOoED z*6f<-E<_)j6VsXzptKz<2}e3dN)a8EK%8Y43mU_%WaJU_i_t!hD2fF98ZH;B4lo%^ zGY)Sjjv3s^)nbk8{Q8a{1_aPyupv`>y*uQfeFmi>u1rb@Xb!cB!~wNJ<}K_9m?&h1 zWnhJlWkNn65EjaT&Wxa5tA(?)aTH)3PF3gJ_;n-SYDTK(;v2gSNwk_FG>QEylsQ)4 zbg(80n0-b5NinNmEx9)wh*24l1|7nF5%&T4h@H7Yu79;dsw)Zd=mNS8(snwZ)83FD`8gZiYOv}| z;UR)3bXUgRAT}-Gb(hPKYXsxQHBoh8S!5%_)oBHp$;8dj!u5bmc0@UrJCwNjIbpI1 zrValSp?5KLBo%NcGLyJL2CH3HlNCGii3_4cE*Tb+#SlgSit$(=J`$Oj1O0-SyXYP< zt_9w`zt_itqFB7DX^Ii3U}QLg$dJYrkPpjAjTAM|z#NGsCk)6!=mVrGqD3JC&HUk_ zKdvh!Wryj=fV_Po1a#32h^Pcis7&7@!urTo`GFz@{+5dTRET^+GS$6hXGKUV!~!3r z(;J6Y1hQT?T-%R0B!llMo zse41_Ujr7vd)@jKLa{&{L24>}VHl*C{px%x_n;tTTN%wDAD9cc9}<{TLF5Q;?} zHo${nrin&{2g(rV&eu%H%t3B*TN2UobF?NyCUH8uetM&Wd*t zX+I?zGkKQs{dD>Ze3EmRgOuq6Ia4t@i0MdR+Z8SG1I3VVa%ud)B5@_bz2dJQbE0G{ zmV;et->XOq9*=C$-kfnArRWQ9`VGuX>qpWaW?Lt{XnCd*8XEPOk&iRn_z)i8+?Jg+dt)Mqd~h!(vGzCeu&vqu9#Mt7iZP7Pn6!e-fZ9;#RD~LHq^rC1$( zPp~o+HFU&fr(*6H07V(YDC847Eh{nu_8~JNWu`+H+1gE5k8u2e_4#u!?gK1BQE@1(OHkC_SS zjR|p;iHb>Bb(DQ{*R<$nv+Y+1s)&xcLR>?oc@x_bi!W$o^Jv88ceI|7(8a8H^TyCh z1UVxTlGv*eNJE024iQMWe&4*II9kR!vjG9 zzh}}T`qC18e8w7vu|b!3vsV%4h5)Nr61y0m$T6lR9LEzR_-cw7iV^Zkj+%h<$folvb7Qs376!aq^5RuvN z*H0Gn$#Sw>8av3~!AwQ0IgCMmxgHWpc6kQ`LZ>mCFm)5yjtK$zw;URXiK*OTH|q(i z)fD)vA^vsXptLvG8I{P8y++hAJZu$L#*ANN=r02-IxQ|j9TPbxNVC~kCpRG8Q5i9r zi64#K-bD>tp&XGVV;ik+?p7>epwSvDDasil2)tH6Ab=zqXy4il##|QP+*BQBL8f{5 zZT#tSiu8v!)F%wuh-aZY9wVqH6Gph!lo8*T4siMg8IEs(9t}B61SPEfpWkSxb+J;6 z8)i}_^3gixUGL~b|Khdmg9<5LToNju|4TSTPOY0tC-&RuCcx@6? z-N5e7kfdAzf4L;oIMMp-UTdQUKmb#c+N1CVzAb4rXZGjekS=cE6Ltt8;oYR}S;#QS z#rb&?bJq^Uk!o*BEZNCERDZE^LL1;-)Qk`{OHJ1BNEWa`Xdr>@An@)M{}-urnh+}< zE`pCOV24{sUa`2k61*qZV#+k^UQ%cPM^|Let|vGY*_nixh59Hz&S!nBE&uOkCUiCL z=?2oqF<-q53gq>9T$_7>S`o8XKWD;g)IMl|4FpEUWReOQl`11!IVPE4NmGfNW)x^g zisVtNGoV)vHaS^Z3`nJ^LUiE3(`a=wG*zZL1Vj?g=+&#D{6$R=d6cPnh4+i{5gO1@ zSTUCv5Q`${bij11S90}0LNYPpEu#i8PW}QuwMp4z9|!V(Lo4)wL5G>CoHOdkff+GGhrYX;AbXX!Qvzh`!C<0B zz2Xn^fFlHXj?xe@wU(RTI~SuV`H9FrPtAS-i}4929=nK1mi%W}x9QZO5l zf+WazsKl98jfdCy)NyCHIc*G9Mf+e#*i`Jl36Ghl81Tp>qC_&Ssh?sm)YX6`Oo)w@ zv-tp!J;V$$pst={- zrM|vzW*EHkXb0-)1$TY6fXKlINV;NJZwYv59SbM!dW-1Bs)aYEvran~F{1!d19?@1 zHbC2K|L>UX)dh$ahdu-gpf6R`UYAi{^7$NB1^Uu*h(C_C<(eEjeMvZeVg^U=apuQ` zz|6l<@9DSpu(}o5qF%4!BCKXK2sj5*gS^sQ?Mf|9Nu%>gO<+m{dn5~55f%d@n24pA zV`u_s_T^Gd08L&GB1o>Q4JGDuT~!kKZOd#mUrZOJn|r)l>MO>+K`q6RgI}QDZjo1G zh8bEK$|qgX>oN6V;+AM$1M;C2;gF>be}yN8;t0YX?i{A*vijWy=T2GTz%0wZ>SvRZF8 z`~`l0F~!8iHt52C!|7tPVJtGMtZ_z`*v2<}&>^wQ!p`xBPozD%+H9P0p*of{lrA?L z#|`@+n9?R?M&>JVPK-Z=;uB&CN1h3JO8-QjS%H@l<#Sw*$EFonF!UETp)+rve|j)* zUv%(0GDfhpLL(fww9+%HX^9=Ki9vCFb>6gKhb;yqAM=FAoGVfy(H0;L=`HO;IBgTy zm4HNHRcmF2VYHA7eFOSp_jKWWYYn59*3wSeFu^%lXB)t^AcLM!aT6kSLr*O7{&m55 zztPgp|6QE>e30#kj7?iXj(jgXhhQ{vj^r;R0Ds%vn*AQSo(I)%Aa72)6*JD=KMz+f zS}>0e<;Mj+>LI*^9@`yOI3Drspu_gj59Q+y_8IF9zu9(H1LTLbFp>7Hs}DBpl|Vyb z*<@yG z_A!;=z_i8juF~NX=!T=el)j-my9CAlnD{}qXQb5*YZB3O(Odn&?QKI%CB+mjm8EPW{$sTLA>JMK-Gn)UYZmEBO@$=h z{$_v#s_<$}&`M(~3x=QAL=VjBv0Mps=y-iSC3bFdsmK(!(v{yBC+s_7TEDromEu~Q zZMV+Uh;U3Kb_M}{Sq*1@te0viER|_r4b*73LmknH3~sK&F?}$3lvP!r#G)A5w z_NoG=o+7n-_?Ih{AL4yuA2lv4<{i}`Cp2rOI_BYGh{FXnLaP!C$Us-)hCtk5i!)8F zY3Z7o$hg&FqiVw>y&&f3l8~p=#i#|nVm@KU+u%b)#h8_YX@^!htLi;gfmF9bF<@+< z*I;**B?O&ow=)<~Pv&?c7=BA8t-12IVtEL&kQor^zFZ7T&_w>?Fv5tMp@vX$tv3|e zOnN{ZYAHwSnkd3(tSE;nJwdfg@Z8lLG}7&jbuY}jb#e8OFa7~V@u)j z#?yz#kz%H+*I5TJyD^EY!%IoO_b3ml?lpBG4z$YDZ|uO-h&2#RV}uBuI(&vsP}hId zkA{K9Y*2NU*prS^;-#~qj*Z9?Lr}jD3CneNI)Go9{n_7z>OH~h#Y!;Fp8C@zt6g(c zGU8izYcx4lG~i@ZD)yFX=%z7x|AvlsgBV?h%!MjU188ROT*ZtVvjk?7rX!wv#}j1e z^iw(3RK=1Jds#8bSkaD(78&XozbIFW$kr{!j*=Ljj0W~Nc!yMC80=<|PVp*63)vua zf4nJfF~Y8k%Udk7;?+66=&Qm!o6Vz0)JCVAOmNgewr#x$$Z*n z&9ljY%-|uPa(2CO7Wwj*F4F@!>ge^ZxZw7@zOz4|w8r_o!F{JMbcR#< z#o8!3@U73{Q33&7_LMXHyVbhh zMur6gnu$>WaySwPw6%w|sOta44H5@cYu*{SSCK3wDp|ECK?mKA6qG3i8k%$$lV@0e z10Y+v0xlaL>TQ^DsDlcedTTBEe&_h>ayU9tm3V5}i^BO?m1;C9&^nl(za|iJw?d~{ zrLyIF2vkYC=M4EP42|I^13z&@mTIq~lXCS1p;;etGWYXiXnqZA~ zB9jscu>;Z-0!;2;9N#Xe8_|ytiWb2(SV3s<)f`m@Jsmn?P2%UQ(5^8*qZc*Gabs$! zFk*f$pHglP5zu-X`wNYTAlmD1&>B!E(6O;R!6g|BS@H(N5nfC54EK>DeF|Czhxq@R zox99O0}xj(AuV)iA+MKxGdtgIa1bN?(pin z3u8&;?4Mci?DD*5+9uSW`DC#e6~)>8{mo5Mx`d9cY;UhfLl@>jd{82S7Fj=l#Gv1! zFTJE^UpnV;$3$rFZlWcv|13zzQ)e&XXp0^A+7`@I?%ZQRhabT!}8I?$Y)?KSru@u3r?`Auch4FS|lt-Q?~M|6;L^ z&XB?G_z;ef+k+H7bqUiM;s1tD-zN9J`kuLjy_7#{uqeaE^=A6tIvS||1O zku$W0XT{fdtV`og8p0Poqpv0`E!Wpy!VNFc7|!j7+uQqXaZclahP(q^)W z#bBTZc{b}awf6gn2R3E6gMw;l$7P?MCm)+Bm}6(Ge+~Ixl6y779<#?@F&=42!GOKJ z<*dC+pi?uwH7fdi7I$0}SGoEPvb3pB6KoajjMgmZS=tC*6ZnFh1rQ2Xfu|67iV8;E z<$&1~S?zAP8U1k$8KDVPkq`7-;f8jl+W%@GxmgDr3`W<*OODz_OA4v0qNft*lsiy4 zhNw;-srEaKF`qfzRn9C(Ugni3FjbX-=FWCH+PM;Hjd>YI*O zWVb?rEg)n}tf+Vsby%q$XQu+;>W^a#=z;rG?a&C$W5ffu(+WB{9U}nzr&Qk1USP)fvQ;dEY7Z3 zYvR5;Uz{_HUfrpOp2NhiMz0DkUY!-i_V&vc1<5aqZE4x>3^qOIU`UPoUm1nQ0^g(H zrQv{z(4@1q3L{J~>Z4H9^$8IWu7;0S(yUL0P17H}u`&zhghq@2cooX6weHZ`X4Bcv zezs-@p_)EUAY|ikb;(9RbCB1*TG`rb$U~VSPTnQ{8TNW$p|L7;Rq*H~RiJiN)dm%H z-7l_22xd#%e#vuaxv4)b{(OdpU;O=G+SShhy{~S!m;5cxLrRhT)dp#$VenGjXH;{i z{)GC@iJ6R{X!Ud?>zPWEugznF(X5hDz1fh_Rf>8ff2;8qeY*!4N#^lQ?}i3lk!1lE z=hsN)VsV3?j8%s9%VLJlAFoLtb(9hOirTQjaApWFNIWctx8fsf;x-SGJFwh?GDr(n zyF+x<>D2AgfRnSuf|EsWCN8h7ZrCm4PEYt(xgot7?LWt}uo@JX@HT`58|LJ}V$es5 zBbi29WKe&!MJyqIV=liO($kH6-kcG&(D#&gv-9#Vx#1Z+hFTpFYyZSG>9^ZePVfsky&Y(j)bq|CFG& z^e1xdvbdv{(P)r}%u0L^jx@AiH0^~DU)t+0?`h4;Gcdka7E%CyLtf&)>bo{hm(HL; zG3oe=hmw`Z{*(;Aq_i^~T-Lj#V{eN~S_Q|Bip#5FwB-^WV{F-yv*J~5Y-g=)d&!f< z;;*4PQ|6aY!^TjY)|_v*{r|UrMQi%oaq%UuH9^s{!d4Z~uo!{o8$D((iVeCkc)esF zMcCb1m=dr)W z^k3G0oR<@%FzWztWB30k-T?TLo$8Fq?q3!svp>(h@=M+$LpNO9{WIbY1$8-P&&vP6 zbX+X|p}-eAXL)_VavgumFLe`z>2BV*X$KOWZ{vh4}`7^M)|3h!% zPGtAR*#YjpoRqKJuNu+|YB;aBdjd~@qnQq-5=N|AP_ba2T-RO7eO%{Qn(l#tHDCru zG8zxv&Zt3zsr!uU;h;-TZZik(f)C2r`{N;=Oki81A0~xmlY+y@Z95?hG z?o{UOfeF&i-T`r;!4p6%&CA{w1ndgl=m1-pynaUC*c<;ndhdI@0b}pg^vg#V8|Y1`)9jt=yODH2Ut=dGKR;3o{lemTH{YwjpHuGz8AJ0mC= zD;x+pIfsgS^G6g2CLvbWtS8}HD(lRR2D$^B-%N9kTfM=bkHfiS-2=ZmdrRi**i}8U zB&x&D>-9i~gqA^*%GJ#u>8c8w9Sk_xkx@;@*rn(IjK!h)QlpzOy$H)YJW|53-gHh# zfvgE#a0dlI2ksE{k@6}Pp`><}$x_`=m`rKQ zWKRpnTITU~*~7YQgSFZNZ7&FaX&OjmhR?W&rxjGd-US-XG9d0iug>A^MYNmIQ1 zc&j5y;yMW!!tdI58~P4LcX;c0#S7hW)sOjt{eA3rn=UGP#;376m-;r`VN3EJje7*> zPsep7t=`nQ^HEFSKwKQPkb%oM>c(gm2vWOG7b?f;)jm&=^^9*;4_O`LktLe?SSJHZ zIHz#qoV7t;aw7l$)IsF0%Xt^+-Uk2)9h7H0wOw{C_^uBNEt7J7|1SvMSa|QQ*ja#U zM3{KI*7v{f^VR@MD$r-$@{)A1pR_07V0?fB*6r}iBBy*$h;{re9@e3pfnGIS15b{GXVwpCi?Oz~ARcw7*4e{ryS(Q`Y&$YIcat7yN%!uzJjmD_yL&m>!aHj~Q2_ z^VByJSZ`=4N_wwGTY9NBhyo*T=BP>Yk@3~Et%YSDtT*-eQ}htJRsPZA->wP7y69x4 z@1^{-hLfOa@MdtPDN8F}cO&D8S43GEpa(wWHh}CKV;y zu`QJ9r!hBwFQmNk{lA?2x0CuOp2WXkf{L;gC2WuIpu-4xC7g+UlBwoUM)@mLag5rp z(~IjEcfRqBikYLo$LQ8Ofr3RY@a!TyH58bjb|;k7Mk z>t*JZpVbU-_2CDfAToSkW&6J>UWXGG-UF+L_=&h?PZIvu2F8MRFhzqeaM!kbjRx|D zcNoi^rxnK>H_+HJN`u@_!;CL>(HFFfXGjUXsOa0K4>z?I-gS@uK>K7B7a0Hy>6J9A zxNm-Z_0=|+0$9JWOW)|_}`nM{jR z+lir5)7Hcm%)moQ;C*^HER~W9+`l9y)Hy5?cBAu6<~_usiux=g9e@P=jgf)eq1Bjh zIKmw5S*E3xI8u9GOxOkzb^14*9f$C(F=dryTe^D1PG0m$bl&uX@`g$3ynASEe^^qA z=|xK_9oAs3wu~HaTarW8^%u8T!NEznb<$^5>W{l(Oo&)N<*xvmEX67ZU zl7FpL;`3oZPJWRi*&t~8mT`r74IfH}+d7XCXv)~DEw0u*poI1B(y+yDdF6bA5zU^6 z4jzFo;pK31fyIWt*8BxZ^i!`^A)h#7W;?~pue_$8arGJc^sg94&zYY-I#Jg6iFd5y zRchW{U~Ky_Ev5tBbjXyFbpx)$WzP<(F*#AFeGfZxN3Qb!8S`7tW_`@s%+K;Kdna2c z6R$WShQ)NQoNmk>IrC+1AhR+g8j}J0ow6MH*mX9;rEPxR_@qRGw+S=PTbY-!1U2{U zok-lL=Pj!xTlIY^@CH&clRuLyQS@J>Juz0gwUttD!JS= zu3FC0lYo;*$UN~30m$US_6mF=#r&p|DZpf(nHq5NB4E#>wK*dV6gFdT896M z&gHY(^C{W%YnkRJG3OQixQo8B1pnFn1#2X1AF>9*9*M|?|HfzH72ruU-#WCKeTn9Z zGP~XgIMA2UQrbaPCY1s(9ysfbX8TNT5K7{j@GRHX;hWWD2Ayn4;LjF9IY;-~0t;y3 z2~ebz$``hb$bA@mC{%Qnqiy2&VzoSA1O)ikvk|&ea^n3`&V~L36#2}ORnvPy^WGf_ z?hOpgf|xCBLT*ijjwfwLujnb#u<4@D+ZN5{a6y;6{P*cDJ$njV{GcZ?-f0^>QOY~B z$&%kiwvBy?VuP(XW0e;Ce9r&qhnfdmL0xuUaEb>sjyrVBdQ3}s=R|tA1GjD4qL3e= zZ2=`91EDloUI6;OWm23zq!MHjm+n(!WMQs4tMJ#Erxb^f{k%y|RZ(BGHGrlkXcUo6 zILGEkOo#h(Z{j?uu_y5uxy$oyPUF0m-I*_;hk1I+zy2^z!7IM?jXI9KQKsWzTk z^TOP_@?3fTRmM)qC-LlYN$)Q`|7lm!niK25@BATN`+WPW9j;A1Vnf{rF!L;)i$`hX z$S;B0*uKvAqUQo|5n44&cr&rmcAI6zVp22g$mq;hA?0}IN z?a6@5Sak{ixG4w=44o1dg5enVY*VD{4ZPt=K5#~q4*^n^&R4jT;arwifPvga2v7<* zV_>i-X$D>Z)f4d!e2=xkmbEAHVBYSN{wXB}Ojdiu*rQjS>YT>=R?UG8TON}=UIDP~CM z&5VF=2g@38%x6%MH$>*zb-!x7xi_9m#pzT0VzC0dZI>rUdwP|lIG=hdSNoLGT<5rL zPJBCyr!i8!ij%hDoU~n;ed$M6j%L3N|2f7Eb9ny{lC=kJoC7rqDRh|sRV$Y+QQ8k6 z1AW6zN?cF`yB)hXXtfeFTABHqtz&af~LzDD>8zgXnJzH`nE2%p4QzLLLLZGkI8 zx1V)(v*Q{b3||%-r-kCGj=D4)$&N#<+jro5tPR;Rx$*Gqu{|yKSI0~5pYN}pn3K^w zqQ#s$)=0ga4e!v37;dH0KA(m{jJ%Sz-Nk8H5Ct34F&PxQ0>%v{@L9~gF}ubb>)gx0 zR+c)7fr=`M9f1rCsDOcfSh&p?u4{ZozK^t?Emv%T<&C1gyZzjSg?ks@JA1F@eWb{w z;+>IRj~A9$0GzXDz3+~8tY^Hp?8oM{-SwvD;@it&I_Th+>-F&BPUpDKfxupLwso+Q z(E%)$5mz{;aF60~BPSayc>`rV+w_LZ*%I#u9x3V~g-tNi-p^)39IWU=YO}VDR!rVp z2g%S|Xr+nhtEEzln|!w?-o#)XhkZ!AzR*D{W?dCa+czcn%Vq=5bfQ$qK;N4JWA+HF zrkhQy0YN5~bu-NSkz22~dEO}-Xc86L`ys z;$$gFX3xz!N$T*p;dl6-)#hIlMb`u))yTDGVN{ zE>1fk2#~-5r;q@7@~YRPJe1NvNkpNA+>{0@EO5QRf$xD4t?C-+VYwE{%mZ5C-#x>$r5pNCFCUiL2H!O zKy}d$$|a5%!LY7^05XAXgNh+QXd0sMkQGql#$q}@{snD;xG5h4jYGP8%=1TN81C=u z@*QT#h0A=ScLjzy2Hw?jL5x;UEQs*?#*S8J zsjq$yoAwQomaj0%71wvF&|YUJ>p zr?|pKT{|h(e)s`nAAdJ#zvqZ?9G8IOa-xD$AF$$Lfj>*^-ZmqV;x@Ro2|i4}XqgYN zm7DtOK6HvGDv7W_HX0Kc75KNj_&$i=ZyapTBwo?tVB*=e(K9-44uqh=n# zL=HSUU$9ibW!D6c9pmwCh<(^%gyjUsCCD>nMkA#6zl!j@a=Ajw%_hi zqkC8YYFFE$g$1;Vh8IIN_siB%D<|z4bOrk?OZE-bXV-K!9ieJkrMt8sQ87#jxm_XF zvQr@Bq>3pC(Uwo~d4Yvu^iZ54-!16SEws{pzhiq{z_4%zt7zbu(`YlaAvWm)n@h=T zK;1Kp&`?H;JV}pB43+j60ZqSW&sC9P$|iX5LvWW?F5Uit)W|+Nt#YaYi|&*HZtCz=EEF6(Ah z>C%+mbV|?&rM+hy(e=5iaHP56vMt#jaAjl0&pjc^M9b zT*8hu(kS*3j#R836`aXP3vCE9FyM2J%0S@hR??B=@YX?l9p3U>$BLsgc@i80rgG*# zO7(uq^30v~eDF7l^fW2!X>g*D#Fgj(TgvNYJ|O2HYs!34&RLpGsSrCBH2kX-hpLc< zMx&I8Vtm{dalUiR#}Y^3DGVy*cQhJf&qRn17PDa~V#ROZkK-{X=9`8YR+}S!IV=$`~J`X$0tUttk)>PW8P%R;9hj_}-!x*sC5 zh9UZEUk~a6H9#m{kcq__;w8OZj5P~QTjZNNAlD#^7lr^G8M8P9=727-q3vcx?V>C& zL)dmy3Gf z@k2l_ropK_OK3Q!l_jmUt;X79&OSS76*ot5;Ce_ejs_6IhkI?=-(%JvThy)X>pmG0 zUiJ;Zt6xV6?gwDPyzQEjc;KnJ!NTBE0fD_6-}UdCo`R}h7o4}EyXkO}NWUG`6^XOE zZ;E$}S=kT3YoUESH9C#3*o|n2|M5{gB=${t5eo6);yFhxY2be`3PdT8HFG2m8dkNmfKg5N0atm# z1yJLcV?Kl?u1b7uFuKd~C2sPxnU6kXIY?1SIc~sV8yFfE$r^$N1{*B2j2$!y_{E=ShIUCN8A^MmRH=f%JY$REK-pnbKcCmJNtms%Q zw%DF}WDK$;6{8S;5DjA*B#?oU&S-w>e7o91!vRzcbfznSZq# zd0QOl{%hZqzF`8!DfG-y^H|)1z4?fe`=A9HWPm7OB}QoU=3EQjIiZd(nCU!9tys`f|NQb6E zH{5_!QWdvv@wW_Aqv2oJLk|Z}tdJZ=vA0lWCq|HH8SZbqG-Y=4hG^-DSw$IsT1;=S z1!Ib@5Cx{V%TmVF;zz*|Sw;zgwOmAbT*tVfssG3$$9| zfFuW@(&C&|=4v|m?cEC3U#yacOcNN?|&L46D&t(BVx{>IWv%5JEzuv_PPsQyX zvw0;K`lvmGSdJDzzU;CUc7q);Ke(>17{@A5U7}egc)6ub9#Zotax`Q zNQzZ#@&35qN1(X=BzOgn&>%#r2^u5z_GSS5hlB4V&VU9)74J+qBSzZF9&J>x?2vXl z4y=Fa#Ttt{^;BBkV}%GcZ{Az{O`*OJ&mX0|22czZM zvw8A40C7PsIn~hS+60?6l&jsw`pi6r!&(P#N=PU>ncAxf>)m24jOeHlqCZ;YVI;9HssX18NS8ja8T^0Plo^VY1=+ah}dJ09o&h*!y_jbI5}RiwZsU62k@7X&TRV*@~`CT9Pz0hznSeBuh%&P zptXq^AZ$Jn8jKaAIYU0)f|t`w_e&sg+>PN95G-G@I3D+F?2`Gc>loAc1(+nJCJaOMcz0aR-Yj6a74sYJ3PWyYf)og%z$o@~DZ9vL^iTNA)o49>SnD z^zAa(QTU-8-5k}V$CjDi#t1S({vy~Q3n#ldR=$D(Ozs^3V?rsgOIN;7q>-^R=6ny~ z0cC{PCySj0WcGrPg(C|koB|1C-mW3K%B2_*XMhjRSOJ%RVG7`9%zX;zP?x&5=U#;B zf64B6Gdtk78~rp#9G7=TMm}r~saA$OfPN*VF+Xo$8xroo^vtYCkkjp)oYy!yy?`~dhHnaJ{>{G7x552`enyIS@bL{A$YMQ# zHLnwd_P}8LBMJr`7mc>73LmS?>nc{{s(4~!7lM6H7^lJoUbst?Ci=w0fKj~f%;NZ4Yb!+= zq#vNIF*-F3Dv;iz;BEF%5&Kdzk0%TUe(WUmDWL_!% z(wG%YTj`2PBIXqfaX#F&hn4?O=kXb~2kXM`mro;4l+tk5@LBHHFkmY|t?gk${xl=N#&^$U5%PqH$N^zim1 zg)uKK)Mo}RHw|E+0gZ!FoTR5w>fgW#dl8yhXphRCLy!>)QsO~?b8dr7h!(oj075FA zc3#4v7d)fO&_#F0G%oHWCMZJ{vPwuPYatoNOM61u#QKdvB9+>xUIcI`B~VHXc11QH zjkHtYXnb@SQZ`z;L+e_FJcO~)Iw&vH5Qx}pA1R+BZLS8$Mtc;R>>GC|c1xsRn;Gqq z8Ae+YG!fz$5(N^ifGdlY)WN_07=Xz@HZLVXRw{&0#1b<)Y5PiQ==Mt^#Gm+twhx}T zY{F|20NUz)pB9c)uEMWkrat$3X!T-UN0ZR|SwzWqRuq934r!zp65+F-63ttmt2MfJpkBBuJ>yQnn^7vOm{>PNA;T*6jRLDYIu6abDN>rmI8_V*w;UsxT z&*EK-W!9_`6as-Z01%s`J_$#}e>IkI<4b|oZsEZJgaGv*4E ziB;omR55E{C94+G{C*5o{C9;+AQtuc7HEmX8pbJx-%}o9BjO@At#mxh!3W}ccv74O zAmYP56^$!GVA~$F6WaSB%73CHix|P;Vj3eDUpngWdDFJt=_Sj9gg-qFn35<&c4euI zU_G0xxefrNP#3cbH8{-e90|*PX6v<+0OcNE*(79fMyA01PK3trcFWNLB2i#(7{fY_sacF8Hz)v*g|;ZFFihfPe1 ztdIPW3awbyZ7)ib4vp+t-=|()yu?V&;l!AYVHI)liqNOM`V(X-yOG0f_xJcc=02=7 z`-0h%G=d#KIu_`&4d-$q1&Jd?wC|L{s_7ZV@XYm}{#)^Q9iNI?!e{}JsEb1cBE(-m z%7E;G;ERKBP@wIkk~KGID2r{>NHQ@4RMnVv;+!058>d3V6w-1pGeXs5JZtCzS8!QY zaBa%UCwn@n7RMN(pkbH1!Pyn08!2Kt@br|WlX8rC0bXm^>})ufpRFKwv@9BdE-?P{ z2b?m6(Add*4zz^)j=Qnd&?>N@3`alE7F=p0v(5n^h8+90yuU`aQ(;D@IMU+Nm%#Gq z7O|A_SRhxY5oilIXH0Ju*%?S=*TJKMFfwExv7n&lNCR20zw0XKdNxC(dv`px5B4c! zZtr7o`0#*ZSR`CP;QFEB@H528Ov4O}MrDgg{BRG^21LMaPI9ion!9Y!~10R+?k>D%@O2b zyhnWFJ=Q0@m%Wh|p&L^dc6gEM@XF4vkbRZ&eMl|$@I?Ih>d?k`*>x~yXC1a#oq6@e zjAwXjHA{^tBbGjRRW6C)s6CvP9eP~2aQ_2scRm3MOdmE-HnNhEam-6(ol=0j7?lh^ zPQU>se{JIie{e{t%*Tx9@8lOdSvPxNj%2K|oFwXC;7&Rt?PE3*DinCMMP6)>Gaw>7 z8czK)vkGYOm%2ufEJ1mL_(%+XFc2m1ckY}t;t67)Mat26*?}QJXYX2%&CVD~2iDQa z0xhdO96paq> z4PBHHge!(FRph0G7!s-VX`m!!N4Yrq9&`)j1cnK2r~?)nZHzZW$cLaiQXA87e?i`3 zzzh0-E^$L2&q7%ea{ipvCig=!_3HE$g*oessaDk7u(QDeccpJqISNLhd>oN!MG)uk zjKM<_VLS~l*IsxZ1h6ghAl{3T-^kR z3d&DNl%pJj>~Fy9aX&=q2(74TH+vWu zk8wLECs6j=>eIcv~_#k9IZ#V}fdY3GIOd$IQB?i-57 z;{!@9jPFRTKJguUU9(T(`2C&}q>d7}aqwNG28x8@*VX^bd28xh!;BZzMw!1x#9-{wB06S%N0$$f z;@w1g<4Cc*gR{s0ioXRrW*F!j-!+z(tYRuOI`GHrXNk;|<{><8F&xDT)Z2*Id%#i@ zH~W;5WnlG>O&7NQ4~R1;fhIM$OL(PbLt&IU{%(a*1`|+@stPOrsysd88poQXPO(?i~3!6yo=PmQ01$`8R?u945 z_Crn@Szp4F(8R(F*kGTmLjM{M6SD=jf8=nc>v0ya&f1k~6F}i_PD%0p)}d!=%3zd+ z#2qc}Ysl2*;$(={^`U82zrwfIDsZo5%X6fP@@Xai@%f`#!o2Fj4y?*~Li*qdsv)=K zFo#4rut2PfWJg@uXKvup`*ws6tx3-%nU+b_a(BPLTY;W)eu4*`_LbfW>~&Dwacrp| zuqaIF8O6RP9Qd`()N=B}3BH!QPp#6}evgm#q~!X9mBg*=$-Wrv+i6XHa!qzY2h_%= z)6olc+EKB`v6P!f@0imX%Z5_0O@j_PTu~0UrBc$8tn73`C3@7kZLzxoUC|CPLJay$ z-Wfi{TDq;lh|Ci=|7V<zJ5u`cEIn)M;qxtCf)4wbhX%9R0A6^@{yDIjGJoVSV%FTWuM3%%8ugfU zkaxeI!P(@}q*Bhx^onm8%6zsm$LcElwU8^ubRDS@zB=-xblT^QQrIIx+8E#d92N>& zooW9RkUA~)DK&c(Z~mw4v-XX;#P|X0`{MoWj682hLBEmq!$$>G< zwu0MLZt(VaF`qgW@DTn|fH3$){~qeuyLB))Sljg}pS4(X-_Hp}kChnFC@zs@w4z}f zk#({fQa|j#>UA%FPW9ZkT+oD^EeD_E?r~_o!HF`yf)R@%cMg$kAonZ}y6x#+y0Nst z@fiLV?l5jFk#$#0UVIM=iqkzE{BiA923SAFd;9}o0I;35ctB&MuR>%j2fOn6QtZs&>`;{D+1De}qEfdM;%tE&9B86MmI2T=VW9*k&gsF; z;ge;@%}bbTLM#@UOJVOZm+oj=w1m9)xeBh|&FIAUGDuG;w!BY$5rV(4(~_V5RFHf- z<`S#s)8Ru5urP#E<2D3;BIu@~-%q7>uyMu#9xu$opkmni)OMd?P$%B=2)MwEvrw$P zmQ5A;F8SI-ys%HQo^sJf%wU%0;yAg>Q%+_L@@Oy>qbfOK#Ezjz*L2jsS_4!E-=loO>`2ofr#gc=Qfooi1dYVx7cqf8U%C!8{YR%+Kz zc=icTj`e@l&)p>`MwYVQ?Zd9OgR;S>&sZbTa(mm=1yDphO9g~l~MI8Z45|)>Y z+YXADgSwSK*J|=$$;J&)P04(qovS(mDFJJH_$+H5D8YP9XHl5a>S?4S3~Ovyz@MX^!Y z_1Q=oF}`FQq711E`~+R#$s73z4Q-H6 z#ndg~t*?RaLA7`iAhLgByM z7^op)rLlGUlSk&oH=OcygSGf|@rG6FjCm|6C`-up$Xz^!$x|m|B%N>L6x+!NuXyL%ny=+M z8%Z&l!;+0t&S(70luiNK&&@)viM9$gZM{`ai8(RyX8V~BL#B+r`8zxx z|2zDJetdRhp8D|NaCrUd>gxJ>aD6!V-|y>J&-i;i=whB-4_@=>-(IBqLY(D2yTW4f zqP$nH2G~#@4#r3Mf1)&N_5Hbq*^Kh6r7(VW7z_+w##|ADc0W^*oAAsugR3t=e9_*) zW$P?m=rYdGpK7r%`aQ!K7z9Uy!QorWxgNZF4V=#g*WVtlh4)+*sm}R&_|CP`!oIz< zI%Q;JiJrQ;nXpDF3}>r-27(YZAMAk&L+aMhPPh;ogkWmjEJ{(qj+ z+WS;}-X5k*{S>?Ouss^B6T4!9zhF49E5x7SQS1hmXgSRonBxbyJ<$&Z@}AOO1I=Y= z)Ftdud)E&ac)h?Hxi0$TOL!HhG@6JCFSoy0?6hvYqWXgj8xLUW?7&vHWBV!!x2 z=Tp2YL;aqgU-I*N{N`MRR25!W@T0;is{8p;=)WR`{SsdL4nJR6LU_peksOz${8Q4- zpD~yJthjox>?`!RC%BG!I^z3JDeas)Li(Kfk^*S-Uf`tf7J)md+R-= z`|;2}8QPE6)DWJYfLmJs@$%1a173K7t^4zH>1A1;<)^;*CG>G6UA20+f^vht28U

r&kDSF{rNDE@}p2w^M838rAOIUv){`GrRH-he>@~L z%VdG>wcN{A#l1w7DrVqD@-t*Exb^H?W)69fvqBe!d&d00e`lu;AHMz8|2zT8DLlBw z?)SsDMDaQCyEspBksrSI;bWI4WD!cBMx=#70oThKW_&t10em8>Tm$pSgBn`!VG4~hg@SiE=BmC|e3z0Fi%4NOBfb$8T1p-pU->yB;62ciLM>)SO zKDNQ_9S{E{JzRF<-!ghWcut=oQ8 z34I9%Uq4AfDe=>%d|SLdzh`c97QgyN*#RBE`OS}qevq;s8C`9cx&ON;`D>y3@`(9T z?3dzz<>@Hy@X_Jr;%&?~*lvVp#Tj!w`2TY54`y6T3 zaqg4im9s5ze|CS1g>(KN5B(2M`SoSn0ybc^H=efoOL2*VUy||%+~o`T|0yl&rN*%% z>jL-0$5{ENl=b8IKEHK+l;2prGmD=!0ct!V_DlMKCvleH%xY?MLP!A2zJDq=b)=TW z)aE+Z@6)T-h))cZbN;~vObO9BzhziE|H);Tk$_A=x>#LDd%Do)c}=f=;Uvp2n)((i zUG&tG9=#uLnb=^q{Chd)U_2T!P!hHEwN-;+DUw9exj9Ke!{1cqEE$x z-wq?xM8D25_Vris|BScj5n=rT&XhZC*WipXT1@+FVYV4cgl=iGeGvG%=IyD?lmM>2 zGRGwjuCE6`ioo9K55OD{{2(Wi3LHG8>8lT~keB7mQnjlQ+U4pu)-E5<7-(7l=i2x` z!&lzrisr;q|J%HW6;kN*2GG=pzFctJ#S+T(bF9{=LGJg8zwm~C2EOg;#U8Wg&)nzp zkTXogeI1NT7KSwTY82Cz#w%B$B#V?cYREsM449u()T>}V`v?0yL-HT z@Fk0_yPwnjBKVhO`>iCZ2~V?Z!Fex)@55pgE7?4cZ60&_IhPYQ-?dglslWIZG)t;f2T4Hn&;?6E%T zp~PAcm#aw=zL5ixsEKQ=_+Tm4x2m)z>WV#cyzINbiZ6enmkqmu>`jgE!Nc{?l*X4D zX(O8$-IF;>6JrJA?yP>$txeZh>}H9>V%cbs8+T;ziW|_EtC5~f6I(W&9d8rR7vjH+ za2LlzrX-R?dH;s@o-8>=5X0@EqkkyWBuV*}?K^LM zSh8zO{WcJ2GoC)8k*BhGDdfCspqx0C(r}LtVd%yd7r;~!(v=W@z2ispl|G$lBWf@g zyVb;6H*G3Sks~aiiTJF`l6Zw_CgnAjpM7!!%UxYtYbtyMj1njl+v3SLeTgTY0!?-C zl;&I8B_AjVLm)cRf$+RzhZy&L=?XmVQKRF@FEj$~IO}jKJ#VmKpIFb@xN&W`_mMKO z=>l}DX|WI7E*+sk#~d=X44%XmluU1*Xoxq_1B@F0p$6&5^yheKW8L*NP3F^6kA9~+ zWJoO{fp4~u_AIzzR1dE;y;4z$bVQRrx;Y%wigA)i*M%w7uIxZ=Rx6!ZBZ_s5)3u!B*H(-WdB7zVf zUUv9_`tlAD%cA76A7|3FIlA~!qm==(^bB2k%z=dY?;QmG=(9eLx3UHL zA7btQYneYRsVhD17qPwGFaq9Ue&k%0Z5<7lO~_0RS7jzX%#YxXH*ynLyVfya58f}E zBL*9wz#w-V@c(Vznl2CXLk~D~4Ux+aC(__AJQ<5k1z6;6f>)>eMa04EDgAd?{5&>r z?)ss7A0b=$CwfAfe>xhU^jM5wYkv~U^V4x=t&ChWOrNLC*w06GK$&R+GNE`{;+J{H z>8_O5j@P1fC$y{ai!>1`Q_ltKkz2(rW>KO2~06$q_dx%7{(5J2b1jl&snoKdMT#kQLPC1*350x58*xRhf zV{G6ynlGBJ*-kJIUlhOMgwJ+4-Ti93Sz**Tr35a%UE@8+I+mFFA9fx0y^Q7&xG35rS2{5R8iq~l@8f#8h;h1M#FA1>( zLH^OF?|y%O&*|C`2UIxOSztg}Pe+_GBMq1GPMgK*;bFxp1wYbw_VGRrndTDY15G`_ zoBR&11DLt(=n6b@dl!g3C+>0e6!%S6ld9m1Huj)#hsluhZ=A92{3;PA4A|=rhrr<( z0xUf-;}nLG_k(YyoEXQe%!X2TIQ}j;lV$f8!ho+d{DD=%Fj*lt<0XFKijbFpP$mo> zf2Gd!--LxLAs`6z#Doy1PQ&(qC7xEU;kA&EwsL7P=xG(L2^(tYNT9Kv|JGQ38o87W^=_MobL@7gFw+GKdE~*Wt$wk#3Y>?hdG*u2*l_IQO za9DbpCCW=nb1e@6C>xSyk!dtawFitDF=y0+pFSJ~3nAXaj?IA&sHc`6f7ivy zi(xZ6U?&6E+UfUxo{WmL_&od>kqW^z^n7_GdA(NjMn4@mi0+MOZ{ z81IQ-l@9xWqi9HJkI}?9;~VkNOO)(U@ev7H@SL4sa{YwVoPBsht@bHYU^_K%O*Cc2 zl8jZ`ekiwf={D3&m0#X1r>{5fT}$0jScQ2-Q-lk zYDNbNQNB3PDUG0zCPLbtrb8`}FtzVWl2xZFp$0PeS6cQkf%LXxd|`L&QiqQr|GTmh z7{*faaz+j(x1?1#UDK;r0uNZW;fonb2f${)MMhI*|p7@H-fo{;&|%%2Bpc zL_`e|u-M7y3^|^_5^)X`1~?vhG&iTBf&(^DI;G*D1X%1V7JlG(*I5ocIWGOslyIa&8M#Tb{S{$uwP9JaKS2Zyu@+V_>GMsKFYrHG)AQcIql1wIikjyK%j&*TZT>eL!RfkJdw+iA|R2MF9fi{uoZk z;(~zsYO?4dNg9!9k^|*&lLfP~C$Yc=U$`?|8bss8u4I*~e-YzKVte1rV2T-R z#L1S$VidDvcr7MDl;g=D@?giWn@)3+**vE)?xAvfgtLv=;0QU&bBu$g`557Sg#L|s z+lK`wrx@4x%TjjlM-+I(PXjkS@GXs(%H$w*pfg9e^@vyy&&h!bO z!I)xroxD-$6NuYHxV8mPrP2V$Zavk=tt*>)v0ZH1-|4HOnBtL{OB`#`1lvG4(`+W( z-%_uLi7O9qVl%7}A~xGOwK%53*RnMds&h|!kDd_iMXpcugvMxNmd7gJIYpxJ zry@R2qr#`kn?N9QZN3oq>>w?7Kao% zImFH8!-KlVW;q-#Pzz_2~{xFm?g3Iu>m=%3_(qr5_ys7g-{7m}=El?b2kUurV?I83MdAzqea%@(q&8e#1Qj4E=`$!!&+z{b zoSxZnQWDt>V&Y~e#;zBg>F$Q(o%&T`B#pU)2z}OeyBN>w;bJr8jvPE0Bf)JKI7VKL z$JKUMSK=_9`oSGnEt~hqR+`y-V%eu`aoPYR(f$?~S zNQ(>#W%tl!3-piass5U~rB(}Cx?6FHjJFz1xy`+X_BPKUe2wAOFKiW^-x;Wbl zzi(e0>~ijQ2EU%4^aeTk5d4zUN02eh;1dM;mSa_O8ZFOSEiS;_)Wh%Dv|kRwrw&2*L~T zO1e)E9}I0}nw;h0>`SpY=vCu7*#0zlgcA#_>}NUMzbjVLc5#t2-ZsV>2bsRn%~jak`PM!gze?kF_YJIOoZSRwPq4Q5YBS zs82cC3naummjb#{F~pjN%X7dUJ^O~yEsO8~?vcbbi>%|PDHog-?;VY^S@Gsg!4++s zQXDNE&3AIWt>gQ)ePH$HSbbN}E`~5)n2CkW#(GEkq@|EW&x-eBUtNj9BjcScKa+uQ zt{gWj@83Rr3auV|<=s1HH9QOrC!CJQ_cT{EDIFlBFk5qJES4HN!PTv^+YCsBTa_%v{IlTSM#Trx2pkZ=M@%4V{BJR4wuq)XE}-L1 zJt&VK_y#Vu8?+8T?U;FE5iUKp^%OrjdPax-M5coeb@P$Cv>fE{+5H1;W@yPp zYp#YE{cF(U2x08Nvv`Am$KrnSzv_z{kbVd99Q_L>t7-*@WP+ep>iwRgr+ha|64ew~ zasG`POsJKbT?g-q-`s8B_uSz{7?GL3=lphtKZ&j zXf-$Xc)tuTrRvRZ?(|*=FOiGj)h#`FyUz9#D_PdEu5S6~Z>(;scsm~FdzZ|FjI5eI zPppWE@Fnf&QWDOTmX&do*@wE6P1J6k6c^P-o{BJW@sf~dUiDN}vifV9+gmLJki*K7 zRh`c$U6@zYncz(b5?7BR9eS&!{w4^LVOHo(A8qmWL ztX~`njJ`FwO@zn(!Xy zbLbeLSSZwv@7hb##}76`z_fj!d!PyK*%61dF5c^hm_C-~ZltuHKBQ&2qZ#SE2BPB=?YCnZC(g%^> z-U2pykr;=ft8W#lY!y(WwNu9l91yr#P+DrMn)EkNlocsDY79xh_ET9jo~4zB8EwmG~Bek+YXfU zu?JXiB%4wjV$gfy6#!|UxzKsXJN{&L+Xa_}FN96OfNQ9i6>$n5)2yKJ$NPS!?`MaYVjeqq_m{W;89(Q#eCc#wdu;3!?>|DW}^y ze;VmfH1`v%T2eu&b z&~G%4(2182M_rHL3=1zjE(VWP$01u7B0u6!;N0j1HzKOa2W7+~qSEmp5Q_`3#$za1nEeF0EVB_*rt-ctmxFAaLHxhG5>ZmCtT4K1w(P2Dd356@a2n^z%ldT2&fUAgy_~)Y8Yp&XbC!j!sD$s8_f+y%GX@5xj zvC3q3hvhap+}itMA$CM_#wOU**%NKO0sj<*hyL)d?z)rCckGG|zFg3`tZ@WNFS-C> zHH9ZU?x~IxXq<4Vh>mqLihE{V^U~MLinX$OHxXp*Z?BinVa*#@m1FZ>g9E z*x0hJ@ItC4hLRM9rz`-tkb+f%{$lMARuEi-0B-}47KBr5wXEo3X`x&ySJf_eSmmNK z-Hqf}tba!>8f|tefkjPf)H~$?Mp|>dRSoN+UP+3&^_bbPiP-)pyyEN{;=p%>MwpEl z8?#3D=*kSVlRUW+-2@EQ!m5q7qhE+Rcd#8G;FFR9_aNRl(I}%dNDAy;Z3Rj&<23A6NVy9R;b;RlLQR~lOQy%PgZj2=Pp2X1l;b6N)%rWMenjE7Y% z3ScgO66O*rf?T&;{tIiv7mYMShqJTEx}0^*ca<*exf$1WIW};B;K~OYg|o17r&Ww@ z_DZB1jM`A94oCQ`$8D4x#vSS8FG^AHma6m7G*kV zA;w71={&c|jE39GKD2jwH|2p;_mMw(_N_2DJ?s`HY z+0~YL3RV`x0u_;HCy3+YJk-8D)9Lt{yeKP}_u{=2(AZs?7ja!gtvKZ11eUI{hAk)7TC<<)-eCrTUuIh$xI7(CqQfQD-Q1WkkP_hT7UVn$K z0se&#+|5Y5u2Hrj^%s$Hoqs#L$g~sFOcfpC8k#6tOBxAg#02vPQ2`G-swl|FB&*2o z$c|B{J6WQLem4QK=duoGOo7SHp@YmO;)(wdSpYY&Hi`?by1*%6 zz1iIzxesdv%Ur!F7(=_swq`*QJ0>c|Ct^_^7FZnmWU2n;Hmo@}vOWUKigmWsWu;7T zH|~^53(V``!7cs$VWp+~$#jpa;0pP30xUsWHw(rL?1EtzKINCLSW1{sU{{$W#cyek zP2h1W40^Z}v-yNdUebl0UBdc8S`&}Z^B8qIiBT?+4g4?zN{4cms6jjKT{vED~>+&^-3!lq$JU13GfVT=Mv_50$Q&?zx45bro%hc*ml00rm-m9BxX` z_Ndr$xW!_m%s1s1i#O5>618V8ZAPC|8EY&w&t{Dmt}U@!IhebT)1mYbOkd z387FV(na>lA$W}Xh=x(eOKk~)3K+{W>h-3pLE?iCx=Lh50O@?~nb3|$8=R2nIazx4 z3M7X4y~|+iOvuH}+mx-8N)5~>a8kCO$fSIoZD936$ZLtjj3HT{Q-Rb>ms)}Y+Ly|q zQju}e?+$}lI0paiOE4@6_d3>?4V?_dU^g35bIgVe!3r|PN|9L)!zO0aih0-xn%!bB zCl)f*%7}HlGe~= z;;0@&SuBqn;l&UgqNTxi6?3<&awzexU66V~pO#sZe<9nkWs*$e73dc}-#8T=gsgIl6<-&DC z{4bvUH9lNl;?MR0IK6_!pN9u5o9K;Uxf)3W$layA0GzT=CKJni02?4?$)(7YACypm zUBXZZS*XMK=^i~j*TA!Xg+Ec@A@)QMLYa`GKD%#GQ1w&Jr^&JefG(^&`=Kx2BqJh5|m~@;|<-f6v(p{CM*-!+z&Y5$R<{ zJ&Z!0EwG&lH@UgZfQ`s_&er+H>AX*4oqfvVT zE)8)VMmx*=;3}uI+14&a)Yg@Jr`^Guu0%1AW&2i4_M;?osw2i%x|RsV9=yz=wJIaC z4dyzBvUh!^XZCnWJz+9S_kA7pC^u)jeCFFeo44+EV`6|Nr*2qnu(Ql=DGVBgLTuuw zxx}|S96UTlZzqhO$p~RsU8>_a{0l=!2n^f^=Tv3eglFYwWU0-ao!(-|HUKtDL&hkk z16%eVf}fAS!&=DM5Uc>b3JC<#n0ZH*;aFEX&krHsasIgUG)y|{6tB>!DPvjW6mO3c z%TLllq>0o*n3O4(;(h3bh|AHb=?1Hx?cJOO6O!v&6!!3@Dc1O0mOgG#U-<%=eV;GiKvHynKM&cG{yU z$UQqzSXZrB9J0^OF@Oce5B+Ex>6Msk&#_A_SfE^#iHx)$H=JE)l2fDIr3Ez*)X`(3 z4tBA0!rb36LjQ`NpLU})WIr%lt7t&W9H71swHTe(+5v+M)nsE+58@Fa2 zVdi1h@e`$3o~1~keicpvyD@)iaTLCtEroQvp-fZR^GY~|O@A4(mCm(t<){5`4g4_X z6?FYsF=yvZCAA|X=16#ji;5H&_9XOE0ybjXtf1k^LVY`~oFdvgR&W~*g+nh`89;^E@V2*i(KrZ9(C zsL5-~YrbN}ka6@0-%b0IJ8qevQ;_#DMW4>-KjKln^EaU)bknY<*4UK-)yGfbx5iw% zo+&jWD=~9rKIfeb@xDNQa&-`LBs0GPxgTmsx;dwWS11(3LYA_+l~_Uzmd8q{@lk$= zaAGHUHqy;3D>*3QelGZ8e^OT6sID0|Fk=WLO;2BJIR_M;7Ku|9BC z9qF#-LJoM+p~dVyV8^g3$5s!aW&5Td!7#jb--|g72+C*b}p< z%j&V5DTU|U)+}=pP-a_gfvpKFb|vMAJH@p>IWlTpte~T1@zisQaye7B1-?$ArM3QW ze+yj~VOJN*j-HhbzNPex=*%BNG4xL3GTR~USTuH&hHArd@(GDLN=>c>`Ie^@4eTgz zP}`1f1bH~$AMp{q>0$)cyzBc~DIwEj>TG@Hi~juuBloWux$*-52l!#?iID?Xiz;84 zGfRm&f!DTq5QKQv<0NEvR@nvU;Pz-dQj5$sA6Kl=;=b3QQWtaN!^$Aagn#%mhF4D5 zI;MglsNOli8oRp%E}Z%JKTpI4tx;lqh|-VV}h)6=rT zFVlzcqJ$@<%aX6~{S|)5@U>^|@OkwFF3LvQEhszcF8Etq#|h1Nj`n=9PTP0kJL^fU zr*;ebWs7W0`p`07f1|t&KU9}qqps4&bYD6?p`MoBdtg14O$yqnKf&wX=apv(Xj)*c zpiQLZK^>SH5gEGkb({!}ML8kHj-QOfV1jj_=UzF4O00f*d=tAmaUOQDG2?EbHzQLx zS6DVdN;kDKiyFd+3(XoHOS~j_8fE|Oav4WzDKt|E(ce;|A2!=MNPH6N^bk{;h>F|R zG_KpR(XEyoa^-w9z{P8-kM{@^MV#heHtPR?h}0g(7h?YL>EMkxGRLN9o+2g~g;^H* z3D7efE}JQ^7o~OSJ;lPZE=y*$y!3q;mYu%!lQop5kT^WWvB%i?8Uayy76I8vY(k&@ zi%5;+!`UkEib{<;S^=ctsVNJJ^ouq#e7IOb%`>Zn$nP`T1$uGX?7o}(1_j^}nr@% zfuP`j_?rP&K2cfpW@9}T%^kRHvz&5Lek3VH*?F>_NBf`mMDt4jDi!aMvvR~l8MF-i zTb84!j7AdIl)$!J>EBP@2b;P&`z{^~GJH71n|P8Fk*W(PzwFcb<|=riU`mHRIRsAm<2ZEc;rocfx%5 zR*#E=!N-r@9ntyr!*^Zht&ULV-L8)buYg^;2xjD89Klh-Ftlu>h6 zV^?C?bTC7fj-eNWm(RCRYShhmg4f4lu?!e(O{9DA^2Ks__0yLx?8~63=hbb9d{7W6E+~MeNHxTgs}GTz=ZrIbhMuO(*e}%+Gz7nJpu?S!zBoe+Mpwv> zFwfz3*kvPkQX_Z^;s|PK zID6d98B%jcK?H*q0gn&Vl(T^pC@XXB?NXM-6AHV)TJfaS^rL+sjg?7T1@m?IZRkCD z9`UF5)1a|p2mQRDr(-6pt&nd?O>{z(16N1wW9sd4@Y5gATBOpSXHt0)eW`?$RF2lj zGE2S%?UUBX;ag~EeI*R*7e9Ue5(x0%MGCM91pK_lXX+_sK-)-_FLH+muQYf~y3=np zo~Mv;PhMS!Q*6@bj((L+Z#us<>0igx%E5!o zN9m2{Jtg2%OF3y0o(j;?cH?tF0dsgo_`+9fcX*TJ|DSyFh${~?UwY(0IC6mE z=`tj{kmx{GNLj;UOEBJpJH)<_&j{#e3p*C1!zl48O62cp{)G|K6DfGfT|*$J4D|UO z_P`uoNOy5N$mNQ3;JA6kZ6F^QVS}p}Gpvr3eokxALDCKL#l?sq&*0ni+#4QxN%JS^ z?8&Is1O1m$J_NOS^PQB5m%eU3>}0vT0d4T?@X`6qG=$q%uNc3~an5D(PIAK)qlAN@ zQ?9npWh;V;!%GtQ3|~nxJ9KocoFw-S%t73)98P#d3&4}7W%WPL@o2tyOEbTH8U5ft z$~t2n%GbA*C5;C^)($$86***5_7^_~{jM zK>W>=PMG192`b8zFq_fz_@LP28&qE1fp!EoSJi% zyJol@|7yD$O%~I?8IKxNZ&4oRZ4-{~a&jHZ(J6zRSdycJL8m%qzQ?PR`(pR^`$B(7 zB^wt`Zu@;ffad~avzqZ-TIh99;=~!F!t+6?|IvOEi$?!pGZS7IIO4x#r)E4>lS=2U z(HR$bU>Q%@+F7un^f&lp!c=WXJhnlWZf<@;rxZJMopy<+E~HwC^GjiA>yEBHUIHV3 z=s6`JW^sP=T%P%a*t2utrhpLO4N-Y{O3HV9fc96b&1lVe{|6w(su`(wxyMr2^2g)J zs#>maGxhMm(H9sAXG`lcYoe+$@M2BqC<98$4ZIMCD)QVKtu58AK<=C`;Bf02(*TwM zdHbiQaI3XD`ux+KRLQOOWl2h0b;K>C+qy!xFv4=0ttpO_l_meULG*BdkFmXkYOuuC z0Rx@U(7QBw%dP?XymjOvrox^M16`76mq0F3qbn?lux4}(v)KyAC-ZhS6$Xxa^FD4u z#XdyMBLv|+q(joNtZzwItpQ}X#7RJwNs+`9Bdf=Rz7#qtrb=L;LUoe?oj0nMmAhiR zVNaNi82~RLf>-3CB(2P}M4`&jc$_Ci=w13cOC`E=CxT|NnqDJ^(u`pxUf86G{UwGf z@-q8DO{GZ!_@HH_sj*ZM8nSNz0h~!4K`@+g+hS1&ZEK7Lm3Rw%*v+Ex)J|!?pKzc| zisevOHROz(@54%*p;G{0z+c(Jw6RicoA7B!j0Fk@w@1(rgcip>P2Gs$lAde;)7~K& z0eYF^0s(Q1zkqPRuc!4;Tjr{Yx(nYy*?`YG3?%Mu0E@J|rOK9G00(MQG3n!AmM4R1 zu~MqH=Qs!l=sgjV8d>xln5Rz{!-_tRJ;Vv~TRp}8)^lqrZ`m9VZ(=L5YYw8SR;7Ph z38E0^j7{v2saQeZi;ZpWdFGiKZ2W6ahOjW65ut&>0{@~H;aPL8kU}L%C zVL@t};vWEh3O!&$kEa5+#!0|_4fcp>3gKpko3&i@8+DF2g)3 zrgD1h`#C=-=bnr>Km&)J)(dvQb_?v&P*kq4W_pp>6iPn-EKm_p}dmGRtsmBAAWoXAwouWINqlLNI~L*d7|g{2u0v0wlgLhn%&{ zIJAW~?$RYeuX@NShw`K^=vV}k#my0huZ@O_#hzCqG7Uw*P$?QCF4phMrSmS+|FXgW z{NX>~n27|+wUM9ja``K0ff(jI2!%JiCQ-h(+;-ei18)m^iqnsJwFWfylW@w!;kPB| zX#Wu}2P^rNhSzX5Zc85_Bj~&agkYO2_OOD%=)l&o3Cdq)Jth`5(#n-{9K5leb7qTi zz$qH1D|jSzIVQ3G;!*(iR7-1@OEAiI92G(ebX-lFjg>>1+j1(mtaj@uOkDF143fDI z+YA&%t$aOs3azvrU1D3D8IQ}eg{|dGTE&I-B>*`SIYQ0gK5Jb(Mgi_@SyZwd2PKpw zM?jB4boQB6r!CJV|BZ7*M}{oVQv*_jhPC#;A(KeJzG2t}lF4g1@;b-7w8nv`2#H0p z>MT84EEuD(kV-o{+@?GGgFPmXO0O0erfO;KJk6@*d*XS*!jAMvJadX&H{Q%0sj-G7 zCnAz*sx>_mb2OWTmRf)-(vC()<|q=B6%(5O!BnD=1Ix^*N*zf(Ub<@|DdVD+`dx%*W2@F=p(r`MYhAQ)&)ZU~t^iC_HK} z`GNIm4du!xG_h&%^iY>ml1ih|Ez;ioNOekTyg>=|)Afea=w+sPfFf1z-%3>^#8Xu=fRQ^W@V~wz{@%^e)F&gdn zBMx_k{6WdbV|Pl90<|iFIH0A@s)$L2Jr4d_UwKLa8Iq{8JHokvr#6+tgvU?Mxk7)z zX?A80&bF2D&b45M%AOk%?_MD3wwpz)1tR5vPgDd+hefl4eceGw{ijgXwIGn!R z0jA4O{yy~zN$zZcu+v5#`WBSP(m)#^uqF{Q2#-O~w@PU7ku=e5z~CdC7cb|gDa z?Lh@bT3H#^rP%SvB)VBQOi4IVjd*0)BH}m9dlT%|wQ@VP ze?4O;_w8P6V}V6dKS`e+LzC02OPz zh&;#BV%zw=5lI|ck+RClulbbk7t_!m1cMvAUcFUS%1@|us85{ zAu-$Ll+P(U+W`-**0h6Gh&n7=TyVkzZF5F4mLn}bK`5NGB0{{~A+_nxt=`~v>4H-5 zT?s+qU9yX#?w~tu%ueZu{4F%LVkOP%7-;kPKm13}aXY6w8VQc_FE&F63>*A8pa;Ri zX;e;Fzh^4>NS|uc)YGN%Y@Dr*Sfb8@hk5i7Gj%edFAoHy4xlWcOoFQJZZk>);BbD1>2U!El8Z8^sVna&H zF~?3grS(X_MWn$5Gy+#@5@%wzFoP zVjBTJZ>h=!8cvmr>1(xFUTrr9jt0(lPd}%tp?1FdI%}1QM<*Ypt+%BZHDW}`erJPT|35h@=@$enQ(OHSpD_CG}U0w3F=9DP?;5srTLp2$(k~~bw26aZO zE>@lPvN9%l^}EXlWrtjWzO5J&j4-m`O9ogbNQRRFd!aQ{I{{V)VSBfk=mlU<1m|9_$`Hw#WhWD7}pz=rwNz2SI-enzpV1 zP@mw^hz0$^QR6yjRQwLl;tt!%6yJ9E4Ve%x(aL9RiL69!>}-9KQ!=`jjS|mDI`(!2 zMOWGHw4j0>&s^#(cb)n)WQofZk%^4QiU&K7mtrMI#t{)fX~hL{tvhd zLtK4)T;X1d1QdXN&AA=@m8xjYiqKTYd&A&i%#YZ8Z<)`SP1R(b-m$5oHGH?%kDR$= zCtvR&|B4Y##WID~K363SXDOI9Jrrh? zD^!!Iv&cn|{o;WIeMd1jBPVcu9?C`J1=`?zEN@a8;kGm%dAQY%0)Qq z-bkhbDgkjJN9l51IEhME-W@TR4ly5)cp#@`MTxW)-xoE!#ix{frSG3yLpqyfnk4FJv+lw-L%gHufR4<)a$ zIf2;bdLdT$aQ)5_GuQ1C_yPLCx;?lw#`+xbrx^b39)5&zHSPm8E$7K~Rmr#|d$dWW z1?5GXDlLf7o7pB+psc#Pw!-ZIf7miPxk%>54o?!p#yk!0nmA_dyS44X_o~A_+Jlr9 z^CPa`q9n}oqvJVS$eRTeIVm~CY+ERQikfQk-Mw1v-T$)0zd?H&OZ7JsHYPn^&z>Gk z-%tCAqxtWcp4lLMA3R84d=v7#Z6_2F5dxx+gp|9mlth@_O!343HjIX6ln~#pLPN~L zefS2$40;8b3n_P`k5o=8AfZh;bmomHII7+a(FLQ0L*H+@lY|@f_mBvMpPp|G^_+c= zqg8Z<{CsO~l@vkpa3 zm;oW??~-rSOU;f>+eI~;zK-(A-O1PN<9MTr?Lr{6#5jwpJr5!NA`~_OHv|=}Dx)dL zuuA&2fSYDG%*XC2&R9`wttc%dUNmZRxESXQ@j1)6w=rIa*)!zaTFgUAyjdTWP-s`5 z@KT>h1X&3K?Sgk?8vry`utFSn!PqAtWTp(wZsY6M`s74%LJ_%Su4;7Pff1#Ul? zuTQZrj)$tR@g-2qI zJglwB+%MWkMC-MAnx!#89kQ%4;fX3v z=k`3OJ@$aK$VdU<$h09>n647y=Lg#MqJukNwV%r-){eqOtNAM&;&Zz+Cw))9L%$7m zSxTUqG{tj5>#a=`RysSDRjkfXnyxuxwQc~xa=g%x0-abew5Ya|gQ zmLZ+_ayWec^2PJR;d!8izRp=w<~iy(ta4@zuSFLNQ*|a)pk#WGr>eJ<5yK++CQDWc zniH-n`feW9VU5mp6gE{$W{DLEYc!_Tuxd$QPN#m$WAqa;Ndh2Hu7kQ+PGzY{&Ekyi zB;JPrZjI$ObT?$~QM~@mQ*(gjT zwCZtfe+m@&Hp*05BAIJ2$ke^D6$YA#1B4jmU;GnKnPFB9?H6b(QkyF_g?2*YvMUs0 zoRyvD^<>Q)h-L>L;p}6z{|L9S{kULLp%F3{Feg7Tler!b!g)H{jv zkR`jLMKk^%Pa&a|XKQ(-#A)?4wyx|1E9}w^CQsgTz@HOo?A(z?k&LcH#Al*~lBp?| zLQ0>3A6_f1C2_>@EjXhRH0)>DAR+JtjU)<`9$LqW<@z6qCdQ5{5}%PS8}Lt)*+`-P z*^DG3*$-&M;jauF{kb;BJF?Qv;Ocm%!^^cakLf+l6jo|XJxL!IFSO;8}vaqZVIE;bm z%8!F*J%_g&=Z6sX)V}HB$R`c~&T#~%INxFc=Lb!uJ+!YO>H+pKzl z2RLyKGctx1W>>2e5u=ftv(~7GrtoJ;TXHx>!~si4*%)F6|u;2B}0u8c#Z49719q&PIl&$V3c7v zBg(4eX*&M#VU*LdjhnFKE!^Hq#DidK{fIv7Uwpr?MUtQ1!69%9_!u5me zR+{a714zzDV!Q3HxNC6A`CQ;$Lr*NFO$Yg~=pAYKu*BPaZGIMIE4;XZFJ$fom$HC+ zAmj)vj>?vQGoC1&?s&Ucq14t!4o6;CtQm@Q6>PTDhK?I?*v~|w<+LR2qeR>uE|tq0NP^)jt#OA2s9AIBtSOAnvMhDG z0T5Wuihp^j$UWeLxS&+V^u_<4L(T5)vxH~P=1iXDTF6GdwuA9o8O-NXof{hD28xGI?7Ba9cR zc?y_}eyMELw^~b026we-5Q_YdQVOXtAj!WcS(ZHRev(FExoQ^fHl5(HT*hvE-~!YJ z-d_Mm)b_k+eAnaUB{Hu$Uv#(^3iM-Oae}EC62^K`Js#k<-KWb(W7%)zqjxAsfPU`q z{ygCzU2t8}jp2hWd?2g~7~QzcTMpa*8*>IZFc%L^<%`LUmz=t1K{7%A33GK;)82>? zkKN8#9%^K{WUV^J_aTSQnMca>_?()W79J>HR>#q{oFY*}f^$B`3S*%C4hm*^!tQ5+ zmDnz736TNgA^gCyqyJq@kt`Xf*plt)@5T%ZB^mS1`g~GGY}bwWNU$v($kr z;%%MPo$X1{(avB|1#TZg`fyiX0YIroKCxU5w`J+gQ6;RAX30mFK#PZXI0lCJE3B$a zS>X$rB=9S=6tHLcK8#L78aQsvjd&_!{vgQgak7><`IaZ9fR{nzb=r$e zcN9d34{(QEzrmD*jkc*JqHF;_*!ReVY}=Gnw5^0_xJ=L<8wS{m)f54aF18pE;9|s) zpjW^gNTF{B3YQi+5(pS%d$*oq zbrN-qC`OT4+0o6DT-iuF8Bz+d?>8kx#SgOyd%2kIIfvkB7uOcdS%~rrsdJ1!UN#mc z+(5SRo+r|vhVud$r8Gtpl0KYcgP9`(7(e|skkJHRsNs}onu%d`BYRSZE*Fk86JwZ` zcm8kh)28*_=;KX+k2#QqYw#5JSfr)kp63k< z7YtXGpf8m=geqwZfS+%C;9@X5g=$*KY}?JkYkOcG4K`7?JTzg3VVxl_8rlKl6&= zz}=qRkT_i_%3-&U@_%9UvC%Ek-5t>?bWHgpk;9xlZO*bO*vQ4%j62CQ#y{6~p7oPL zxe&r89MQ2!C?eq%<&XDRGu?lV6wIlxsJNc0@*$ZsBV{-wa@b zE)Sy3`hhSZz}-e_DSpUQ#N?lI9LswQ2*&iVwJ;1jAi43S8VkyT<)A_9If>`7jVZ_Ku+Bm zTDi551Say{F32B@n!_UE`ItRe2SD^$rXXX_a3|s$C^#q6^4+BoSS;5+{IHxmLVOHc zDS}f%OUa3_#T+;qvA3mBtN2SJwhceZDB>H9apMUdM;0iIH0V*`gnpT2xWLl|ZwK+_flz9T9G8&F40X2-^Z(F>KUb4lu&i|INgj(~J*Eywa7b_Vz%b=;i$0sRc z*QS4A?-$k&{iNNkOEd9?agR@$K-YqSMVyQ6r6o)`BVvTAz3U4o*~uGhJyQ(Vu6LV} z6z9NXg9zk)Q9dCK&|7YH@Px3kymI)3r3J;7Ht#)-faKj_$%Z#`DYTyl*WKJ=f&;c;>&)PknEHVcm^qK}Da(zH!Y@ zq$6k~Ix)Np(VLNusN~#hyk3So*^CItqJih~ePP+a&g z1ID1kpe*Wy&TU(!V6c{GOdp|;W76eb=!OF#EFTH z<2jj8qknx1EdSTlzp?YH`^#mXMP1_7ce!3?FL|AC`CnN4b*{c#J6l^zo+YFU|0^N~ zjkGB(@zR#dmFD-%wJ&cSi;L%!m#6txYQT%&+gPKYYxSME{53_c-Dg6SvEa2Paa$rr zv-*}>@{;?dO&NYmTvBqTkxT0@c=%HeXHEaUb>qw!!F$gkLC4c9`&%+42uI{3d|=(S z`vsO|RS=m|RM;*cZR|qC6*NUP=Oihpof69*_al_iOcxi-*jM%$oZm7?jN)Hm>mbq% ztp!`{AK7M5?#^G?Y%nEjo8?X#Q(kdKvNUB^OZ&9soX)3S<@fffHRhCFE&oFvQ=3Ox zTjthrAPrLNe8S3J0NSF6A?4mr2*28ziaX8>#_qGZ)MIYtxLh|QY)t#uPngv!_mi?A z?vKcv^wyg~?T_4~ zXt6FF{I%t9MS|<+5yqJy-2YjOfymF@vvt*L%F1n722A$fOIcwlw&X86n_M!~kL*iR zP~o(?Vm6!4E~7unrk32~D34suI-!T&qgEo9uz%r_GHHnKBF`tI*7f@TADsJ#tGCGA z-^HJrw;xYQ@5fo`{nU6!cOUB=Au34UamUmgpX9Cu{rug&*%I%?|4TY9S?%_xC35l- ziU=>5<;wNKjgq=>s! zk2LI8N|Ay;`D$`qBiV1a`EL7bAoS&S1cZgn=3@?0{wmUV-=HuQZrZSow|sGLI-qu` z04vwaCh8-LxyDT|38U8yPyrWTFIQ#U=kJ=Gzj@zp92sq%m#ddNUU8^-r{DRL-1Vj2 z`k1f&eXk1T5@@#puh61L{f9nKC-U=2AJ9hPp-zVJ^wWoAWFC5D>`>R=e5l-$E6TQ4 z+qD&yv4QM(Yc6Ddvbp+dLsaw6_t#bWq57b>nd=}I2&cw#>Q^764W+{Ewk~rYvX@M^ z$JXvx1p`~>Q%JA~e@Lk%$ml$t;<{5^qt8d0(_@M|pGRumlioEQDm zIi7(7F`TjbNTiN9>7;9*#WGM57}uvF=qi7+hyBoKIl_^A+AF8l!q7kE-ytEbwbdj_0f^+r*cEu*z`LeS}N}X-D=#S>`yS&^t=6D zE-iIP9V3Ny+z316Q-dSaW0YH7z=+NG&EH^dkcPoR;QcRYBB!$f>D#B2@oCQIv~9^O z>Vn7S4nNVxJ_Uc8zFhgtLE~?8ZsM0~$0(mq)1Ffrm@22u-!&ha5}*1kgH8Pj$|)@% zsc)EqU${KlxNUBsq#X@C(r0};>G&VHhR$*}F|g3501IKxtKIFZ-{q@Ld=2ZU!)L1) ziCi)2jsPZ<&gSg(>@=3STQ_wWqh1evR!0L&`Etby;ou7Fmc-Ugjp(4nfEEZi#jO^8 zEuo*{#hE-h#Xe~#wmg$<N^UXA!zEf^rAtZZ|!mBzfv-w!dqQsj}RGwWT? ze$I5TkJ;}IGbM}j@d132XD!-jNMI%R*zh!^VLW8#J+5q}tSwp#jZ2j|wS40;V!6If zU1vAyDsvuY0LEM&sPj0ikLHFK0d@Mqw9<49VVXXZ=45-h0~>r`?DVN0X4^aqa_!v5 ztX(ku!Jmv9cK*Wh7?!~25~9fF>=?RWsfrnpbmU>y`2PM|{8Zf5u63%4u4gFYW7hzQ4}Aj8Pu=p=P*C%#{6?k?$4z76MSylxs=@ zS1Z12H~Q+Z!)516>`}W!cs`ZE?~yqMnVup=&lL5_WT|)LUG$aDl*XWI*_zxdb4knM z>8g*^%6@gQ^vD_C4|Sejj-)uHG-R$CJeiv6(Q#tBIk)t|Ec-kngrMcx(1AR$td$1i zdF}U^BK)&w_>v)sD zb6XyIlxHL&(-c%}s+Bc>iMsaA94}WVPEh%jAJZ!ZUBV{??5FdE%2SUs>Yz^ZU*=0G z?RYC9#U$UHv19ZQ!fC3P~}iV4y{3x;1piHR04lMcZ4E^PCYFnkTPs(W= zQ^TM*)7CY`#(fF?sndr+0j+M)&5(`P;DDs0h#dL*)U0a~w121brB;7m>P!#p)z@P7 zIv~rrTaQ9lnWeh^&d;~sp)tO?`kYPr-&|dN{^p8j+`mP8e8u0l-+HzTZ(qH-y88BW z-e0{T%jewkCO;>~=ihzH`&X}Ck&ry*^r_{%diCA6eqZs`0dYQFtk@ZMg%wdOZ(0PVZ0w{Lv<>Xpw;5jA?o0BLLk$Ax&E%l=M9nCkf^ebj4> z-%(?J`t})S9(@8CZ6O`ie9M1Iv%$cA^-8_#T*Dtatc>kNN7V5hA`d-D=O{M&o4=vM zo*i#bA5V-QyRWwn>dAe4d`c?_c%1s=kSLDGT%LF3J%mklJY|}d1)14V*X4o|>s6HJ zZoPNyJO4z&3*p7e5{Y-ThlfRGh4lB>!%s=QRMNw^Nd(kv(nTu9feSgOumaG7j zSCIFSeH9$`&XID6R1^g?PWsW`MEYt{{YCXv!JDc3Oq4EXDXhlPyXtfnN) z9o5OLIo4ndsABG=Ew-Ons0l48h@*lVPKpn?URUKb;}}Be_@5ay9@sWoLOnpN(uX*D=9$>dQpl8^CQs*d>fkft4gBF# z4lC7{wJFTqUWwqnze?{5LV*V2$VII@Y;lByxb{kGE&XM(AHbd(391 zlUE;FN?z6AF4IV8i|n!W$T$j3v8bl&guT5V71(+%88!Sd_cAVMxqabGQbcZNnd1>F z2tMmg#ePfBlky+wKas}VC({)9UH)#K>e_<+TeVkdOpUdTYq1^mMTK-%NQ0!d9JRe{ z`IxQ{#*hMXn|bI6>~vZ^Jj;kLBZ$6+p8Ttiey8r3Hp16J`CpX)iU$Sqgne#Q5LR|AL&%9kC( z2Zbh*dj$ptnIcW)W4@76g~Q5^@eKj4tRT!3sg+xMb^8u$ZQUcSwj6*;el>CLSN+h= z9k-HhO*u+HrJ$(F^LIKQd9s=^E(dZAf1_{E^G#rxIi)rBA`h5q>Ue(n_6FGb9v`D5 z`Xu$b(Wc^rUDqn%y{S-n%e7b2;4ipJ;^oN+>WXY9zA=tOXG6DgTrKuL>=jF7$^UweIu zK7pp5CZ>_81E#^!C;RB`hgt={P!4t5}tULHfRhgH#$isY; z4X;&Bu=i;(4{sBf+)y7~*Y6LJ3ZI~P-wo(T=zz@Cd&ixniNUV%f}?YHPhp_}2?M>|rN$-0{w4p-m4LN|JgiiFmNc6aqg zeNJ7EcPfD2qI-RdCUo`P=ce+x`q<}aNTGL`#6ue2e0z0;7Dgc+rmRMll}QqrH=e1r zq2*Bu-z^k^fzB4NSq8e7TG|`yeibTe)&Y4yn)q%tL$V3AaK0gD3r$>653m>$p#2uZ zl*XwMw#2ZGO^h-LA1mLNE4-_?2#vtUu}-89GCJvq4as*GE1F(Jo@jPuYQdu%e)lLP zyujzCi%pK4c)g8Dtch%nQi;Ktz$3Gj4?-N)nI0t&bS_5r$t$UaaVS)=aYI}QtI;Zc z&-l(TQy=9a#ti#sXea(^f1oYDO_kv@x?#zkIfWPBbq%HQ=d(HG80`@@RY2c9x78Mk z19My=B#1-l5K+1{hK>lL33!Y4vZBKFW*cKsrA@Ih{uFa6<7BtHVR0U``)rFmpPy~8 zcoUBeISw0YGSX9T+CxOry%PaKd1`HVY zNR&c}_W&knD~N++jEQdlTrmMo0~bB63@_(A?-eD9K}MZJsTwlU81q?FsPrxbe%VRH z^bPkPB27fhvDPkdRZt#rER;}nmhVYdZ9gX>l#@)M$;7BvV>pu6E6ZEiBjllnjG>79 z+~vOZ`Q>VNw%6f9^^^Ise58kq6m9QD+LvfnRz#<58S;MA09_oLm{f9^5- z63Jo=EwzKSI`CGf&j!|%F*tY!HmUj22&v=}*hcNB{J z`q-8S`;RV7FOUUNr82o`=9J_$ehsKvJG0S_ zP*^+(D9X-8zZgD?-aa?DPP35^|;yhmwG1FS|a?6Q97ctSIrE#3CWEU3y zdhA$Fy>>RC1(YK0DDM;afFoiJa*3BWtil&^jbh)z0p-Z>yv(!VymC_>@Ei+RnE7Ds zFlIR_?Dh>7G&y~1f0Mn#OySqBVe#gL^#pR9`i|w*;Zcnv?u5F%z6I+~$-LegxmS)EjU%Z$rC%(a|2d-165#`(`T30dx(SPaTU+y! z2Sz~jSQ+1!+85M*Nt0ohWajZ~NsL||o^6U#P=J;lOfAUNcjy_T(T8da1uIuW3pWq~ zAKH!BZJSsC39ZAbB87{&MlABL8*1sdHOCHBN(;e(;EQu7VP4KMXC-1lIOcbp6C;=ScpbDMR$H)O&hv!neR@}6&6S-vXr)>@9jH# zHJ8Ly8=+|aMT{dkz8t7oDG=KH(r@WpI+Y_w3aCSRXmJG{Po=HgUdwkw4N6*Lh%!}2 zM^UFfewMC~NrlSXDArIoy-1Wf4ZZZ2bNP}I{BKG03_HbL9pUR;UD18H^T{s{NOiTY;zh5Ic z1`p)->buY2cfR@TtvnE3$wvwD&DCdcLw@+DU&9~s@k?1~_xIERdH3PJCG4pVTB;n}N@V4fj0Z z3+KStND3y*X}3)?h2s0bG(}g79#~O0EYiA|OM{|O2`!?Vj^tWt{d|Hdt+P&ktIFnt zM_LoWz#Bsy>oN^Lb%)E|rgn=2tjG-N2v98u- z8q<>80028u^SJH@?r0WSPTH@@Eg)DoBKIeH>rIpf?2nJi5q?&TB-@zz9e`-vI8x@5 zvkt&E#Vjo^hqMd7y`gUYR9ZK0m=8`WMg}ysT*SG zDwc~q>zGk9eL%4xW^j!Em zZz!MVrTHFD1=nGZqK^j1w7}ct5p9Ph1OMk>_rcV-sAb<44ah9Z!li zD^4P}c`1;RyDXKOnJVvB#|CWkCpayp(ihy;LEm*A z0*vo6D8`%=*DrGxkg`5A^1~TMKGHo`g&ILww?5+Ea9STN_t+Vbx62qJZ%tqfW3A*p zcaOa0uI?u95*!(}_7rZ;xaYPVgLT00jt5$E9jiQ{%$WIVfVT~JdyYI>@t+i3?4B7C zL}ca+Qem1WpGHAo76D`U|1tGsXVX=WH(&<4y$R(HM@nhi{W@KZYaXL8yv%Y&NaYAC zdI2Pfr$4pYou}|IYNB6GT1N)PIPRToz_ZQeo&A@F8YE43T2bp@MLV4%7{$Wbe4;p#x!Nn%YA!<>W*nZi|E}hR%0wL zN9pO2Hv2IG^tnAZ;MyFFyvzGOL3?9xfj6Lyp}TReLe3D|#4{iw(J=Zv^{J)X_G|R6 zL~41DJSPelLpe=*pp#oss6JX5UVz$;&??R88;nvv7tX%f!8esmk<`U$p?^PYPNbbh z(oKE#g3-?ySLoM($FiA6Hs+YS|1?VzXO`U-y<-M*HZ&6)ft`X}fw-TuofwA_61|S3 zjirsXnj;RRxvQ4sB<+T;fGX!haaZNRPl^ zN;@BTruPDbaL%TwpffRbCEr^4y4y|8>f~2u?JD1YGVit60sL9schyyjml>a@>}n=P zqrGr0c5IC`nd~CAerbXDfDe-BGV=#Zni;=DdREnBz<@roo2~@_neh$TW`x8P@h2XmV4vTpza` zX~9D~XY$e!0XWtLx6dEj1gLz`ciPf+oJPlPR|mEc;|Yu!>R}c8a=D%F7xmes%=Bc* zQc4f{_E|G_&l!!en#kOtWyiPiNWJ9y8Cm2Nv&{ebru4-CON%Gwy3JVZhQy+{5xO7S z7GYH&y4LzO%*~tK59j7%%pPivOt1eErv^Yd2Rxny?LrBywv%nN(z&EuXNxrm96%9k z07DOOCI#CdUg~O2t0eX;lTU$U&C_;F!z|)8n@XIkLoE@xa6Q}o!WlG6 z7^%8xr3I(k>h8s!e60UsoJUK4VQ%)B)X>NHtcTS>E+PBf?A2+LfhQu;rY;S zViDis7x^SY&O1FRD6-*(!6%|l8$KB$(eSQVQ>5Wdcu(||e6Ht1{ni*aYvu_yzBdNo z2_D`XArTh+G+c+BFuW#SxBeFDwS;KUB`(fftv82aeQ%T=Rr0MZF~eYN9I*p2P-^}UTK2rM#0rt1C^D(0AH;B9G*zex1 zT?ja1PUI(e)}s-k6j2~Iht6OXmW(XOV`m2BRbD%2t2M{YxX|#oqkbCw7FvZ6pFD?W zo(9x6x@E6@cWeI5e8_1hvu{$zRf*m7C0vX$H`FxGX@0C3EwBvV!TNa^rQ%NDA;H0$>>5$P)!)6qbI@JE{u|quO`K?EB}^vrm<|0 z@vA0q15nmjsT#4SI9^w?>h+@<@@QGRE0e8#2P%G zPk`RB4bzetQ`TknW|aTgsm`7duyPB(Hga3pjZ`c8XQ-}UJ6k*wbL25st99nOOVvBqs;MCd>xN)C`_CDAB41HyNbqkeIUB$+7q>vz$}@6 z&+rbB#<5P&z|+ZIqRvru10TF?QzD1xljQ?sP5n^QB7q-9?ZfH08@D`d%psOCQV6<8 z_0fB@w)4f>9s86n31SrSy;a>Q^7GR z2&f8SrdDgT;J{&At{L5wEp+oTXd`hyn?2F?-!k?b(S$CD3pk1hV$7ugns99->u0VHi|R%nF1rd= zS!aAa2SEm0kB@zDB;SLNkZQplwplhDq^vbswFHk$-Aj6Zdczg`9W9KSW5kTr!kn`+ z436!OIi{oM{HzRyZq7JHVkDf6)&##p{}?jBJ|bIbPE*gANiY#zMyL z;7GRS{4^a#e?d(rG1f`{z_;TSQYy5);B{uGxsEk_*74Rp$e+i@52V3RM@#?SHq$~G z9>2u!(Fz4^to-RtzfG0+kB?!aja@Ok@Z6)K;KhbLrr4e@YXTc&xYHwx>e)C^O4NLg zS)HO9_5ohHH8zjGfr{{?Bhb4C^*xKb*k~621w^W+7>5vN4j`NnAI)xVtdrj_N1Q~1 zzCao*`bG?}SsHszvIk&@pdM(UIgS~9E3Tt7Qve;OWU%$M@Y=6og!~4nqS>rxh6exewqqgtRfRVB789#6$yYgHDA2-AY*EIkKHFk4`QQwCTnr9<_ws{ku!XVDC?Ow=A!h!7z>&qyafRFK zutRj6N8goD&d*Ve~CFaS-t>yDRtc)QV$hL#?9h+9~-O-op%SuG~)2$^>?f^69ph_Of=Mo@VC`JA03g{8pF z8z&GS_H59x{r!_k*dw>Y7S=O4-k!Z-VH{wHu$!JEh5#Hm0efY$O_rQ!t(`)jrTAO)Z1#6C-v_K_^tG}5gqewLDYmKt&meSmBiQWZH0`MvJT z(<$q2_ydCb)wMfv)2qw+%mAEs6C3F+pm5US13q*s$4h+i-x<|u<#Lh?14%AN{O!&)ARVcw8=Kp9g$yY-in{BVN z>l=GEu_X+9(B_><;lI4}2=P4!CQRVLu%phhcRTM#G9~~_yFxA-)ga)!f=I>eOY3Zn z@EZ!z9NP_-;QI}XI@7VI{@im^f%A=L3Nf!}VH&07-GuF|4zZi@3;;O{f$8F~aL(X- z>ewfboqRn@GR~v7-RvY(Z5C`&G+#Eg6CiuM!@=2IhiJKNciUqRPDz-(Pfrn0)kjhWcI?&1 z;-^JNiIZCBrI;Q2xgYQPd+gcp7EOi_4ZXLLYOt=>V21nQJ?(T$xTN#w~^ws3o)D7Ro5N7L*By1kp7n{Mw z2`h+$tV`o9?P92X4BL0uuH|pY?$DqDdozUK#O1W^(vipnr8^L$rz~ z(5kZ-@>9h1GmCvct~>Gi@mvLWhtqD-gYvmHc3E1su~QmmOH%pyK6P*2YbzCtQ0wT4 zw_bZ!pNUMJq=Db0$Rs{l1qHWpn!w^?EuCn*TcHsL=!eue0FE~P5|Cnj%R&z9COG86 z`&5wYvc4OAVL&X0g7Jo4m}PIrY<3gP(Z;29>g}s+CDVq5(d+8fU*-toY!@?XH?RBD z^rf}y?VD_;`kd&sS6maWp}h>#)LTmUocF|UM9i;iPqlba67RB=O*>RX0*A#dTg3b} z+AUkg!qRnF6B-sa)`aF_eEOHMew5+@GHQ&Kqd=hDE^KYs;i6ni)bfUnE#gT4*BVIn z>djj%VWy5a=Qjb7#<$i6XKdZ6QLAUhJVHrYU*zeCvPK$patsoKvW@+7%HTQd$TUny z50RU6VevNpj*=8lWdE6c9E`mS9!Z)0)eVB2C7Z@~E4^6ME(36+=A4msoFk89>z91i zjPQJmf!o@S(tn28+}0^%FSSP$7*F^!zPKC%VL!ZYD7pcI@19|eSTv)ZWCQoaqOnPZ zSMK$TECXfYWnzGT2rtveiv{Ew=>=NWI8EOB6MGTeFiaTzFtyNBR6LjxrFgW-_c>*? zeMkG5X<`(&@Yn(&bIKRn#%r1T9$Yzw!G(W1N05wKYY(;Eu!{>^A?ude@?^9vvzs^t z`^X%8sF}$!U=kww>hk>NfOt!E+)s#%`~2#Ef;zD5(_3^7+C=6O(>ir=G=g{ipiUn6 zCgCb&!=#5G#UK2)rr*Gv*FKS%dZl>7p6XmNzOlNIL-)>A=Lwu5MGyc>mcCWcRTkmY3V-93Fb4BUhBaYO4A@|MKd z{cF=;m(bC961T{zF>*j-pL@vxWYEeBMyWsUy3t;sTQ%TaO0(UW=9%#u@uW_56(2zzt<)sl?Id)C%lOtu_7Kk3w)Cf)`|eqX)El`1^S5r2?5h zq;AQ#!ugZWoNnvc-H{6!fn)qAkzvVXi#-4lLO9rG1w1&(O85T#Yw%Aa_KZbl%?3V_ z&)&i-zy0hj?vrqw=tBs9#+%QG*MsZAZDqoE8|1W10pX)~8*Y-AQeM4z{YHMOwG&NT zl^#w08!r3=K7%i@>*+Uh1bplbsBQ6_-gRt#qk%IH51lVh&AVyGq1!E`g&{OC95WK& zhk1;VLp};G%N+9(oeh_O;u-`wQY7TQ$N$cu%E;C$3VEu#kQXBgjFU$EP&W|8o|01e zBr72BgtT2eg0~#Qr%pn?s_0F50D1Wz+9laEEkdRH>XW*>HAwy8Vwd!t4AN zTvpnNn6*RoJL%`t&{8<5prNO18!(!>`|Z416nFbEn2;9JkR6ocAU97v0UK;>DV#i& zCx{KW0JY~n;0?pz?4Fs#D{%sow9d|+%rYoHzg!))UA|Zs>px&Jh*sZ694fnR25q|+ z=v2OtDZ&%S3ZO?q7xK^H>g9-HMdltjoZ zawyAZ`ebB4UyPbH{3parIF#_jzz|bD&7Uc=KE|_I>5h*W~DV>_e|Mp&%oBd7=+|~57!*rNX zxc-x^M#>V6OT`NN?{+gE*>ScJB_^7ZHfbJMULSwej<0|s?W&)(`!k@ZkuI3c> znIRom8wO=FrQS6bg4CV$m=t}Bu>i-{c!kd> z?_oM@ccd&VHZcJ41<_#o?W1%beyIZM25qG>+OKrA7UtcYle1{c-<9QM&VHgc=AR*M zwc-3Xa9t(@bj^DrUA{>@cdUnm@wA4V1381NU3#55>)XGZ;j_liMDE}lr<0R@>%Fk0 zwo?Ew5y98B>=n-4LUe(QIEH3@`)YPY3;E1X=?j<lw~~Tj;mR|Hb?Hq-R^XH ziBW+#kenY+H}ue;Z%EB^Zql(2He&%|T!UO@)WPH?TpzjTUgFmETFoSWyhXei- zF-|U1pwEo2Qfo_Pw&qi;RvL-%dsR2_Af26W+t|VIpE*0%l7p6sNQ5ki9YDTd31-V9 zF<(KA@rk!_4TmI7&d)9>(ZU>pYS@Y}%nfA;=Y-LwiSb}ynzv`<6as%}h`S?~CA$w} zz8y`t;%D?fk0!>2P<`S542j$zo>_lEXTv`>!0qj3vwm8y(2}~N7zL^OfWI66vEB>f zGzxTK{-X7BJZ+_M36 zw3S=Vd5pEQ6OIV`EpaExPrnAE9EUQ2-#u|m;QcNo*d`HBoCgS$L^Y)yXL?U2H>1D7 zs9B8Wr*iV;r~~|9At2fmHs0F#p>leWE2j4(K428wRBXKM>CAY)$68^#V?EjP;am>W z$=uN6$2pOJ_QQDaPV%82piKauc}0J49eu!wG7~)c_7zvmmnK4pCZc=Cc@IS8(_ZP# z=Vci^TohlgOK=4XX3C{}%ajH@_o}GSDj2#uY;ly!5^9M846$1HBS_T-1s;R#3|JA% zX!<|)dsi*|u>0__Jb?`|d^JkL$OArprTS74>&M82V;m#mI~c|aTBscxUA_U5@v!=I zZzm&J#bE(HUA0$@s*gs&-04+8hCPxA-V}B{svxahVAqqD_j+I|toEk0l`Ww|^B^-Z zKg`PYL?;B~{zY1s93?^j)7%@xB*re>hi->+DB*Pt_5@=+^6r{)@+;;ehCZBo(v;%S z927*|c}&?$=krZ9gX<9Cm#Y1Vapj&`3O5ZHooqwTG^p=;Y?Lfzqi8rC9YL(TJFg;_ zz-ne-_(Wd-YnNOj^KOY+{{B7wAV{q|juWuJXF=#HB=RR|>tY$n*32oRv&9XWB1&ik zRbI2#h`dDJ;paMNwO~%AC3kH~)=L(o1dHH88GfmZq&x&oyCxR#o##rASf_cOn75Z4 z&w(Y}#+GteVK%Wi@`$`2ag1pJ`N5s!eqosX1)f3>^lEkTL0flaXWbH)oZdbia@@UyGC zi}kodPV%PJ=Xth1Gv5-H?C50dj-B4S*ghSl#t5kopdA+Xv(e;;&xkR=2(Ae|UU&uAV$o@hja!5TEQ#5epSBq4?3G`tU=A=ibt#UKWuyNAN= zZX>yH0Qz!=+i1HE1J;Fpwzzxj^<8K7(u|+K>lX+{qva?|PgQMp_dj4o zt$rsB&-fqxxS&1{&#dU`8BgvjbS&b6dBmZI`(`Sksd_S3o;aPed-xdhHXUu|z7~l6$74Z_VB)2Ng2Cd~lgNsUcMRRODKQX}W?zWuH$_bj- zyJ#6&I42%+((^C%7EOTYFyIKp;%>XVbG*`Inu5n?%Yi<&U#kQ?iGfKqiirJm6Dhr*NU+xNHv7-8HN1-h^9s_1jD4 z$U6A#|B;!)!F%G#F8x<(qiSJ?@iPC|dk{5qkUo1^AFYh%xWqRcn_1lXm;u3GGj@Jr z;Lq+Rxn;hjH>M(KE$gi7in(idA&R#qmc@84}s#3CpbVU z2J7&a^S<|tAXqyk5{JOIDAqvZDX-a#Nz=KW^^hWha8E%LT3J+pB;~wnw2h3iQ=!sT zlEO+PERunpOz*w!82=V@|DcYdrLp6nfp*lQRwd&AmW;N7OqObW9MJ!Ofq`n&BVV&l za&CEXZASf8W#r)-HKit1=IFGO03K&(3|Sx*uX95X5j>I8ewUuTHag%>XNMn}x;!lL z$-^PtVF4wJd5*X#-Zf(xHf)R1o2j#=k#e*QoGp0jRIJSK3-0NV-}B(GyW8#HQ2L{P zpXS9LlQ^M2gt)+Q7!RcIJg4m);c&o&5WDSH6>m8=cLBXong$(8egy1~^tN2}Lz6zF z?}-h8-@|RU6&!~VFNYFpGE|&II~&~>cZ+4TU4Bb20*1J1oB6MuyuT~%_XYDjX{1eL z3PQgYoH{v?9o_{cG&P0wnJU1g4mzbJXX*@_@I|fqc_{Jz?taS=d)5IN64gb<-~BUD zFTe&q7q*wiR-E^`ZT>KU1Jfj&0Qy6Uv^@Z_VSsq{&BQuFT6GA<>G=1rjv% z!GkM?4r?7h!gp- z$raxGE5uZ|Re|IRj|*J^`QIG{S1Sr=W6C$iWxXdKiF0aap8}cnF8FNq5f8H;JR)x~ zzlEzA|6uHPh4o5%)uBIyGQ*#)U)mzFmql;= zn^Ro?4LBIu+jYffu(*ESXr?Ew>JIXKmHqs-4-F(SmI>rSRUps?E9Qmj->-6UHDJ#mP zI(75OVl;{F@5s4i5c3Et->oTgIrOwSJr&nM65a%N7rR&eKZ<<#0qYd zZtM;H5p;e;6JMi-^C)#jv!J=2R!GaCoe&FG)a4)TrQx*JD<1M}(`faiT#R=_naY%b zeC}aEJj65&!l&^`<=yD)zhAhVwvqKWVq<&!*%67B?iDy930%de~fr0it zMzy0pqUG~j?I-7R$Tu)qrJItHu;B?P5+39K`z+=79eKXC%&^XXg)B74c~9&^Z5}M4 zG7EICh;v(u{a(ysM>v-4S)G&&!3{f9q!sobbZ=oY?&p2G&PB}}D97+GVDqE=SHstg z3~CF8yu^fn0sHIv^_kzCNk<}MIPlAtX!`9 zNQs$7;tUMr>FNd<@GB`Gf5JP0RX?9O5jgxco{EZ8oVB5TCL$hzmKppAe}1s_h)j|M zvAwR>&HOo+x8m`c(p!s4agi34e|cJWF>zk7!3MkdBl3uFB;+y16@xHa;$#6_Z3;#P zYea4x@p^)_Z4vzlUAOC8xKr!Y7vLx`1)xpg&d56UUU~=oy?9b!(EVG)uKjk&soC=- z)A;`0UP|DL*`Zu4@2Y#0j+HNhpS4gQj~t8L^2 ztWKLhi8&}Kd=x-6nl)JEI@sj8fdk{4#9;J1<~<6?;hG1k|EJP4i4Yb0)oVMv~iLiw4kSV(zbFTQd)ORd7qx! zRVV6X7Nwy#H0rXy3rdaSCtB%aKI@W_Ik9`Uu#N-l^p}Sjws>T_67B7<*ev%zg^PE$ zI3T5+PK(*y9bz*F9QHTL?1W$AFT)6P_$M?>`UN!R7$K~I|7;!XHFJkIX>+$M4sgRi zDsZvBV>37BN7t@zNQ0N*J%%F`Qv44J3wE}=r+Yr~EtU3HJcNupn)6vTtz>xOyVpEA z9&H=_Se3RupUCt&BLHl6=-C^~CT8ix&&HSuU~AUp<}lwAs6s407@&D-pcLNy+Y%eg z-S)mLQF{?uL(}R~KXwT0nVuuQF~Wbd`D3%&yJE#SYOP(<$B%Mltez}grLt&LaVinl zwwujXiS0+^w(aKUik~}T^&a09M5;udW)aERvGIe}{ouR`h$=kcErr`7hK2`U9YZAn z@2aDY7<=T(YSxss!1$27%52)0h{SGFk{oGsDH-*eS|!Ybd()s}oGYhMVtPZ9 zIoRfjwlx%N!-cUH5YIq-N%MQOAELQg%K}lv3Kw{r^BIUl)a1#7HE6w%|1~w*%wUHU zi-r9VR})!nvjxOY>R(0+9LLf4KI*r6@6X3LmQFMinJ(Dm4M<&ZBu>Xw9P1GHWNdl4^O_o5be4^hy(KQgQB)ZPv=!g$d-BMb4|cMG&H0yn~zSb+hI zqD0JdLMLg6>7oE^7fZSr>6+3N{Lu)ABwhe?Ubn%BytQRY>=LgTK_w~I&YoS+F=p&e z;Re$#a_e~9W8~JW5S+D?At;~24xwK6)0Ed`VyCEGdKFa77Z&~Q3aUS|=aMDzs05kn za(&{{bSuFP>Xq}~FeRV#`Nj%2JyQz08j&=VALzk}X|Kl`9|CaE7dYcutKtYl58z|H zn$yjd8XDFyCa)zb){>4<*O{c*-xv3Qz+T()A*M>Qb?BWX1}8d^ zh&N ziPde=na~TaLfTjJ!B#$J)HIZ?;Wk2PuCY99CJ%=W0Uwj&|o2( zE${btXh}e4&^(F}VfXa=BJ@k3PcDt(*EbbS<9;XcufFxhbV_JOF%> zK0leSGsti|69lGDAf5@m<&f0|DkiPmM$*8(4+CfQoVqbwg~VE7w&{Enudwxg|ae#r2J`v;DT~5 zMe|hlNL#sT7uN`y{1GT0p~g8T*!Vb%-7?Vj!OOlOI5C_6NG3nR^DCD5joiN%(!?%J zBb|SmAm$~Av3@hNu2F6--*3{dc{IXa>&M6A5y*CrkDSd8Mp$ut z)XJ3HB{y z=Fy1R0K7R5p?E+;QOh?7X`@`9vYJ;aey!glZcayeY-XNgsFiuYYmb9*a)3s@I!3T}<$_I;CPtzn^cJ70EHlJ-)=&%{DTdrj{!bV1vzfM}OP9^Bqe| zyeqe8e9mPwmbSoHNA|b=$f#ZG5}bjJXJiA=msWFq2Q0J1<^xBRi_PeO!*01n`XvQc zpTt@ehyx4Mmbo*VA@@kOoA56}@gMJJ3MzOg_tM;wV94JI1FL0dOa+fomxxgXEx-@A z+i&Ebv$EkRYn&FpRziWeg5IQX@j!|mo(!3&bs~+xFCAkC#;W#V=<$n5SoQX4(}CWb z(~n4(NQ#FgYqo&?9 zt9IE}zM1WIyvIZjZ{!?ib9s`ZJ)gbHpm?W7mSbs{R@s}31d|>fxxX~8AG1n(~TAoK;v|noszzIn@*7p zk#uJZ5#jDoYRSiX169XvE3CHG+=c{uO~M@=Dfn_+K^Y- z!UeQ{Ns&3~E?|s$TuDOlHVim23{l4$N@kxH+QTZ7T%sws0#2a``&tX7@B?lDBt=0e(?V!SAiAnD4Q!yAIk&2t7Ie@Or4Xs4iv@^{WeeP;%D?qg0zZ+vJF z<&A@NjKI_x5W$a*Mjz*ra+xxr!#ni$`}t&ae?J+WC=H1KaV17BT;{QvAsXqiNHC&y z4{*zHoVR7km5hv#p^(2hLEMzc|kZNh#Z2N#&&^!DWqn2z807`2-4^FIaZicV2z^}K_WN0gy z(H-kdVR*IiX4gjKbcV-O$cSKpy>~~~lNoIuF{cC;uo2)l3{OcRrk&HN@2EXa*nz9X zx){`ph|dsC-E2PKCmwAJVp;dD5n~SPKFe`%IanMyMo73bghl)?)X$s%581F>n5Ey_ zaRX+p0jZbv-M|4{!9&}{JUCYYsck|zR-wV}I8_>Z!Pcr7fNk+>#5;Ws9Yu+{Ghp)c zq2M_8aJea#or?58`zxBFgO z=bl_0pa}|TSCLU~oM`~GuhU-zm9e@W+-fm~^~NVwwOB%=g%0@yZLx|YU=p^)8Jfe| zp%aR9)&5eztC<2Q^bD*<1k+*_wV+u?FZ6zaxLzLkBtKV2Q@`~TI-5}Sp{0c zcv#`@`TlOpzUW+kn(vbl0UW}_jxdE1G+tKvcf0-Gyw%;-$bxEbH1wYZ1NPf!Xy*Yq zCR|g_diCZ%!B5@KiaoC0yyhBz!dvGCcGi!lpXue$D-pl?HQ?;*vGv)j|AEQn>WzGL z-IR7sk|?@qb+pmR-n1{oVer8;hX)LK7VD z7nHGTx~}uHrUaVk!?(O9#YgsH& zT6LU2?*Y5d7`ZD)9zfaKE427=V*J<+Wh^*a?2K+JC~xH$&d$sW&kkx7Lv?chmwHOr zZU>>Zb^u}}XXQjd9V0EqgCzu?s~OKRpX5;}bizb0AIHu)7b~z@=OfUm142!I0r~P_ ztam{`E+P293FxW~yUHN31%2ld!BPoo-qe>57)@r z!S8(otTFbw#e1M$@_*}0emo-Gp;s((AX|3j+YfMSq{z8F$?Tc?6!q(oRUVkPRU`Lv z+Nh?(v_~PzeW*oD808xFANmbkwq!p2)ucC>)N*e%y2FmS>`bqaG`E-)W+n3--Y?_H zfYv)c2V>%_6DcEnJRxtO`}|fLwR&jGg{;2v-iU_#R^G4_VkA&?*olB}HsD=He~jH3 zf=*ZJ_=E$#$OF=^{gZWp%Q*N~TbgKqO=Q176gu{w=7#87qbzAK1rE#RX2jxfrYK0} zr?i-f)E2n9@JXr`MPQe?ac52hawC@*;U!uY+4Ahar8eb@nI2}*WY6u0fsxlyH+>AZ z!V}3<9cIzyG-9?)Lpa?8--;_Z5yGt*vsCoEt3&AX-E3P?7ggN^cB>w%)mYVk4X;E! z)&#R=o(O(HWE>E$u=a(_5wR?+B}R4EB0<^5tfdp|Lj2;hT%r_DtN$su>Wo^E)`|JK z!FRxXK`c62S{i&GI*pKmwhbc{tYk=k{*hCwn6FWMSPN6NGlg_bM&LxtgSS-Me`{B| z{xUc+axKhNnI0KGr0CD|_rhPFS5GVN!mZ)n$hlncHcR6?^a1kk8$O(P!UN?KKBt64 z%72gmE{=@hntn!TFn)j|e4mo`%N3(~C9c>P6!KyfL@Cdpe;DBOMIF}A`bFxa6!@36 zD}9>u@oBu`n_XF`ffCo{kupPRPpf#Nsq|fvldMmzCkcqgJb9oN{2fR!dSncn(W}r+ z5965a`vLKA^+*8-+vBOGvK8;Bk37xku`~pMf1UbK*tx!Hry%(K5%{7dwE#!y?gIM` zICWw4X!D>hU$bB#N;pOviR(+Zw5|Jik~_6K5FGV7tEm~5@*+39TrmcWBZs$tuyLpop|%K zqBd7^tX9l59lFrU)&Q$-2ndawr=5(rZbYC0IAytpC7`-WU!0J4Ap4KB;aa<}Gy0`n z!*s(r0~Xwim227eD^y4V&6plI(obSC%M?Mu$1ZE4jwOMuQS(p1hUef4eNB{u*by@5 z7TqL4$#!xYu8zFuUhrn56>pEEB~=-ezLo}hz3!=m8wkE6vySiFozzKT$MAcdNFllP zr$_pvYgB|)j~~Dnz=Yg^t`%v_H&{KasGRKdJR^^+{2Lw{%cGSYVD#LEkT4v&=|RfP zV{c5FZW>ch{UA_Q9HS5HPib>Ef#q7-eWAw36TNzqz4d9u8)+Gy8@&^a3rT=my?06v zv^ubLq(%CxQ~$^a>T1_`*c7A)KF)?W;e#F(*Vs1XGV4MOr|Uhvz3Fm%yWl5-&skWBis5d4FWopL0*A zIF-?eP)YVoDzOtdu=tNJ*eF+G8xMSYhS~dST9-be?|bz0EqT?7PbW)&YtysrbBte) z1GlllPy_9-z3zRfY<+{*ggR_5-fY{;ng~YshHutx6t;wKs%TEAOdF*irY+_GdpGnS zb!w&KEP=7gohw5+4GnV^SJNUk-zYq`%_1IPi70UI2Ch7H+Qndo)flm6#FT>sq$gw5 zKsD-ai&Q)`soV1oqZ{8ArBf!$XFF0XnlaYy;gUzdImUa_9g&2HlNzIZcKt9%H+2}* zbp-K&Hig)YYP3Jk0Rlj3>VhzpJoMUR32=g(YB@9t@*;jugUUhE%jird)*AAZCs@PT zMT}3BO)}u$F>iOsDvq*LZVaqaxi(l!j=01nfB^4NfbMz`H#*f}swEQIJ*sGkE4XP` zpQDCu~7Vhn(kkCNe}toqt>*AF1c3aW`F7{T4nq0nd#I5_ZknaTWG^ zIl5~(xQQxX-q1&s#Q6a$0PGA0#~AgDIJ`8@nOaliW+f9Demp+MhTB6=G#21l#)r?8 zMrmJK(pa?}ue@fj!EI;J)8m`^Vjp8bzk1!&CfWk=*IJcpdj*R!y=#wBs_eruk&Qz3 z>0MVt7DC__7yHOJ^y}!cVK^WYBEzuX7Gy94`(G@G0f2^xTHHGjE2&3!CG-M{@PPFX z-|K8sqh+rl+vBNFcA0u1{Y&WnGPL-D=d-j7{Y+UCs}nx!sGgdJ%{#?HTOxPx&CDiq zqmK_q6K~~MD{VDPUeF?7=F`WfN{nV`XY2_s1z~ArMuJVo&UNe<*-SI7QhL|@8}}6> z&&;eygof~D8(i%bk(K{Ij5Gco+tBwOf9s4nzAC!9f`1+8RLMBk2DVUJhYZ%@cxN;uuV2R5TO7`zj1_{(#(Jy-d zAcuv6%gdo`*97x%XArf%h+T9^=4NzbLm%1kkkljIS-1h;@B#1VWlf{DN@fo*>&DaMPAKgU8`M3O*LP z6PYp#%zRf{A~emjd$Q5^ro`P`2+#dwyZfO5ovu}7{#hDXnzdn^G1VZEl=0xKXoa>;I0hge&wlgW=|E3Jw+pYJ{LgLBpQj$*^ zwz-ehF+7=F(h6?H^?YbsWywg3ozZQ`|pV5NkO^}j)d1J{$V&fHKUNXMp$Zaiyer9VHFdVZYE5xRr;}E8tLc%}P z4-gQ%Lj9#cnn7AZt>yiP8&Z6#8Ldymt{sf7WBuyi;*Z}fXGi*@ER6)Y!`@v&`@~a> zu+XfGQ8!j?K`Tf1hdH|TAMx4$g4W|)1r>P5kf)F~M}_rd>FadbZWdT64*PrgVY4AL zMawA;S^`>-*jB9a9AYDwsCyG;@&P$4d(?1JsX4oU8d^8%wEiSx!ryrJ`CCJ`(Y3LJ zs)I*j?u{wOa}|-<#*n+483|i&8CO2TI2vVHK9`h1qKG0Vfqt)u3HMdIABEnqHdfra zLep3Oe*+|*B~3A5eZA7lC1Brv`(5^b39CWqVJEQkPap#ZUSh}9vWtB;TXl1aD?!Tp z&INSYuO~#75#`wmM{jvzHW~82SC{Fh%E_1%O8E-o9FCIubpyrp`QJ@P#@i8n9$Cf| zrz2yX`NrN|t#D7xw61J6x3|m1l3hga*^7mN6+PJL`xFR|xbJjly z)1{q+z1_(f@(6RrKeeqSmGKwY+%TcdjwLm~#ciKvkKCa%&7Orf9VKJn2R`NTepv(RQ}#F~kwJ*We#Oh5NmKDCU!9`;xbl|D;b0Ucn( zP-bDZ+!^Tmme);u5o^FXpL*)y>D=$N@f+WMBWP%EH>`4~p#l4txIF^?vXsOQ?Q8+3 zB|#e!R04+4;lU4mYPS!MPw78J-*$-6=0QaDS}2x4G6ik>*o`4;53o) z){=5+e4J-B!5dzPyOyGDxP9GzRzQ#*m<@;d*^K8eZ_AbI!$Q8JP-*i7_Iim_CM0e_ zOAlAzZ^lzpWIFs8|M1Sz0u_{ zVPl~U%+cC**NM%HDVCbLj0j|QCfxX3u805w0#?N`Wo&Y71w~snK4Mxx+qv}v7ef&u zXmDpc0~@9T>x4(%1A{iu$Y7g6xR{%GO;uxEo;IYlnNu&jf- z`3090jDk8RcP{1IBI`vmszCo>4CNNgkawcR2`6}5ZLs$5Ha^48LD$ofCHB-lh);F! zEa_j2$TP-3ng-)BV+0xk>y5Rk$m^5A z-SD5S6J5ssQD?y`#%_ZQGVK%#?x0(eXqDM5?}^7JUY#c{lV&YA`xxBQSZrxpy$-WH zb2oJuBWBx1R@fWD0T1$CI1eioWq7?>FUt>KC*U#b*7JUvLW zvT*FoE9a5YldPG?23YW+>2}81ITFt2`FyuikM$c4#44TLa!hWLXmLR2wr(#gbP<4m?yg_R9Us(k`8+j8xz=Ssq;}z=f2!o8cVez?&X#(q=4%?W8vxyoF~jU66sEZH>`J?O?6MFWzu zk|JnxcKuEER_GCH=?bn0mho4&5@V*Z7_U-W9z$d58X&}{+OnHdmT;6X#hEhXo|55g zv{)Gqc)B+N!$%D7c0fUD$FFt62k~%R<7{?D$?4wHyUg3{baR0G=}&A7&=GSKmJzs1 z1*bu)b;kkb@N9G3FcZs$IjQCr@=$I<*q^~oG@VOCKi)3jiBOt-M>iV>4(an5Xs?Gn z4lb*!cJR!u#Ij7w#b|-)Df(J_3PvZ^YAgvXmal3s;mPa{cerPL93?&}0KBaD?PFP@ z--JNYfisiA>j|~eg5`F%hho{`Q%f%&XbtZ{#g5na1&28RVgbm$D|`oOVQIN#VG=FF zcES=QX-d!;uWJrnB-D*o!(ZlGR)lb-jdqBP>wwo=&T84RxGvfxV`q@hkhIu|fOD%8 z!Vc7azk!WIu`+$x=YBi7W6dEu6_7kzab&g5LJaj18s9lx$-}V2$f_w=9=pE1eWEBf zhMDZ)JjWhu9kFY19L-_*zuit)b+_FjV}XNv7K0!dT#WHu$W-^?xQpNXzue9UC0|bd z*Y$y+WhD7_Q%XxSX|)U4-`?&9XPdK#i1Gx({I_L^9wH5l4V^{Qf+7nHP` zZbrc<_OmiW%^zU!>JivRXyvWTU>*S;RL{TPxla*UgOwT5`?w$H-h1x3=j)yerYYL7 z5<^-2yBI^Ac!o}s-z8sc8;X6Wg)^0XkGzFmz4DI!Z}Jpl;pXcV(($X^P9Fe2;#|Tm zq6h91c2%2vSnm6$&_kbBzN)3|@}9^s1G#barZfKFGGEb{nk%! zI=z`_F(VaRr)|&4N&BDhx*|`sneY0n*Uag$Zo~)FUMDB~>aG49|KS~4GhX4hsBhxS zm+wL=ra$_#Cp!8&^6FErPfYT5Ou5wX;lzjr@0>F99#;q0>+hmeGLSF%m6M8c(dqpn z^kr(|D42Ke&OiOYKRq;b*2Q~0@;}8zN0%IP0(?A2wFV?4prms&h&(+c;1_sLH^ zU6Gf1Q{6|8bvZmf@PE}vDENS9+1{dy>O^V z2JGWZ9&K2fB>*3I&?5@G?^;Oe1$IyH8AV*wz2;kpqMWh|20}Xlxf`?<@thT?J2`~6 zP2VD*>s$1C^19E3KewsLHH6Gq;=FGa<>{%$9WHyO!BC0KbGJXcS$%l{hB`;WxXYJ% z9SnG^b=odlVKBz@+?<$OSS5KJ&kg)(^qi1ONweFwQ%1B_9$4!nvg+;4 z&w)?xH@&(2hd&xz86v50GpFfM#}!jt2p1tyXj{@k!+Z0v8-ZchZxSqXlu}8KD$)th zu&H`dfvR8C3a5E^>ZVj;s|=2JDW`3e>E$0a|F^9O#jY?m_iIW|_4aS)cih9^ViZi} zME_7Po|Irc(CNzwO~|6teh}Ta1HDG_;#gJ1%m0Jl`d>!u_?IWIF=gnFj@`p$;T+?{XKy(7 zAZ=Qb!s4r*EHA%!gRlCF7jNEu#JM}zP1xyl^4U+IwG=>Jz2C8IXa_kt`4n2q_4lYO z5wgL5Hjsdkj^RA@bblg;-lFiisc(cDJanEQ148j=L&G}EA0C$A$}#sby<;YQBOfDp zq;&MBGBYbK%*Ww?Nf!--dWh-W<29$IO$pJBAg}=ULgv)6%uetPG-f(Nl5hsVLfqY7 zf4e6B8RO_oJI*uay3$fw(bJWDG2HCX(wNF{xs!@$oyGNSWKTog(_Dk|3P)pmO19o+%XtBU{)#F%qyNgJ(K8(dv!# zcTQQr_OymEKF2<@B-a4BlsaU|Cr;|CzEs*lIdNKvGNah+k&pqQ!qBrWg0)oG-3fq> z8L@p`Pi`62A@Np-*2Zr1yX%gfmUD0kyF73uLo~V6WFhbH>~0RMN4#QZuvmd#couz6 zO8aHk4QuYvM3Yt=PR|oew60)nLEp2UBTB+I{|Am1s|xmMAu_Lt_01>j2^-{??+DpO z&)tWTB&gy%zh8cbGHWxh!4hg)rrsT(sg5yWr7J1QVyb27Zywf~e*s6pv;+ge!OSyT zSf?33ZZ~l!-GTbPN4IUf;^v^Qsr0>R^n`62SYSvRUT*N8;FkJBXd~;Nc;P?WE#AVj zurWgK0x?hy9`9qgT9FJrM7~T08f;9U9=c(kM&7xp1HWELkNj&{Q?nzV#N0;^rUu?2 zA+*FZshGyJhM8QJHpFg-vJ#i2T2IlRcE(#Ug*rIj$)woV6jTF3W7}WCJl_Ch*Zr#+ znBbfLHvi+o8Y!D{Ej##U;AKYhKB9L>9l%0;Amq1sykes}3W3#@-qi}=?5197g- zmdlGjDqicVh`oX~^9x#=6h7rrNbnGuY^!@#w}P@P@A{hHp9D$>O_vY(P%FYck(+1H zxBWB7#2mXE7OQvwC}nx2EeNF`k|(+msCNU0)B)g9*#h@M!W#lDzeUDKz%7;K=iKQ~ zxhx$Y_jDKR!6pZQn=&8Zt&yLtSM{V|Uv|dq!ZYQ_@yh8eOHS7*F36c1yBn@t59UdM zl+Jn9&k-`(vW*duJ~oU;!+6N!_V6dni5pUQit3rQIYf@$bGov_P8@ygE>GI9M1rCb zXrgGHZ^SRJY#J%TnORLc*3C(AHZf-V$E&|4Vmh!!dxqiFfLe}GfKEh*fS{xcFG-{Z z0LjO4h=9XK3s-O!mkoWraDxN}#VpSk+7&Yt>vE^ArjeYltKcX12klfo)7qRbTwRYT zTJnYL&?^R*kgf^SJJuvEyeVDs)wsWd#Yr>8#|5|qKO*ZK=|m--;SAq}`zi;T%i!9As<{gY{Pluc?w0d+qpWP+fuH^;<#OFb+Mym_%g#r3N;GQ{5!84?4 zU0|t+FFm_2|CGh9m^1Q3u2MxuO!<4_M-V;kcW6)<1?Jxba=;9vxcJagp4F(Je1>L) zPtZl?YNSd}t~ms2c26LR=bQw5K}MnF;jN;lg_I+%XcpPlmO!jNM`F-`!i>Os_4tg3ZbdG#0dL+gbDIm{!d*aE)7&}D z1pq${7xp3aAz?W?%$gmgfZFnDXD;u@eE`7Qw)8ZyhB!<6lhJy=tiZecg5KuLx03aG zJ4cZ>ElWd%A*S4QhcW%YEII{ddRPka>*YOs4;BC-527t*{UipKJ%?2houL11FetYWmuVOA6Cxlg>_(^a*yY6$+Dd{7H71zjrxShf=Bh&GYN-(DK z4#}*0#12TnG0Y9b<)zAWo`6) zQK21Av06Zd_@8rpGpBoWbiRJxaDZWx!7RbpuFzLRynsTRADruItbN55oIq-L27G~eD#H?rn1>E1_ z)H|Dxumr-<^H;&M(dWrjv%R2&W1UG+omg}E?`fg?BHnlxXZG6jI1un}DRr(mz@CG7 z7w;MWf#*iS*o_eIXOCKMnN5zlK3As2rcvEb-!o_5f`xFoOdsa8%9*eax8YeOPrVpl z@U8!cktnrr=);52hT4|bH>}f?%gM$m>m%IPh;!(0CEdawZ6_RwyxNYTGH~T+^|TG< z(A$!GH4ZRD_?2i)T!8iVA$Z|lS^mu-i0H>=;11Dx=ph_9=kxU_>=sqRl=XTFo`m%Q zWFyw|hLh{jLfp@m^i@(>e9dpfAuH#Diay*x^Y{1^$Y_> z_np=!Fa{ef(Rq{&loLt8K>$Fe1prOzb?F_ZrG&mOw8?!iT+_|7$1>uhA;QSED`N!%*7@!J`PPMAEGEZ3M zT#>f!d$8RRc`VQhGb9#1{UPr2pP`-V7Fs=i%N=-Ry|$V;M|)7f#dXe@ zj~D98#*Mg<_!FoVA5Z~$m9DwF`jF#t36Pd?Vj|XqrQSK&7)%1EGQ?f5SDZx`0^P~+ zsbXI47Oojg(Zin7SX25p8x)U#9fk6u$NP{^QvxmQjZ0ej=^9qjy$=j=94?V=hIKnQD3cRdm0+P2bOG zK#C2Ma|BgYAEKUMgh&BLMbCGf%n*3WfW!W8nH@Mv2kx-GPB!yiKy zzvHh$u{s)x3&BgFv1PCz-9ld{X_eV?-I0r!S$U&qF=V z*>Ke(>A|=xzg%9=Do^BeK`^#7y1C5Yme-qM>qH!&Nma{Y1-!yBSx1>YjF~ypTxi{Zj z-e;1t>BT3`+Qy`=tUVsOJ4ZSv$2hw!y8p~LfK)5=bZ|bLqYBng9JNDi!S8>DUkuwX z7WsQ4_Cxnjy?|wVms>!oLxSQBWQ2eY;P!4d1UMF5KQ=RlmtAExV0(x8Nvv@7gyERs z9pPyK=(0mQhgOQ!%=3g;EhO{M<2ei9YO3!H9g%?n6@{CXPpaAIzEe8RPb75j@1vC=T4dWWSI^1~VFkD#f zo&jTb2>k|qDOTOXmi~ZjP%D%-cExdo&>4*{4rL>kcllT{^djjHm3+evVyy^+t36L# zCeK@9 zNjdG#6D}reWxpbI9#SygB@<4@I*vzp>)fz97Z!$&Z#$ zJz>Qa-Z0*P8=01R^o;}W&5u&h%Z(HYx`te0>j-i>W9tq2q8<%^npxn6o$qO>*!Km4 zu-S-91qh>;GE<0kC*fD9$dGo+Mzqg|Es_$DLJyq~uJ$U8a22toKw1$Ho9pmlQ1(&J z;_0BcXKrkf{ZVhE*ks#B^K4Dlx7KzXoKxU`YCli*YG!+_Hv7((%sLs;RxX+z8KA3y zBoABzB--3{#;VGU;MEW9Y60vY@E1JZJLLvx*nhA zf%~O$o@uX0)HIAk=E>6}EF*QR4uTn&dU0=10_U4g+lKj@fhBUL4j?u0Zj7WHc$Ezr z)?PJFR}0beao>{c6h0thEDSa=$fUeitZMxArQp}!%?$CjL%`)eX`1Xf~>Ub~cU`NbMBY)QcrI5S7aX zm9{Ygwu8*<8ua8xpq%mZ#e&37?I?`UX*&vI;Nv&QjgTvHXW&q$HC`yR3kB8xj=hEz zb~qM#xn|xXSE+Nj?g-G$HeOhN*sPwTX6u4}pxyQQ7M=o~gJ&XW)=R=IGQ=G2iNY`i z@mx7dR@$1ln88Y|ISr0oqj-+WJ;?$iE8?e#C>v?!Bu8zFz_?xE!%7Ob%px#jM@R40 z!Q|esgg5*3P6XBfKDH6KFUUjK&h z^&HHF1qk0u4n3Ne9Creypic)Yp~+I&B`ZNypCXY0%Q8qKRDxj#x0amc;Ci;b^ITjW zTjA!KylAKPy~T}Z;7hg-ihP-qU;`EnWBxZF68Vzt(yRDXk_*R!zE!wFpL9znusA9; zGgxT7rt{I}u0V&t6C|AAAy@MaJENvNQB^QO0>h(qy1v_VEt;orGZA;Y#hlj~FOg)- z$S4(zi_AGmHa!~6P3JEw3 z#4g9$dgk;73M>f6J(dL*DLsWl7+}`uqX}*3rTbD!j-?B)k1b=1<#3CBl+Nc<(OY!5 zR~tqu3w}dyT{!Cfeq`DiWBaAU`fK#yoH41GUI9F#U8J!K(Ynz_WQWExy&=5{(HUF`P~TZk>7h-lgP)K z6sr-liYE3n2Xe#M>|BnLgjg{#sZ;12+1^2_A`v>}}4jPZwJYx=0Fmjji znsIudHqPyc6ncv?c2MH+eqoIz>hCPA8`O-2a0gY-@Na;w2fg09CLH^hth)mkl+`tv zPZjNxsjN$lmen3L__%R}CSyxRp&CHXw9(%dbPv)I^*W`&J&3pDzF z!NELm5!c@mV52~V7|Z~}k_^oI_yKiDOpg$&&nYOZ(n=>~ITRUlQ*^AME_L>7b|9O&=a0 z+*rbQLG3AUd1c4Ti#)YVnEKSE-f&qO)qKs}sXRq`+jYPB4fcZxxHr6BqA+CdN}gfd z0wb@#WqS)&V#Z9InWr3J`DBX`B1gr{lcbxa|HfS_LAwBs)RSuGjxd-m<@eb*8i?87r9A=!%!T9P^7wr|!)D}%AJY^iMm!}JLke!pZI!ZJB{tl&uHURU5r_k?1X~WR6Vc{B%xId*gmnxOe`?aS(x zm@`}G1rZ-xfd1NtD>v)ueupyRv&K0luA*;IAmPQ!9l)W;x-x z##8ui`a99SG=fLW#jA4PQ9n}Kf>y}M0QEeLGoz8gR$H4`m~zgauH>E=(;Q9^B*8&gj`QCU*lM@Kfr6mWT!Xb^la$4fhQk6gdXeo~W$p zk0YCAKq^iAi8&Aa*OY@>YSR9#YB2}Stg(EU*}6NZ6+GSimZ$KuUsGP>O!hW=zMv&i zFnCp4yR9Sk(*}vf=bjVr=&Y1|zkDcJfL#M%%t;-)LL$b0>XnFX2W(P8_EpmtKBqo? zXw^*C=yPWIrRcofa$|CT@RWW*#rQryKi8{YYUiI`qHu}k`Nf-f zqSSpL);WEEz%xXn+a6GHZP?$NBgrxP?W4p858%yBmE<6V#09Olb!Y`b(^uMQ`?jI; z77e%nec(+CwyKM~=t@({ha-a_1CU~PAcf-yUJn;w#`P5uihN_4YELg+_rm*efL_uS zbI)r>$a1p>MlI=+87^jRf+NaCA|>VWjma-m`{kFXXzSJQMReT4k%$vep+CXBe3d^c zBOuv^Tp>dvu7MT3Ur=w;X~&C4}L$ zDZ9eF$2S_89;XWeju%jiQ^p0f$<;TU4jO(JisH9T47J2_soxcJ^!O!k&MDRKAyJvs8>l6OBKZK;@_Nhlx8itm)= z#zV*K%96tajF#!`Wk1pbMwui={ee0d)f#- zUL5feqRZmg8Bwh$h^RI(Nnu%Kj0DgFMQZ2O zfp!|T_fPOYPW=I_;&{N+V=p!#tp|ga4GE~rsfHG}ws+jhpJuEgr64hy+@69}z|)oV zKY2_Lq#>tM#0`67r`ZU^~WN|t8%F6LOco61pf zm!>6}{tu}I17fpq&q=on%gd!W0R7BJP&db3;Ra7vF*fid)!>~yAXYfqw&bc&Z%3o) z^9Gpgi5A-k)#O@^VibpHp>1NHr+qxmCbDF#9;{Spad~6~ARWH4v3MO8G#m9dHML6` zCQXZSgHo6Fgm`tzNT23>C7UZV^%NN1tFj}vu;y?KC!~fN!RuPaDRck@YIFmQ#G?tLkPDNZgztH4bcB~Zq`dz#-dYgw46!Ld%CD=hQO?BQ`%yTj0N zq*JIa>c4^B)T^)L0%;NJ(lss8RA_%CTyiCa+dib#C*h!0t31&sb}K*tDY>BlRzqO+ zvv2HoT~5W@U$L2ohwIf%DUFxtXA#BS9vly&r_pQ@qa`ATI|JAc0HknaDZ+Y>rMSgK zo566YS<%xp@g=PV_8!>rN(~_TF})dJsZQ9N)B9SWW0NUMo({^E_+iM6y-1vyyqbOx z;g11ZW^_rC>pu}*8*x|#x%G!|Z~nWJclb?MNAmqho)f&K+*F3qEt3}qP$d5D9p$}z za}H}LZ%Ay)7d-b&Aqz`>Ay!HWyfdBpOCFe-U*1{2n#WYKJM@vDsfRQPvhebFLAj(! z=@72T6Q%O4=Lh>$I`m6mw4;${3rFLkY`kTzfDKShW-7NxHxE3^hYRi!Wo>MQgX*EWG1t6xr)XUbkXb` z;5yG5zRQKPKF@->4lgs~66SAMvE4O{DW}kKn(+FGDuE=vSf%wU%?(kMFrDL!)NSI$ zE_NKJ5quVDp={4{Xn_HZ_>aS^C;qDkK$K$>(?Dwe6Hh;8l);0u=>%7&j&+tH+sTl}=KznQ( zjU&gQjpvV2$TxZ3N-f0*29ED0C<(MGqY#!~9%Ye$nsRI&;1v`Aigula;0yl=UrRw2 zr(Q(H?g!(gRD#jf4}d1oT9!BNhvOKt9Qx4+q4$Gk476Td96C=AF6;_EQlt1lhp|TB zy~Ao{Kk>_Ga~hMWA|19Y11p;DYb@n>2UH}RMgNb1_QCeKvNr%SUV6uW+$otcLpbwA zNE6aH%iH_SS`D`-kk8n(+np6qcMx)U4U5zF8?9kw$_KP{2<5}-1vQH@EQ~CqF$GgCL zl7Fy@z|nNVS}vT}@>LEMMGbakmgkwcC3Ub*guEq8%Y`Gx`sffNEufnx%|l33=56RT zxbX2|!SleT=wEZQaf~+*1y+TqCt|qekMeRE!|XVdvuychThG{9!G+dwfHI8%Arp5N zmeD9R=i@AE^6>jSxWaLt7QpCz!^|KZ^PZmpi=5@0cDp1^M}HJ{ZcDMjQE`pY?8q5s zzB~43%}&VtDhq4@XIPW+<`fQMkvpRclk&M*$k&qRbI^d#17i|?Jr~>r2BoMCU;y}Y z%J^YtV^&cvCE`<_(SB#<&^~|K`4&0lwe~x`H2{%M7iHTb@ZIviDv&WKf>hvtZ-IPh z9W)+Bze$zlHc3H@%jCz^Jn)GA*&QquT;z>*=F|duXKe2<6LyJDG|jThuf^(e@iscQ zarCkUWQ?Sa15LVmY$-U)iJ0-yuHJ}#R#{v%K zz^4c%%Lp@w?>%x>XbK_{NKk_n=E<1l6-PNRJ0d_P_S2_6EBe_6*>JX1n}R63uVS{* zqc_wCq(-7I(p)c~F*cUZ5eq)Nf-7C*!v(D>h4gaYAL2{M6PX-T55l9-$?#uivN?DLD zLHuPwUCcSCSnT6)U85ws^e2Zs5-GB)eAw!%;HfZQ%0*~V)YJ6EyL4r2p`Y^nvzM?k z@HH>tSc1EG`RU20$J8X}^jdvov24QUSOVXuykvvmrFanPFw6Am$xF&m|9^h+CQ78F zNF%dG86-+PQRvpp>T}`jQ_I=Cfj2riffM2loFG^5O5}WZ@>7xl6TDT#Cwf7N)Ck{2 zv6iBC&UAp{uc^<;*q^`qsrA950iBSLBO3DyDoiC9Swndc8VJLG3huxdF+*ABLZAI) zQEJPv97p;qk-^H1gGdmXg=JeMW+&{to1jpPxQt@2( z_!KvR(=`H)KNvS;!8~Nr!vfJ|1G#4KA=P-a4JO-;eFL2R>7eSldD1e2ox&|^DTT-> zrMyR*6gkG-pIG8N-uNC1zPk1?8CY|Wbjg+83aPqs$M#rKx)QI@rMKh>tkd%1{=}!8 zPiI|H_5yA*YC|92{nH}Ow`Giun1W`XIuo3h9wXP6Rrox5I@|5O)Hwwzh}Nr6UPRll zrnfn3{i&}R_r9;$BBFIk8$LuZO4svGsx?}p37)Thj$RFG6ch|4HvI;JGN$)|AmR71 z&uIOV1wqU>_5@yQ(J3Tv)F8!nx(<|!L2FSlB8UWEiApgt{=^jzD?Bamkve;>@^eiSLI?XFrT6dTgMu z;rRpo1C}(XC^^M-kWL~85gg<)VgOw#>ObI2QoBXPmL<4Te zg`UdDL%$`ves+q#Qo^1;0KM^6=?m}}?2q-0cb=#HmynphJ^7D(^ABnix+(ZFEto$& z4_XBk3jzl_7PL*O#{1;=@zIMI=qlG%^T==sUGC2 zO|~OYM@GM)35%R(bk!J?%n-yEL1p+>#%QrvfE}$E2hT#PEcPV276<-8OJil3PavFYDpWAcy~Av%L>b2e<~|-;;~N8 zA_y6Pe*1uG#QQU|-Ox=!RFjDhZOw#l^>xAB{{3RCt zS~K{wJ(r({j@udv?!YdjK)9q>Cy}A9uEzFlFp2uKlCPz`j$8o)&8ayJ}^MpQfH_368Z{@AP0e+Di7t~7H%cXIQ-J z)_OgOTu!lGSXd{yg@M$LEu2+KX|mKFq9jHNe$RyTv0-!-QeEmjZIro?+SnbSk=$74o3LfT zo3}ItGSp)qebBdqdcTh)%kHWvft&OXlsVXsV{C?u4PFS;28shE-BT|3)-C`}Wb&(v zEO+iL#%*I=F_t(akPCVCG3>;Y%=Dr}SHT8cLH8FOM{}v+S&Ldct)54XD@6Y`}xa0M< zmJ$@Jvp^b0v!5rStAVHhMOcxf46wxXB7ldwU`Swu`0_oMq|IQ4~L2?s(uiG0YesXN{AF zMY)AwFq>H}8{S_H2aL;*-00|HWE|Zwb!XIW35_H8o|Kf_&_{=(Y$Xqm4ij8X^T_kh z#N*r1P0YII78@H1tOri#o9E8TeUJL|w6(be+Kj65Y{6)$k&jl=GxDyB#ek6t+M&+a z`IIGQXa1dB$9F&Fiq1UJl;$>w}&#Uwus%_E1oaG&~@Ti4Ly& z%#V5y*JmUMY(SWnPQq%$9q#Nd&%AN%)}}-{o@m43m()qelk)cO(R83hQ5&P>i*-At zK`{~~geHU{C|5;@wy0mcz*D`iJ!w?JhL&U*wI)hAFa^C%hLq@9%zK0ffDnNMjQ{9n zw6ysSU@1HDQA$c5cS%l)QWA6oq(&QK8cHBxwA1#XiHd@GcpltF!$)gD`fmB)fmyj@ z22Yy2B5G(|b5-GN#nU*uCazeWBVwM!&-snyNGXXDF(n-j#+S#d<#O50=LCkBelnj- zs*$o8q0fq9GC6w-Ua>ElIKb7Yns!U#qUCvo!@AH_wn&6E?n<`H1kXrQg6UaE*f;^W9Ow~q-re=2$D{sBYZ=TMoAeCNEv^TE~ z&@yvbnwie8M9X#?WDb5A=P)+75PhFE*G5%7q!!wi3bE@5o|GxE1; zw~9J6L_?v^`7h3iTnu3aL&iWyzk!7nZKDT8Mw%I#3IwuU)CuqSL)LOgotR6{(g(D@ z(vILh9A&D0L(;F#&E}0pzxi z)a`Qh1uK^`j6R~5jCo11ewbmDQF!_EthgQ%gTM(yAd-BXJ6o7V6_^-hh~VE#-{&k+ z8R@NZ2VGm!x)Hs-Nij3&`I;Fyp|^NLq(gcc?qi_`kzF{UF(f98PCg+&<6~$uaB5bgMq?_m?mfw&0O)tR?%yT0j-&uo0brknRqo*Tj({ur+fJz08f^tXKHM<&Y&B5qoeS|MzuEx$SB<1~{ zXf=M~xNK-`9{b+vkeW$%hULL=V0RnX$OpXD3aeeD28PMVzRf|kZfSpmZUvamgcQoU z5;gg8)Yt_IdJ{`?LOV9V4dl%Bw|Raof3)B8o|KLzCD=Y&QEk!p5x@-tD={mdajO<9 zh`9q%V20Y0^dO10^3SB+j)-5G#zTnnhXv#9$_)NC_J#7f%63r4Oe5RhmSPw9nX z1lR;Go7gY5mvx8a)#s2X=@wlK-r67baZV2=9KmmXvi@tMqVDxd*rfvbLq>1!_Oz#`iXBnlnLkjvrez|y!Zv)-LoFX*qND3r9cUPzSi>Aj zpT#eIsq8jEbHvGJMFAak?@7_?;MIlP5)YVp7WxcyOI-=wWy{B{N5M?ke>*bt8Du-+ zlByaetd$BNZ&@_G25K}S!8)5GJKC8 zf%qKzqoT)I32OR}(W2*kKqqeYI~F?7bib4Ou2#Qg`UQ2Mn|fNwh17u`D5@A(cCPIF zFQmQDe6WQwnBVa2XzzmRJ5h?V1mT=gh2k0`d0z5s9Pj`_p4k=5ab)}!JgX|k z49S3nG@uD)wPpM(hcs5Iw4VdJ=N8(XMJk|+HQhwi5bK#U!*%M$(V?e_2Ech=YqtCt z&9M7~amr@{!?6-S>Avp1skfZQ!I-iB5}5^@RSUQtZmTt$NGI%4-xIr_@aVJ*CRqMI}?Ne5#7nx(oK84`&y|(xRJZ^}74E00bf{5l@M2b!(t2@@%?vAT!39K^N0aJaZHRJLs~C{pL^0E0BhF3PgV=`7HvT!KZT46Ff{k%$L5 zyWIk7mU|it_f<@WMg9X%_12B>lL>V5qW6fvBTHDZoxD-ThPwbGMM3wXr&)`vL|5cv z_Yc516kn}|csS`J8<-LElA+UbRFH04FgEo)`VAM`4fKJgv3*Q<>+E3o6m{oGQR0r!nI{BL*JhpQf@g2WA{5$eu^ijN%*^HrU>=M^WsfICZxb zk*8~pYnnU)PTGJc4O02swW{Qe5FkD7S{2iT7N{5x>7KRB`J2)%_+KJy(6*Yzi>Jif z&|(2WWT~pjSVv^E8Ly;m1Y;mZVYHw~rd?ZS)PuAQ%6_6@-%_uDCezE$NDHKjOLw=_hEN<}Cg$km8X%+oY(gfL;1m=lowHrlL?{FZ>`#P5s~+8kS&%O2E< zfEPq6Ow>X{6Uza2>-^AyXLK;&GqxVMLP$BT<>o1KIsmKOYI|4H+t#}-SXKzXIU-m& zd!>28xq8$Kf5s+aV&<{t5{(pVGZfIEyhbhrSLtgwJh%>wA*{yI6XOa2F)I?Y^n-VJird zLhIq9X?e2i81$A9da?F$0yFdXj-xx-`b#X3D?;2-FVXRcvY|PHwLDIqrR5JXJVPL2 z73vP8Lp-tB>iZ6@@=;(JbTlxE@2bD@Nj$46FPMkK6ryDp(Zf=xSV~uam#@Q6%An3ZVq$D|4bl*6wzRe48BbXrytC-^-E}kOH5Jj9z{eiP#nQDnd42WDbHzfu zz{h3A#c9uDK?%|Ar`d$!Q7t0u?vB!(3QA+|#q{j3lOH>a$Dt?+wTxOJH9P2qUh2^j zUOD)@gkc&TO!&X_(FtCXQg0cIJn0Sg9CbhX!k}z9M^}S(hLZ5%A!q?n4RF1o>?a)& z>CnuO*t$|FsdnBY&XpMCa5NCf9I9CpxXrPd^PQhC4N$Q^P6N9f36uQ3tvMIQbw=*6-_F`5U$ zf$ZTAA!%PFJ8LXN#(NMJhnA?P_>Tv+Zq|(ooZzi&EZqq)EH!SrD+GH)J}N zCK*kZZ>Cb@!@A0qC>{(-ymv|Y|H2Y)!?xU=VAT~G8blph8lw!ZFZ!}3W7-Ks);A@m zJQuZSUjlvN6SjbYOJq&8Jd|TU@NeH~9|7~`Ot#JHZlM7<-aPqqxcI;&@4J!~N{}D& z?38{&Cmp>cJoZg$r;DRkMu_rR?5EWh+9GZBdhs)Bd}uQAqhZ+T!{*wy`tre6T?ScZ zeN#qtMgSLm_9Q(34QneC8sZR;xz8V2j(EwyM=A4u68DD5s@9Pk)!h@V#UHJYa%%NvfFFf~$o;*JD_qmUV*rD{N zzB=Ao&%ALQtS>mVPKW1e!*uMC8vjpq!Unagy4#|Ww*&nIs5!fMZ(S6$S zWXG)?-eYmZ(A0(=YMu@QQUp2lV|KuE)B@;yzQ`{FZwqY_;I{)QRo@+lBuWgWJx6Wy zyLTs_swvlt2WrFFUi$CgOWz<_)xc=aAIHqrIt$Y;URJCnUNehY_Djg|!@O5=M66m! z0DW5VG3A2k@boLyCI))nkk6Fj51ht4&Fg~BNE{RcX3wO&^A!1wxe+~8iwzTMhcgO} z+UIlMmBpNh&{Ia@BE3s>kw)s&z~#|Kc{~{! z0PWwW)9TV3qzzS$D>@C;EZOV3q|T=opq6qH5ZNtvIPs(*H1so zK?g3-BjHELLQL<>IfR3<*qNs`1dT(5#|A3`I#HyVfsNglZoUQQkX4YX`4q|sj2@Z< zQ&nh};caUq4p(E|-EtJW!QGddFr5uyd?_lsy zF_S;A*HCBC5*p%|*phWR>5vCZ)HGw^3Ah3hI6JZIgISdAnZJ0#P5w6O^=)=m=n};zCaBgukQZ|R!zbde$%jJ z(7$({M<_kRR}uOL!v}4Y!toCduJ<4EsmvTX;NGBta&sS96lo$qj3WX9pOEefaW?R` z$VCy>9##<-?4;>pZz9$5hzqRl}IDxLG}C+I;jd3>xYP60>dPlwB!#ZVMr6h_J z#<|;C3^WhYzKUkkbY=u6?4_s43Q|x8MMryROw?i(Jfv)@;2ld2ZJYvkUQdBrO`|ZY zk5H?F{*tC?5mZg6Dedtw=P+tcZB)x#hlC!h&~iB=GE_C1@IBIkNM_nPVecWfb8yKG zI2q7m4NE-?7}$VV^^d2%82{jv@6v~>B3;4pLCG0|s#b1eVW@KB7OH%rJHMbdf&1lX zlJo?m1u`f(W0glbN6OU+fczj~+D_&*E!BRATA!-&%?;;?`X0^JWVcuAluoNMH8g>W zT}k2?I_9``KZ_fVJ{h6gf+*9X$@)xb3$OVFvs6hgV?z|}N0Oi)G9K*rzDr|Z3qxkp zYwQ9TnCYnxa1TqnkBSuMF~O`=RBLaYM#+(}@$|K= z80%t9j=sdokL{|||9x#VM^Yyx9Ord?0-DsE+^tnJ`oWbst*D#7XNaI@q-Qq#k(KZF z#mA&19Hr@xHa(gWm{@?}1=o&k!9^{;JGXgpov^&0x5Ti=qBoshV-rKS27coc8g_H0 z^Ys0dy+?2R$Bb|uGnGK?W$F0@gbY_9$3zT>H)mL2b?D2XnR>fWqz!I{ zdA>lm37n(p#`907fRo^ip1s2VP%fOAChggn%J+<7d=7`Oy{R!>xqi$ifR$17?W*qg ziFbg`r=D z;}dpxboy!a1Lr|?_LuDwbmFjQC-qV3xOD;te;YiiBVs4&b36JgQnOG( zAD{1qiM9F6@9%k@QGK+`Dx4YEkdL~cL;>WOLC`^c=6G~VR&{w`NV@hbfW&7Rg}?G~ zk^wM3@SI`H@8FuZ#I1sfP*jA4Lq837!9q+=u=7u?tLOi8JC^+w%oxw@M|9F~K}6cx z-p#9tW?pKQS4107hcUT3dqkz;z(^(_>5^EQ%Z;qlz8+2&b_Ja9UP-1_;RrG;NtX zb@6DDeM!5fB$jOseY`9UPgA?(v!|YGiFTH-y_|1E=b-UtRAzuZvsLsON7fJ-Zp+CR zXz@n(lUs@-WE{qz+q-FMrtGJh%HIQ)?4ZO)VP8=Pk%DXKLR8Ecr}^yN^V-zElAb5!A#M{c6-ng zs+AV zpVthR9kJ7N^EH0M_v=C`W}o4jK_kMKu?PrPQ6U%)us$hb_Hv=$clZ?XM#G`@L3$_Y z1L8zF1{U2!%`O-06Hi()C>Z=J6bwm_QKx&Q9a1o67Rm!k1I?4b_H)Lj+d*ZZ07U_H zD6FHJ=Ub=~CtYs0Os5{#^Y!K3lsM!QZ3i6`4zGZ`W?~!cQ|x!XaKevPH|GDn06}(o z?5E$oYN-o;76-k_FDG3au*uBviMELz7&1b0rH#$uO7gRk;v`z{fNr{n`}~H|?^#H& zlrMf3<*&J8)@9nkCPV^bBIS44C_HGo@1S6`28nO(RG~hsQ0N>8Kwe`}e}`X}q79r1t6VS0Dfzl-uw5PRAbhAj6?_0G)PK9_$^LVTy+ zp>Wn}7W(DTOTW?6SqoPf_};xxuW}wW@H8L;>d-!G%Zqv~HOetM5g*dIUkfdaW;tI{ zgSwfQ=xq2V0ky_2uZ=O}lV{klw0)|bj`M9gPZB^I;P5a$Be-2wVtnVS3jP>8tyfbH zVMNL+@OJRslyVf03_9%}-Htw;J)LQs2?IzA=whBhKWlro5RV$y2hW z)kS4`uxn~vDp^-pC@2$62Xg{>VTwO9rB~!0O@$U0>U1U<^se8Z+IU?jCZI&mfnIe-9I^~nWVAc_11Dew@dWMa@v zX)AMzJiN88obnJXsmGFdLd{&!8v6>-_6nVfoJ^;&7!pi;BflZIcvPw1W9aD-~>pWbq{C^Kdt`=}1F!;H7;RBYmYrf6XVa{B|^Me8jvOQ0cIL{#{MR1`OvN;R#U=PT`j}tGn06H6 zfoG$T=e7BG3*LDJt^m$&ToUSH36xi1vLV8U9@%NqvY*d1i1?#vGh3kMVFoYH3*mg@x z^}GN!3#U!;rU^FsoVK9(f;E`A9;JN8(OlJJNbtQ1ne6}KhvFiA0YsO6lIrPe=D_EH8E zBOKJLeRLh;My|jYip7vMp2%KeYm4`?3M|y!!w8;003Za&UP#V3LC)A+k4Qo$GzZKN z*o`Zc3~*Gnsrbkd)Ud%Y3X0YAC$ki_9&Uih6;NU*6KNEeYR{}(ao8Ve?x)jY4LdQP z;>R?FN3%VG1sRUE&;shyOeEuBoou6aj9fB3Z|MKy7E?ugH639q@rBjetHwdXR6FyX6+iSOtwExE$NF94#yU zr4nZVHF>fe;#!uk(Fb(Y63U<_UXnh7S3kha|B2%RETE@&xJ8S6546&9N725b3y_A> z8}oDwd)AKp-?q zE__q0Sc%E+HRT=GqgBDmSj0nDm6#2R8gvwX-JEoZpJP|RQJ~$J!cyOH(&dIer?;UD zuMxk4COaE~ntqIG;LbNkMqc!Bdd39q#9v8VtOllP?RC@piLq2rwu9_l)o(;}PjniI zVQVV9O=1Po3hupg!I|KI=rAKi=~^sOeYwza7E{B$NElrzlh)t|9P#nqrYi1q;ZD#6(uW@I#l%OLA5t&5X0h%-SX>v;n6Q>|e$wBqev2f?dfJb3w69+qU&MOq zng!0LHLD_D1;DVGv{XHK#dv^IF%loH!!KSddFbJn%&{`~^6YT*$QVS*I{yfdJ)i00 z$JeseT*BvXdWsQXS$aTZVs^yD*+oq)C2UW~rIl zB{2aH8~|~skdLzVf3iqd9AyjqQ)0$JMY{H`5KLLEBna7MF^nPl=J6=-u|4`wE>qZM(fcd;^x!HTr_B z!ecEW*A0N_5~%0??Y++U$I_0&{G4(VA((IlrM0A^=5xSEUDHBf+bar$l;HU#7o>}S zec$$@T)M*RcVkUQIMX|PWm2iR!@tsrR@uKUih}i`pl<5@AQuz`;*c=GrPI+e-ON@O z;W3k>*oiujP<>#Vc5G5PmM0YJ7M;apV##buA>Y#-$}Hf;gS2Ut=vWIS=>Y>*)EJ|9 z9Bm$dZqY$`t;9+;7!@ks@jbXKI|u zW!~;SfR+tU-jR}$)XImJ2S!{PM9h06!dvAlhdUtl6L$DxZ*7xbD+D`E3+YEbAPpP?DxNWa|7%3dQA_ml$!AbKk+c)vKnSd! zF)CT`9^~%DiBu3;$9?R_$A8f0@fPh3niwhHXK$c~dN`9lyaiiuV*q~?T&8o6`4a64 znBpp7+MKrf47?;N6{yfhnOM+E;*8@i)v#CmcWg0!M9>=FrvCEz{QD^)E#>m>gIw;q zjQ&sMeef<)2~~ngcsYsZ(dZCEwr1lDJT&^uWz=jsIO1{gW(xSpui%jCQw*TZ`wmQJ zdK}>9g1`IfiQW_GyoU=IzfTF`xeOBHs{WC@_p7fRL*`tX{HcFzKkrB{H9WRdUd(6m zXLHMzZ=?|Z?{;Ua^y%xEJk>4DpoZSN*485(egGHr^}tuWwfN18X&D zkV_d2Ez58{MR*v{oBSU6x}FD?ZoGc|f?Df)*u>XAW=8%Mlk7YqStZY0n3Lc*oRdH4 gISsf8`3`;}hLzgV-gk}g6KFeq-_Jv4G; + +// if(_dirs == 8){ +// cost += (_n_i < 4 ? dist_scale_factor_ : dd_2D_); //This is more efficient +// }else{ +// cost += (_n_i < 6 ? dist_scale_factor_ : (_n_i < 18 ? dd_2D_ : dd_3D_)); //This is more efficient +// } + +// // auto cost_term = static_cast(cost_weight_ * _suc->cost * dist_scale_factor_reduced_); +// // IROS +// // auto cost_term = static_cast(cost_weight_ * ((_current->cost + _suc->cost)/2) * dist_scale_factor_reduced_); //+grad_suc +// // RA-L +// auto cost_term = static_cast(cost_weight_ * (1/(((static_cast(_current->cost) + static_cast(_suc->cost))/2) * dist_scale_factor_reduced_))); +// cost += cost_term; +// _suc->C = cost_term; + +// return cost; +// } + +inline unsigned int AStarSemantic::computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs){ + unsigned int cost = _current->G; + unsigned int cost2 = 0; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + c_wall=1; + c_door=3; + c_colum=2.5; + c_furnish=1; + c_stair=1.5; + c_panel=1.5; + c_lamp=2; + c_glass=2; + + // c_wall=1; + // c_door=1; + // c_colum=1; + // c_furnish=1; + // c_stair=1; + // c_panel=1; + // c_lamp=1; + // c_glass=1; + + + if(_dirs == 8){ + cost2 = (_n_i < 4 ? dist_scale_factor_ : dd_2D_); //This is more efficient + }else{ + cost2 = (_n_i < 6 ? dist_scale_factor_ : (_n_i < 18 ? dd_2D_ : dd_3D_)); //This is more efficient + } + + // if (_suc->semantic != 1){ + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + // } + + // SEMANTIC COST + // Wall + if (_suc->semantic == 1){ + cost2=c_wall*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Door + else if (_suc->semantic == 2){ + cost2=c_door*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + + // Colum + else if (_suc->semantic == 3){ + cost2=c_colum*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Furnishing + else if (_suc->semantic == 4){ + cost2=c_furnish*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Stairs + else if (_suc->semantic == 5){ + cost2=c_stair*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Panels --> Barandilla + else if (_suc->semantic == 6){ + cost2=c_panel*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Lamp + else if (_suc->semantic == 7){ + cost2=c_lamp*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Glass wall + else if (_suc->semantic == 8){ + cost2=c_glass*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + + cost = cost + cost2; + + _suc->C = _suc->cost; + return cost; +} +} diff --git a/src/Planners/AStarSemanticCost.cpp b/src/Planners/AStarSemanticCost.cpp new file mode 100644 index 0000000..376fee5 --- /dev/null +++ b/src/Planners/AStarSemanticCost.cpp @@ -0,0 +1,148 @@ +#include "Planners/AStarSemanticCost.hpp" + +namespace Planners{ + +AStarSemanticCost::AStarSemanticCost(bool _use_3d):AStar(_use_3d, "astarsemantic_cost") {} +AStarSemanticCost::AStarSemanticCost(bool _use_3d, std::string _name = "astarsemantic_cost" ):AStar(_use_3d, _name) {} + +// // Cost Aware AStar +// inline unsigned int AStarSemantic::computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs){ + +// unsigned int cost = _current->G; + +// if(_dirs == 8){ +// cost += (_n_i < 4 ? dist_scale_factor_ : dd_2D_); //This is more efficient +// }else{ +// cost += (_n_i < 6 ? dist_scale_factor_ : (_n_i < 18 ? dd_2D_ : dd_3D_)); //This is more efficient +// } + +// // auto cost_term = static_cast(cost_weight_ * _suc->cost * dist_scale_factor_reduced_); +// // IROS +// // auto cost_term = static_cast(cost_weight_ * ((_current->cost + _suc->cost)/2) * dist_scale_factor_reduced_); //+grad_suc +// // RA-L +// auto cost_term = static_cast(cost_weight_ * (1/(((static_cast(_current->cost) + static_cast(_suc->cost))/2) * dist_scale_factor_reduced_))); +// cost += cost_term; +// _suc->C = cost_term; + +// return cost; +// } + +inline unsigned int AStarSemanticCost::computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs){ + unsigned int cost = _current->G; + unsigned int cost2 = 0; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + c_wall=1; + c_door=3; + c_colum=2.5; + c_furnish=1; + c_stair=1.5; + c_panel=1.5; + c_lamp=2; + c_glass=2; + + // c_wall=1; + // c_door=1; + // c_colum=1; + // c_furnish=1; + // c_stair=1; + // c_panel=1; + // c_lamp=1; + // c_glass=1; + + + if(_dirs == 8){ + cost2 = (_n_i < 4 ? dist_scale_factor_ : dd_2D_); //This is more efficient + }else{ + cost2 = (_n_i < 6 ? dist_scale_factor_ : (_n_i < 18 ? dd_2D_ : dd_3D_)); //This is more efficient + } + + // if (_suc->semantic != 1){ + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + // } + + // SEMANTIC COST + // Wall + if (_suc->semantic == 1){ + cost2=c_wall*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Door + else if (_suc->semantic == 2){ + cost2=c_door*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + + // Colum + else if (_suc->semantic == 3){ + cost2=c_colum*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Furnishing + else if (_suc->semantic == 4){ + cost2=c_furnish*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Stairs + else if (_suc->semantic == 5){ + cost2=c_stair*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Panels --> Barandilla + else if (_suc->semantic == 6){ + cost2=c_panel*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Lamp + else if (_suc->semantic == 7){ + cost2=c_lamp*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Glass wall + else if (_suc->semantic == 8){ + cost2=c_glass*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + + cost = cost + cost2; + + _suc->C = _suc->cost; + return cost; +} +} diff --git a/src/Planners/LazyThetaStarSemantic.cpp b/src/Planners/LazyThetaStarSemantic.cpp new file mode 100644 index 0000000..d6ef0a5 --- /dev/null +++ b/src/Planners/LazyThetaStarSemantic.cpp @@ -0,0 +1,297 @@ +#include "Planners/LazyThetaStarSemantic.hpp" + +namespace Planners +{ + LazyThetaStarSemantic::LazyThetaStarSemantic(bool _use_3d):ThetaStarSemantic(_use_3d, "lazythetastar_semantic") {} + LazyThetaStarSemantic::LazyThetaStarSemantic(bool _use_3d, std::string _name = "lazythetastar_semantic" ):ThetaStarSemantic(_use_3d, _name) {} + + void LazyThetaStarSemantic::SetVertex(Node *_s_aux) + { + + // line_of_sight_checks_++; + // if (!LineOfSight::bresenham3DWithMaxThreshold(_s_aux->parent, _s_aux, discrete_world_, max_line_of_sight_cells_ )) + // { + // unsigned int G_max = std::numeric_limits::max(); + // unsigned int G_new; + + if( !los_neighbour_ ){ + + unsigned int G_max = std::numeric_limits::max(); + unsigned int G_new; + + for (const auto &i: direction) + { + Vec3i newCoordinates(_s_aux->coordinates + i); + Node *successor2 = discrete_world_.getNodePtr(newCoordinates); + if (successor2 == nullptr || successor2->occuppied ) continue; + + if ( successor2->isInClosedList ) + { + // Semantic cost of the succesor + + unsigned int cost_semantic = 0; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // float coef, c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // coef=1; + c_wall=coef; + c_door=3*coef; + c_colum=2.5*coef; + c_furnish=1*coef; + // c_stair=1; + c_stair=1.5*coef; + c_panel=1.5*coef; + c_lamp=2*coef; + c_glass=2*coef; + + auto distance = geometry::distanceBetween2Nodes(successor2, _s_aux); + + // SEMANTIC COST + // Wall + if (successor2->semantic == 1){ + cost_semantic=c_wall*distance; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Door + else if (successor2->semantic == 2){ + cost_semantic=c_door*distance; + } + + // Colum + else if (successor2->semantic == 3){ + cost_semantic=c_colum*distance; + } + // Furnishing + else if (successor2->semantic == 4){ + cost_semantic=c_furnish*distance; + } + // Stairs + else if (successor2->semantic == 5){ + cost_semantic=c_stair*distance; + } + // Panels --> Barandilla + else if (successor2->semantic == 6){ + cost_semantic=c_panel*distance; + } + // Lamp + else if (successor2->semantic == 7){ + cost_semantic=c_lamp*distance; + } + // Glass wall + else if (successor2->semantic == 8){ + cost_semantic=c_glass*distance; + } + else + cost_semantic=distance; + + G_new = successor2->G + cost_semantic; + if (G_new < G_max) + { + G_max = G_new; + _s_aux->parent = successor2; + _s_aux->G = G_new; + _s_aux->C = cost_semantic; + _s_aux->gplush = _s_aux->G + _s_aux->H; + } + } + } + } + los_neighbour_ = false; + } + + inline void LazyThetaStarSemantic::ComputeCost(Node *_s_aux, Node *_s2_aux) + { + + // // WITHOUT CONSIDERING A MAXIMUM LINE OF SIGHT + // line_of_sight_checks_++; + // if (LineOfSight::bresenham3D(_s_aux->parent, _s2_aux, discrete_world_, checked_nodes)) { + + // los_neighbour_ = true; + + // auto dist2 = geometry::distanceBetween2Nodes(_s_aux->parent, _s2_aux); + // auto edge2 = ComputeSemanticEdgeCost(checked_nodes, _s_aux->parent, _s2_aux); + // if (edge2 == 0){ + // edge2 = 1; + // } + + // if ( ( _s_aux->parent->G + (dist2 * edge2) ) < _s2_aux->G ) + // { + // _s2_aux->parent = _s_aux->parent; + // _s2_aux->G = _s2_aux->parent->G + (dist2 * edge2); + // _s2_aux->C = dist2 * edge2; + // _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + // } + // } + // checked_nodes->clear(); + + // CONSIDERIN A MAXIMUM LINE OF SIGHT --> CORRECT + line_of_sight_checks_++; + auto distanceParent2_nodes = LineOfSight::nodesInLineBetweenTwoNodes(_s_aux->parent, _s2_aux, discrete_world_, max_line_of_sight_cells_); //REVISAR _s_aux->parent o _s_aux + // std::cout << "distanceParent2_nodes: " << distanceParent2_nodes << std::endl; + + // No line of sight or distance greater than max_line_of_sight_cells + if ( distanceParent2_nodes == 0 ){ + distanceParent2_nodes = 1; + } + // Line of sight + else{ + if (LineOfSight::bresenham3D(_s_aux->parent, _s2_aux, discrete_world_, checked_nodes)) { + + los_neighbour_ = true; + + auto dist2 = geometry::distanceBetween2Nodes(_s_aux->parent, _s2_aux); + auto edge2 = ComputeSemanticEdgeCost(checked_nodes, _s_aux->parent, _s2_aux); + if (edge2 == 0){ + edge2 = 1; + } + + if ( ( _s_aux->parent->G + (dist2 * edge2) ) < _s2_aux->G ) + { + _s2_aux->parent = _s_aux->parent; + _s2_aux->G = _s2_aux->parent->G + (dist2 * edge2); + _s2_aux->C = dist2 * edge2; + _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + } + } + } + checked_nodes->clear(); + } + + inline unsigned int LazyThetaStarSemantic::computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs){ + + // unsigned int cost = 0; + unsigned int cost = _current->G; + unsigned int cost2 = 0; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // float coef, c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // coef=1; + c_wall=coef; + c_door=3*coef; + c_colum=2.5*coef; + c_furnish=1*coef; + // c_stair=1; + c_stair=1.5*coef; + c_panel=1.5*coef; + c_lamp=2*coef; + c_glass=2*coef; + + if(_dirs == 8){ + cost2 = (_n_i < 4 ? dist_scale_factor_ : dd_2D_); //This is more efficient + }else{ + cost2 = (_n_i < 6 ? dist_scale_factor_ : (_n_i < 18 ? dd_2D_ : dd_3D_)); //This is more efficient + } + + // double cc = ( _current->cost + _suc->cost ) / 2; + // auto edge_neighbour = static_cast( cc * cost_weight_ * dist_scale_factor_reduced_); + + // cost += ( _current->G + edge_neighbour ); + + // _suc->C = edge_neighbour; + + // SEMANTIC COST + // Wall + if (_suc->semantic == 1){ + cost2=c_wall*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Door + else if (_suc->semantic == 2){ + cost2=c_door*cost2; + } + + // Colum + else if (_suc->semantic == 3){ + cost2=c_colum*cost2; + } + // Furnishing + else if (_suc->semantic == 4){ + cost2=c_furnish*cost2; + } + // Stairs + else if (_suc->semantic == 5){ + cost2=c_stair*cost2; + } + // Panels --> Barandilla + else if (_suc->semantic == 6){ + cost2=c_panel*cost2; + } + // Lamp + else if (_suc->semantic == 7){ + cost2=c_lamp*cost2; + } + // Glass wall + else if (_suc->semantic == 8){ + cost2=c_glass*cost2; + } + + cost = cost + cost2; + + _suc->C = _suc->cost; + + return cost; + } + + PathData LazyThetaStarSemantic::findPath(const Vec3i &_source, const Vec3i &_target) + { + utils::Clock main_timer; + main_timer.tic(); + + MagicalMultiSet openSet; + + Node *current = nullptr; + line_of_sight_checks_ = 0; + + bool solved{false}; + + discrete_world_.getNodePtr(_source)->parent = new Node(_source); + discrete_world_.setOpenValue(_source, true); + + node_by_cost& indexByCost = openSet.get(); + node_by_position& indexByWorldPosition = openSet.get(); + + indexByCost.insert(discrete_world_.getNodePtr(_source)); + while (!indexByCost.empty()) + { + auto it = indexByCost.begin(); + current = *it; + indexByCost.erase(indexByCost.begin()); + + if (current->coordinates == _target) + { + solved = true; + break; + } + closedSet_.push_back(current); + + current->isInOpenList = false; + current->isInClosedList = true; + + SetVertex(current); +#if defined(ROS) && defined(PUB_EXPLORED_NODES) + publishROSDebugData(current, indexByCost, closedSet_); +#endif + exploreNeighbours(current, _target, indexByWorldPosition); + } + main_timer.toc(); + PathData result_data = createResultDataObject(current, main_timer, closedSet_.size(), + solved, _source, line_of_sight_checks_); + +#if defined(ROS) && defined(PUB_EXPLORED_NODES) + explored_node_marker_.points.clear(); +#endif + closedSet_.clear(); + delete discrete_world_.getNodePtr(_source)->parent; + + discrete_world_.resetWorld(); + return result_data; + } +} diff --git a/src/Planners/LazyThetaStarSemanticCost.cpp b/src/Planners/LazyThetaStarSemanticCost.cpp new file mode 100644 index 0000000..2675a65 --- /dev/null +++ b/src/Planners/LazyThetaStarSemanticCost.cpp @@ -0,0 +1,332 @@ +#include "Planners/LazyThetaStarSemanticCost.hpp" + +namespace Planners +{ + LazyThetaStarSemanticCost::LazyThetaStarSemanticCost(bool _use_3d):ThetaStarSemanticCost(_use_3d, "lazythetastar_semantic_cost") {} + // LazyThetaStarSemanticCost::LazyThetaStarSemanticCost(bool _use_3d):ThetaStarSemantic(_use_3d, "lazythetastar_semantic_cost") {} + LazyThetaStarSemanticCost::LazyThetaStarSemanticCost(bool _use_3d, std::string _name = "lazythetastar_semantic_cost" ):ThetaStarSemanticCost(_use_3d, _name) {} + // LazyThetaStarSemanticCost::LazyThetaStarSemanticCost(bool _use_3d, std::string _name = "lazythetastar_semantic_cost" ):ThetaStarSemantic(_use_3d, _name) {} + + void LazyThetaStarSemanticCost::SetVertex(Node *_s_aux) + { + + // line_of_sight_checks_++; + // if (!LineOfSight::bresenham3DWithMaxThreshold(_s_aux->parent, _s_aux, discrete_world_, max_line_of_sight_cells_ )) + // { + // unsigned int G_max = std::numeric_limits::max(); + // unsigned int G_new; + + if( !los_neighbour_ ){ + + unsigned int G_max = std::numeric_limits::max(); + unsigned int G_new; + + for (const auto &i: direction) + { + Vec3i newCoordinates(_s_aux->coordinates + i); + Node *successor2 = discrete_world_.getNodePtr(newCoordinates); + if (successor2 == nullptr || successor2->occuppied ) continue; + + if ( successor2->isInClosedList ) + { + // Semantic cost of the succesor + + unsigned int cost_semantic = 0; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + float coste; + // float coef,c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // coef=1; + c_wall=coef; + c_door=3*coef; + c_colum=2.5*coef; + c_furnish=1*coef; + c_stair=1.5*coef; + c_panel=1.5*coef; + c_lamp=2*coef; + c_glass=2*coef; + + // coste=1+static_cast(successor2->cost); + coste=static_cast(successor2->cost); + + auto distance = geometry::distanceBetween2Nodes(successor2, _s_aux); + + // Wall + if (successor2->semantic == 1){ + // cost_semantic=(c_wall/(1+static_cast(successor2->cost)))*distance; // + distance; + cost_semantic=(c_wall/coste)*distance; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Door + else if (successor2->semantic == 2){ + // cost_semantic=(c_door/(1+static_cast(successor2->cost)))*distance; // + distance; + cost_semantic=(c_door/coste)*distance; + } + + // Colum + else if (successor2->semantic == 3){ + // cost_semantic=(c_colum/(1+static_cast(successor2->cost)))*distance; // + distance; + cost_semantic=(c_colum/coste)*distance; + } + // Furnishing + else if (successor2->semantic == 4){ + // cost_semantic=(c_furnish/(1+static_cast(successor2->cost)))*distance; // + distance; + cost_semantic=(c_furnish/coste)*distance; + } + // Stairs + else if (successor2->semantic == 5){ + // cost_semantic=(c_stair/(1+static_cast(successor2->cost)))*distance; // + distance; + cost_semantic=(c_stair/coste)*distance; + } + // Panels --> Barandilla + else if (successor2->semantic == 6){ + // cost_semantic=(c_panel/(1+static_cast(successor2->cost)))*distance; // + distance; + cost_semantic=(c_panel/coste)*distance; + } + // Lamp + else if (successor2->semantic == 7){ + // cost_semantic=(c_lamp/(1+static_cast(successor2->cost)))*distance; // + distance; + cost_semantic=(c_lamp/coste)*distance; + } + // Glass wall + else if (successor2->semantic == 8){ + // cost_semantic=(c_glass/(1+static_cast(successor2->cost)))*distance; // + distance; + cost_semantic=(c_glass/coste)*distance; + } + else + cost_semantic=distance; + + G_new = successor2->G + cost_semantic; + if (G_new < G_max) + { + G_max = G_new; + _s_aux->parent = successor2; + _s_aux->G = G_new; + _s_aux->C = cost_semantic; + _s_aux->gplush = _s_aux->G + _s_aux->H; + } + } + } + } + los_neighbour_ = false; + } + + inline void LazyThetaStarSemanticCost::ComputeCost(Node *_s_aux, Node *_s2_aux) + { + // // WITHOUT CONSIDERING A MAXIMUM LINE OF SIGHT + // line_of_sight_checks_++; + // if (LineOfSight::bresenham3D(_s_aux->parent, _s2_aux, discrete_world_, checked_nodes)) { + + // los_neighbour_ = true; + + // auto dist2 = geometry::distanceBetween2Nodes(_s_aux->parent, _s2_aux); + // auto edge2 = ComputeSemanticEdgeCost(checked_nodes, _s_aux->parent, _s2_aux); + // if (edge2 == 0){ + // edge2 = 1; + // } + + // if ( ( _s_aux->parent->G + (dist2 * edge2) ) < _s2_aux->G ) + // { + // _s2_aux->parent = _s_aux->parent; + // _s2_aux->G = _s2_aux->parent->G + (dist2 * edge2); + // _s2_aux->C = dist2 * edge2; + // _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + // } + // } + // checked_nodes->clear(); + + // CONSIDERIN A MAXIMUM LINE OF SIGHT --> CORRECT + line_of_sight_checks_++; + auto distanceParent2_nodes = LineOfSight::nodesInLineBetweenTwoNodes(_s_aux->parent, _s2_aux, discrete_world_, max_line_of_sight_cells_); //REVISAR _s_aux->parent o _s_aux + // std::cout << "distanceParent2_nodes: " << distanceParent2_nodes << std::endl; + + // No line of sight or distance greater than max_line_of_sight_cells + if ( distanceParent2_nodes == 0 ){ + distanceParent2_nodes = 1; + } + // Line of sight + else{ + if (LineOfSight::bresenham3D(_s_aux->parent, _s2_aux, discrete_world_, checked_nodes)) { + + los_neighbour_ = true; + + auto dist2 = geometry::distanceBetween2Nodes(_s_aux->parent, _s2_aux); + auto edge2 = ComputeSemanticEdgeCost(checked_nodes, _s_aux->parent, _s2_aux); + if (edge2 == 0){ + edge2 = 1; + } + + if ( ( _s_aux->parent->G + (dist2 * edge2) ) < _s2_aux->G ) + { + _s2_aux->parent = _s_aux->parent; + _s2_aux->G = _s2_aux->parent->G + (dist2 * edge2); + _s2_aux->C = dist2 * edge2; + _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + } + } + } + checked_nodes->clear(); + } + + inline unsigned int LazyThetaStarSemanticCost::computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs){ + + // unsigned int cost = 0; + unsigned int cost = _current->G; + unsigned int cost2 = 0; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // float coef,c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // coef=1; + // std::cout << "coef: " << coef << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + + c_wall=coef; + c_door=3*coef; + c_colum=2.5*coef; + c_furnish=1*coef; + c_stair=1.5*coef; + c_panel=1.5*coef; + c_lamp=2*coef; + c_glass=2*coef; + + if(_dirs == 8){ + cost2 = (_n_i < 4 ? dist_scale_factor_ : dd_2D_); //This is more efficient + }else{ + cost2 = (_n_i < 6 ? dist_scale_factor_ : (_n_i < 18 ? dd_2D_ : dd_3D_)); //This is more efficient + } + + float coste; + // coste=1+static_cast(_suc->cost); + coste=static_cast(_suc->cost); + + // double cc = ( _current->cost + _suc->cost ) / 2; + // auto edge_neighbour = static_cast( cc * cost_weight_ * dist_scale_factor_reduced_); + + // cost += ( _current->G + edge_neighbour ); + + // _suc->C = edge_neighbour; + + // SEMANTIC COST + // std::cout << "c_colum: " << c_colum << std::endl; + // std::cout << "cost: " << static_cast(_suc->cost) << std::endl; + // std::cout << "divisin: " << (c_colum/static_cast(_suc->cost)) << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + // Wall + if (_suc->semantic == 1){ + // cost2=(c_wall/(1+static_cast(_suc->cost)))*cost2; // + cost2; + cost2=(c_wall/coste)*cost2; + + // cost2=(c_wall/static_cast(_suc->cost))*cost2 + cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Door + else if (_suc->semantic == 2){ + // cost2=(c_door/(1+static_cast(_suc->cost)))*cost2; // + cost2; + cost2=(c_door/coste)*cost2; + } + + // Colum + else if (_suc->semantic == 3){ + // cost2=(c_colum/(1+static_cast(_suc->cost)))*cost2; // + cost2; + cost2=(c_colum/coste)*cost2; + } + // Furnishing + else if (_suc->semantic == 4){ + // cost2=(c_furnish/(1+static_cast(_suc->cost)))*cost2; // + cost2; + cost2=(c_furnish/coste)*cost2; + } + // Stairs + else if (_suc->semantic == 5){ + // cost2=(c_stair/(1+static_cast(_suc->cost)))*cost2; // + cost2; + cost2=(c_stair/coste)*cost2; + } + // Panels --> Barandilla + else if (_suc->semantic == 6){ + // cost2=(c_panel/(1+static_cast(_suc->cost)))*cost2; // + cost2; + cost2=(c_panel/coste)*cost2; + } + // Lamp + else if (_suc->semantic == 7){ + // cost2=(c_lamp/(1+static_cast(_suc->cost)))*cost2; // + cost2; + cost2=(c_lamp/coste)*cost2; + } + // Glass wall + else if (_suc->semantic == 8){ + // cost2=(c_glass/(1+static_cast(_suc->cost)))*cost2; // + cost2; + cost2=(c_glass/coste)*cost2; + } + + cost = cost + cost2; + + _suc->C = _suc->cost; + + return cost; + } + + PathData LazyThetaStarSemanticCost::findPath(const Vec3i &_source, const Vec3i &_target) + { + utils::Clock main_timer; + main_timer.tic(); + + MagicalMultiSet openSet; + + Node *current = nullptr; + line_of_sight_checks_ = 0; + + bool solved{false}; + + discrete_world_.getNodePtr(_source)->parent = new Node(_source); + discrete_world_.setOpenValue(_source, true); + + node_by_cost& indexByCost = openSet.get(); + node_by_position& indexByWorldPosition = openSet.get(); + + indexByCost.insert(discrete_world_.getNodePtr(_source)); + while (!indexByCost.empty()) + { + auto it = indexByCost.begin(); + current = *it; + indexByCost.erase(indexByCost.begin()); + + if (current->coordinates == _target) + { + solved = true; + break; + } + closedSet_.push_back(current); + + current->isInOpenList = false; + current->isInClosedList = true; + + SetVertex(current); +#if defined(ROS) && defined(PUB_EXPLORED_NODES) + publishROSDebugData(current, indexByCost, closedSet_); +#endif + exploreNeighbours(current, _target, indexByWorldPosition); + } + main_timer.toc(); + PathData result_data = createResultDataObject(current, main_timer, closedSet_.size(), + solved, _source, line_of_sight_checks_); + +#if defined(ROS) && defined(PUB_EXPLORED_NODES) + explored_node_marker_.points.clear(); +#endif + closedSet_.clear(); + delete discrete_world_.getNodePtr(_source)->parent; + + discrete_world_.resetWorld(); + return result_data; + } +} diff --git a/src/Planners/ThetaStarSemantic.cpp b/src/Planners/ThetaStarSemantic.cpp new file mode 100644 index 0000000..f6201e2 --- /dev/null +++ b/src/Planners/ThetaStarSemantic.cpp @@ -0,0 +1,276 @@ +#include "Planners/ThetaStarSemantic.hpp" + +namespace Planners +{ + ThetaStarSemantic::ThetaStarSemantic(bool _use_3d):ThetaStar(_use_3d, "thetastar_semantic") {} + ThetaStarSemantic::ThetaStarSemantic(bool _use_3d, std::string _name = "thetastar_semantic" ):ThetaStar(_use_3d, _name) {} + + inline void ThetaStarSemantic::ComputeCost(Node *_s_aux, Node *_s2_aux) + { + line_of_sight_checks_++; + if (LineOfSight::bresenham3D(_s_aux->parent, _s2_aux, discrete_world_, checked_nodes)) + { + auto dist2 = geometry::distanceBetween2Nodes(_s_aux->parent, _s2_aux); + auto edge2 = ComputeSemanticEdgeCost(checked_nodes, _s_aux->parent, _s2_aux); + if (edge2 == 0) + edge2 = 1; + + line_of_sight_checks_++; + LineOfSight::bresenham3D(_s_aux, _s2_aux, discrete_world_, checked_nodes_current); + + auto dist1 = geometry::distanceBetween2Nodes(_s_aux, _s2_aux); + auto edge1 = ComputeSemanticEdgeCost(checked_nodes_current, _s_aux, _s2_aux); + if (edge1 == 0) + edge1 = 1; + + if ( ( _s_aux->parent->G + (dist2 * edge2) ) < ( _s_aux->G + (dist1 * edge1))) + { + _s2_aux->parent = _s_aux->parent; + _s2_aux->G = _s_aux->parent->G + (dist2 * edge2); // This is the same than A* + _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + _s2_aux->C = edge2 * dist2; + } + else{ + _s2_aux->parent =_s_aux; + _s2_aux->G = _s_aux->G + (dist1 * edge1); // This is the same than A* + _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + _s2_aux->C = edge1 * dist1; + } + } else { + + _s2_aux->parent=_s_aux; + + line_of_sight_checks_++; + LineOfSight::bresenham3D(_s_aux, _s2_aux, discrete_world_, checked_nodes); + + auto dist1 = geometry::distanceBetween2Nodes(_s_aux, _s2_aux); + auto edge1 = ComputeSemanticEdgeCost(checked_nodes, _s_aux, _s2_aux); + if (edge1 == 0) + edge1 = 1; + + _s2_aux->G = _s_aux->G + (dist1 * edge1); // This is the same than A* + _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + _s2_aux->C = edge1 * dist1; + } + checked_nodes->clear(); + checked_nodes_current->clear(); + } + + inline unsigned int ThetaStarSemantic::ComputeSemanticEdgeCost(const utils::CoordinateListPtr _checked_nodes, const Node* _s, const Node* _s2){ + + double cost_semantic{0}; + double mean_cost_semantic{0}; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // float coef, c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // coef=1; + c_wall=coef; + c_door=3*coef; + c_colum=2.5*coef; + c_furnish=1*coef; + // c_stair=1; + c_stair=1.5*coef; + c_panel=1.5*coef; + c_lamp=2*coef; + c_glass=2*coef; + + auto n_checked_nodes = _checked_nodes->size(); + + if( n_checked_nodes >= 1 ){ + // std::cout << "Nodes: " << n_checked_nodes << std::endl; + for(auto &it: *_checked_nodes){ + // if (discrete_world_.getNodePtr(it)->semantic !=0){ + // std::cout << "COSTE: " << discrete_world_.getNodePtr(it)->cost << std::endl; + // std::cout << "COSTE SEMANTICO: " << discrete_world_.getNodePtr(it)->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + // } + + if (discrete_world_.getNodePtr(it)->semantic == 1) + cost_semantic += c_wall; + else if (discrete_world_.getNodePtr(it)->semantic == 2) + cost_semantic += c_door; + else if (discrete_world_.getNodePtr(it)->semantic == 3) + cost_semantic += c_colum; + else if (discrete_world_.getNodePtr(it)->semantic == 4) + cost_semantic += c_furnish; + else if (discrete_world_.getNodePtr(it)->semantic == 5) + cost_semantic += c_stair; + else if (discrete_world_.getNodePtr(it)->semantic == 6) + cost_semantic += c_panel; + else if (discrete_world_.getNodePtr(it)->semantic == 7) + cost_semantic += c_lamp; + else if (discrete_world_.getNodePtr(it)->semantic == 8) + cost_semantic += c_glass; + + } + } + // if (cost_semantic != 0){ + // std::cout << "cost_semantic: " << cost_semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + // } + + if( n_checked_nodes >= 1){ + if (_s->semantic == 1) + cost_semantic += c_wall; + else if (_s->semantic == 2) + cost_semantic += c_door; + else if (_s->semantic == 3) + cost_semantic += c_colum; + else if (_s->semantic == 4) + cost_semantic += c_furnish; + else if (_s->semantic == 5) + cost_semantic += c_stair; + else if (_s->semantic == 6) + cost_semantic += c_panel; + else if (_s->semantic == 7) + cost_semantic += c_lamp; + else if (_s->semantic == 8) + cost_semantic += c_glass; + + if (_s2->semantic == 1) + cost_semantic += c_wall; + else if (_s2->semantic == 2) + cost_semantic += c_door; + else if (_s2->semantic == 3) + cost_semantic += c_colum; + else if (_s2->semantic == 4) + cost_semantic += c_furnish; + else if (_s2->semantic == 5) + cost_semantic += c_stair; + else if (_s2->semantic == 6) + cost_semantic += c_panel; + else if (_s2->semantic == 7) + cost_semantic += c_lamp; + else if (_s2->semantic == 8) + cost_semantic += c_glass; + mean_cost_semantic = cost_semantic/(n_checked_nodes+1); // Dividir entre el numero de nodos + // mean_cost_semantic = cost_semantic/(n_checked_nodes+1); } + } + // checked_nodes == 0 + else{ + cost_semantic = 0; + if (_s->semantic == 1) + cost_semantic += c_wall; + else if (_s->semantic == 2) + cost_semantic += c_door; + else if (_s->semantic == 3) + cost_semantic += c_colum; + else if (_s->semantic == 4) + cost_semantic += c_furnish; + else if (_s->semantic == 5) + cost_semantic += c_stair; + else if (_s->semantic == 6) + cost_semantic += c_panel; + else if (_s->semantic == 7) + cost_semantic += c_lamp; + else if (_s->semantic == 8) + cost_semantic += c_glass; + else + cost_semantic=0; + + if (_s2->semantic == 1) + cost_semantic += c_wall; + else if (_s2->semantic == 2) + cost_semantic += c_door; + else if (_s2->semantic == 3) + cost_semantic += c_colum; + else if (_s2->semantic == 4) + cost_semantic += c_furnish; + else if (_s2->semantic == 5) + cost_semantic += c_stair; + else if (_s2->semantic == 6) + cost_semantic += c_panel; + else if (_s2->semantic == 7) + cost_semantic += c_lamp; + else if (_s2->semantic == 8) + cost_semantic += c_glass; + else + cost_semantic=0; + mean_cost_semantic = cost_semantic/2; // Dividir entre el numero de nodos + // mean_cost_semantic = cost_semantic; + } + // return static_cast( mean_cost_semantic * dist_scale_factor_reduced_); + // std::cout << "edge: " << mean_cost_semantic << std::endl; + return static_cast( mean_cost_semantic); + } + + inline unsigned int ThetaStarSemantic::computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs){ + + unsigned int cost = _current->G; + unsigned int cost2 = 0; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // float coef, c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // coef=1; + c_wall=coef; + c_door=3*coef; + c_colum=2.5*coef; + c_furnish=1*coef; + // c_stair=1; + c_stair=1.5*coef; + c_panel=1.5*coef; + c_lamp=2*coef; + c_glass=2*coef; + + if(_dirs == 8){ + cost2 += (_n_i < 4 ? dist_scale_factor_ : dd_2D_); //This is more efficient + }else{ + cost2 += (_n_i < 6 ? dist_scale_factor_ : (_n_i < 18 ? dd_2D_ : dd_3D_)); //This is more efficient + } + + // EDF COST --> ThetarStarM1 + // auto cost_term = static_cast(cost_weight_ * _suc->cost * dist_scale_factor_reduced_); + // cost += cost_term; + // _suc->C = cost_term; + + // SEMANTIC COST + // Wall + if (_suc->semantic == 1){ + cost2=c_wall*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Door + else if (_suc->semantic == 2){ + cost2=c_door*cost2; + } + + // Colum + else if (_suc->semantic == 3){ + cost2=c_colum*cost2; + } + // Furnishing + else if (_suc->semantic == 4){ + cost2=c_furnish*cost2; + } + // Stairs + else if (_suc->semantic == 5){ + cost2=c_stair*cost2; + } + // Panels --> Barandilla + else if (_suc->semantic == 6){ + cost2=c_panel*cost2; + } + // Lamp + else if (_suc->semantic == 7){ + cost2=c_lamp*cost2; + } + // Glass wall + else if (_suc->semantic == 8){ + cost2=c_glass*cost2; + } + + cost = cost + cost2; + + _suc->C = _suc->cost; + + return cost; + } +} diff --git a/src/Planners/ThetaStarSemanticCost.cpp b/src/Planners/ThetaStarSemanticCost.cpp new file mode 100644 index 0000000..2abea31 --- /dev/null +++ b/src/Planners/ThetaStarSemanticCost.cpp @@ -0,0 +1,345 @@ +#include "Planners/ThetaStarSemanticCost.hpp" + +namespace Planners +{ + ThetaStarSemanticCost::ThetaStarSemanticCost(bool _use_3d):ThetaStar(_use_3d, "thetastar_semantic_cost") {} + ThetaStarSemanticCost::ThetaStarSemanticCost(bool _use_3d, std::string _name = "thetastar_semantic_cost" ):ThetaStar(_use_3d, _name) {} + + inline void ThetaStarSemanticCost::ComputeCost(Node *_s_aux, Node *_s2_aux) + { + line_of_sight_checks_++; + if (LineOfSight::bresenham3D(_s_aux->parent, _s2_aux, discrete_world_, checked_nodes)) + { + auto dist2 = geometry::distanceBetween2Nodes(_s_aux->parent, _s2_aux); + auto edge2 = ComputeSemanticEdgeCost(checked_nodes, _s_aux->parent, _s2_aux); + if (edge2 == 0) + edge2 = 1; + + line_of_sight_checks_++; + LineOfSight::bresenham3D(_s_aux, _s2_aux, discrete_world_, checked_nodes_current); + + auto dist1 = geometry::distanceBetween2Nodes(_s_aux, _s2_aux); + auto edge1 = ComputeSemanticEdgeCost(checked_nodes_current, _s_aux, _s2_aux); + if (edge1 == 0) + edge1 = 1; + + if ( ( _s_aux->parent->G + (dist2 * edge2) ) < ( _s_aux->G + (dist1 * edge1))) + { + _s2_aux->parent = _s_aux->parent; + _s2_aux->G = _s_aux->parent->G + (dist2 * edge2);// + dist2; // This is the same than A* + _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + _s2_aux->C = edge2 * dist2; + } + else{ + _s2_aux->parent =_s_aux; + _s2_aux->G = _s_aux->G + (dist1 * edge1);// + dist1; // This is the same than A* + _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + _s2_aux->C = edge1 * dist1; + } + } else { + + _s2_aux->parent=_s_aux; + + line_of_sight_checks_++; + LineOfSight::bresenham3D(_s_aux, _s2_aux, discrete_world_, checked_nodes); + + auto dist1 = geometry::distanceBetween2Nodes(_s_aux, _s2_aux); + auto edge1 = ComputeSemanticEdgeCost(checked_nodes, _s_aux, _s2_aux); + if (edge1 == 0) + edge1 = 1; + + _s2_aux->G = _s_aux->G + (dist1 * edge1);// + dist1; // This is the same than A* + _s2_aux->gplush = _s2_aux->G + _s2_aux->H; + _s2_aux->C = edge1 * dist1; + } + checked_nodes->clear(); + checked_nodes_current->clear(); + } + + inline unsigned int ThetaStarSemanticCost::ComputeSemanticEdgeCost(const utils::CoordinateListPtr _checked_nodes, const Node* _s, const Node* _s2){ + + double cost_semantic{0}; + double mean_cost_semantic{0}; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // float coef, c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // coef=10; + c_wall=coef; + c_door=3*coef; + c_colum=2.5*coef; + c_furnish=1*coef; + c_stair=1.5*coef; + c_panel=1.5*coef; + c_lamp=2*coef; + c_glass=2*coef; + + // Compute semantic cost depending on the distance along of the segment considering all the crossed nodes + auto n_checked_nodes = _checked_nodes->size(); + // std::cout << "Nodes: " << n_checked_nodes << std::endl; + if( n_checked_nodes >= 1 ){ + // std::cout << "Nodes: " << n_checked_nodes << std::endl; + for(auto &it: *_checked_nodes){ + // if (discrete_world_.getNodePtr(it)->semantic !=0){ + // std::cout << "COSTE: " << discrete_world_.getNodePtr(it)->cost << std::endl; + // std::cout << "COSTE SEMANTICO: " << discrete_world_.getNodePtr(it)->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + // } + if (discrete_world_.getNodePtr(it)->semantic == 1) + cost_semantic += c_wall/discrete_world_.getNodePtr(it)->cost; + // cost_semantic += c_wall/(1+discrete_world_.getNodePtr(it)->cost); + else if (discrete_world_.getNodePtr(it)->semantic == 2) + cost_semantic += c_door/discrete_world_.getNodePtr(it)->cost; + // cost_semantic += c_door/(1+discrete_world_.getNodePtr(it)->cost); + else if (discrete_world_.getNodePtr(it)->semantic == 3) + cost_semantic += c_colum/discrete_world_.getNodePtr(it)->cost; + // cost_semantic += c_colum/(1+discrete_world_.getNodePtr(it)->cost); + else if (discrete_world_.getNodePtr(it)->semantic == 4) + cost_semantic += c_furnish/discrete_world_.getNodePtr(it)->cost; + // cost_semantic += c_furnish/(1+discrete_world_.getNodePtr(it)->cost); + else if (discrete_world_.getNodePtr(it)->semantic == 5) + cost_semantic += c_stair/discrete_world_.getNodePtr(it)->cost; + // cost_semantic += c_stair/(1+discrete_world_.getNodePtr(it)->cost); + else if (discrete_world_.getNodePtr(it)->semantic == 6) + cost_semantic += c_panel/discrete_world_.getNodePtr(it)->cost; + // cost_semantic += c_panel/(1+discrete_world_.getNodePtr(it)->cost); + else if (discrete_world_.getNodePtr(it)->semantic == 7) + cost_semantic += c_lamp/discrete_world_.getNodePtr(it)->cost; + // cost_semantic += c_lamp/(1+discrete_world_.getNodePtr(it)->cost); + else if (discrete_world_.getNodePtr(it)->semantic == 8) + cost_semantic += c_glass/discrete_world_.getNodePtr(it)->cost; + // cost_semantic += c_glass/(1+discrete_world_.getNodePtr(it)->cost); + // std::cout << "cost_semantic: " << cost_semantic << std::endl; + } + } + + float coste1, coste2; + // coste1=1+_s->cost; + coste1=_s->cost; + // coste2=1+_s2->cost; + coste2=_s2->cost; + + if( n_checked_nodes >= 1){ + if (_s->semantic == 1) + // cost_semantic += c_wall/_s->cost; + // cost_semantic += c_wall/(1+_s->cost); + cost_semantic += c_wall/(coste1); + else if (_s->semantic == 2) + // cost_semantic += c_door/_s->cost; + // cost_semantic += c_door/(1+_s->cost); + cost_semantic += c_door/(coste1); + else if (_s->semantic == 3) + // cost_semantic += c_colum/_s->cost; + // cost_semantic += c_colum/(1+_s->cost); + cost_semantic += c_colum/(coste1); + else if (_s->semantic == 4) + // cost_semantic += c_furnish/_s->cost; + // cost_semantic += c_furnish/(1+_s->cost); + cost_semantic += c_furnish/(coste1); + else if (_s->semantic == 5) + // cost_semantic += c_stair/_s->cost; + // cost_semantic += c_stair/(1+_s->cost); + cost_semantic += c_stair/(coste1); + else if (_s->semantic == 6) + // cost_semantic += c_panel/_s->cost; + // cost_semantic += c_panel/(1+_s->cost); + cost_semantic += c_panel/(coste1); + else if (_s->semantic == 7) + // cost_semantic += c_lamp/_s->cost; + // cost_semantic += c_lamp/(1+_s->cost); + cost_semantic += c_lamp/(coste1); + else if (_s->semantic == 8) + // cost_semantic += c_glass/_s->cost; + // cost_semantic += c_glass/(1+_s->cost); + cost_semantic += c_glass/(coste1); + + if (_s2->semantic == 1) + // cost_semantic += c_wall/_s2->cost; + // cost_semantic += c_wall/(1+_s2->cost); + cost_semantic += c_wall/(coste2); + else if (_s2->semantic == 2) + // cost_semantic += c_door/_s2->cost; + // cost_semantic += c_door/(1+_s2->cost); + cost_semantic += c_door/(coste2); + else if (_s2->semantic == 3) + // cost_semantic += c_colum/_s2->cost; + // cost_semantic += c_colum/(1+_s2->cost); + cost_semantic += c_colum/(coste2); + else if (_s2->semantic == 4) + // cost_semantic += c_furnish/_s2->cost; + // cost_semantic += c_furnish/(1+_s2->cost); + cost_semantic += c_furnish/(coste2); + else if (_s2->semantic == 5) + // cost_semantic += c_stair/_s2->cost; + // cost_semantic += c_stair/(1+_s2->cost); + cost_semantic += c_stair/(coste2); + else if (_s2->semantic == 6) + // cost_semantic += c_panel/_s2->cost; + // cost_semantic += c_panel/(1+_s2->cost); + cost_semantic += c_panel/(coste2); + else if (_s2->semantic == 7) + // cost_semantic += c_lamp/_s2->cost; + // cost_semantic += c_lamp/(1+_s2->cost); + cost_semantic += c_lamp/(coste2); + else if (_s2->semantic == 8) + // cost_semantic += c_glass/_s2->cost; + // cost_semantic += c_glass/(1+_s2->cost); + cost_semantic += c_glass/(coste2); + + mean_cost_semantic = cost_semantic/(n_checked_nodes+1); // Dividir entre el numero de nodos + // mean_cost_semantic = cost_semantic; + } + else{ + cost_semantic = 0; + if (_s->semantic == 1) + // cost_semantic += c_wall/_s->cost; + // cost_semantic += c_wall/(1+_s->cost); + cost_semantic += c_wall/(coste1); + else if (_s->semantic == 2) + // cost_semantic += c_door/_s->cost; + // cost_semantic += c_door/(1+_s->cost); + cost_semantic += c_door/(coste1); + else if (_s->semantic == 3) + // cost_semantic += c_colum/_s->cost; + // cost_semantic += c_colum/(1+_s->cost); + cost_semantic += c_colum/(coste1); + else if (_s->semantic == 4) + // cost_semantic += c_furnish/_s->cost; + // cost_semantic += c_furnish/(1+_s->cost); + cost_semantic += c_furnish/(coste1); + else if (_s->semantic == 5) + // cost_semantic += c_stair/_s->cost; + // cost_semantic += c_stair/(1+_s->cost); + cost_semantic += c_stair/(coste1); + else if (_s->semantic == 6) + // cost_semantic += c_panel/_s->cost; + // cost_semantic += c_panel/(1+_s->cost); + cost_semantic += c_panel/(coste1); + else if (_s->semantic == 7) + // cost_semantic += c_lamp/_s->cost; + // cost_semantic += c_lamp/(1+_s->cost); + cost_semantic += c_lamp/(coste1); + else if (_s->semantic == 8) + // cost_semantic += c_glass/_s->cost; + // cost_semantic += c_glass/(1+_s->cost); + cost_semantic += c_glass/(coste1); + else + cost_semantic=0; + + if (_s2->semantic == 1) + // cost_semantic += c_wall/_s2->cost; + // cost_semantic += c_wall/(1+_s2->cost); + cost_semantic += c_wall/(coste2); + else if (_s2->semantic == 2) + // cost_semantic += c_door/_s2->cost; + // cost_semantic += c_door/(1+_s2->cost); + cost_semantic += c_door/(coste2); + else if (_s2->semantic == 3) + // cost_semantic += c_colum/_s2->cost; + // cost_semantic += c_colum/(1+_s2->cost); + cost_semantic += c_colum/(coste2); + else if (_s2->semantic == 4) + // cost_semantic += c_furnish/_s2->cost; + // cost_semantic += c_furnish/(1+_s2->cost); + cost_semantic += c_furnish/(coste2); + else if (_s2->semantic == 5) + // cost_semantic += c_stair/_s2->cost; + // cost_semantic += c_stair/(1+_s2->cost); + cost_semantic += c_stair/(coste2); + else if (_s2->semantic == 6) + // cost_semantic += c_panel/_s2->cost; + // cost_semantic += c_panel/(1+_s2->cost); + cost_semantic += c_panel/(coste2); + else if (_s2->semantic == 7) + // cost_semantic += c_lamp/_s2->cost; + // cost_semantic += c_lamp/(1+_s2->cost); + cost_semantic += c_lamp/(coste2); + else if (_s2->semantic == 8) + // cost_semantic += c_glass/_s2->cost; + // cost_semantic += c_glass/(1+_s2->cost); + cost_semantic += c_glass/(coste2); + else + cost_semantic=0; + mean_cost_semantic = cost_semantic/2; // Dividir entre el numero de nodos + // mean_cost_semantic = cost_semantic; + } + // return static_cast( mean_cost_semantic * dist_scale_factor_reduced_); + return static_cast( mean_cost_semantic); + } + + inline unsigned int ThetaStarSemanticCost::computeG(const Node* _current, Node* _suc, unsigned int _n_i, unsigned int _dirs){ + + unsigned int cost = _current->G; + unsigned int cost2 = 0; + + float c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // float coef, c_wall, c_door, c_colum, c_furnish, c_stair, c_panel, c_lamp, c_glass; + // coef=10; + c_wall=coef; + c_door=3*coef; + c_colum=2.5*coef; + c_furnish=1*coef; + c_stair=1.5*coef; + c_panel=1.5*coef; + c_lamp=2*coef; + c_glass=2*coef; + + if(_dirs == 8){ + cost2 += (_n_i < 4 ? dist_scale_factor_ : dd_2D_); //This is more efficient + }else{ + cost2 += (_n_i < 6 ? dist_scale_factor_ : (_n_i < 18 ? dd_2D_ : dd_3D_)); //This is more efficient + } + + // EDF COST --> ThetarStarM1 + // auto cost_term = static_cast(cost_weight_ * _suc->cost * dist_scale_factor_reduced_); + // cost += cost_term; + // _suc->C = cost_term; + + // SEMANTIC COST + // Wall + if (_suc->semantic == 1){ + cost2=c_wall*cost2; + // std::cout << "cost: " << _suc->cost << std::endl; + // std::cout << "semantic: " << _suc->semantic << std::endl; + // usleep(1e4); + // std::cout << "Please a key to go to the next iteration..." << std::endl; + // getchar(); // Comentar para no usar tecla. + } + // Door + else if (_suc->semantic == 2){ + cost2=c_door*cost2; + } + + // Colum + else if (_suc->semantic == 3){ + cost2=c_colum*cost2; + } + // Furnishing + else if (_suc->semantic == 4){ + cost2=c_furnish*cost2; + } + // Stairs + else if (_suc->semantic == 5){ + cost2=c_stair*cost2; + } + // Panels --> Barandilla + else if (_suc->semantic == 6){ + cost2=c_panel*cost2; + } + // Lamp + else if (_suc->semantic == 7){ + cost2=c_lamp*cost2; + } + // Glass wall + else if (_suc->semantic == 8){ + cost2=c_glass*cost2; + } + + cost = cost + cost2; + + _suc->C = _suc->cost; + + return cost; + } +} diff --git a/src/ROS/planner_ros_node.cpp b/src/ROS/planner_ros_node.cpp index 177b6ec..6f16f28 100755 --- a/src/ROS/planner_ros_node.cpp +++ b/src/ROS/planner_ros_node.cpp @@ -1,14 +1,20 @@ #include #include "Planners/AStar.hpp" +#include "Planners/AStarSemantic.hpp" +#include "Planners/AStarSemanticCost.hpp" #include "Planners/AStarM2.hpp" #include "Planners/AStarM1.hpp" #include "Planners/AStar_Gradient.hpp" #include "Planners/AStar_EDF.hpp" #include "Planners/ThetaStar.hpp" +#include "Planners/ThetaStarSemantic.hpp" +#include "Planners/ThetaStarSemanticCost.hpp" #include "Planners/ThetaStarM1.hpp" #include "Planners/ThetaStarM2.hpp" #include "Planners/LazyThetaStar.hpp" +#include "Planners/LazyThetaStarSemantic.hpp" +#include "Planners/LazyThetaStarSemanticCost.hpp" #include "Planners/LazyThetaStar_Gradient.hpp" #include "Planners/LazyThetaStar_EDF.hpp" #include "Planners/LazyThetaStarM1.hpp" @@ -254,6 +260,12 @@ class HeuristicPlannerROS }else if( algorithm_name == "costastar" ){ ROS_INFO("Using Cost Aware A*"); algorithm_.reset(new Planners::AStarM1(use3d_)); + }else if( algorithm_name == "astar_semantic" ){ + ROS_INFO("Using Semantic A*"); + algorithm_.reset(new Planners::AStarSemantic(use3d_)); + }else if( algorithm_name == "astar_semantic_cost" ){ + ROS_INFO("Using Semantic Cost A*"); + algorithm_.reset(new Planners::AStarSemanticCost(use3d_)); }else if( algorithm_name == "astar_gradient" ){ ROS_INFO("Using A* Gradient"); algorithm_.reset(new Planners::AStarGradient(use3d_)); @@ -269,6 +281,12 @@ class HeuristicPlannerROS }else if ( algorithm_name == "costhetastar" ){ ROS_INFO("Using Cost Aware Theta* "); algorithm_.reset(new Planners::ThetaStarM1(use3d_)); + }else if ( algorithm_name == "thetastar_semantic" ){ + ROS_INFO("Using Semantic Theta* "); + algorithm_.reset(new Planners::ThetaStarSemantic(use3d_)); + }else if ( algorithm_name == "thetastar_semantic_cost" ){ + ROS_INFO("Using Semantic Cost Theta* "); + algorithm_.reset(new Planners::ThetaStarSemanticCost(use3d_)); }else if ( algorithm_name == "thetastarsafetycost" ){ ROS_INFO("Using Theta* Safety Cost"); algorithm_.reset(new Planners::ThetaStarM2(use3d_)); @@ -278,6 +296,12 @@ class HeuristicPlannerROS }else if( algorithm_name == "costlazythetastar"){ ROS_INFO("Using Cost Aware LazyTheta*"); algorithm_.reset(new Planners::LazyThetaStarM1(use3d_)); + }else if( algorithm_name == "lazythetastar_semantic"){ + ROS_INFO("Using Semantic LazyTheta*"); + algorithm_.reset(new Planners::LazyThetaStarSemantic(use3d_)); + }else if( algorithm_name == "lazythetastar_semantic_cost"){ + ROS_INFO("Using Semantic Cost LazyTheta*"); + algorithm_.reset(new Planners::LazyThetaStarSemanticCost(use3d_)); }else if( algorithm_name == "costlazythetastarmodified"){ ROS_INFO("Using Cost Aware LazyTheta*"); algorithm_.reset(new Planners::LazyThetaStarM1Mod(use3d_)); @@ -481,6 +505,7 @@ class HeuristicPlannerROS std::string heuristic_; }; + int main(int argc, char **argv) { ros::init(argc, argv, "heuristic_planner_ros_node");