From 1d6ed94a3aa108a65e9d9f1ca4c641940b6416ce Mon Sep 17 00:00:00 2001 From: Malcolm Mielle Date: Thu, 31 Aug 2017 18:38:42 +0200 Subject: [PATCH 1/7] measure the time of everything --- src/acg_node_review.cpp | 104 +++++++++++++++++++++++++++++++++++----- 1 file changed, 92 insertions(+), 12 deletions(-) diff --git a/src/acg_node_review.cpp b/src/acg_node_review.cpp index 562ee991..bc421b17 100644 --- a/src/acg_node_review.cpp +++ b/src/acg_node_review.cpp @@ -1,6 +1,14 @@ #include #include +#include +#include + +#include +#include +#include + + #include "ndt_feature/NDTGraphMsg.h" #include "ndt_feature/ndt_feature_graph.h" #include "ndt_feature/ndtgraph_conversion.h" @@ -20,15 +28,79 @@ ros::Publisher occ_send; ros::Time timef; -std::vector all_node_times; -double node_process_time = 0; -int cycles = 0; - int count = 0; bool new_node = false; bool was_init = false; +std::vector time_extract_corner_ndt; +std::vector time_opti; +std::vector all_node_times; + +inline bool exists_test3 (const std::string& name) { + struct stat buffer; + return (stat (name.c_str(), &buffer) == 0); +} + + +inline void exportResultsGnuplot(const std::string& file_out){ + + /*** TIMES ***/ +// std::vector time_extract_corner_ndt; +// std::vector time_opti; +// std::vector all_node_times; + + boost::filesystem::path p(file_out); + std::string name = p.filename().stem().string(); + + std::string result_file = file_out; + std::ofstream myfile; + myfile.open (result_file, std::ios::out | std::ios::app); + + if (myfile.is_open()) + { + myfile << "Full time\n"; + + double mean_times = 0 ; + for(auto it = all_node_times.begin() ; it != all_node_times.end() ; ++it){ + mean_times += *it; + myfile << *it << "\n"; + } + mean_times = mean_times / all_node_times.size(); + + myfile << "\nExtract time\n"; + + double mean_extract = 0 ; + for(auto it = time_extract_corner_ndt.begin() ; it != time_extract_corner_ndt.end() ; ++it){ + mean_extract += *it; + myfile << *it << "\n"; + } + mean_extract = mean_extract / time_extract_corner_ndt.size(); + + myfile << "\nOpti time\n"; + + double mean_opti = 0 ; + for(auto it = time_opti.begin() ; it != time_opti.end() ; ++it){ + mean_opti += *it; + myfile << *it << "\n"; + } + mean_opti = mean_opti / time_opti.size(); + + myfile << "\nMean time, mean extract, mean opti\n" << mean_times << " " << mean_extract << " " << mean_opti << "\n"; + myfile.close(); + } + else std::cout << "Unable to open file"; +} + +inline double getTime() //in millisecond +{ + //assuming unix-type systems + //timezone tz; + timeval tv; + gettimeofday(&tv, NULL); + return (tv.tv_sec*1000000+tv.tv_usec)*1.0/1000; +} + inline void printImages(AASS::acg::AutoCompleteGraph* oacg){ nav_msgs::OccupancyGrid* omap_tmpt = new nav_msgs::OccupancyGrid(); nav_msgs::OccupancyGrid::Ptr occ_outt(omap_tmpt); @@ -150,8 +222,12 @@ void gotGraphandOptimize(const ndt_feature::NDTGraphMsg::ConstPtr msg, AASS::acg //ATTENTION: THE BAD GUY ! ndt_feature::msgToNDTGraph(*msg, graph, frame); - + + ros::Time start_corner = ros::Time::now(); oacg->updateNDTGraph(graph); + ros::Time end_corner = ros::Time::now(); + double corner_extract_tt = (start_corner - end_corner).toSec(); + time_extract_corner_ndt.push_back(corner_extract_tt); if(oacg->getRobotNodes().size() > 0){ @@ -177,11 +253,17 @@ void gotGraphandOptimize(const ndt_feature::NDTGraphMsg::ConstPtr msg, AASS::acg //Prepare the graph : marginalize + initializeOpti + ros::Time start_opti = ros::Time::now(); + oacg->setFirst(); + oacg->prepare(); + oacg->optimize(); + ros::Time end_opti = ros::Time::now(); + double opti = (start_opti - end_opti).toSec(); + time_opti.push_back(opti); + + count++; // if(was_init == true){ - oacg->setFirst(); - oacg->prepare(); - oacg->optimize(); - count++; + // } visu.updateRviz(); @@ -203,10 +285,7 @@ void gotGraphandOptimize(const ndt_feature::NDTGraphMsg::ConstPtr msg, AASS::acg // timef = ros::Time::now(); - - node_process_time = node_process_time + (timef - start).toSec(); all_node_times.push_back((timef - start).toSec()); - cycles++; // nav_msgs::OccupancyGrid omap; // lslgeneric::toOccupancyGrid(graph.getMap(), omap, 0.4, "/world"); @@ -389,6 +468,7 @@ int main(int argc, char **argv) } + exportResultsGnuplot("result.txt"); return 0; } From 22e217effc7258d059043f924401987a866459e0 Mon Sep 17 00:00:00 2001 From: Malcolm Mielle Date: Thu, 21 Sep 2017 19:08:11 +0200 Subject: [PATCH 2/7] remove attribute because std::move destroy them --- .../OptimizableAutoCompleteGraph.hpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/include/auto_complete_graph/OptimizableAutoCompleteGraph.hpp b/include/auto_complete_graph/OptimizableAutoCompleteGraph.hpp index 2cba95bf..408962d4 100644 --- a/include/auto_complete_graph/OptimizableAutoCompleteGraph.hpp +++ b/include/auto_complete_graph/OptimizableAutoCompleteGraph.hpp @@ -25,8 +25,8 @@ namespace acg{ typedef g2o::LinearSolverCSparse SlamLinearSolver; protected: // g2o::SparseOptimizer _optimizer; - std::unique_ptr _linearSolver; - std::unique_ptr _blockSolver; +// std::unique_ptr _linearSolver; +// std::unique_ptr _blockSolver; //TODO : test with LevenbergMarquard instead (maybe doesn't scale as aggressively) g2o::OptimizationAlgorithmGaussNewton* _solver; g2o::SE2 _sensorOffsetTransf; @@ -51,10 +51,10 @@ namespace acg{ // const Eigen::Vector2d& linkn ) : _sensorOffsetTransf(sensoffset), _first(true){ - _linearSolver = g2o::make_unique(); - _linearSolver->setBlockOrdering(false); - _blockSolver = g2o::make_unique(std::move(_linearSolver)); - _solver = new g2o::OptimizationAlgorithmGaussNewton(std::move(_blockSolver)); + auto linearSolver = g2o::make_unique(); + linearSolver->setBlockOrdering(false); + auto blockSolver = g2o::make_unique(std::move(linearSolver)); + _solver = new g2o::OptimizationAlgorithmGaussNewton(std::move(blockSolver)); //_linearSolver->setBlockOrdering(false); this->setAlgorithm(_solver); @@ -114,8 +114,8 @@ namespace acg{ // AutoCompleteGraph* getGraph(){return _graph;} g2o::ParameterSE2Offset* getSensorOffset(){return _sensorOffset;} - std::unique_ptr& getLinearSolver(){ return _linearSolver;} - std::unique_ptr& getBlockSolver(){ return _blockSolver;} +// std::unique_ptr& getLinearSolver(){ return _linearSolver;} +// std::unique_ptr& getBlockSolver(){ return _blockSolver;} // const g2o::SparseOptimizer& getoptimizer(){return _optimizer;} g2o::OptimizationAlgorithmGaussNewton* getSolver() {return _solver;} const g2o::SE2& getSensorOffsetTransfo(){return _sensorOffsetTransf;} From 40e346e8dab98b447179850627fcf76d2ec98e63 Mon Sep 17 00:00:00 2001 From: Malcolm Mielle Date: Tue, 26 Sep 2017 16:48:40 +0200 Subject: [PATCH 3/7] library --- CMakeLists.txt | 6 +- .../OptimizableAutoCompleteGraph.hpp | 19 +- .../PriorLoaderInterface.hpp | 640 +---------------- src/OptimizableAutoCompleteGraph.cpp | 20 + src/PriorLoaderInterface.cpp | 644 ++++++++++++++++++ 5 files changed, 680 insertions(+), 649 deletions(-) create mode 100644 src/OptimizableAutoCompleteGraph.cpp create mode 100644 src/PriorLoaderInterface.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 4a228cee..35344271 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -155,16 +155,20 @@ add_custom_target(headers SOURCES ${files}) ## Declare a C++ library add_library(auto_complete_graph_lib src/ACG.cpp + src/OptimizableAutoCompleteGraph.cpp + src/PriorLoaderInterface.cpp # src/VisuACG.cpp ) +target_link_libraries(auto_complete_graph_lib ${catkin_LIBRARIES} ${G2O_LIBS} ${vodigrex_LIBRARIES}) + ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries ## either from message generation or dynamic reconfigure # add_dependencies(auto_complete_graph ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) ## TODO : find a way to remove this by linking it where it should be in ndt_feature -include_directories(/usr/local/include/flirtlib) +# include_directories(/usr/local/include/flirtlib) ## Declare a C++ executable diff --git a/include/auto_complete_graph/OptimizableAutoCompleteGraph.hpp b/include/auto_complete_graph/OptimizableAutoCompleteGraph.hpp index 2cba95bf..e1ae1315 100644 --- a/include/auto_complete_graph/OptimizableAutoCompleteGraph.hpp +++ b/include/auto_complete_graph/OptimizableAutoCompleteGraph.hpp @@ -274,22 +274,7 @@ namespace acg{ private: - void setRobustKernelAllEdges(g2o::RobustKernel* ptr = NULL, double width = 1){ - - for (SparseOptimizer::VertexIDMap::const_iterator it = this->vertices().begin(); it != this->vertices().end(); ++it) { - OptimizableGraph::Vertex* v = static_cast(it->second); - v->setMarginalized(false); - } - - auto idmapedges = this->edges(); - if(ptr != NULL){ - for ( auto ite = idmapedges.begin(); ite != idmapedges.end(); ++ite ){ - std::cout << "Robust Kern" << std::endl; - OptimizableGraph::Edge* e = static_cast(*ite); - e->setRobustKernel(ptr); - e->robustKernel()->setDelta(width); - } - } + void setRobustKernelAllEdges(g2o::RobustKernel* ptr = NULL, double width = 1); //Same as ficing it to null to remove kernel // else{ @@ -318,7 +303,7 @@ namespace acg{ // } } */ - } +// } }; } diff --git a/include/auto_complete_graph/PriorLoaderInterface.hpp b/include/auto_complete_graph/PriorLoaderInterface.hpp index 70440339..33bb4a30 100644 --- a/include/auto_complete_graph/PriorLoaderInterface.hpp +++ b/include/auto_complete_graph/PriorLoaderInterface.hpp @@ -78,149 +78,12 @@ namespace AASS{ /** * @brief Extracting the corner from the prior */ - void extractCornerPrior(){ - // AASS::das::BasementPriorLine basement; - - _prior_graph.clear(); - - cv::Mat src = cv::imread( _file, 1 ); - cv::cvtColor( src, _img_gray, CV_BGR2GRAY ); - - AASS::vodigrex::LineFollowerGraphCorners<> graph_corners; - graph_corners.setD(2); - graph_corners.setMaxDeviation((45 * M_PI) / 180); - graph_corners.inputMap(_img_gray); - graph_corners.thin(); - auto prior_graph = graph_corners.getGraph(); - -// cv::Mat src1 = cv::imread( _file, CV_LOAD_IMAGE_COLOR ), src_gray1; -// cv::cvtColor(src1, src_gray1, CV_RGB2GRAY ); -// // -// cv::threshold(src_gray1, src_gray1, 100, 255, src_gray1.type()); -// cv::Mat maa_31 = src_gray1.clone(); -// maa_31.setTo(cv::Scalar(0)); -// AASS::vodigrex::draw(prior_graph, maa_31); -// std::cout << "Number of nodes " << prior_graph.getNumVertices() << std::endl; -// cv::imshow("graph", maa_31); -// cv::imshow("map", src_gray1); -// cv::waitKey(0); - -// cv::imshow("TEST IMG", _img_gray); -// cv::waitKey(0); - - bettergraph::PseudoGraph prior_out; - convertGraph(prior_graph, prior_out); - //Very convulted code TODO - AASS::acg::PriorLoaderInterface::PriorGraph simple_graph; - bettergraph::toSimpleGraph(prior_out, simple_graph); - - if(_extractKeypoints == true){ - extractKeypoints(simple_graph); - } - else{ -// bettergraph::SimpleGraph - _prior_graph = simple_graph; - } - -// //PRINT -// cv::Mat src_gray; -// cv::cvtColor(src, src_gray, CV_RGB2GRAY ); -// // -// cv::threshold(src_gray, src_gray, 100, 255, src_gray.type()); -// cv::Mat maa_3 = src_gray.clone(); -// maa_3.setTo(cv::Scalar(0)); -// AASS::vodigrex::draw(_prior_graph, maa_3); -// std::cout << "Number of nodes " << _prior_graph.getNumVertices() << std::endl; -// cv::imshow("graph", maa_3); -// cv::imshow("map", src_gray); -// cv::waitKey(0); - - } + void extractCornerPrior(); /** * @brief scale the corner and the graph depending on the _scale_transform_prior2ndt attribute */ - void transformOntoSLAM(){ - - -// std::cout << "Transform onto slam from scale : " << std::endl << _scale_transform_prior2ndt << std::endl; - //Scale transform here: - //Then create association -// cv::perspectiveTransform( _corner_prior, _corner_prior_matched, _scale_transform_prior2ndt); - - assert(_same_point_prior.size() >= 2); - - cv::Point2f srcTri[2]; - cv::Point2f dstTri[2]; - srcTri[0] = _same_point_prior[0]; - srcTri[1] = _same_point_prior[1]; -// srcTri[2] = _same_point_prior[2]; - - dstTri[0] = _same_point_slam[0]; - dstTri[1] = _same_point_slam[1]; - - std::cout << "Point for transfo" << std::endl; - std::cout << _same_point_prior[0] << " " << _same_point_slam[0] << std::endl << _same_point_prior[1] << " " << _same_point_slam[1] << std::endl; - - //Translate to origin - cv::Point2d translation = - srcTri[0]; - double angle = 0; - cv::Mat warp_mat = (cv::Mat_(3,3) << std::cos(angle), -std::sin(angle), translation.x, std::sin(angle), std::cos(angle), translation.y, 0, 0, 1); - AffineTransformGraph(warp_mat); - - //Rotate - Eigen::Vector2d vece1s; vece1s << srcTri[1].x - srcTri[0].x, srcTri[1].y - srcTri[0].y; - Eigen::Vector2d vece2s; vece2s << dstTri[1].x - dstTri[0].x, dstTri[1].y - dstTri[0].y; - - angle = atan2(vece2s(1),vece2s(0)) - atan2(vece1s(1), vece1s(0)); - if (angle < 0) angle += 2 * M_PI; - -// std::cout << "Angle : "<< angle << std::endl; -// angle = angle * 2 * 3.14157 / 360; - warp_mat = (cv::Mat_(3,3) << std::cos(angle), -std::sin(angle), 0, std::sin(angle), std::cos(angle), 0, 0, 0, 1); -// std::cout << "mat " << warp_mat << std::endl; - AffineTransformGraph(warp_mat); - - //Scale - cv::Point2f vec1 = srcTri[1] - srcTri[0]; - cv::Point2f vec2 = dstTri[1] - dstTri[0]; - cv::Mat mat_transfo = (cv::Mat_(2,2) << vec2.x / vec1.x, 0, 0, vec2.y / vec1.y); - double l1 = std::sqrt( ( vec1.x * vec1.x ) + ( vec1.y * vec1.y ) ); - double l2 = std::sqrt( ( vec2.x * vec2.x ) + ( vec2.y * vec2.y ) ); - double ratio = l2 / l1; - - std::pair< PriorVertexIterator, PriorVertexIterator > vp; - //vertices access all the vertix - //Classify them in order - // std::cout << "Gph size : " << _graph.getNumVertices() << std::endl; -// int i = 0 ; - for (vp = boost::vertices(_prior_graph); vp.first != vp.second; ++vp.first) { - // std::cout << "going throught grph " << i << std::endl; ++i; - PriorVertex v = *vp.first; - //ATTENTION ! - cv::Point2d point; - point.x = _prior_graph[v].getX(); - point.y = _prior_graph[v].getY(); - - cv::Point2d point_out = point * ratio; - - _prior_graph[v].setX(point_out.x); - _prior_graph[v].setY(point_out.y); - } -// //Translate back - translation = srcTri[0]; - angle = 0; - warp_mat = (cv::Mat_(3,3) << std::cos(angle), -std::sin(angle), translation.x, std::sin(angle), std::cos(angle), translation.y, 0, 0, 1); - AffineTransformGraph(warp_mat); -// -// //Translate to point - translation = dstTri[0] - srcTri[0]; - angle = 0; - warp_mat = (cv::Mat_(3,3) << std::cos(angle), -std::sin(angle), translation.x, std::sin(angle), std::cos(angle), translation.y, 0, 0, 1); - AffineTransformGraph(warp_mat); - - - } + void transformOntoSLAM(); /** * @brief initialze the structure @@ -243,96 +106,7 @@ namespace AASS{ * @param[in] pt_slam : points from the robot slam map * @param[in] pt_prior : equivalent points from the robot slam map */ - void initialize(const std::vector& pt_slam, const std::vector& pt_prior){ - - assert(pt_slam.size() >= 2); - assert(pt_prior.size() == pt_slam.size()); - - std::cout << pt_prior[0] << " " << pt_slam[0] << std::endl << pt_prior[1] << " " << pt_slam[1] << std::endl; - - _same_point_prior.clear(); - _same_point_slam.clear(); - -// this->_cornerDetect.setMinimumDeviationCorner( (80 * 3.14159) / 180 ); - - auto randomNoise = [](double mean, double deviationt) -> double { - std::default_random_engine engine{std::random_device()() }; - std::normal_distribution dist(mean, deviationt); - return dist(engine); - }; - -// cv::Point center = cv::Point(7, 08); - - cv::Mat rot_mat = cv::getRotationMatrix2D(_center, _angle, _scale); - std::cout << rot_mat << std::endl; -// exit(0); - - auto rotatef = [](const cv::Mat& rot_mat, const cv::Point2d point) -> cv::Point2d { - //Matrix multiplication - cv::Mat point_m = (cv::Mat_(3,1) << point.x, point.y, 1); - cv::Mat mat_out = rot_mat * point_m; -// std::cout << "Mat out " << mat_out << std::endl; - cv::Point2d point_out; - point_out.x = mat_out.at(0); - point_out.y = mat_out.at(1); - return point_out; - }; - - auto noise_x = randomNoise(0, _deviation); - auto noise_y = randomNoise(0, _deviation); - - std::cout << "Noise X Y " << noise_x << " " << noise_y << std::endl; -// exit(0); - - cv::Point2f out = cv::Point2f(pt_slam[0].x + noise_x, pt_slam[0].y + noise_y); - cv::Point2f slam_point = rotatef(rot_mat, out); - - _same_point_prior.push_back(pt_prior[0]); - _same_point_slam.push_back(slam_point); - - noise_x = randomNoise(0, _deviation); - noise_y = randomNoise(0, _deviation); - out = cv::Point2f(pt_slam[1].x + noise_x, pt_slam[1].y + noise_y); - slam_point = rotatef(rot_mat, out); - - _same_point_prior.push_back(pt_prior[1]); - _same_point_slam.push_back(slam_point); - -// noise_x = randomNoise(0, _deviation); -// noise_y = randomNoise(0, _deviation); -// out = cv::Point2f(pt_slam[2].x + noise_x, pt_slam[2].y + noise_y); -// slam_point = rotatef(rot_mat, out); -// -// //ATTENTION : next line or for used the points only -// -// _same_point_prior.push_back(pt_prior[2]); -// _same_point_slam.push_back(slam_point); -// -// noise_x = randomNoise(0, _deviation); -// noise_y = randomNoise(0, _deviation); -// out = cv::Point2f(pt_slam[3].x + noise_x, pt_slam[3].y + noise_y); -// slam_point = rotatef(rot_mat, out); -// -// _same_point_prior.push_back(pt_prior[3]); -// _same_point_slam.push_back(slam_point); - -// _same_point_prior.push_back(cv::Point2f(786, 373)); -// _same_point_slam.push_back(cv::Point2f(786, 373)); -// -// _same_point_prior.push_back(cv::Point2f(788, 311)); -// _same_point_slam.push_back(cv::Point2f(786, 373)); -// -// //ATTENTION : next line or for used the points only -// -// _same_point_prior.push_back(cv::Point2f(614, 306)); -// _same_point_slam.push_back(cv::Point2f(786, 373)); -// -// _same_point_prior.push_back(cv::Point2f(637, 529)); -// _same_point_slam.push_back(cv::Point2f(786, 373)); - -// _scale_transform_prior2ndt = cv::findHomography(_same_point_prior, _same_point_slam, CV_RANSAC, 3, cv::noArray()); - - } + void initialize(const std::vector& pt_slam, const std::vector& pt_prior); protected: @@ -340,419 +114,23 @@ namespace AASS{ - void extractKeypoints(const PriorGraph& graph){ - - //vertices access all the vertix - //Classify them in order - // std::cout << "Gph size : " << _graph.getNumVertices() << std::endl; - int i = 0 ; - std::vector das_v; - std::vector prior_v; - - - std::cout << "Keypoints" << std::endl; - //Adding all the vertices - std::pair< PriorVertexIterator, PriorVertexIterator > vp; - int count = 0; - for (vp = boost::vertices(graph); vp.first != vp.second; ++vp.first) { - -// std::cout << "A vertices " << count << " " << graph.getNumVertices() << std::endl; - ++count; - PriorVertex v = *vp.first; - PriorVertex vertex_out; - PriorAttr nodeAttribute(graph[v]); - - - //Creating a SIFT descriptor for eahc corner - cv::KeyPoint keypoint; - keypoint.pt = cv::Point2f( nodeAttribute.getX(), nodeAttribute.getY() ); - - //Calculate smallest edge size - std::deque out; - graph.getAllVertexLinked(v, out); - double smallest = -1; - for(auto it = out.begin() ; it != out.end() ; ++it){ - if(v != *it){ - double tmp_size_x = (graph[v].getX() - graph[*it].getX()); - double tmp_size_y = (graph[v].getY() - graph[*it].getY()); - tmp_size_x = std::abs(tmp_size_x); - tmp_size_y = std::abs(tmp_size_y); - double tmp_size = (tmp_size_x * tmp_size_x) + (tmp_size_y * tmp_size_y); - if(smallest == -1 || smallest > tmp_size){ - if(tmp_size > 0){ -// std::cout << "Smallest size " << tmp_size << std::endl; - smallest = tmp_size; - } - else{ -// std::cout << "Weird zero distance between points" < keypoint_v; - keypoint_v.push_back(keypoint); - - cv::Mat descriptors_1; -#if CV_MAJOR_VERSION == 2 - cv::SiftDescriptorExtractor extractor; - extractor.compute( _img_gray, keypoint_v, descriptors_1); -#else - cv::Ptr extractor = cv::xfeatures2d::SURF::create(); -// cv::xfeatures2d::SiftDescriptorExtractor extractor; - extractor->compute( _img_gray, keypoint_v, descriptors_1); -#endif - - -// std::cout << descriptors_1.rows << " " << descriptors_1.cols << std::endl; - assert(descriptors_1.rows == 1); - - nodeAttribute.keypoint = keypoint; - nodeAttribute.position = keypoint.pt; - nodeAttribute.descriptor = descriptors_1; - - _prior_graph.addVertex(vertex_out, nodeAttribute); - das_v.push_back(v); - prior_v.push_back(vertex_out); - - } - - std::cout << "Done" << std::endl; - - //Adding all the edges - auto es = boost::edges(graph); - for (auto eit = es.first; eit != es.second; ++eit) { - auto sour = boost::source(*eit, graph); - auto targ = boost::target(*eit, graph); - PriorVertex source_p; - PriorVertex target_p; - bool flag_found_src = false; - bool flag_found_targ = false; - for(int i = 0 ; i < das_v.size() ; ++i){ - if(das_v[i] == sour){ - source_p = prior_v[i]; - assert(flag_found_src == false); - flag_found_src = true; - } - if(das_v[i] == targ){ - target_p = prior_v[i]; - assert(flag_found_targ == false); - flag_found_targ = true; - } - } - assert(flag_found_src == true); - assert(flag_found_targ == true); - - PriorEdge out_edge; - _prior_graph.addEdge(out_edge, source_p, target_p, graph[*eit]); - } - - } + void extractKeypoints(const PriorGraph& graph); - void rotateGraph(const cv::Mat& rot_mat ){ - - - auto transf = [](const cv::Mat& rot_mat, const cv::Point2d point) -> cv::Point2d { - //Matrix multiplication - cv::Mat point_m = (cv::Mat_(3,1) << point.x, point.y); - cv::Mat mat_out = rot_mat * point_m; -// std::cout << "Mat out " << mat_out << std::endl; - cv::Point2d point_out; - point_out.x = mat_out.at(0); - point_out.y = mat_out.at(1); - return point_out; - }; - - - - - std::pair< PriorVertexIterator, PriorVertexIterator > vp; - //vertices access all the vertix - //Classify them in order - // std::cout << "Gph size : " << _graph.getNumVertices() << std::endl; - int i = 0 ; - for (vp = boost::vertices(_prior_graph); vp.first != vp.second; ++vp.first) { - // std::cout << "going throught grph " << i << std::endl; ++i; - PriorVertex v = *vp.first; - //ATTENTION ! - cv::Point2d point; - point.x = _prior_graph[v].getX(); - point.y = _prior_graph[v].getY(); - - auto point_out = transf(rot_mat, point); - - //Matrix multiplication - - std::cout << "Point out " << point_out << std::endl; - - std::cout << "OLD value " << _prior_graph[v].getX() << " " << _prior_graph[v].getY() << std::endl; - _prior_graph[v].setX(point_out.x); - _prior_graph[v].setY(point_out.y); - _corner_prior_matched.push_back(point_out); - std::cout << "New value " << _corner_prior_matched[i].x << " " << _corner_prior_matched[i].y << std::endl; - std::cout << "New value " << _prior_graph[v].getX() << " " << _prior_graph[v].getY() << std::endl; - ++i; - } - - - } + void rotateGraph(const cv::Mat& rot_mat ); - void AffineTransformGraph(const cv::Mat& warp_transfo ){ - - - auto transf = [](const cv::Mat& warp_transfo, const cv::Point2d point) -> cv::Point2d { - //Matrix multiplication - cv::Mat point_m = (cv::Mat_(3,1) << point.x, point.y, 1); - cv::Mat mat_out = warp_transfo * point_m; -// std::cout << "Mat out " << mat_out << std::endl; - cv::Point2d point_out; - point_out.x = mat_out.at(0); - point_out.y = mat_out.at(1); - std::cout << "reutnr point " << point_out.x << " " << point_out.y << std::endl; - return point_out; - }; - - - - - std::pair< PriorVertexIterator, PriorVertexIterator > vp; - //vertices access all the vertix - //Classify them in order - // std::cout << "Gph size : " << _graph.getNumVertices() << std::endl; - int i = 0 ; - for (vp = boost::vertices(_prior_graph); vp.first != vp.second; ++vp.first) { - // std::cout << "going throught grph " << i << std::endl; ++i; - PriorVertex v = *vp.first; - //ATTENTION ! - cv::Point2d point; - point.x = _prior_graph[v].getX(); - point.y = _prior_graph[v].getY(); - - cv::Point2d point_out = transf(warp_transfo, point); - - //Matrix multiplication - -// std::cout << "Point out " << point_out << std::endl; - -// std::cout << "OLD value " << _prior_graph[v].getX() << " " << _prior_graph[v].getY() << std::endl; - _prior_graph[v].setX(point_out.x); - _prior_graph[v].setY(point_out.y); - _corner_prior_matched.push_back(point_out); -// std::cout << "New value " << _corner_prior_matched[i].x << " " << _corner_prior_matched[i].y << std::endl; -// std::cout << "New value " << _prior_graph[v].getX() << " " << _prior_graph[v].getY() << std::endl; - ++i; - } - - - } + void AffineTransformGraph(const cv::Mat& warp_transfo ); - void noTwiceSameEdge(bettergraph::PseudoGraph graph){ - - std::cout << "No twice same edge" << std::endl; - std::pair< - bettergraph::PseudoGraph::VertexIterator, - bettergraph::PseudoGraph::VertexIterator > vp; - - std::vector::Edge> e_vec; - - for (vp = boost::vertices(graph); vp.first != vp.second; ++vp.first) { - std::cout << "Vertex" << std::endl; - // bettergraph::PseudoGraph::Vertex v = *vp.first; - bettergraph::PseudoGraph::Vertex v = *vp.first; - bettergraph::PseudoGraph::EdgeIterator out_i, out_end; - bettergraph::PseudoGraph::Edge e; - - std::vector::Vertex> vertices_out_edge; - - std::vector::Edge> edge_seen; - - std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; - std::cout << " v has " << graph.getNumEdges(v) << std::endl; - - for (boost::tie(out_i, out_end) = boost::out_edges(v, graph); - out_i != out_end; ++out_i) { - std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; - std::cout << "Removing an edge test" << std::endl; - e = *out_i; - - for(std::vector::Edge>::iterator it = edge_seen.begin() ; it != edge_seen.end() ; ++it){ - if(e == *it){ - std::cout << "EDGE seen on this node :(" << std::endl; - assert(true == false); - } - } - - // for(std::vector::Edge>::iterator it = e_vec.begin() ; it != e_vec.end() ; ++it){ - // if(e == *it){ - // std::cout << "EDGE seen on another node :(" << std::endl; - // assert(true == false); - // } - // } - - e_vec.push_back(e); - edge_seen.push_back(e); - } - } - - std::cout << "So no twice for now! " << std::endl; - - } + void noTwiceSameEdge(bettergraph::PseudoGraph graph); /** * remove eahc edges in between same vertex */ - void toSimpleGraph(bettergraph::PseudoGraph & prior){ - - - noTwiceSameEdge(prior); - - std::pair< - bettergraph::PseudoGraph::VertexIterator, - bettergraph::PseudoGraph::VertexIterator > vp; - std::deque vec_deque; - - std::cout << "prior" << prior.getNumVertices() << std::endl << std::endl; - - int nb = prior.getNumVertices(); - - for (vp = boost::vertices(prior); vp.first != vp.second; ++vp.first) { - std::cout << "Vertex" << std::endl; - // bettergraph::PseudoGraph::Vertex v = *vp.first; - auto v = *vp.first; - bettergraph::PseudoGraph::EdgeIterator out_i, out_end; - bettergraph::PseudoGraph::Edge e; - - std::vector::Vertex> vertices_out_edge; - - std::vector::Edge> edge_seen; - - std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; - std::cout << " v has " << prior.getNumEdges(v) << std::endl; - - for (boost::tie(out_i, out_end) = boost::out_edges(v, prior); - out_i != out_end; ++out_i) { - std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; - std::cout << "Removing an edge test" << std::endl; - e = *out_i; - - for(auto it = edge_seen.begin() ; it != edge_seen.end() ; ++it){ - if(e == *it){ - std::cout << "EDGE seen :(" << std::endl; - assert(true == false); - } - } - - std::cout << "Vertiuce size " << vertices_out_edge.size() << " and edge " << e << std::endl; - edge_seen.push_back(e); - - - - std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; - - // bettergraph::PseudoGraph::Vertex targ = boost::target(e, (graph)); - auto targ = boost::target(e, prior); - std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; - for(auto it = vertices_out_edge.begin() ; it != vertices_out_edge.end() ; ++it){ - if(targ == *it){ - std::cout << "Removing an edge" << std::endl; - prior.removeEdge(e); - assert(nb == prior.getNumVertices()); - } - } - std::cout << "Psuh back end targ " << std::endl; - vertices_out_edge.push_back(targ); - - - } - - std::cout << "Our for vertex" << std::endl; - - } - - - - - } + void toSimpleGraph(bettergraph::PseudoGraph & prior); - void convertGraph(const bettergraph::PseudoGraph & input, bettergraph::PseudoGraph & output){ - - output.clear(); - std::pair< - typename bettergraph::PseudoGraph::VertexIterator, - typename bettergraph::PseudoGraph::VertexIterator > vp; - - std::deque< typename bettergraph::PseudoGraph::Vertex> vec_deque; - - std::deque< typename bettergraph::PseudoGraph::Vertex> vec_deque_input; - - //Add all vertex - for (vp = boost::vertices(input); vp.first != vp.second; ++vp.first) { - // bettergraph::PseudoGraph::Vertex v = *vp.first; - typename bettergraph::PseudoGraph::Vertex v = *vp.first; - typename bettergraph::PseudoGraph::Vertex vertex_out; - - PriorAttr priorattr(input[v]); - - output.addVertex(vertex_out, priorattr); - - vec_deque.push_back(vertex_out); - vec_deque_input.push_back(v); - - } - - //Simply add all edges - int self_link = 0 ; - for (vp = boost::vertices(input); vp.first != vp.second; ++vp.first) { - typename bettergraph::PseudoGraph::Vertex v = *vp.first; - typename bettergraph::PseudoGraph::EdgeIterator out_i, out_end; - typename bettergraph::PseudoGraph::Edge e; - - typename bettergraph::PseudoGraph::Vertex output_src; - for(int i = 0 ; i < vec_deque.size() ; ++i){ - if(vec_deque_input[i] == v){ - output_src = vec_deque[i]; - } - } - - for (boost::tie(out_i, out_end) = boost::out_edges(v, (input)); - out_i != out_end; ++out_i) { - e = *out_i; - typename bettergraph::PseudoGraph::Vertex targ = boost::target(e, input); - typename bettergraph::PseudoGraph::Vertex src = boost::source(e, input); - typename bettergraph::PseudoGraph::Vertex output_targ; - for(int i = 0 ; i < vec_deque.size() ; ++i){ - if(vec_deque_input[i] == targ){ - output_targ = vec_deque[i]; - } - - } - - typename bettergraph::PseudoGraph::Edge e_out_output; - output.addEdge(e_out_output, output_src, output_targ, input[e]); - - } - } - -// assert(2 * output.getNumEdges() == input.getNumEdges()); - assert(output.getNumVertices() == input.getNumVertices()); - - - - } + void convertGraph(const bettergraph::PseudoGraph & input, bettergraph::PseudoGraph & output); diff --git a/src/OptimizableAutoCompleteGraph.cpp b/src/OptimizableAutoCompleteGraph.cpp new file mode 100644 index 00000000..019c44d7 --- /dev/null +++ b/src/OptimizableAutoCompleteGraph.cpp @@ -0,0 +1,20 @@ +#include "auto_complete_graph/OptimizableAutoCompleteGraph.hpp" + + +void AASS::acg::OptimizableAutoCompleteGraph::setRobustKernelAllEdges(g2o::RobustKernel* ptr, double width) +{ + for (SparseOptimizer::VertexIDMap::const_iterator it = this->vertices().begin(); it != this->vertices().end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(it->second); + v->setMarginalized(false); + } + + auto idmapedges = this->edges(); + if(ptr != NULL){ + for ( auto ite = idmapedges.begin(); ite != idmapedges.end(); ++ite ){ + std::cout << "Robust Kern" << std::endl; + OptimizableGraph::Edge* e = static_cast(*ite); + e->setRobustKernel(ptr); + e->robustKernel()->setDelta(width); + } + } +} diff --git a/src/PriorLoaderInterface.cpp b/src/PriorLoaderInterface.cpp new file mode 100644 index 00000000..aa27617a --- /dev/null +++ b/src/PriorLoaderInterface.cpp @@ -0,0 +1,644 @@ +#include "auto_complete_graph/PriorLoaderInterface.hpp" + +void AASS::acg::PriorLoaderInterface::transformOntoSLAM() +{ +// std::cout << "Transform onto slam from scale : " << std::endl << _scale_transform_prior2ndt << std::endl; + //Scale transform here: + //Then create association +// cv::perspectiveTransform( _corner_prior, _corner_prior_matched, _scale_transform_prior2ndt); + + assert(_same_point_prior.size() >= 2); + + cv::Point2f srcTri[2]; + cv::Point2f dstTri[2]; + srcTri[0] = _same_point_prior[0]; + srcTri[1] = _same_point_prior[1]; +// srcTri[2] = _same_point_prior[2]; + + dstTri[0] = _same_point_slam[0]; + dstTri[1] = _same_point_slam[1]; + + std::cout << "Point for transfo" << std::endl; + std::cout << _same_point_prior[0] << " " << _same_point_slam[0] << std::endl << _same_point_prior[1] << " " << _same_point_slam[1] << std::endl; + + //Translate to origin + cv::Point2d translation = - srcTri[0]; + double angle = 0; + cv::Mat warp_mat = (cv::Mat_(3,3) << std::cos(angle), -std::sin(angle), translation.x, std::sin(angle), std::cos(angle), translation.y, 0, 0, 1); + AffineTransformGraph(warp_mat); + + //Rotate + Eigen::Vector2d vece1s; vece1s << srcTri[1].x - srcTri[0].x, srcTri[1].y - srcTri[0].y; + Eigen::Vector2d vece2s; vece2s << dstTri[1].x - dstTri[0].x, dstTri[1].y - dstTri[0].y; + + angle = atan2(vece2s(1),vece2s(0)) - atan2(vece1s(1), vece1s(0)); + if (angle < 0) angle += 2 * M_PI; + +// std::cout << "Angle : "<< angle << std::endl; +// angle = angle * 2 * 3.14157 / 360; + warp_mat = (cv::Mat_(3,3) << std::cos(angle), -std::sin(angle), 0, std::sin(angle), std::cos(angle), 0, 0, 0, 1); +// std::cout << "mat " << warp_mat << std::endl; + AffineTransformGraph(warp_mat); + + //Scale + cv::Point2f vec1 = srcTri[1] - srcTri[0]; + cv::Point2f vec2 = dstTri[1] - dstTri[0]; + cv::Mat mat_transfo = (cv::Mat_(2,2) << vec2.x / vec1.x, 0, 0, vec2.y / vec1.y); + double l1 = std::sqrt( ( vec1.x * vec1.x ) + ( vec1.y * vec1.y ) ); + double l2 = std::sqrt( ( vec2.x * vec2.x ) + ( vec2.y * vec2.y ) ); + double ratio = l2 / l1; + + std::pair< PriorVertexIterator, PriorVertexIterator > vp; + //vertices access all the vertix + //Classify them in order +// std::cout << "Gph size : " << _graph.getNumVertices() << std::endl; +// int i = 0 ; + for (vp = boost::vertices(_prior_graph); vp.first != vp.second; ++vp.first) { +// std::cout << "going throught grph " << i << std::endl; ++i; + PriorVertex v = *vp.first; + //ATTENTION ! + cv::Point2d point; + point.x = _prior_graph[v].getX(); + point.y = _prior_graph[v].getY(); + + cv::Point2d point_out = point * ratio; + + _prior_graph[v].setX(point_out.x); + _prior_graph[v].setY(point_out.y); + } +// //Translate back + translation = srcTri[0]; + angle = 0; + warp_mat = (cv::Mat_(3,3) << std::cos(angle), -std::sin(angle), translation.x, std::sin(angle), std::cos(angle), translation.y, 0, 0, 1); + AffineTransformGraph(warp_mat); +// +// //Translate to point + translation = dstTri[0] - srcTri[0]; + angle = 0; + warp_mat = (cv::Mat_(3,3) << std::cos(angle), -std::sin(angle), translation.x, std::sin(angle), std::cos(angle), translation.y, 0, 0, 1); + AffineTransformGraph(warp_mat); + + +} + +void AASS::acg::PriorLoaderInterface::extractCornerPrior() +{ +// AASS::das::BasementPriorLine basement; + + _prior_graph.clear(); + + cv::Mat src = cv::imread( _file, 1 ); + cv::cvtColor( src, _img_gray, CV_BGR2GRAY ); + + AASS::vodigrex::LineFollowerGraphCorners<> graph_corners; + graph_corners.setD(2); + graph_corners.setMaxDeviation((45 * M_PI) / 180); + graph_corners.inputMap(_img_gray); + graph_corners.thin(); + auto prior_graph = graph_corners.getGraph(); + +// cv::Mat src1 = cv::imread( _file, CV_LOAD_IMAGE_COLOR ), src_gray1; +// cv::cvtColor(src1, src_gray1, CV_RGB2GRAY ); +// // +// cv::threshold(src_gray1, src_gray1, 100, 255, src_gray1.type()); +// cv::Mat maa_31 = src_gray1.clone(); +// maa_31.setTo(cv::Scalar(0)); +// AASS::vodigrex::draw(prior_graph, maa_31); +// std::cout << "Number of nodes " << prior_graph.getNumVertices() << std::endl; +// cv::imshow("graph", maa_31); +// cv::imshow("map", src_gray1); +// cv::waitKey(0); + +// cv::imshow("TEST IMG", _img_gray); +// cv::waitKey(0); + + bettergraph::PseudoGraph prior_out; + convertGraph(prior_graph, prior_out); + //Very convulted code TODO + AASS::acg::PriorLoaderInterface::PriorGraph simple_graph; + bettergraph::toSimpleGraph(prior_out, simple_graph); + + if(_extractKeypoints == true){ + extractKeypoints(simple_graph); + } + else{ +// bettergraph::SimpleGraph + _prior_graph = simple_graph; + } + +// //PRINT +// cv::Mat src_gray; +// cv::cvtColor(src, src_gray, CV_RGB2GRAY ); +// // +// cv::threshold(src_gray, src_gray, 100, 255, src_gray.type()); +// cv::Mat maa_3 = src_gray.clone(); +// maa_3.setTo(cv::Scalar(0)); +// AASS::vodigrex::draw(_prior_graph, maa_3); +// std::cout << "Number of nodes " << _prior_graph.getNumVertices() << std::endl; +// cv::imshow("graph", maa_3); +// cv::imshow("map", src_gray); +// cv::waitKey(0); + +} + +void AASS::acg::PriorLoaderInterface::initialize(const std::vector< cv::Point2f >& pt_slam, const std::vector< cv::Point2f >& pt_prior) +{ + + assert(pt_slam.size() >= 2); + assert(pt_prior.size() == pt_slam.size()); + + std::cout << pt_prior[0] << " " << pt_slam[0] << std::endl << pt_prior[1] << " " << pt_slam[1] << std::endl; + + _same_point_prior.clear(); + _same_point_slam.clear(); + +// this->_cornerDetect.setMinimumDeviationCorner( (80 * 3.14159) / 180 ); + + auto randomNoise = [](double mean, double deviationt) -> double { + std::default_random_engine engine{std::random_device()() }; + std::normal_distribution dist(mean, deviationt); + return dist(engine); + }; + +// cv::Point center = cv::Point(7, 08); + + cv::Mat rot_mat = cv::getRotationMatrix2D(_center, _angle, _scale); + std::cout << rot_mat << std::endl; +// exit(0); + + auto rotatef = [](const cv::Mat& rot_mat, const cv::Point2d point) -> cv::Point2d { + //Matrix multiplication + cv::Mat point_m = (cv::Mat_(3,1) << point.x, point.y, 1); + cv::Mat mat_out = rot_mat * point_m; +// std::cout << "Mat out " << mat_out << std::endl; + cv::Point2d point_out; + point_out.x = mat_out.at(0); + point_out.y = mat_out.at(1); + return point_out; + }; + + auto noise_x = randomNoise(0, _deviation); + auto noise_y = randomNoise(0, _deviation); + + std::cout << "Noise X Y " << noise_x << " " << noise_y << std::endl; +// exit(0); + + cv::Point2f out = cv::Point2f(pt_slam[0].x + noise_x, pt_slam[0].y + noise_y); + cv::Point2f slam_point = rotatef(rot_mat, out); + + _same_point_prior.push_back(pt_prior[0]); + _same_point_slam.push_back(slam_point); + + noise_x = randomNoise(0, _deviation); + noise_y = randomNoise(0, _deviation); + out = cv::Point2f(pt_slam[1].x + noise_x, pt_slam[1].y + noise_y); + slam_point = rotatef(rot_mat, out); + + _same_point_prior.push_back(pt_prior[1]); + _same_point_slam.push_back(slam_point); + +// noise_x = randomNoise(0, _deviation); +// noise_y = randomNoise(0, _deviation); +// out = cv::Point2f(pt_slam[2].x + noise_x, pt_slam[2].y + noise_y); +// slam_point = rotatef(rot_mat, out); +// +// //ATTENTION : next line or for used the points only +// +// _same_point_prior.push_back(pt_prior[2]); +// _same_point_slam.push_back(slam_point); +// +// noise_x = randomNoise(0, _deviation); +// noise_y = randomNoise(0, _deviation); +// out = cv::Point2f(pt_slam[3].x + noise_x, pt_slam[3].y + noise_y); +// slam_point = rotatef(rot_mat, out); +// +// _same_point_prior.push_back(pt_prior[3]); +// _same_point_slam.push_back(slam_point); + +// _same_point_prior.push_back(cv::Point2f(786, 373)); +// _same_point_slam.push_back(cv::Point2f(786, 373)); +// +// _same_point_prior.push_back(cv::Point2f(788, 311)); +// _same_point_slam.push_back(cv::Point2f(786, 373)); +// +// //ATTENTION : next line or for used the points only +// +// _same_point_prior.push_back(cv::Point2f(614, 306)); +// _same_point_slam.push_back(cv::Point2f(786, 373)); +// +// _same_point_prior.push_back(cv::Point2f(637, 529)); +// _same_point_slam.push_back(cv::Point2f(786, 373)); + +// _scale_transform_prior2ndt = cv::findHomography(_same_point_prior, _same_point_slam, CV_RANSAC, 3, cv::noArray()); + +} + + +void AASS::acg::PriorLoaderInterface::extractKeypoints(const AASS::acg::PriorLoaderInterface::PriorGraph& graph) +{ + + //vertices access all the vertix + //Classify them in order +// std::cout << "Gph size : " << _graph.getNumVertices() << std::endl; + int i = 0 ; + std::vector das_v; + std::vector prior_v; + + + std::cout << "Keypoints" << std::endl; + //Adding all the vertices + std::pair< PriorVertexIterator, PriorVertexIterator > vp; + int count = 0; + for (vp = boost::vertices(graph); vp.first != vp.second; ++vp.first) { + +// std::cout << "A vertices " << count << " " << graph.getNumVertices() << std::endl; + ++count; + PriorVertex v = *vp.first; + PriorVertex vertex_out; + PriorAttr nodeAttribute(graph[v]); + + + //Creating a SIFT descriptor for eahc corner + cv::KeyPoint keypoint; + keypoint.pt = cv::Point2f( nodeAttribute.getX(), nodeAttribute.getY() ); + + //Calculate smallest edge size + std::deque out; + graph.getAllVertexLinked(v, out); + double smallest = -1; + for(auto it = out.begin() ; it != out.end() ; ++it){ + if(v != *it){ + double tmp_size_x = (graph[v].getX() - graph[*it].getX()); + double tmp_size_y = (graph[v].getY() - graph[*it].getY()); + tmp_size_x = std::abs(tmp_size_x); + tmp_size_y = std::abs(tmp_size_y); + double tmp_size = (tmp_size_x * tmp_size_x) + (tmp_size_y * tmp_size_y); + if(smallest == -1 || smallest > tmp_size){ + if(tmp_size > 0){ +// std::cout << "Smallest size " << tmp_size << std::endl; + smallest = tmp_size; + } + else{ +// std::cout << "Weird zero distance between points" < keypoint_v; + keypoint_v.push_back(keypoint); + + cv::Mat descriptors_1; +#if CV_MAJOR_VERSION == 2 + cv::SiftDescriptorExtractor extractor; + extractor.compute( _img_gray, keypoint_v, descriptors_1); +#else + cv::Ptr extractor = cv::xfeatures2d::SURF::create(); +// cv::xfeatures2d::SiftDescriptorExtractor extractor; + extractor->compute( _img_gray, keypoint_v, descriptors_1); +#endif + + +// std::cout << descriptors_1.rows << " " << descriptors_1.cols << std::endl; + assert(descriptors_1.rows == 1); + + nodeAttribute.keypoint = keypoint; + nodeAttribute.position = keypoint.pt; + nodeAttribute.descriptor = descriptors_1; + + _prior_graph.addVertex(vertex_out, nodeAttribute); + das_v.push_back(v); + prior_v.push_back(vertex_out); + + } + + std::cout << "Done" << std::endl; + + //Adding all the edges + auto es = boost::edges(graph); + for (auto eit = es.first; eit != es.second; ++eit) { + auto sour = boost::source(*eit, graph); + auto targ = boost::target(*eit, graph); + PriorVertex source_p; + PriorVertex target_p; + bool flag_found_src = false; + bool flag_found_targ = false; + for(int i = 0 ; i < das_v.size() ; ++i){ + if(das_v[i] == sour){ + source_p = prior_v[i]; + assert(flag_found_src == false); + flag_found_src = true; + } + if(das_v[i] == targ){ + target_p = prior_v[i]; + assert(flag_found_targ == false); + flag_found_targ = true; + } + } + assert(flag_found_src == true); + assert(flag_found_targ == true); + + PriorEdge out_edge; + _prior_graph.addEdge(out_edge, source_p, target_p, graph[*eit]); + } + +} + + +void AASS::acg::PriorLoaderInterface::rotateGraph(const cv::Mat& rot_mat) +{ + auto transf = [](const cv::Mat& rot_mat, const cv::Point2d point) -> cv::Point2d { + //Matrix multiplication + cv::Mat point_m = (cv::Mat_(3,1) << point.x, point.y); + cv::Mat mat_out = rot_mat * point_m; +// std::cout << "Mat out " << mat_out << std::endl; + cv::Point2d point_out; + point_out.x = mat_out.at(0); + point_out.y = mat_out.at(1); + return point_out; + }; + + + + + std::pair< PriorVertexIterator, PriorVertexIterator > vp; + //vertices access all the vertix + //Classify them in order +// std::cout << "Gph size : " << _graph.getNumVertices() << std::endl; + int i = 0 ; + for (vp = boost::vertices(_prior_graph); vp.first != vp.second; ++vp.first) { +// std::cout << "going throught grph " << i << std::endl; ++i; + PriorVertex v = *vp.first; + //ATTENTION ! + cv::Point2d point; + point.x = _prior_graph[v].getX(); + point.y = _prior_graph[v].getY(); + + auto point_out = transf(rot_mat, point); + + //Matrix multiplication + + std::cout << "Point out " << point_out << std::endl; + + std::cout << "OLD value " << _prior_graph[v].getX() << " " << _prior_graph[v].getY() << std::endl; + _prior_graph[v].setX(point_out.x); + _prior_graph[v].setY(point_out.y); + _corner_prior_matched.push_back(point_out); + std::cout << "New value " << _corner_prior_matched[i].x << " " << _corner_prior_matched[i].y << std::endl; + std::cout << "New value " << _prior_graph[v].getX() << " " << _prior_graph[v].getY() << std::endl; + ++i; + } + + +} + + +void AASS::acg::PriorLoaderInterface::AffineTransformGraph(const cv::Mat& warp_transfo) +{ + auto transf = [](const cv::Mat& warp_transfo, const cv::Point2d point) -> cv::Point2d { + //Matrix multiplication + cv::Mat point_m = (cv::Mat_(3,1) << point.x, point.y, 1); + cv::Mat mat_out = warp_transfo * point_m; +// std::cout << "Mat out " << mat_out << std::endl; + cv::Point2d point_out; + point_out.x = mat_out.at(0); + point_out.y = mat_out.at(1); + std::cout << "reutnr point " << point_out.x << " " << point_out.y << std::endl; + return point_out; + }; + + + + + std::pair< PriorVertexIterator, PriorVertexIterator > vp; + //vertices access all the vertix + //Classify them in order +// std::cout << "Gph size : " << _graph.getNumVertices() << std::endl; + int i = 0 ; + for (vp = boost::vertices(_prior_graph); vp.first != vp.second; ++vp.first) { +// std::cout << "going throught grph " << i << std::endl; ++i; + PriorVertex v = *vp.first; + //ATTENTION ! + cv::Point2d point; + point.x = _prior_graph[v].getX(); + point.y = _prior_graph[v].getY(); + + cv::Point2d point_out = transf(warp_transfo, point); + + //Matrix multiplication + +// std::cout << "Point out " << point_out << std::endl; + +// std::cout << "OLD value " << _prior_graph[v].getX() << " " << _prior_graph[v].getY() << std::endl; + _prior_graph[v].setX(point_out.x); + _prior_graph[v].setY(point_out.y); + _corner_prior_matched.push_back(point_out); +// std::cout << "New value " << _corner_prior_matched[i].x << " " << _corner_prior_matched[i].y << std::endl; +// std::cout << "New value " << _prior_graph[v].getX() << " " << _prior_graph[v].getY() << std::endl; + ++i; + } + + +} + +void AASS::acg::PriorLoaderInterface::noTwiceSameEdge(bettergraph::PseudoGraph< AASS::vodigrex::SimpleNode, AASS::vodigrex::SimpleEdge > graph) +{ + + std::cout << "No twice same edge" << std::endl; + std::pair< + bettergraph::PseudoGraph::VertexIterator, + bettergraph::PseudoGraph::VertexIterator > vp; + + std::vector::Edge> e_vec; + + for (vp = boost::vertices(graph); vp.first != vp.second; ++vp.first) { + std::cout << "Vertex" << std::endl; +// bettergraph::PseudoGraph::Vertex v = *vp.first; + bettergraph::PseudoGraph::Vertex v = *vp.first; + bettergraph::PseudoGraph::EdgeIterator out_i, out_end; + bettergraph::PseudoGraph::Edge e; + + std::vector::Vertex> vertices_out_edge; + + std::vector::Edge> edge_seen; + + std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; + std::cout << " v has " << graph.getNumEdges(v) << std::endl; + + for (boost::tie(out_i, out_end) = boost::out_edges(v, graph); + out_i != out_end; ++out_i) { + std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; + std::cout << "Removing an edge test" << std::endl; + e = *out_i; + + for(std::vector::Edge>::iterator it = edge_seen.begin() ; it != edge_seen.end() ; ++it){ + if(e == *it){ + std::cout << "EDGE seen on this node :(" << std::endl; + assert(true == false); + } + } + +// for(std::vector::Edge>::iterator it = e_vec.begin() ; it != e_vec.end() ; ++it){ +// if(e == *it){ +// std::cout << "EDGE seen on another node :(" << std::endl; +// assert(true == false); +// } +// } + + e_vec.push_back(e); + edge_seen.push_back(e); + } + } + + std::cout << "So no twice for now! " << std::endl; + +} + + + +void AASS::acg::PriorLoaderInterface::toSimpleGraph(bettergraph::PseudoGraph< AASS::vodigrex::SimpleNode, AASS::vodigrex::SimpleEdge >& prior) +{ + noTwiceSameEdge(prior); + + std::pair< + bettergraph::PseudoGraph::VertexIterator, + bettergraph::PseudoGraph::VertexIterator > vp; + std::deque vec_deque; + + std::cout << "prior" << prior.getNumVertices() << std::endl << std::endl; + + int nb = prior.getNumVertices(); + + for (vp = boost::vertices(prior); vp.first != vp.second; ++vp.first) { + std::cout << "Vertex" << std::endl; +// bettergraph::PseudoGraph::Vertex v = *vp.first; + auto v = *vp.first; + bettergraph::PseudoGraph::EdgeIterator out_i, out_end; + bettergraph::PseudoGraph::Edge e; + + std::vector::Vertex> vertices_out_edge; + + std::vector::Edge> edge_seen; + + std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; + std::cout << " v has " << prior.getNumEdges(v) << std::endl; + + for (boost::tie(out_i, out_end) = boost::out_edges(v, prior); + out_i != out_end; ++out_i) { + std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; + std::cout << "Removing an edge test" << std::endl; + e = *out_i; + + for(auto it = edge_seen.begin() ; it != edge_seen.end() ; ++it){ + if(e == *it){ + std::cout << "EDGE seen :(" << std::endl; + assert(true == false); + } + } + + std::cout << "Vertiuce size " << vertices_out_edge.size() << " and edge " << e << std::endl; + edge_seen.push_back(e); + + + + std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; + +// bettergraph::PseudoGraph::Vertex targ = boost::target(e, (graph)); + auto targ = boost::target(e, prior); + std::cout << "Vertiuce size " << vertices_out_edge.size() << std::endl; + for(auto it = vertices_out_edge.begin() ; it != vertices_out_edge.end() ; ++it){ + if(targ == *it){ + std::cout << "Removing an edge" << std::endl; + prior.removeEdge(e); + assert(nb == prior.getNumVertices()); + } + } + std::cout << "Psuh back end targ " << std::endl; + vertices_out_edge.push_back(targ); + + + } + + std::cout << "Our for vertex" << std::endl; + + } + +} + +void AASS::acg::PriorLoaderInterface::convertGraph(const bettergraph::PseudoGraph< AASS::vodigrex::SimpleNode, AASS::vodigrex::SimpleEdge >& input, bettergraph::PseudoGraph< AASS::acg::PriorAttr, AASS::vodigrex::SimpleEdge >& output) +{ + + output.clear(); + std::pair< + typename bettergraph::PseudoGraph::VertexIterator, + typename bettergraph::PseudoGraph::VertexIterator > vp; + + std::deque< typename bettergraph::PseudoGraph::Vertex> vec_deque; + + std::deque< typename bettergraph::PseudoGraph::Vertex> vec_deque_input; + + //Add all vertex + for (vp = boost::vertices(input); vp.first != vp.second; ++vp.first) { +// bettergraph::PseudoGraph::Vertex v = *vp.first; + typename bettergraph::PseudoGraph::Vertex v = *vp.first; + typename bettergraph::PseudoGraph::Vertex vertex_out; + + PriorAttr priorattr(input[v]); + + output.addVertex(vertex_out, priorattr); + + vec_deque.push_back(vertex_out); + vec_deque_input.push_back(v); + + } + + //Simply add all edges + int self_link = 0 ; + for (vp = boost::vertices(input); vp.first != vp.second; ++vp.first) { + typename bettergraph::PseudoGraph::Vertex v = *vp.first; + typename bettergraph::PseudoGraph::EdgeIterator out_i, out_end; + typename bettergraph::PseudoGraph::Edge e; + + typename bettergraph::PseudoGraph::Vertex output_src; + for(int i = 0 ; i < vec_deque.size() ; ++i){ + if(vec_deque_input[i] == v){ + output_src = vec_deque[i]; + } + } + + for (boost::tie(out_i, out_end) = boost::out_edges(v, (input)); + out_i != out_end; ++out_i) { + e = *out_i; + typename bettergraph::PseudoGraph::Vertex targ = boost::target(e, input); + typename bettergraph::PseudoGraph::Vertex src = boost::source(e, input); + typename bettergraph::PseudoGraph::Vertex output_targ; + for(int i = 0 ; i < vec_deque.size() ; ++i){ + if(vec_deque_input[i] == targ){ + output_targ = vec_deque[i]; + } + + } + + typename bettergraph::PseudoGraph::Edge e_out_output; + output.addEdge(e_out_output, output_src, output_targ, input[e]); + + } + } + +// assert(2 * output.getNumEdges() == input.getNumEdges()); + assert(output.getNumVertices() == input.getNumVertices()); + + + +} From 8a1e8284f1f0eec0cdc7f9ed20fd48dca5601e8f Mon Sep 17 00:00:00 2001 From: Malcolm Mielle Date: Tue, 26 Sep 2017 16:48:48 +0200 Subject: [PATCH 4/7] feature_lib --- include/auto_complete_graph/ACG_feature.hpp | 518 +------------------- src/ACG_feature.cpp | 516 +++++++++++++++++++ 2 files changed, 524 insertions(+), 510 deletions(-) create mode 100644 src/ACG_feature.cpp diff --git a/include/auto_complete_graph/ACG_feature.hpp b/include/auto_complete_graph/ACG_feature.hpp index e96ac1df..6bb3ef0c 100644 --- a/include/auto_complete_graph/ACG_feature.hpp +++ b/include/auto_complete_graph/ACG_feature.hpp @@ -38,193 +38,16 @@ namespace acg{ } ///@brief Create new link based on the distance AND the angle of the corners - virtual int createNewLinks() - { - int count = 0 ; -// std::vector < std::pair < AASS::acg::VertexLandmarkNDT*, AASS::acg::VertexSE2Prior*> > links; - - std::cout << "Number new landmarks " << _nodes_landmark.size() << std::endl; - std::cout << "Prior " << _nodes_prior.size() << std::endl; - // if(_nodes_prior.size() > 0){ - -// int a; -// std::cin >> a; - - //Update ALL links - auto it = _nodes_landmark.begin(); - for(it ; it != _nodes_landmark.end() ; it++){ - // std::cout << "Working on links " << std::endl; - Eigen::Vector2d pose_landmark = (*it)->estimate(); - auto it_prior = _nodes_prior.begin(); - for(it_prior ; it_prior != _nodes_prior.end() ; ++it_prior){ - - Eigen::Vector3d pose_tmp = (*it_prior)->estimate().toVector(); - Eigen::Vector2d pose_prior; pose_prior << pose_tmp(0), pose_tmp(1); - double norm_tmp = (pose_prior - pose_landmark).norm(); - - - - //Don't add the same link twice - if(linkAlreadyExist(*it, *it_prior) == false){ - - // std::cout << "new" << std::endl; - - //Update the link - if(norm_tmp <= _min_distance_for_link_in_meter){ - std::cout << "NORM " << norm_tmp << "min dist " << _min_distance_for_link_in_meter << std::endl; - // ptr_closest = *it_prior; - // norm = norm_tmp; - //Pushing the link - // std::cout << "Pushing " << *it << " and " << ptr_closest << std::endl; - - if( sameOrientation(**it, **it_prior) ){ -// links.push_back(std::pair(*it, *it_prior)); - ++count; - g2o::Vector2D vec; - vec << 0, 0; - addLinkBetweenMaps(vec, *it_prior, *it); - } - - } - } - else{ - - std::cout << "Already exist" << std::endl; - } - } - } - - return count; - - } + virtual int createNewLinks(); - bool sameOrientation(const AASS::acg::VertexLandmarkNDT& landmark, const AASS::acg::VertexSE2Prior& prior_corner){ - double landmark_angle = landmark.getAngleWidth(); - double landmark_direction = landmark.getDirectionGlobal(); - - std::cout << "Orientation calc" << std::endl; - auto angledirection = prior_corner.getAngleDirection(); - for(auto it = angledirection.begin() ; it != angledirection.end() ; ++it){ - - double angle_width = it->first; - double direction = it->second; - assert(angle_width >= 0.08); - std::cout << " Angles " << angle_width << " " << direction << " and " << landmark_angle << " " << landmark_direction << std::endl; - std::cout << direction << " <= " << landmark_direction + 0.785 << " && " << direction << " >= " << landmark_direction - 0.785 << " && " << angle_width << " <= " << landmark_angle + 0.785 << " && " << angle_width << " >= " << landmark_angle - 0.349 << std::endl; - - double landmark_direction_over = landmark_direction + 0.785; - if (landmark_direction_over < 0) landmark_direction_over += 2 * M_PI; - double landmark_direction_under = landmark_direction - 0.785; - if (landmark_direction_under < 0) landmark_direction_under += 2 * M_PI; - double landmark_angle_under = landmark_angle - 0.349; - if (landmark_angle_under < 0) landmark_angle_under += 2 * M_PI; - double landmark_angle_over = landmark_angle + 0.785; - if (landmark_angle_over >= 2 * M_PI) landmark_angle_over -= 2 * M_PI; - - if( direction <= landmark_direction_over && direction >= landmark_direction_under && - angle_width <= landmark_angle_over && angle_width >= landmark_angle_under - ){ -// if( direction <= landmark_direction + 0.785 && direction >= landmark_direction - 0.785 -// ){ - std::cout << "Good angle" << std::endl; -// int a; -// std::cin>>a; - return true; - } - } -// std::cout << "Not good " << std::endl; -// int a; -// std::cin>>a; - return false; - } + bool sameOrientation(const AASS::acg::VertexLandmarkNDT& landmark, const AASS::acg::VertexSE2Prior& prior_corner); virtual /** * @brief actual optimization loop. Make sure setFirst and prepare are called before. Use Huber first and then DCS. * */ - void optimize(int iter = 10){ - - _chi2s.clear(); - - std::cout << "BEFORE THE OPTIMIZATION BUT AFTER ADDING A NODE" << std::endl; - overCheckLinks(); - checkRobotPoseNotMoved("before"); - - /********** HUBER kernel ***********/ - -// _optimizable_graph.setHuberKernel(); - - _flag_optimize = checkAbleToOptimize(); - - if(_flag_optimize == true){ - std::cout << "OPTIMIZE" << std::endl; - - if(_flag_use_robust_kernel){ - setAgeingHuberKernel(); - } - checkRobotPoseNotMoved("set age in huber kernel"); - testNoNanInPrior("set age in huber kernel"); - testInfoNonNul("set age in huber kernel"); - -// updatePriorEdgeCovariance(); - testNoNanInPrior("update prior edge cov"); - - //Avoid overshoot of the cov - for(size_t i = 0 ; i < iter ; ++i){ - _optimizable_graph.optimize(1); - checkRobotPoseNotMoved("optimized with huber"); - testNoNanInPrior("optimized with huber"); - testInfoNonNul("optimized with huber"); - //Update prior edge covariance -// updatePriorEdgeCovariance(); - testNoNanInPrior("update prior edge cov after opti huber"); - saveErrorStep(); - } - - /********** DCS kernel ***********/ - if(_flag_use_robust_kernel){ - setAgeingDCSKernel(); - } - testNoNanInPrior("set age in DCS kernel"); - - for(size_t i = 0 ; i < iter*2 ; ++i){ - _optimizable_graph.optimize(1); - checkRobotPoseNotMoved("optimized with dcs"); - testNoNanInPrior("optimized with dcs"); - testInfoNonNul("optimized with dcs"); - //Update prior edge covariance -// updatePriorEdgeCovariance(); - testNoNanInPrior("update prior edge cov after opti dcs"); - saveErrorStep(); - } - - - } - else{ - std::cout << "No Optimization :(" << std::endl; - } - - std::cout << "AFTER THE OPTIMIZATION CREATE" << std::endl; -// int count = countLinkToMake(); -// // int count2 = createNewLinks(); -// if(count != count2){ -// std::cout << "Weird different detection" << std::endl; -// throw std::runtime_error("ARF NOT GOOD COUNT"); -// } -// overCheckLinks(); - - removeBadLinks(); - std::cout << "AFTER THE OPTIMIZATION REMOVE" << std::endl; - overCheckLinks(); - - exportChi2s(); - checkRobotPoseNotMoved("after"); - -// cv::Mat d; -// createDescriptorNDT(d); - - } + void optimize(int iter = 10); virtual void overCheckLinks(){ //Because not all link will be created @@ -241,341 +64,16 @@ namespace acg{ return false; } - void SIFTNdtLandmark(const cv::Point2f centre, const cv::Mat& img, double size_image_max, double cell_size, AASS::acg::VertexLandmarkNDT* vertex){ - - - cv::Mat img_tmpp; - img.convertTo(img_tmpp, CV_8U); - cv::Mat img_tmp; - cv::cvtColor( img_tmpp, img_tmp, CV_BGR2GRAY ); - // cv::imshow("NDT_map_C", img_tmp); - // cv::waitKey(0); - std::string type = type2str(img_tmp.type()); - std::cout << ">Type " << type << std::endl; - assert(type == "8UC1"); - //Creating a SIFT descriptor for eahc corner - cv::KeyPoint keypoint; - keypoint.pt = centre; - - double sizet = 2 * size_image_max / cell_size ; - keypoint.size = sizet ; - keypoint.angle = -1 ; - keypoint.octave = 1 ; - - std::vector keypoint_v; - keypoint_v.push_back(keypoint); - - cv::Mat descriptors_1; - #if CV_MAJOR_VERSION == 2 - cv::SiftDescriptorExtractor extractor; - extractor.compute( img_tmp, keypoint_v, descriptors_1); - #else - cv::Ptr extractor = cv::xfeatures2d::SURF::create(); - // cv::xfeatures2d::SiftDescriptorExtractor extractor; - extractor->compute( img_tmp, keypoint_v, descriptors_1); - #endif - - - std::cout << descriptors_1.rows << " " << descriptors_1.cols << std::endl; - assert(descriptors_1.rows == 1); - - vertex->descriptor = descriptors_1; - vertex->keypoint = keypoint; - } - - void createDescriptorPrior(cv::Mat& desc) - { - cv::Mat m = cv::Mat::ones(4, 3, CV_64F); // 3 cols, 4 rows - cv::Mat row = cv::Mat::ones(1, 3, CV_64F); // 3 cols - m.push_back(row); // 3 cols, 5 rows - - auto it = _nodes_prior.begin(); - desc = (*it)->priorattr.descriptor; - for( ; it != _nodes_prior.end() ; ++it){ - desc.push_back((*it)->priorattr.descriptor); - } - assert(desc.rows == _nodes_prior.size()); - - } - + void SIFTNdtLandmark(const cv::Point2f centre, const cv::Mat& img, double size_image_max, double cell_size, AASS::acg::VertexLandmarkNDT* vertex); + void createDescriptorPrior(cv::Mat& desc); //UNUSUED - void createDescriptorNDT(cv::Mat& desc) - { - - //Convert to OpenCV - auto it = _nodes_ndt.begin(); - cv::Mat ndt_img; - perception_oru::ndt_feature_finder::toCvMat(*((*it)->getMap().get()), ndt_img, 500); - for(; it != _nodes_ndt.end() ; ++it){ - cv::Mat tmp; - cv::Mat finl; - double max, min; - double size_image_max = 500; - perception_oru::ndt_feature_finder::toCvMat(*((*it)->getMap().get()), tmp, size_image_max, max, min); - std::cout << "MAX min " << max << " " << min << std::endl; - AASS::acg::VertexSE2RobotPose* v_ptr_ndt = *it; - - for(auto it_edge = _edge_landmark.begin() ; it_edge != _edge_landmark.end() ; ++it_edge){ - AASS::acg::VertexLandmarkNDT* v_ptr = dynamic_cast ((*it_edge)->vertices()[1]); - std::cout << "Position : " << v_ptr->position << std::endl; - // cv::Point2f p; - auto vertex = v_ptr->estimate(); - //Getting the translation out of the transform : https://en.wikipedia.org/wiki/Transformation_matrix - // p.x = vertex(0); - // p.y = vertex(1); - - //Transforming corner into NDT_map coordinate system - //Corner pose - Eigen::Vector3d vec; - vec << vertex(0), vertex(1), 0; - - auto vec_out_se2 = v_ptr_ndt->estimate(); - - //Uses just added modified node - g2o::SE2 se2_tmp(vec); - //Obstacle pose - ndt_node pose - se2_tmp = se2_tmp * vec_out_se2.inverse(); - - Eigen::Vector3d vec_out = se2_tmp.toVector(); - - cv::Point2f p_out(vec_out(0), vec_out(1)); - - std::cout << "Position " << p_out << std::endl; - cv::Point2d center = perception_oru::ndt_feature_finder::scalePoint(p_out, max, min, size_image_max); - std::cout << "Position " << center << "max min " << max << " " << min << std::endl; - assert(center.x <= size_image_max); - assert(center.y <= size_image_max); - cv::circle(tmp, center, 20, cv::Scalar(255, 255, 255), 5); - - } - - cv::imshow("NDT_map", tmp); - cv::waitKey(0); - - - - } - - - - - } - + void createDescriptorNDT(cv::Mat& desc); - void matchLinks() - { - cv::Mat desc_prior; - cv::Mat desc_ndt; - createDescriptorNDT(desc_ndt); - createDescriptorPrior(desc_prior); - - cv::FlannBasedMatcher matcher; - std::vector< cv::DMatch > matches; - matcher.match( desc_ndt, desc_prior, matches ); - - } + void matchLinks(); - void extractCornerNDTMap(const std::shared_ptr& map, AASS::acg::VertexSE2RobotPose* robot_ptr, const g2o::SE2& robot_pos) - { - - std::vector corners_end; - - //HACK For now : we translate the Corner extracted and not the ndt-maps - auto cells = map->getAllCellsShared(); - std::cout << "got all cell shared" << std::endl; - double x2, y2, z2; - map->getCellSizeInMeters(x2, y2, z2); - std::cout << "got all cell sized" << std::endl; - double cell_size = x2; - - perception_oru::ndt_feature_finder::NDTCorner cornersExtractor; - std::cout << "hopidy" << std::endl; - auto ret_export = cornersExtractor.getAllCorners(*map); - std::cout << "gotall corner" << std::endl; - auto ret_opencv_point_corner = cornersExtractor.getAccurateCvCorners(); - std::cout << "got all accurate corners" << std::endl; - auto angles = cornersExtractor.getAngles(); - // std::cout << "got all angles" << std::endl; - - auto it = ret_opencv_point_corner.begin(); - - std::cout << "Found " << ret_opencv_point_corner.size() << " corners " << std::endl; - //Find all the observations : - - //**************** HACK: translate the corners now : **************// - - int count_tmp = 0; - for(it ; it != ret_opencv_point_corner.end() ; ++it){ - // std::cout << "MOVE : "<< it -> x << " " << it-> y << std::endl; - Eigen::Vector3d vec; - vec << it->x, it->y, angles[count_tmp].second; - - // auto vec_out_se2 = _nodes_ndt[i]->estimate(); - - //Calculate obstacle position in global coordinates. - - //Node it beong to : - g2o::SE2 vec_out_se2 = g2o::SE2(robot_pos); - //Pose of landmajr - g2o::SE2 se2_tmp(vec); - //Composition - vec_out_se2 = vec_out_se2 * se2_tmp; - Eigen::Vector3d vec_out = vec_out_se2.toVector(); - - //Pose of landmark in global reference - cv::Point2f p_out(vec_out(0), vec_out(1)); - - Eigen::Vector2d real_obs; real_obs << p_out.x, p_out.y; - Eigen::Vector2d observation2d_test; - //Projecting real_obs into robot coordinate frame - - auto trueObservation_tmp = robot_pos.inverse() * vec_out_se2; - Eigen::Vector3d trueObservation = trueObservation_tmp.toVector(); - Eigen::Vector2d observation; observation << trueObservation(0), trueObservation(1); - - //***************************Old version for testing***************************// - Eigen::Vector2d trueObservation2d = robot_pos.inverse() * real_obs; - // std::cout << trueObservation(0) << " == " << trueObservation2d(0) << std::endl; - // assert(trueObservation(0) == trueObservation2d(0)); - // std::cout << trueObservation(1) << " == " << trueObservation2d(1) << std::endl; - // assert(trueObservation(1) == trueObservation2d(1)); - observation2d_test = trueObservation2d; - // std::cout << observation(0) << " == " << observation2d_test(0) << " minus " << observation(0) - observation2d_test(0) << std::endl; - // assert(trueObservation(0) == trueObservation2d(0)); - // std::cout << observation(1) << " == " << observation2d_test(1) << " minus " << observation(1) - observation2d_test(1) << std::endl; - // int a ; - // std::cin >> a; - //******************************************************************************// - - double angle_landmark = trueObservation(2); - - // std::cout << "Node transfo " << ndt_graph.getNode(i).T.matrix() << std::endl; - std::cout << "Position node " << robot_pos.toVector() << std::endl; - std::cout << " vec " << vec << std::endl; - // std::cout << "Well " << robot_pos.toVector() + vec << "==" << ndt_graph.getNode(i).T * vec << std::endl; - - //ATTENTION THIS IS NOT TRUE BUT REALLY CLOSE - // assert (robot_pos + vec == ndt_graph.getNode(i).T * vec); - - // std::cout << "NEW POINT : "<< p_out << std::endl; - - NDTCornerGraphElement cor(p_out); - cor.addAllObserv(robot_ptr, observation, angle_landmark, angles[count_tmp].first); - corners_end.push_back(cor); - count_tmp++; - - } - //At this point, we have all the corners - // assert(corners_end.size() - c_size == ret_opencv_point_corner_tmp.size()); - assert(corners_end.size() == ret_opencv_point_corner.size()); - // assert(corners_end.size() - c_size == angles_tmp.size()); - // assert(corners_end.size() == angles.size()); - // c_size = corners_end.size(); - - /***************** ADD THE CORNERS INTO THE GRAPH***********************/ - - for(size_t i = 0 ; i < corners_end.size() ; ++i){ - // std::cout << "checking corner : " << _nodes_landmark.size() << std::endl ; /*corners_end[i].print()*/ ; std::cout << std::endl; - bool seen = false; - AASS::acg::VertexLandmarkNDT* ptr_landmark_seen = NULL; - for(size_t j = 0 ; j <_nodes_landmark.size() ; ++j){ - // if(tmp[j] == _corners_position[i]){ - g2o::Vector2D landmark = _nodes_landmark[j]->estimate(); - cv::Point2f point_land(landmark(0), landmark(1)); - - double res = cv::norm(point_land - corners_end[i].point); - - // std::cout << "res : " << res << " points " << point_land << " " << corners_end[i].point << " cell size " << cell_size << std::endl; - - //If we found the landmark, we save the data - if( res < cell_size * 2){ - seen = true; - ptr_landmark_seen = _nodes_landmark[j]; - } - } - if(seen == false){ - // std::cout << "New point " << i << " " << ret_opencv_point_corner.size() << std::endl; - assert(i < ret_opencv_point_corner.size()); - g2o::Vector2D vec; - vec << corners_end[i].point.x, corners_end[i].point.y ; - AASS::acg::VertexLandmarkNDT* ptr = addLandmarkPose(vec, ret_opencv_point_corner[i], 1); - ptr->addAngleDirection(corners_end[i].getAngleWidth(), corners_end[i].getDirection()); - ptr->first_seen_from = robot_ptr; - //TODO IMPORTANT : Directly calculate SIft here so I don't have to do it again later - - std::cout << "Descriptors" << std::endl; - /************************************************************/ - - //Convert NDT MAP to image - cv::Mat ndt_img; - auto map_tmp = corners_end[i].getNodeLinkedPtr()->getMap(); - - std::cout << "Descriptors" << std::endl; - double size_image_max = 500; - double min, max; - //TODO: super convoluted, get rid of NDTCornerGraphElement! - perception_oru::ndt_feature_finder::toCvMat(*map_tmp, ndt_img, size_image_max, max, min); - - //Use accurate CV point - //Get old position - // std::cout << "Position " << ret_opencv_point_corner[i] << std::endl; - cv::Point2i center = perception_oru::ndt_feature_finder::scalePoint(ret_opencv_point_corner[i], max, min, size_image_max); - // std::cout << "Position " << center << "max min " << max << " " << min << std::endl; - assert(center.x <= size_image_max); - assert(center.y <= size_image_max); - - // std::cout << "getting the angle" << std::endl; - double angle = corners_end[i].getDirection(); - double width = corners_end[i].getAngleWidth(); - double plus_a = angle + (width/2); - double moins_a = angle - (width/2); - - - // std::cout << "angle " << angle<< std::endl; - cv::Point2i p2; - p2.x = center.x + (50 * std::cos(angle) ); - p2.y = center.y + (50 * std::sin(angle) ); - cv::Point2i p2_p; - p2_p.x = center.x + (50 * std::cos(plus_a) ); - p2_p.y = center.y + (50 * std::sin(plus_a) ); - cv::Point2i p2_m; - p2_m.x = center.x + (50 * std::cos(moins_a) ); - p2_m.y = center.y + (50 * std::sin(moins_a) ); - - // std::cout << "Line " << center << " "<< p2 << std::endl;; - - // std::cout << "Angle" << angle. - - // cv::Mat copyy; - // ndt_img.copyTo(copyy); - // cv::circle(copyy, center, 20, cv::Scalar(255, 255, 255), 5); - // cv::line(copyy, center, p2, cv::Scalar(255, 255, 255), 1); - // cv::line(copyy, center, p2_p, cv::Scalar(255, 255, 255), 1); - // cv::line(copyy, center, p2_m, cv::Scalar(255, 255, 255), 1); - // - // cv::imshow("NDT_map", copyy); - // cv::waitKey(0); - - double cx, cy, cz; - //Should it be in meters ? - map_tmp->getGridSizeInMeters(cx, cy, cz); - SIFTNdtLandmark(center, ndt_img, size_image_max, cx, ptr); - - /****************************************************************/ - - addLandmarkObservation(corners_end[i].getObservations(), corners_end[i].getNodeLinkedPtr(), ptr); - - - } - else{ - std::cout << "Point seen " << std::endl; - addLandmarkObservation(corners_end[i].getObservations(), corners_end[i].getNodeLinkedPtr(), ptr_landmark_seen); - } - } - - } + void extractCornerNDTMap(const std::shared_ptr& map, AASS::acg::VertexSE2RobotPose* robot_ptr, const g2o::SE2& robot_pos); diff --git a/src/ACG_feature.cpp b/src/ACG_feature.cpp new file mode 100644 index 00000000..e566047c --- /dev/null +++ b/src/ACG_feature.cpp @@ -0,0 +1,516 @@ +#include "auto_complete_graph/ACG_feature.hpp" + +void AASS::acg::AutoCompleteGraphFeature::extractCornerNDTMap(const std::shared_ptr< lslgeneric::NDTMap >& map, AASS::acg::VertexSE2RobotPose* robot_ptr, const g2o::SE2& robot_pos) +{ + + std::vector corners_end; + + //HACK For now : we translate the Corner extracted and not the ndt-maps + auto cells = map->getAllCellsShared(); + std::cout << "got all cell shared" << std::endl; + double x2, y2, z2; + map->getCellSizeInMeters(x2, y2, z2); + std::cout << "got all cell sized" << std::endl; + double cell_size = x2; + + perception_oru::ndt_feature_finder::NDTCorner cornersExtractor; + std::cout << "hopidy" << std::endl; + auto ret_export = cornersExtractor.getAllCorners(*map); + std::cout << "gotall corner" << std::endl; + auto ret_opencv_point_corner = cornersExtractor.getAccurateCvCorners(); + std::cout << "got all accurate corners" << std::endl; + auto angles = cornersExtractor.getAngles(); +// std::cout << "got all angles" << std::endl; + + auto it = ret_opencv_point_corner.begin(); + + std::cout << "Found " << ret_opencv_point_corner.size() << " corners " << std::endl; + //Find all the observations : + + //**************** HACK: translate the corners now : **************// + + int count_tmp = 0; + for(it ; it != ret_opencv_point_corner.end() ; ++it){ +// std::cout << "MOVE : "<< it -> x << " " << it-> y << std::endl; + Eigen::Vector3d vec; + vec << it->x, it->y, angles[count_tmp].second; + +// auto vec_out_se2 = _nodes_ndt[i]->estimate(); + + //Calculate obstacle position in global coordinates. + + //Node it beong to : + g2o::SE2 vec_out_se2 = g2o::SE2(robot_pos); + //Pose of landmajr + g2o::SE2 se2_tmp(vec); + //Composition + vec_out_se2 = vec_out_se2 * se2_tmp; + Eigen::Vector3d vec_out = vec_out_se2.toVector(); + + //Pose of landmark in global reference + cv::Point2f p_out(vec_out(0), vec_out(1)); + + Eigen::Vector2d real_obs; real_obs << p_out.x, p_out.y; + Eigen::Vector2d observation2d_test; + //Projecting real_obs into robot coordinate frame + + auto trueObservation_tmp = robot_pos.inverse() * vec_out_se2; + Eigen::Vector3d trueObservation = trueObservation_tmp.toVector(); + Eigen::Vector2d observation; observation << trueObservation(0), trueObservation(1); + + //***************************Old version for testing***************************// + Eigen::Vector2d trueObservation2d = robot_pos.inverse() * real_obs; +// std::cout << trueObservation(0) << " == " << trueObservation2d(0) << std::endl; +// assert(trueObservation(0) == trueObservation2d(0)); +// std::cout << trueObservation(1) << " == " << trueObservation2d(1) << std::endl; +// assert(trueObservation(1) == trueObservation2d(1)); + observation2d_test = trueObservation2d; +// std::cout << observation(0) << " == " << observation2d_test(0) << " minus " << observation(0) - observation2d_test(0) << std::endl; +// assert(trueObservation(0) == trueObservation2d(0)); +// std::cout << observation(1) << " == " << observation2d_test(1) << " minus " << observation(1) - observation2d_test(1) << std::endl; +// int a ; +// std::cin >> a; + //******************************************************************************// + + double angle_landmark = trueObservation(2); + +// std::cout << "Node transfo " << ndt_graph.getNode(i).T.matrix() << std::endl; + std::cout << "Position node " << robot_pos.toVector() << std::endl; + std::cout << " vec " << vec << std::endl; +// std::cout << "Well " << robot_pos.toVector() + vec << "==" << ndt_graph.getNode(i).T * vec << std::endl; + + //ATTENTION THIS IS NOT TRUE BUT REALLY CLOSE +// assert (robot_pos + vec == ndt_graph.getNode(i).T * vec); + +// std::cout << "NEW POINT : "<< p_out << std::endl; + + NDTCornerGraphElement cor(p_out); + cor.addAllObserv(robot_ptr, observation, angle_landmark, angles[count_tmp].first); + corners_end.push_back(cor); + count_tmp++; + + } + //At this point, we have all the corners +// assert(corners_end.size() - c_size == ret_opencv_point_corner_tmp.size()); + assert(corners_end.size() == ret_opencv_point_corner.size()); +// assert(corners_end.size() - c_size == angles_tmp.size()); +// assert(corners_end.size() == angles.size()); +// c_size = corners_end.size(); + + /***************** ADD THE CORNERS INTO THE GRAPH***********************/ + + for(size_t i = 0 ; i < corners_end.size() ; ++i){ +// std::cout << "checking corner : " << _nodes_landmark.size() << std::endl ; /*corners_end[i].print()*/ ; std::cout << std::endl; + bool seen = false; + AASS::acg::VertexLandmarkNDT* ptr_landmark_seen = NULL; + for(size_t j = 0 ; j <_nodes_landmark.size() ; ++j){ +// if(tmp[j] == _corners_position[i]){ + g2o::Vector2D landmark = _nodes_landmark[j]->estimate(); + cv::Point2f point_land(landmark(0), landmark(1)); + + double res = cv::norm(point_land - corners_end[i].point); + +// std::cout << "res : " << res << " points " << point_land << " " << corners_end[i].point << " cell size " << cell_size << std::endl; + + //If we found the landmark, we save the data + if( res < cell_size * 2){ + seen = true; + ptr_landmark_seen = _nodes_landmark[j]; + } + } + if(seen == false){ +// std::cout << "New point " << i << " " << ret_opencv_point_corner.size() << std::endl; + assert(i < ret_opencv_point_corner.size()); + g2o::Vector2D vec; + vec << corners_end[i].point.x, corners_end[i].point.y ; + AASS::acg::VertexLandmarkNDT* ptr = addLandmarkPose(vec, ret_opencv_point_corner[i], 1); + ptr->addAngleDirection(corners_end[i].getAngleWidth(), corners_end[i].getDirection()); + ptr->first_seen_from = robot_ptr; + //TODO IMPORTANT : Directly calculate SIft here so I don't have to do it again later + + std::cout << "Descriptors" << std::endl; + /************************************************************/ + + //Convert NDT MAP to image + cv::Mat ndt_img; + auto map_tmp = corners_end[i].getNodeLinkedPtr()->getMap(); + + std::cout << "Descriptors" << std::endl; + double size_image_max = 500; + double min, max; + //TODO: super convoluted, get rid of NDTCornerGraphElement! + perception_oru::ndt_feature_finder::toCvMat(*map_tmp, ndt_img, size_image_max, max, min); + + //Use accurate CV point + //Get old position +// std::cout << "Position " << ret_opencv_point_corner[i] << std::endl; + cv::Point2i center = perception_oru::ndt_feature_finder::scalePoint(ret_opencv_point_corner[i], max, min, size_image_max); +// std::cout << "Position " << center << "max min " << max << " " << min << std::endl; + assert(center.x <= size_image_max); + assert(center.y <= size_image_max); + +// std::cout << "getting the angle" << std::endl; + double angle = corners_end[i].getDirection(); + double width = corners_end[i].getAngleWidth(); + double plus_a = angle + (width/2); + double moins_a = angle - (width/2); + + +// std::cout << "angle " << angle<< std::endl; + cv::Point2i p2; + p2.x = center.x + (50 * std::cos(angle) ); + p2.y = center.y + (50 * std::sin(angle) ); + cv::Point2i p2_p; + p2_p.x = center.x + (50 * std::cos(plus_a) ); + p2_p.y = center.y + (50 * std::sin(plus_a) ); + cv::Point2i p2_m; + p2_m.x = center.x + (50 * std::cos(moins_a) ); + p2_m.y = center.y + (50 * std::sin(moins_a) ); + +// std::cout << "Line " << center << " "<< p2 << std::endl;; + +// std::cout << "Angle" << angle. + +// cv::Mat copyy; +// ndt_img.copyTo(copyy); +// cv::circle(copyy, center, 20, cv::Scalar(255, 255, 255), 5); +// cv::line(copyy, center, p2, cv::Scalar(255, 255, 255), 1); +// cv::line(copyy, center, p2_p, cv::Scalar(255, 255, 255), 1); +// cv::line(copyy, center, p2_m, cv::Scalar(255, 255, 255), 1); +// +// cv::imshow("NDT_map", copyy); +// cv::waitKey(0); + + double cx, cy, cz; + //Should it be in meters ? + map_tmp->getGridSizeInMeters(cx, cy, cz); + SIFTNdtLandmark(center, ndt_img, size_image_max, cx, ptr); + + /****************************************************************/ + + addLandmarkObservation(corners_end[i].getObservations(), corners_end[i].getNodeLinkedPtr(), ptr); + + + } + else{ + std::cout << "Point seen " << std::endl; + addLandmarkObservation(corners_end[i].getObservations(), corners_end[i].getNodeLinkedPtr(), ptr_landmark_seen); + } + } + +} + + +void AASS::acg::AutoCompleteGraphFeature::matchLinks() +{ + cv::Mat desc_prior; + cv::Mat desc_ndt; + createDescriptorNDT(desc_ndt); + createDescriptorPrior(desc_prior); + + cv::FlannBasedMatcher matcher; + std::vector< cv::DMatch > matches; + matcher.match( desc_ndt, desc_prior, matches ); + +} + +void AASS::acg::AutoCompleteGraphFeature::createDescriptorNDT(cv::Mat& desc){ + //Convert to OpenCV + auto it = _nodes_ndt.begin(); + cv::Mat ndt_img; + perception_oru::ndt_feature_finder::toCvMat(*((*it)->getMap().get()), ndt_img, 500); + for(; it != _nodes_ndt.end() ; ++it){ + cv::Mat tmp; + cv::Mat finl; + double max, min; + double size_image_max = 500; + perception_oru::ndt_feature_finder::toCvMat(*((*it)->getMap().get()), tmp, size_image_max, max, min); + std::cout << "MAX min " << max << " " << min << std::endl; + AASS::acg::VertexSE2RobotPose* v_ptr_ndt = *it; + + for(auto it_edge = _edge_landmark.begin() ; it_edge != _edge_landmark.end() ; ++it_edge){ + AASS::acg::VertexLandmarkNDT* v_ptr = dynamic_cast ((*it_edge)->vertices()[1]); + std::cout << "Position : " << v_ptr->position << std::endl; +// cv::Point2f p; + auto vertex = v_ptr->estimate(); + //Getting the translation out of the transform : https://en.wikipedia.org/wiki/Transformation_matrix +// p.x = vertex(0); +// p.y = vertex(1); + + //Transforming corner into NDT_map coordinate system + //Corner pose + Eigen::Vector3d vec; + vec << vertex(0), vertex(1), 0; + + auto vec_out_se2 = v_ptr_ndt->estimate(); + + //Uses just added modified node + g2o::SE2 se2_tmp(vec); + //Obstacle pose - ndt_node pose + se2_tmp = se2_tmp * vec_out_se2.inverse(); + + Eigen::Vector3d vec_out = se2_tmp.toVector(); + + cv::Point2f p_out(vec_out(0), vec_out(1)); + + std::cout << "Position " << p_out << std::endl; + cv::Point2d center = perception_oru::ndt_feature_finder::scalePoint(p_out, max, min, size_image_max); + std::cout << "Position " << center << "max min " << max << " " << min << std::endl; + assert(center.x <= size_image_max); + assert(center.y <= size_image_max); + cv::circle(tmp, center, 20, cv::Scalar(255, 255, 255), 5); + + } + + cv::imshow("NDT_map", tmp); + cv::waitKey(0); + + + + } + +} + +void AASS::acg::AutoCompleteGraphFeature::createDescriptorPrior(cv::Mat& desc) +{ + cv::Mat m = cv::Mat::ones(4, 3, CV_64F); // 3 cols, 4 rows + cv::Mat row = cv::Mat::ones(1, 3, CV_64F); // 3 cols + m.push_back(row); // 3 cols, 5 rows + + auto it = _nodes_prior.begin(); + desc = (*it)->priorattr.descriptor; + for( ; it != _nodes_prior.end() ; ++it){ + desc.push_back((*it)->priorattr.descriptor); + } + assert(desc.rows == _nodes_prior.size()); + +} + + +void AASS::acg::AutoCompleteGraphFeature::SIFTNdtLandmark(const cv::Point2f centre, const cv::Mat& img, double size_image_max, double cell_size, AASS::acg::VertexLandmarkNDT* vertex) +{ + + cv::Mat img_tmpp; + img.convertTo(img_tmpp, CV_8U); + cv::Mat img_tmp; + cv::cvtColor( img_tmpp, img_tmp, CV_BGR2GRAY ); +// cv::imshow("NDT_map_C", img_tmp); +// cv::waitKey(0); + std::string type = type2str(img_tmp.type()); + std::cout << ">Type " << type << std::endl; + assert(type == "8UC1"); + //Creating a SIFT descriptor for eahc corner + cv::KeyPoint keypoint; + keypoint.pt = centre; + + double sizet = 2 * size_image_max / cell_size ; + keypoint.size = sizet ; + keypoint.angle = -1 ; + keypoint.octave = 1 ; + + std::vector keypoint_v; + keypoint_v.push_back(keypoint); + + cv::Mat descriptors_1; +#if CV_MAJOR_VERSION == 2 + cv::SiftDescriptorExtractor extractor; + extractor.compute( img_tmp, keypoint_v, descriptors_1); +#else + cv::Ptr extractor = cv::xfeatures2d::SURF::create(); +// cv::xfeatures2d::SiftDescriptorExtractor extractor; + extractor->compute( img_tmp, keypoint_v, descriptors_1); +#endif + + + std::cout << descriptors_1.rows << " " << descriptors_1.cols << std::endl; + assert(descriptors_1.rows == 1); + + vertex->descriptor = descriptors_1; + vertex->keypoint = keypoint; +} + + +void AASS::acg::AutoCompleteGraphFeature::optimize(int iter){ + + _chi2s.clear(); + + std::cout << "BEFORE THE OPTIMIZATION BUT AFTER ADDING A NODE" << std::endl; + overCheckLinks(); + checkRobotPoseNotMoved("before"); + + /********** HUBER kernel ***********/ + +// _optimizable_graph.setHuberKernel(); + + _flag_optimize = checkAbleToOptimize(); + + if(_flag_optimize == true){ + std::cout << "OPTIMIZE" << std::endl; + + if(_flag_use_robust_kernel){ + setAgeingHuberKernel(); + } + checkRobotPoseNotMoved("set age in huber kernel"); + testNoNanInPrior("set age in huber kernel"); + testInfoNonNul("set age in huber kernel"); + +// updatePriorEdgeCovariance(); + testNoNanInPrior("update prior edge cov"); + + //Avoid overshoot of the cov + for(size_t i = 0 ; i < iter ; ++i){ + _optimizable_graph.optimize(1); + checkRobotPoseNotMoved("optimized with huber"); + testNoNanInPrior("optimized with huber"); + testInfoNonNul("optimized with huber"); + //Update prior edge covariance +// updatePriorEdgeCovariance(); + testNoNanInPrior("update prior edge cov after opti huber"); + saveErrorStep(); + } + + /********** DCS kernel ***********/ + if(_flag_use_robust_kernel){ + setAgeingDCSKernel(); + } + testNoNanInPrior("set age in DCS kernel"); + + for(size_t i = 0 ; i < iter*2 ; ++i){ + _optimizable_graph.optimize(1); + checkRobotPoseNotMoved("optimized with dcs"); + testNoNanInPrior("optimized with dcs"); + testInfoNonNul("optimized with dcs"); + //Update prior edge covariance +// updatePriorEdgeCovariance(); + testNoNanInPrior("update prior edge cov after opti dcs"); + saveErrorStep(); + } + + + } + else{ + std::cout << "No Optimization :(" << std::endl; + } + + std::cout << "AFTER THE OPTIMIZATION CREATE" << std::endl; +// int count = countLinkToMake(); +// // int count2 = createNewLinks(); +// if(count != count2){ +// std::cout << "Weird different detection" << std::endl; +// throw std::runtime_error("ARF NOT GOOD COUNT"); +// } +// overCheckLinks(); + + removeBadLinks(); + std::cout << "AFTER THE OPTIMIZATION REMOVE" << std::endl; + overCheckLinks(); + + exportChi2s(); + checkRobotPoseNotMoved("after"); + +// cv::Mat d; +// createDescriptorNDT(d); + +} + +bool AASS::acg::AutoCompleteGraphFeature::sameOrientation(const AASS::acg::VertexLandmarkNDT& landmark, const AASS::acg::VertexSE2Prior& prior_corner) +{ + double landmark_angle = landmark.getAngleWidth(); + double landmark_direction = landmark.getDirectionGlobal(); + + std::cout << "Orientation calc" << std::endl; + auto angledirection = prior_corner.getAngleDirection(); + for(auto it = angledirection.begin() ; it != angledirection.end() ; ++it){ + + double angle_width = it->first; + double direction = it->second; + assert(angle_width >= 0.08); + std::cout << " Angles " << angle_width << " " << direction << " and " << landmark_angle << " " << landmark_direction << std::endl; + std::cout << direction << " <= " << landmark_direction + 0.785 << " && " << direction << " >= " << landmark_direction - 0.785 << " && " << angle_width << " <= " << landmark_angle + 0.785 << " && " << angle_width << " >= " << landmark_angle - 0.349 << std::endl; + + double landmark_direction_over = landmark_direction + 0.785; + if (landmark_direction_over < 0) landmark_direction_over += 2 * M_PI; + double landmark_direction_under = landmark_direction - 0.785; + if (landmark_direction_under < 0) landmark_direction_under += 2 * M_PI; + double landmark_angle_under = landmark_angle - 0.349; + if (landmark_angle_under < 0) landmark_angle_under += 2 * M_PI; + double landmark_angle_over = landmark_angle + 0.785; + if (landmark_angle_over >= 2 * M_PI) landmark_angle_over -= 2 * M_PI; + + if( direction <= landmark_direction_over && direction >= landmark_direction_under && + angle_width <= landmark_angle_over && angle_width >= landmark_angle_under + ){ +// if( direction <= landmark_direction + 0.785 && direction >= landmark_direction - 0.785 +// ){ + std::cout << "Good angle" << std::endl; +// int a; +// std::cin>>a; + return true; + } + } +// std::cout << "Not good " << std::endl; +// int a; +// std::cin>>a; + return false; +} + + +int AASS::acg::AutoCompleteGraphFeature::createNewLinks() +{ + int count = 0 ; +// std::vector < std::pair < AASS::acg::VertexLandmarkNDT*, AASS::acg::VertexSE2Prior*> > links; + + std::cout << "Number new landmarks " << _nodes_landmark.size() << std::endl; + std::cout << "Prior " << _nodes_prior.size() << std::endl; +// if(_nodes_prior.size() > 0){ + +// int a; +// std::cin >> a; + + //Update ALL links + auto it = _nodes_landmark.begin(); + for(it ; it != _nodes_landmark.end() ; it++){ +// std::cout << "Working on links " << std::endl; + Eigen::Vector2d pose_landmark = (*it)->estimate(); + auto it_prior = _nodes_prior.begin(); + for(it_prior ; it_prior != _nodes_prior.end() ; ++it_prior){ + + Eigen::Vector3d pose_tmp = (*it_prior)->estimate().toVector(); + Eigen::Vector2d pose_prior; pose_prior << pose_tmp(0), pose_tmp(1); + double norm_tmp = (pose_prior - pose_landmark).norm(); + + + + //Don't add the same link twice + if(linkAlreadyExist(*it, *it_prior) == false){ + +// std::cout << "new" << std::endl; + + //Update the link + if(norm_tmp <= _min_distance_for_link_in_meter){ + std::cout << "NORM " << norm_tmp << "min dist " << _min_distance_for_link_in_meter << std::endl; +// ptr_closest = *it_prior; +// norm = norm_tmp; + //Pushing the link +// std::cout << "Pushing " << *it << " and " << ptr_closest << std::endl; + + if( sameOrientation(**it, **it_prior) ){ +// links.push_back(std::pair(*it, *it_prior)); + ++count; + g2o::Vector2D vec; + vec << 0, 0; + addLinkBetweenMaps(vec, *it_prior, *it); + } + + } + } + else{ + + std::cout << "Already exist" << std::endl; + } + } + } + +return count; + +} \ No newline at end of file From 53917ad4036d894e99144e657f2f181d4e431b1e Mon Sep 17 00:00:00 2001 From: Malcolm Mielle Date: Tue, 26 Sep 2017 17:28:17 +0200 Subject: [PATCH 5/7] missing linked lib --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 35344271..f6888827 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -157,6 +157,7 @@ add_library(auto_complete_graph_lib src/ACG.cpp src/OptimizableAutoCompleteGraph.cpp src/PriorLoaderInterface.cpp + src/ACG_feature.cpp # src/VisuACG.cpp ) From f7e65b465e13b557d1fc3dd9342c03a6b1be2a5b Mon Sep 17 00:00:00 2001 From: Malcolm Mielle Date: Thu, 28 Sep 2017 14:55:30 +0200 Subject: [PATCH 6/7] added image example --- Images/result.png | Bin 0 -> 195507 bytes README.md | 2 ++ 2 files changed, 2 insertions(+) create mode 100644 Images/result.png diff --git a/Images/result.png b/Images/result.png new file mode 100644 index 0000000000000000000000000000000000000000..f2d1f33b5d25029fe9eebeadd6590f670b1ee51e GIT binary patch literal 195507 zcmb@uhd-BX|3CgF$x4Nc2uYMgw2+aRS&|U4S4LE1OER*OBqWJaWS5n_mC>?QR!LDI zS*d)VN7w!N{RO|reO-_HdKB;Xc^>C+yk5`sI>U939A3+?iGf0)tkqCg(W6kPYstTK zwD^-0@y03qAFY+vVHL^>`QP2DhjI85dN=ix=P49MR`M?u<<@OZ{NWmR4IR}rBlJ8> z`*u*N2b^Z3jx{Dum_!SlP zga4e2EDn^F_P*o)V5+}=+&Pe+F6jT?e=@mvB&ihF(u)7#cg!yXVSU_$CXKiiDr%&&2c5$(^wqCVv z-MYOl18glZe1{bkskox~C)WSk6hdxw@a}Z?+{zyN7Z%-*PHYz!56jBhF*-V0`(cKk zjp3M)(UovkVXMEtm)0|cycBk2xXgdWFzBcd`OPb(4fhVmTuV)jDRFsgRTs2+yQpa6 zm(GWU7gqvuCr3YgIQwm2pO?4yY5LPF^)$y0Zm0RTwq|?cm3j3=HnOm?N;vh128V`@ z{`}JUd7yY_PHyhmsX@8i1!EJFhTdL|@87@Ms0U?keYQ#)i?iM}@#jx>=eH$mPoF+b zZl0EjlfoRfDnl=veV6fY+)??uD&K``iHTPp9!(w1ulZZw`S7Tvt82{J56yM$?b^F? zo-_XY9IP{ABJ=n66)pRn`)Zkaq-q%$82a$TC(oP_Gbuf@IeE7w^}&mOWp|2+**$&w z^y_%)MLT9@X6@~4lGfJNJw>OF@5hDDe|#P%GIqU~KHW~24wr{VOgoc3xuTcFW|(iL zs-{NU-rmk1uUTmGoW*bD&%*GGS3z-ci0<~_kdW1CQJj}{9DksHV+|uCqm-1?-Me=w zo>PO{w&Fn_GEXMA+vvnry=~hzDZj(=nqHaF95+^{xE!nE3tYo|d@ZJKhJg@r}n1D)icm*WkuUvFS!7Y!^eEuFuAWQ2S) z`SfJAns|+)NA0x|#B9I4Ewyh5U2B~nZf<95Ybz=u5-~T?9hrNo;^q!Eh6nm09#tt> z`XU$Rzn<(Vbv5_cuA(ZXVr0Y_qO@LRSDKC+`N(5yMh$1D-n`LcD9$Wub-b^uM!gza~LSv;U#-#@SHRc^SgKNc3ad^-j#bWV$~?a!^44B zHy=zdDq<6f*Yua)?Gmx|zw?MIteiW4zP~koXHsKP z{ohKw-B5!a^|dG0M0D%c%T3MAj}Ll&-`&hv;Wk3ez1Ly=){h@QT8uV^ zJK#jd?`9xpZX%8Izw@n%V^e6=#Bl$?1FPmJuIZmYX%gC0?d*iGaI`oIH+PvlVl}GF zF&cA|y3MfR_vhDJ1qB7~W@gf{3Lgo^+15LLd;=ffIzB$WM>Ij1R7FaHhA zHz}TyU9aLzbPmzZ2jlgoYaM{ zoL;h|0tjr~T4>$EjD@UkZDn}y;K7MT@$r?+=l1(fzoEHw>C)%E!mR--e>~sST;xkj zOLMz$LCw!kwzaj@YeZ{ST)i5qFVa+C*}%^dZsFiSMR7 zeuIkjCE0&lkl4EgI&q%jd^mq~Ul?Pfyq42Max?%&?}DRh~ioca)Qd$)b#IYZA9+lI2~u zfB*j7`}VDlX<22>6c7+l@Z^bdB>S$~al;g2bJazI%F3n z$F;S!@9J(ZQWD!PP5bXu)6BdXEj?#Eie2_Z!n%3)`Sa&{N?c5O3at;buU}t#*s&u@qWSOQhjl#} zS{(b&f6~60lA=SMNcshOS5mD_R3TQeaC+M9)9266a07|D+ih6FgXg}#Pe!dRG^_F{ z#7@`zj$3K3YW9Q~>!|7}xB|BhoWX-2fpPH-x%)jj&4Hvo+N@=37l9TN2 z`tQV&AGj^!!Jw+DY7up*VdSpw!go%E09jnBg^NoxK0|p=`@BcI!q)Mn zS61?@TEk2e){u2QVo~SA*w|`wbMxC$XQ_F4d8cP)>Ym35qeK|c(9({ghV=Rv46q%( zMiC?3!i^W(Xv1&<$7Q=EsYH)myKC8FucFMr)*V{iZAS?t!&Z%f6? zOlAJ2@~i(_-e|K$>OgIwhNtJp3(mZkxh?C>qM5-GCGqoXKkMJWf7LZK6tfL-cb|SE zxcBs%`w@$|>jw4FoMY94Q6uZ#z2iXxT_3I@<^FkndU|^8`0VR!L-ArdA@SXc|Lu-V zJEWzh`-)Dp?mzP`li7Q>galPgO9M7qSiqlOmVE`5_>)T+8QUh}?7H5qUn9G&b9!Nc zfEj=lT>}H!!-o&=ZZ5Fv*mR}I%FD;caTl%n|F+9QoTbk8Wj3YceeEY6lA(4??4;aC8&mEYqEM#YXBA3uKl zD(}?6?eVRp)u&_r+tXeh^@be6M{ZkS723PHZg6pP?@7~r7Ob>okA#FJ8m~oDQ&Ub^ zS>g`1h~As;zj?^nqirpZC72s6&wuNG_w;;{UY1P^pMqU%Y^-ztV_Q)Lh13_cLYww| zq$0ayQ_*7X?;7EwclZSasJRcEA&(zb3)R5F)^>G>64k+j2i+%o)~czg`5cJuZYiMB zIa;8*y%GIzWMqVjIqaUixRF@Gz5DlRMB*bht$Cf9R>nv6$+0VBpWqWMz6}@k)7 z?LoPsA`rzR&4PP*_VVRnT;Ry3PxC!jrLx=X4MgIleCI_=T!*gaovN^Eys}}U)?NtQspvxH3bF9?dRuXIi^op04LPEy``~P2TEKR#S$2kv}watsD*`vr@bmg z?hJXV3L0Ep^9i`9u#hUOp>F0w%gFe67|^8NR?;IeowEu9v64a%#4}h z=II%hoXoAMsrf2Rc?}bnBn@iT+z+oO<&Ev_OjzAA?^&UMKXZlzl-JeOId0G%r}|gL z6e}-Nmj!io>Cb;F9g_6)^z?XkIVp+jNkM_d*27nAun%l-SaUKnuk46#rDdI;7O2=B zuQ|UkbnyvL-{ZQ=Yo0ju<{jhwAGWCw`}uvS=B3?>+s|`yauUPC=?M~QXt=z~q$JA! z@6x#QL|4{V{MK5t#R-<$D2WHU+xt-JjS|F8_1UNTH}lGR9TNDje2<=D_eS5#v2M9K z5q(A}?OL&O|8;_+Sy`m-H>+a=V)? zEG?;6Sy{&xpVdS!y_Z;>~*MA5(s-PYh3JjW7IH#?vtAo_EcR9-^HjK zH`tutmv02}JG}7yJ<4P>?SI_MizCE!EPwLbw{IigzD0vV91=@t7#P@8U0n^N5qgOK z70cy~dkvOnykyaHEq*V~=x%4b5)q+v;X=t^)9U{^j*74&WEHuXqU-i~Z zH5=vYZoh^*!-KJCxw@HjgDic513>jGot?GkjK3`Hb8$F*I{ezT_0Mc1f6w)rf9}cU z21D%9P~6TI#80I?n!tZWO{mCWG=JzrrBYgL*71i0j@=>z0AkalLXfKd;7AGs=pZK- zSL|Z08qIkr9wQTzd!Q^=Vq#iu?Q^nlc8*#nzZm$7`gOswqB1vU46mH=wyWVlE4FU# z?!hrJ>*ybN9-@qY{KzjPM4NoTwKdeDH!w>6!NhE^qfwFZs16 zA6R$u=FJHoer^`Qz)3)o9hAVkclpaIDvp0+0YqwSZWh?TpB?82f1S0sIuH$fIKezX zG2g6;oL8xX2S4DRIHk`CzI*>3Wtr4imYU-Abp{3obZgg!Xl5vxn(_dN&y0leId-q< zzs^r(8bi;(P!C?3d4WDCvye_`;^Crg)W}PPmBxsTJ4vm^Va7(Pt*xb?Fni5^<&u?^ zeO2M<%E`%jZ810G-=-}tR(*L#?(C;_F29BMo)jEChik8-2@F-KVyTXAnu0bk{qZ?# zk#j!_$anK?>GQRm4d`hWHa0YX4WtmEq@&dzPqnzKrOqnO*60QDDPjMD2RM85^Xq#k zb=w-&uVoI{`nkPG59)()ovJ}*jR#>TsR6&}(GQP5(5}0yc$skNT$9pta8m%>X8i6k zQ`0C$4zasHww${yC|plMXYW7w77b+j^t?SGc%aWAC^B|0@950b{vU`+k@fyTPIV{> znO%D#72r5%N>Iy(Ez;6lAbuz)s@P;?;{^s%1h;Lod|&PXurNJ0ry8QRwa(!D250R1 z;b99D>#bY1P@O${mX3)@P<{wrL{Ha-o35Z zK9*KiLG|@YM7Ka;2F76gH8&Zi9LBswQc_QgrZd=_@lx$rItm&=U=a}!({EjCVvh~h z1vGJz&5mcQCSbJce>Yh^9p5%4<^4mj%v8+J-~Tn19oxqOGOBFLuP!>K)K z&l)_5Aib<$%?!QNBE|i=L;hM>`e16SlJ~oiT@O*?Rk4$yB-=m1Y1Ach2yB^XM}0LH z6;KMJ?#TJp_w{j_lsMO+4h(<)&K$3~I#yjjLl%e`Jt{pXhY84l)|v^DOPIEha@);a zb)1(U$ZxHiKX>ECjp6B$hQ25E>q42hf-DO+r^pE|-d}WQAr~UUZ8=|d zY{W)TaWvekOS9wFxCAgQR6(6k><2GyR(A~zdVs_A8#Y|RH{CO@37}(UZpMGsaVit6 zYFSSMRGy9}Ez|bVO=>+I4Ov4Jmet^H_{4^u9(L~i&WEr(544l00T&+yZh|QGI_tPF z7X2mo7w!rEbpsSW;ZvWvD9FDBkKiIw%-Hco3$iPK``V zXsT_cB05xMG<`W}IaW_aMJ0IPpvTe=ThUYHkUkgy5IAMMb`y+eWkoHPkiEl4I=;>M zb^2<;ECHmT5n!ci0jt4oLZBxJX(v+9K3SZ^>BAZn@u*%^dY?z#Cl&fK?b>=$m9JlC zA&r-vogGkmi*;2~!2QTI>v%1eevI{1c#31|-POyw!zeG$XH{sl^O&~vcgBAp=gI+@ z)8^&w^jM2p^NW90XX!t>bGO3%3wb&tpf}gl1=mM54bLw9qS}{WPX)u4zbSe$=;Gg{H8`xsjGL5|l{vY&Cq-){=2x?j0@=u&RFo>` z8(OpSmm4)(D&V(NL}X;$hnZJk8o;&CrIh*CTL8B@&SV^2oVfjJ(T|RX`bK>G2zH!9 z=YzG-%V+_pQJx?)qQYJmdALc$w|DK@wFH);fDD5VkmC*zNYDucgtcfioCnU_Hc08L zADx@O2Z8kibV2m0z=Q-2PHV4UKX=T3dmF|Vut)`o1OyM;%;C*_dR}?I%p zD9?WC;PyAi)+O6wUZVnKq~`YzM#z(aQBh2|!Zd7BP6;a-`K6DnxD}MahUR9qoh3h2 z>q{S7IN{oxuWpX4`TL6zO`a%hSn3TMHc&yvX}`6PajI&8m%b!{tq$LZAJ{G?){KiH z@~j^qAg-TB#$$rU-rioak9$HH3SgP%6z_$p!D#4h!wu^cR6qn`Q&OSqjL8hw{PEm);Hy&Y#CKpP_Uae z(B*x3{Oc|6X%t^A&Oki61htMs%+#XufsQpwb$erDa8h#e9(2l*3*U_A7iX-2M~S4z z5E2Bu+p1b{E8q+$xG%bAg~ud&WOTIc0oOqrpj9i>Kx>AObc3-2^FE^D;`WdkY#|~! zzbiZY6}wbhD6S9{qu|*y^$X)KHb4I2^w?iDS^oSdrrG&h;@U&1B19bd2T?5_PRARXyv(_Di3+-c+lS`0 zUk9tWK?z6!I5Sio4W)$WzN=`N?&?49)|GC)^>X|kI?3XvWLJU&u!Xm?G1%DJjzH=J z@5q0{{_H{iV3^2tBNbKEEiy8jo%|J4AQ)Uw&x*+OU)Dr#z@z~vy!s;Jx&4zKv5 zI3=jTAv-JTa!Z18f5;Ia0I~)hO}|BDu*#Q%L)F`Fwh7i&OIjxNRx+Lp!HmkJ}F zKVQNAtZismMdWP|i3t;Eh|}})v=qPJGcD@s>biW^5B0K&ju@TR))lbd+ZC&jcLBC@=b^`STkCR zo(E)Ge`Ui~v?D6;;0!(bVeg(s)QfwzZ8sAYF3J;206^9PMhc|B+&85*l3b*H@$tn# z{JM8><*yVrYjX@=%+H@c)tt`%_@~R{%UT+`{rY*DI1Eyr-+45(w4ez|IQQ+=PL(Gz zvrLSo&nYt{XffyyMkh~h*|lr!_{-E5plT?DOc0eE=vV(RFc1&gH(8+?$)0$?l^1pM zn4Vq`h%Ld4cx*RN>^oM+O(Gr>{q4Y!na3_i`C(U*P!d+d_#4rgBDQ$!>O;Y z&*I0&=MHa6a$oogJmRQ>sA^|trw$c*?#nCx|3kuvul%~C8``*4)7Kqj7F28%yoR*drO^!5sFE7$mBs{;HF8=zJ4ng^U zGQb1Y1J+EXu0ze>4KvGAHQB5tQqt0vQ0O_O-1vc+CY&#u=rnDbmSwZT@$mY+C{g0v z9|X-c$E1{*`Vs{cMBkNNK-{f^aIA+9h3CKauR;lGzaz)Jw6sK&m-~7CzRo2cYdiYG?!E;6865Jko*oM`pF9&dCJLA4q_jrnm(nad6VjH* z?nOaR7G-aE_Kc1pgc?AQX!aoLIqbDICVv>8y?bZ+b*P394?@Y<_?Aph>8R|G^!ZQx zfPuiRcm`c2;^M}1#>U20i_;^dHe7|V!46@=<4bQg4d2hT|g0QEIQp; z^w=s^*H;>-8zo^2dnCazL|=tPN!sU++1YN1`jV28E>HKGP^dRKW>uR2%~T=Q;dk0Q zI<_RV)s49Eucv#Jb8-(hYnRlX^t_O}Dgs2pIQ#vbwBKB};o?Mg{_v+yJ=@>P(+?Zt zhaJ1qvKjS+0cSacrlEx2fB0}Kgy;&-DK%6f)I>l^a*E-=nA<;Vc)PwPUd{r$33ah? zZn8HPdIJ0>9(g}b$iAHW9B;_51!cxY0~G0k$w9uZfBu{vN(?z`J$a`Xfx+4nC6phI zKbF`U_k2A!cjQ{`{lmYPX1DLyK}8`ux-0V-*nCJz%4UMl#1c$CTwCLh<5KqY=}4q_ zbuBq;sA9tq?B4w7I>4?@>7@oQ#ZHZ20*SrHQiG>{IEGghCkc!xcy!bXO2o*A7=`8= zJB|;3`I0qzBdl~wz+AWmbQJAdd+7o9eih$j{=Y0hU#0h+H=Uh@{>vALct%A<+;{_blo+2YXvD-w_;p}rHXQq;Vf zXC1HXA)@WCT?@iSjq?K$%nCO<(Glv=oq(0b8M_R|Ex^xDK`%a}ug_*&Zs^w(%weV+QKehzIMsbrPM+7d_u zSwv+zyEtu$1i_&UJuHtkbagQ4M%=8fvGJo>_fW%cS}>i<&W$m^7^k?px-xB+VS`fA zSM0=54$KdsvF6yWzj&;L{F&k~o3`e4*!P6R|9V?JWms&f%=6B}_T8gg9rNN-*VYH@ z`7?>bw+Kma!^VvvsMv~Wy0x%B_t>@99_I6>iBpI{HFVeq$P9=)IsOI6%a)rPRXpgxSZr z$Bqf-cy4g^`Zg^Jg_IQZjDTNXgmcVmcwzXX?h$Q(mYFAW?hbY{c-LBT2=zr)Q($!n z2ny1meRMr;fcnHAtL{GN84w_kRvn6-nVD)L$WqtY$!gsk1zwdpI6he7!u{sW8~osI zyLL_}rvP+hCqf-vMM2lwiXHx;C8jrGrbn0s0HgpnM3|(40w0BF1dGedq?H=a#iKLe zL{NM2D$PO%GuT-$^}ZquN06H0=jR7pHw29o0x<@>2w~)y@MkwMF}Z+Vo>Bsr&RS7Xv3nqW z)E*^TrVUNqmXfFSa(l~i)}#`ZOE#DxczFr;`wQ5Bg5(n-vzN`Ip6(HN=od6 zgoN6AdlNRx`z@yU=Kbn=080OinBtS3j| z`7C_zz$VD-h@%8Np)OPEVxXaB=izCuudg>!SEmCfG`1=nmBAwIhsagp@LB-w|J`jY z_aI6IV8aBKDDqB0H*0w$tW=7r`#L*e8vKHU+TDxTQFX+jQ%}!r zGkJP0<7QwNn`}8v!GjbLl~;(T^+PV{gMC>%IQ9K|-fqpIB0WD)RzLc2?;$Knj9O;2-qbrU){=Y zIOFT>{q$FoAj@;DwW0XVPfE{+hEjK#mR-|H-mlYU2EOJvV{+_E{Q1+5z26FjG*K_h@8N1I+YNr`p*{BwuOs@v z)2Gr9#yBgyW(2~A4GX@Y{`EnXH;NO|NmLiK0upm}V~lKlsb_55iUoZ^T)&%%iO-JQ zmZ~E;iJP}?x5IpD6c7+FLilDGD}VCPA<8mZHFik0K!Ewe9|W3iCM7+;DR!!rxOmuH zSODjl(I(<04IHGm_(R>-))x7`=3yUFukA4Y@;!8{tgJSsaq;k&s(w6u z^Tf%$63s^L?nO6spMsvoJE7kdHKvFa>Ybbp4GAfPP;H>6SD$|G-bpnzS{y|b@kguK zQeWCbTXKqjjHCKOMIhF|JASp>*trW|`;KMY#_wS7<%n5B67yN@*7OoM?$MRZ<%KCH z`dlcoB4gT#yVHza@7o>BaoAbTPV>aB<4whGnR6en3^r-&(71&p7bBT>^UgX>zg+ z{k0kO8!;~{crtb=G9FfF?b>1qPr&J)0DXSxTJ5StF}yMiv8E8Dhol04If>c?_}Mk6 zL7C*JEna#(7T?VV6Dt*-hnBtltDiSD1zD=LFyBglaIWPITS!znzc|4IkwoCDu;_bUF(`7LvBO?t$b=e`)E0hn+NZ2!0^m`Mtb_! zKD&g44_9$+h-^9`bXW(TME96}my@Ms+CT|9tWSgX-qe%F-K(_^=86XP=9}lw?jfJ< zky2gqaL1yxmDSGy{obHQL12M%=ik14Yq&Fzw1HB8dmEd~nha>a#=WtWynYoF+NQtA zx=F(4vpaL<1zA0Y5a*B2Vo8y6M&oowzi)r}GG>=qW#S*yKrB~H+?I9X)(NN(>>D=J z0n(D~-Q3)qbE@KkGi*5HLFrpAPSpj3!Oi~ssqf2GvpC9lGc|SPMakAv{``CP#Qi~6 zcgE8cm6JII`MdJ6-pBNm8$B!%C$#r$_eH;<&LXfvW&;0!AbZnc^*TzfUi8HiQc9VP&s&R(NCU; z%)?73Gd3nqxNq3B>Cr+lQ2nEe`F;FGb$|aXLl5t=bvVP6-CiHUh`)~jbk9DpEkZ@0 z*d;@62dc)gF@MPUMkUT%`&|YI?01Sc zTwjs_u+ zVf{K?^~#kiwT3q#NOQP89w;_5CR28k`Y4TFa)0jl{*ZwDKz|n$C#aeJJ5&^%x zJdE9#!;Wv$5*T0cikq``aJXXEaSNb)6EN2<=he+Q2P!4$3 ziGI^5VO}QA-IQ#@{JbAr0F);l#`KiFHDv_@nwu&tEc6NSgi=2@7^5!u#^i5PBu976 z^78T|kC8|#m%N`8dD_SQ4Erv?x}WIe7r|~V{gtGwq-2(rB6IMdlU$75=F_|T}5H#Cs&EJwsm29c|Donz6R@d-Q>G1m<$@dML<9)rM#?u@-3WBqQJqEqr3tf8|y?#9iSv=E9uMH%bU9t=5s?H>mAltfde07j{c7r3BOTi|Mtr9usq$-|nlghRQLUoA3qlV+ z$=JUpt;Cz9Had_YMqv7P_5#C{v(AtStHk{sj%Hn7=DaWLQ!o*VJ54{!0So7k&%vv_ zGb@rw1MrGBu(Q*`>;lTpZeWw#vu6W0HzNfeX&&MLJ1mz4kd+Jr$r!1NI3@5(fm~vWQA^d0PU>OvTuE6M-M{$=%4ycJGT1 z75RNTCFOO^#fz}_NASU3KR(ivSUch_wU7c+{eIA+UF<8^6m{U1ODt0BpsavU^<=^T zDi+S=C{~kbkKy6Z56(J!dwV~7_UsViWekjr(6jiV$xZg`0=A`v=$$CzA%ebdkRR8e ze|we}7YTw4S(=0Z9eQ%OAO-F|_fZ{jjJ=;PXi_ikqKho$GGyJf$@pH`n+dCfbNz>o zzjBPQ^v_oJuh)3Oqo7bD5-w(TLi@x4i{1=M7DO^@I0&?qzH*OjV~XqB5}oWj69?(( z=|6X(aMY`SbNBaifw;SQc!UtOK~C=V10C*M8m?m1*(Z+1EzvrQlFicqdDdu)>PL>K zVOE3F8hlT&Cg9I{78Wo?N}*9sr&jm1)vmUXrAQ79^52JtsR3lL0g}qaVWLkK6db~@ zs>Sf;vO9iUowtJ-OIh3DwS5+c!1EYQATXE%YXUBkZq`O_V; zu!q-;>cUGjyJwEv{jx9n+5EiBS$B8+mAs=r^v!(t{k>?dnPuFmv5ZdHS9W&m{P*{f(9m;Lg{+yreE9;E@=|1Eq*;usHLDkpARRsZ zKl*IhKnvUZ(c53xO~{JQAMqBMyhpcx-#*n;d4DW+P-f$8$#ose)Nbr!@^@xi>XPDA%mqo=z<`40z2w0u!8G0l@ zk1e-2^8v1(*T~;(EVU|CYI~aZi-~;?p_W4VMfQay{Jw$NenUe;_;>^>7{8CWMs;dc zbakB2-Ve^%2cwma-*|BU{vl#Tv@MHVkVQ;|G7L+`amuU7B6rDofr%V$m2CP77QVhOG}@u+M?epnE7Yt|Bw{EAdji49Ny;cu(v|@SnHJua%HhLA&4u}jJZj_c*@ z+hFs;Rwr8*A}SHR!RG2ZI=s4Gn%S!URveIAMy|lB0(?5KK@+$c*Us+P9?&Uwq>P zr?zdGpnVNJP)R5bVWyMzqEo0+-75-sO3b{nnE^WIFX@@D;n6volaP>LHp56kck%yn z4!S~aZyrO4QkBLv1m&a^?@3%eh;$bW_NzFHmP6J4$lr#+X3^HsNz)f0U<~|(1uGJg zoNN-GzhC2-oWkY|Pz$0A%D8`~P>9t90dY5U8~Dw)g{q7r#EN^P|D|{VR-+KPO2?@u zNqxdQi+lgL?Bd6PBVsyiUB5qby-0o@ggJB-Vact+!fW{ae-fX+dg&84&^XDk$o5yj}MF-ffy2y&o@^970Lea zIeG8tAQ;L-0tB#-S?;XpdI+EQp9h6#D;F0RT<1ktrZa#S>)>TN6@0s<#P6tx5i#UK zOg=1}Jb7{iA3kLAbo@lN0VzpPJdycUMExVBes05F=*%SG1N7ZJMbF5XeT**nli^N? z(MDx%TdKkSQPD`woK;9W5cwQ183?ikXfzyoyT_s85|j`Bo3t`G-NgJRV?loM=Kj~~ z(UrSKr33{(hKzUiJbE&{L`H>h%J2TYT~xFe^7u)YhZy?!$85)8tHhddgHh2EFubm^ zwqnCy-9pY+Oy^HNwxNebe|J7eUvO*ELC-Vs(_wi2Rih_hIOAX$LCb?jCTMmgQgBE5xn6>~E)uOA;CE7`#k-Un}Ha_{}mr!+!LpY9?PNhm{4K;k8c`UxQi z3eS_mLQAW{#44nVLAS5CSby`9{`~bakXbWn>Q0>k0?qm z14WkR0ZZE|;EC--t_a%#BQySZ^4j*B#ytzy>Q}FTLt~8RW+51fb~&?uNW6UIwJdkl!L20(n07z#ll6S+Rq?zl1!TM zPVG}?_2DY3YikpV-ffG{4g!;YPCmZ7GQ z@Fw}fLEDZJE|^>Q@83^owd-52dim1|2_>O?4g-Ly!0JaGtK}ph0GOIYWkpR&nBdOr zfKNW>^U*;+$L`$6bI8rDBRmQ-Q7DkxMMZ=4MO0yl^Lde#EmHn>+B=B~gU8sWsuT&om{BX$dWSim9x#4NkrqWg_G6im2>-+rrHabSe1}OjC+~H=$ zmetWGV)ESU^3SD+A$#@NV=Kr9`ElWy;?Cr@e1 z=AZxVwfVyfED$NRJksZA@Dm{I&>^YA8j!22higyb=|OE{Z`4X<3jC2JCZ1q>yEZJ( zVU#IONgFycJz(E^-Nnh(x|#Eiynh6CB}twmSD^;YP6CbD!*Rs0urROsC+stlBzRlu z+5!`X%v@nq4Z#b)nI;af-L4((+@k_|o$|N}5)39$$zC%NO>88UQk0C51v|sU!A509N?|QWJs6cGx zjaQwXd>bEbQWsp6cJJ>0WdW}HT%6CBr=g~T-#F2=$H~@qu6}Le+GB3|y=JzOT+pX4 zq3VA?CVZkp30SoO@PLGuF+PDzN9g05-IfY3pFOLEW>5062b~g2n=to?x>9~X0v0r$5B|a5>GM$uucsRfe{yli-Ndn7 zNeO%xVIC4;94K{N2MM~!b%+-+#IlPk@+7JO7AyeHMH*`6v3tXxKO2ql2e4S@U%h;J z6>?ga5ll0!3D^uRjbs5(*4)3Jyu0`LK64w;f|w`?S>JgkEJ72mNy4#fd+u&t{}TV# zRx;w^>keP#slzHGd6miT0eP&s=I@+1gt;T*eZ(|2M8Fz?AXH-Ih;1&Rb7KehnHfl%3rj(sG|-TkN0}Rm~<|( zAJ~6Ei z${k_H%-hCgLeTjH5Jy52I)n#~EX1w-E)f{A&`y!rh*_*R{hpg91s;sP-3C3GZR18% zqX3eoC$qb>2adkJqEX3?rcP$YkKI$-A|}QxnUteBzjyfQ!g4%?)?m7{v&?Sr1o7zx1qXA82{NLI}Z*R3K|YohEk(on+)gdMxMZ{6L9L;UM( zQX=+ZM4hOl5IRHATA&xIu$Ay96xZX=lrt`z z!P_S=0K@}Lp&p9s>qjScl6hH-R`?GbRdyT_3=HoLMFb4U2PZiY4Q1=LZK^5!N&>O9 zZEcKrB(Eoo)_PMM-fXkNE=7b1DUYI{0y$3p|Oz$_aq}{Em&!`4&)5-Q7ythZdeTj@U20rNWKb# zl`$xq4R79DXF8#Uz~c;t!V!N6ln4cb!FUOD&~!}gpz7ybm@(RteiXeLP4ce)@;pf@ zk}*hQV+LFZ*@Yx|f|pMinC_fQ8OPv6Ek+yj)%}UH%>>cu9^A$^>as02C_<^DkucS{;{HT$w*ex6jJbGY5`d z3yP5XKqH;}>6-Pej1F6mif$LN3fl{9Z}zSo-_b#}HthCleU(GU4yjQkjgRoW=&w;& z^a%)ZFmSy4a(wQ`I_b{YoZ|VxRQqo)&B%KU&dyDo!0gM+&!0As>SbpdS&7o=KhoK)(08q+Ksiw>l+&0d+mS$Z2|b`hGyQY z4GnuuT35-pT0i`9%f-e<#lnIgDXL+Gm8Esv-QCcdIx)+HfYOrgw{z;zy9M7RP|X?A zsyR)j2Gp>d(#Oy)ttOEZG75k)*?`nEE(JR#JUV(CpfqM`5C)-VX0{ut4?!dRR1)TK zfAQ(ctKMGWy?bw9Ez+{HwIH`*)7+Nxy@~d>@4C0fsnNeY$gPvWl56Emb4S0KySqEO z%n1CVz4k9!TQxC8&@q``^8%XhSvNPLAodLm=$V_xK*Z6yDLMlG_93cZM^AG=SId#O zRt;!uNg z?nGWpq~muqj{Xx=UL0~Y1UNA9j5)RI$PVoGTXYM$d>M+W-)EE95;e$I7LJaZCr)fc zmKR1wG>4fN6)+g+O$$UpF1+Xfh$kUxjsvi&5jlj+>};Yi4?K1N(d~82X=`mIlQCfG zKfk?AAoHkQy}jqL&E*$|SCPC>k;4Yk!J3;N^q=#1bM<-de3^IkqeqVf4ziiG>Fcj~t&e_9n*tL00Zs?)017daFg6{shzJTjZqK{JL-ss%^i=7{AzetaFE9drecO)b~pxW4}VU7}Nv zAdrJ8`IJ-SP|A#HKr0K2LvZrQc5 zWzlTfw3nbKv~7`{J5S=x2cZ39DV~EPOXI1B#S*lxhxxL-MJ0gOhY3l@?3OQXOXJ`o zRs37`>lyX`tt#tM^pz|8=<5(tCnhIx|F#%5>+0?%bBkz{N6;9rwTj#4fpT*p z35mBrK+vKzt4wLw6I}=R06o;hG3Yh(R@awA}fo% zO&F)zy%C%v_o=}Y94W0_BNGYwp5ESvP?uz(nnLiufdL|LG>|wKLFGRkYo6V@wTaN! zbLS*6T9w)D2++1T-LS5(sOaN!;Zz%VFrUAC(J1zxk^uN6g%Z)0S2!CLz@}JD+6JJ>^~xyI`~KGQGWh7ZVBUWonYaEezQ7g z=o&|kG{1eD49+(MM&?_B;xyf3W*kggE5 z>847>%t1Y&?6J7viuRM^*6FEi&3BnG}V4(UPyya@e~G2Ra;ET}mp^(A@uo zZ=a^2VFEVEbugte7as%W@aWCn+I^u zJ25n*oJ1ub@VkudDa)Bis=i%WIg|~VDv#KRo(C^~b$yNgDdW{eS z&K!8jD)KHf7z)O6(`#A!-q5|}i+#83-GSGhAns~qZH)naWTk^qEy*ksXbmzICX%{u zmgS8wO1cLv2`A$uL}XAkYlyx7MlzO`G-%2)hMOr%5O~SI8PDSR73!2(dg1=99^A%ljaWSS?%8xnYogBf~4_eK!cU3V3i^;*y zo1atdb-xf96Y~(?CcE@8j=Vww8zMJ11Nujjb|{8l@l~Z=3-QlwFd8C(q&b2eD9g%O z`soJQvCnOy*?lzj49I9)#!H3j>Mo%k#3d%ek(YvRi*Ho%4XWO@Sn_o7MSHsqY65Wg zb?Bpa{O9{?a%Y{td*XTGdyj(mTI2dj?=dqwf?r1r!EbRS4B&xXORG)o#2UdL%fpa4 zq08B$7K<4;UP0C~H0U*1LG;SeELFG~;^6SQ^mPO1ES*LyED z8T}_uMLIetPaeCx>V0E7fJh)YN~tfE3AFE5YxD}ri8pa-CuKxR12YRod@a&m@;i|aWO zUF|?RUgIgAcpJ*;;=kV8nd>xGDb>HXfDRQ+>*V6H3xMT*b+wt~)!>8ad3nqb(UFlQ zPAWbQksyHL7f=Ukk=QMSl7P7>C#T5@nX~{TVE4NYg2z~rNMEAF+v+mw($Kf4S9_Wu^G?( z`7D>i8bd>`BW#5cqH1^rYPR8s&UBD?`_BAIfu^`%6LyzqHS#j6MZAc~VW?UT;OPMZ zHQ-Tk2&h3&F{r>x2#$gPOi3MhU#T;Qp?}O>k~ew{4&Fhhz!hFX${)?K`vQwoN606> z6D)q`dHQj>P>~&-oWi4`8sEQ9fpO=UA+}P)M&>AyKf8=4x`BfuOf%z6^#gu*8F`SU(Q$U_2E5+wfO#Ss&&{dhAW;uZ+)c*AHqww*1S`I6?@p>w*& zjuDrSbhby27>*u&X_sMw9^#;Q|C1eFY+*(jxCm4-3K4oC<6}&4&*q&N`eKI`&W?n| zdJNgIK+aI2+d>o$BKDp|9YN(0#ZLWR?%WmK8?Tv>`REY~_C5<}BP;g1z^+|7z`fy^ z#8@_t(5$~4o$>3J&sjVd0@4Z*Ha~{eSPfsb}QI10#Z^&zX6(*GW7QOe(Pv*#yfV59@~U-%KMdhfwHQ&xa1OM2SH;4 zNaF^uWe87t2zBiLWwzs!$qU&`y{txP=uLpyLJ%DJFMNNu14@r7=1tJ7v+&D~@$zxT zTeQ4BN=l-hd;r|&y>qU5O9)|&^ZMEDi=SWL`kMSV7jHX>R=bQTGC=wkJV3DaC^Qy~ z8$Uxn0X>8$9}rmnW(;-r_8tc6LAQhR6oEYdtGkLQ7PHOVuK$mwGY{)=>-xB3NF*gg z%F#eFW-KA05HdsvC1XfbW)VVZKte(YsgPtYl8Pvjp-fRJmCQ*(()50o^FHq%&wE{m z^!wfS-fOS*ownHGNsZVV9Uc8P+-4_T5`c=R9fZU*S7d#lW4|8(FIc_W2&wTRst_Ah9KWc9 z`tngK*!DxlMEy@0bF$(sIs_z7%4ew^?LORU@9!aaafpMZIrI8 zmu2bJ%I^`NwdNSzdWq<4$28U5GrOJ$&w04PgsxI@P$6B$)DAAPuF$XZ!T!#g9P}SP zf3Ev@J$$^!WumF*&p1hmoV$~ev76l;xNo2ER~m+n6T>XktjEQkdznqbM^eqNc0kpg z>6$o3E)wc_eND;zevbz~{nDVy^IFdc>oE{axLU;XxXpYEgdFu_A!={{d@PrhM1949 zX-E(Vb`GjC!`AE5gKZ~InL2ejnnucj1ymi43fiybWrZW@6FxkTQU_{&_Tok1moK?z z!_Bvsdu-~7C>gfYl!Kb2o)oIx;;eJ+fpq~xlq41sq;uYqB|EGmm-cBqxU`LR=K)Ou z^q~9KD*Z!<*wrzXmV0-Wf9P2co!=g~XP^`fOaTN!9Xx!PiEISHSXP6}8bY2UsrrWq zO^de`F7cC$HWIzqnnVsfSeMv2RH^ZxxVV@N*d&gIhvGYwsM+eT|MevewR8YTwe;n= zxkqRwsj0P@pRKzE(IH+UMiW?R9CI=hlvwr{cfhF7%XNgwW@chPu(X=6>)$Y_OJ|d9 zf92%qbLZYs8}8h_i_Ci~hcPmVOzDO{cGC^9gd$ku@&GW@aWMA zVE@3ciy+fBR2Cm#AI?K{#?NDCyn%TelKuG9*H>FPsA;|0G7D8>K!8=)m>WD||8P}n z{ld(HUskSIAuSu&vGjvz05pjEVCM3%jtpnoVrCMZYIJmoY1;JH8`?X?9O74(V~{*C zv5On26|_joEb4lYhR84S&RptleZ=VZG(|JiaLi`&=-~h$IOF9n0_wAgwt;l!eeb`8vO{!M&z zQ{9hSv}?!RMUpaL^(QgEG69J3Uc9Tc27F_bhKEf{HuRb|9Q2V-hB9zG-vJ_Iz@R~w zuucj|-qLEY8TkkuL&94fi0=5vMOCqJ)i4CdoR~_b96&)nb25^k844yGGlq9b&jKY9BQSx!`xYHtr$9OY zK$65W@jd4=6+8$rQ6~-#08#IIPW|`E%-}Q?52!!*ydCg!BhXZB*;4e+cUZN-xZ{|6 z0UaoXcja&O?|%{=n3lw5^+K}_H`TNj=k7Mo&DAL)JWt=yaEjCJvfWm{=sT$8lkM!r zQV<2;B29#8MC#l6A0KYP2J!3e-K$ZNm)A}PP<*ujUKmROqLj$XWY3|>@{SI{lan>%-T{+Msnk{G=k06VL` zyljD^RjN2)AM_0=Jk+X9G|Mx4vL1X`Z(mAEP&X}jadrllWKh;$V=Z|_g6 z0O|!k?mPzvFL2HN>oPR8o^(>a;5DlG_{MKv8{XT!>VS$m3xTzCWT?kcs`KR8v#o%j z25$UgSXWz-+q5Mu7&p z4Yo79rDognB8Tui9+%9#vcb-r=~j;;3(WZ);oWno0)%AwL*C4&`cpH4Avb?RxiZ^W zLiqrY;3V&GhDJt3gjAmjk)tzj>ATv(|Npv7lwK6NIHbqjK6B9{>d2lN;b5hkn zx>>fv`NTinST`Wr;?%-DrM*i@z@!ZG(chH2-g$UUcblU@gBi&sW6~aOdg^G%iE)YK zZ|O==Er^Kf=g*%M$|vG7e0=mFBKxP=aV(V$se2_i#_dK8JxNQ0IxlF7ObkZP$l*Ls>eGT$( ztwsB+&1qi=%svAnAJ8|F9??GYT5y>Uzg!*;rU_ch>`;c#btOw4!Dl+enjEbZ1b|Z* zx^x75yrBl5YAL8N8F(5G^8RY5o@=1>Yd}Ki_yEEKS#B*lTBx>d>uVl5%*rZ&WxKri zero{NZBbF(QR9q%oGQob=6@QWQ17O;7$$3vlU@HMy*f6LtF6B+zY1Gb_EQ z@O&3neY7rPDT+)ha>g*FUHx#&46<|c38WGO_@-x8&teEAOD zyN{h2w_+p~v@sB5JMjB&=N!skx#Go@u2P2Y(5`e`|MOEP;ygOglaTmOVBg|4140?o z>2^Ah?WkeKa7J%um2M~A*iTkCdvH6C$B)(#7`v`)dTWmcDxU|tg_)&|?UkShN!*p= zVC3S(k-q-^t!3k-0H&pIfZah~G;+p_SM8m{(Urj*rT`I=%B)JN;yea1xjDcf@918I z>B$|HBF$36_V{~xM}KHnd{CHYj%dzo$9m6@PEDT$@z%w_IXbRvlBaJnww^05APzcNQ@6LEGQ z_$=+=!v%!M1Iy#5K4vi}*L@ppAua=e@43<^j~poqCO`{xQ69f534-8cvLxUeN>Hau z7ezGD?;eGut{qLHPfiSWy?2@ z*3)dOHh7pk2?kun6gUFC2AyRJi34a&*z{t`hxbq)KK!F)JRp zNznUPm)G|XyC%LmVW&4%DX!sS-9Sx;!Oz0O&z#vVQD(v8Qu(`3GI|VUuq`X;G|}YA zs0}pb*y7Yv*F+y4Q8^D|c|md`PDTJW8svV!E_|I+oo-nVt}S0K&QGEtUn07tDnk|3 z6KVn!456*$Y+Q?vZ!nQTfEO?4B|HiV>g7m016be4%OM4beA|8=wHxI5jMs@Vw6oNh(?rc>>y*}o1!nXw$RcQ^pAsrwa$+gu0G3=?E1Yyd zi3EGUUTRkB@ka|EJBUz6V`KFgTjkAAjNoTWS1p^I9sK*f??@&lC-bHLcCO=*?=e0SaCR@7UD5l^))vbt)Kw7v~d#GM4#<{u3*9t z*If+{9Xv?Kf1oBT*%P~0kw!pkZ>z$B^i-U%68yl&e+&(-L` zLCvQ0X=wT@FwwwWA9l73wT_h7D~bxuY7iQl$q11Mm5i`1c=Ki$O5L{1VLU026sOD2 z7z}Wod7{tAH=3LDzBV#?8=2ENuDbnWxBNac<;|N6oz=jl2#DNfujxNx;=8laOi0b_b|hJiIM%^fV^KQu(qXc=wXq0N&{l_b3iHlja9M294`*o(1rW0W#nb zFr~w2M=y-~WxR|dT4Xo4C0L&DC0?{bunK6hMTFt(yfI(XF1NdUA+RmUy-;zWA*<#H z6DWWtGIC(*&{m58$fZw2c^$NMYkkUF#>54GBd0VpP~Mr(ne)crZN(b;ML}?>uY7fQ zR~<^zDS%EI6xvzKVZ(-nl~#3J(bY=_Zj#NohmsbEVjqbDs5J0ZU+nI7XAEh(;o2)n z&^jF%8A`B0VQ*M`6TB00cGW_w;i4*Is-R*g0|A47c&#B0g z?j;rk8gY6*uA~Tyib@ycx_|$7Ol0QlIak;GFW23!em<$X73`3fcNB6Y-UqWxb>#FQ z#S0Ca7}VR_>cr1Id$Y4`CDVIt4|x2OC*O}6$6nKh z7MlzFjr2t0fke74#ggo78dh{}6)_ou_!n-1--HR0|V$mNLZ*EKh8 z+z158>PA1JrlJyHVVB1=!$HcP0$+IxA8{AH07?T+KHH`i+jS&Cb{IZ9?3VO30 z3mSD-C`1kvnr6cSkt%6E75O3Wk0m;P@^$TGi~+Vb-iMDmC{`zCUU^q4%vIrHGc?& z(UT@zk}!(QbFFJW6cpUz)P+ub4sgeZbB{617k(RoqOAR zaj6D*&zm_pcxOTyQvX<#vZSfFKBrE-->7@@s>89gtDdIUOJ$9Mg@^L4oE#yBM?m6vd>J|`U+M-E)JO6uT@!w`kr|cWCOXr_ zi`P9qHxg4)U>Yo4y_;N2Kq+Bai07I^GkbdAyDm-CY`=xCkj!T1Dec;-&fZYAZHiCK zw%?<|GJV0+d;^C384X!Fh0(x|R*-9BdU2NM)24MJ=cES#Q94lZc2lDtA3lHab-C&%vKp+mTzbVXl7>k2sWx9J8A zhJ^UqD`m#hima?GE)-Gh15wilQK&eJm*X*8PF@%2C^J}xJK%5IEW+ZP{a-*nFm&sR z?1GGwJG7rEY_1+;c7VJcjZKZRjc!A$*P(OgQ3&H_k=$lBWy%!!Xn#KTfOi}CtdzH`L(^Gsj03*U)}oky?+0k zrn_Q=W?uPj|A2SZaF+Va`JM41Y-5%~;s7pUf1@JLy+fx?#jzJF*M3=ER8Fb~W>`O1 z*Gc>yP@HZzZrm6_FFn%H@q@w2eTM0ycV{%!Zxd-|k^W=sf&~#TF_pJ9U4KP9ro>fm zRyFr!qUpmWD`oe)pZ8_vz(Cvu=-xIY=};aVavZsh7g^{|BesHkbOT%2kY1=i@uhy2`pqJOEf;T#nr zX$8L$7db6=n1z2bXb{~~?uwhIVp2mHqu7!R8J?I{mR!|@{<;r3xC0;tdgH0f__2K| zD~itExN$^GEzCV6aB*rRL#R>W(Z-aOm(Pa>qBw{i{%Vw;p@G2y>JAVAATB7QCzag! z_SSYuDr72To!-{RaEg?xTij|z^%r>ngX0L217eJ3q5OFT&xoH(I{Ic>gWIBe5{~@h z{Kfu31v_-*Rw5sTggA&>w&ZrXvfTOhde-z8TZe}zI^e%o;b9wS=X-0PrN6D z%*i%%D{OM%s%v=h#N6#^pMX%|(U#DQtqlROwefRJA$Vx_qCq|C365Uz|>fXV`#10tR zoC^bH(^2~YJowQxPO`Jh`SNSol325i8xw$))j4oo_swM%Rp%I0N7rUOE-!4r4nMyZ zBo>?{|E)FPFQzLcxWKYxrCz?cMtqqbY{A!TK-k?i7d>3Cf+t4sk{1g1GXR8p5dEG& zd#T3vYl*h3b={w=Br3_Qu*c6|yx2~Iv;)k@k4bz7IE>SRVQlgaMn+R*J2RUJlYyRB zhx}$85N1<}cZBlmjKIn*C-%+wqP{G47F5ins`pf7>1=5#ms@2IsGDs$%Xedy*TEt7 ziYD<2ah@@&hrd{xKSX!?c9%Va2cPX@J7tO<0GIxtHD68#4F)9I0WY%ygHhubPZB;p z8cDTtL$h&ZMO)^3shjdy_yu3v^cyusCaSOXt*82W49S5swj@f7rdy=ZpwILVXaR~j zxaedLaUMTGr%y_j-Kuq$lMb~;v=zZNfKxom*dRUWt5|w!4w^L7Q?S`f9Y%F+xuHTM z1|=ydrJ{<;dp1BA57FNuY$I_Y85r2XPT?*e+PwK~^2^0Gt-xZfIm^E!vW6v0-MY4+ zvM+BCz@-tNXqH<+qk7WCpMouOe)X?I5J7`lxmY3~QYWI3rTF$9jGyPI{=sNuG z!z*H6U2fMmX~Kl7Qeb3jeZkzSC{qC&31&&|tsuCRr(GNlw(Oihn zmPUeu%$yJ?#xk@K1))8a)(ro|MT?IwEl9tTvy)>|x)ix*>d28R){0Hm0z<>^G14Jz z5PF8$8#qWr5%i+;esba~sIBdAp+XbRfQJ|QS9T)dIpp{nYARDAd4k9Pllb!J*fZV? zx@v9Oq|&}ul1qy9H|0OB<0yr|OO?rTqMexVe;(!iH|GpY8Sk@rI6-%RO`p*#!77rpH-}0=GbNN3rlUc(*4yo z(02^S`+LoPgwPu}c_bZ&Fpr>Bn80+1 z_=ztlaph=#e+{aOTs;|PKrgrW=6+3w>iJ62?<@e(X4EPwDAsKBq2SAaf{ z;(jIi6nTTUIfW#F0f7r2zouAik;jYo#WUnYHA&8OFf9yH%F}1hI)L2M zSEC>ru<_58{SLxZf<@q=MTSg(Lo>QlE^GzQ``df{GwdM4y&~cwdL(CbQ{5JC zl3d@@)XFgnh7S|R$dUo?fg{0c{rW-jMISwCjzlp!+WE3W>D=<$5BnoMIVHQ;hLL=dW(dU81Vn54x{=7J7+AMKn$$P&P z;*sQ>^Y0|#RZ~(#g?X8zS^CtAmoAxuc5)LB06k)4dHs+EK>7Yi4_)=pH~sP+?*a zpT=4k_w75617ARFhV$1yJ)e7CGuCY=5=U0cds^ZVVVM#IVi6`mEixlf$G&KnhwMXp zT3|Kgm8G?B;4_^}jC#(xUfgcQ;M1Q0*3it(nK;(kw`vC@8FL9j zqJo&LSVE z!1^BjD>k>*)_zPn1qiPSE7HIDb;8Xi+uM&ve}A*Vp25|x8gqlvBVY|MAQ*=yT!aCB zC&Bv+JAuEx%>p{^_+(W-2w2K{LR6KLi;q5M0-TFn4pCx+T>bUWYfJmLw4JVaxc{xX z+N|9_qt7Yy>UGdqCDnh)?xBPAX3UPUeTW})Iv3}ns}S0YGzmf_7@yJW_TffA#-K_f z+Tu3V41#Eq>p$3wIKhL7+^3T^kG5G^c&7<34ADhM|I6!(%!-fo4WzcCpMWAh(D|ra z{TSQvD6A>a*E;<|Bb%|cb8pCvn#-qD&B<`}<BY`j34ihFi>6WCa_jZrfgrz!Oaa*Hc;brAH5YH zCY*wu;%u0N9cnCqQ&X%Z@J@FC@H-I`^75X`+LCrbmcC)5wzVB-t=RdL_sKS?spdP| zcfV6sq+I;aw(Owmxr;o2OOW=e3>qz|=E*53Bkcx}pr?c%Nxnsk_U#R3dDN^f`24v$ z4>LvNP!Ogm9HAqpOxXu#88Lv+MeHBf2&7R3T9Hfbz|XcL0{n0ORi3PMr{*N%zHn7M zylEUh+o7ptxR#OsnbXgq?x(mHfRio8uIa< zR<6-Qx?Kc68AH)zA9Hwe`xGumUV?L*@{`VELPi-qqC*fV2&=9W+A_NuvZ)u3HGY+y zP0f_s%LK`5*UtD!r^XE%N;*G)mL(U&(HDsL1nFtNHD9Jvh+lu$ofA?RI?fsw<)irSz5IV=0eyMgzUlmEu; zaY}@S>e3ttJiBk-h{=;p?-~7VV5(Eh494hweV8mAmQA#+z{ecW!g_=LZmKRDMOl&G zC7xSQ=ZBv*YER9{`*#Ojtuz=Y9)w?_TZf1LbNj1(faMXsDS+M#wyr2&_p30YOUejv z1PB?5St#9~N3(t<98(!O9)Q9UZ#^+H-0g!5peb4o-gyKQK6gHFvtQ`**?A?^QzlIc zHHhovMLM9J`}A)Jc1|Mup}EZ6U)|sR;p)}9_dT0fFt=v?y|jPk&qs|FdVl!zwl7~9 zbx1PUc%yDon|{W|2aJ}y5cph}iJYrg<*$h5VLXd5I97Fe#ira}OSy12Xrex=>d*5Ch za7s#HV(h`$>UA8(MkRNe_%aGy1-#Ev_eSc7)(5o(1JUBnD-n?bmW<=zVa%t;jhYdC z@W;eVw=JUUWEjU<(}xIN1!c`U)JVBw3|RPXa`K5i+FBM>ug}d(rtz45ab6>KB2Urr z@&t@NbboT451r|*UAv-B?99{txY&8=QmkWxDah#WW$KU-0gVI_&JOtVbccKA8kO;} z!0YyLw9BQ4{2OA}1H>8p^VwwV_@k;+mrwJ$a8jYC{npp7!EZ{ z*5n3MnxQR0NoF2;JTXy=o`91!690;)%8=un$XD~$kIl)hGJ81bN&OCH$@xcqFlte1 zGA(uM)g)e<{XZ=LdbwAlo0fHH8T+n{FXJlQyj)#|b&OcKK-Lmih-mD1*7UcqJpm$S zQ7`t`=X^LY@HXp2ULSG?$_^84|Lq~CT(8hSrA0?8BP7+0ZA;1$pvWb3za ziqT{x3S&*W4tagiLmnO4pO${_-tqA8hF}jo0FiHyI6=WGXQ1l;sqM?$guLHFSVQ#D zqR@~b@aWN_a{V{gx9`}I{<_3a@t>3wWo3h1THEg3tFzi*r1{}llcVmRNY$1YSm z*m2|g>qq~JH{~P&ed)kF%M(YH))+O4lA(hyLAzjzSqlf)xew0stA6qP`JVmzQ|Xt) zu*~EPJtck@vX(GG(B>kY8pU{oL~N6z?V=^>YfVjw{O^sfjPsMN)|(p<#hZr+Laz1| z4e6stUsaOE(pTb61Byl8_Vm+$1$|!`Xq4McoZKKTPPLs9afOxT$_D;pEj349^lU)J zkSN10e^F#z#w$T<5)?$VLrN;IlerY6b zxve#vPrP>Cw=^>=3yHm`VwhCSz&)8vc>yIZb`11fLL<)*RzaA}1q+G|UcE^oUEFwKJ;wxITz2|P!Er`{S>s^ z&zgPC@%kO3pLUxjcpXNED}7d@V8U9eYA%7DVt13obb2B5_+rKbx6nBtV$G$oRe9R4 z-l&{eD#(g>t3aoD12}4$>o(-E33tw*BAP6GiZXl<%uql%KrZ|K=%3KVD|d46Vr59f zw)^|b<;QYgz0gnav^07jtOv&}wzHk++|ebtuCuv_^_q5c;`+8aiG zd1AZac%~yY1rMV5jOgoMu_Ni(K-!3%Naq8IEqUXgA7&`sDZUW*KqZwqK^9-b8)ZRl zvgE-V=Pg|54O}j<9}wv54EbRg316N7F&CuwiY^D$r}Q{3Iirh8Q^R-dY7WlTOnb-? zDS*AOBO2$qHDKl;>p=W_YHzBB*n}6GLrQ1#o>ukW@NYWmZF75>HuI^#jDcvd zVEe|9v4nUP@;J;Us`AHEE9MvMr9h4W!NISFUu|7u^{NKfiP#j_^~Yes7-%Oz#>tEf zUKaf#)i{31m$MUD_Fe3?^VTkz+Pw^Q@@HD=?+c|N*&`t+9HPKL^TeTHm2zSdQ-2?DO( zed0P5rN-5+;9e8T!(;i{H8!#=d%y7@=*rkCD)y8gNJ^O>A;1};xmKW}6f z-lfy&5&twW|In$`mU`xD=3`X4hF6RU9+))r(Zc;V8~)SP?`YNacZK)8f{&CReShO| z&5-x&O5I=f7Bu?Mp+hpLfE?3J`S2M5B_tt}FEsS}8lS3d_!${Dgj1GWkkZn}g6txg zmOv~LRsQLf@Z(9vr#pGuPIMTs&U!=p0rfg{nmD=RubS=MRW4?mEbq{;;pT*d-+#6^ zd|Dis-@pC=Dl?OlXiwotY0GD=D{jrvBuP9pl1WR(MV~$U^+{iknSbJSer>(_%I&J@ z&kJ>>M%PF)WH=Bd21#@>G#xs8_!ZeW;G_vrt+}8zxAbB=_r94F9B9 z6Z?z)cDyaD1`Lg{@!h57HS7F)Bm;n|V({S*b#!q_&CG1^pGyWjS><_^erQpdQ@j>S zSHM`980;tFCjd$oajzsx^C<4>_`jGj|NE@B-8*;oK_Enzej7Sa`H~gg6I+p)_#l`7 z6xHb|XO11&cl6?~Z8Z6;zlFOu9HuJ(4S^Hd`u42@CHGfN_|~by7^Y zq@eeo@Pftm?(^Y77a>C6zyhCQN}f}A$4?||L>q0Y%E^C{oBM!LMO$?OMK`=S64Mi- z%(qVM)*4y=Nm^7m5wZd@8t;8yb*o4(g7a3Z#-VcZ;%&YAr=6s21WcqHFJG|&98<0t z6< zVJ&ZK^2CV%ehrZ7MMOsWaYU~~kt4SqAd--yWqra?_~p#g{a#raq-LjDt2XphxP(0F z)Kh|~lXOdYG*?a#)yrH9z^N>4}wg_^(Qye>T%^uy!qiD2o6E6_q`| zvtM2b?DyGn`I^qme$dC-OpOtU`#D`jyNCZzyoL{UOC08-McS@@o;Qz_USn@x3*&Sp!RIF>ioJIZNz6; zv)ug|mWJ%P7}yOwf3QMzD_h;Kh*h$x+-JlF zZPRS6tMA^v73mA*%nU4ZAm$0y-znN)`kBlR=HdO!&Sx>xaKhudR5tA2A9v7BR6>X% z8sR|dxAdEwr=$|0J%^$7YGqUM_2L@2_SX`ta?NKJ|7u5dcFHkwJP`c)h%N-gdDk(zj}-R*^057pk&3s`jRn~+KWJ#1Dq@GG&#_S z9y-huqdoQCwr%7A+hriyG|txm(AY>4*TSZT2EOaMsk|LS>;GE~*>?S){OF+B{`)62 zNoX8nL&$L_phYI&UV6BeF@dp)YetV2>jg(l!3<{5vY<~YE)F7G>i&r>!C7QA0~9DKC& zV^&Fgw_G0UV&YylLG#);#*-niHW@g82c33tK*|4%8AvHWECWr|S6a)G>8K(d~ zF`KBr%40%s5xv1)0Lpdj*>e{R^HGo5bzp|kmdf^$Cz zB<$NGlTtM7qcM*0Imw~j#t#ylwawG>b_4q=le$eD+#<1rE_a}Htu9ng>iwg~*w(On z*Dbachbs3Sbm)jldc*9@vevCyeft_;s;Om`lbu~yT%3aPP+mH^j6Q(m(9&a5+gSB( z?wYiaHdz`urenD!22HncLuf2cU39*!7IInT+W2$bK}HCF;;zlE=hZ!8FVr(J8F%<_!JpLw)=tn%a!yE4Rz7j`y!k)6y1kbj zAHBi-N4>_4m#s3iTpyq9Mndsrgh?#JYg}f-E8&VPhyscl3+rh{#%98^#D7PB4tLfP zT8U@?pM=DabQg`2NC@te%^&lNWJU4H!y2;r>w@dHbIx z9;m=LsZw58;(7PXgAR6_B&9dXo6}eq)5Yyu;oY!_eIK(JuD_jv^sZIC+uczm0M)kG z85$8Wk{j1t<0}TG$0=^rp}d-%dfEiJX)=7K7a))#70cYk<=i))q19#|a;~1gfW<=B z)YLx1DaITjdS>~)6K~UI$K!{WoculGo+Ks_UoLIPXlcSiL&t0t$r! z^`zh11V`W&-4UWox`1^<96`yP^Il+X2y8x%(zZ*kIUX}rRkK~Ag6|8=rYG2{)|RQ5 zO}{c)_0NwMUKtb3mMw2FyLt1ia~5}1JkjK$&cVY7vacW9TywAKR)0T`)CxF2pYm%5gQN!VA+a%L(Kbqq#I3pf zs3&^cnIa4k$Ah{48=+w zmFcs+Ak!3K5R$nwjT?@4x^K!)sNFPqa-iJ&EEgb~TUy??FRJPC*xqRi5hi`!%(d0c z&YO*Cm?>~dY+BRReZ`nXVWV^ga}^o=7mNbk!Dz}7|FWcu_Ud&${!GUwpK3m)==ug2 zp~)W&KaCm+VSH9b`~X6wZa?~Y>UmSSG64pIuICh}6FgJ91jDbPxs#R7;TXnxtTs$voxP8d)>m=Gajt;fLJ<5w^Ni|oQzhzQG5}!bbAg#J@;V&S!;K=0f_#Xf$zmR<i{7VBpzV2|_hX^ecH*|a`KChw%O#ML7m1(~C>^8#{BZv6QaB@@q$s;}`I zeq@f?e0l`h+MEfKf6sF9eE04h;+SPPsibojH8L~EpV1*7o4xNDq1Z(2=mUoh=WToe zS@PV9lm*mSvZQ-Ga3l0+?;^*aTdU8}fk!Cn@eO z!7%?|_KAp#)1ZRU3ST#@-1x@QW_8TV`@0WxwpBVd#Ng0`eFt`!UXO{HI4QHXAD-lN zbBFMk@5oE5%e#72J?P(ETCJ-#4j(?UvhUip%LDBipV0|fx3kpfq;2$m+99wCX*QGo zJU@?LPEvK~2Z}y_P6vHK)ll!vw4^_+aXs-xY4E^nYsOgi-!%J(&9rG^a-p%{cI|gy zi{hFS5GdMKJQcIaW+8dz?SZ7~PGlCwz0ZI8aTUgrl|-M(*(9MlqUjYdMiT1o-JNv? z=iE21Gp_A59Ego;cjI^A4hG>XRU53W_im{-G;RCLQGv7O&+mxCk}@Y(a*{5&K0%8) zmnXxF%YDPOZ~NbR#JQzDjxOG3drVq;HGIU`?+X`h56b)Gw0yqp$ZgY$ z6Kc4m)Hf(+bG?hnOXhd9S!O@;j??+DqLK#s-3Gb2@962=E$CWgw9?O?c}s45{`3if ze4id4I5o(DPeytx(k0r-S?3qwIOKaGoDr0G9pi0_hFi!uyIsF_LRRdtCmVik^wvb+ zOLHa2V5@7@PRW<2f&sP>z1Jyky*0#Mve0)hgUFbLe`HZ)psSr8JmjExh` z_=T!z9g;$hbrC=Teclc>F2=)A4Btt-SCE|zCc)Q7t*+UbV#D)ir}SI8e_xsdO9&Ci zO?X5x0t@)l^FR?g=vB8TE!yW2|5#L^;Mmp$3=qU^Ui@^nHBU{R8hSQ6a+R>k9Y z16D>gUc2{<#MLa?1-P)J7pDP~(t(wiX4Plzq@3Jbp?t)a7s;#0ud6l2pUx=`*E}O} z!#b0a0`2t%;Z0%vt(KkWy>NGC3vu@I4o%{-JFh#-=}G^aL9dJ&h3o(f($9`_pP~JD z-Zs`Di<+E>5t(sO61FJ8Ok!5X=EF4s_c@=MO%3TkF#PV%AEB|a``LxieqDO>2uJV6 zrXWS+9%m*a?JzKK5)KyUEFPpcFD7PQfQxfUUEY$F)=L6)S~e`Jd;9iEw897@??ajw zO$(BuCr+Q?cg`sDAU$uK;r9NGvNYH-4C*<>o%PdiUp!BC|XC#vz18YSN_4jT;jg5om+@F1Ww1^QI#_dwd#dF}D5) zjBsa&JcmIC`;EldeS8vuuIa^xRMoDFS8Y;Tij4-MYVyf(a<_w+mKpQGbpmL}P`m}` zW#($kMh}HCPl_E~fykR-tWH7tgiP=uAcm|J36{Y)q~Ys!N_mw`81|}xUTOOX-^HZs& z?$QdA2}2bc$obF6L#dWD8o&wqjo}mlm=uIRa$PL5nuH@FNkNg{(#pyTJ(3q6hqPb> z(lIWkZw9ZZGD0@%+IjV20?#0eM6yTkPOF0!X87dEEg6If#E>47QkL=gC)Nz%T=<4G z*K%JF!UNH_5@u4#Zh46CquD_2mo5l!aQQ2Fv6^$j#o4)7yY6>mX?|!9D{AbSV2xDY zbbj9W>~kl9DCG1&ZZG^E7I+{w)rS8h%#!-cgNE&FLw|03!3TS@vXdSwh9yc@7e}a)_Qzd z=|qKNlz8^+*)sBvJma~ORTpU-QZV#u>Ag0UDN#(vBjgw5H3~dbQO#HdIPD9nzMieN zEPtt@e-AAaC+H}80G=We&5R@uk69baMv8T@M-M#!X}(o?_LB2h+fdPVCcB>5oBO`a zLwlc27S{)lhS)HG#~hWThxO_s#+Yw$_{t0?r%w$$e&HXr>JjM}!z;7Jy>yG3z941O+MXHnpy+UF2cF7&U2~8QcFxFaqKgD^j?w8j}$2RKU-)&^* z>+n3;Ja^xVr~{|ZW+)gNU%V7GWrbbb7ms$&#*H7jcWL;6+Eb%5cBbsHi7KWq7K9JY zN=rWSQB!ven5m=|696Etc~L=@m2r!>#G6vM5g^pedfKXqO8*0^RwXd&!9*=T(a53TuV z)n2p57`pJT6SBAJNFZABV~^UEoMcz~-Ezywq7rJwDPHTd{5uqmB8#jgjBro9VoIv3*jG~jA9L&emj@Atc#lW^p)EOT4Y6=ifR$tOncV5V*i6=DJV zd4jlTB{qO+Ez_YQ=P-&v&)(otb8)#Q)AnowWNAC(Sa5Jx z_Q$yCq%*;<>zd(@=4 z2`exC25cfvSO>8sen|9oT(lN}L7Ohu+}tSM@Adz*0Ok_CfbW}?<9(wp`!q2GD}H^M zA;N)Qzbv{{uSxjyu;e0T(aqE+(f--UvLZ99W9e%-y(AJJNq%8z15f98xHvfxYp|Wuhes3)i-eZ}ZOB%x#^SJQ^`D5)d)=2cIG^*MkL~II zv*_?Nmn3h*w?w42+vG~!=6S;Fb)ss(2TbP3lubcK75^>yARkhKDc zJ&ryDx!Un-*A9|lVCmV@%zTmEKhtb%nj(L$F?&9H7?;vN=omS@ZPaP;EF(R+@psk- z`Bsy6%q>DqJgSSdX|j7NqVH)f#xROb=;_m=f4?7E*Ok1ICK#M>-yW0;$U{$@Fh6sq zdUUt`ggA=XvI8Q!;cSOiT;1TcHgDaiF1>msz5i*{#tv0Ta_OcDlewfnB*X7};YQab zh5@hm;S1>dbo=$24AH(fwC}Uvd8cn%FP*S!`cHpf)rLw+nL`G2vsA4u*EYMhX1wa4 z3&sb&`ZaD_WRmgnWtT5GSFP}ECyFVN#>s}3uNCfQxx;M=q{H=PNDxEmkB2W=`f>fL zN1t;tGIZ!M?WiF~zP+$>Z2}CRO!wu*oTdbiv-j^mnj1HnQ%Y5k0*=)Ig9bH)1~nfy zZs#`~S=GmvbeoFr*KHiV^n99g1^=`&IcvR!){~Gxn<%4hjebsSeYTD;>I33IPjI zFRbggG)LcNqw~@^89E1zt*)rXUS6_DPj_lt?GLKPDZTu@zBtJ{*wY}n5^jmS&ZT;y|F237r_NUlPfA##kEBKyB;KzWxBW{CnoW%SL z&tdjo$gA8`r>=e=UTf^tf!)%IS71_H$L#=2&m5`^#H(b{{%)A8*=N zRMpJKj4Izh&#pTpHe2bQ;`&Y&eH8TeBXeTYkf5O&3QL&Qp_#i=D$35dmj6q`|`;X+Oh^K;&SI0 z=K|R9K3Eh*@X^O1Q5cTo?f`}vmJm>kMElWuG6L9VYgV25xACBmT_9mRB`{9PN3&i)gT6z_evi+uY0gvdx&F(#5oGM$E8i1p^eeu7(*bnkzRmEt@;5k|2t&EK^`VZgWov)B1-fPA|UY* z5D>cSZ!&<8HuxXsZYeG*db+sHBsDFUM2e{MsR#VYb~+wJOoNaVi6DxM9qUL3kVv9+ z)U>s&fIARLF-c++*1dd#RhXseI$JxtIBtkV&nWNzLBGeniL>QcDecfB z#JhU`fgL5h!eK7wMsLV5jGx*qb4#@A?1Mwv|M?kz{){VM3ZhNHC(38fzN$Vg^7=z^ z3B5#7=f$2vz7H19!b2n`FuII)`}enD7Gq2C>-yr+g`R4r(B@KUpZa?;j5sEt;w(ZZ ziu{um@(^W>D6>FA<&GA`t;1jj;NK)(kxp;uvcZ2J*m#Hpbq}fjHk?eNv1s~`R?tvOqp}iNtOON`Xa*%kx1ckx!$!=15y|Gz z8#pi+$+tXQRJ^c|y{}B<{ArM0_vxVJ^_%u9Z*g5YYlC2^eI$jgMEfo=_8?6r9dfg? zWek0J5z5eE6Li7o839QyA0(Y$TF z%*+!d%cdWE`RC22KM8{ps5&SNnb1X1L7@~6212n~J;TeTBR9b{NT}fq1fjGn3X2}l zsUxMYghRTvte`$@E}{d;Qi1M~ELyCVix$0ie-xv3-Nxlh7Z-FKLcxa&3L-0~4=bRd z*&8;1cV`fzXw>NC_;32UeS6dRg~|c(Bv>7sxw(s4EowwU9+tH+u$2tWqzV&6>Gx=d zzM6c5aE6iCf?){?mM{nqj^POLNs>9vRLihgfJ_WS>PFXj<=?)|A>LioqWG$quGvCd z9M;x3WcTQ0S+}WIpyekyDUg(+e3CE9u3M1o)dZC+el2I;V!RPtBerbCiVobW19A#i zM*(7niF*1{BY)(BLx)FJ#7>QxQ@82jr_UdoEMMMxRhNbe+x1)T-+yA=wmq@_CP`co zw}%n-B3bAXUc#Hgn0yOcD|R_U&4&Sl*6e&ZoTtI>6b~etH5owBo%LSo1lu`0EVK8# zJBsMW#Rb>5?_Oa}NsGao<+yYy0e@rfRCM0g8Ny#K6k{;qSb)0`RWE57)MuD2ka~8- zkY`U@OF-DSeJ(DWF+50!Ry)@lx7`fg{V zaLl9mu?_XJ&Y3w!JDOD|EA?K|W`K#OdD*ah@@+@+%(OTC)@3)JIC)Y5B*i-NEnPD} z`vtOnhab)iC`i0EE#_)y=oVhJB*RJs7+@=;ztI5qG>5(o%}69@MdMD&BpxjS2UJ_M z*pigw;S+8AWW)EO$AR1g^!n$tF0J^Se_=;lr2>Cp`1Bt#<1e@n^6gz>zr}oc`3|%p za?2#I`s40;`6~F=7!K$Iwh|$LUIrz{8wMLW8F-h11X_gkxzcU0<2->-@F_B3bDud{ zBao`gF0Th6%Shw;ZMm)ERLqs2Z#50w;NlqVR`Ss5;jSn{YR8A61ClwIEY$%6+G5Zm zM~NaSOgCEBFw=q%i(*|<`!7FhK6SsB*23@W<;Tf|DH&mnb1z0!Z;~VtgiLoRvwZMS zfPYN8^Z<`|n6D@gSmSS!sfKK9ZDmRUA|-r65*;CN1k_uBM~FQg6R0m{M_3zL_TF9Y zOBMwn8>Ij#@snKLf}S$oR(@ZAT%6%WZfon(YWo@sQ^|2n=s1?ToeQo z^@?0FHgW1y31X0FtnBDF5og9{`K4hNXBkR~Lo7<|hR0HFS0quJ912V*=#03S+yccb zljrH@pB_biKc02_;`|Hq8vSe9&1FOR4==x#b07V?r&=>|dcG3#gb-rv9|>ha_zA2i z$}${weduiYgae6F;qLWeQP01Fs&J3?u?ZIkxJ_9(jbFj+?X5fxU=~zfFdd4!T;hyX zg@q+qlmN7n*vq3OExsXw$uKLW@VMcJ0*2)dSVy*;*aqa4F?Pv`z_=@<(ATfEH~Sv> z+jpI6IRE(^(my>ION7o9q?E=ddm|d?$l>*8(z#OqVa39kzG*T}OzD>P=#jpOiCoUW zLgUG=b9^Yzcf3a#=m=}DJa^^ei`?2O_ow^#+#Npj(B5x9G8fJ`6darewA2;E1lKAH zo!JTqNc7t znKS06p2mD$c|IztBh4a(dj(Pr7$JBUxsJg7*HQ){Z`3ign>6yO>gsa&j2w{wD!jkd zmD}9m(Ww6tGzG8Sl8Juz?y1SDZNu8VcF9$ps#RDt(yyPAQd?6^ z0tBaO9XXO6ckQ*r{3UXQE{bae(|7OR-;PqN98_EM7O1A^g5|Oe$y(ys^4797(rA(> z@rZADeA3UM;Y(f<-65nb@%NCCK1d+Z_THv>qEEQR^oOvd{PMAyo#YZ^K6`ctm`HZm ze@aT>-KZBAVq;ksGy7iLz3lNz7&^Wwp(Yb3S+u9`1*Ap0KGgBip8NgO^j6hx8>P_h zvNb{@L%yy;MSsT5#F}4rc$=|vOVYKpfuyGFqakCgp}$KqGcI4gCy;iCQFaTiSPCor zIZ#X2Zrx5qMy7qZqu(j+(byFzQj&)IYeq8Y#IG$~2rCM*(NFm4$=gni z-(aGbxIDIyp~0KdZeNJZtzqsi@diaP9omP3#sYzW1Xq*%|1(an4 z6?aJ0mws(}&U8H8Y^Y=P=v(?`=IW=f<+?;1L1slxEH4+BgkbT}Y!;q9f)9i%qMpVL zgh)=2-tO+Z{i~`j0$Sl0yT#bwL{SlJy9stk=ze-V@9~qZFMZCv_<}YS(c3_7^dn6L zq(1Y>ldS~HMow7)`OU=}GHKwp%CaAEaj_G+xZ^>v{x<`#=ej8dmSSU*QdM#wi?L7 z^>zx~_hr!Rol_ybKV<0kcga<}i3aBmzmys;)*|>q=XLh} zYWe%y?5TFi?GihJvgh-HZM9L>{&v3G5q)5>u7UJ1K%+m-NW=dA^bqWG z2Mm3YShVE+$K>R~(0OA-coMn;1J=?1(gRYZn2=ost#X_x3}6&g&Vo{kV9Dx%LE6D( zm9$E#4Y%+CP=$HJGBLZRKu$Mq?4zB~V%RjjM6e5BPAd9hC#MeFlLf&|J)XbY4A)FD zQBOKkpGW$h*YPcBzHS{Rxi7C8bnQCPx`S;StKj-$_Y*RavE^J3-{-GH`t6b{9Vkt+ zcYY-;CuA46Kg<^lwGitE`^?9=n6#+fy^sn~JK!*;Y-4y^D-<2gV794lT=~Dp?)=uY zn`mfcBpG(N3dqSem4F3CQbg(2GiJ!o3iFP42{Kz45!fDvajxU=D6Q6g?XUK=<72E3 z0#U(~iRhaR2y3xKCrPEj-)P{pv@z{q=5ABi`BVxb96S2(=@_j*}Bj02U1Q*@v&WBw6vF7|Z5Ch?CB;jSQXR){*3XWUE+y2v{)_ zqd?k&2jNJNF=C4pgL+PPCnp4YyE23!jW|Bo{mN_UO0Ta>rY{K@W-{EouH6$g%FJhdD^fu=IC zP=!~M<9Xyr)0nqCZ@F314V?ruJwb5Lq%tCmXlOuNqf&D7m6gp3x zaD4c~?8X{_{TE#$h2=7O7nU7Rd?DRDGjU%|I*v*0S6j=f`p3qELUf}AlXkvAB{cK` z@G%5sdjPH&_qetx$Nm_XXx+`ro7EvvO-logRZ1Z;+jpD-tik-&?kX+ki&8%{aBm>9 z9cxOC4)6=PrHKJlLSE@*(S%ihwDQ0%-UwZoyVK$!F1eBO3MjgSC{|MR(s*nnD|YPM zx$!o0QAaD^?KXAGu~|mNG?NnhL9=ohnW;EVK|i%O{%8TmKc9GZG2Q@|h7CGwm5^2O zq|@&Y9bd+bJ^Sa=D%F3RHBcCqv?=3iuiw8nxA>UUpCP2(Q5&J+xUL43HKmhE!gm!= znAAc-f=i#r)F$?cD<48e5HC>N1}KbD2=bLgH&TFgdi5$jcmKO{Ylpy5eZAZFPLL3d|btDn+FbvstYv{?oBVOWteL!J$D*tsZ+w5C@Ia)zOq<0ytI~_ z5i$?{{OMfbHl@QYD=nxZflR>%082c{To<%~8=1(|w2U}GmybVi{)$;vS3lWJZjisB z!LdzE-#;>&5$rgx?91iei`9Pr*>1h4+jG;HjYx^)#sJ7P9V4S4cn}I5cnFXE-;fET zDDaBSnsHy2X{`G=L{g*+1HiMZ@hr65Nt46YNzY1ujrAV71Au2qOs>qK{{IlAFsp>WLdrAVKz& z%c9(`|28yRwQ}re)il@j*MHYun0vy%?6}#yl!_s_jj22|bvjs1k$@q(X||bF!hl4x z*OJQ)RyET~8IT*-^$|&GFst;pTY)M-AvsSjVAqgK%K+smTgJP;RmII7WIO%+`}Zx0 z-e7Ly_V^-haRfEGV%H4RbPiDmq;JT<%;upap>xs7UOjfJmrq=&vbQ=f_+`nL zFX99eAO(z991}|R5QM@Z-k~H^f&S~byhN2E90ENN zK(i-K@0Qx0{S$JLkWtch0AI`9zQhvs=`s;0rR~&paq4BQ8*Tw|X|6p4ieZUdvkde> z+gC&=8lpyyPz)T*$Y@CA5&OW<^}} zo>o?WH6)W$k!(q5f+)MNjF5W8883=*E_X#-?yY6Ieh$FWvju1R>4%w&S%w6VP1tGZ z&|~NYb|FR(uOztIwcn%N2JeXC7fJXWhrZvgUG%R9DTrJtc&s}(YcjT31EpkJ7?rHk{sueAwNX9FlPp8|vlYlZFyQ47;2uR<}x+7A(y zP;qzey!}6#&I7FH{q5r^6ryBhr83IQ4y7n7qpV{_5z5R6Q5q^`ohUm*Az9fgm55|E ztgMDr(N23juiN=Q=X$Q|x&G%Qzu))!8Tb8Ocb}~lr@GYtm<}05rBGFt{}b<}EX9BT zug@d;3-xytFf!v&Iz&z^m9!nRP@Cvs~54x5&~<-nHy4|-jMvBb|& z6b@bYL#A<1WpTa-tljAyHrV$D;5el{2Z@Xb;e>EMWo06V;e%IQE42>zx_pNqaWB&2|m4f16bH3#2 z1>e;FY#zQ?pGxz`hnaifbzb$-*4>Sr%q;w28}KJSl!kI@1apm&T1Fpqf0+)h>u!x~y( z$>4PWLy81}WD{Rs-;1E6& z(hc-G{3@}vL7G3nTOxZ$L zb4iXD*Aw%&C^mo{7BRDz;tx3B(4gh5DZg>Rx1VP{{LKO1qP0WZtgrVsaT@o!l;B9i zyDyG5s;yn^f9@NdkdPO+m?)Q%5{o92WSm#Wmfmfc=GubW6hda$yKVTZV)U#Ca7YLQ zAY$-}<+^p(7KF|ZGAYQVgZ)bS*8-yBfcc8xT<{OSh~Ot+-7M9`{sYjjRu5cetiPPf#fnRe|v#pCwrM+p#0%`pV-?jGcm|e zl>vD2&A3G5j6@+poj_>ofaz7oH>_yeHKx7cj{RvDdR=K6Vq<#9v{N@rZT^n-Y!Y+U(lzA)#ne+sEjY#M)R~JS7#^IUyz1HXjCZHzkryosOFEdC$ zx9r|ue*gM4<5v5V-ix!mWb<&ExSzLTYI>u#g%A)Lkav36Xk#A=u~C#j0KVVWR+P<% zI_)y~L5etfur++=EC5*u2oAQQ)!@wMM*6ATbHsnt?f&<5G8crb&ijH?6OjsR#4Ut6 zK@y=^O8J7h0P{J#xz#h%QlkTJjVBN8rUP#SYa;1<{EMbXPH8l9D=5E9?=7xDYE3zT zxH6b1_)xNc80`buC3+^R{LuE{$8&~e{n>L=m1M1qhanGxd>X_(iVf%*a=Nf%`zv|a zZuRip{TIy&CeIZwF|HJ0s5V8a&9wx9@9XdXYT9y_+ig)t+uonE`KaTGf^U zlxM$TnBC5?7F#(IAv4ru%ob%LVlbERy3NT+_A9U-rftp>gvzrd6OGSD06u5a8XZF60Y@6V;K-&ynyIN^Ov9O8>D} zJ=)YC`M0U{FYJcw3trQU-;BxZ5Q~?NRMhoAVFS1uDYlrcbj-75UCVR*!5M|k#YY7q zFrL3pre)CV?$Ye{;A}h3mUB1G97gjlBM_(x8+J_Pf)MhSLYDXRcZAmF&AJDl8Fi}Y z-OIc8T-#qWZm%)_RQ)#0Uw_Tur5d+yJ2|XKIy0r`!DlD{@cOlbCWX)B9gI2uCX*+5gf}3KDBNfT87Zn`J5X#NnQ$oko6M4N{{!}^) z-9_4qW`Xp+-&b84b*Uc6l9c&EJUs$_J26M1S?~vG%}{K=v<=T4uB@#5p9N**LA$>< zs$Ca-UI$eMx)?Ue1W7}Ziym|7=&%&&6{WxT@pD59&<}{36n(R}n&hTptck2t#1j>~R0@^WxJ!sfJlS{29EnhuZAf z3-_0$+Am1b_48BD-DRXwN6{_mLR^0GltiEm+kz;L(n%8oC+;lds0&xFMR3R3pPy^`b!NK66_AKpIW{3FVKmJWBScmPmyBAdxTWXK`T9}}T_N;b+cSZj-K zGtI(+(*SS;+i@&ehdh)2?KZMU|-h6@c1)$v>(EhAIDgLnGLy)>V^;Ro8{7t4x%V=YuR8o`= z0AC`d61C9y(^Gf!?tJA9#&wVa9yRlA139OF`n>3;`C2>;L6}6qM*7*b>_7MHZRW4+ z-C?NW@^?Fysj;6mbXTnn8rUc#tX9=Mx4{LJ(oj0Ipe$pN}rCLoIYMBHP5!<+}=vICHR!u{M2R9oNZ`ir5$HMRP2 z8(K2Dx@dw3={Y+L9lr>gB~}E2TY->LL6)9fL->KNR&ux#!A&Se?N45ME`uNcM>nUee4%^_C?KEt_i-||BAG>K0 z_&ToZrP~U54xid6ju|oCTD{etEonCC^YYR<<(L2aWO=DdPH|M9J_a-Le{Om?w5)7s z+0dUshsLqggnd__gE|ev&ePAFoYVg z7DPsi28DW6GQIKd+hduS^UsyB6P6v1+tRW|`OQ}AW}iQ={?lX8B8QfrSEapOv~}#i zuLs`k+Qq}`pIg;GoEDVQF9hUpRf zFiMn;JXXd@irxu7JbaG8o4|(g9K<4BfF$BYkwhR9B8R$F55W$&PcYoHO`&6_{feaC zz8e`yOu;vaPx|oT2+*f^&uX)SYqvwzakO-Dxn6f~)l?dFAkXm=CRC(*sS)0_1c8fy zxd;1SxcmDTpH4I!GG(rP`<Te>>ZrOmQs z15cIJtF9R|O{;aU#EF}npFjK8x=+~Ivnr$rhlX~Bv=~e19Nh^rR_*`~4+Uy#Q8jei zlCwbLLPUf=a1aB$P~SD=%n&oDxBv(^+LNu>N^h@CBd?C|tYAw8@uszVY2jHS^I=z98fd~%;(vG z8uRaiY{jnOYYK}GV+8XD$5)8NVl|`&wU;37402Oi+hzD6#ApNrgz;r~QzDD=R!1Y7 zL3hr?gHBujTu6%;yL}OTu$c-3os4TFz=7}0g*ycPkeL7k#!1e$f3|vPT}5;XKqOgo!~;-%F*`GX3KT`y{;k)%!*t(hIgXe6NZgT4q#|C3KT@1w0Icgfmxa{XNUVdBYgW7nm}49M%0)s zS<+237WADIZBr@qN$eIi#^AvRkaqAd{v~!xJd-qm3&=O3M*tUnAC{MP|Gol(M`D-- zbtIMN!<>ZxK&L{RH`0hcouY+G6NzhkS~IQ%8DmD-DsEm#ZAx%)n^7oE{ZTd{Z!wE4 z*tMt;>oF`OL=i+*NFx3OaYRUo&Z@O_Yn}Ib=H4{WI&q?y)K#y;vmn$v*Mgi*My8vA zwKdzdEA1Skl$`bULu21&OZR<>E;sAE^mj%*gXpu}*A)~bzOHuLy=Dc#G9{^$PZ1Fj zH}fiBU;sE!9f>IH)29y1kcba>WdGR_vEI<3L*=40CrknN7^y#rDJfix{{%HZI9|Jp z>W|y+l9L}m;E}B+!{(`~7*TfaAM@O-ENxTMP7u=g9u0WwJT<^XJc!OvGhHmA%x_QD!9Y_%^$^0G4JzA9Gp|a6ghq z58kUZqxgf>gWKmCm;O%Dzw`NC_~Fk+i+7xfrGRQ$QPb|~myR7fdYnnk1!88E^yl1? zGngx$K6e4Jd0>uBP?P^mj&Rz&i|G@Zblh=iX~FIl2i>y`8<_1d)Mz-M;xilz{tdBn z%Z0js{GY6r+S7aNxAb{!(Dj!8z&$yY(N5iZj(lJk2WSS(Bg3Kz3i9Ukyo_R##{=Rm zfVG|7*PmnF zja+(GmLJs)HX4}~E+Hwv_{>=_C#(}T_`$1Jj`v4RtF-nS-{4@MrGAbxT2G(uak^_< z-2HR^^j#D3qc}o4282OUu+c8U_y|(L%=pl#sAK%nWxvYduG`|HUU%?MP5&5rQ(eX- z(2PjBlQ6d!AuI3o9dB2^tLn|$VbgnL%OT@lL%#X&%>(fj)Kt6B%%KyQ z>hrL%4*JqA5HRTZh@2MQgYW`u!t^_yUS3MPRD5=fx~{cuJlFN$i%$%p;Evx59f?lp zmSfu6@gI)koC9yTW*fWJe6>YzYdAjUPK8x!2IPu3JXNXZ!YX+PG1oB0#1T5lsng zB`uTWqBBU#V_@guJ^K>xNd-?aROIho?ZstFp^8Wy&bk4OEorjBcX!uJ3ChXM{f-h` zx(E!+lD>dCM%;oE4)oHYuH+JzuI|5(X?iXaH%|;Gt{U|&V(Q2(QDYvIr&wjY?fqh( zZ}(}oj~e^!RBCfDe!S-S={+Pjny`O~PNt0c_?(!#2nhgYGu?5olcAAwZj4HZh(1~$ zMn*ETzPQ(I5lI#Ed%=e0xa_@pU!!3=wS6K5WmAXYoq_%)Bo$QtN2tGv4Aro*dZkyo zwWnY&TISQKCpmCVo{mOpDBJZcr9oihoFp8MTHHD z;OpL6r@ooW%57WvI{v;p{|vW>q)%O`Gd#e6O;{u1;!oJu7N%H!T3jkx-6L_cpaaDUAwE z&UBhzs>?ONeCPmWYMnHb$d;ydPkL8yOj%E#dsK*LM9-oyUAHc9>n`t+g~>K>U{sxS z1KQ*{vHC^9O*JGs`dODfkV_NoQyurVJC7#dT8?%P5HD9a2SgP>{+j$zU(SX6s4^|u zqrbT!WQW|ob0@olVV9MOX~*lkI6D^r%qDX%V+Z0?e*lAo)dA9FBDWQS)Gf!;Y$Ma| zuE+tV!5QZTAhEhEZyu*Eu%U?gu|ZK~NGL6{b(qKN#eQDk=xD0_?N(aluU{FThE950 z_PV>naxV{sS@$%5yhu@*>zeTXE`=b2315H{VnRG~?V3Do-Xv~UOrhH#im1-Sp$@e( z#K@?uy$^PSugH~RDYbBJFT{=|kqFSO%l^?j-RrWq=Z-D(+j6&krBkLXAyJfS^8aUT zSLe)(VJcb2Uj~~z{}w}53Op2yI8$wG{86~k%COstBtsI?mBW|2Gck2nmz90fj@36! zTy8aPoY)6x&Zhy$kW}FhJ78LoV1+C>tFvq0LxVTYD-J0p+8s&>a*Aq2LA_NgY|f2& z)6^I#A3ur?iiin%z^qTI4NrZ!6+J&C>*nH}V;;{^Ib=M0T7J-;6NhuFG(~>{SOa^R z8o4oIMn-pPN}e;iTTA2~jC_!J?Q-dW51I`A)jQ*vjn?A+hi_^*6XK=XahRx1RdWuG zZuF`TZ3vMKkEm>Di#baOdj8I~(q+@*WrX)XckEa1kz2j>MorZk&4?)pBO;&MXUK-% zhi*F;hUgQ21Lm%d#sm=0{5J+bgaDIJ3(s>m8@I8v%B36O6q$4g*XYbNkR?3;d<1&g zL44*8Ty9ApKN_9Qi|XUz;ON+fd88T~><@;aVB3XIWBOD(v##Y1lCR=m z$8@m6w8E?@zUKJDX`K}A=6C{&6YjvHX-HrzbiZ?5O&RVoDzd{I>vZ4^N2j}&ET_f8 zyXlXvWg77wzy~xCGWHZh5BsC?&A)SJ&(6MQV72zM$C9TH@2orWJU=@nF{xhXvCE!z z{PEl~-PYM*#?R2(8}qdUHNYtgfOGfmT}1nGE6JV(G|jyoD#r)2%O`ege|gSN`-F{r z=o|f$xM=Kw_0ZFh`;hkY&V;gm9;kI3JIu%^;ptN|=G~-K|1dRRnlI@qDk zAUnyz`FO{F7;M3%39&|6R~QAl7=;*!2H3$C0Q#en+yT!MY`1Z#S8Yb{-tniIQ0R*r z)|bVCW}1j-ncT<;S->PkrnWz+=hE!1qPvTW5mcMq|M+tj6|KpkflD=L3h+xf{PS;g zvn!hxF3-=~_F>NMqlJZE_XH~4a$G)MYs@Y>;Bn&!eRF~Cm|bxTQ3e$T`c@Je8f2HYxQ z{$O4(VF^g9m)*Bgue?}Ox^nlv!iwS}NlRL_Ix@y^zyRo}1ATnwnZm+R zA^73cFc5Jm&zVxCi2v0eVt-Np)OWfu0XAD)DB4B)2M)=ca*8Ru>f&u;^K{%ZWwXX{ z|C;G464-`Ibs_0D)-i4!b?Q@0b2%u{`r)Y>=ukb6BJcQwu@^60LfAjoC_u!K6tQ&Q z$kWDj3uJW1?!drlF&DO9A6a+V`FcxfHSi30X)(IGZ`w$+t;?4!BR@&1Az8~m$Ft0+heNhlS}inxH|XnCDiiQL zA%tnIo100d6KjW4lsiT3kn5F~>zmY@HxIHDd-|S(%Eyi!QO!Tp51`^}{FQg^e*dop zFtNa>K@rf&2H%keE9pK4Nf}LD8JO^W7>Iix-*1OOJ7ermrxOEI?q# z8Mqdm3}1tTMy6PCfH2eW39P~Tmj(y5GlD_@q(Om1Xv=5H&dr6^XbhrDWPtR~bg1Zs zVsFKd^S63XJi?8=D;j4mO6GH_=+viNLlaHx?S0|-=gtk7d}C zE?dY1tG#=hBf904vu-NAh8xTqEW%hBEWuj@{-ps&o&OSfCxc8MOUE~QYURbqYb`(w zrWK*pdHrT-|9j!#?WXKZw@vJ~J#)&w{rjaNrNtRNa%4R~FdzdN=fGv!w%%=INih89^Ur^D+iE)sgmTx_?YYEdxz$?e}+&!FiC%c#Bj9mNf zfM!Y-Zbrjw^XKp0w`OF$>$l7&@9Fj{a7u@VH6J@xnfLZz?A!#p+hFIuhgM9KQ|w$PtMA5xPo?{2q>J!1k>icW?H(G9C8^#=B24#daLpYLK0Ztq65mxAv030g)= z&8-8TMz-%b77>Oe3G|{K>`Pac>-y2Ni+j!6`IArR#3-vh*xmlb40ES}7v`L~Ih zj!W64mc?CM4T~IXJt8BGNYeQM4n)0MfSitdjOYYRGFLlQbaZ;BJ$y`~SGp7?GNqLk z49S5q0ofo@q^>MPYs1s(%heyBqNDp%!zoXVgQ>6SQme!L2P#gZ4VFo#K6 zkZWFO{i)&8ft;U0;fP}#*o7Mn-e8QYt1;VHu+A1O0_*9yZ+ZLWE#^fo4Rhatif#Jz zQSTJd-9^)=wN~ID4oS+q(8>BFzNUjsOXCbY!dMV5=r6G^(3WsOS~LyyYDr=NrgT(% zR_r5w>QQ{Wgnctp-fG2)3pZPuE%OU3n53bIvInS1q_#W-zAOzo1*}5DnrD|sd2}_N zW|{i=^Tpx+0>$eA3PU=PydkLvWDs_vMud?Bd2<>ZX`y+~S$#6oJ%%vcUeG7vbuP@0 zI>O&6GzC=SyPul1K`V0njVweq#}51oh=EpUA-FL_{j6x$p$7K~6xkq3t0vUQb07p` zWqa$$GvRejRT5uUo;l?(UMqUk=!nS3Ael3WTc3jEDMc&#O$FYRFWR|4(0Z_9%RwgF z$2I-b$f@yrv*F@Am6SmqJ0mRM zygat-fY%_cagj0J_D{QWAv)8u3Z0E{#+JfDfI-%@=&L{m#QkyPNC@=n$`4lE(IRJO zXAAy_2MdK?Zf>qb+JaM}c#1AOQ+xYI0y#6+7&;qWp4nt&f;mTn7zg;hAckenjMW?x z(C#LboC#Y#=IFf0hMPC5w@`w28gq20(emgsN_3U-8)3XS)@7-kXug{%$>J)O$UPzH zGBcB3`FH8m&UH0I-BCF5^M^%ABhcddoat~U4$GIDhfmMx^?9#$M$+xGQ^OII{b1!w zk|!szl*yp9(+r1O$l1{7)9p2a=CE!b6OSM%lp{-}tyR(S<4{1d!l2RZt*jSe#;6CO<18^{@oMdHGgFbM z-R}KocI2Fkd;5R6+p1ZoZCCrRUg!0G)}*%^Ge;#Zs8hRCF>*;?e40{5PnZChsQ{Ef zCHDfcIvh@?)l<|O+2jsTTOmXKCRl>g{MS>j<)W%3I?xV)m|6+bN#LrZ-UhpO8m{`3 z?hXnjV`Q+mFpe_g`}apI(8@*b!P{nOgKAjaFjxG9B~gyU>$h$d*VU%g*@1W={k*c^ zVMD>;(MwSbp%J&9`>Pu(!c^<^s&{YRkS5099n?LZtlG80gZG-n>dBhr+$Kf4te$@@S%KUPit1GnYS!2nrgLF-e(9 zZpgYHs$@4y6a{v5bRM_Cx`02BEnHrdpn+u=2(Uvz;VO;jju2e9Cc}WMWD^m)VBN=_ zE}cvzITI%sT5Nr}$oj-eJ-K#rUK5 z?=>OxU`n{4X&nY^D*ER3!XkNFjg#5IiPX{k0UG4V-Ml#%Nd%qlXts!*UFiM^ZcaVC zFKOFgCPio@E&*C!;fI$j8H4VL+trTMSMy_bGwpmOKOWQM^RD9 z8N}X~LmvhZ03XDwO64iMyM~r1pDFBI$;)9+z}Rl5Lb|DD%jdDFx<2VIavXmviN96G z<#N!)Lt;tS4Ynr{t$bH`WMVl!Hh#Ls@s2`gzCzQ=sin=O2ImI?ED|Jc3lvXU_S4kj zrb=uAT2^LQi4~j76CfLOJ;S`JJp$8;e-8Rq_P(Ef?>DbYUmjL6h^n8Fp&giAZ3JLW zBT8+E{ZU54;<}_de!_W87prYzavT{*3oWfai?;+fhsM!p+0vW&5QsBb#v);cSTZ#V zJf2@1^{z+D#^Ut{Q+h=l1+7Cf1<0rBZ+fN+K=DDPOm1vZ&=|0%U^;Uw4q<(PL4C@J zzI6HWuleqEMnI)YXe!`5o9>u+%v(>1R*Pm{#$-~~(anDS`V~WYJd^9CotdLp=CCIp zM3{F#v9*?@TZqScl4QhmwT0+y1#p9QvUF|VPFrv6fK1|b22SgwsAya3I?nQ~pSAIi z1`2|hvV)qV4g_HbI+QtoG7W;+gkXj7lBi1T&6E5ACCRi$(noA3TZJE@w2(F&!$0&U zzK!v^u~P#qf?AfR1lPu)59J()rK|x*yt3>~4+&hF82{`~$|3_cLBZ=GQX8{K5a;b> zN;S7XKaZ$c1%uVT@uz3(9-rgjR%%${yHa>}jDzcdE5${%aibwfii*x5g2$kfhqZSV z{+GcBgga$Wr2uKsLhu>&xNLcOYCE*k9KFs(yxV8=`%|MwkB%hJQ7u1X{QTJY?y&0n zd=aN}f5X{7W==HGkf1ZSw^R*gH*r15W4PGs_9)lj;k^C+ps|DzTksi(OTfRcg)W4+ z73RO59kn&sj_HHMf9`W2*Ob-gIA!T8&!vqMEPyalK>Rp5X4bRx zBceQ&Fh*1?o)f!0{PHFG)!tn#?**%I<%6}G(aWR2;N$+6kudC^h*fFPFBlN{l)_tZ zB1AAiamWB97Xt~GS47gJaPKBv2)qH`8N4qY;6Le56_&x$p;7g8f^Gr03sCb)$8}+wp+wE;`KqN9v3lM z8mA2#C`(^Z_=|v%CMXtyj^v)+No}8B-KpXBe$u>)GjOdFbK$Y%h!-k|J9lQEpID!H zSVOUSQ#Och3?Y<)93@;$a6^d6PTOp=yMHaZu@CTCRX(%o5v!kLrEu*-8FqH^6S^ig6ew0Jrnb0qKbvzPkI~sOvq-1YI>mhz|E0YRup1rraT(O)5R>t zc-!*Pgl0if_#Lw8!>S)h2Izkd1Fdm&`*&4S`k{u=qx$xlZ#qVE&A0hB^*XCx{>;Yq z!@%7+LI2(@L-r!;mYNuE#)mfENL*3a0pXkk(5IO?w!S!^)9{a1Zr-|e5QtAEW~^f> z30SEt@46DJx;V~>E=JCe%TkrE#Zc66mDdAj*Q9>S`SlAQy$s((@W)k>6n3v*=`Cdj zj4encqn^{3TLZa64GAHFEQ^FHU#<{3FRp~r z=6g4{Ug*{GQy0~9hEsLwGY=Wi+K0;lP%D8PQ8<#!SpQ)|h7^RE)@v5MEMP%2TwaEx00RA%ow?~(|c~3e11^qi<^$1vx7#xf36x3kbdKx z_Q00AcG-R#xBJtTA7)eB3+fFgfs7%X(0_Dl>Si)51~(IKYVK4~ST!-Y=KiFa`R?uwioa? zUEohS^#eAvn#yGJYil? zE0#kh6C!p4e!7&r^Kly6)hOWEcOf;%v>Lg5fSNn#%1)}5?d-W7bSWpBDCH`LT%Ah( ztdHOBRu4W|tElS^obFdw>!`D1hj&(XMNII#s5!+oz9uHY#Cn?C3@y`z|amE`Z%g|d?G|M>XEfBxBD zUglo6kqFzKps8KBrM#zxx8zz`$S_S^k|9B5vp(4ccQx80iVf!<^-h4b@7kp*ncY0? z5zzj8S?Mfr=#^BYf+4Wd9}=cQ=;qazp>rF(GQi&~RyqNh0AMJba?1p?Awz=#@L^h7 z%&Wa$Ml2p&S@E!@s-Q6bvc3P9_YV@)mpu3Q{*1AhwdiZ=VKg(7oz@*cSu>+sApDjYadR9@60k0+XACrflqIHy zx>G4=`r7_Gi+Fi5CZW-|Ib=R0IL~d0KvXO=sDD#VplXsxPme*a8New3M*xaT?;_K* z7-MtO<(~(|E2q(t2r`Y*3=gLnwFdXjM8;PVUMiJ1f@J^4MfLPz5Mw1rE)5*>`QrH| z-6kf!u8J;DRPEHve{V^2kNTbs8*1wBuZgx#O1wY!=gT#w{jsyQ3IEsXft`SW$So>( zz$3}3K^;pq#W@aE#*1}WIrC~z*Z>oj9%EIXP{z*U5Ei@!075zx$1le0;>x`?*|SLr z8$RUgLxwVB+SL8A5sk$o#u)UVIvBNa=X^Ik zW^a#jaj8nbP}aLo>r6t1RT?#a@O+}m^5r^bEL$yn)>swSjeq58|QMHAUDQ5aDr$$B8KUVraDM<$xjW%z~o3frxTb(DeknTT|!aCry@uR{i z7ia7Q?Op?jjBZ6Az38I|w?92uiTW~Jg%q>iG>^w4?RzZ-07|+w8S@LcI8TtHQAT%x zcCd2j80>(65ydbQ6)oX1cPl1KBKb?itV!`V7GzQZG+X*65C=&li3pna;9Bq-&c&bD zLj^4Zi%Vvognc6s+R{GZVc^SEC37RKo7ul~cpP+W$VvLUz@?9ade2hO(J9ch$VX?z zU71Ri4h6H|(D+AL5p(WG=0EuU?6Te1;9(29hw9ZEc%ztwMQKw+?qTxh&%03@@WMwk zQZ^~++&Pl4(GSJq-gR4J&BHxXdVr zRRuPC&{~b#`z6{RJ2HmI0!8fqcFBfU@5t? zzUo`aT5O(`-N?P>*Soosmv*0cSh17a*`=3U9F9%>@v}mPnxX+;g8mYkb~Uj;pb>JO z(NoK$p}Q7VWAB|pT6Xkk2hlzf0YpfO*ubI5B>w=_y3@J&FxIdu5=^ek(8k>Ob1j@?YjL#wefSBN3m(fI` z@-z>=b16B+dGN~d;nR0ea{0CDIYSii=y1F9(nOdTM;aO{)Q4k9>3C{ZS@6aUjo0Mt zQz!d5BkOF!<6%Qo3O_72J8E(r9o?>t(QM+Rsyyt{#jnQ$lqKR5Q@2KBpfZT_`u*XRqVj44#N1g=aTcimp+tZDToq>>n)x*-uD@*?HKhaCX> zgfwAG2w+GLP2BMEGsaHqM{XX5)B9kbkrQ?Nvwydmbk!r*!aE=Li(|lUFb4ykF+uoD)Z7ZE-MYRhF1%q`Om{kw{j-PBO`TCsP z-~mFn@co<9#Zg4p)vTWN-cawpLcIUO+iQ*l?D8EosEbB*b$~5!vV1+%B{VsikZv*< z*A`hm+nw!`H=y05@q<;Hv4v!iHXmLlC=s2kZEP$_h;Ea1B^Q(SF?U6QjnD7jEBc|W zTSJa3hIqL(owH9L#1ptj?ChgJ{a&v1H89$-soWkt(4)DIQC)!oAAwcH0gjI1;FaTt zJ!%>AST8$#_~)DJA$AJU1~jG*TfkuMMg0$>1#d|f%3gr$+Q&CbM!o&=;avBXv+hjw zJ8ABt*?*Kun>IRbC7pE`1(4a#F4bE-FND86)jqM=P=W_%U{)1Tfy0%wksLgx@ROG zUTz1(4{-orE&y(4*Nr+`a$(?}yM^ev*94%C5pX)*pBNnk%0 z=G@pJ(tNDc`A!or0u6Fe!!t6epczs@*;GJgtciQImA}BiCZt{n`*c(AUf1%zKu)}& z#H1uoEb)}8Vul4J>KvHR5Y~Ba``;fL7;Q8gS(%z#I=`_KblBB? z+qaV?zZC`khmRlo_3s~oPyx=6|3Vtkk(YsO8d+({)xXQ;&P$F98`)fZ_xwoLw=|!B+S^d=;-p(#!(j!@rOL$U8jW-2Q zHn1aQ3W8|&glaX2GTykcsb|g2SyvQmtL-m-yZUWFfa$sEJwz>+R#&?bDA%7e3>iMJ zFA#W8h6z%fEizELu2#lvMAI+ad|_b*Tj@R+I$eqgW7xy+<_AhgcHGndzDD%^6tajU zpPH*{R@CM}2rj|W`Xe6yPfu$5pKSnw5EFN7YHEc`tIilLM8yIqEQVAxD*`1B9EjPt z4V#WZ>-huH=RQck5$>CiPZga?&h z?fK`|pc}WFHf?9tu6>j4-TS&38;==xf_VqridSH@_=u28qUQlI6^4>y=iuP7rSJN$ z2|4qnJm|qIt801T)4G1$m#7R!fvaKwRguEcW5-aV$p~<+^FPfy1z3JKZVa3)?s#P9 z;zPobEUA8sPI-k>lz~|XpG3e^x^@b>r@oaH{5QhfF1{K5A3*Tx(pxc$=}=i9w7gcB z)*$L+niEwx&X?#mMO9hNJ33solb#bjE@yv#g1o7RM&Q_>mV-ShxzoD4it79#m%7?5 zy(^*+X<)ICEFsheoRlOHfo{67hz1Ud&HH?LqrtbI<}OCgE)RDaEIVWDyvg(56*tUI z%EJMgmWM+_!RLwPMT>3XcD_rvCf;3T_n>%5xp7E?N}@ z{%qs_IF+WDKhAhboS5>+c#9y30;hA0f4;7#=?FH-KXRq;+tHB8Vjzp3iiHD*evZnR zV!Zq35j3#nmn`3;`i@Zj;b9WLN&$|3PvVjVfJH*CfE+6Jf2OX6_6c5dnhqVx z@TAq5_0iBgS>-gam(3-eLwAq75xqHDqIjhJ99#d>FcY)Mh?nk2U&0uofR7OMBd>_V znII<#PVU#QITui^`;cD0f7v8{xKYEVa_yQWQx)0KlIY3nM0>%{Qds$N*h4H3ER^+C zFQ9jgc0U!eFhM#fqIR`6{FlweP5G}{EUl=c$tEEw5SIvm|JAYqIkKfJbAtz1VfrfxuVQu@;9mU zgR5GZ@DO%L6kvk~x5hpkF=>YTiTfA2#)8l@Ut=GN@Zxtdwf{suW&_J|01`RXt3cu7 zKkQ_2>_d+u_h`|ol@IoEPK6Ikf^dCE_`Fn(HVH}&PdjYLd+oY!pU0Jc&x69k{~R0k zPhf+$p2{z_aCga7$giB0%ZA2N?jKCeUlZh|)zH!-A zbilh)Ya%QpDGQ8SH!y*lnjtlN`HHAL@AD*Oe1g z>v=kTEK`2BZhhujQqzI6)8HGRbXs#ga)k4Z_Z~eeLk#g-!9tf-MNyX^3AhjSlX`i9 z62f&X8W`Wf;Un^Hn9ND3DsZ^=b_Ro}>Z-o@c3SqC&vVP+Lx=iO zr2?ZO?oBz6L3to81o!y*rFff+O)^7E-`wf_68DkP5kVYhz;gQ{#IFxRONn(7a6>J*FUXFZt^0 z>#Iv%tmtV*MK){DCqcta(`B;<5`pck%$=<9LV~CNdJ2)hZs%Ou39YyTtH~Pt)1ZpR z={r^piwHe8-p}8(^}@%hI=y-idb%_=)(kD4nRQGb?`Hp8P}c9>y?I@2eqA3hW&^G) zDXJh+uS$Or$I5W3OnFGEb949dhn>86f+EHD^z>W^n0)t5I=#S&5!XyiO?51feHZq1VwcfYA=L~k=Cy-PZmDO2|Tg?z@0*@o<88xcgU$$iq`n5fwof6Ayl z_pANPnFmS#I65nG!$ksST8ZHRD+&74?Q}s?X3y@9{mv;Srok!I%OwZGeHdDWQ51YQn?gDnCKPc)adfGbhntzkWaau??T->VIeB1LwQbvu3`>J9O7IG7 zku@vCx{n+M(k#i8+}KwU+EY#aLu;C4-!Wn@i?oZyRbp?(dyGj zjA-8T@ezm2K{l%bY;vNuZ|`=eTfe4uGu2nrSC7?uV&K=(kIdfmJE%9hQ08Vid0QT007Q8&`g4^e*h1owhA1x9S@TVB}P6TNo zJ5X#+-n#}iN5zBB_N#PItyjCw3l60fdR$4XV698&7A&FdwNz23K#0qDT?$jHWzApo zwAz%FrEtl*`S;4lj}`s3>MdL5am!G>WtZ`TY_FXTNF%hy`u6I2zRfy5pi`DG#b&-< z4VttTg%!rISH1Ioec9a;c8R?f&uB3cJJmqyXvZ4ZJ>Ipc(6?!0#bzCxi>@)V^j7M9 zk3!{!TZ;VoYPdAHg%v4<&{)PJZlkGURG^_W%=b<%UXlIit=-AVe)N4Hx|!hPA~8Zo zrl3G5K{-Cvq%U8Zfn_q0gbHJO;m3mt>lCYx7|pe}*Q4Q7@6cfv!$oL5%(c~-mer2u zfUskL?TQt~+ULdxo1ET*eaWx|Y={?q7E(^m6km#F(LFD$7~E}sbw#~u1c*b{ep4a4 z(t{*eTkai>vk}Y@1TgD|t_@^`alg}->3r|07xUdBObt<>Cqb z30lju?dzCn(+u4>!0%|{`v}i^bajvayBqP#KcX7YR#(w1dZupM(BRsWjqBIzbnDiT zazg+q$}ireKU`_&zJ1m4(s^*)zV=yvV#twW$2!t{?+FM{#HdqH;mRWxktxTvhp(^l zK9{9d&(a^Q9IvfDV#bWtoRYw;kEtzD1gN2LBY&ABTy=@c7`QZG`sjaWTDnHw^+=w| zh?l+3Q@xZ!_9+`0+9qfuxepq2`pbE;b|I2S!6#E$_`>d@Sg+4qvY>IL{H#=S?myfq)G>%qio??}%I1|3Fbp>U0>5j%0=+Qs|DJ87=P^NcuClX+Get zn-}ADOynk9ja}4LDs4^%O&;fz(=usCt5FYqTO>Ty2tTJ0RoHNfb%!Z-b`d_yz~h~` z>yDuNg8NtB`A8S=?F0DfygO^ZyZ6ZZRcl0JaUDN4M#!$McaDa6bE5IhEUwsc_g38K zz-|_;6g~^b20_Nw;AEH%H?;q#>Oked zGiK_Vn&Yhd9Gumw^(JTM$^6n_3nef6kJIr#FSfT&K@+LQQV#_*%gM?*L0-fTiBrO3 z7ec*Ma(0H>KX!c{b@wwf^Ru@0o7Jm%+oOFw9jZ2jRF!Q%e)9Ed%9TnWz9&c|hjeIm zWmd0tL`-dgf!P-rSR7WKk`kk*u0lG-F;PzTYP}OjqXRXy6Z61KYT9eGS+qz!;n{?M zbTt!O*R8QlDkN#LBT4`iTV?8#ki*7#nL@^|BgBb{uapZpk&kuH9n(M%?J$ zBO^cW855MWsp=M9OI>7ZJ0h4FRl(bR;~Jnnu<#&uEACKXqlO0QV_62*amgRS4Oqjp zy$}xcZZ}Qz+=`ryhe<A81V61%1tq zX<9sxtgrs2XYc|p`!zb=sqbz)o5O1mk`AOUnL1;}8QP{4j*9RZjT07J$g0@TwPoX_ z5{j3dZNWQnLI*2rg+u!Tj@_EV_)aAS8RkHoIfdh|+o-3#oe`4d5OPAB9irQ|ZS#uH zxA*Fs96x*Tx=(zQcVK=?ad>bxk7YSPWMq?Wa|-)G_?(owUjsJA%mgE-;cmh(GJ3_} zAW80wsjGGIciQ>$%lUANeU$|R8yz3Kn@iB(UiY5ZvSm$hpmsENzU=#W&;U!TFPV#2 z+0?=YvWEr-^|mx80B6XWJJv;IWnqZx_fFQ|=NG)|O+VWL#czhV2SsAhj+vE1zDrGa zoq&z`)3h4?!Y}(ek=h>kGwA(_!KoiUOhp#a;;ha6GgukBnz&6M<-cKkib{89^2HeRP*437)0cs^V$qKN}U(W%f-bMPc=kYlis>=~Dvof4(n zxoe}o+RLhA%j0e76uzWvNU{reW!7O4Rs!T(!*p2S4#%$M5X_xylh;@E~fq#4`gK6ggTeWT9Uc%ae z_mU`ny946#3~F1u=R~&!*gYvCVc&;3Y{tf_s;7W#O0&}rmWO=#5>WrpL!EP%mQ;Ik zvdqNu&Id|CpiRHy2V+P`|M*uUS^LN-_j2!M|N7M;=tVbvPdntm4DCt;)jdlz9TmZ; z#~P27>#Y0sckqhKzUw}Nf=JbK?B@XPVOu2LFTb4fqJSf_XIUVCECwz8yo$&&|}xbA$r=dy1uT z`?EHE*RWr?^8TCiA&*#07OLi>@JGd;ZQFhwFKnZi(LnHd`qY5NhgEjJc)S9EeTl148os2M$EvGEc)-!yrO&eX~3;l{2NU8gMRCYw*u(}Sa^bDum!M_u`*?MT4>dv_f^ zTrs}rXJpUS)xcMa@J4_?gyMfH(La)1JPYOItLc8;^?%gg5!)n{cdEB|$&zFliV8n; z9rRPn@qNSM;wC<3=Pq23qwOh9W(wp=ki-N;`P4RXk5=)Ozh!2c@i{|yIP8ZdmRst^ z^wqoX;5^qQyW1aw%Ut0_+? zBs()F0`7vwx@dX#%s#ynH#j+sKpI3ph$jkcK}k-v4<8z9`TL>{+@&?V9UpsYRZ>jj zj{(ljbhQVx7_vdt&rhMKNa3XV>a`k!JXddMJ;-NI^5Kg#g_2JQMvSm*Ctpd$#|;05 z3Jj1!E6a#dm$@coYlWn_$~ww~TQyNQ)0Q4B49ty}RWN-y~0Y^6nu z{NnwV?ui}I?rzLsfY*3-w~S?Dh!^T-QNb*9Z`*6b>*1^T4l)G>p@=ZlpxGIjnTnnx zJZP2q)UB1mCF*&-{D9Am_4 zh`!6`7|kl1xgMhno=P*~Lh0f6k}t{O>GAA4*&$OW>dyCVU~^;=iUA#C;|_wbf0i0y3LwbbZEA7ITGjyfg@Y#d-1oppV{h7eEDH z!T4bP3FSWbj4!(w0wD!9xq8hr_oJu3$-=D$UeSR~Hf@rLc4G0!c<8$Z&4v&d$;oRI zA5R>y@2}jJ?E;=9l{!0AqF31A=!;ZPeaO%{%3aZ#j#FFk#6YRxtJQb&pdZ7S#}>@J z-1UrSCkaI>2^wZ~h((!8!mhEALQty|~LJvLWWE)P*w^V?k5 zXv%Ku)+;e*pjduXJ5X{%2|YV$+)Z`OHi~uxo+tf^&E&%ketATP0OQHg$}_ z!NynIq87D_OFTJBty6zY;Z3SY*6z9zrjj-+tN4{^SWZ~up2{i1tVzxXY&av4soY%i z81uq??m)R$!r?vzaGCiDQ;Cf`2B5lhMXX0`U8WQL({-%=+$f<79&X!SyaTK~u6K(n zuiBgun$Jk>+XH6H9onCL$fvHW47|_c< zOqI3-)NtaRhX;k!jwla0azvjSlf)mXzX7o=CQR4~GQSjt^tJwJpW=1#SE7&mJ=@O3?vZ5RDRwD>)Dw>9HYe7EWH@cIEQrp|A=)NLt}LB{Icq6su%9<~(ft zx_B30!_JW3mxNbdYUZi?`)LMOR>htgp{nltt5&Wa6b?R6>nBg0st+f}UH6zQL;~n{ zV=R%V;^BFZ?#OqMd7i(@~N}a z6h^QN5YPBi@nygs;40XPt4&5>fy0yI$Ce$9)DxAKB-i(|dpxeZ%U5&NdP@?=`YL%)vdc&{N<2AnI9EmM zL5m_`mgx9?8#b`0Y2_cES*ZCdE6WxhmHs)Fx)emhlfDs8X zLj7|8XEEy3rka|XB+XUdX)sQsi*tg8?JF(qK6wdPl$8e9@A#gnsqs90Hflr}C(ga? zC10HHNbmtXZloN?fKy{01S<#h9yEBcOd1u<1?7m$AmAMIdiC=whLZHPcL=9xz~L`R z1k{xPh2!Q0we4H~P`%?9yFU3^SU|)ns4BBu=b2O5@#fJBZ%6$9fa;DuXSk*7p$6w1 zA=l!N-w3$GnW5XKPc!R2Z6qj(v%KNOEp%f#Q1@siAEPKg37<@zWJ|@!!79mz?+#&})Qcv(@WbWLH@RH_OUVoZ9*ri%Hzyl;q+r0r@8= z0;xC<$w{XT;t8ag9r70|5 zK0;f)#(GZU>R&eZ%hCqa^NL+3)Bd;+MuH1)rVA_s;wd;Mp1knr&%tkdE-egr^)nQy z0b4hH^$;mT@L=eW%FS2g1XrYt03YT5I6Aip)@5eckd<4|p{Qre##0a=A-L*{=#X+d z3-lkr1~0OB9q}=a+n=}aiDQ~Y9NO=`TPmIKm#Xmq*^nB_cWc|7sB81_>GS8K=nZ9Y zl8d>fvpUEnkiF!na(5~FKFki@-J4;@VNo%4&8(wUr_WSE9opilhr<2XlkfI1)TZGe^699Uz;(iR?<% zwu-uDNZ-u(_Ed+Qb0ewiATJPJwE(r*%^ELDtXb6I_jjdIaupImcUfRVh71{(`*c8J zf+Ii8-*FPt9pOE!o$Z76GI&810+*~!fww2`*KJk$G{JFF)78~O0Qf%L>mFb{pkMQ) zRhu_$_q*IO1TaTlE@OB^dCOosRMjXCwsPzuVP*)lU%f!nw0R%=A7%*B3->ZcsO#m+ zW4{)zW~QR-bwqC%oJi=)t}-o38XJZTSsV* zAeWdcOBR_N(e&cNQg^dD{wZRblDC--<5k2jB-#}Q9n#Y9Cp|ca@H=qIi94P%rSBg@ zS%z1?o#Hf>@n~$vHE0bx7(1&YFUdSpp9@n?W6u3X&3qr8GOpg<1&KCoXk+B?qF^93 z1wD!yhhkwu>IjoUjmAFOx+pV<9#Uq24`*+E--jc)OgM;Sb`oiflX5IFdKzqK(bzL` zqvu)u=Jj4CG(Tt~D_y=7U@$#L{Zhev^p%AhqWbiwmMgZnLh+H(7q+*((SvJS(hJLUY!tNph1+alX{ zebO)9YIx78Z~3p4Yf&3f=8a`nQ_*nXo&E4tn za>O`BS9B9O7)|2uw3tqS1|ro5!IdD0)pxA7RZErqY)E?r2@8y=t?Vh6DSS8YnIq=@ zlP4;?>RGh#46}Y?P}EPkJzhgUq>{R9EzlCQwxX#dH&Ay<)TgvI)nE3RgYfoSn%qV9 zq>W7{=;I-4L^bh-hQbp~3YF}ioraC4)^zSSWnao+3@$syeo~d}jy3xc#+J9cR zQIJ(ZK(c%_ns<}7P-y>=`2 zJLz1yL|wCoH3zTIga)|3fFea_qwW_xZ>Hb6b*nSn5o<%< z4LGk`#rHPwJ-XW33ZVHlKT1M;{in~|*^=-krB$C5osFls<>b8a2-CA&@u_D;Z>R-; z_SG18QS}2v!jVz($#u1`2D`$>pI7A9OrS0W}O5|Vo_C9y+JpK z?8$i9GLNkK(70Xp$Qi_55k4eia)d^qZ?uPAguK-|CNVQVH`!o*rv&G3p&cJTnRYVx z#Aw;#3&AONn?fy{#vXg&ON^y#$53lG9TZ3Q8{uA2PC8ag;cmkCo0Q@xEB5kOsAFY0 z9pVV^kx*m`t4<6Nj>n59XZtjpTmo$<%)q%M0;9npLws!N$<#p#tjl@lJ@}={Gjco= zSB!4eF$pE6l8|xq=h}h<|93tp4E%Q$wdyM5wA+cO1lgnl{+q&YmHBX?>JC(!azN0W z*pzTOxm_WySF%RT_GsU3?&T+k`}aF>`#=W+JN4tEW#u}w+py7n%HLrlMx;}&I%9>z zC1MkvIMxE*;PTo#I7q$rir*j`I@PQ{!6@$cEQXP^Nq@atd#J{`Y;6Y{I%M*1B4y!;H(J)kO4&oIj4Ep}c} zdWw5NdBmwT$8W8<1|1{zCh7fNry8BX7PjpM;uYR0GlmMbQ4>Z zy*f%(1Tyj{(jpiXeHxNHZ+zgH7pW?XO%i-9`iXtaC1V@X`h4=QiIEsqt zRNBHzjX|^BPrjf~SH;QET} z0?T1Eb7onXd0p*v&za`tg2qNn@88E7sO}q02o};}clObti~BA3@vrhutXgLB52>^? z1IJ4P3lkzGlu2q+)vX^|&#$@=GiX7{SqM~GE(Xf9hA+D>mR9pw(2%M@hKQKUNwN)i zRh;_|dtsqC5cWXS!mjmINL41aCrCoD|22!W+asNq7ckqytFub zpsP8lE5XCxgS9?W^@86P_C*MsV1!*OF8t0scp|7opz?+$0!#&~2CYKyA%)+m$YJ~& zm)z^Zoe@%g5~EAgKBDt>M&ZCLpg@y0Z{MEA2Nh1+titIE<8T}S5yPWhI3vR9Q!^>{ z`KaQOQ9NdW9dpA)e@QuY11})>q9WFIh=CL9WU!X12YCxY^%z`dX}UBbREA-VX&eC^ znHPSHK90|_5C262Mp4#1svNRN$Rma?Yd8Cp#0rPqHCqfUI#>Pc8Kd{%lljIChJqRv zUMTqa>;=0pcsZy=1D=mlx3`OJGMnbn-XW>)2{>8p$j zm^Z~LRSp+(2K@yix1IYvCWzkL_A|$}kIl&Sx+H5oS>|NeZedK;N9Z7q#PDMsp@6Xr z>A^FwzP-9L2-JzEJzI*87(rrERv;JO#>?}_a*yZK?H7emUfckg=Aa*N4HG!}O2GYt5s!;b|pm@i6R=3P>NN$Cy( zDOPy95AS+yo{;QP=pU7>_AO^Xc1BCcfY_Dup4r=r{(_G>A>@gbT zAhy0(afQZ+Sj7M?ZG{Bu7HD>E=2+5naz41C62pdF^XxiWrMdlj{n651)sMT(o&B{k zsVz`w%cA{p7!k<@;qbYK4^>Uxtp6kV^rP)(lI?b8Bia}4`qLSB3!q3wLNqyor*keV zN?L#Be%>N}EkJ)Dy@)6dK|pXgk~#LGhu0&vTVn~*fl6sghe37|t9x{qc5#17%DL}7 z71R%Gao3qGeRP=8SUb$X-D0_~q?)e;bPnOcyEDIn>u_>_^y|;u(&UP5p$&9rZefgsKF0N}Q>I76d zDpFzgiKZ770wt|=(5{k2vpw6lE2>?qF=!cVf|kJVQYBjg2CxN!`Dh7O^VbGKlfmVS*VWz4EMuOSe#pW8?(;pJSX8V|meO zYKyeBO@Nh##9^!Sed-4~lqipMoxQ8Q#=8L{1`RUYv11%_16_OcXip%+65r%kUe>Vz zN!|l>^b!8R4U(&6DV-=@5IGz^dQ^t1%80CDzi6F9fTtnZ$@}gEV6LL4oxAQ1*PZqz z=R=;&ks6H=9$ub5UiamuX$&6Rfkp+5+8%%%h>x3&+5LzRNi|;|wXSC`Z-0_HaB1$pk(?nZe+3-*~NL7prykXol^|Dxm>2x znQzZ5VHNw-A_WMgYU<0n8IqOR!0tI1#F*0v#j!bY5<#B#yS;6}is`r8UayB)gt|XS z_C(%u7=2+mGD8$zgBT^O-_;s1>6lh~0Ih8ZHK;oJ4L>#${F?s8f@yT&S&3EMMX^Mc zt|A7zpyouyWH^Oge2`Xj-?2D~m! zia}%-f_p@;6ipDhjJ?y@BZaGeTXzGP7ef?w9)Ej~I8X~jF;&{g^=EC<%r_rDHsn`_ z-i^E+>R4>ruP8&^#wPp6OTCe$=QnncZf6c5jpQrfTN!^gCNi?>0bDmz1v4$AA05ejL8e<%t&j$U2WVop9lzz$R`pY0{4KnLPkOC>8YvG2(|_!biSsb!AUhKdplAd zxyo;8Cjk^|!VU%=5N2PZwH37?NkDkeQy8|xiiVgsdXR$D5k0Y5gCdShZG;99IvUNN zK$jSVpr6>CwxY#S>+S;&D6t|6`w1+KEu-nJaloGxB zzIgU5nFj*?Dk>3Z0_Ly8eq6rHe*fx@4Su(8UotZ@eHPkLzt#H9t;QtZSqBG8`}{~- zBpUVm_XVIuFk$$42Fs6$X*a+={rlOjE!zyv2H3k9Q8AiEF;c;TvBz{DWGgw;Y5&J7 zGtGx7oiIpQPOoSh_#gTcT*ysiHB(R6d0>8~fjR;R2+~pTG79Dx`X+iF#U?bAEd6JiimkR3w0=-|*F*!KW6Wir$OkP`9G zhy%;Bb#G~neKVt?uvh%(z`&l{JNMx;>G!pMu&~yybLW`ignRcua8<;H2BuX3p*z!U zkO4$f$_T)$*5;XCtNn!25EErW#YiD2MeauvAqV{LL%_0DziV0F>aL+JDZ>b}k^7$PrYvP2gYYmF&j`|hlSzxSRbfCMgCoYGBcRE~d0Om*;kMw@D@;uR zB=9hirFjxC1K&io%Z#C2pIyyBe&g)ybr885pd8NeBMuxq7=@wLTq-f-JV(cEDwqWl z8ja)p9_q1A{ihzu7}fjkpV=n!F?wexr61QB78Xyo>B0v~EYT*QaF)w_zgvfI#Pcwl zQKPkR>rpIFLtq8G`kw@g3Wv*iIQ&oJ<=>ank2yMNPx3nBnAU+Gh>EMTnw3D&y3lr;|cFaN$DHN|SgF9Wo-Lnvu@VA;SHrTD^XsRg}% z^5en%`yAb%N3D(P`AWii88<9ptlLjv(zPN6JifO-hW~b%08jY0)az12+{EJKcRaN)jaT@SEL(^^DuKT?nBY?|A|NjhEDO}`DVXlElr-_1>B6?KE_YoV? z`GQ!U%pe>@k)yH^u$IzBUw|~x4~k9oMN!&~V&$CE)~7Gq`KQ1dk*p9c~ChF>X@0ZJt$X`lCe0d@{e5`k< zQgX?^@XC`!d%+mNtMTT9g*?*;0^EZ5BJPfAt<@okOA$RNQ+gvQ&;+Dhw(PUo&Sa0* zUp^=HQ64{gOr`gw7llc!?ROy~|In#Xn(*hm#0QHJ#{C2=iw*{gM6oNKp%AY#&y%0% z-iuogOUTl6A2w4_jP{H7=_3V~)vBISvPJBKV~xsk7s&qLX2TIj$}ZZ5$GDpRqK;hoo{nbctPR>+D|dF3K+-xzd_3)5<5iSuPIHP zt4pfAZ4$hFWT$l=zHXhwvSo8M-<+Fv?%h+XBfTZ&&Uip4N8hRe?5n57goq#YzA*E* zXSzCmX1{NiBi20m{KJx#ja2c~X&*O21m@kl0kExqec$|2+5XS!xmSwQ>nkR+ipReA zS+D-Noor{)QZrbAwpg%y+;15Pv1b-9KS*M+l$;1EcoXO441{dO8A}e0*Xov4$%;iu z9mLcz`9hF9dVx&@^32~$o=hmz*s8X3C##FZCN)yWUW!=H#-BQfL{i?r?*%^nRcZgl z$*J3Q0x4w))Fd`BeurH_XNlwJT}3!%z@39td*$e(DbF@J^jB2tqB^xp{zLh=cu9wJ zED47#Zl~P)-wt(12jR0Uaw94puz9*)!R|2yCOj`Slf0@|52y0|Kga?MgNKjAPlghj z?08_n_r_UEr#8)6sSq7~E~0(A>^|OmrB@fJ==B0z9XNET3H*+9J4pibNXSxn7sG+w ziH@BG;Vpl&&zw(lbQ~c|s594bAOK_Rp<#Sp6z?Ih!sF2I4LRV z?!bVI_f78Kbz#;D+{%XOjvT2tei45s8b3&y$+ADHrc1l4e7vpUl&Q9QxQgC;HJc?% zO2OfU3Ya!&#Yt+~3shbQ%HO0u{!+5)|Fr&F|hTElV`-u520=W2QA^=E~L6<2(~f zw+`x<;{b1xL(le%`DosnKYtrR4x>1M;0Fa)9=CV!@Orh2wn*rEUY(x2XwPOktX!;A z3(sp@&(xwP3z67*&*bgfm#1`Hua^T+%`-KXTMQ{vUR|x;WuGxqJR;oA#pGgZX{vWh zVR;naIF3tA)fzfsES6}#Z|+=u`KwtDScefin|?$O+i-+ zOq0Y*^O+~1DL&8l%i%(r;u}NL^f50l7Y`U?$dt;tKVQ|qE*u?;@Jpza!*y33kd_}e zdh~g6*tJZZ4c&U_?HXt$xiefk*7nuQVLm_7mHQzxJO?sMn|5Eif#Nut{g89u!fwx9 zom{lwbU2E?SwoX*J{Ur6{1l2N8b^as0H%qK4EY$N6SYV%5adVCugQz;c_F;_xzm&VryoK^*Qu|0aoNo7 z-Hhfh)DAH$^KAxx55!%-68I5*cNVh_JR@;@$Ouhg*Q?7+CjmwMBy(y*%=#-OU}Kn= zwSKjK$2%L#PINdNocwZx&zg`zK39j%oum1$h>5$-v>@FcWm-UGq6t$L@weZ-f1gXN zFoi5%kpe6m3Ebu{qs%L{ovhfw7dpuVuCbP#Yv49LSFKz*hhBj6MYN;MHAd>yvEL5zwU6@gx)-&V8eE$JKDWRPY;m@QXSNI>csk|tx<1e zkc{Vu!mp+{LsTsg*tTX9qtW011axI zht^|p#LGW!*gMMg{sCK{5sm~&S+c9p{4zRcL8BBs;eCL(MU7+h%{CwOYgOtzd&;O^yJ3B$@%xrB@G$;uRfl84X*NqO*g_;mplSh zy?o=w&Xk&<=*v_0ceTnpsT-E(mDE=%88r_mtrdSk%vBqmRV0ak)Z@9c8y<%)B+cz* z&Jj(m3j9)YWX|Y;yMO$c?A0puuuXroWbCNw^47%^Y{K0IPWmfZjYdRJi_muhr^D3( zh2&oU9+c%5m#rr}Fhmm!^2Z2J7T)Ze%q=Y|=XOdzm|t|qhgn^rYh=eGy;C>7{9)E^ zGvd2{Yud*R<952a3n}U7vvimb z7>sKG#o;_02j46j%Zc{15&cqoY3VFvd>MSNQ#H)|&BEjOEX_wFMxwyJ$_yiw3roGmEnTo+8eV?q zsjW?e?J4ER6o;Rs{LYzL_)l^c8|eLPEFe);lcB_E9E6bIRgL2xv}O;d|^Ylu5%Rw{OFFDpA!QI=Q11G~r# z6l&>4kDJF*k4cgp`pfXn7{&j*v(-Iea0Qch{%H3Jdg0H{(aOYWZl-NNR@xu(>B*S-@VmT$aw6^Z%n~x7FyY=W*_vwvT&=ALD zw=Ujp{4{)|#GDA#N%`3WkLwNF64viFFd#^YR7=-_bZxqT=0GwBoPAUm`;+!HDke$afgipms3C%J1;~xvMw$@CttAQ(aII4D$T^YQ;@z z;X?>uW`Nqgd269|K;>SFQWm~;eDrLgXJy{+>n=Nr#!t-6(MEN-^n6wIv6*IFyY^iC zQRiZk)s|{9*C3)EREqzLl5R|6fPjBuZZ2_4G9p7Vz0~jDVv!uS6NZ0d>UAR>20&mY1qS#E9RtE6u81aG4kCU| zv#>6rafu!T8(xq9_u;HViqR2w9IGKs04Cy#zFIdkWK-#`I2&>hc(MOb0L& z&yW&;6dD;FT~bmpe%nAr)lPRGOueTuQRTyfUe*bL{y{zi7lH(nvNce4K`zicNJnJu zBh2<3zH~no1`aneq_$4gqIW{h5!gjwl@JAZ7#oYFH7!eFS%UFdFIA{KF zAd51(Ew*F`PM9Jdc(VC~MGxg#g>FNESm^!E0f|wM!xy!uhY+$hJaT}MX4VJ9?L4B9 z;^gEVq0Vy$Ypj>3s%f`vo3gvI^vzokqZI9e`XO8L9V78|L82{a587cUPM=A$1@FH; zevX*j;IYbe>Lj)rfJ0St0mY76>m<)9;9@G>^bCY-6!<^@Xw*HpLkO`H8+#N0B@x#s z)O!!Vxj!sS^3^M=SjsygOu?kZhdP=vSg|XfQ37Y?#0$$Mel*Oz5A7B|oeM7segKEJ zg6SUiEl8Yvb+oZ^bjRgwDN$yjXoh9=BNPZf+yl&hdxJx!^3z9c{1m6Qqc*>xsnxwG zXF%jx!`iLJQdI@+$zPtl^j5I{+B9LIEg)`ska{`-Wud_Yy`a5Zfkt0>id&p(ZfdX{ zSb~}swB}O+!dzYfb5*z*sbLQxX62s-_U*{`tNvNkvE)EPzuQmP`X4U z{k_B-G^o(iV$n+T$6T$uO?o3+tAB~hP02uyBV-laap4auWGJHL9W%zj!lL}%Nq7Hw z_EJ(se==EI#w2(*p}l)~>Z41)SCNIOW)fn89JqiW=#LfI6i@4P2q#0I&q6MOUg|EdSFk579Ec?apG0G?9)u@q})#LLsp_A zd#k#EI^*R(oy!g;M?F#n04c7<+xDl@1sQ}unQ5H&_biL6`N=P=cAm~ z$?P)FX?NXD7NcXY2tAdNqs!ur3els$1&i$`R86=nx94y(t0%nS2-b8W1h<|^!`W&x zji?T*F7zX6L9&3|r~zcSnL@U4;Cb7c%9l^hP0DF$lMMGLlwRCjvB%Q6DLu~b?^9u8 za;|IW@mX6Ov@ju8F}eWj*5q-r~dIc<9X&njQ+BVmtWfyx|Ln4T%YIE_DtzV?56i(^XaG+(ugd? zj(1%70W+tzHIFuuqni`!9LsJWZHaQR@NK8x(*0@R+e?NLQPC+=TP3|30`es-y{~O> za=O4?K+yNw6r4hO#)7PmA5ReUs1ca#S~tzJ6vySF&3;bCXw-&Ht|)$V*{PY%w?OULO{!m(P`S*J<9oP$!7VX+{ZXBowYdJm)pWzwpZ*lFNYtey#l;<6c zj3R9k#--m!z$51QsToONz$jSS;VH!mmq1ic;7%g$oS&iK+1juMFpVYXe6~HrHwm#m zj!Vv(-DrSpA;(^`=0_Kc)S8uzWgo^;GEEOsvj8qcXeO3+Fc^YI1)GU0Zsea=lUJMA z&DNvGyQ}wX>`Tn8A1XJuL_a#(bob9hd2mg!>_>zNI%=(n6IHyK-UF;t#mMe;q@mA! zzwS|;PDs2ct%?%6@z7kcS>y~gKgb1-qzhz=n~dSOiqq+rhJ=~(BxdX#0b-RG5yDuW~4;IGzT=6aF=s?jV0saJhR70=4VQ6Km5(t zE6v~dEF&YQ5Q2%pdWM!3!$9zZeWk@gb8jDQ)?{D(V3A$4!io@!f!?>&5Y?iHn%%Pvb)z7Dy7NaU&4Z%$&2Z8A2?{$%W>C@z9|`=b;h5OF!Pecx1C! zG((Wl+$#)ZNP5EBjk!90sgMpWU!J{gOIYILpbdtx@845Gf)vkLyx5;k17kFLoIgN~ zVy6PK+1hS>ly7Zvd%tb7_kt_-+2)PJ0(R#*j>>t>o9#;@7op@n~V2PZ`WC4;H3ri#x~zR z<4Q>kufnxj7yMMFi|T&yrz>&iyp61YI1dMmSMm|2=ct>xasuyTjS^B~VjlC{owHPj z$D?Yd4JNHJ@<%{n6{jL{teuK&2kyKA9mbb{-IA7MM_R7KXS!-iQz~P;>hpZy#!oMv znOY~=8t;mCEgN=db=B$mxhJHj+ScR|r}(D4G3pb`NwvMP7lX1CdqdbxG1~QmO~rT> zT}jUa_At1&GxcBKfGLc6`7>1J&On!~_{P;>t#t2>U1W9THNC)PUEVE5wg{zR(p1P|b{D?3QI1q&j+0L!vI2yx6Nz`|E8- zXj_1g+B*d$X7$+^+y){P-%^w;`Ka;N5dUV-AS;|Qk~~|KSw2jX?3+~D%Pu*2cetWl z)?Sn5>Y(t?> zN;N*`OS<%O)cZq{r`MUwbU(xYiEe+_)k!#L#SPCEH{nz>Y?%09xUi05D;#AThwE@gtccK|dt0@ZgLc4etczcg(CI+WTUNK0 zxBczphFG9@P;GU!CUc&2Q&4WE8hV%^O zi6AFEEELmAmx`Oll_DJRFHy(R`dWNE`pwX@!1IL1XdH)moQP2wtIptb^VeB=D@j|B znC7vsJa2L(F}ZT@qev@MRLTBIRzvS^7~<8}CT8Ik;Uvp!j9A?){1%*?W@9sf>ct-O ze`E+Vv>)lNY&Y~tm6i}sunI+)sWeJ&VVg;n3;|@5W}e~Kk{wz|Ux$Zf;F4>rnHdzt z=F$f{4hj7bNH*nrrI_*bmzX;CY2syb<4J>uq-4nZDacC2oX*=r?uLLZp;rG-9AV`T z=}#=BQV~iM_RGw5k#D$nrGor*s-3JLb&F|2A@1R zlNMlVbCnc&@bt{g*s}DaJGy;!Ctg!vVOY|K#74cz@WT_v5=>b!O_K;(>tNOP|SThGuDFrPKc)%C7nti8=; z)g{Q^F^WuO2QiXSvB?^U%dB`&0IdNUSYr1V$_Zr^6_zd1I6Nhr8~Vs(lkL}j8I&$R zwZ5HQLJPy1C&q2;jl&Xc4bw2sh?mthHD9slNspK6I4IE>R&eG~N4=CKK)Wv^V$IGD zo!n6^=GxF9L;7oK?nY=Pq_v<+)wQ+4=u#{f#GXDbr2mm7BbYlkzi9y+yx}PO5ALV==DR6e{2Y(Xb5BGJU6B^`#8(0B>QY$K05KlFf}7WG z)Tp^AZRZe^JBFFR{ncbS%?8tR#WQD&l>2n7R&UcZF*Mv)X;-HU!1mw%0i>%vxn0bc zE(Wrg&--15Qo|o3+%5?lUwDdLCfJPc`|!x)0n+XJFsa?i?2p-(#49q!LG-`Bf?4@e zI!!UVoBhCL)2J1xasnPloRYCHbBRrGL{yX4JFzdo)~jVZ!l7Y&MH5h8@uM%XI%-bd zuO81cdp%Aul(Wz`dbK{K-Mt{S&#sDJo=Yd35t2K38GxrdO2bp#!JjRG^gB;sldWMyP(^0#IlK6WgfL?|rY z?7UjWQXpH|#lOGf_I|6&`;~j$|Gs_Do^@Ayr4Nk>&!3_2d7&*P0!-3#R@4M_jK459 zORp|}E6V*PBTkjX+zQgYf2KU-WYPPvV*sZ_*N5AaSUm!9C27%|Z`anih`u?p*TsQ- zj@qrxLW%zoof;>Az%ogbI%lcq}k6b3rI!Go)SZnA+WMoEF8d>(aaLB6F%SH{)B|Y zv%!G<(zR)*#UOnwmxpNiy9<9q1h#WnjrEr?B;acEDdPGxIu`i#-Gt85ywHmo8u$#zk- zXJdh2MFc9Trw6q!7Pnseu6^(GD!reWu@rxOR!MzHg(q{J8T7V(ycAPWr0BiSDmln$E5sKb=XN*}jsvSxH0voS{t zT*}@Zg14uUF=SUOZIf`tq2xrYDGocr@o1|IDiE=RgF6M9_2*<^vma29kIMJrj7JVM zR?8U#K-51MZ5P}!2pAlgPyk~#QW?7}slJ_&(U^6L;cvUJ7^BXUzjv1RM;!siu z>zZAxzM)&8{M9nYldrF@kL#CIb6dk$J6Tsvj&H*cb!NY=S?_Dnze5kojxHq^ z@Se6(>XGx(;hqUN#bCtzRnwJgspvcP9`j72!Qy|r$KrmqPB&obTUYAMaBEC7tWK09>3 z#z47kW86E(Z-rNP|My!{TicJ+Ee!l9Kam*F-OW^cL!=`bKc@#2eMUn=1Nl`Hn(^^} zrOZONJLWZaxxc+^`pT72CfmxzGCkoW#0Zx4L)TGk&sqA=wJTjN$A6+rg{rvSJVO%h z&z(c_nqFOOS-jC~PgCtr0iZw2%+w)wik0A`MZ&Vm*mXxt_Do*+qxIi-i{?$U1HW$y z>tO4t5~vo|`HR$t4BB^rYygj>P~foR<0*uYSi#DPC9?UxJ$K1+_(C76AjQ;$SdsDD6~XTR8bL#3g^_#O9Pw=-$k8T5My6u zKc&3zXw(G)J0DT0PoEcrZ9LSE%8hcgQiWN}MQbVcY@qL^#>N*+*R9r(UxyK8Bs1`^ zvG}@Q9B3O(*umo+Ot+()VZfmzXJRfRki&lpV=uJ4%R1FY^FlC9!P_cE zT7w1Tyi_H2z$q0qjr<*%A#;blHDZ2i;#O^X>=HV3VW0#y>Qh{|cHD2b^5e%Y9-eyp zc5dqYJEn`TvSF#W7!M#rk^ip0S|7m@SOogrXqA``+Q&EL$E-r*LZ%RfMdQEnne5X> zIU{1|0YwERzs5!Gg}jzo4@1|!1jylc5%AbfA*MBPT@{g%UINC3sf#m={s`i)stWsr z-2g3LOG;LaJkzjN`-$Jz-MB}KwYfw{=5tRY{NcZfb$EGtd)FyOcy^HO;usR|xG;$} zr}x`#DjPqgQ+u=aF9Sm49>Xdk``o)X3cgGTUby6{HUA|C&%O*L-B^*1iUD1E+p5ya}W%rFo0~t?wziX&maby(M6AXVOON^%joHhWW$UDfE!f#=Q)BbvA%-N8;>Qyyr2CmWIBY4#xBOa|G1^U8C<7?XiRg^~FyjfN2#!Z_ z%a%V}v}JkMp1(>u**uln$98sHCO{}|0;JKV1U2vY@H+8Np!T#a=FdN8+PYhWKDW_P zEpgWSaoTs}I3#k*mc63q6JvWwa_E&AGfGDPCs;~K&oRoJv8SO=JF68hJ|NgA$NvG05qC~G3e^mD^{))lp*5UW4`mc5^uKi7 zuhH#L>!tvy&BGX(Fe1JIX#wJF;o=i1 zvjff7Cmi$4(bc{;ZRHItuTyvACVV8rj~w>KF( zwR!V$yS(`FbJ)`E9S)7VF?;nyE32Y!L0{^UD)q*n3Xc4^ydgd#R`JNOFz4!=0mHG& z@R%+$`t7<6SFip2QJGmPDOEK$=ElLGW3tf)b(9j_%qHtAbl_mEj+JwK(-D?N;?<6~ z(6Kz8@ArP3d6JtuFC;W1F}XL0urnqOVn6`q6%vW=N!WB?F(!tT$wTjFuGC1dnHeNM!Nu^VdC~tt}aK{~EIjbt*jS!y2R2k)d=8owP4U+1JX-OiF1pOUoblJcts1 zsPzr+qg^gv^q20_VJD>sxycXsQ%ptEkp3)4oXp60k?4AG#JaUNzh&$#?dT17H%weR z#(Vp%EAjD;?2*QrB?K`yiV9i_nD*n6QZj;)6D%f&TWn`!7Jhv~2Oic+vX1~vDEGeK zRBs*Ay`MOR>`#l6P%;uCM*#kqD_24vJ~Wae)c{0n*ed&V?R127L_PpvMySM&W&y@P z!!UqYm~^_SsgR8nx4ora8NME0;2q)V);#`7-@2{e9k<1MwI6sg{Mqa0UmvFh6t7$} z4<4CIgrujo?0t}TvcXj_zi(#gXN|+(zd8vFoimF1N9_IfY|1NSj7fMMk{k0Md7Nb6 zkxIYLAfw&=ZVm0lI5xe;hP*q6`0~{7pjHoSo(~auH800c?vUQ|Ps!J8f=_m|u;|_H z_YYZ@hiA&y-D-zg|3}y&TTRj{a1iDLM3$`rkt6FP@nB`?Gm;~jWL-jU#%+F}6MaI3 zn4FxvP~KckR^Dm7>Zgw%M_~j?-_5NP912Z1I$&l&#F}#PQlYCqHeHbdJQTeNb>au6 z=n&ImP#;da)o*X`*LjuG_WXT%HXuN|fBvmiE*<|{tF|sGdy-GC{cBaTi}iCE(DLC% z-2TzLGjPo+npx*<+gIU%wpXuB?~#=3ijvZS3MMMc_DQ!HJ$rXg2_u{Rh_0~%br#bn zwB-}&w|Q%zJ`gS`MAC>3i{tLZ4H>cQerj7wVVh`4usxbPusd#wVf1vYYT0{b_uU02 z>UT)|{OKZJtGR40P=(e$H|WDY^nFzLdhmNkgB z5))b2^JG$y0G<7slVsY`weK}~A5-)DHcSD?DZIZFo)z!%nvX3|S13b!}ktoq!?5>VxI!0(?zt?@OjmtA)vDBCy9-7pWafzvb^TsJ1(Z1Lg~EIx}r z&W;br>;C|*%uGwZ>wgV5ImQyDK8~MU!g8(UcG}dK|vtQ5G3SPmcDK@1Lw55a_p5~zz<;VCdcH38)G-D#S6^tWV% zbisg)KmHOA7TNCfh2kZu;=E{lc21o6%!VE-JQU- zwln<7mq*R;{E)d}ro)vf4|Uck|5gTc5aSf|%=pyJ{^fpc@7ZyKvONAyGw|k;JP&i} zcy&qpfL=4J6D)6i-Z1eymmUm3(6tesjs7^!om+V2CxHnNegH91)7URAWcQKu^JsV^ zE8^%7QlW>aOG8ec44@EaSjKT$?fri8@5a{PxFz5|xB##mVU@&>kZWrQfRU%<;ULZLX~I3gz>Fj9VU1+blmW{gUhxHb7RJQ zO4gaZ?NHjUzUYHOiN8Xo2ulU=M*5`nen#d$0ai$8+Z27dpRpeutjn(qO&uLsx@fbH z2GZFyfPrGi;!Rdb2D#&B`xQX^#w&@ zt0D7Yls?Gep?i04|MT*O}}r?IyGS~ zbEWhg@Dpj-*@uM;xWIX_PJ_Pl-^<$VZ!PIO#ZCFhRCi?_=Lo2D9i+sbEsX-Kw#Y(9 z3Tl)?+#~dhcMNOK;+}8;7F1Le4Cu8>cTDdWI3?grCsf>&)=-EJMajE?uw)P@`1@zH zM4O$_@7r^zcX?iAPZkZ?x9&Q$B2`H@u#>Nz$b^XA1%B}}_aa2H=!&p8I)gDkjP=IN zbtayxS3VorX=hMWXi8>g5aCvAp99{SNI4E&&WU~0R52M@PwDf?u{?i}MzKJO(wlew zE&7lnq{BdL>;qoLwKrSLxC z!_?LFkJ!~OW@`T8RVjI!rgklNC^ZNgcmC^t35$s%p}3-ZVdoNj(jVq^Mlo;>m4 zPPjCO+uDX7+`K7qdqQ$T;p3SjQtGQu?@*2JQM38?hf!=DGshp3fX*#bQdND)PdfoB z0l;3j{Z-)5S!#bhKED{JceyccL9d3GUG?RST5>@g|{rDl`NPN27sa2*Al;%a&WK z)6UH)^)=WwHt2^S{D%z-)AM3PyO``GP*9?zdEHc+Df-v8#`j4R@YJURmzgr?){MJ- zjkh=4nlAY`&*sm4CG(n*hr;Ieaa{cR?b`(hoEHu3PDC>^v!q%t4lLXAZ+4UI$yJ-O z&rJjH_J-d?_$AaiLjTbdzH!+$5O5lK)PEd%bW-!3? zKX|aXkRxzns+Z@3;=1MCj>{&lUgPAzC0E$2BQ_G7M_Y}^*W}I8ZVz|QMq;6ZR8;V?jdK!Sy*rAYE1g%i;tgP(-W>*(VAe{Bq>4U;b6r7eSw5EL#h1OF5}xgUGluOp(Dn$n!lfQAW33^F%N^arD{};#V!mn#&QlTX0>gts%h4b9Z;$CBVU-@)= zE|HspBOPxIfsbu^SS^#(QohN|++2uIYby)Yfv?3NFb8>Z{GMco^pY2ImR|L5+rIhk zh`;-0_!HFtBf1)4nmlah-EBWc+?)D9W{HyzvOeJ*irW@P35}W+4Vbg@DE_7Iq~Dia zULEdFdu9FLpVMxIse7N9R@Hg^cF0gP8#;XWcP^M{s|CeQeg+p%X8VC?t(nvZODOZu zp$s*yJKXah;z?F)_oVa|u;QkQfh+Yc|AXu z>0wjF1Ca6;3SW$;uU>s&OwS>M2T$_wSk*4y>B0Q(~_#tV!oqQ*2WB#$38&&zL^IX&(lJ-2VO&E>%~3KB{fm z5_w_zAJ44F8Ez64wpykxs$$V4px+jWmu$<39|DkxKgU)Lj+xCnND%;!hN08_gP6K8%g zx!uDO*AEQVRcdej>c?t_ghJ1g@TKjlTAM0IV@lRs>6)gl4SVXC<^RAlKWmu;X5kN> zP5Sf8;5TJttjI3X#`w{)Fc;PdD}@%Pr1)Bv;O7DW5a1`+^3 z`LO~H!o=zfs=Rw69*m@>Eq!~X7ibkf4BFx;f?7JJ$Rjlg^RFz)k?c0K<)-VXS*JdP z3|d#5t@g*7c^fT2U18!N3>t8cL`Y&t!V^=U?8p);OclnKxby!|vsgVdq=I54ldj_s z_3jF{6z>)mR+R4f=IL2xSn;5L;m=Z!DF^R(oqB(iU}Pt4?DqC>b%wU(oTO}tv;2R?Ne=+?QeEtN3xr% zYt^QK++r|Z>l6(Ssjg>8uaI1Tl+NS^A_2*HK zD`D>U>7J=2u+yx1yU32?ZQ<%#KjpShhU=E{W%z&p{CHc3qqd7JS)EiT1k>2e#T#S! z^0O)apMyW=_Lx2 z#FW0BUE#i8f5+Ay?5w6|-57E9v+gkT_Zgh?iPRTAfBx+KHS)YR+w(pjxMar};XlK_bbFMBxHUw!Yy z61Yi~yuO(p5ICvK^}ep3+&fQqrCwZ*lVb5}k11}oib707c|!s3FA^-yH^2Np1v)N% z55Rjs_%pRNXSQ``M|n@L#@q-K7>NgUs~kHbA)j@1NxV4-nkBB}`+@r9&@l*c!%av* zo$II7*5-Lt`zq?|16Kej%$=LP_LE71*Aeq*aHu3?B}e}c>R5qU)K^aXIY!vu?W}nG zZ?>E!nN1rYNXvFt^)zSLb?4$|U7Z1yC?7TH6(`r~mG!t3+v{en0m>C`=lVIwwunH)g494 zM$b*j-jYm3B|T|*TQj~>VyDk+Y|G2LCM)!TgP@aZAHlHdw6tAIC|Eaor9px|oT1an z5@Lb01{~{>zpv=I9>f$(`F|}y#mDhTX*SI&T|wS$r^t2dMTuYp9@6OK?0j=RS?JN{ zaf|P4I3c#TMkkR9)$bp2s{9x-C3zY0FcmjV1#lX{YXZWu4CjsPk{(k7<*%2l`Sg2- zU|eVu@ZiaX6&Yu&{z;f=GUG$|6N2Z^)2FZfbrWsN&yjC)XAPIQ6uWQz`!Q>S4ZpP{ zX5MLy*GnOM@AdT+QVXhNLXgmn0X8DFaNfE#w6k%qf6@x%S%CwVJntdsa0YF}J#P8? zUQ~}vX3nZey`E5#^7fD05^KkYkM36|ugQG8CStdwLeUeyamCB2y+ur7&VulW^hD5- zRKI1PGoREn-&y5uc}8zgqJo@UR+Amo0?mF%U3Pl9@X{>WGGo{Ux>{m4%{`@qecFK@ z*tQ;oXm6K=5T6}h(+v%Gceh1atF_a^o%?z@kjhE4kYse&60x=>ElogC;2<=&R9hp_ zn9gQRwOw5jN^0^eYL;W&t_-!g^E*)f&7$N6G}pvm-&z-7>@n#*Sq09jGKB8J3ss2! zKx0CV;gYLL`A;#xU;n|r;k65n(FjkmtR+-+de^{Bx9S$jb2E*&GJh}_V$^00s%nu= zA3S*QCQxYaM~_xwfxN8xE(12q8V1GRi3K()7#wAlkQ5pc0)gQ-e|mxib(U!8Y3y#@ zxpi>Hw;qUvFNm$}sU!;4yBPbT5x~k%EM4fyoNCv>VV85=Q@1UOAjf?rRP+QK=q7x* zGWDCTGNjgvz2pagO3qQfef3lrDW_>-Wfg)RL0ke6K$zYL=-g-Ae(;|Fs-Lq9uSA%S zxDnXVe1FyESHC_M+U@sf+Ix5Oj!EApkR!yJ;C@4g&cf#V0LX^$dGv>N)?Cw6)_A4} zbi|pHBUl<|=1QEQ1a8uG3#ga`a6LgOt6)ObkT}P~k9vJbG2H+A_deY-wZpfh&wN`S z>*Y`F8Zec0$}4~~LYDPr+g&|Xdm1tWHWU1j>Z`RrQz~DLB{Y8@?nD&5Zth=&sJ2(f zM;VjT6YfvnzCHd-uPq4hu07Y%)-Jg1G%WEp$z=HzPYbR*oxRlws9e3Q=E%QpIZqeg zK*pJ&ba~FeR0;u`Fj$-S4=QoTNo@SpI^sdv-EKzvDJt*OoH=^zSi<0od9q?1oxWZC zy0F@vC<>_xo&J7?n7qk)hnRep5tz7dl-$n>EuL+sxpsCVID^sSoLKKbsZ;*%8>1$B zISd7V&qyoWIH=>OixlMk-OXS2xc)fpqO}KlMGw`>r=RjSDm=(22e7oWMxs8G_tTL= zlzFCp`VGZOP$(B>cvi0Im(}e86{bI*SYXD8gHmzN7|7Wp)E_i-sGfi5eC;+(28on| zKHl~>E$QlnYB`N@inr@D z>ohvZ)){->zI{85ha7!vy8#-ognsr*tkyBaF}T>Em*|17kM?Y?x0~g?=&E)0_f6NV zZ$8#o?sZ(+m4Uau>s|n&kFrmei1|%N8QpfxF3GlW7ux=7k0vwXBU$>_5H$35>o~`* z^bG(&LYu=mMan=PzWjD!=DcZVhTF-M?>;vBh~#TUF{309K_pL%;AEM88#`uSa0JAT7lJJa{Wq7SroK!8=1eZmd)HE^Ae={IV>ew{#9JAqtIJf;N#4tX zPfNgAWD>5wzqHIetFMk4d=Eb>;CHAbOKLetkO{?BE^Yoni3) zE?y*M8Eyl#v__&yTm33Lx|eMJ;vSknUMxCCa3F&U1-Le~rsM@QLh9qk=fbR>_~iSX zKHXQaN=RMd5I_k00sH7?sPlDMsl{N;2hHUT!}r-FRA?u=9#koswDMH<4#Id3#T>l@ zs0!*vNDL-JgHiZ=D=S++(#dN2`+%m}&;VURjRDYEaPOs}msq&)q2tWQIBYNfS!owuMbB&$G$-MpJj)P{wO$-hrJ#i7 zDy(8T$h+I0wJ+{F=9!+I!%L|B8uR({XZg;Z2Mih%)8pn8(%4uR-OWfVPLo-wS(ilL zLXDD8>&a$wg*W5zUMjmW{}-qEQ?cr&`)lWINqDbKB7GY=_z2C`zDX+icb$Dm3>i&f z$bu=uP)e>uly!Res;d=GXxGyb9YaS;f%J-L6To@?Sz;lRw9N=x?g5CHkvw-%*Pn&x zPmD~_wLzNti4K@DN3X|;v?%>cS8_`u*69rP^2$0fe^MXxk1Asv6={m1co7)sZ2>tG zZ8aT%=wzrSCrqAP_W9x|&Ff`iG>=k>yx<=cG(%1-$U=E|t&4<9>EeY0i*hZOzZrN) zZJfbs?dGI5S+Ax%kGyeNzpWuQw+glsaKmre-DK(Hr=P-|T|yqb3?DmlMD(90T1k-; zudX(oY~2yu1vf)60tAoQSNrY7*{4IgY+@5Au&;LCV0UZB%-sBLK}J$-oaY?(Ws7g! z`M!d3fyaP!{8&%5C6Lh%EyfU|a_1C^ z9tdvv=ifsMS6n;KaJz2(PTV!L4*w`AdHY@O+Q!hM`v$FQH}u4&HHN4#|GVRobTed;7v10^4(1ep*-uVz1Reu?m2jxPm!@Zjwi{ zxA$sYqC1lD5>EPKxD}z|qC@{QU}S~&(fER~K0eFSI#|d5a@rj>WbBD=6|;&r9$sr) zJf101!A79dqNVy-_(3i?+0f^B-GjnWjOk1n@%_B(KdQbRne(6ZO-l>t)$mQd?HLu< zC#_RFt@3qpZ6S}muBMu<(O(xk9Hm9bxLd;|0ffeZT2p+nC2~BJcwfJv6eM-os~bhERxP~nB! z`!_!8blif$uI2Gfw8$7@mA6sxn}bNrNYUYLk}`*i(a};DWdUG-rZGG zAX+V$eAJpM6Mpvt^@ZSTXQ+FCqUs=+^}3vX(dn*##q3m&@TmHw!%kegbSe1M$R+Lc zaO?T${%H##CG@ctTYj>Cji8NcHC{(`)iJh zrn`59f!?2&qe-;4nG_Q}fRod>(uVR`d5!SZ4}+W~3BnOxp-T!qkB@Go_d<{L+?CG-?7-Y;G+O+0Rfb6E(F~axkQ

A>yzr4LnrA4`hk!uxWYB&cwRVa&gkucfVG+|7;UO z)PD@rZu&HhWk$f*mP0xdvYt*LO%)($yN^EgeZ|Ex{oLE`rT%rr-Ggj^1OHW^$*6vw?TeMB_-xj6VymfZ<4w&KLGA#Bdd zYG1dnjuj1CBRgm0%KVdm!1SBt5ZT`snT1fDlRC+HT>mJ%){X3_W9S9&%@}-fD-xWI ze1zQqZfaX@I(%LPV#%?=Hygw@Dq1VXfqXpJHRe7(X}02Cr)QXBYkMEK02-Kg!lDtA zl=a3M&)mCw_p9ej$}69DP+AjFqG_^2fWAnH7&1Wnv>Wa`+uQkzg@*d5;tK)eQVUc_yz1;-}5_;GB_1j0dj9~O7v`KAs4sG$%e2uQ? z%q9K;D+cHx^ms)8X-JBNrGC=gMqQwquk0l2X?;A_jl|LO>Q%=T2?=d)-wasxz7d#f zFXsb@k{9ijIBSp)^_wuEXS_{=snwlP`XAaP5ZZi21Gs{5K#_4eN&p)F6ySXTs$YI1 z%Sxs7Z(Wi|bVwQ=wWEL8XTV-izh*^_L)3LJ`11i4yh`_u1LH6|(m~3)!-lkdYu0!N ze${v>JM?X0-<8*YPV86s>N6Ks%!l;9#cpd}HsCNSs`VoKu3)L>5kNWeX#M*q8co+) z6#0cE?kbs1(rxAKp;_vNZI>5%e|Sl`U#YZYQGN03JGDjAl?z+x9^cxw{UZRo@RwJF zC?thB&yuZ`I<#v9!F*{b(=o3#Jzw@ZfTGXjl;??Io@qpx`H zn38(uxMjQuuGj`EQ;cQ_j*e#f&!ll01e@wVf1DY$fa>hwPUd4jj%{mRA$;cGSX%)! zL0sTL)}*&Jr6cXC+!A_QyQW5C;-b<|-^v=(e=<}#F68lSXp34h34UYK<4K`2@5}dZ z-xhXpMhpK&+iq~!IEq_-<$#$_m=~ab45!PuW|>zIH`%YeuSJW|z5L;UmSVQR)v@|b zN-!AA9$vCV%3PtYC2(TtgFQV-E8Jkd_vC1k-mx8iGgnMu-kR1nPESt^UNOeGuvzX= zc1!OO;;_YBHM^+BY3|D#bG-iY*0s%fip zJYJFTKxZP9Otq}jjVc-N_Af99!-{`NZH>dB0QGyL!k!lZj7afAq@e%2d~3UXYA>uK zI-acNYqD#*rZ>H>g5u{Bj3F^J{T_(UK4X>HO<;78^HXCwG#ohNmNwt}KmRMW3ImSX zqT*XOZtUbToj&O6)!1~*_?*~jMIVPg>;LN2D+Q*|X>O8EP#G@TXnsG_JjQnT`_w!b zi{2+v3uzJ7%DefQNC zV-Jr>Ke&4A$lmo9{G;p44MV$h?>gIX@6KLbY;9*5%{m>}&GnvybjQ)sqaRV2uD?4Y zYgfDGCx0HDdbF+XVtHEC&3e{>5{$l^ANTIrvy)n3X|kQ?$KfQB3>td-M+`{yp=Jy!cH|9zXVRSy*wrIM7^Miy}cc z-?VYu?(E2kXNI3PUS5zhfH=vjNCZei-@a9fC1C)eR*MSObcjm2o|HWagLhm0F8cia z`}Fo5RSk)Z zl-v24a{wLGf4lTSy1BXil5V?%_K{Rce&e#(PIVpL?|4t#fAnY%>ok}HDIB{R9TO8j zjSQ`bo#LtPyOZk+-@^iyk!FxMh9*bfU>^zL+s!{bH-`?ADxsz>KbU$X8NGiF5Jc5u+h*kfX@eoV%tZ8F?yIQn~-g_;ae zDP?@Jomw15!evBq3!R(pTs>Y?{_V#P5+GCr(?eZ73?F4dsY5WzbWCtVm%6%Ie6P2S zx0N~jvk&A2b8TgORTP*-2vrD5n6f_QDCXImf!327WMFSA&fI$>GIBd7Zbu3aF;e~D z*XF~7>tXJQ#@(m7H4L8D?P{8LnOuB}!8Xfn`-X7+ge{koQFYi(tr{QSodpA>cDFoo4)d$Xbi z8Uohz?_ulES9izv$-$c71 zQ_)X)O;W=Yjptl3v=vwY3+c;tLl&OYX!=pKA~G%P?%l~gt)+JoK6}5w=yy~{tWTI7 zp4%|6YlmQ=^k!hL*{wrdQj+4@wN+}PkDoi7@A7QUkwb?HKfSayiwQTrw$1yndVJiA z({*c?FK>JU z;L?%BxzPHmSePD5j{Bre4EO zj$|fLM4*lNf^5d)Qw2>FAHGl+vkhGG=D2yJzf((a=s!G+T`j*fS+3{UJs?g^W!}0k zXK&gx_9kIX0D}Dlk4?a=$(Ju{poar;GMRMd7W%#SUmt*?I=H}*V> zOp3{=;+UG?R-AQhOT5zV?6Tv}?`i*OxP4`GLrwm03ltDx&aeJlwlQ$`tJpho&mFCb zpY_`!o;GPeegAe@^`sA{#{FtKztI2Ch?PFwQZ7sb$7F!XuarkIZUXg5;Ff&xyms~b z$DSx(8XS(GpdEb3%7=<@hDBZ*qvg1Sg!+ea-ND(-Fo9wO%gil+nnaT_6VpkK8JxqQ z*+_GfkKFXbjx+lF2Gv=0$N3R3Y61Zs2>bS^{%i)#f9{}Ai_cw1r{BqJ&=t~sH59(T9O^;HTTmvlZYFU^LnC^MAssQ&SY@z zx4C!h_&r_tV;X;dExvOhK6vD)&e2B}E-IYtH#u>!y_#EMlGIn$qcUCAx`;5{uvaCjX8)N#QX} z=D03KoQ5=b=UPT;-|$P7W(&~9#-*ev3)6cYNp3aVO3|*zzPpy<)LS{!RD`|5=MXb9 zz=)E4hkISRaL&l&u->KQE{(T0Nzz7JDt#>9QuX21rnUA7<39dbmsF<}+hkEymr`u+ z*JnUasdv`>C86OVDi*OX0DlAoXLFd1^e8bDvs~D-+b(_D5@ak!^3~W6m%@8X{R+Kw zcjvjam)p5u?2Q0VM8X3CWRbrPEmA~qVZG;biGTxEgh)-VIIrOu_U*J*gdAUkWwaep zC^nyBc+9-biCWikYsuXXH|1L&bUG0iVA=GoLT=KG>#uW)efUW%J+(L2*8ewxabea& zj}NWWwl7}1SZJwnkrNA4qWh@5O4~UULLxu%qJWV)a|MVuj-hBtSx`qGpMMUwYF}jn z_8-oYjY~P$uA4})SpGY5B)%BX2efd_W=3pxZFNt&P^;-(j_3Re{$c9Ln4CjI7AV)4 zR8EqUgf>*LOh9{VihcKQ&nXpD4(9hnsSAER2JDJx7k(69Rp2j4Y2psoUeNr7T`K&E zRol1js_flM?`W@NXwvR=_4RuUuH z(Oz>;&{NV$i706yp+*)*W&~`JvLP-{vsRI69)9fDULH4yjwTXLm|TKVRJnTN`Tns? z#Kh78wvh_UF`;(i?Gw?V$XgV&H$;3Te;N)>@taH>YG;B=6806J;3fs^C41{Le-ofs zA|%TQNQb&95Z5*Ig{RxXPo392ajRFwx06FMR*(H%^1d{6l@e%lEt?``;7Zgw@^FEDnE&yK? z_P1x(FrZS+t(|+Ktdv>uY1)J$A+5nvByU_X802;d^|%+ODB`+U#PL@ z@bUJYyM2la>M4$r9iy@s8YBw0tmFkYxKNd zgoDJ{3#ZBywYrShHhx*VUk*Rj#lqONi)hYg{YKAt@%*_4v|vamE95+;^p$@5_N|D5 z!4FNusp9s*ex~!%p*S~^%cR39g3@h!9T`RonW?`!g{gKyT2mfQ=AgO&*c z)xc`NW9CMFOxUO=l$fOo5Q5`w-|h|Ah}p=2X9|C}Y}hDSRI_=#w2MvD-yW)}s$|1| zxQEki#lcqwMkKA{cBrb+PkO2G$-1PGWXP#H!5X9$Y-VKRwq zSa{}!*4BzV#~ipD{vz!eZSWgcueW1Y$(nT-*26CS_#iL(5UEEcb2E8S!jA~Dj56uK z6+eF5r@LDRpiGXJ(GV3AZRK3o?XlWRVn2^$O2^}`jfr`Rzwc*qSlL?b7n-brw4 zv<|$nUUsE>`{ystSx*^hGw5YnK!7A=^HN90-vxj8wWeAT?@sQ~%xqDhqyeWl;w*%= zz=8m?g0ZoWhu=#iHZeZz6ktfS{6ucAPiy^}ddD|x^qA!{d*Vdh-*<;NIr%H}I5_q` zc~tHC1yrm+HI{`iU>zS2J%Ah&4)Kfu9GI?>EGozMVb@v3_dB#f$?wq*ea2+6Az5+q z$ke(sqC`X8UYG@QPVQ=S-rBnnfdgT&L3Evvw;_h_#p=Ee5=58U&j-5KV=0~ff>!xc6$zhWSGdDg>xVbh)!8=lavIcsxS*GCu zmglj{QnP;YKYy*X2^0MKrY`S=tq0+b|6LV2$Ob!btq8i72whAV+Fa$=rXaLU zix!o_o8FGu8iw4w{Mhl6bwjc;Y3Brk*Z$UqP^)tTb#4}whnulZ7_LdFg@r(fpte^s zE+M6fMpO$^8TuAINi`IVqWa&kD@}gvkxop=^?g!nCsH=*bn=MRnQA|*yX1DIjC)cZ z8)H5`_$eE%Gf1%Wg?SXm-zUa98=N|t2@x3wGtNAirH1DPYXsgESx~}}6Jk;z5brS! z43#D540rC_dE!~hg;nz{wGU=XZTcb6+}x^wYfwoq@;fD?h3XwC<7=ZC)sO#D;Hm(P?&jmM7`t01h zH<(}6UQw;tzO;Y3QgpP$)vLA@{hggl+Ub~VSpWo0m~(FwsC5r7ujEV-e*qpYT);Pj zpTtncZcVwx;qSynO>8_VxgpTeu}2i@DM)VJfa`y*8}ie2b#T(~%Uj1>USIAYyZS@N zA$AfEwTrnyBu)H#-Z2$M$H*q;-|XIuSuIx6otRPKKP{sv!+C)#M5UCFE7E zA39{n2v`erq6IQRIi=zi2xAv#nS2p6PQJlQkIwi&kqDw3D#Jtl_bEhugt%Oqn(8h0 zkA0IngY+h3z*fbQ65Kt;>_1d|;%d2W;b9_OP;8kk@wfKJ<}MnxM%v18B#gSxe%Tc^ z5L9hRFa$>Iqot=#(M+dLpy3z$7kpkGM`dnVQJBE*V>%gftlEWAxAGDi;OZM5w?srSa8RJ$(ObHf|IMwu z4!gx^XI}YyDg0m+Jmr+GoL5kwor8OQQQHx$dMRZI{Pa6*V$TW5h;<#H^Afi?9haz0 z&~!Tu1kRVFL?w1um6@s0#2pg;G+l!2m@sg^mD;N$ha84D$(yT|2oVUYr)p%N zJO^d=l zztR^QjcQEFgeC9%(ZyuGh%{bg(Ay(scwL6v1|fRV{_fQ=Q{6c{jHmC8oN_i@?frXd zN@zx$Ti^Q){l^Hsd+UWv{GrnnMk>WU75Mo9q?hPBT4tY}flA+s|E<^tZ3u-rV6 z=?~n)&j%cQjqp$V8NTW3qn^zSNI07LP20f{072Nb7CCn8ACZ8HPD)crjxtxCTAVu~ zf5G9m#l@6wh40^Yq8}4st8~s765j)qEh#HIZ8{6S2kSHd@fWb3iB`l3`Y4cg2z(P^ z;;ek^xi+JqKnYZc>!7_Lrl55dkqZnj``7#I?Ni{_t;d|MDSJCPuC-nkVAA$ZKRV_b zw~`Z54q?p4ypQ7XTsI5TU6kp7xPed02UouAdFS)bCP}_2)v1u;gGryDRix<0(BmM^ zJ&0;Zw2pfo8+%iI_1pGdTV^ZE`RCpE_vJu_;*=5HU*w50_n#zjNU^!Z%$?2x7Ne|n%LdM+2cks=~mIx;huL9R5;`{F5x{t!D$8E|Ei03;OY z*coBZprNfTliu1m7+q_@n>V2hlttDFhd0tEqI^elF^8~o#_Q|nEpX9MmIr}fhhHnf z9?~al3dW8Z6Tr6UqFfoIJu#OU0;h(WFR&zpX(KaJ;Zg$B_SaHRZo$bXrPT#&XGqt~ zv4meS(G&BuDy=Vc@)>mh=FNsA)r=)eGDfddci1>eJHnjZPmGtQa_FpCv-~Ogk51a6 z%t$Zn&Jtb(PW3^oqbw+np$g5rhHqdC!Q{c-IRp~ENS0tj;#EBje4pV~J8SEwlu)|}AREw)ZV{V5Xx>9PM}>p7erB+t#tG+Ik+~uEF8hdkLXwfx*6%mSJBAA* zF0csX^C1=rDA#C0Fq0dWkRA2YYgdsBs09>xaVsHx35tu;WEl4wyVAS~7Y*_yEaZeG zHdHnA2DUh|2yd?H>IDA4dNR#Iix=+l_?X^y;9Zzjovq7AmEAU~64A+XXS@E^j+)^{jWu@fq|NUw0 z&^mSM^N`19%#$O!==7|umD$lTu64Lho`FGIRA=+rjdF1|8so-DZr%F4JX0!uN+(ZF z#2e_z@N@3mIV6xhg5kNyFbdO&0+Y(5ScmT+$L+-~n>1=eufPK)zHA_{@Nk|g+DIrQ zeS?&^DxENWp;AX5alob}?egE&EJfRadX+bFzS#KH&qf*{H9^s4vfuAaS;aBq#duv} zpzKvR82K%KOT(sY&;L@CzV4=dGXx-!pLFb8A>9lZGCg|CJ0G<%m+*-Ont1lgcAHA& z=zZ!_)KI+-gjo)MeJ4bof+wHo=mjoeY8n)ob^3GK4f|nYhmj`$NLcjI+sjL1$dHa$ zch1UlJWLJGDPdqYdZx(cwq4Q$O84;L!&&-P)vv|zfr>%`o4l%fkUpu>F@+7XPdmn! zV1iwn%=iTmM8F5Y!4BTak50r|Yuhk6+Knwkglex|%6ya$)IpW&hb>46lF*Pa-?HUqUipEBeG(e{X3LG#Po`~X)25Q~1#gR(?6)bR_s+$mDWnE{)F*PMcD3W@cK^ zbybDmZjSQ%$L^zPWqg#EtKr+$vYDn^7%T6~nFz;J)P78a`Rzd*2;?RROb`TygAmfp z2LhAYAIQ%J1p5uW_7n78oPI`e<_G)1f+r(9i&i-qiUvBRj!gOks1JF9Y7^^zOsu*? zBA&e`H_ zY}76J6j$7#uyj@0ouj)XBxlu7ZCEB0Dh>&d=pNVzRTt1o(2?m%0vVl(WFAJhs`?uS zQn#+mw_-LVp<8yyZb*BuRTC5GVT*6cFb@!4782?39M6X(5gU(j<-iEXkFYz1kAPP| z??rkSZNfdQ;RX%)y!-r=n|&|Lz2IN5(o%YeLa@x_q<)MEVM2gI$nt_j(mgMj^e=&P zF+R-vw=B~zbuS98C3T2MAK>Ks59TU$>fHh__Fe9{Ca=ruS* zDN%f+5XS5Y+(#2_EY6rwv@4O((Wd{lwK^~Im)CSb9D5%b2H>O;M^TFB7t5Mox0@cm zyLssT$MmSnc4=#m&7D))W$49KPHP_blazE)Ry8-b?WQ?>zfy`*ySlYpg$p`&)V`k^ z+Iaa*THBCKo1V9HR_}j0K6p~E^fs%V7Y1*vIcXLY9bG%&!kP20&L<{n3!xwFyCwq^ zoiD7w#b%6sr znUhNUSH-b%1&4}ht>ZY$UF?quyH`Qp;n}D!YnVGpU83;Ss{tGWmN|VUZ?k(cD)C0X z9m-)S9@uBX)IWLt{oVQx-nAnMT0CvGykLI|VU;s0n_0*@gV$`@bggI|pDxbN+RAF4 zt7Lmau7Q{jpso>^tHdm8ytM!jW_i?f=DNZMb>!HwXM|0e^h4xZ4?*3c+b4uDGK-?^ z4M#XyAoDsS!=D>A96&Yl$B)&JKrHF@rV9TGoMI-W@~Jf4*823W;D}BuSDK?F$ORP6ML=YRR>js* zZOQVqL6=80baq?weucLA(EuVm*0JvYI#Q zg!z3w*335eF}FhYwLxN@Wf2_}6;)X^1z(5wKd0+a7M}@wduyXx7zC(S2aa4>CO_iH z<6pCNUl$b_NBN9B@_vO%o0#uC3KCXm44$JnQ43w378HbUtH~WuMyqLHHEb7t(*4o? zY2r<#EtoX8+X){Q!3YLhi#&Z=TbZyHO2voVoVoC1Em%9sxxYedPbbXz`R>*A%{wnW z8b2(nhmOc$K{VDCeEH@mAxaTt7LO3u#4dU|pbyk=S1y?a%B0k)G<@H_qfNU(_IBYbi)R@EBP6pAd2Y>T@G$B~}phF{xcN-Z(y_;4o_ z$}3PrLGkI3Y#*{1g~K7k7&(Fn>D@%j2+uf>Nd>_N!ccu1xTf9RZ4=mRnNG>b<|H_s z7s?Lte&4v&vCUUE^{e!uBInF(vpof~RHUQ>mS*|qV?WvYaHBj(&dmj*V>Q(4o=cukT5DDLwr+_vO{|y)rO>SjSMAO)ZcijyT~D zaZDro=~G2YTZ!G-C)3)vu+-kj%4u?ai~E+Vn>j0ZY`-3HLDf5bCv1cU5GIaj^txI= zDp#(UFqEVjl13L6Q+eJYcxz;D=e>Id4*gwSYPjfmR#WtUxkIqJa`Tf?PGHTy2ThnK3AbK#j7m8GI;osJLVw+j*WDl8uq13bE8^ifb7Gm z?|{TH>+}9ud|Ln6PzQD8Ax-r#Pzi9;9T&$29W){8;ic2vlUyMVK@_p&LD61&vvY9-Nq_%xa*BsCyedk6Qok)GVAa`X&F6$AeV&>4A+4qkJ}1wh_n; z!K@3``t|Y)a&9oce3mmac5+%yQ~ogB)60tHy!oxRd|73V~=f zslRe41Aw@)L+9maJwaqeHYgRn0DZt89kI*WYykaBm>w0pdL=?91hR$XhG)TCe!#WA zjsGOFcD&Cj$?R@-_g(jqBVEm>=VzWUGMe=wDZc8$_}qE(=d<9Xr?md-C&rr*<}%LC z&X10aQ>3ZpZ+umq?Tn>g3Ug$ID%RZcZa#3 zFkb|%gFMu^M~?$Jy3@^2CY925GM)9l>~SK}k-@Z3N9>z1dVfieIaLxsp8FWWfw9Av z(l2%4%x1j%C2{?XV|TXJ)oW?&y$eViKyM=kDI**HYB{wyItpyQ_9{vf%^Q^ z4i|1!p;i--Md0Sr%)XhBiG*kYl_F=86w)k^9r259M!!CvcYXkXATsAgR%6#u%W~J2 z@UJ(-I{tPNFAa}orcF{3knDFW66(wRYNeZ-34RFnDFO2jHIKUA+;E@}6gvWg7@*sN z_V}s2oHT!X>x~+TEfXBl^8P@ka{YcOx^`E#Q)8QrLNfiwn(Ua?O-#BGluAo*SZC?= z7sQ%gTm_D3aUg>eA<%x!O#>_nAr?O3uE17ds%rcpyS?Akc|%D~#pWY2M?6 z23PQp=np+NJ~G!l?(lwk=}ty$y*a|=I(5p14hna6=)yJw^po-9A9q~R>3Mx>ySk(7 zGb1-&KO|ShdA-1AAxM^Qa;Ti7vF1wH=&>Fy+Y1LPuROPD{`oFX9z8mpG!c?lYho+k*FNOReU@MczyPU3mju8SfL5`{XRwnk>4f_KbEZH{iQ) zq-3#Q7+9W(JUUiSuY}NjK-Gu1<3`i|Bmsu3F#UeXFIf^*DY{bDhlJ@y!Z{;veWfow9yMqc|x2TIL_B zzm{6ME^!o3QH=3<|IN+KLX9eHs2I;No4SXij)2x65Ow7;db)ZxyIh)(WO8iwdjs4kQ`1OpCc9FncPnuEFb^R3Iseuq`wpNGv`9Cc$r7TE|naA)3 zo&s%XCKC7Q)78YN0!~o#&$WJ8U^g*ZvQ%2)vKu@vF(X{lWTo3F_CaL7Cxe&uE&CHt z<5}^icXD2-uKSPS8Fg;TiAy@wYIncwA^H1{^u4SA+0fv!#EnmPOIT6id?=kNMz6iGJb?(Y9pFs4!AE7lK$YFWh_@a=KxFV;`#FcvFlI6^&W<1L zwp~8#Z*AQrJ9n-jhS6f$cWkjIa#Vn|j99-`g4(8%D%N-OiYG4p8xAb%8C5ME5#u}P zW&BC$;@uCpE?uP_ee(GIWMb8%15Hd>pY?jj9XVlo;(5J-;xr*^=;sygiBYoYe zjB|%gdc9AfW5?*hO=2wFHiZ;ia@#tVd@58|9U*hjNO6{SM+zE2`4bNilNIP8okSKU zW)Wrgj6<`XpvMZ0<~~)PC$^@~mfpMXl$ZSYeP6FCgBMohWgK%%b~?~CT=kIG9yjf|t>YjALg*2zXY)s&5G-3@-Ie6U3>G8`LB2ufD^4iku!{CM2mk=# zZrrr|t7sY6Gr~fQ`dz}1YKZM!W@C|VQ}Ipe^wY1Or4AliTC2M8$7@Nwu{I089Z&q8 z6DG~@sky<>)wN1_>D;pGkYun+y>C6GC5YuIa5=D346>&JMMIU`$F1Wivd{Ha7W8{t z{Vdf70~lH<9Lpp)$u)vXnD>nLD3L(KvE<)hcR%g)T_1TMOb@9KdvagPLcRG9SB+jo z{3be1n4BfwzIA|1f3scr1(mwEDJI`8x09esvE3pPH-!agQS3$xoN6!G;}y$1v(5fj zzpJk;+de+~N94^;bZ3Qr=~R8XVNsE<1-5^GUc`|6g+a_JzwB(gvL{%u;KEB}&m!uA zI|GLrUFdg*|B@2BGB;dl5r7N@NansU= z;nGaWb!N;QXSldUUrbiv2kPYX%g&v%uI5=`VJ5aEWGn9z#VK_p1Z2c#B1jp8HUyGU zzsZx;giq47Yr=xKuT3tUbZE2gevuH#+_Ggez6+?b_aKv)pxm5i*IuE+*&D9U^JK!e z^c{Po$R;6S&c5{qr^9kSWj+7AtgHuMJnA zqwtI?M6g?Lf4Zmmvtw>jF{v7C)nkxYd2@G8=~AxL4L2ohZ_GZIb>#Cu@-#d67cY+4 zp&7NeStB^Q+w`G%^k1HuFI6WQsCN48He-8yRJ5s90Pm8cMvQdDpd=dfzMnD~ z1_8y@W~eek113M2yiT?M498EITJz*rkG<^PcZBoQkzSLgZ`kx?>e5eR*mz~@I=QndTr+&kh5Wk*5(aoQ>go9XtC_xK z#rRbx;uEt&6z6<;Ho5iR@B#Oy1*>jVHCnxPt>C5!9vU%s_<*WHHDD$wEDzW;y96W- zZE4s&leLTVUGj}-PP+D=A(+dIiwSQqk_#}`HfB*_F~HL9#6`Zmz{|2`aD+Lt$S?|V z5OEDHEh%0Ln7lAPXTUGIdchQ(I(4e2jqZbcb)F1Qg3xf50HH}rAp6qj-+yZ54fY-S zV})9k*8F=sJwfpSHRl`?wFSrOkGdupaNRhX@1s$g1?_-4QX+cnf|r$@Bp`sH5!t7f z^rf`aWI%qn@|Fepw}(jXe<__|>Q^yygoj%Wn@|#}O z5T1Hgj|z#n`)St?h}j5K2a3ppqn35R8cPUJ1c?ezl!A;FdpnL?M?3%8vew6q6e^Ba zZg#l#?F=VuhW~Nk->dXi9_g@$?RKq5%rLlamYw3dcI`Co1qN>!pFE&oDnhS7U|P6f zAU{fUU<_JzG~YEAVKd1@ZpG-YhBXVCt?Gb>*7Px-AGT7HyXz18^(WGpd$LrNfP|jf zA9Ywz^Bp}K#DY?`_55Br-I4|z>DKQ?$eIZ(lnE;~ys1!}(dPAF?EP+%&gUd00u23G zvqEAgDtd?<%3Zs{m~6)%7E@h7;4MmOGo|Ovdpmo%H}_nB|Kf&De?pwQ}f2_(7Dk&f;bov+8+Q zGsRgm9yc=i(9qEd-fx0HfF`t)fC&JL9ljZwPH|h@mx|I5Z@dKAJ_a3T9R2sYN`98| z{+UP0j(u|Z^z}^f?AhHlqaVEZQtd@zx#W?@I~cffN>(VX=b{t60k?)yw{9}@t1i_Yb!-Vu>}4;xQO_dh?Mzhd>=dcdQHpA}2J&Xd6a0s|1?z7kImxh`EXLUw z6$zKY44kp!uci+_FnqC!gRjNLvy8U-dV1U4Gjja9CW?U%usjlPjhb$XX3ujx6dGR@(@-E4CWRf!Wtx@3^3 z(-M*O+dlT`G=jrK+lMbz97I9EF0$%e@VvHfUjAIS@O$?#_@1?9w#>kvzd+0krPxy5&{%5o%H8G!&%$K6FH+rmYQG*x!TUA!nZI&)`(ITeYTCOb3+ z4wPdio;og-%ZJIwmmyih4V+bD74`IH?Jr4omYnl!z;Q!klXJF3A)RMeZ|}bGU2t&5 zk+n9S`;+dTJUw(*pexm|=;NofHFr&K`P&=7mJ%GQl|MdzpJ3A)GwY$~DEa<@Wu61+w3~0LC{k-iQ`#Ez=Lgq*h zTx&-qg_m?Us2*W;ogu{B7lT?HBT<;*Rv{7xSW@G+)((U!+z|uN2?>X%buv%+f`%}Z z^W=fSqH^`blFR;D_j-@Zn^vQ=n_Oo9 z`=*XLozH)W7f2I3wwj5JB4?!F5Ch($Y7hfekN~KLfmxpnSzsDUq?An^l=^P>QN3{``zLI16r0!h26iUn) zB$MqrPL72FzTc_ougANz3wI3GEN}ngo%}=7WwYPpc9VUM`!U!mETX6n?mX803L9E) zKxsCGDa#_%j4)S1;Y;6i)WBQi@87?|`xO32wXNw~##PkLo~Ezv-IL_8ucQ z+kIHUyBQNQDk~(cKba-%l6!i5W~JZtwFjnLyR39@L_m=jsl*vy=JgvnvI}Pyh4T(W z4Sxv#gjV^(w*>*}E!GuY=VDgRK-Yw8-L>b^qd&8uTJbu94FGdVl7<6C&C9H&yX9($+ z{+t*28kwG^r_aijcuEc(YMI#7F)q|4^zz-wm)G<*3py~Y9d!Ay_jmi6n^&05nl{* zn}{bvJAn0QMt1g>bBR_ktpzt+pdw7LIiLk!l2yfv5-1nD%VCLGjaPKtd~GScF@vOr zoU;Da$q87z=b=^C%OIQDOqgOtkdjOVpee*eClB@imCT<+QTSI(x}lsGZJ zsOOZm%Jxf^bmnjnZ7^_I1|K(k|Nb39A&I{D>Yh0lv}$DkOX@>KA_rn4ntZ5O52&4l z=LJeGXBdpSSC)<}I{-;m%rPxzEQh~8bEbW2YNFYSa#`IYIZ+FJyl=&_nqjl-ps3@L z&dSM=1+SpTXq%JsYT1=HLeTbCS5pQ!8RD~-%>W0pH7gAbB?J)n@@4x_)9qmKyi(mY zpVFh(RNvA+aYMDDLZVOKLGq@E`%S;`a;Tcq6}&2VmJ3`;G3ru>4{ zAYy4%CvF-7Pg8iuiHP|@i{2=N7#dE<49(UpZTq`?QQWGjXYGbXPwF!B#9J2podUjY5FpSI~av&W*{deUy~%1xgo69Uy=oU{-dH zDUFF3{o#1aA?pa?S>Wk#49m)lI#&MQcUO+;Ng;s$;Wc-Iz>j{hA-~*v#IIKwzTYul zrEb8r#`Cvg=^xNf(gSi024mmd59T{Y1~9uFsOUR^BoYiXxq9psv;m^Aq{YBtrX6@c z%5tcU88|qKdE1JZZQbPO?Qs-%BIkC1w5%v=xp@Ws5wHQ#xaGvEG>^d^bDlXYz^1=! zNJiQVtJ7umv=|~qhXERYx8s~=U6ndqk2~e8;d9h(MzCdmZrmn?)6EG<5$eeG5cj(* zTecL?`QT(9{r*-*<=CZ^!J;4JuJ-)$B3ADB`LTe)o%s*|-0#x7d!V*s!X)_KlA5{sqieov;HgvRR(8R_>s)k`ltuLW+4L0Ia7>^m3n{H& zi$PjL{n&$hcKOre?}u9~v7W6a)?RD#7WSKI;4{wMui)JB ze@m-Y{wMSbfn$}&UO##1*PQq>CEpeLOgz&*d&oiSQK7jXn0Ve6zY0bUXbUa08$%GG z!Kc{8OX9)dF>Ywu|K2Z~Ul?FPKZ~-9G0TJh2@J(W2x$oz&>y+SoCzbvwZMB9mJuu! z(K55!dC0=qmhiAGt6FMCzi?fq^F=Np$$CPD!I#msspjyI?nBKG6lzdGDDKXj4WiK# z;uUcZ%}F@FwAo8zRAh&#nr2hmmwYjcaCF^Makty#)udMnUN7}LypxRbKNN-)TYE6R zFDg3uc8*`iz5Qnn_hs5ci=9Cs0fn0C<32W!zuSHs+k(&MtzUkRMtA!&aP-cdQ%i$( zb?Fi~_2|h5EAy)?4|V%6Wi}BQ%K4q{G^r(zc5_2zCMT4Ec*`>#a{E5AfBRuef(Fge+y8NF^!`;^4=*mcxOZWLUDxb= zvKlybnLwN+8d)S-FJr7PVp?$kAiHKuV`ais&1Aos>+!^T`Aws|tPIrd2^#@~@C)St zBeDYg(w6wt%@w&w_%Q3#3^v*>6Dl#?tC`v>M{!Cs-1hPb9**+5FGjq7;@C0Pw?lf< z;;JqV1rTc_g|Ol!lO=wE_hcU(bAadvpV;C zzsVHc_SmxmTkK$TagtEYO`Dcu=fY1B#oD)^?d~RyCw9m@J$4~f1Cp66XqWAR7!*ZGg< zY<1D{=fnJl;2gL1<6Yq>$lXp8CVVv^OAa1yl)1^P7}4 z?Kl34$z_f)X5O6-+UX*-44nJNyPHv*;)KFH1dT%6R!&@0KM?6!lV`!56ctx+bdnR% z;ii3OLni#(z6LLQy_~ikQ57G$a6#>hRb!}M^*=@2o<9Fw;IKv48!lXUcGgfXu6pFk z9@W2mi!Z=yW8rfu=kVnySEWw)wY7pezz}V=ii@B4GUDo(A8%#VePq;q&w4+d@8Fu4 zwdne)Xfw6>DX*&~P9x1l&p7~ZB^-DNvd>{u_6A6R8hKLP^Et<&ryjShS;TAOV&xD= zMb%YB<-yt6r=X&U)&OLNOuM~!c+i&EI4a18y$Ct-Tvo?i#_n*R4gEtte|DPOIB@r! zJ5>_z&o0x{?4|xVJp4mHtjve94^uF%zi1zc!Rmvj-lZbx1qxKxhM#+H)cmxV4y?>I z@k-f|eiA%ez2dhG<}1Q|A#T>nw*8m^!4(B0(9cx=C2JY4+^^p$tGBsZBO>C~-5R6! zd|P&{#;zsvcTZz{0D|X2s{urG@W1I)UTm8!buZ>a*v5GDT-Sy*AD91}(yg_ohn&JQ zJKwi+yUWXuSgp#$G~ubiua_m)7PkvF&Sa|yyAtRrI`B2PcI<=f?D!Qw|EfOe zvS#ZW-n|o_k=pD(xyk+dU7cLZCc1;~-=z9?>y<0R|95PCP&l&u`^UgLchWcB+Wgt{ zb+XBN-}BcWCh;`DM8%E~;XrIPSl(QoCA?%rJWgxYv=p?o<9AzFS-sRe4=B$v>&kn8 zm;CGd??@E5jO;~rp~&1sp%a729|$8l+|ncI@9}6M%#^?<<%)B#T1fR-JuyfX7p!faGcTsTIa4GlJ{n{ z+044|f*MEjKt4N9lNyTA6@3Lwe1D8VOiWBbRvD{=nfmHX8Vdv3g+su9`Kz^H<2Lc; z;c}NveaFZi`rtF}z}yRsn{U;VzMkGXy)%5_+V2;#sXXh+t5H}gw zf!M)Ul=26{J7%)9@3ZGCHa>px* z?=VE;&ohU}!$x;!T%0C`f%@u~lq+L?PdACTiKzec>MG80wwlV?Qq4(L+l=}xt^51- z5Y{es*9-S9{kd?Af=cZ#V-gy2XqH5DA`P~_i;!V{$_nY)y?by-NXU}(k0FLjkia;C zqEn+rL`4O19l1M$)H1?3<^1MO59Q`}>z|6q3i=tWaaX^;6@&3Hl$k;cH#>*7Bp+VE zlYrRF0P0APEs?@PkwF!>jtFhiLGmvp-qO+8+)d-xl_Y?U{orL7n^_a*lHjeVHtFo# za>2j&_|c&%AmMhzv;hM;6%yJrrc1l3@T8nrna%fsEx<8eMmiLjmjwp}RXi*)aQ{+~ zw<3j86a+dvDk=+G1e9U%iHUnSxaotcfB!BywBmR~{{`~O+8k>4N@s49WCGDpK4qqU zgoBC6m_J{CmfkGaQo0xLVPPyMRRazj4J@;XT?V0{AiysvCVFeMWIt>>M1s1A_-5cK zD(s*Vto56#+FFNG4w5eR?|9ZQX~-R#QMq6=rywRUd%J@20YRdChYsJ0df3Lz0_b^4 zF*;%6w{9?v77q68jXE2{tPC=;!o!tXT;mh6tfv^QAN{ZC|I+jr-~uI|<<^6nr1;>OuePcItoC_S!($nTbvl!Sx9y-@!; z!qMlC;F}1oG?rWdxSz_)L#|#OBN%3u@sSX|e&7Dsaw%U?Ew}Oi3XIh%S79|kn?|_q z{Q2{PO8e2HR^5Nw^bxtH>A60I7q+;1uVrA!d~0C04q&d_sY|h`VV_IGxNCaZkmisg z<+yBFHnL%^x6f!nsLmzP^5p^ehUdBt!}gtR_H`5~go+n#MohtlPIZ@rUz+f-FXHxUe*-}e;fLH)cZTS@3Lpc5ujs&ODpV!E_x32Ppu2#en zdBtZQ&z?23%)WD>)ce$%^YeHfv+e`a#S)5w#Dq zzhMZ;0boUBG%{JGf=n0}_I@d*>nzcOsi}G(@7Bn|v3mubp++($>6kyyV@@WLmXb6% zB}F9h+_b-RCHRsekp)yJ-8uyCm-s$|7^}mEs{Q*P&RScq`rayT7Cu%n?zwBdVT`8` z3M3^heTZDNu~V9Qe;h8qY5lW*aZ_BiU&A~H0*Z==5KuSZYq5z7wc&&J?~h?c`~6{H zi}II(>m_11i=dmC80m@S0!bfsASxy%7zZ9e4#B^NB}g#qkeP|f$5+-gYnV2>mc~G_xMim#d9i zosJTv>%69V;EtD<7VkEWJAr5bdxMo0MQIu28iW70y!`lex%u>GN43{)dO6UrxzCK# z2^-(Od$)%aVuRq|VMN+PgvMo15cJX{XKXF*pWc@Cpzr7Rn`0*_{~$(?aOD|r9!O$8 zL8ynO44;N~g{`BBo!#rj6!ktPu9^(j4cOb8z;EYKU#19c_i}da(5nN0eD$D+A z485nU*1olLN~`oudn-B^Q1&XykmUpd!2{GdkdLdTFk%>jZVhm6a>2p{3m4{bZ2*i2 zmLOt8DIs3tuQG`)!(IN>p|y1vuZ!ij;K~kcr3rf8VLxnI|0wYKd;EW1SgB1sHn{R% zv$%YCEy84j4r*ZaSXnsXy1fTi(2VyPI*?ZYIcu zG|){&{|O1|e($0A&ZSvFH#VHhsVm;}k)@l>(NHxZjM7;E-df0P5J!EO?|p4}-mdN^ z=cHe~rlK{ny0HF$_fKogHIy0Q-=m^iG=&!UGeI=R(8c3?+t_2U$=iv&d-XE)^}S1y zYB#|M$sU|^M+I0dYKe4a2Ja~9EB765{3=+qqxllj9zUK+gNy z$2o|sk}ZlNBZ-ViiBNGRuCy`P~B_Sl0RFoE4(xjbwUY~P* z&-w2;&-vZm_xJl5*Y#f4ElSBFI>JtkT3Yjm)EeimSx7HXRFba&ndhoK62Tzv->v>CdkMg8tinnvJ|30C#M?U)zQ!m&} z>$hyVoosKInw|ZYLxb$=Z=`o;)O3yYv)f-XEIGe&i=@k!R~DcVoU){$k)?lYg_ba` zQR1Qi6P$>fTS9K#HTey*$lnt*E02_GU;Jc_PyXSy5*~521C79}W$ zI+l2?6HEX(fqmX7^iy~)fWc_6I~Cl4l{wit^}lLr`mpvH*KQ)_2(;Em#Pz4y>Z>0Z z>fBYDg!Lm2LO)#6&-$m2|Mkt^&3=4^yZZ`elJU@@{y@l^sp$@L3Fnj^BVK^MhJ+uE zW)vk7;CodIHZD?#wL-5djnHBPziPwp(zLIEKC=d1ycn!;EB<5Hntx2ZM-YM{|K@q- zq(AJyNyOENIc6Z|5L9Oz>OXIN32kC4@ke!qANT11G7L9Rz5r&=#=+}B<0QNgYpMoR z=YAltQ<{D>7NL-XMQzJ5?bbP>r4`(nNY55S9)Hcde0eMmbZH3*o!?ce*j07D%#E=d zpN~dUSwwuoUssI{5ud`jwZEYLsjOsut&IPzd97dN4XnnD86%DMsXs{p*&4qZ8U`9_ z)m!O!2?)AV%W8UnwrtoRmihyP}QE~vDs%EUEH#6 z+u63jZq?i$Pxfhv<47if{6D$A1x&)J2p?#EVA;N7V)mO;6;``I8!Nz9d)r6SI>&jm zRNtM4^G(CQQOL(-&C=fU^~J7VHPn;atJcLHh?+7>{_Cf6ro-jF9j$DPAPZHPx+t?b zCf{9csA72a@@)sUnqo74uAbUz91)SVz$qkD+qwqSV6c4}iSX+q+d}m))`h4JJfW)JvrQO(>lRyhA=^;3sQm`FB3B&?IT+5wNI5>hr$9X2bLr7YKtEBX(e zDG_1q78G=JaDCaY*|*Xer~rutxSbH|+!8ixd$Z`1{O5a!@v)vgO{~usd@#cQH8bn{ zIg2u*)e)724Oj2aniaAx`W3~L;GsYqX@;=nh|wXJ$Y9_yd%a1GgbNXjL3&&G&-^%f zz6Iobw;nwd)zm_l-+I=f;t~6FB?xpy_EbETF9=5n|1*Jn3087UNk_T5p(Ez#IECHQ z+PB$w+vI;nwhmn+=JaYQJfqM-Vk@1NJm)Y}HfW6-m#5i zJKHtCA|X9FxfiZb_4+V~2zSVAG}-0^5^53@Iv% z2O@ETG+ECepaWm8m-SN6qxe}hl=RD`kwK*%a<3jz(QmSJV!Rhwe>i6{^p-6VJ{kb5vBFd~$4=`J#`k1L zuCmJp6=^&n@?1C!1aJvNJlUprF;&Q`xOS&5TT?WCe3|L2fiz#&>!tqya43#dFK{SM z1k*U*c*-j#bpC~qo@n6qvwo+lrY{^k2t~xR4pgm6P)YOJ#D{WwBas`cth|w46w;(& z`X9tXSS-Q@Jmwe{E-<5eKhH{3({7VeSJ>X_*FIO?dF8r583Vt}OL`rB9lH-5Ru!F` zlch)92DF(A64W_G9Au1m+|1!4b-FWgZl1$He#6ZD+J2Aj*2C@1dHJ@)JAktA1MCJr zn*Uz}Rjl8zK}0dL{x*|lPbpV=*M{9*ONPsGGqd+}kVMrg;r&Mt2WPC$17gBfBDncn4#kkNw>o6Ps7YVAUz^Ck1#9%UY@ncp;uZZ={2y=wubopjOmf)e;k=` zi;D!eZdC6+6_*|}e9~uAWU_OGOKob+b@)ajw?&;->#XWw!jGh;6PPzR!DQM)P=&E7 zDx1qQ9cQ(FF)V3%FcG_F%~&sJSwP@I^5hc9V|w?_kb$HutJ+-q{6eza+$HapyC-E9aXF<$UmwqcNyO*2yI5bpD;TWl)ptCjlN%FbWSqI&vg*HMA8sel~;^_D! zv(`?vb^{q0u=?ki;mcI^j5X(iLyf-mSi0sO2F(Lxsr=SoCwAK#Cv;j7?lG9cQF4)< zmjK=z^&*zcRgZyJ2=S$G*_BxBIl7#gPRiFYd z%TkPW8FtcR>iFHCCRW$S-bt{|jeqgNorcv0ZIqb2!7__z`sd!gITL(X!~Ub5+1vDu z^3i-8zTDzQ@w@yNC$4O8(^YhM+i$w7+_h_tS;tle8iDekVC*tI0M;OpK}qxn%WgeD zHJhaP{;fEuH}U((rUZYCWSFb4RpjUU0TXlNAreW<%35_NI9gfUKgPx)Iv7WV4(|$y zhJ%BHkZ`gmh5S?LJcF4QF$LPQD&%|f@WMTF66bDhZa&cB0q)4n}nC{pU4^OjYyHuFbUfq-+(*$=DzEMqQ%`CmoYV z84wy;J4gFCya@S0Qp}CXt$2KKz=8#l-`XZ_>J}L}TXm%m88Bi*7B?0E&Ax4WV5^Gn z-SHLUr9-q$tv9whH2zR-T$3bs@aN7;TC$#UF|M1tIlI@wUgA^~##0;o)D)5cA>WW8 zZ=yLQ`?P#iTyyiRgFs1{16x_0qRSKUPn>NQq#BTUS$8 zmr>(0wr`!m7855nJs^@+;a-UKCPOY z@q{LG$aMVl*y<{1v22J{8OfO2g5v-SM?wf9<8C}m{#R&{{W@}+d6qkp966D;z0>d9 zn02JyO*eSuqg}Z(vnw+GUkjiiXg0)S)Z)S%s5o`1H^*nsp0jR;hK9WVC4ZoU;RgeK z>a5JBd=#zhP0COMOG|Bjd&BD$BQy+5D9f2dB7?(#s#y$yY5%3&o*?34A3Y-a)g1`j zU}YNpjP`CbI77U&qex|?Y9(IXR^@PV^6tion>JbYetufEtC^Wed6k>NsfrV~0k>El z8n;%;Q{950^ZL|0j4$X8koHguHEZwuH7 zVQPSO;G}Bog35k_m8Y#7UG3u_^L8ymTZPZ1&)~shski@~69zuBVDaLg{YI59%ZdXu zfC}pa4lXT*iK*}UB7N`PHUV8dN9KAcLDs(R5ktk8ULu1Iv@a~@*EnX`y`+sr)>5LVA$v?!@lQOvhT3_2Vj=KZ~(te7`v&LK|zek4;$0|!93EdO3yYMO5=p{nx_NADPB+w%x?fl_RH zn^VOg9$P=&M|L@n<3~S}r_l>`R|Eh)MV;U-x?WBxI}m7AV}FMi)GZpP{lJlSgiy13 z@H&s5^P6kTD6``zU5sUe-_x;}TFEEG%r)a!d`VvOXf+q#$RV<_^O>ZI|ME<|FVniO zN6r2*^~0y;jI;UdB@fD)<3wh0iwCW9H+QO-N{Gs+1J1Ssoy^TgWQTYe8eL|(%nNOD zRDs?9#k5whzJx~UTHeHmUVpbSRB#@l1FOR<&ywl-H|C_1jikP)Qb@eujF}H!YY?qj zngU&ns-ipEPXyyVAMXFP1&}?>*7V)szeW_N41E4dmn8iW119uSnAvjkzR@xJuC(Ly1XE$(Hn7_Xc zs*c6)uFY6ZwM#$Uqwwd?@f77Rkq6FWy@i~4?U}+6A6e^5LmrVtxwfaBv8=?sj?_nS(m{-IAzU zUF?b}%HPm$R`y;_tN#ho=ntXx-M(dkc>jB^{}*&z#a$U8rLk zIo#dk&(h}EEvxP@>wtIPLss@`^u;Ag=Oy86_)CEej>g6pK-Z;tZ&F`gS*6@JSJkLE zHQs!JqdV+Q4FH2!i-o170>V7Pcz8yS9)e4KY8F)GmKnb5(XV9M}V8R4aar}69etF~1M=4^JGH~q%@aLJ=Az=%&(>g~o z*XSuomS9=>uK&ZF&$`M}Uru+}VR!oNOCa~~%+K}OTrk(ea?V$CoyAmn0ALGM-6B(b z!ZX*n)M@4C{hix}7;t2sbHlo2D^`p;U8Fbh@ksdsy;O@~?U@8|)1r!c91xCFjr6u@ z*uRX7o~{npkJ!)urbhF3=CJG*9fq7Uww2G9;`?ICegI1ddg9Ph5dpYY7G5wYw^z47 zqlJixI8iN-5C9op<`%24y}VeLECnQwcbE;0x&|zIX83YL0M<*>_bAYxZKhz#?z90^ zD7VEK6~WKkpk*$*?T%)dxfK+ct#B#r4)ul=;5w-S>|2e6(QBCI0DnU70ydR<+m?_9 zrive-lOWZmq2Gol%1>*%|IC+~X`k1WE@d=^qL#Isrie10GG8HjU27lMb10dF%FV|D|IX+fYbK8!PrY z#J0fa_U$8IZds7DjI{JKpn=?g*?-B5)O?Q+yM!qeGhLgK%p17}&n6Xt6HK&By|Js) zQnr!ZOx2k)W(d+ewzYN(9rIR#M8F>POoNN3|3Nl`BScKZ%LQP#wk8 z?i`lVDNM_pY*JiZTnewK6RyfTpPcyNlFM`uGDW30Nb*~^ZeauPvtg{*1^rRbWt+VvQNJffhXu>-anMh@l!+f5O=UHQb)X9 z7msk1){Yvyt*woY?0x1E zF&s^z;Mcj*;p-V)22Q3$tvg$GxFRxPv@Pz^LM;kaa)pxuT8&{1iBPnoWv+LYG!(-t z25Y;tYMs90ds{Yb%N)mNH9dx`D~w)vAv{^W+1KaICT79am*yIU2mpGCi?{wL-scwB zW>MB53s5N>LgXl$bQFIM561550tJ2jO6gG>H!isq@z|?iw5`aTpXgM-6BV*JM>4ai zgx)~^(sGQ5ihC9xKd1Y)@rCBSD-yrE zx%ZCqdzj~)X>XVw?Nc)9t1`V}ucj6EjPdv$=Gi~wLPN9`wssn_G~%~CIUJbH{4iGCa(bsEti|_|Iii6w-fa%3k-P(x@D!|!w>QjNtk}mv0c;9khQB*Zph;uSLLkW z;iBy-{BPZI7izw5uX@40ggwlKGJQio4eg4N^#~o6XuW^`evz3u0JAoI|3h33AP=m( z?|b*(S<0q*MYpR)?Se*q0i6|hpqTQoc5P0y!7h!axZN0HjvW4L$peolo2f0$UcSpH=-^|75P}miHf} z3+nGn%e(f>%p4fGck?jRFd$-ji^hOV(Im69P6FRzP<6gp=Cw+OIjKqGe=2khNn-PcmHwJpgyAzrUQ6x z?ea_ZdPQmU*#b}7yicDNkVuMTj;AG}JULPbgGy^^>~Q+Xbh<*AIJE4d5fW1tQc}Fm zos;3tK{Rli{CDgZY>Q>%yfwwqUZL6v$4n1W#D#o+yUzB*QhpCl8-EQF?@X zeZdD7{(k%_gEjV9MjV@3ne9Tn$PS<4>a}y-l(KXD=cn!pYFSoy$a7@mOg~L(H}MT1 zJ8Zi>@beQx1qH+_EK^&yWGZ(p(0J^0Re9ddpV#BOFGOzG)h3yjw?>%ux$7vApZ8FG z`iwBohdW9Z{ki*NrMYWzN=gYD-<{cEC#Z7_Qh3o8fczL7Im|Rhu2G0Z0eS`;DX}+u zOpG2E2ozhi13mh2+Ig@!s4$EmO@1sg!6_Z>b!B-)1-+QPL0EhCfSEuvR2&$9Shl7? zV|KUHTg5hh?ZHXP({i_qud?itsi(wv(I^-ZZeoAtAh5EzFpl-7v&T+W)n^HQk3+}6ND0!t7bM)v+}0-wO2q!x5Tqar4c5&x5skvi$g#!Vv;WrYM8 z{O&W3#~|iNQ%(p$In+6sZ0t|bK6<_kQdV1OZf=OW6&XV@B$R;awrqKY;CDK=UI%DR zaZ7V(l6M#$`?n~DX3p$8XwYjfZ6$)FPf-By?}#U|{A1t0dlzJ{jOw_?F`ph{t_>L| zD3a#sueDlKe7xgN_CIr3a^=b)wKJ`<6>XhM|4w!^5;G`)dMSiJx|Z=>0Hp=rgOe;I zI^IoYA$Jew59I@o`bb>c)T2p0!^WsgZEMoFHvQqj6+wsLiAItc<<+H$(83Z*Fyi>! z0KS&4TzM2EnEHghPa((s!qFrMfFD62f&dWsF4n%(J#!GjxsM)9+h#OM5ZWQV(3ilR zm9OrD0!cVGX-+;a(^&m@aaLV?w#m2V>P0es$Clj9K7I(CSoluCy0C&N!gh#OnIn+XplXy{hVc2uNxQQofRqtDCAPAzV~HS%sqR^+UASG)T9YUwxZ zTA8hv<_h3Em*#?i6Cp{2n-xEuG|)XZHiTwAS(TwRB_s1S--&R3;X7grK6146>wRBZ zO>J_(WzEl}XR{V29tg_VPAx-|xFPw<)RCaf!Nojn;U1=unr&kzvY_B4wzY&azk=!+ zw5!y%@Jw~%-0qgcGtOd{YX1QQaa=#}Ig{CFwJ{O`S_Mukohv)|byE7Ew(M_)u7@8d z6t;KI9EM?>Npd>Kr8(sxT*ROulD=QcT0g}hp-A+<&>1NQ1g;DcS_Z*&5U(*u>3kZH z9K6{=@V3$FT}O1rO#(V~1O|kai@H)Lc%>*7kki)BHrlmoLdq=JxeFGUD;fHpLNzbK zr}4C2UYr>{Z+YMcOMB-QmG32P(KDYmeqFahUM^z(b7bQAZS@hP32dtiHsmV_DF@Il z#1P5ArDqC!SF6@}FQ4GE+{oxKmo;BR)NP``WykH@`F^sKovYo?-5>MXv*Lz4wCuAl zeV>$bN9*!c7$byyfwd!0a{i~3{UKssG2#J|otx^6 zP;Ux-ePfM?Zxb9ZZwWq51P^hu2~GX}ANTGcPJHp1qKGlVqeW{2oYb;Uo}OEmF`KqA_R zBXmxrcOr#Gn~7)h6~_seTa06pjNIg~({UL=Q?=O(n%5@T#g+RQyGiB$6$W!MtLb}R z0F<%g#_0qa)m+VQJ^E;CyN69l<(YqO&Mo}<(p9Ba+5HC65q@}mWo{B@_1#^Qb8TnG zx%?3BXmx$6`gHMe@2m50o7HDVD!-3#7R zTu|J2w9FkwbQajPLuFJ6XnAR!+V3zcdV;2w{Py>ct#X7hlRmJOn8%T5`t&AL?&=(g z1qLmfz!RH)mnG~7iP0q=SNKiPO?}0dBPI~SPXq*fOK~TqwbHUvr}3r^i4n2tckUl|0rHFr>NCV8r5%WZbsuCgT ztbQwP@A1#P%7!*1t5-jIX@0n~WX$n1(#eiZ9m=n6>gdvWz$Azvnt{dixTH^YLDxKV zdWWo#a+5*y-mbw?oknzqeHE8E9jVHRWn=nfFR-dOd;NMceY9ln-b#}vpGQTqZEoUY zB+O?CV<-HQeJkdd1Id9P@Xmog1_82xUr_jo7ME}!Do$$mAE8T}VtT8oS)?nSE_Zu4 zX|Z4L6s@el^0|qQi(|fWowFK{q;rqGLD z`I~u2-73GNxqz@@EBZOt4<_Q8OSFR+^u{5M2$WWJoA+RV12Lr-Iv7TZg@axf&B8fB zn06cl3yEHuG7C0&Hr9Bi>-@_$ZD6ZAzNu0iA*JW}>_p!oaX=M?I8JmuKMp-y-jQS) z!wnn!Gi~R|Gf)jrb=ICkje*@}BTuJ;=9Z1?rYZJaVKv-A1O(`(+>H9Ab+Z}jWo{%aCaZn_V?TS`KqDbp`kfqoCX#C zNmvP4slc44h?wvLEn7B+&VZDF5=uroa3Lh&xTlJwh!cV; z9_ulrTAoMu8Rq!2e_C4)a8#CMg~*FtBan6|bm8KOjE>f>opuqQb>~*YWsU!@1;F7I zsf-P9;erLTZ#oPcQMuFhDp6rq^FNMoPY>DBv0Oj60QURZEaxj+qTm$2eK&E3a6*U? z!6G`8vOprrQt?3t#DikxR#h2NW^#nFmssoobt8e2uxz6X?$*8ghdq5UZa;hR;`>?Y zx!0dqS{@9EJNnW1^k>&rhvZq#1OJvwcc&yQHLVu8byN%a4F5 zN|b3`bjAX}R1jeFFVorG+PdE*3e5KlsShH1TbSwSgLXM&X#n(WNW1t|7rW)?2?asrS+SyA!zis7(yk z2g)Dmx7vw*Xrg_kDPetrXMx8;y}7ofrndd_%&N${@AuWX9$G(WkVWalo)h=Y>C@+d z;<)Yq%vreDf6}BAleE+;Z0s8accRz~^6o4zzwd`0QH4wadSp{TlZB>4jtgzs==O$qImg#eCGY#hwZ6P&=Ny>i8fe4xxe?F>*y+$53}D%iU&TEj zl5w~P01#Ml>j5k#)n`rqT=tU0L!`mN_84U|nqs&JbdLZ-ROzKZf4<1eb4iU;Bu7I* zp?kIJ$+X7tO6S8;Iz5oNUfC<}!16ha#AC7A@9bByH}Hm#vY>mCowoA^`O7h8hQJ57 zo#zH+kiRkNHATM)can})0aXB26gOHS3AgpLH;Sw&YES`52L^7wrtP{bb;9nLVFg?o z3<47q!|(-~1f!?@d3&MTL?xxZ{rX>?dv^Z(g5oWYLndu3*jil5lI=d@!z!^i(B9Qh zcS{c%Z@Z)_Iz2ek@vd{`qI|T`$V<_atw=#hbJcr7UOGdUQ;JZ9FFD z*iBV6B*~!X{i5(cO)1sM>ONQA_Zx6U**K>0Yh7FlG~x`5w4&ULwy(M!9Ng=~JmG>x zsLUD^^T@d3U2{g$SkFA9Pw*j1Op;aR`V05#PL)5`MP9>Ry0Oe_5S(9A!^zyjqAPnFQ*LYCB(g- z9vq@hzL~L|lZWU=k=j2I8Va~swAg6>v|DT&+S_A7l(FEA_I1!X-U<}8oUk6|l@AYF zRvCPM#6{h{JkCB{8V3%18NNfM{N|#ODxW@EJ+qkDBb)1`roO&d8-FXHbmT^R+pCL} zs1oTM3RooTfms=vE7j;K1Yuln*t9vWc+D^1W4Mc8h}@I+2onbd1}V&9HgUWK-&BG! zUR+eAr53z62tS!YgO0BZ8a73398Uj-4@YP?_S?UIp!n~HGbZ3H{*)(EC$=x z)fN9OC8gP6d)?H)S*8YRdZ4a2BVf)@uhpKs9?vsuYW(KK*H$9cxog*BSJleO=HE$| zlpTPTg{LPkFVE`+m3+pvK>xuTP*{9wu~J`AD_y(@5%OkoiYCV;4!REtI7brqj14d+EO)k;{WKt-N!ht8xC4DV#w4a?1d`4~HQ`aaS1fndd%OSd)0!PeDi!ak@t+(XZZaoRC=!Li z0+tMr>xqi`%U&xp|DgjS5Cj7?+6j@RGi;`vu;^1_UcY|bt-A?9sc6xLt6kQbF=OkS z*RLN~n)f8JN{6pJ&b#|{13kj?SkZ8c#GeRmOyjzzsQ6el$lk_`A0M{Bji8+oWV*V= zn;yYv;OSHubqwi-$A$AF9@+S^KE`4BuHH?Z!>dqH(U6YoJL9Rb?oO< zUO|sv;n*Gz`qi)Ykdx0F)hzd~j-$1xws>ZgU0iV@Z-L5GBy*XCYz1ItG}J^+2^>a@ zlIv?^M7bbtb}U`uJLI<(tD}Wk|5|BuOi4-M`uANbbG++w?UVn~{4^sxB0|JRQ7H+2 z08kZ-MPug7Bkd)~(@AL>r0t@~Nr)QyOTU^5uQbbBSjx%H3T2WrhOXhpe$0i`BVMlQ z+5cWfXegt@0yC^_`gP@D9yZio_W}>ognd<{p$KcANV3`XVWfv?thvcy)zJ&6eGb%R ztP-i(K&P>7%{zo5{J+)|hTD8NCw)XZI^^t>V5>3Yux9lpP1^S4@CY;4 z+%G>qy^*YpPT6VUT)QTu?#hokN3J@gf|gT;&?Te@X&7+^yH_+-Y)0e)WG(K5)$_)N zta9lkA)qFbBye&rgf_stvI$oSu}~rh!eZhe&M(UWlgIsC6_~!4m^lbrT6}ivIkFW1GCNWg zGHdB5haun_8-@4O(^7xZg{rK!d*nw8*F0fbhFHS{Dur9*KTkY0&151Z257s_$3Qi& zV_Q+F{GWAC2R%>dFRVcTb9-vPFC4Ko6r~MT=dX-xnK$pn8ND&b^j&6ZXo%ztraTEB z0k)0w%*uN~*jr88#VpCRhIu1ObOAV)}c+9|x=^w7Hz?@)9-%m2%LOGm7Dn_1=J zk^(lTuI_&1xxZxm>62AAAm@9^s$bc$tEj}y!(;!eUvHInU;dIBw1+59hFkTbf){gk zB-{$G1jPO!!@Y!CGak(nI_-_t*5vf`r>I~5`>p|vcO2_VClEn!g>j;2~NIrCcrek~l;9ke&urzir2kjX|Z zvNh-+&oQW&_5eVHD(n2EOM+=bhN0cwl)_FYLr+XzWLeX zjSCu!bf)$9pbXCnjD}1k$?Ksm3!AJ6Fk{XihnWzt0^Nu}u8QoCL9-4-rhf9bj+i#l zM>)N0AF?uv;)QU>D?-|$f2Gv+wcp(#*$}YxT5U3Cj^oJD{#V7FoE#`uT zo1A82A3Wo!w&mR*3ONC7qbNg@A}uY=5;|G!dhAE+#RUaTB`WzIDELm0GhndbxQJgW z-KW8)&joPdkSfCN|BCC8tZd>xY!XhZ95p(elbxMvIfYu|W_p?X1Sjm)z;HeMhHdD# zTHKob3f3x|k$2vA@4L(;Ez1YPO2EONHvb6X_C)G_Xt9!rfIczrIa#iVnTDxJMw&HE z9n_Ojz6K{`4M8&k#nTT|z!ht`)fCEyJYa^~J+j<0{_FxQr|}foxcP1w%|zsgiIM1t z8aNOcve_3aee-pyeCRMNCasv8ea(eslZTupX}&L(7YJdv#gP;k5wCsZeh${YAm!pQ zNo`1SElTNP6Z_!cVrfJ^Iz}>)(fMau>pj1PZA%yRBG)6`+qz#VQBR(Ts3C6YBX5qq z*`yPYhGIve0~a+AtB_hUXpg(?9XsDW4p703jV9rCi1Q!dLj=)gXJ47`F<=tDU2Y9= zlO`p3pocG@lf+-1`la)`TxnH3jGU=s0)6NxdwiDHKjhT9$DwXTUybWcSu0k29^sRp z_;kO7Fyxt;$#J-Yi5`ZxzWF4o!&norLn-{JkSFh)mKQaAo$t`@%&;4q*RJmd zHKw#rNwSXn=q5{S?LXJii@0mj8fJl*`+!k#KX7Pi)+}X!poEvgAYhLuF zF{vgI)Q$dukws##Jy0^U!at;?%|VI_M)DGZCQ;6*C-wvnyANnU20XVFSJMUx(x>-1 zZ%BPAmA#)i>C<*yCZHiYqU+yNBm^mE{%8qn8r+2Q{R%-C%*m#=j1-`^*;^6Ot-nj4x@f2zh)JOK)d zgf(Fj;g!HY4SDcIngwF2BSLVF=tSYD(}YjuJ`PtY)~;k@K$7;)oz*Zf{;9 zS`iS!t@MWT70yny{qZsB?Y#V~uVrO#HhO7^AEI>r1QWq7u$kzvBH0FrJD&Qtn&f_o zjq~|#pUgzjqmk2XA}Alme{U#x>e-gX@p6@&wa(^u*5}Wc>HiONFP_KkOED_CM5K-k zD$er%``_bifC|YWGH&tDU{u(-Vk|C;k*FCFWy;nS>DI@Oni+PDNjg2JYX5+N1J_<# zYiKCt7-Lpy*I+a4u-W~mIs5^TLxOL1+x?9EU8kt`bGq%@XMGJd4*|1*(?tYU*Aw^q z2qO@X5r^$S{SJ@A!X7ZPhGmZyCG@Tf6I5CHW1cCfAMso1(?!nt3>bcM)eHXdY1)%kEZWs~cr`#9J`);Hqe1(c9CX z2-cTgnTtcPIE2?j-gX){$#k31?y8suDw5r{wwt-3DbuN?!LK^`C#ts`+BIqApCbF; zmZTad*Y2>^zE#_!xZ7^5_{b9Y15T+IQ=Iuicn#cOiZ38K6Dq;whFUM_5D*WOC%dR| z7_byuQ_5Q(@M#P8<+H%ov8EH^ZohX|S8D^Wp(A6U$U!2sSQTiRSc))2eLsxZRgk?5 zy)S(}My&+PDWUty7Qj(Bw@mmGXIpN%CiMGz>HIbsO|)%*hD}@rVvf`%wLJuuffn!^ zY2@ru8+^s7!lRw5qjxOonTxrv~*&}F`xxUjNts!Pk6}Ml97~J8fZP>as zkyuDn<0W7ptNIt<&l8Rf%2_-n9U0$#gMtoSh}?ndIlRy@P4{|=(O4qh1SD1Scj{an zK~m&RDXf4OQxF2PsHn?)3XR!IDlP$O1^Sq6Kyskd`H}r8iIx_(C2}Ab906iJ<47eX zk%Z0RN$aiIXdxy(pWGy`@qO;9fxqAUh_otepCxW5!&yxu;enX!v^G*tNSUx6^4aKm zddQ5|J;bTe=G`Zuqxzh4v41l6{#v{ERMePf8Mj6N+T-$DH^ynR+U3S1^S0+Wi<=M> zC|y_>{UM>v#C&VJALY_*lnY{V>Nh+z{jxva#vz`WskGCM93X%MlbzFTY;8voF@mzd zb6C#8MKc%9o_%os%n~3_5wA>(p_1KC>WFFX-X<*vX}b!wq>zxRz_4TG7tGU#|Ni5` zPN5I%vk8{$G+g*|1?NJ2M!HtNR`lAPqSdgQlMq!@9MiB~i3Amr;pQuzf?z|hGhtpu z$dt^Oo<)O@oc z==xn_C671dQrbN=^K;f5Zjn1iOaSx(R;VKe=XkUtjSFOf#JIgnHj@6LP`g9#REPY| zvCVI5Bh5SfI?44_8Q1PY%K2mt(0d5>H>sT^QG^p0Ezy8w1?8u|_N;#vMDjZ(`zh0= zfkHoLWed6O!-r`b2F4oP`3AR!ejq(JcL{<80gg2_VS##y<7|PRp1_Rpi4%)94{4vY zWFEpWw3Dbo5gfF5cvPgE%kR|HqDX(b&8utap}TL+XlU5_y2?A&9LoU`yftwyF%R~c zuU)$%t+0H%kR2iTMZJp9!b#-qGVS5=;#VAyVx}8Nc>ldmycpZWkqfU!soQ$dyb~?3 zuzW0AcJ{$xT0R)wJ25fW!5}&%4pHjCS$006a|o|$ zUS8!pzmSpuuLnxc^`Ucd}R$}2d%=+&j z{wm#5rB|~!Lzr%m&$tySZd(N^9;lR-Uu{d%sg_A`l` z)!u}l^E(^KWgr%i#_)3boyjoA!@}}*ZrwVX6(XFuEE&o)QTJk)x!ZB4+GTM@b8&$> zEPq`@@%oZ>e`e8|nRi=b>$92IRz1fi>d`Fkzg*tiPNW(Q3+vYRBycK^JCU8GHT;LG zmT_8zeZT9gdlc+n8e-8yx>7}Cbx_v zDXGg!B6dxU(7pKOrk^MB5a?4;ZjIT{60Al{B)jx|1f|hu*}?XgrB~Zh z?_3x=X_E91M`s1Pbt;TPIP(soLJ}CVb4%=KIB$V|Ak15P{JZzOqP_diGP$rgrXf$v zRRiG$rxaWw55OP65Qu$8nVp+Ai=T#m>2Ag$TJH1E-W{z@P=Zb;IG2W+OO;oOvXxlS zmkQ1M^j?R&>AYqQQWMIHGNZ-_*G}Qt{_m^8JzdS4Dz3XDBoZDAgaxleP>^mwq3+7N zbY7whLWm>)CJHx`org~%QN&2jKU`;`9DMPj=cnCv%A;0O>Chlia09?1{y&QF5;qxk zaqh`3mlxZu*}nrV1`{6mNwAVs?!d&U>FEgoj9}H9(93r2(gjnY7aZ;K+n27^Pn}|V zUHo%h7)oj+p1mSA(MS z<&uGq>e8j@U(~l3pvhtP&)L~%`i`&*Y1JDWFWJ!32Y2l@@zO6B#;u8LSDF?&Z85UZ z;7;`B(^^O8xhRjb$QbuJd8+)KTQ~~VEk72ayv~Ee7dV&vDnr32a@bZ@%25Y7xz=y> zbHm`kmf4JL{*=77OX}V|>@FP_dsT`&oxkH%`;Yjk;+jQhBsM4_{MXYra?d5&Dy{r~ zEr8ML)nmd^E8CkL({%x91@TBgVf-dF0Ui>Nq{Ceb05_Ttu9jJ2m1R!MI3H-8^{SWb zyT1;MPFr=DU&X86@}H2;2;GZW$Q|xo-YF07y`q<5dD@47nwTVCcfo{!GV97rU=nZimOJSwrO?|u3hfulX$KiS-+X%vMh(P?`szsz8b zcRm4D-i1l_#%FeN6VaY9^cC-{FXb1!j&KOD-aBo2!F(7pF`yne6~*?o`?;F9v6GAz zxvm&jR0O^AU~`YK2x4`rQ|ES4h|5xlqZ!2f!j9k{0Ym*O!$ZozS;qzSW;iU6&I7!IvV6yPj0_ElG}3^F6{ek@2I2>W zfd}=O&Q}wIas(0vY0_g&Z0^N%M;=yr=X+@%HJo**+3{DGKi}jF??)GO5Bwr=)t%d$ zRrL(FGRsUbw<2@_kRDg17}d&nL1w|HS-zl8N0v?Gao6ORmCA@KuKeerSb}1U?sFpx z)NR_|rE$iwq@IZx+Cqu`?5X4<)(skrT08`5FssTZeW z3zZG;R*f=+0ulC%-1_zXffouYD-FmLW__~%h1q{J)CdpBLN!Av7}6Zk-$}&6(A%e|)U;+}BG3wSRl}qd)*R zenTvnsBpLo`F(=+HuT$qHrlQG?yXzzENx$Y&sdBl!E8@kl}P^p=y>xX)3O>4F4zn0 zhnpVASajVWfsmb@^fw`uDJ1s@NfCG}r4!llDEp+&oePyFQ5Fsx3UtG_JS)}S{rgv^ z=@r}7G&>HOA%nT^QLEWjp9tI|BJGY~GlVGvFV=dTJPC9Tv1%Tv#JNKYCGeJe#?OyF zi2ti4M!V(HMz4p2SfKAa^7}}9<%xK+a_%-758(T==g%w7YnLMbp9Lb(tvdK!*J+m* z|EKbRY1zbbFLmvnRPX5lWB8u|^`fe|C+8}{#4Wh2A&#W`_lGiTU6H7xaH#25^5qFJ zw{BnQ(rA$6RiXVxvPTaAJ@6)1TPo+Z`1TK)Bf6o##_yf`#j-iUo4WMhkrXXIA3ax# zSQ#`w&?pVrwYPVFgt0oacC(#$hNM}#GIVHF=|BBtWDaxca+QOKEc(>*f}fx2_^}P# z5MCg9AZZXoBm}5i_Sh7Vwt#Y5^xTxCDDBPm7xgDV#(n!=RCzwmOY<+*2BlxVYI>l4 z@RVs+itLN@FU|P%(*5N!&pmLL?T3?b}Fh|(w|zweEj zukk8aW>oOXBvgGunobKa)JwBgB<01krLe84si}$3YWRfNpf|LsT)NC=)k*Ncg=_lD zIb!$Czz(jzdJ!CUy=ni)h9Nt`O-3wH!pg>GV7&q`Gp6!CFl9j0u073B8S?k1o}7$z zP&|)3mli8lk}l<;XxSb=zDP<2Mb_Bw(|nQY3J#A+fI2syfuQ2~#vB^yP~$H>KM9ut z{W?`36U$U?O%*Z@<8csmMINfL80m!26pTw{pIbX;tacg^8CC5zm~xNY#i}`(~YA}#Q5Q;5#y7( zcDtWu`JDzwVA5PL9L!~vm9O5uJ;~qXY)cS9O}7TU4e+ckByzce9Hfg%}6L z0cKKym! zjJp*Znp=(El1w(H&E%dFRsR~QwcYct{5OyWHnjg@kPoDtLu*aqkt_LvgfH5=e)$jY zCqI$?{|hl5w2pnK*%nnMwdz~}+Gj@j;q4s8-yHon$-)lSLU=Yp&l>_ijC$AQ35rXzmF#lcyN@;#MNc&t0V zT&E91(cImGBptVXq+^UPeJ@C;1A_y2E(GB_Kb!Zh#50`v$V(>)-jyf441k(Vz^|4z zTD_|-kRZV6geR$C(V}n_!WLy^DE1>l3}$Ve0&fWE&2jFFAlGkQjE>S|y+bY2LZgSchl2}m{>y+NWiss(lQ(qikEDMOa|_fv?65>J z?9p_>R>G_4Jtrf?LQDWjB}lxVKdH=)3N5L*xpwIm>YQ=(bd2Tkrz&PEvGVzz0e9|{ zj8^@L44$mzVpM)|Fe1P#1rHPD6emus-a3D{^}zA|aV04UvevV8kIv{9Y1s!EML|i! zqxXsEb6i^@TmyK8Fe|;0_#=Qsa#^hlx)P2zQpPxyAP)@~FNEMuYzl6lwG-mu5=3|+B5%@vUNGB| zkW(aQr*Odpq**%9E(ki9XRRLgW^bCpqKfSGLEA=2)Y{rbsaO#3Ex_kEq;tpOj z>L<<}M(55e5z)w9Afk8#A411oaxT;TAb{I!i3S=lb&sv>{BhobcLcTIHz7|wNTDDc<`EGMn}cqercD2B z=r(5Tr1t2=Lt3nsv`fB+7Z&^@Mn4oH)Dj6CnPb9yJ&zw}c*>Fs7XLP-^Y5SDm^j|+ zn8wxzRc_-sPz90<{>H{9(33AXRd`DF7U_Ta@3dwYsUI>`;ofdXL>Zlur#> zU-{dvSGY?EDIOz5gdk$T@nJ_|zvpHM$2e5}t()j_&M@8x4K9y*3*8~S01c(Y>#C(* zQIy{Tu>;Q$erDduGt=dEB&9=$<@f6-_s>345Ex;WNLptQ2>YB*V`wpv_BTY^5?)pq0_^1cSmU$d>9uNW}4)0LA%sv+rIk{R! z9Lr*CHNY{aSHu~w;uMEs-XnqnMEpA`%JP4VY|0OyfMpt6fSiRmqAi%m@cPh0na=3imYnt2k zf3ennvjjG(2V%*=+y-(E1sz#C5CB+WPG*@oEjeC)IBIAXmpXrvP92N}il6xCbJwpg zfg6`O(V5l)VF4h@O^|tb0vOhiPiKD`^!uwv;oIaRajjiWdc-4|ipk>T7&<0~`+l=n z)QG~C*K<_(2yv^-5D6|&&N^YPjIOr4Vtm{dpAk}Ds(E3{bUn} z2wTcru^{^NnKauaxOtCWlJ&alQR!=Sk4Dv3U7Jz;ae3Q|dNOd?T{)T$|JV z8lf5hKc@e_r_`}{NTPn81HS zn=ZWE5|ebjCFN{Bi~?}RXFC03Qu1QJp~!+oB_@o1NG-)dtf_fm_K;UBt#-+s2A-Qe z+pjNZuc5G4_>W2u??Dv5q7)+?b=jdYwnlygk_b zuB6LNvp#xpz_0r+eaw$Om^h-UVSBApR26*>Oicm_Wbp)j+zSd45-c7%egsA1Pr#sv zEPy-j{qv7784=UZ3qTp9heS27VwY_{L{yS!e4LzSirEsHn$R9YnWGDfzsj_Kq*+ad z4(g9TmM_+7NL!d{GdGjy79Qba9*@q7n&A-i4N-jci zbL%BC;TS9qWP?Tk4JNCB1`L&r$v*3TibA!+N!3lNwk;`O`JKEcSz>l3zPu(v9OOla znrQV=xC>uAIu|8q!Wc6z%$=yb0OLe<)0`KMN%9K=jVQ-?ltH@4|L!IF2(;M(vU7tmmiNZ|FRQrHFy*|3PppR9b}rBNG#db=CwMCcig6 z9RELBh5zioo$Av!jH!G7cEKHJ&;q^^4kuTxbmiH@E6IQK=+n8Bm$>Tt@dbfjIogLw zhazt-SkRMqzeCT(LM z9o+opR@u<}_0-wOnepW!{y@nsKjQiBJ(;yz^`Is(LXl10jV&gEzU1$M)1Ml@=CT)JM4SVHemDJ_dfnubg&WXl(2iX~kw^ymtoR(+xf= zvJY=a4A3^tk2%|k>@(xWaGcH##yVcU%GV6r@1ITj&&~0kxwXY7YY>AO-X|6jAG}prLsoHTB|hx$}#ptE#@Z z)O~&PMZeAWZ10Anb&elOD1Lc@SoQMg0pbL^O9()D_1N7JVS7C~;Nx$Vtb81_h@ed( zg!UAt{#^*!6CV%6bIfKH}O^_$3vP6*&=qO0IpYmfnNM;t-)R^sO4$X*5 zomd3TiLQmMWV^+Z2Uux>|Mdg7M9F21;cJ=CE1yn?`F5h+>eYm$+neoUX}E=hI>Ist z(#(qKsP6F`Uo*R*Zjbx+V-QafaY~kE>relWAN7Zu4;!Nt}gX>ddO4Tn#AmO^dv7-inKj#KpSOzc})rN{b=J|tXf>28QQj_cNl zljULrO-JF?gEwz_(IUjF$9@f8X_HV1cWIf8CPgTDC$K8 zLK|Y_@}g<}5l>5*ty}*cc-?VUSF?>@zN~R?JrQGlf-e8^mB&p#=~N({OVL~s`yCz! z|KH`-+H>wEns4B&PlVJd;3?ydgfZQiBuGp^b!Vqg$E};Kex9wH3#UK830x z+&-n}m>hvMfV73TJv=t)jl^<;KNuGjxHVkO9!5;&btsx|J#M0OM_HnVHtOqRm{i=uLn^Xuh+cPl-KP zJ$i)BIyDKI>i^eCC<74yIK)iV5fD2hT|;UvA~~JzAJ?CUx)ZWLa<{o+mz?f(oI7Nn z&CA;Pr!4rl>JjuG4UM;8*V08Q%cT!wx1+sj2($2c{i_ zOSE&cbHn_Ig?JXy4sUDwQ$d|)h;_HHgCeSsCWXW6iju#85TFZ=cnk{je_AQ1_vH6n z5)>V`sI4LV>T8!~1-txO*R94u<@c-Cs!3*~9YNbA%>5tbf#0wgnD0;`yXgNK=h!O2H2|^%c-tlwO0Z(A;xl?Xl0XYR|;>>c@Bd%Q`HxLax_+%VEM0A@rZL(pn_}O{q z(D^#jf~Oe`yy9OZmK_s2SV>LhW@5u8&=VN_!H$c^0!b;_G14jre-5#F0%L`4);ZI3 zx@sq8t^KZtgmOYg-nidnR^*v_J8`2#J!kBzw zaj1AbTh;-bBFYM>ABgNUcnlmdj1ESbDV$r`SQ-5p+!K;57V1J4prPS6#nN9+FLl9! zLmPd|{QFhcJU;QbHnVqIO_t^$`C&hAUBJJJD&SVz-x>iER8~&K?}cjw_22LJd%1|0 z&lu+D(z$_}LJNFa(+Ef_)~US+JAZy8tSnJHaM8qSd-VFZs>hAPtP3?gbX(S}O%UW! zOfw41+WWxS!-{M}PNU~~%V-VXhS|idaqi_3)CEA~7a1jTxI=n8Fk9LixSB&(L50}) z#|s}yxz9XqV6~%YK}u@h?a6;sSChHV-rD-n%n^Q%k;_JdR>8g(c4HhEm^tr}djmw> zlc{j)qPHcwYv=2}x;H)y+974Evv==8jVYFj-)5eCUM1>!xGmzJx43YIK+aT_Q)Bn3 z(hf5s00;)L0cTa{M@R)QF77~H!eA#|bz1E`M+3Y#rZamc&I- zQL(+^KH8ikv%-Ks(7O#BI1o13R4lVV`v`hmll#20l!b#6Q=D0XD)i=5y#5a)uibYs z@<8GtT+qM|xtv**9-An}Nb9DA8gSFjv~Um%G^b>YItg9hUs$eyF9UJXXgw<`3Ssj% zKL#TmmEzKGTeJ+G+6F}I^gAN;*6f)Xq3x*euSI-DZ2x;>m4X&snNAVh*mGv@5tILP z?|ePuXxuTG2%dAd9(Eckn`P1oeAIKo8xNy;)J=C7=P_)Bx+Q`O4BtB^2Z24?`!>$g zT6L8^L;^&g_Lm6C7>_SDS84vB|IY;&zPJ~7Ob}yqLP8$&4(uq56%=CEE$X^GUO#L6 zkvB6kTe@WazN42F6Z2(B*}$U``yN>MHJg6r=l>~dZ*|CIp$PI@FdisQ5l1yle*Nmg z|JKu{`u`uuPW(vRd}-FHoLf4TLuB(PBD%)zJwHY5oE+7#_d zu=nF9zP97mHJ%&`AOs9JZfm_Jsu;Fef$u?p;_3=miXn|Ch8dZdWlXUM2X1EJFGaFI zPBBt(S1Fq{d*?f!)gO?O147a{GD0`B&eQSr`>hrIqOs}Tbp?{%(!jVK6s?taaHnYHULo5t6M+}Y4 z7b=Fl$B#ebe!|@*p9nM5|IsK(zM!zZ=LVm!9ZX=|v11v68dm$xTJyEC#5!Q6^i8XO zJqNPB;`;TFS*!M!EpT8$A*-|Imw#Tx=g&fH1R~Cl6ipA%8nB9Z>_`D9F|`KX7@jfD zi2gz>ItE%4wq-&hz?70jn49+vt7$J5>@v7-G^n|l6heCtmLiy$ke}hcwK$EkD~LB6 ze)X9?94#<%e7IGT3U?3>;i8WN_V2O0N7t@7!WEh8z%Yfd*6B}1->UY^+V;%$QPVHZ z9YV4VfjXhpZ!6{{*j)Xf3df~>W06l?P0F(GPT#Lv0jMUX*6Gco@R6qtqtJp}MtzOF#a|th^LT9{|w6|5IOsRAHR3oQV)r z3I{{azi!)$7nqatAZ3)VXsJ5RGC`#0bG1HaqJV`IcvXq?Il}xFS44 zfFHG}ioh_wzshRs9(3E>$LD593tsQcXo9SgZWk48e(Ljk%dQy>Q4&p=b?x)Ch2ti{ z6Nbq++zYsA%Te&tj4)m~dhUyK)5$2kCBJJfB7YGtEFUSOt&3v zKT0q}U@OG&+wcc)k|LDI?mO2OlLO|?y!3a4S$jT}VQ`N;35rSaIQ#UO!FZCtLPba) z0=UP=6*GQNSLVyt*N(oU6kYbfdh9l}cix>YUzs>8EI;=BrCi4^GdLoLPyaikJw9Wo z%IfOk%%Q59ffCC)&e4o9d~o_$!qmRmmx8V&@1O5*?jMKLf?sD+uU$*cdcv;X61T;^ zZbjqMlpDj7UrOrB51MFW{$=8QP021@^4$IWZ7xickNqI=w$ZogdGw(PUwvxF)qK73 z>zxcA8Ky{ZY^)Ty#QU$Sg*tDZhR{8hCtmf_x&>-poF4>NV2_5{~_jhyR>Zur;U0l{1C2}q)<2z$to7;gBa5a(9 zpMHGzt_*B|e<5YIkqVs3vjeR%GNXnbFgpDD*9rwopVn|VXZGGz1IWE-B@)>mNud#D zt|`oyCLE4Vb1F7Ms^tAPVdBTx(T?gylC_3=_e)uSE-l!-yJ^4Fv1&r3E%S9+H zToNs227qedUu*Z5Z=M$PKB2q1dPkP2sYOi6XO9Y>5#9$3J6Xnw*kLBIC>TaX4#{HI z{14u1^47b$PTwEa&tJyP&CcVmY4e)tyB!i$E03Mrd)v_wThjE670Tc*QFM-@f3ZB; z3T6<4KV^($kwcj4bVEOZxPxevy)qxtCEFpjZV)ED6*=R|D$G;43^N(b?+OL?=F=8Yz^&DC?EVs?OpI2JX%M8d6G zeW((xh-nn<4aOTxCT=e|_hrA(b7Zxt)7rAR8`G+wccx@2AveP?CKOB!*PP&&p6!nO?65;L&qdsOD#H#F%-*1#&bA6idJ^KDE z@#F?OuPU1$xh`rh4ckYI#;5~DK@Z5m=+O|mJSqHmiQU_mBk~CK-h&HhNJ-CH-8v=~ zy4WCHpy{QvmVFoOoOWK+x&VViOp)ehh@S+n%vx)sFqX>vGH51?#1v0&S==|0f@ba>2j%5A@%% z7V?BW18nY1CvFe6Xw{Q_^QJXOqIc#{;=Gtu3!*06H!aRD4B@UaQj*A;tyL6_SYx2z z?l8rtm*)81FCt?c&dl9OpRkRZUDRW!&38k{6`KrkZx5ZSGr}6}Rh*EWCfkMJkhCPr zuP-485fL?{YR3>rvAI;{T-@-ec^XRRaUF2gXY*&y|whmwUtFg5osyxi1EZBL%X8aevtSa~%#n4keAx zJF*r9I98&;^x@#!LL^M669are6Z$JhgBhG(HF}rEv6AoI$Fgd19MBTK9zE8N-miPI z;kM9~GS~1~qN2CY8tUSIWZtV+yHQx-dAD=+kKSB+c)Qi}6l;?2E*R6@&gnyGR+C&` zcc1c~e}qFE@k=;%(PtPN{88e*x;&NnZ8$JHd9uNcN!6S*`h7GzJ7GrLE-qF_P4pUf z9x=r+X2BopG0oF{=2koXu7CfpnZK#f$AjYm$Mk3HPry(2Z5~aX#28N%P>Q<@!$w8W z8QWTZ{sY>(!%~}O?gJ2xFkuj^AE=3!W}YdL+xg+cenpj_Llw5>t9*rES~` zLp4QX7;=O3Ga`5G5{?7R&ud(RMyV_LwKgue_-6mqnHixp4yqQyI)J)C*sU?+h6czk z22FnaV5x0c(o4hCPrP(Yi!zhl-Ba<5Sr>@zwlhXuj?Fdx)SY;Y$Yh!eTh7&qI? zB68EMvNXCm@x%(BxiaZl-T@DB#b;bEBo-Y*q`0$iI-#To1K}K9vh!uXX9*L7bhCX` zZO^o=IL+5rU>xKE$H_Ps`{Z|7Mmebdzr|Yg(Xk(OlD<<)GA2Q}!vUC@Y6j z&%*H&*CC@iSj5taUCT{nC#ghV8sdImM+NLud;lH=B+n2Kz`&gM7z8VeMTK;GFZJloS|)|4u+EZc>~cVG zZhBBs((k0uYwT3_veDlnS*61c zYDLuV8(60ez3Ky2CSxIPax=ceVg8U0V`uN#Xkq*RKgVG^awm8aD-pxEBWw9TG+~R2+=t zMZ_Y;nEZqOXCy$n66uPmj2ftmiNysF6(V8)>`{^3nBF1o2pKfA)1*Fqm(_gkaR0_; z{S|9A?QisXV0z>DGf+p)+1QO=6lpdF9SEACo3y6TZd3twY)VRvPhIS;z9kHJ=Q2CE z3me*S-P^JCTW<~P-l?+f%4e~e541AaQadm*QmIehz9b=8&_;s#yNv;R5_5^az4+(< z9k)@JB|dM@oQl#o->eI@?h-TkhCcG)Yg%Wxr!W@Z?fjUx>siQY)w4!{P48)$B>`IiN_mTPf$`57Q713Ch2ZZh zqz05fw9=ZIniAA=a}#=o<%q3ARKw!bppnpqCX232q-A``cAv04o(JVL?jg6IQLMk zCY@~vzvskUQRFImO3GjFSXtlzz;2?_9GTyK8KI$f=ML)T1ecbp15txwP(i`1q-9-t^JXVZWwt;6s^YKo27)sKFSTh-zmf?Vq<}+jz1AH+$XKA#9 ze`^TfmMXc}CV&y)SqaM;eS$1JLP_KY67dCLP~&{N{^CQUz_}W;;_ZWi+>+d=<*zTV zkbkP>uHtmjuunPti6~!jNA1jGWeCNcr?~*&HfM|gUa1-Pu<=1FX4@vcEJb-fX;Qzb zF^Z*c&kMr`PL+s@tcF4np+PbAn&}wBN<$Ipeig+AZSk*{=rzk@v&M!jo!fjPj*cSt zMtD49n-g%)DUs68zwOV!)W7xVduNZa8ise1kIJ`zplPwX?-6}Xa&#=09&np3VEmKz zr8&PgyicG~6le}$)B9)k<(-t&GvsxzDrkINgPV6Z;UW%4jx-V;W%^eh0_ZRlHkc`v zDDAmXrd(9tB$_D{ZNWS|VY+8Ypb>`{z9tuca#S9xh7;%)XnZNFrGjn;P=j}ufd&vI z#*FFduTLLMpCEK)pQ{X5A(H)%KmJ4;_7n|f*53p5dpDIYuvauF7+JwrNK&~L>p+WbY0&hE(L&q`~*NVaPyvUngKXp?Z=FgcU ztq~nw0%P8WrqJ{<_<)7x*KXO*sYb8)GRwp_JxB`b=*CR)W!KVge1!X|$4#v`?_ zFG+`3c{pN#17GdG$6+%lc*!ua<61mn5~>Btq&KVLzZJIJ3N7d%u~4rEgd-uDqbhit z=_`uPP>=>>7|T|#F8Syc-rVVT%l`A*JO_qt8+cgSZ;aMZ{ToQQWnzCNtjC! zAGKrTLDxlxJ^!J!nH!^zveya{X$n6|i;ZpiwOv%!MfrlR7 zXI!#tRyPeD3OiBYvlAr=u!TDbTSJzGKiN)~c6kfI68T59Yu6y=vODfMiN}O{9=9%N zs*c6ht?5TIyg$6DE*@oU+=n`6GNyYBk~Xlqh9CmEBP~dXmX^UsHU704Gu}Gr=;aBs z43>Yh*OnZ%L}KNWuS>TW=-kF7Je$xUreDypklSJYA^kMx->fV4~C`$aMK13 zlykboP(72XW_ABX^y?ks9&$fAKpLA3v_ryi)82q#?lu;)vpdB#);2jTUqParf*sXZ z06&V{O_PJlistE;c|lpv!tn{E5ti{SN=u(@E0-|v9baDE@%)lEH`hvC-J5k31tmMA zM6Lif7hO33gnx>~-o^vhG`obO?dxY7AEjYZTs5+8UGMAtM!0?*TRP6vaQo48zh}zc zJ9TCMT5Z{Kw?G;RC69JYd_ z*d06H;IP$mMRV!M8wv$aj3oArQ6>!m@)z%P_Qo)}9o z!m>HBXT=CXSp-|5Qe*>m1b+)HZ&%`=Y<$5KTxRx78Ea~)!GxK9IH1sCph*V;3o2`M zJd!OyYC$WQ^~AuKpclVWTG|?T+_|Qv{AXh)$8J5gjB59cIOSQOQC|N(vzK|U(sVz^RI~T-j2hJuS zRS8G?oIN)h8Z5hSCgR}7o9(Qjp*%%e>1geST`9&>xu>Bx=ev*X!_(?-WYiE-YyzW@ z{fGg!XM#Zw$)%C^?}Ke0DB z+WG{)fn(z8=ck@`8L9589ISeI<3KI_&EAWzb?78N`^;QR?U-mm6@WnFm}P_P-q@h>5^e_v{B+W zxm17t)}(}6YHQggUwiJey0vyz<7SUj@VL8oIaYL*?4=MM5z$|m(L;mRWr3qMSsGT) zJu0+S(PEc`e0)m#gwmOVzLpl;u0M+MaVj3Z?>(*yN}qA#i#ZsSYD>!hsn6Ln zh!#-vC@7c!{Npf<->=L!~POly1Rviv)B7ez+2n{;1WZG-QsV? zk#h4#fNhGr{?2EQo4$wVgCXE=_V4IdQUUdUw*BDBcG+iL^nSD2x;rmr-%eJkr_gTr zy8rNDVa61xF$PP}@mt`(!kcux;y~V+HfvUGeP$EnNhoT?8FHra|A+}>Qd3)#Z)XW- zh9Jk;$;5>3++#yhpkOW!y6R;c;?^gp?CsWqOcp}fl&X% zs^OeU#)6Z8DPRL>8*48-qFqZzU$9WAk+w{y5{g(bs-t+`|Fn_O-Q(PT0m&9QC;{y-6tm zJY~z&fH<+2O}lgB8v+UV0S*OrdA@N4_CN?TPv4>De! z@W~K%bzqdmn|?>F{y1{Mi`YN802C>A*j)R3}>JbtAUeEHXp%Q zNQgq}w;GFp!3ST2AI&st>t_>&w~qEKxZkNqWmZ$NwDsmuT8q=VjBuO#YU+9)ne-Iu z{-a_!9`clyR*h|cJ?xtE;+%f6uI4o{DK*pkLYkF~YP97e9r%>06KKQ05I z5uNM%>gvDd5y=f>mRv_Z*|Fu<;)o|r_BM7M71f@;(p#>S>aA5>Q;~3ek#h320lx3y zr6t%77PvuD_acq%^tSWdkC~{QoG5KK#9)|1=B>w>1b2&jWkq{%SQ;$uu6Ny1T0_5< z?^6Jp&o8;&g|x*(o5+Hfo4uTfNut#j4v_v`!!3o?AvH}fVA{kX`#xYQm@DjPzRh7- z@jm}4b}T3VT9(ys%rcT>F4cxBYsvO6;SS40tA2)rUquPmAd;Dva(j-xOGC61F0qR`tiPlJ#BTKbib9?$Bdh?gp^q z5AeX)1rDuakVWVcw}^N@c${6&%q<>Jx@kem^yK-mgmVuBe;#c3`N6W1SoTrHQd@Z7 zql(Vr&+Dza-XE_xq+e{-u=l=s^ZNB@?&$pp74N}S6DK(F~UjbT`W5m00<3^4mzzAQ+?Jg9e(EhhOvE=!F**UC^XYq(Uj^yEzsBwb=GsMK8AsN!>$AFKb$mMqixs&kw&nmRXMqgq@>7GzJ)u z2o!^Ao$)T;I~%YKDS?5ZtE&~D+izA0ZvfN{v(3bDB0y5QK81k?1Vc7#1Tco9>1Vx2 z5ciipG65bgO(&CRAQrJUks~({<6@9=@?$8Jt{r)KWs(vo@4&ytV3kp#8aZX! z_Q~3v#qNT&@cZtGf=gaK?xBbns^B^>)zXFzU{7sA+xqmq?}}5Zf29anZ2^B9h9Qm$);MvsUSX;GI}8{YbY1-!A%%^K@2V3W?c1~`wCW2169hnz z5d|f3;Z>K}aTgZ6^82>*O06lgqD=$e^wzz0RpEv#f=5syi=+*5!v!MVzg5`_Iw`Y@nfc0DLxU!vS2q662Uh35}$ zhq+;*@m=3(olcxnS!tlAhLxKTuR!b|mXd>L$E&@T+;cL7aLJnQP!woH4QLfe6q=^` zP?F!KQDBqC4hXg4w>4GE_bspwoT^hja_x`V@7FInrEKWh*m89ZlHtQ~7SH=WW}I4RdAU=c30o9_6mein(tQ$j*&jUJ^<&?)Vl9*5+F~Q7YjDja zc*HZ`IG1Lcr_H!=!RlH@^RvcH*D8G1{4+e+$G-IA+)ASt^M@awE;s7t=BOl}$M>x> zn{>P{Ypy_ijz|NWIi9NpvFFFv%TNMhhc9b+j0Ga$ju z5VIra5yAo(Tt2hCi{Sww>~;ibBw9Q;Ew?18P!l^R_z4(A^8yW!3^(4I)-+v;6G0B7 zK@jT<_;=-Hqz<o;cI|NG=< z_2TiX2i~xM(!9vaC%S{T#%RDj;X}s_K4x<0-rc(a1r^KT%9na8FV$*%Q2WCA)b~8| z>6*n=cQ;SC#_hKX^Ef2*wWQor+4 zrnO(Wq-S$~Q^S&B6iM0FH=0jVsINNZJ7MdS`Xeq!whi9bkrdBJTFkNpkzcS87%M9e z+#Ho-g6&C(_ro`$5RO%UySA%m?~n_!S5595zxj`ktz3@B!~45q&&^3%+%z`%)f_v! zvttU^72Ln^>iHps|F*Ec(J?aWCfFSq3<_Txu2Qwhz?^_@zY-bYK`;R5PJ3d-(MYuAG$Q?J!*_>MqLcs%H7ARhFkLMH-y6& z=5UhIve|fHLF&K)9F=bM&rc7Z&LX01MI8b6Xkuz70k)Tv2+joKD8WCb*Ak>ExXl_& z&=?Ih6|V%Iqm`)t9OpnMC3fl|0cIQ$U^D3W096xXty;I624CfVZ*y#{zIl6NO2*5k zGKGyldki*bqapBV9Q~QRPc1oTfK@wk1 zeI)h(FmK19S`jcvcyA5g_~hejGn$S6%=Rlp^Va$G{5x-|$7O7)vJLAnnvg3nlIkn# z0y|C;`%Aw0d7|TRJ7cD&HzR5*YPpEN?Nt87i6fnW!S<$&)6+YjlYRZk{U=k}FTC?z zq;$o+(n2?O_GE+cVyr?_RMOf;m3HDuGoGM@eRXFB_@snkSUUmu@AlA?Tf)0~QC-N0 zk>_5OEbts~K4taLj~_k=icEdIJacmbuI&LW08Wa6;kaW2=6<}*yb6utZMxUyrL!zS z{l!3#6N?Mx6euvAsL|%r#`tdyxbpaXvJ)Ms^M1r*9 zww$A{rSxs(OIxzI=&nicUlnyKI5OeY=`a}fAJ|)c(ph}CzAF`9)28DI-8|aAATLks zVr=vRh4LacrOS3ojijbKm|>d3>i}s@d*{nS*Fd6a*=| z==%3R+n{0w;Ir{?sLc55_nVD3CB4O1Ny$PU`_Ww#0HgQd@)gL+O`(3E8x2-nl67=9 zqfqoFIqZ~vCexJKB_{MlEDH1g7zO3GC%sOqs~9b9{M6Q|h^qktDa!9q#a`PH?^I9g zG5#`$Q7@V`Ve+pta9|F9h$fE9fD!sn7TG6Pw4Ru-Ts^7_3;9He24xsBg;>-~If2$m zQQb)1SflPzY)xh6t7Ka`S}U8bPcg%;5{cTL&MHOU@rd+66g0%vHw)7)XvZ)MTGH# zgdrz{Tc*;?@_<QQ}? zr;jC>gZIX?K(f{X(Dq)jHVtXC5V44@3wvTmHri%xyzZNIH(}kPT$+Rt9-pQu^mA|LkAR3wyQCmUNZsy7cfR+l>;$4KE=2_V*$4kGE-WyIUU zK748zJd!W(Qyg{ zZ#urVxTq<6;oz5$7cXNQ{R5|B)k_O!FsBb+sHe-CCzY#9(k|KN!KJKf*cMt>h_hRR z^(XcSSNf*do+C)(_zW zF9Q1^piR4E_^ma=Q!VqO@1UjC{U< z39ISqo}W6%24FfT!QO4V5n1l$hKzx z{T({|t-EP6wd9wdaW=1vX=V%^rhspMU~~`-g)?5rrSBWNt9;5Z3Tf`9oK|S7 zesb!Xf%BHfhj8A()OUfA^9(3%Kt{zfWX=R6Z!266d2k(&pHcXVT*!P|5PI#y9hVmz zOPl2R#R0oe-mRegFtPvgFJfDyc8^I5Y69}Nl{=CDqwfI?pM+p zm71REdJj>1RW= z47}Id(C6@irD_&#zCyw4iE5qS*)-*C(CPDQn%kbIn^DzLuLvY*zyL{?m<9$Ks#yFM z)p+_0as1^MRajJ3R^a9R_sF-1Ej5h&(<^rC+HcA#_Iz4roNcu~oUQg@nOxa8IHa6Xn18NFfcMnB8-PIXqLshr;b$7mY-YUQ>-^h$Lp5QVAS}_JZLQjqHDAhQti+Z?Yp3`e&Z!^>3Q7hQ zX!2;cEAe=GVg?TB&VZU6F0?3XAp?6JYRUH9CsXp~%`zn5^73jjXRa!bIB>r7!FmMC zoJ%#MK@to();`dYHiyjwLt1&xoH-PjiGXx{l;!B0`p!2w240xk0hmj0uxYp(=8t7+ zxB(Oymz~B4g%RRwNVR0=r@Sx2ida-7j7`c>MF55f!Ybhx0%aseA@_7kpl-IOAsL=W zk;8g+UImQL^;e>(udva8zyc1h)gwZ*f!Lb;x4vZAj?B?ddku?KkdY!Y!1vuKL=RW4 zT$!yPf9UbaWA_Hm_}6joQ#QfiYtWxDJE0HcauNUzAhTjXLJ5Mn z!2!>rt*DFd@*9kiV{85t8(cTjzCWM`boih_4Zmp z78h*>*Z0~1&F2)8R{tcFIR}bJ;QQA|)XNYpiA=wr$K@IP@BF>uV5K*xc3ss~O_|FJ%`Watsn)|XK;$!QhOD$$Ru4cc#J{JKqAg0meg zurWfoP>0DyT1iJ*1;N!2nT>|Rd$&Syrx_n-Z(rx{E2rywX+!mB8~y+c7Fal)1d);n zD(*UxY!gL>`H^OLGVcYs$f9*tc5-j6+lIP>eemQ63Ad3K6VE5Z3K8_nxkDPaE7a7~ zh{anBTo~xzq4%Xq6g%K4sqxx=vuZPN*vo~iFo(gc2(yQ}69)Oz;1H!8vib&M>*%JV zpfz-plHuVBzX_2MFcJ0~)Fht?(|55J0B*@lzkU*mBX0qQtZJ@!sjwcwBRV~)Ky&jB z_n`2It4Ir+^h{sq7_9zDEZ7=Q(tjE%n%~TfM8nMYKAv{EB!FQ2*hbqB%g%~<)=@d zJ|s!zu~$FE;-3=FV|UfQf5v1`JH$!Z!eYtnd5v<_)pjH9cIzqa;IDs=%^W*+ZF&)5 zD865=YJ_X=hM@%(Ls1!N1xFJmVzefOMzb~`1}6Yv2{!^bo_QHPsPWK+&kTN1D^p`36C@&_-;Y`RncMNgHM$&Rnw=OhVXIs|Se4z$~Fd!E5DqPe$J(n+$%{+&?>;rgJ1H&f z=DmA`C!(9V>fM2$`AI^A!gn{oY(UWUA?%5~E!Kc=@|=Jw2vxyH<1S68So1gg|8oKC zkF*U7G-z0}yVporW-Wr%1$Ir;f_p88W%#@a?0^Ilsl)Wi z1>!zoNr`gk*6$Ay<-cMsFTU}Mzb{mp^mt^p3l3SkaSy}cBmr~UA%TyaM?g%C;6_jn zA(a^}7^e)&pcGG(Pi)v@BgoKNJpPb;Q6V4`eWm{)4kx~!yITX!s?Tw zhu0-bG}!v6!g2%wfZHX9a^g{FYR2Y^U)?$~qBBEL5l}S?P`=_2PyqB4{ zPsX#a#_vC?^s!G|WzyyC>q_O}DFc4znzc#t>5B7=T;AsROk4bZnD=JY!-jEfoT3dp z1hE5Bj5AQGQM=OaUflM_Luj}JbV;9uo#BxyGZzvt-RDJ%p(Kl} z2AlUbGbk6wq6{O&oIpq_{wFM+ryi-jLW1Q73k@MGSh1yZ@SLNTJRnpwa-tu3T|<8= z6qLxC2_ z+OwrA^I*pF_t&R;neiGDFNliC1 zwLgquD2lT-%1W`wo+eVv1!P>PvP2==-UCYn05XKW|5c%c=fo$3k+G;cc_-eQu>TWzfJ&Y_}`ej4Lf#28mlrc{g zhf~Oo*7X&m0Wv|xklDWXGASbj%LnHS z>?s7L9&kd4H<5JFa9J_4f05jML0c##JMe7!l41NY%^nd#w}>g5Bh?L|vUbiE@42nJ zmQ`Pvo#cI?E}_s+%nY!EhvzBC)U=)m&(b&7^uSn+fj}oZ5ARf=XZMYl=-odHNh7ly zp$)=ufe(D!=@JgEfm9#;*?l;C?CDc^>uYRFPtVRCQ&!ovyiFN>mRSD!9~prfZ^%Xc zapQV%@Iye3xU+-9cLE3qqApGute|5cF5Dn_afo?@?;0kLSoSzwwRKn@l<0gHio?g; ze`vOv#W6-!Ct>d9CLB(ety&d^Jk$DTp3@~wRe3SjB`7B{F9JtI6+|Iw6&L3Ewzpzg zMc&k6U6oEi2WsOt4MN*Ytpf_9LgCgqSd~Zmo^G0W6NbiV=625ahJPyeb&;p?g7qU@ z^kEQm=Ic+C4+OLq9vk|LuQ@{aQweU_Vx+07`%XXVZM+y2vs{Lb({}nkbQXjY`o=JF z2|yi;6rt1r>0|sajsyVl+yf4<29{)Q>&2K5dw^;23fl_T1_`0Uh7V(rD-Zh7NrF_$ z?SSqa%7^33i1P81{5eGl3y96#Pr5PE#|V!|^1Wc}KS`N(6;O(KvpKo`tr856KBl=baAEiq~l zENZF(=qB82fWQv$*x}(*l{VZ;@KxXs6Z@=8(qKYTh!LGaAiF@r0#~UgozM0P*c^Tb z&zuc^eyl*hlkxHC-GpX?7wuM-S1a3Gjeq-DrVZ~!W)NLboP%F4&MW~Cb~XyX95K9J zv}jt|X1e2srBdfh&M>gkTavCS+?2?Zlm&<@>tTBdv>kX=#j>tM!)|k6a=J%I?T*D_ zve0UuHmJRO^5I2 z2fH@nXj1-i%Yt8ZGJ(-Z%rMQ`>Glj+7BoP-;BUy7Em39q2OBH-*o_8 zT_@^bU|RvfP-&_s=jHylvo9QYL~M_svp?@e;MOgMhk;vHy-)uYqVmEGz+~ zM9I;e&SuhNPd9zh*xvs*!*4T=q|i5%g!8mu#4<6_#?FbM?H&dLdl*W@(oY5QEn>sQ zHLo}688=e!%+LE4%bDn|}9`qi(vV-O@YWX0GTuUa|T^o@0u_8Hq3>g|7~GC5`*e-bQ#C#cov$EXrs%2@Iq{pjk= ztdl86D`4B?G;;d4`~3}UijRK#cH8;2Q_u~%WlUwX#D_>oeEOlJQZe(5@C4;N2L@K&>& zzIKO}aLG>q&VLSVet^P;ZKm;Jmu{Dcdv_~-=EG@!cG^-?HJVC-;4~W`n-f|HP;dr~ z^(O8_N46?(%tFp@ss~T+8kQ4NxSYs$(A0N4RI(!L+@bj)o^(Ys`-kpX{(0{opA__2 zl}Pr>$Iy&OHjNztDy^`HUflFtZ8Y{R>~V zo9_1$qnC|OUYw>2P4*yYD^DRKwbu1Sard4*hpu_s5GJ!aps-=h@v~n`-@bJr3OGAC zSw!_SJ4rzcT%y19xh;|BflA^qKK891`c^Tup?~qL;aW0In5?+j;fs z=@|E%V4={M>br^(MIWUX^>I&joLD>ng+= z;>%aBuDSYn*~UqeL)LVV@6ldz_34GB6S{N^*#x_|qoU$*)ZVc))+<)6iUlmd38)Zx zs?M~`6^@RM(P6r2L!=Vw>)pjmViygh-Ck?43M3v^!e2PX_;wG+C)qyZ;MhJ-7H4!& z3S3ue-}6C=<&w8G7Ju~*mp?FnS4MNNgXk2Vem{*0f$cogd08vR7i4E^=5&7duh|PVonzkGPpOMVDM4rz zEK+DD*#fj&w{ABf=@>A|dfymXzb!p`R^2@Smhs`yp>F@^^$==CcCCdG07TV9$;G(I z0*pZSOawuKN|nO#4*FNaHLnepAU8#NG}Ef5y2TbyMt(*B&-nMYw#BjU6%`fTL9PK( z4Sdgs?CPl(eeI*`^MCt}`Rv7rOCrOkY5(O8L>IA@WWZfR1A`Z1J&pd}(yR*v&=t&M z>Z1H$UFyE->Ye!U=Q-z%=`M9^^SOpQZ*F=%v>*Fjmc#%t(Glkvbh*-$9OjxLd)<$U zm!L&gGU@%j?X+??{FwbaJCYoewNn;0aU2(dcdr|H7n#;E<~+a(ZD*eT@N)Pu%7BkOa@D`L4qn!0oGCc-;PYLMFnDC-v+GU)W}1qPAGP`R zj6z(B{#BXRIx^8_s_^;b$xj_Mwen?h?{5svDQH(*F7Ms{Q{vyIuARNMPWAU|-ttf> zXzO#Q{yicfw;vQc^7rVZ0(pG)W=nn z=~t-?2$}n}jfBn^m*!C}5g%{d$u_^Hem6f>fAxob6|R`LALs9O3AdbUV`EN|xXN0> z@h~X6qXMDip2;RxmXb|mvdC8R2}AVsbildza%=+_TK(oqPZO^n!3eQVvn-EnPr)2R zISHl|A%xFF<&KNglTSt-y>MYzB)c&b-*rj&TU|61P6{X6IAni8^XrTAidPS?irlmN z+bWlXMwPyAxjE2RliW+;!UARh)@W@|4-1t zG5C6?F1H5uD=)e~9^8F9WlcOeD#XlS+^ANsDKr^Ou|y380KzY^%Z~~r#O-hn8P#kS z3psaCJ>0>EkL)N+(ws0xG0LOzy-O3dY~4ELVR4;!Y3!Wo$-oi3Jml8h{es;`(vH0=|FHiS z3JKm-4ib=hf9&(=z32VjT7I@Jm7KJRmfz~n+>9HZb-Q7A8=aAPc2ej0;9{4tHc1)y zE{i3J*q2TL6CFFp(~cOx51D;v^jhcI3CssTh>roa$558*Xrzy~OLdzJJLS`tFIMBm zUH?>5GaWEf|I6#2v=05(udlPa*JQ;;XfW=<^w8@LT;FfJY<}u<>x=baU*t5Rrog#7 z1+){xH6Ng(^OP21uz`WikW-ekE0)X3j*fe{%?io{LT+7pSw zPZUWOWbFkxPJGnItp5QmvJ!chnm)hV$o18am5ohK_?vDxwqj6k3EJ{lRXq$(iz%OH z!Y-g8%3}@Ni2J;P1c=IX;3VAQ8y(8l{Yn#RoZ){pyd{v7CP+gcb@QAV3 z9^j_IIy%896$Y`Rec8vQ=LSl6ZQU9TApQ2>>v=G-tfxe2oZ#Hq+S#c`$ekQh;<|al zN|(R?udXkR$NJya7NvwpiV{VrNYS7YDpQ1#+$n@Y141NIlFC@hkQ60^Oi_x;n9NhD z%!CXjl87=p*V=nOFQ5OLb3VJ`zJJ5|u60f8ug+Q8X}A?vQ}@V`c-lg@U_lh->HFX0 zP(=O9_rd0jmgF$rJBw4NK2e%GO5z0&>TDiFU5@#r_ye!Po1&ph0hk`4N&3yLx1Jj8 z=T{j$j|#dME+JY(fj!a7{bpyqUZkhf5d>bL5L>d5EV=pX21aS7AsBu2uHXJF`aZ<`uL*fLYfq8B97;V!RZub}{NkPf3k_J{mRJ zJXD$S;;!8J^xyM~U-)6jr;`Rhj}ojw%P!{QEA8}L&d=NUYYwIFVY|*4`n~4}StKqA zFJ;(uZMY{M+qUPub{-O0F(3@r0LnPFPH)n%`&3(7gtrgkl<=O;lwNI_?f^67hXUfH z{K6P$@qUkv7DIvp5O?viWfZtg;cVc4?5%b*T$n}JA803y^eebO*!sB$f?k4G!H+CJ zJ8^%9J|Z{CV1>6>cPQ20W(-`(b)fFAjeZ$wJOiu&jBDc-At}epQji1f7qJH&(PBO*a3lG0q*%JdP+C3=G(4lZ4MD|VFfsJ7| zFcHR3RR&Xy73@lz?CX|Xfhum^nl+DK@t6wT_5q6ydFQXE5y5w*J&&Z#aPyay1;qq* zz}<~X$^i`!xOlJ}TdiHD{TPefe3yy7D+6h(ql05Nl#O%4lf zhKm3T90Dz!TJqf8P;=MF%jYz$Iy7gG8f#5f#>wk@%MNFv=HS#NwKTZ&F|ZR5MtLFx zit;DP)#KyiqxJ83^G&PKd_a`T(MNuKa&Q&)8m+`^cs(-GI6$xlX|mF`ZI^OfN0U^! zvn!n7|05vz#*IotHoKlt6h{$MDOH}13a6(+Gf|0bdc$inYq!o84*{~LvkE91R1O3^ zT=(|g%v1Fi8|ID6C80F+f)*CS#U;RWg09O$BOHTy9<#K~>x|S1J{Z+=E{*fxXaH&* z_{`qj-JL8l_ExWDPrut?7d7%O>ypbKw<0hGcYgQsU6phgY(XY#sFFc#v4{fbH2Ug3kk+;Su@QtUHgY?HUm z`SmG|ozx)FI*pwt*GRTI44a?bH9B-6Ry}B$I%J`cb0Vlf5bzBESMVfZXG5!EOWxK@ z`P!n^80R>90!{5e>I)WEB7uR$r*KYKr79Mq(3bWod>qcgO+D^@I_tP?3te>_4(K9zAWC1Ttd)s!E)UcS)5@Nrl+(qgr7zEk9`Ti z;ICi^iF(0nMT@zy>~CM^f)@zt0~fO*b?*`FZYMm|)DQ=nK)5?H*uDx4+-4Px#o~_} z&c9E)eK>hzs@p%=X{S5ey+hk3!F5v5%8Sz;o|v`Kkgrxy5JW~5N&hi60)HAaE_pGb zK&&-3d_=BHr_)YO0h5_qoauVp+!JnXQn5s*sI>wRQcLs zHb=?8!W)UiUpjS*<58Dz8oSMprZne8o&_;h^DGY1pz1w!wlba9dFO*Qvkzz1wA@E zKWMVv!hM1;Bu@__#7yzjEK7Tk9kThjzqm@-9IM2UFiZ z7$s0%V}m=W!9={O{H3vHLrOw0V-UIzO&uA-kS`GIGlF+J!X?$$(f+WmdC1rBzQxHo zoLUzz%Ho$AY6l(Q%KcF*-}vFEN;boep^XjU|#l{}&pj zqJm?{DD5=fA}pHFF`GW2Dq4V^hF`&TD_YLiMmA4#3MiKAeCKsN?-UWYs$`#aXD!p4 z^Zm1~sHv)cO-{>G!eAygF@uFhTzHEXy2};4jap|F4r&;$BAN>#c`zwbQnvKgt=G{^ z0f&M>7tQR%_P;B}qPPsk17TQXcOB{V#5Ezs5}G)~$pD`&#Or9N@*^%h*xH-R)?m;m z8*!44VO3ngFFj? zJ}l_qRFKn%CSFvS3$a7Q{h>$*Y--aN} zmUrPj9fLBJyzpof>iy?>faLV`^E;&eq0!^Idb5z>tIO^Ng$n{tzAwNW)`-1<$R`zZ zwSm(WPKD)Ysut#cH8VZ)zFU98GQ78JQ1Kwf{wgBHC?Q0n>{?!)B6g`;BxP-NPB+BT zH{jbfIFczb1~MSD?iBS;Zw9zJu#L+YHi^T604R*@zP~>=^)Kv|C%Vf5gx(XTj=D}l zN;Ne#>CKzp;a-xt3CMm!V``Rgq{CoaE*g+b-soh}BGi#E5f_|0_S_g8l_qtsMX zOflpI{|bU2Vhm1m(guQiiSSYaFcy7^fjh?X?kFF+vXQQxrLivuv4P~o z!M{b5gBULs(o{m03&gEFX~2+{L2oa4Z=h8>JxPD$}G2JV-hJ@-*HCls5{&g`;Z4 z<$%-!mvOAzfbI9pF z+7^9y@=1kH2O&;k`k)Ibq7p3_6yk*>RK%RF_Oy9OmU#pB0s>#?%{DX?KnwuV+`B~M zK1SGW ztGk^U>rW?4yE7AI}NL8}}gTNO&IWPw)V_9ZA+KnJQq18~zgUm#& z*XUE+U$ zYZ+a0y$nyttb+l%5IBHgdL5v2Ov&ry2%2_&X?c~%*3I6-CLKru(R+dW7Z-#&_|IF^SUr_{}W0JtYoS14FX zIlc-BVM$2Z@Al}H(DZNn#IrvsAOl-4VZ)=$I|_G2DTA@z53HUz-$I@7T&x_0?07rs zU|et;@BH=YtMO{I+b?t^u1SU7A_GmcaW_GNnVlTzoZX==r7;kRdY~SrP_NddJ$Tk0;+~mW z&7wb>^6Xh4X5C(#^f5>d0i_osd#*VU2r>~NP$<#;w|DB2a_qo@uXyb>%~_-Q9}syp z{M&iAaYwTR+JIPmI|Ix`xtGR+IXF4jZ`&3M)7lv%Ds08sb^iBD~>&O~~ z%{FV-`q1qGK=l~ImmDIco3Jy;({s+!Wy^E{wpJ&J!1*hZXa-4#ryr*AZWoCi58}bs>_XxmPf&LU0iTJ0li6eFne< z-_>BDLr@>r`n30hh~D`Pwo$!v-mVM1SJ;+_Z#4+kb7&eZDyfhyabET1iDgKR7>^$X z)Z+~!xhG8u_{<;UH2F|_SuvezXDK?2eg_d#1j7|M^HDtC!7hw50aYJJN)d*)nl}!o z6Js|m@?pUxkD=uLH1MZh*WxovO8~- zE6;(+zq3+Bj-mS6p54QDq(CyG$+`}(8F&A8F`olG-H%SfHw6$<^~IS3y3^wX{^HgE zHqw=Nk)6)+0EGnaIG+Bucmc2p3E;uW-yH=t4Gn3G` zSR6h2vmvbO0%~Zl93EadSyGyxn)9hqBY{KPY7t1oLO?B|13@5%Pr$wf@CKJFUN!Wm zx#=0-ZP~%Mk%`p_#;*h-SWoaP`-7VyQGidC7!;J_Z3kSoxNto}`Zh2^4VMyZ`SOJ5 zUZ&Gb{lQ~DkLCu0#xm7d6gDx7!Hfx#J|DYxT;&NTi*V& z)&Yk$hFGFF15y24sC~c{F=JfhU%vbV6|IXG?^;$LZ>el<&T4YfNKRUd(xfXBXq!d* zJC-c@{Byxx?JxWR0kc+aRo{~C=B_I(Ej5GShQ|{$nubZF0Er3a1 zHj`rcaSJ-Ymz^)d(?Gur2iRuEUV)sVV~*gX4sF)p=jVTmX&)@-&8d3jyxlYF4EbJL zj;OoekwCN~SrLN8Gz0J4nTvu2vH+&fB`{0!3@2kMBvCTxwd#5+lko=_vj|GU1+>)q zwgQ$6wSX1#U}<<0*_mYoAw1kUVG{ifMr$AA9J{%4XZjIGPrTX)KKDVRcS`wcd#&Hl z?-R26&t1lL!!t=BBzh+tR=N@&@eo5isHKmu7PRk(x9KT!bF_Ir!Q9OiH_$4fr6#JO z#Uk^gP)>SiH$E5=rWOKVd7$8ScX7K@pzV1XU@E!m4o3XFxU)X?=q8iABDB$)evD)Q z%ZG981e|5T)*g5TvD1Sl6VN8ru2V^_SCAjUj+gCChV{0sTd7~6EErc;*HQ62#+Ksk z=bA;u^1sQ;%)|VFu4P+hV5;l=d-pmhy-AjnMdDF)v1;@CEJw3HORuF!;qxq`lY2u6 zMhcR5^>dfL{Vn8de&on9azSD~C66Ff=fRE!kme)b7qN^UUBf&s-4YN1KzVTu)e214 zH4wWM=d267b8R;N{S#t*4~@UWJ_#3pN`=06kNcb5Wk4HI ziWwg+FI^oi3ETlnqs?LgI0*>K#i*_se^$*s4Q+525W&rHN5hkUq9Rl9KC%PQWV<38 z5q1KX!MHPuwYym7mbrSQnVfc5cI{;(tcyiOMIFFveXs_L;xZBCg4ZfN8y^!OQ+s+s0W%1921m!LS4z)r#LqVOrt#7tq`HPrLf&aJigqe-lJ=ojy zVl5VR%@$zg9)Lp++sO8$FwoTKKw5t8zgGVFF>n=9EFI6fkjUUCGyspm5YW5rP0k$^ zr<*b~|6Ui9y}Ov7bzF8a0*NS68004f_oC~hh$6z-w3PYrO;_h3oEWDom@6-I2Iz@k zTm%*+!lq680T4e?EdKe-4PQJXivjmN$8tVu+ClCAPs>fqLns^=j0{PBaWprY{}$pc zt=4vp&U`+ewktFz&tII%Yh2p#m?9S9Sq5GzahNd4}i;D47fxLt#W6juZA&_lMimW|+@ zC?gICnYJ8nLj3i5*clMXm{)I6(|sIcJ_v=Nsv*0>&R{7mB8+2WpN;!}9gs!%<_)Yy zpl!P9>grfMxDshzz|kmJEAy9(bl}vIVw}`K+d44K5m4~$!=p{YZ&4b0n=>SVRC+#0 z3g8M4mKyE-$bxfl2Sh7qE$pDrpn8W(_Zsf%8>{sKqE!?XKe1=Vi|aJ`Cg5!Z5a^SZ zme%U}3X_5|XnHg{>$mUJ_*j}4@AP!U1}hAq_x+RW=II7d3ds4^rVwryHa1Y);3o=k zIrL$^*nnegx-WQiv*RndMXA$jL3(9F;g22{B; zTG_|^K<&M`%MH?V^&%s227EHDY*`Q@35~3!}WH(B7 z`ijsDqq0of_C+QpCa}%bM~toD=QoAV8YTm>{sD3pwP@6~I0<8mG7evGzI1S6i@h)_Kx>CXS zZ^^tAg-{t%WMVHVSB#WDcrA1}6CkNs`|o9}MhhF_qjATnh@suZMV4l<-D7*)*?Ikr zl|i*4GavVTCuAPE46InPQ3OmTT=^o1<}+Mu(ZRU%y_xV+TLIT~Mo|t_mFg zyKSH>4N7|;x?k}&lY$-;Si2ifRE~2890`PNaE7lpar|>MH$Ky|z~lT#l`MasnLcJB zdTB|V45&+3N{VwgR&9}97sXU|cJs>w$Cvg2WGNUpzjTi* zV2XS4mU{7c8Nl=qj@Y_bBzduAD-i(AN5&*&`nwXTN8z;y7)~CMOHcxmV zThNSk!$uKp?Nb6AqmOotjEtPY24!9(1S7LO2IIpgjQIpmP@Fi_aYbM4XvpS_@23a! zJyR5*5;+_S_?`hIWrGF@MG~8%RYxF=48c+8;^y`lF+n79tG@jx#UNw|-0C!MoffSrS*2>sDBv(iPBg)b&H4_cJM+3EIK;Ao!J#T*NhCmEH`Fr^*g5e8T< z$>^ae4Pjef5>z~2@Y2^qv1ST}I)(fI`` z2N(ur1YpB7m+sJ8ElUo6mCI0oaAUC+q-I@UvwGWdv+pb^Dl1!n!Pw=`jepa#feStF z?KmG(wd&cLhfaqR`X1rU`UnK!2OvAdaKK-30z1=`aJy7gwnEPbFKo=3eHRZqk2M6( zX1hn6X_1X7zH#5EpB*j+(pKfq&P3p~>>tU;Cqp3?{`B#qFdz^}Q*OtWyonw_Vvi57 z7>KPj!fH*b^A6YYR7H}FbH}@V49>AwY_TKi%ANO9j z@xa83=}A9{$JZNMi+?MUiWBwhF${fj&{&QB`0RraL_{X<*E?Q(lz;9u5xb=bjKM65 zW?#|(+rQDZ9Rdaq!2ZX!^VVO&(Yo|PmGc72=Mfe z%`rzVn;2v4eJ!)?^J-g0l)zTbZa>BW8{Pqv+U(zSm;Y}C-CO~ zZBt+l{rARRHM6_v>O2%L#a4MCY>uEs3-H5H#RD+u4f^VZKQ{+v9iXSwzLL`ece(&u zZbUO|kpFc83$KtZYVi1x?`7^2(izVA3q#=qrYsaNKzqPI;aH`8g4C?{EjVUkvI_iK z$OVClGUqQ#Q~N}0Z9gapw^KFJDv!b{S!@1Z?fLCz1WvMg|0~z0Z_LBP40#LfFvyc)7{{1?R!}7Y9*9j2W9xkJdZm7*(D!jCrmRo+SiKWozc^HJKUv!f?QCz6ZeRErcpcPh-&?mzFv?J>5e{mKAL9~|e+#?e36MKz5&&0) zTTN7~-^0n|dvmTHBaY8QXmIqqb!(sEDPR+*{~{P&`?arXYiUua-2$(7P9g=43cA4! zGtN-(XC$#ybq#fV{pyK&{U#z6(jypWJLw|u{Rtm=kuE+2n(zeB>`?RVNU}gucde#k zsE5aNmUXU)nOT&??$ayY|Bn972~gEzcA5`)U|5S4CO1Isq)mHXwURJ@xV#C3VTfZY zMp%_J)UMX;d4iaI?npQ`0a#wCcjR_DP9|?eG?}Zaj#f5I-1>?UgcdG4`OnXUQVUI?MW<&wdh|DqLdqi^xbJ@+*Nv#Izi~VQ8tJ3ekw50%$ujT1QkU^#^;A=}BK72`x!S z8A9DrOAiM%uRo-nzvM>o2$Th={CtpA`auX0z%O$Z&jgW9=+u2nyFQ})_D0y|1z9dJ zWQ(&*_>s-Z0pYs-j}M)lm|sCCw9TYQ3D#M(JU81%b`HEt`}^wZm!i}?M*aN^1~9H! zGXLDl?rGx<%QQ2jQYW?#i?6~di9?$tr3TQ+6qlAZ^xek}O7eSvd_0H@uhHP++K=@0 z^mJ5Jy;PP#^TR77bO3Xyqh-0#c&d^xI$sq=rR*yk?F%F8f)E1rD8Tb8OZA%Cr-s|f zn*i;sy5fiO@@RaKU^snyzJK4cS7z(ZHeGD1K(BNsC}=Mvh}d$ccJlc>e}ADH7ps_< zR&3Bv*{kQD0CEGc)frULm*~n?Y`1x!m+L0mkS@qubn>~m)23xNg6`b8PGanR`{v_? zFUI%84C0NMYzju4q<-ty zCzcGkx3DSUOayHTtxC_;aNx_tLREuwZV3^dc07&o)F`O54^VnF(kvJhtw<={ew1J~0$D=RBn zwL~IvXmCtVpPmn)Ji70NO3}Y_*B@q_?C2EHkqBqxWP6^+g0n|SIr zDLX8H`T=0O5G(b7fM4oTz%vJ$i*i)aI3>Ri-GGZvDi(B7I3>H#`|3W=8lAQJMmZpRpMT`vPylf z^5eeK7WNK+U`VY4nh*Xt#^&uvpTwII1tSK0h&$Hgaco=r8U)*Xz{HreS)u!7K@C7! zxd@bzxD;d9=t7(l-kv4EKHX2J4Ms#tt?6={vK_79)=!l#e)@sGw4@~O@HGx}fMA@y zg8SN5U-|UGO&Av`!xLjI)Qz;+FL;MJdTFEl%g1e)!y(SWHOAb_!Ong|PHd1-;({56 zP9h>cL>G;@%O)oLbbSp2!}1R!fQu$dM5B`)jgOZHw+ks8eZlS>zul=7;r7rr>;7HG zz2F(dQ1=_1#1*`~FE+#HitNJWy|sx;ut;?QNUZX3IF7Dh`~`Oy5@ZrDKa3UE&#|h{ zPoEq%K*&j<$nA?tse~2{P{&lq=!xVb-oRuut|mz&a~x`ynZ+SF1R}4DTT|$^zE%1U z)Nf2IZ@NtIMR6JzfL`F+XoRh<{XO2s=#qrx<&FA;aAn}ar=`GFKO6sw4_kq~gK*zi zmu1YIZ%f+cN2HXjt7AwUZbOp+@rKf&LqS@Ns&%uuj+(MfpWj|#Trxcq{zna6v8;6? z6NrUGml$-S6oLS}VR@qI8J#xW<->%g!sSr@fOptg9)9Tx$E(tU7W+k;6neV5O+ncN zcMa{|Oe8nyQ1Ad!I|Wpik`Ui~DNwww#Aw?tt#fz7OWO}k82kP z0V4zmV38GDo{dKh&&oA`VE2Q!03`;J!wUK4?b2kKOGsZki4!iEl?Qzx0ouUu`;5}H z(E*Z&r*mAm%vL)+$75EJKn#~}xF?;c%)Y+9XqNL@Prr85ym+{@YtHReTij2bX%=;c z+ynewSbDy3t}9^ZM?vh~td7mOuA>XFVnG0-=?!ECU~8pTdL-s@>KlM-Fn*RS;}|`R zVgDu|N2BbEoS1oeVq%h#76Ld2)~)<$Gv?M?W8f6K@48F`E@X_(7{00y;@iSwwENgX zFQvrHJj_T`bg*XFAI`7*ZQtq<)_@UL*}x#&d`W0zK`_*1kQ0W=JyXyxK`DSGz9!t zFMGVNmdXW$q`D^#Y1wnE3VsDM7X|HMETM($s0n&yh43{WGh@>duUnQ!mP^7DK?qa6 zB$y|R?w}_~Lgst>_CCy4h*9LgQ=|1zZmFN2UqFnOt<~a6b-OP;&PWnSOtq93qTB^F zOuXb^wy+pg+mwQN4C>whpzj!3Y0W7tXi5549|G)~_&dOU?%aT!k37Bc*iTo8UP(Z2 zdyf~F)bT96iY=K?Y@!#2j!&Iut;v#c3#t6&;gzk>u6TmdHN|NIV>+Ba|H+XR;2V;l-%$8sU@0_{)$;UIKK zv~LY8*IQT!VBHKB7_K=wSfKtpyK)Fm7xcSfclh?<8H8@1z9%sSu&Ct)U0DPM0UgwK z*fHip3uNGRASX?eh8Lt)ELf26JX}S&r5-N{a8Ek%MC{BGJ%(%3w|g0lNL@2G?`vexiBp{ru#1?I|c^3tQay zUK`1*$>&%o;{^1;45869SATs*)vMRZmG9; zx?7T#4s505CFm}TfJuVN&9?~Kw(xE3wHI|WhUV&5$DiKyHoS)qzypwaO)n*aK#^q# zRYID>Hg7IR^eIU3_=?whGo;#*c`Z6t)I8FJ)yv3)@O<=X5N2S> z?kWIYg_t0_FE*Y0WR}2go4CR6K2qet;s6`p*C(n2(>$r7Op;RK#MEzL zV#~TX;15GU#nZ0lm3O|M6TMgJ_Ry|~qjSI&L0Z0WChSkzL_H8%Rj>xFZfv$hl_Cq% z-+zDZf(*DCNa;ob{>`Py+GmZD6%RW*@5pkTWK-$cob|@labrZva^91_sB?j=-yb<= zJa`^R3`#*0Xq28UE9V%km;B#ogZh6BI&Oj&K%cXXZn?m!{>m+-&ZB4*(^uk2(KCC8F7AI!BT#j1G*`olvJ( zLO&)u?w8u9Zw>0kd;W|QCyNp9 zi+QlLm1HF-xY57`SnwoCE+pv9NO;*@Uwg`+yr%WrEuj7#K#rYZvBsNh2je|$l?2!9 zn-U&cb>YERsVOlCwDnVs3U<#}&M z1~3xi(Yb3L^XEVNxS)MEO44}~v+hHSy7c0XE*8C>Ls~b?Ey6JRSzR@VumY4$bQss} zsVe}~$n1=pe5b|xjiq%MB+?YDh;8HIyFW7AQ?D|cj@gY*tmWPi=6Vpi9OMih5Rbfn zR#e$ROnSR*TM_UH^thxUAOoo@K^W$H7N1njXN|`K>xXu+66zu)+!xL6ZB_X_& zzIdKDcUJQ53!lO$!wY-UUW8186eAV-t?K7Nm~R|!(57#N$A`8 z&_LKP@!>smJ}J*|&y}fLh9xB_N-Em+n1!)srv$+3biFvg?Ts%PSP+BagXo_1%D-^{ z$XHbHLJF_PeiD3#w(qSH^qvvxx6{fLTpK28}-7?-bjd$W?9 z5`XP{6oHKp5~0l6j;I-NXse$G-a|48NH^r&{&L`0rNTv0B6w)PF~ZzI4P>>*)IVMIVtJ3n$>$fSyrQbXtdT5-@ph zd;V^CHy{^dc_S>ReXR8I^k_!dtE^j&{j8$m`w#x5c2myj7fm|7y}fV2qd=EZg2C|U zd?{A1dk!!@lA#y9$$Z@ILcm1Nk-_G7>&53qB_>Q!NKgVi?mRQKlU#5}Pe}Z%47?O8 z!&XD>>f(NXSlve+JRuWAPNXsyYx{yj*BK_lni_5>xbZJtZXDN(vr1=%Y=z4&AyU2h zlcP1zWP9Z$Z5Kx|qpjI@>pH}YSZe8o>mId{?7G+k`Ql#hjOJE%LH&&f)5H&67UVJ_ zrx1D+Pc)M%7pZ2T{lhh`JSm3C9I%j$jn)}c_A(jG;IhXoh;V%@%2~8#i`0WD|KgMK zm#6r_8&m&G8_&sy!ZS>>B0#3xrn_e>#`gG!K+p(1RUxJtbW=M(fnMK1p@l$#(dZp6 zQ+eeiCh73KVy)z3wesN5yAn_Ep3-V@U2Pdl2gp$u!z2K3J-oGRDrxgmb{U(bzxRTf zM}A4|Zu?ids(lIyS`7m4Vv9$R3G)p5F{oEW%ubbZNzKm&N#MIs5Sv2Q1JexUyHTRr z#^YJ0xIfm98%bDVUftyn2(7_YVzr{YW6RWVi|dZi-mLmz`W;|QAQjQd0fmkqf zJc;+DRD<{JxpFCO)5rd?;l2|A8J`POs_w}s^KhjkCi>x(q2UT+(dM-~tAH*>3?Sfw zm<57Ct6u_oq-0`v&Noln%#jxt6I1;(mjW4d`+abB0ebm5IN1I(`_tx}eVvjJ@uE^; zX$4dri^lqr({yxoMao4R>gtLi&$atjwfu<5^T^?i>k@YQB|2J}mIvSM;Y>|c2DqY% zK!bLEE^BDY5lbwhsAzm5=WbnY-skwblr@@R^|^2M*G=w50mMP!iGqnz26qVh`}uV4 z!y#Xlx;#9W6Od*nZVN#l_!}@4{Dyd-@{XLj?%|Z@X(@V+Q)B1R$N(%9BDLssc?#+P zG(Zea#P@se)aU!RL#8x4**;4N>VSigR7hJ`z#tq&TpQwMX@T<*xgQE;Q`&90cRM-n zI$1LSfPhITL<3|~hD?w`%w*jqDH2MC16*-@bv+j_X993zbP8`l_Xbri+&hIiZ!vy6 zqI?ew7Mp1k>^qp_B~D+_(3UBkf%cLxDOfflEQYrzv#i$=yN?YxJeUX;pztGjb~y-g zT8s$F9QWWhrWU$O!;?asqvs+ORYzGH^kT$eOahzXg|SA<(0q~4e+WL@8!rst2(?(h z z`X&oGFOD7JTxj zPOt8QlV^Qwq+Xh8^308>@jW)TG^+SXVPVtD>f;*&K0X+~+~GT0)0&&p?R5KKn|@1o zu8zLKhYueznymZk>+gz(Xnb($`)0rM;e!XYFbzM|lK|P2p|kGHxK;)Z*p;q9Xv z;{W{l!#DZd*2bo&5l@=k}{ReapYc7RDhZ?C{D)<7hVqR=en<@2C{PYXmqU3I-`^+owNqW zQ>WChQf>s)T*v#|FRxb$HgVq6|1DU;*u%ucG_&A9aSVec_p057_=&OeuajJwPhWGs zeERf+yGxVAn6a75V4Gbk3nvp(jjYN!>&8?QVU505=;ZYqU`_Rye zY`y)XqgDos@iXT%npxcX+p_+ZO~7R5yy=!}+?O6H4#*!75V*O7iD^&Nm5lUG6UNQb zfzy|#R&$tG^h$-M_&8ZtA8K0>%SW|;O*6qk8I~xVC~U< z)oyFwsZT7}e@@pKy;rh+vYlIZU>;M{t~Ex?Mo#>HC)z5* zM2ces1Jr)E|JWf?9xLedtMU9~roy7|O(rT5OWihvd93=PE~@hBY|xLhLG!sTiBFa- z_#?=~#4P=e`?{)%qC1bvWc|C}K3pQZJuc2}&$)VjtEF(dNfIL{B&6+HswB_i`{C&| zZnJq0Zx4#D9b;zN!=(1Q@R@H}vc5=m_A=k(y2{BGGqYvBj}J{Yo>%ESKWQv)^Jv$t zdB0Enak6N3Ulic&KHXh(t1?*2purH~MvLP@>|rViWIegq>i*c@YUcBAYTdvtbKZWC+ z-K&DvMwu7AU8iR!{CD}OsFair40&AJ7|loD(JnFiH6ugfwo3OgD-YYJr*7MLq$Ot@ z9IKa_3~yPx^0sE(dC`xbyG4J}FJw)X a method to integrate an emergency map into a robot map, so that the robot can plan its way toward places it has not yet explored. +![Result example](https://raw.githubusercontent.com/MalcolmMielle/Auto-Complete-Graph/SSRR2017/Images/result.png) + ## Paper The auto complete graph method is presented in [this article](https://www.arxiv.org/abs/1702.05087) on arxiv. From ba4e916c8493ee86e285c33e405824846d4c3f95 Mon Sep 17 00:00:00 2001 From: Malcolm Mielle Date: Mon, 2 Oct 2017 19:38:24 +0200 Subject: [PATCH 7/7] spelling mistakes --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index f3732d1c..51fd2536 100644 --- a/README.md +++ b/README.md @@ -5,7 +5,7 @@ Using emergency maps to help robots save you in emergencies ## Description -The goal of this porgram is described [in this blog post](https://malcolmmielle.wordpress.com/2017/08/07/using-emergency-maps-to-help-robots-save-you-in-emergencies/) and can be summarised by this sentence: +The goal of this program is described [in this blog post](https://malcolmmielle.wordpress.com/2017/08/07/using-emergency-maps-to-help-robots-save-you-in-emergencies/) and can be summarized by this sentence: > a method to integrate an emergency map into a robot map, so that the robot can plan its way toward places it has not yet explored. @@ -24,11 +24,11 @@ This should all be soon ros parameters but for now here is how you can test the * Use `rosrun auto_complete_graph acg_node_review` to run the algorithm. -* In Rviz, one can give an approximation of the position of the prior compared to robot map using the Publish point button. Only two links are needed to initialise. +* In Rviz, one can give an approximation of the position of the prior compared to robot map using the Publish point button. Only two links are needed to initialize. ### How to use your own prior -The class `PriorLoaderInterface.hpp` is used to load prior image and detected corners. Just inherite from this class to create your own prior loader. See an example in the class `basementFull.hpp`. This only argument needed for PriorLoaderInterface is the name of the file image where the prior is. +The class `PriorLoaderInterface.hpp` is used to load prior image and detected corners. Just inherit from this class to create your own prior loader. See an example in the class `basementFull.hpp`. This only argument needed for PriorLoaderInterface is the name of the file image where the prior is. ## Dependencies