From 64efd4058b967183df29929c7b429f1eeb11eb69 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Fri, 27 Dec 2024 13:59:09 +0300 Subject: [PATCH 01/18] Fix Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/costmap_2d.hpp | 32 ++++++++++++++++++ .../include/nav2_costmap_2d/static_layer.hpp | 3 +- nav2_costmap_2d/plugins/static_layer.cpp | 33 +++++++++++-------- nav2_costmap_2d/src/costmap_2d.cpp | 5 +++ 4 files changed, 58 insertions(+), 15 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp index 927e5806122..8673fefb51d 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp @@ -163,6 +163,8 @@ class Costmap2D */ void setCost(unsigned int mx, unsigned int my, unsigned char cost); + void setCost(unsigned int index, unsigned char cost); + /** * @brief Convert from map coordinates to world coordinates * @param mx The x map coordinate @@ -311,6 +313,36 @@ class Costmap2D const std::vector & polygon, unsigned char cost_value); + template + bool setConvexPolygonCost( + const std::vector & polygon, + CostSetter cost_setter) + { + // we assume the polygon is given in the global_frame... + // we need to transform it to map coordinates + std::vector map_polygon; + for (unsigned int i = 0; i < polygon.size(); ++i) { + MapLocation loc; + if (!worldToMap(polygon[i].x, polygon[i].y, loc.x, loc.y)) { + // ("Polygon lies outside map bounds, so we can't fill it"); + return false; + } + map_polygon.push_back(loc); + } + + std::vector polygon_cells; + + // get the cells that fill the polygon + convexFillCells(map_polygon, polygon_cells); + + // set the cost of those cells + for (unsigned int i = 0; i < polygon_cells.size(); ++i) { + unsigned int index = getIndex(polygon_cells[i].x, polygon_cells[i].y); + costmap_[index] = cost_setter(index); + } + return true; + } + /** * @brief Get the map cells that make up the outline of a polygon * @param polygon The polygon in map coordinates to rasterize diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp index f0735904a9d..e91448d2544 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp @@ -162,6 +162,7 @@ class StaticLayer : public CostmapLayer dynamicParametersCallback(std::vector parameters); std::vector transformed_footprint_; + std::vector transformed_footprint_by_index_; bool footprint_clearing_enabled_; /** * @brief Clear costmap layer info below the robot's footprint @@ -194,7 +195,7 @@ class StaticLayer : public CostmapLayer unsigned char lethal_threshold_; unsigned char unknown_cost_value_; bool trinary_costmap_; - bool map_received_{false}; + bool has_map_to_process_{false}; bool map_received_in_update_bounds_{false}; tf2::Duration transform_tolerance_; nav_msgs::msg::OccupancyGrid::SharedPtr map_buffer_; diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 896dfc77a5f..5e095dae10a 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -161,7 +161,7 @@ StaticLayer::getParameters() // Enforce bounds lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0); - map_received_ = false; + has_map_to_process_ = false; map_received_in_update_bounds_ = false; transform_tolerance_ = tf2::durationFromSec(temp_tf_tol); @@ -282,13 +282,9 @@ StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map) RCLCPP_ERROR(logger_, "Received map message is malformed. Rejecting."); return; } - if (!map_received_) { - processMap(*new_map); - map_received_ = true; - return; - } std::lock_guard guard(*getMutex()); map_buffer_ = new_map; + has_map_to_process_ = true; } void @@ -339,20 +335,23 @@ StaticLayer::updateBounds( double * max_x, double * max_y) { - if (!map_received_) { + std::lock_guard guard(*getMutex()); + + if (!map_buffer_) { map_received_in_update_bounds_ = false; return; } - map_received_in_update_bounds_ = true; - std::lock_guard guard(*getMutex()); + map_received_in_update_bounds_ = true; // If there is a new available map, load it. - if (map_buffer_) { + if (has_map_to_process_) { processMap(*map_buffer_); - map_buffer_ = nullptr; + has_map_to_process_ = false; } + updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y); + if (!layered_costmap_->isRolling() ) { if (!(has_updated_data_ || has_extra_bounds_)) { return; @@ -372,8 +371,6 @@ StaticLayer::updateBounds( *max_y = std::max(wy, *max_y); has_updated_data_ = false; - - updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y); } void @@ -412,7 +409,15 @@ StaticLayer::updateCosts( } if (footprint_clearing_enabled_) { - setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE); + for (const auto index : transformed_footprint_by_index_) { + master_grid.setCost(index, interpretValue(map_buffer_->data[index])); + costmap_[index] = interpretValue(map_buffer_->data[index]); + } + transformed_footprint_by_index_.clear(); + setConvexPolygonCost(transformed_footprint_, [this](unsigned int index) { + transformed_footprint_by_index_.push_back(index); + return nav2_costmap_2d::FREE_SPACE; + }); } if (!layered_costmap_->isRolling()) { diff --git a/nav2_costmap_2d/src/costmap_2d.cpp b/nav2_costmap_2d/src/costmap_2d.cpp index 0302801297b..e191ed3cd5b 100644 --- a/nav2_costmap_2d/src/costmap_2d.cpp +++ b/nav2_costmap_2d/src/costmap_2d.cpp @@ -276,6 +276,11 @@ void Costmap2D::setCost(unsigned int mx, unsigned int my, unsigned char cost) costmap_[getIndex(mx, my)] = cost; } +void Costmap2D::setCost(unsigned int index, unsigned char cost) +{ + costmap_[index] = cost; +} + void Costmap2D::mapToWorld(unsigned int mx, unsigned int my, double & wx, double & wy) const { wx = origin_x_ + (mx + 0.5) * resolution_; From fbb3ff1080dcc8a710845e8832f2aa39f51bfe9d Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Sun, 5 Jan 2025 01:31:13 +0300 Subject: [PATCH 02/18] Fixed some bugs and removed the unnecessary variables from class Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/static_layer.hpp | 3 +- nav2_costmap_2d/plugins/static_layer.cpp | 35 +++++++------------ 2 files changed, 14 insertions(+), 24 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp index e91448d2544..08c9049d637 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp @@ -162,7 +162,7 @@ class StaticLayer : public CostmapLayer dynamicParametersCallback(std::vector parameters); std::vector transformed_footprint_; - std::vector transformed_footprint_by_index_; + std::vector cleared_indexes_in_map_; bool footprint_clearing_enabled_; /** * @brief Clear costmap layer info below the robot's footprint @@ -196,7 +196,6 @@ class StaticLayer : public CostmapLayer unsigned char unknown_cost_value_; bool trinary_costmap_; bool has_map_to_process_{false}; - bool map_received_in_update_bounds_{false}; tf2::Duration transform_tolerance_; nav_msgs::msg::OccupancyGrid::SharedPtr map_buffer_; // Dynamic parameters handler diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 5e095dae10a..abc6b57a5d1 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -162,7 +162,6 @@ StaticLayer::getParameters() // Enforce bounds lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0); has_map_to_process_ = false; - map_received_in_update_bounds_ = false; transform_tolerance_ = tf2::durationFromSec(temp_tf_tol); @@ -220,12 +219,8 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map) new_map.info.origin.position.x, new_map.info.origin.position.y); } - unsigned int index = 0; - - // we have a new map, update full size of map - std::lock_guard guard(*getMutex()); - // initialize the costmap with static data + unsigned int index = 0; for (unsigned int i = 0; i < size_y; ++i) { for (unsigned int j = 0; j < size_x; ++j) { unsigned char value = new_map.data[index]; @@ -338,12 +333,9 @@ StaticLayer::updateBounds( std::lock_guard guard(*getMutex()); if (!map_buffer_) { - map_received_in_update_bounds_ = false; return; } - map_received_in_update_bounds_ = true; - // If there is a new available map, load it. if (has_map_to_process_) { processMap(*map_buffer_); @@ -398,7 +390,7 @@ StaticLayer::updateCosts( if (!enabled_) { return; } - if (!map_received_in_update_bounds_) { + if (!map_buffer_) { static int count = 0; // throttle warning down to only 1/10 message rate if (++count == 10) { @@ -408,18 +400,6 @@ StaticLayer::updateCosts( return; } - if (footprint_clearing_enabled_) { - for (const auto index : transformed_footprint_by_index_) { - master_grid.setCost(index, interpretValue(map_buffer_->data[index])); - costmap_[index] = interpretValue(map_buffer_->data[index]); - } - transformed_footprint_by_index_.clear(); - setConvexPolygonCost(transformed_footprint_, [this](unsigned int index) { - transformed_footprint_by_index_.push_back(index); - return nav2_costmap_2d::FREE_SPACE; - }); - } - if (!layered_costmap_->isRolling()) { // if not rolling, the layered costmap (master_grid) has same coordinates as this layer if (!use_maximum_) { @@ -463,6 +443,17 @@ StaticLayer::updateCosts( } } } + + if (footprint_clearing_enabled_) { + for (const auto index : cleared_indexes_in_map_) { + master_grid.setCost(index, interpretValue(map_buffer_->data[index])); + } + cleared_indexes_in_map_.clear(); + master_grid.setConvexPolygonCost(transformed_footprint_, [this](unsigned int index) { + cleared_indexes_in_map_.push_back(index); + return nav2_costmap_2d::FREE_SPACE; + }); + } current_ = true; } From bf3c0e103da11b378d37d0aade0065fbdad63bd4 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Fri, 10 Jan 2025 20:16:16 +0300 Subject: [PATCH 03/18] Keep the branch updated with main Signed-off-by: CihatAltiparmak --- README.md | 6 +- doc/sponsors_jan_2025.png | Bin 0 -> 180794 bytes nav2_amcl/src/amcl_node.cpp | 6 +- .../include/nav2_behavior_tree/bt_utils.hpp | 37 ++++- .../compute_path_through_poses_action.hpp | 2 +- .../action/navigate_through_poses_action.hpp | 5 +- .../remove_in_collision_goals_action.hpp | 12 +- .../action/remove_passed_goals_action.hpp | 10 +- .../globally_updated_goal_condition.hpp | 6 +- .../condition/goal_updated_condition.hpp | 6 +- .../decorator/goal_updated_controller.hpp | 4 +- .../plugins/decorator/speed_controller.hpp | 4 +- .../nav2_behavior_tree/ros_topic_logger.hpp | 2 +- .../remove_in_collision_goals_action.cpp | 12 +- .../action/remove_passed_goals_action.cpp | 12 +- .../action/truncate_path_local_action.cpp | 2 +- .../globally_updated_goal_condition.cpp | 2 +- .../condition/goal_updated_condition.cpp | 2 +- .../transform_available_condition.cpp | 2 +- .../decorator/goal_updated_controller.cpp | 2 +- .../plugins/decorator/speed_controller.cpp | 2 +- ...test_compute_path_through_poses_action.cpp | 26 ++-- .../action/test_get_pose_from_path_action.cpp | 12 +- .../test_navigate_through_poses_action.cpp | 10 +- .../test_remove_in_collision_goals_action.cpp | 62 ++++---- .../test_remove_passed_goals_action.cpp | 28 ++-- .../action/test_truncate_path_action.cpp | 4 +- .../test_goal_updated_controller.cpp | 8 +- .../decorator/test_speed_controller.cpp | 2 +- nav2_behavior_tree/test/test_bt_utils.cpp | 64 +++++++++ .../include/nav2_behaviors/timed_behavior.hpp | 2 +- nav2_behaviors/plugins/spin.cpp | 2 +- .../cloned_multi_tb3_simulation_launch.py | 136 ++++++++++-------- .../navigators/navigate_through_poses.hpp | 3 +- .../src/navigators/navigate_through_poses.cpp | 18 +-- .../collision_detector_node.hpp | 2 +- .../collision_monitor_node.hpp | 2 +- .../nav2_collision_monitor/polygon.hpp | 2 +- .../include/nav2_collision_monitor/source.hpp | 2 +- nav2_collision_monitor/src/pointcloud.cpp | 2 +- nav2_collision_monitor/src/polygon.cpp | 2 +- nav2_collision_monitor/src/polygon_source.cpp | 2 +- nav2_collision_monitor/src/range.cpp | 2 +- nav2_collision_monitor/src/scan.cpp | 2 +- .../launch/parse_multirobot_pose.py | 85 +++++------ .../src/constrained_smoother.cpp | 2 +- .../plugins/simple_goal_checker.cpp | 2 +- .../nav2_costmap_2d/costmap_2d_publisher.hpp | 4 +- .../nav2_costmap_2d/costmap_2d_ros.hpp | 10 +- .../costmap_filters/keepout_filter.cpp | 2 +- nav2_costmap_2d/plugins/static_layer.cpp | 2 +- nav2_costmap_2d/src/footprint_subscriber.cpp | 2 +- nav2_costmap_2d/src/observation_buffer.cpp | 2 +- .../test_costmap_topic_collision_checker.cpp | 2 +- nav2_docking/README.md | 5 + .../opennav_docking/simple_charging_dock.hpp | 2 +- .../simple_non_charging_dock.hpp | 2 +- .../include/opennav_docking/utils.hpp | 2 +- .../opennav_docking/src/controller.cpp | 2 +- .../opennav_docking/src/docking_server.cpp | 2 +- .../opennav_docking/test/test_pose_filter.cpp | 2 +- .../test/test_simple_charging_dock.cpp | 2 +- .../test/test_simple_non_charging_dock.cpp | 2 +- .../include/nav_2d_utils/conversions.hpp | 2 +- .../nav_2d_utils/src/conversions.cpp | 2 +- .../nav_2d_utils/test/2d_utils_test.cpp | 2 +- .../ego_polar_coords.hpp | 2 +- .../graceful_controller.hpp | 2 +- .../nav2_graceful_controller/utils.hpp | 11 -- .../src/graceful_controller.cpp | 5 +- nav2_graceful_controller/src/utils.cpp | 10 -- .../test/test_graceful_controller.cpp | 34 ----- nav2_map_server/src/map_io.cpp | 4 +- nav2_mppi_controller/README.md | 8 ++ .../nav2_mppi_controller/tools/utils.hpp | 2 +- .../action/ComputePathThroughPoses.action | 2 +- nav2_msgs/action/NavigateThroughPoses.action | 2 +- nav2_planner/src/planner_server.cpp | 6 +- .../test/test_shim_controller.cpp | 25 ++-- .../include/nav2_rviz_plugins/nav2_panel.hpp | 6 +- nav2_rviz_plugins/src/nav2_panel.cpp | 75 +++++----- .../nav2_simple_commander/robot_navigator.py | 4 +- nav2_smac_planner/README.md | 4 + .../nav2_smac_planner/smac_planner_2d.hpp | 2 +- .../nav2_smac_planner/smac_planner_hybrid.hpp | 2 +- .../smac_planner_lattice.hpp | 2 +- .../include/nav2_smac_planner/utils.hpp | 2 +- nav2_smac_planner/src/smoother.cpp | 2 +- .../nav2_smoother/savitzky_golay_smoother.hpp | 2 +- .../include/nav2_smoother/simple_smoother.hpp | 2 +- .../include/nav2_smoother/smoother_utils.hpp | 2 +- .../assisted_teleop_behavior_tester.hpp | 2 +- .../behaviors/wait/wait_behavior_tester.hpp | 2 +- .../system/nav_through_poses_tester_node.py | 6 +- nav2_util/include/nav2_util/robot_utils.hpp | 4 +- nav2_util/src/base_footprint_publisher.hpp | 2 +- nav2_util/src/costmap.cpp | 2 +- nav2_util/src/robot_utils.cpp | 2 +- .../test/test_base_footprint_publisher.cpp | 2 +- tools/underlay.repos | 5 + 100 files changed, 492 insertions(+), 424 deletions(-) create mode 100644 doc/sponsors_jan_2025.png diff --git a/README.md b/README.md index 10a5ed3f249..dfadfc6a0cc 100644 --- a/README.md +++ b/README.md @@ -15,6 +15,7 @@ For detailed instructions on how to: - [General Tutorials](https://docs.nav2.org/tutorials/index.html) and [Algorithm Developer Tutorials](https://docs.nav2.org/plugin_tutorials/index.html) - [Configure](https://docs.nav2.org/configuration/index.html) - [Navigation Plugins](https://docs.nav2.org/plugins/index.html) +- [ROSCon Talks](https://docs.nav2.org/about/roscon.html) - [Migration Guides](https://docs.nav2.org/migration/index.html) - [Container Images for Building Nav2](https://github.com/orgs/ros-navigation/packages/container/package/navigation2) - [Contribute](https://docs.nav2.org/development_guides/involvement_docs/index.html) @@ -28,7 +29,7 @@ Please visit our [documentation site](https://docs.nav2.org/). [Please visit our Please thank our amazing sponsors for their generous support of Nav2 on behalf of the community to allow the project to continue to be professionally maintained, developed, and supported for the long-haul! [Open Navigation LLC](https://www.opennav.org/) provides project leadership, maintenance, development, and support services to the Nav2 & ROS community.

- +

### [Dexory](https://www.dexory.com/) develops robotics and AI logistics solutions to drive better business decisions using a digital twin of warehouses to provide inventory insights. @@ -39,9 +40,6 @@ Please thank our amazing sponsors for their generous support of Nav2 on behalf o ### [Stereolabs](https://www.stereolabs.com/) produces the high-quality ZED stereo cameras with a complete vision pipeline from neural depth to SLAM, 3D object tracking, AI and more. -### Confidential is just happy to support Nav2's mission! - - ## Citation If you use the navigation framework, an algorithm from this repository, or ideas from it diff --git a/doc/sponsors_jan_2025.png b/doc/sponsors_jan_2025.png new file mode 100644 index 0000000000000000000000000000000000000000..5ee6446cc7e56184996fe67b96be91e1684aa4df GIT binary patch literal 180794 zcmeFZ_dlC$_&%;fJ*DdDqiCz>vPTq+iq(bMReJ@sE2)YtLRD2&?G<~~D7Avb45jvn zQ6pBWjZM@{h48)gd4FEd`}O$)K0kf^Cduu-?&~_w<2=seJRckS0j0o0$!n#^&d} zGvl};#MNkgvMSkEC#Brtrn>11l@s0=GX>hy<--^ zFk?U%j)~19`urPFt@F`X)BfbW2CK65VrF=kuS0*Y^cFHvgArK4|Nry<@4)}_9msm4 zs;0)q&CM0>8PMp^m$J8abevQF^OMEUo{w$*ET?ujk$4cu^nYGvU>G2`=i{3{ z`??)Ao%-)pCxmU3rS;6sBcz&|8glHjX=R*U;2za+WKWuH;m1Md|H>7a+CE{)g^0*V zUh@Tlz1(6}@au#1|8)bIiV|VTGILz1VE~E4^KkW{%jjqI%_hG8ZZ_~0o8SDIOhwi8 zXO4WB3k3c5R#uqy{h&Q*&%@92SqJO?`>quwVv@Md^?loP<^6#ZOjo~eHeLSjx<7wX z0Ro|QLjonj59%rZ*OJ7AC3~98ukY2^0oNDQ-a2yp?^*_JiW_sU?BmkjxgtoD>w{6? z>A^>&6aRfernaI(LekZ_Kc)%G|9`*pNnFy(qw{(wEc3|qze^aHtzplZdsp~7*jQP8 z_x|_eKl$6%{E0ObIMI>K6<2=8&Lbs+o!zbOqsIR(fA!io?c^5k9*O0@*Mx2}_x|_W zEA{N=bN~H{zWD#-&C5JIiZB>#b;|$z-S4j~H=DS$KjQ*3_||ZZrjRL>EAn0)bT6l< zI7SxEn%xkVPX&6nn-}Y97IjL)-qHo1{N&_N=JM(^PC5`8 ze}^Tp-V4uyev>%i{`e?uwf51v8|_05L4?+u6SKgDdOPTt-0}V}LoCX_f3QjOsGpet zaeB03R!xX*@{0YTy1&8JlLxs{0<@^qI zP>90@A=_;pwGzIw4CosxW^n5FVJ!>AAytaW(4so&W)r^e4TV)eBMNh$c7@x(YCdF1 zQ!9(HNZtSb@QuriP~Y*4m?U@W|KqPq~G@p zOUn(_QNW!Qc57J{UHf6DlIK?1B@T}Xhod9A3D_4c1as`0rF!zA{4>Ae@M`#GM92;E zv1O39cjDIfIrjeW&ACRS{Vc^1!)*Lrrft9RFV-6qN3`gD zEXYgekPZ!qr$`(fT;BArY!JV?2o5g_r@wT{=DdhGsSAD?{^f79X*g%ZxR)HMBXe?V zOz&yKV&ewS&vi$rV=Fl!0NwEIE9D-y@zHd6`c~_<)sER6*RJNLC{XU$r@bv>udimW z^1sW%w=>AzY-^$&3)7yF=3TLPwe{MqM581FpG4v07&t~Lc{@*x#Mmc)aCe#@;T66q z&d4zS?B=9XhcV=9ldKKxZ|5Rd?382c_W8XX)g?&_{-b@VJrY;9_Ljxo5h?NLh@ZQF zZ%0EEC#%><(me59JIq6zM@K7j^@O~Ka*?|d5SSL< zIBy-z+yf<>ZO>SrqQ2O}L*dV{9nifjy!lu@+yC2-AZ)Ug$ zxV$Ex+;dGA4J6?{AIj!z-`XSbefx6H?E7F&l@e*f$r{9Nn7Q}zgqf9qLx|)1ezYph zLYx%NmU3-cau%ZTK7)zhyQg~5VQ)vHD-XdVZxx`ZS*lmi?YWU_N`h!a#eN?7A_bKk zC>RqeL*DJ3>G&pa!kXDGI3s6yIVZziqdR`hx9n_@+Jw)`qt%&F#a~sCr9pW_sjvu-b(P`VW-VU9iKH4eM6gBb z;kB_sK4i>(QADin5{-ISo#>I^J*IUM!`6|{E6#|-=CG5oD`d7F?V`%~EnV{1+#@9X=X5r_Vs0rMF9 z+_OVX-HMy(W-q&N9Pjg8OV11Z%H7_A#9{jPo)kIF>LA`mO!Kaq8d*2ex3+2XAzhW) zcMCzcj%@w0)55Bb-x-(6KC)2-b1UDwoQg`xeudQwm`C!DLGf zpd>qaI_J)ll}>~F`!Mv?o60}6Jp(8R{>Oar2SaZuuO?Uwy1}huE0ha$X?hq%^VngH>j% zIT??v<$MG)q1SK;fU3i%dFw*7;R$l3nsK*Kb%qlKNL#GpDHKGpNg`o?TJ*W7PgbFa zu!pi&Xio)xD*mv++i%87f@+`Ge&*HE{h(w8n{9`NnZ=#N4X>e(5rEM z2ouOuUe97hsC33(f09j)rI&-A+(20_-E366V;^vD=!qD>FS~n#cyVaDl!22l~!~&z4@#m0Bi2;o(C-opo#`YY!D1r3@y!R|h>Z z(;DT7?B13__!}0Gm1@VPUw9^Zk@1G9jpH+lYcue8Vw5J$yDIqvr|jc`?kJX9pgqhSNeypwfCJdf>zx0|%#)_VB#9?r(G z^l4uCj#tFj@6{$SUl542Jiapacbg0Ml5@reQ$4aGEmt$lve}pzhJ%3Z&RK-|Q@hLR zEEbdN>faH1^Wmb`lWZ(tjAbEb#*E7{3H9%l& z&+v&Otcx|%`;e%Dz{rSL#Y!X}UA|8np}X${2bme&5=%UktE1LL48@&8M!8T*OM3M! z+rY{Ul5io(IN>fj7!eqwvn+cciE2_X;G5tSB+wTM&7kO!>A0t{@OPbsl0QNs?Kg0CH2Mn##+5QJXsGqkPF;3 z`O9MOyz;WhLqF|Ud=C^p+nu4&fHXgBc$Akj_MH1;+3o6*3!89LEUc(xGzKrhEg6#I zw2^o#=;~Om$rbaT;FM0f&i)t3xD?5R;g#^ipkyuQs#ESb4~Ih`xrc{Tx6KtNa1nT= zM(I&@E%{$0gj$yx&}j3^VyeoBg7IsOmHm!F=9Hm4%uY%^JkC`@CXsjfSA>2%jGxUr zJz}aB@~|^%+6HbpGL115zw|-R?;^VELjksKpgOkFQRRU2~t`m63yY1LpL zw`KYbQsi9ETi8H+8t7cC$h()FTMuM!5u|8%I4a#1NI#K<-yPT$FZuaYW(LVT;6RhzP$i5!BTApLQ7%#n%X{7v4jgIQqMUawSH7~Wp5JR| z6l8AZNp=)X7XeRPcep`sH!zir9QNAHZv+5it3t7hnY~`O$IV{S$H;n&e}l;w zOq1ti5Mp5NwVTKVS#8fBdQZ3Zs!|?t=iP+($(##q*x*W1*p5H_CozSYd%L4{XQ232 z*Y47#-nYYCzFf;si3z1A;#@^#A`&A@v-9f8uvZD(%U2hUF}>V|Ce7V*C(Itqjo!}W z+A+7xky|lV>k3mXQ?v2Q4a1m<+BYc?JgT0!rJjvbe!L$zdYaPQKcH9)07Ab8zxmv2 z$MjgBgk8DD{n6Dg^!zq8cl$JV8O1f+Sna1MC7x~;FMeH&+Ao_jfmOC|GJdh?k-*NA zW@Ii>zq+7S`FxQ7yJwes*N$hTJ5cvYq@K#@o&|!VyeI?u#BrQB=)(a;(rd0XF}^fKq6`OAywv!7D)g(XGVjWb`|pkD4-bc*OduTZQ_vF}41{Bo-1lA`>r zFWR3#SIM2fqU_=NEO6uPx17qd1Aw&S?xG^OjI5r&-e!sAZl@Z~AEeV4Z~Hu_=LdLtSifp<|6ApTFLOSO+_%zXsUM6(K*xI$a7|(;x@uwwYc1887QQwHo1;m`!1@ z$C159TO)=f?{bPI@cGX#^p16XCom9jEO97u+F`{YDs-!(#)5cjVS7iwi*FHV<8Tj} zSQs2mGCD{hV7u;y%>C5}vzl(R!$J zW%~S&H{j`$IZtiaDjjk(ZPi|Y8yD#Xnx*lc-iM<|dSm9W}L9mg!95K-T; z@G&2adnmK6r2qCU){AmFM+02=%@qhp<4mPEhtH_640G?t3qQN6A5(Z1l7)Ox$TS6G zrm+M+()8h>oY_m+nEleKu=4{c0}lK>;+q!Uv0=lGGJRV@?Gdm^>|Nhd|0d-!R3xMW zYY+pj(d?f)8d;YOc4n|{e_}1b8ZFdlxOtPi#v3{K{d+^3^ZM@(4j0e;iP>7_-WIXx zdQGdRU8klpS&{xPByA8Cd;%ai&`j@PAGAJSTD)SithN-2j>xocWSu4eoljYEsY(d$ znVmU6#=r6FGzy{WEnM&*oAB53J(d{~ihQ@$6RbjaCUQH#fi;5%07AUgf$vR$y2@NU z!$YK++y|BFw~U=*z0$1;vCH+kRkj>)iD4jL~EbW zx+>le}Lt&frj_%@c|%ruLLzn-N2xAFiZV>0JU=!A^z(ol4+ddFhP>wSBmi z@KOT`z@~VYtvSaJ`0n~5srg70mbWEo?-3|KU_RSRlWVOQUVOt z0(!vNaHXI1E>>7QFbhBhVm)FggHr|}Tne1by>Gs0vvZy5V1Z*qRVAQ&?D!y))Q<&ss(;o`23HEyCY zIN7%E1F)E)(@UoithDg{AJuvoM|ipBmSPl)71d#YOjHL+!}f2w86#tmsn8yg25%Pw zaX)`DvcCV#*~<0mva4OvJ~;WRf6n{vwV!0rk_WO@7=eqJ@*Q&aN#`=~E?INy>Pd2V z^oPe!oU9yDoFZSLpG{0c-tCI2%)`{`-pS#t^r-3iI&u@fD3R&2s*$7()&jY*O&8CD zxNV+%U3Fq@y%+M%5 z3oUO?t;jJI_DHL}oZttg2@7?$?Mx~R3=X`E4nvQ+68Su>b{}{b_A3o3s)>9kf{FZ# z_Y#t0iAlw!v4jmpb^+?ho$BsoS?l3R>gY94;6O#eb6OK(fm?j)4@Qra}=<2K09bG|hXT!jCO{c+|>Yn@U3T~nKf zROQ(E<*PW13ROgYEPPl*n%^-)B6ONFuRisz;>6;s(03fy9*aZapf;AgrUNDJdd27F zr|-BPWx)V66o}fjagAOfe1g+5BvUV#L@K@BCBox*ZCbaZJSXyCgInJD1*VfPn0$Z zQGG{Hnd9IPu2iR9i8;Tn3n$Nv&ZH|jHaxuFf&21r&f%NWb_DCrWCD_5$GQE9=N^*Z zh|txm`xD?ZJg045FUKHYhX6<>h(k1&q}Xf6p4XEnnTHF@Tq&<#W|>ERL4OhtMU@=T z?xov4>gGY!2Il&!H95Be`r$LG0foO0=x2oQZPVNfrc(Qd`77mnDsSk9OR!0dO|v;l z`v_t+Yo+i8*wVr;^n%-qMJLx{ z&|K2U{+!$b0nvYe3yb>(5W9?Zm@Tjr=J@@}gr5KtCmLNDA`mjyLxushllC5&3Y+B1 zu)js^+BkY27He5U?ZqC-1>F6uz+ES;wL6{m@^d%m8Xw)YBbH1Yx|^1IFE_W@!UHHK z!;bn`nfLu)&rWYlEG;iyP9trHq`U@V^zrn?+-9-5x-%cbhN_9HofAD92ae+U+gnx+ z!OJcHld{2=NInEw2){4)GN+JA;x?C`i9bI>sTX+6zU!TSL42ZrNY>IJrwGd3biL!d zQ7g2^ZZifMRzLQ(i%?1IRiu3KE9>hQm$?cAi}fIK#1pKcl)Y}sDRFgIl(A`d@hK4+ z&wD*{|7ok3UV4{*BWo-byEN*-sJzSi*&gaT;c~+}XO~IfYVM{A6N{DIGw&?UnXL%M ztP^_H5)j~T-mS3lOY*40uY`_p?d$ERC-_jY%<13XJ~#$QVXYujPY+h{o#5@$dltBn zz0Y%+-z9!Mlr?yt%okDM8F2TTZSM9OLaa39C9FG%bx61FYt-~CBo)v((a&#AE`~o> zzUq^4{`GdwHt21TtX)rTNQMj9cR?Q-e{OVFRa~_x`!SGi4+Jz^6VfQ^fnNSD5ht5$ z2T?DK*KTF*(>E3IUtW>|2Htd)c{1Eabr1)M^{xfy{mNtZ_0xaqW1XxPHP{Q(#*92q z3|thF{?LvP5y>$cr*l)-l=mh3^f@Sd4PkF~AWk$S z;QE-4M}9;^EEiFT9%ADR3#&H`pg#uG*V`l`^fREX@g!-aTV7uv8N<;tG8;aBV;Ij4 z$ybBcLb^mN?Ol*#7+Hr?Kv`x^tG`7WR`m7!Wsuj2nwUBC1z#EOdD}I{I%(=e*~}rk zfD7@jPE<;3^|!%@yF&Ec-`x>=w)&V`byr3l0YX%KcU|YzKUx0<-1SO52(RqKK>8=7 zG>~Yo`qgZKE&_K4T)D_ZCVS192- zMk6Q+X}gqZi;U$s=J}X4LxHPF82d)9y3A^o5iY~$<{=DDoEOpIkpSQzrW%RijQ|Ai zo+}v`4BT^NaNzud>Mt1`#3@TgjH*@`DRarfeLW>QmX>KZ85{Bt@)A?n)}Gj(Rrd%_;49A_CQj~o37LOX{wXns@~eP z-vvtK#}~{d)|{wN!bk}-Y!M&B`aAh|ttN+a=;T3X`VYon6y$~?$pQ@t=iD*pHncKG zRqSR-hOvFQMt_1-XlQsk#r369v(%gA1{Y3kBzP`uA73KQZ?=o#?%Gx(R3O{SJY9EN zg9KMLSNDe5r9**zRj1(e{P3i;^VRatD+&tNjoWebv%{6!(qqn{07=i?cR-R4^Ij54 zA{=Tb`?n2@lkd`bHEkUSM+%izLR;mHeG*Tku>FhW8gctt(3-7s*BjpN!iGqrN?UKdgbY9G`lfD+D@!R~UH)`&8%@A_ zmVht$zpvUV_<-;D?0!`v;To#>EydsR?B^CaCK*BIUKK#NjTfP9&OKFr>3YYFb}q3u z!}kwk`oW0~F*UFhW9wXxCHQKl1M(&88{FnOx&!qa`1b`P`_ZRko*F=TFXHiN4!QavO8M)Iijbx&k+I8Sz%M~ z(zT&oA-Qp&MB$(I{?IL^$cts})WB3OQMMq~zi|QI&#wRtZ{^coTcu);C0}Jk8IFh_ zW1nb(5x<8lWojEJK0m}5v&qhls$rfsdb!R~{ikFrjCm_NQ}Z@Odrrem+{rK=0#NN>eKSZ z)r0vTdp5QA0Q%EttpO9dT;Wg)KKEhudkN53>h45m2VJ#Sfd z6EJIJ0XaIJ0if;2l?{b(; z{1}M|n@*kc-D5U-*4(WBH`3J_GBE}uSMB95|!W{8od*&cI~?4E;~HrI3?pHi`UQs30$-oKz_VwpGAeGnG$ zNd-t$1uAhMeJM1UAnHK!vMgpT0!6zlduzwfSS@TNiPwpY5W!x^@~7=a%U2|!CevyY zTY_)%D)?g8$9Oiyw!(mfwG9cocW>)o_I7qK2?Ty=JT8QaT2nVNNUUGmBwf^E{XFQxB!34W~jNl9>NWrIgkl%aO>6O!5h_lPZ7-LPjb@yp*G z+$6>1bFI%fv<98hB1?c3dYrER3gG$r==w{S53rxW)GQ*v6?0b7bE4M56twWoSD-Y1 zFY)BS$A5{<1Kt>ykHP-0$1JB4?8*86wn7Sw4mMo%DgruD{SJoOuyBlu<2|U*n%fh5 z$Hb&b|C^JYD0@eC0ls*zh6>W-!RW`E6PNbeka4%bP##q3Ns;{rwuRzZpKS+#V1XmVW&l+3&iuEMJ}1 zAy_4My$`)l_CKuUt8eXK%Dq_pOS%Vm5~&Q>$Q$xAZo{ZWpa;o3DwU}RWECXXM9ug{ zQORSO3RVpc?|SlZwdo2Y_Y+AtZ651w=v|pDKO(tk7RPEJ`Ng^g8*=Zolppb!Gl49A`zL|} zo{1kTTpn-gS%(9^ITJ7{giMm1W(k$!g>W}4Bp4vOlbGNUyuHFJ%9=yO9Foa@Q zC*v4$V=Ep&-p<^du@pXZd7TE+nfWGAU#U2vg0*NphT!w3{w_X>fI0uXab5_0rX)Rl z7;5R;xoCtEtHyshP4OP$E&G0Og8AJ^_d%dbCcEX_T`Y@yQ8<|IT+yVe-Cp`r;$@)B={%`!$OV#um%#X||-5ICW?R+ z_~t$_ib>%XIb{*z^!$K+NM<99D1<7=MBi0ssiE%157CPzbII2FsVA&-Pz-YS=Okj?KLDS{aPjoN>Ckx#feV|$P5i9Vi1A(d!+yKX ztxFd@vjelwPPydql*;7seOUu9Z(0LP$I-XkkG6moBDSe6sSg?9v|&xL{2F6O8`?0o zv$6bGxf^Y9a2_Py0&74&!p%}ILks%O3PUk-m^nX$!7%}`UklgbIL7aY^M5rAu*D@U zi^wEAYt(h_O6(rZi_HBT4c&B17Bfy6Z|stAv`>ead1QrbOOpf_dP_VfN@0V@xxCF) zB>Mb~ep${}umA12&L(TY;%Bb&G)p)5G>cCq({JN0{;A*J7#-|^)<(cwM82_DXFpz? zdOXUDI777~ALUm0Ot)t9)yb-J)2nsr6U1pJx5^Nu4Q)WblHe)^OHAy>B=A7*mY1E4 zTX&ho>mb>mk~`(rC0;}gjX7uEI%51nJ{Efdo|}KMlLk{Iri>(kNn78H`=g~LRYAdT zdk1sx&0TMLXYhU8zs;~YI8U%5&Z;e$vDcEcVYnfCeYoc->X+k+muGTHmqB63mIIBG z0i2b!kRwtv43H=~9mo>CLNveKCtow9%-{T}cen#`-)eKR;0f0tp!(!kY zplb~P#wZV|wyi_sS5QHF#0kXmxCl!q3UtLpd~I)S!>bQ>=eqqn&SVfqZ^!-Nw2Be1|mYZ-6SQJK##6!;|Yil_`*_DpGdn*jWPNFa|vE% z!Fa!4C6)}{7qr4{EC*OVS0Y(3Fu(aXtL?UaP!iIXLnx*b_j?0#fBpWG3>VR&37qL6 z&N$QddEpjtyz;*1nPqYH*Z$@Sgii3<#&SAYZr;Z^iF>)qm>4Uby56>= z31IoGDVGqStsM6p(R~qI`A3p^J1kId&#@Nqb(y~Zc^2svGx|)npeEA)5uy^9Q|;d( zNxR({A=dAWip2a;px;u`!OuwcU8>HZqFQ92b_JK*B8ghQhtl{-cBZfghal?8P(D_k zNBleV(=gCmU)Q~~M5*~^ybHUk7ayHos?2aeXN$OT&zb$!tRHVIAF9WG zBS;OM35TKaEpNN{1hD!`IfUP16W35|#hxel?+4W`0;|N>yU8N;c5VUAFw-U5+SRT< zde;-{fN=ya{cLgZN9}&82K3<6Dj-jKMlBCz@By~YKnb};G_iEy(RZcU(1*IEPks{- zfGY^{dbxBcqX0c&9qDg=?Bj$TRyLH^MNK75ZdvgufPrMz5}-INjinE8p5HNeKbo|( zp82z5DPZ$5ND8);Q%edTDsx!x>!yj_MCn+Ht4;i1dh7ntF7i%m0Cx(mP zQtr59$brFLl#BDCfa}?T9Y|p8-I)6Ruar{(Xo{Fs{^$XYh5e7bDkQ1=x*v_v+mv!n z>d{(qyj>q*GB(uNQEU^`B%>J^0DgxUn{9D zY6Nr1F(kyhFE^3*J#Evy1m3(^;(?O!4mWXJlP9$Sq5gqD0#jbpz6(2l=;FPW18O1B zce?mNtruQfX`woQn;_-9JJZ`vxpeHA!x^5fs_H2A+HBd*9a?B`e=r#j;?{~kZ2ua} zWGJHb?Zh!qX>}Ss;^Qo>(xZ9pCL{x*;G1u(jPq%}KsDAPE5T0je$@uYO`=F|y1HZ2 zZ*AKHTBNvZe6w^?6GWisgI1t00Cj&xV=(a_|8vJqFl}#$k@=NWt{njc4xqFcMP4XW zxJyow)y!k}Lz=!CQIeiJ+i=59s`fsO(s67sDKQwWcs9&_d~3V7k|FonZC9xI*C6*} zTk!M`6$IYK)Gp$@&~Jo!JO!GPT-@lg;9KFodCog>_NvcgJd3wFJ|`H&Tyq3rh`)Rs zMG$~GD_pX)e!ZP_>;N|K+1N+_Pb#nc%5B7rT_6c)9a;;WR-YP)m0kJg#~xNBBL?0; z*_J~DDq1S-)573-n8(Tw@hr+i^sZVRSVdz0%%P5R&r$UHVB1?4=Ie2N0=0)0vuY!_ z4tn0Oq_r2UOjwe`jh*@A|ov1{D-w2?*;1@L>jdjz>q60*6HK(RH-#aV7cnDyK@3kkMgts_;?-$)#4L< zEl+9Yp(3S;=Za!MF;{P~jStYr*_c8_fxHC}^(xST9=DA{M^!eosIzNN@UZBghk{+j z^*+}t^USJT=T%M>cR0q7C((az)^sJtHhp_LVm#6ILT@+yfhBOv#MLQS3mN60=jnF1 zZ@?g4*Y;}LSs9eMf&W94>~46wVX0mfq~z*FPCtPnUi+IJL*p>)@$)zhW})O$k2J5I@14n0G7{T*1^xtqyDV&XS@le zps6qL@E=vH&ME5~-p>HPXaTcIy7=&)I7g1*YKSCirnc+P*ot^>e@;-YDt&sfrzy zuyNsgoxvyk*M6MgFyKz81Z*~7t$vy6g!`MBO|V)uN-{}m_PYi=)!*GlincIb`lSE} z_`<3MZO;kx-%?98$hrFM9qh~RzT2kDKp)b{sX|?#zr)!bJ?MY&%`~+-593*%8e7(B z&=V0$?P>fdPcl-m<`NVoZ=ptiiRBWrPCW*|n2mmhK}hTviQT|}7+%R*RJL^Nray`h z1;(g7CnOPk~NZ!C1CDR zE`V;+T0R+B^aajiRKo8HdU>!)6kjA?BHUdHCJONkCbPeFe-6$;T}Opklqq{OZO5%+ zO!Wj(yF4N+hD)zR_5Z57e>g3UIG|htO(@U^j;G)l+itD$%Tbd;9TY^ZQX?Rfa2nMp zDQfsK_nO-5ECSw<7pAs=*=EH4Wj&MCtQsX4(MWr5k=mc&G6wnxmx#5v1J(Mr!Z}tf z*xxr1$0yRiHJ0m}e^+qzm>uc^%cXe99oFeiC%;k9BiErG!1+XY8+iZ7lWoHP%xVP+qX&9)zUBjWJf~ zB*zSlftKqhX*A_N?H&;5hbo9XN}k9Z3sSYAo!XNJC0Yp9!Vi2GCGFugp=Kg-RFm8yLV>GhzsfCXMjok{fwYFxfL+|+bkQ#GCMQOOh z(+=&AUr(NJB8tvsTDd;g)S8h|LL|0q^)9ITKBkrPomWUs4!dJ7EV-Y(ABd+&4};R3 zA7ltsuLR=@Ti6HkFpZs!ecuvqitQ`HAA+M*lGs-*C%=Mzj8+3tES5mny0FwUWwqd* zD9&9av=9;unhohqj9o~z{v`~J&#=STTL@O&PEJ|8^EmUihwF+9f78f)edu>3o7dz= zd*17q>EK*!hhp{SIm;VAYDtZrfO{8pTChRZl547Ur@>HGb=?O+-=lKinb-hq+l+hwc`)Fql${RGWnW~ zTs9JG9J@Tp2KuSOvK#xxrHfi$^dT)|V)Ykh?SeL705GFEl4ROwrE}nK-y={PXaQQF zGR=!$HcN38)6xj<|69t9rs}Ng@Rv5K%E`+SOD*DzKSed{s@Hy^_!Qp(8Zt#zRwJS; zS2>ek$Yv4l2RuQA118>E%411s`Pg%~^Wg9P=!vP1l>|sIOxeLeNb;xKW91USy&*JK zs5gD`VJ26^`GM?#gTl@``&@tz-qSPHpPjP>a1S*Ouo64dT}`UhsEY|(q;&YtswPuG z`$Y|2peVzh$DtM-ABB~QxMM8SJ_C*)hOB5nn6&5t9Ng1iTL}X?b(X78r{L{(uy*(8 z49C~7WW998e9)4q(o4t<9tYo7zmxguP~jL{?`T%@IcpbtYIP^i4N^7f3h$4dEi0GY zZN;tD1jPjL%*%J>ftdlj;3uG#x=6EbWtJHXuIa$g8Q1C6iXWr!aD45rubeFaZ%RBP(Nk4NZc6FV1c=daEJoJ2cK>EWb8;8h1pE7BCe*>)FK&Dd`-^=uK4 zTG%1|O{VngjwVFs?wsIYkLZEdjHQZ!m%87blorVK%J|qS@ELDas^9c^O_p%SSwVJE zNY04q+WcgRQ1AIxO9aTT(ncj;48d1BqDpCn_x%>jJ;lvcK-joJy+cbk1$XYOUY({1 zk)8k`n$v6n>6!Mb^A8UzB2-O}a4jNahQI|8QCW=$|4+Q{`}9+hc_?Mqq;pDnL;gJT z!YV-p*gjSN);K!bzW3$wq5-2p0Lv8JNId znWoBV1wQl8%$~S5In*>oDtfeZD%RZ-sN#GRvANA3x>ho6IqesEqRG9I}4 zvidp~eA|0lJ8t%p85N}k$E7km;;prpwWaqkFK5d$T}xE+=`5ftKB-eozKNga%#^jF z=1tEqXoQ?}@2WQVF+J&_F1K_^(R5M`=^rYeIKj;WyH4=4bNZ>D5TU zc6LTm#f%(K-Shh?adk3PoW86xOnmbbnFg*)ghk&&Hw-yQGizFXC)%B~yi)Hsb@1}B zqpLN`;?OwQtHT7k33uK`{?6+EC|iBMKzZY#cf+yc4S$b^w9?qMUru*FR#FCe%Vs_) zB0@VI4=`Q354BxyS0m376wDJR$w(>*;#8iPS}O46f7@Flnp+U>mdbV;G7)>|NYUtxnRm4;&z-D4_fPVVep{ zP_@u_`SuC0AND|6OmDgSca09MTM4r5;Os%w$l`F(h{Gp*>ofWLgb3eBUTlD|+$HHaNF!REXYSS5oQ|?>gTSv!z;^N=PD< z^nA;ZR%%Wx2?i@e_E$ke0j>jI9ww+ZF#!gG-tlME3G;_4IO(k$1;~!1+QpjtrNUOr zCQ?;0BrTO#@dO_JvLxF>M*&Z}S``{1vyj#3`7b(pZvT01P~*q-U+`9I$G%3y`9MwM zu5Vxb_vTMBT)e{Qpa8baXkXVk)aHFTBeGXim75`m>pmr|DGN8Hd?R|n-8^v`d1dkY zxAlP?2r+92Y0b8pY+cpRr@elKM{7vDNW%B$sN7^#h<3ItUUSn;2p~G1Lnb)$#$#*7 zzmD9o&)mb!(H5NCX1+P(ayAx9SASyduQjFZHevMqV%I+5JH>c_g79)S>G!_mf*7Flby_U7^ee%e0?trP~V)9^QkprLXx&FeJfW?L>36!wcAgTMb3(8u%pZZKBsMkUzuWn8N^$&elR3=b= zV!^Dn_hVOqmrgn?_`W4?WjyfcA|KZK{0p~T1D#wZ6BFD-FQkwE$_|+>Zt>s0*bS&c zc-iQH52efc+biwtf{*#4kzKWG748v`ntS1e0juXLiJaW$9!W#C6tt8nfVd1O;0*DA z!5emF>7d{IbB|*^O523~ZZPR-^#kejqOOJeOaAm5+|yRhok>T>Hq}?3MuG8)hqFZ^ z_6oEY7P~_51RR%Txh^kFTRFm8t`m}!-js+(Snk^94JK&oY~^}TRZ(H1zqZq2l}3Kc zwKaDL_6y`{VnTriqe*uVe&%?Z#T_8rojme%vY@sum9GXDxgPatpLw%EI;@lan^~?2 zn%742Z%sVG=%5t?bnGa3I%Qc2aHqbl!kwQHGLA82iO7CoDOs*Dd6RTc_|u!l_nI@YxxRU}~kV;Uxm^5IXbbkVdOPCET6HmCW6c=^9> zZCF$>U~CD^vkVl3`^)B11-J_|Em7D%g2(UHr+}u!Fnm3ggImBgcAZ2L@aOB{LVZGI zTLh0vn0%kug5N>X7JLA&+1XeEQF2c$J+uD!8>X=M4A)kVs-Zj9n5JexXo8hUuc4N1$B(x%r)BaNO8kyVrS`B)41lGUN| z{cTcmP&;y3u-)<_8ZGgFNL1rB#Os7;lzS!(>iJKc)K<%@AH1N_x-oB;C3S)Blp$Yz_gVX! zkvMJe_fP#)jK$!E9a4W{_lpmMWbwMwRa2)T!PRukma;2QFN=y{@eQr!v8RDa5BUQK z7Z5+2=9lA?y>fmj&=Pi&N}1SfBZ@#2Ds{U%!49Fb62q1}m2Naoc7Z_d%!)Wy$4$c2 z4Z^fwKTDCO2){f5NQ`cA@5!!eBuL*JYqej)e}(*`YTWPr?#5Q%QyDjfq5O3=^5N!9 zhxU9ng7r~YssFcY!Lt}c#s(q97S$yyfrEy*9s%xrSxu#(ijNl@Q%*Vg(CKvd_V)He z3Ex5}@LwUQ{YRH&L;#TZN1Pa*G1-pQn8M?R2AJvTlYm`M>H7!yNj6r6%pKXbUb(xKcpy~yQlD-913n4!%lP(#U zD|36?3+AeOD9TzL+YVTSJ}eC?cK}BG%|=>4m(l9@EqWfGrV+UFRhM%@qkhkse)~z2 zmw}()9o~qNCWW33WnSm4A5|hGWmHmIq8MN^scIVovLeZ~`X2^;YYz{PCVxG-q%!i+ zxhot%xMd%I-_-`sxW{B{SzISmT8SZoOKRfGeOeFp+H}*?Smcq%KoI*- zBA?_rC;!ij=Wz9~#en(H5!s0hyATRD+EopvlrHC5Kdi@{XLYBVE>&AP64kG8@YFm_ z0jCAZ6qdBD6El-}HdiMd%lc7luu+%lDeJb=dB$ACx2|eY2|1Amtj%^yERM4;+*^!8#* z1Al#CT8}<*cY1UYeS7D?X?-nk>yFsMNI{3yCP{hL=kLB?C|RPMe^mctv9~f;k9X6zylm|=eu|l(34l^&hn+gjWJk%cQD=Z z-Zf4x;jH=6La2%SuyCFcC62$Q>q0*5IX?G{-t;Lnm=cu?pg5x)TzNqtQ;&= znX_|TKVS8|T;N{r7@64%D^Mw^TTidDCnQhrZ*c|7vL(}uKl>M~pJPa5l^@y1K1S!( zygD2bE?YIIMUBm5oqGMOf&V^HrP(Fx_wy^JBmX&s)ecdAYFbjBEGY9&6@2i826R?< z#1x7@#qCOX2(da0Hr&Wp#WUaY{Z%Cy7^s-F_eNqLktEq{+H(vxxl`8Cl)@OspPFvB z=1p?A5Ba4Om3@elg(^h~BBdVN8oFk$8iSeT*6M}nbMWvlU%oVKMD-ut>OhasC{_!BIctQ*wvlAO z@vak9g04hgLBF4O&6EC}K#_i;?`tBAzD;{tsjgkw;E@mu&dq3P@FWHMavu-H%b_>! z>dl`NC)sU18EOcM=Ys=Rv&~^4T>>QnL4i*Cq(jCM6^SnI|{b>?u!!r*=PaEDHrZU5bnH2p5euM6?EWFvm}@PC_lam55ZZuf&zl0 z1yP7K6sJ6%5*JZG3Xetl>*XD2IxO*TcWO3O1itI?#HTPhCAGKJG<4Jmc+^GE%EEn; z@p~%yQ+)$?xXoa%(`g~1SnmwtD*an)@o&6>GZK27YqL%hF$(6AISOYVQJFcoi{b_C(2bhm=+g12 zylCjOZ&Yo+&+pOQLA4IU(P`0!ng%S~Z%SM%rpG*WElDluOnZ;?6gi5s)7P@-MH&>~ zN+*DT4Cf}PYdqpC&d@AAO%K#>^4`0biRZ;i8DgY5M#0k5lO~yYckn)~>`^w~- z+@Fo+b&d1bm-XuZ5oiT)0zAF5_nz-o?1=u9;ZXVk-o)Mi4E^T_7{fQuZ7$bfN)g6>)SF+imNjaVtVy=h zE1`5cU_aJ375+Gp968KZq0QNXe~40H0X+wv@j!g4GXOH3+FyA@)2sd-Z@9YxXqqAd z^Q`*g%;Z(s=RG8q%>~V1H-w0Z312s$f-Bk#x5ow_T8bJzOjU=F?xd zj;ZHb3~HWdz261aNrIX*uAaoyJ)Is-G!N0*ST0NPT*I>pT?64^NLX1Km4@f$csFN# z{{2}B%uChpmbY8<9)EuK;5yona2q>NqhtPD6SOR zMIQt7q2lAasWY4ev8ci9-iSaSVVQkS=7c1j5p>S}xrZ;)F}S35&3Z(jLnvM{x4N@# z!1=In-8C~a6Xf;!bLLnGUk58V1eCz6>oDHb{x&#t&_#E1Hf8cztbzq4<1;k zyv-+>$(8Q3S`Kq_x3wfeudFdY=YW1RH&*iPwx>u% z;Lbzxvw zBJ0NR!LjvfV9U*-CORgjozq;3b%Yg*o-Q|?7uWBA;8Ik>*lwh;f%8uQW6Sj*tyP7c z=1PT{yBc`siwMBrA-d^nx=0&4Lhf*Djx;nd<(SrguN8oQfqr`89tB?OnBfS2lzKoT z2;}ylFAm+SR9F>ZY1^U|Z_ zs!f3CfUw2H)@2f;^^}uPv$LG0bfbW@LRiH8Fa|-jy;!jS;V%0tmpL(;s`o~qX5Pp5jgasaFTnC|s z<_>YWpeY014NIBeW;NII`$V)05~xPWVSp#?;Xuflx;-!OigeIk0(o>yD>(CuA-(5U zj8xlHFRG=LLnY3&>=wZ(M0icacEGUCwUgkpFR&=T#JAp+Spjuyl=n*EdTy%N$DGfI z4vs@&r7LReAE2C^sZp-3>8?e9_!KjZh_P~+8>HR!S2@o@dK(C_Zy+glPd zzxKCqaOYXUltsZdkJ4L%;26itb({*`u zK^v*(v!KP9mfo&cNW&Q*Fum(N*{uFDv1=cbP)-L6*t|MkRcO(ojVLs)x@6qoU3-EW zPA>^o?m+QI5>MNU>SAHhOX^)>hW9X~>e@&9^2^tyPv+dYzdTsaxK%4pETHyObL5+> z;5+N!Qg(Al}CS(C2k+CIz6@fVSw(>m7rr1 ze=5Lai@(~7-L++}VkuYu(Bot;lrP*v$MkUvbdGZO2m9QHs2~<52K7#}kJAyoihLnw zBYGv14w#O`$<>XFTTiaNQ?Y=BJ84FzC~xIZX`7o08r^NKqH2q8&m{54{ASwR9iy`p z)<|k5A8q%3i{8mt)4Sz?KKj$Q!+G3M7+HBgtaHSAxe%-b>*Dkk~fY;khW}9 z4nI@M@4QFju`aV=!~x0TdwPKWRj9;GyG-%0TE1(1g8~AJVSd(m&dJyJ*VTEUCD#tz znIpb5?Cf}DCzAzt5<4SHRt?TNj=>1|+)!ofc;DaePQ{>2`so~!QcqIZkCa3ZVxfxS z6{O`Lt^B9=Lfz?&bg2&3S4vxoulr8t0*+l8F+ffh?O6S1f1)V|0=b&d52LvH=k^ty|Z z8iWr-+sA55%kc^(o?+TGplS~X;uV>6h{Vv8?* zf*Q-4pOuv?X1bj2CvhHr0fu;xZ!b({H(?$r82>x!U~Il8gmF~*p~S#Kku@pzNT&q} z1kPW!{s}6bb7!>1U)Cewstd1w1R2hbwJ1omO4nPhj5lY(JZt&LH*p!A4sU7?(UDq0 z%^e5ag(*@2duQ-E#mTDg;%ZcV#()zeS;w0t>c@f=qT(pM zb=8;mSft)ig)_iu)}eFvH}RAUtg(x(?U6P9dKHVou7#QU=AWxh_QX>!^F7wy>+l*r zZ(7|gOky)0^UBDHBJc6?E zc(nRi%$M1p9p~~H>5(@QCmub#gd^T+p+U}vWr*DIrWEBc-G!{t&?6zCyjS`rEpZuT ztE%fq+|_AQ?nN#at#D83y_^fMGqlv7EUsJ>{-kg~x_(kenu*w6*W}(K>&?V| zHo>1*_`h<0wJsq0v^Tfm4Q)z1wPSw1@jhHbjuD;_(UFTe&Ytu%xudlgaPZBo+R^ z4R2kYgN?bOJy)*_lG{S=Ctqxy)Ckj*wKYK8L`~Z2=(LPha69>aDbJ(li^urLs5Uq4 zANv+6r}9Y0Jl*DXbtWZqI!}h76>^b{v-H=IFU4u@$~<6HYi029lZ2bxBXKj-DaZ32 zdSqC68s9j&+FH}Pv^{-50y5oO#I@fhg+8eRLh4u~=z9B>{@mRz8Lpj2Gv#*-8C{LS zEHh|)Wt4t^<)D76@bdZ6$C&9u{$t_s7Hk>j5btyl5SUcNe4@T&I9p!%&F=;T68-+$ zw{LhyOUl?t7v8TnZ*LM39reIVaA07j>e2O*#dO1xsnt)X z)BxqRvBiRhx+-9t{D?zCU-7G)`G~@rY445NbTk`#*}9|n>p?g8?PHkIX&}27A8Pf> zQO)`?jlYIHRPg@t2M^^LYp~Ca8UC6tBr^17_t`l}C#Rs4)bByg^&h?tRXB85(RmWV z&r)@X+9q40^_n~#re_Ig{zV77TgEuK$+TMH--mU6vUO5Dov(=|po1ZLn83=z%G z$?A~rZq6H?4>97`RSO30O%bL4^ ze!4EsQ|kKUx)`zf2T6lcSvmBiWcq6OVYc6Jhq{W+<6_}15X|Z~5?G#do!ngeke+^s zGG(~vbsas%;yvH?36WQQAn|&TkN&OzgS6FD@Q_cB)A#Cb8@L~}IFrn>xB#L6W}_06<{HlMXsbwRvJX`$Ouq zpby3JGu(3bp`q8@;rU6%*IiA#`fPc4wqyP2p;J*0JosHC!}feIS>0jgoAph{3B+eK0~#GC8-sh6(mjti?vO**8V1ki$C#Y zkzjq1vfbFO+~(cHwI*guet3h-ozar=Ub+5^y0EM>#yWf#gxcfer+so zr2r(sg>82fafgNpCF$qb3Vhazda(2~(bqhwEvKm*-fI$R z6Ay(VSuXENolk#A79?uUc=3pX5iK=$n{DxJ5t4nfDT@njOG@mk;GEH&C-Z8uyw4$l zXK#RhYh(2Ic+y+*58SU|jzH)0 zBXt31)gc_KQu9;ybsZGL`ohZs0zvRbL`H^;ej*oHt6F}7-!Y(PW+vZ6S5$^97t+ql zQgJeYgl@+>YK&+>6+Q~-mlA|DPJ}>vimK%k?hsPBfV#OCXInu;qizVuY<|hpX!e3tG+dt#K)ys^miO z6Pz96n~}g}`$@n*XUj5ajJxYV{TQd&=X?LYdY<5{TLz>`cEngBLx;OCJ{3!E2_Ekw9}o8iLT7LcP)gTD!NN`dDvATQ^ZU8=z7YQXsI#By4ih6&Q4<^-^XK0=tV(zjL_hc%T6hWOs`@yGA&OZZcIlQz{9%2f3^RruZ;_u(v^kxs738geeoCuX0 zb!2>#!{7WTCD%`;l<>Z|^>tuxL+y)Oe$q#~leUj79nw-V?~wiMq1oUm zp^965skv9f5qp$nQq07d;fBtgu2jZLM;{#!3NcB2h!bTmy!dTi%9+#p#TRA@SQV|U z>A8JKC#*#6s9HHF8hk8VdU*X0!i#pallJ-^x^s94(}`$|AjbCd zuUVek{z$OSmp~HIEn6QR7_ju@HkV|LEKa1&eV9R{;08T>%-INpxSbv`e9JW74ttDo zl3n~!ddgYEmM{BAgy!Ln^0`Wf=vtC&frleAdK4$?{n%?@2X2fT_5+)7Sut#h8a+;ZFqzsKSm79}c$kshmey%u@U zI%MDa&pQ^5 zQ~voK1Q9~%h)2AVQqPuA#03V(ceE7gfacJsXq~Yvus^P89I@o^yr7bi@^3B z6}rm8gi$f~d=_4a2+2|+=8MM>#XwmflgE%sS^mZbQ%#RWEDISV?J9C!G#fplW%k}O zd27KtHElc8os?i67ygRZXcs-d)UJl zZdBx?n?%4F5h8kICxvgy-dAlll^~p^{IVo>5Rdv5O4G{wu21@I4gLw?w?CKK=HKu? z9Qh@insY}^L@pmUUBwmT%0;pRh&` z5)>0_SeEvhMF;Ckkh1B#LtMNiv-qJ=Rc77nr?+d@p%@ z&h77+`sJ6^v)tiy)P$n-m4QD9VT4$sP+Ibb3Nm3Hr9pQ-Vl^y6f7K~q*%Ux!Um#MhU zH=CM97Vc;DVc&nI>^Q$_+Fa{y3+G{3Q<55vBx!)~lN%xo;B;9Gl;#wIf_PE=5obP{ zCWV=4Eo8f5*5FT&&_Kbl0W0DABPS=wL>>l_+gM6zMXZr=L+~pWZiom{`RNrsY?H36 zWw7oA-&k#V%0Dtr9IMY$nTJEZak$QJsLQaX={CS|%BWn8(6 zMpL1r!|%hZ3vJ{g4E}x9${nvVQlBE|(giRq>x>bt_kIziB?{26R604n2dIJL(jK6m z$!bB~+^j|x4J^?ww`#L>TimlW?*_cbuq5dy(J3^wgr0&JfrP#x1~$G<#>SZ9Xa*eE zH29a*K<_FG23w?js85LXXXk28mltLgMoxo}Q7_LZwiuujFSB_0_?g;v49<;46H?IH zu#$?*yAOulFWdi7c>5`a2*UJ$2mNJ!Obok?B+?0O=ZQt|a051DP5Q^}b>M2;P_!J* zBc_HUE-zRhX=~p3{o51ol`eXexlDJd-l)m?$aS6RWj(8_Lu;6~y!xkB>^H!zSAGG` z?V@E|nY2E9(@RaBva#T;NipAs!#D6XAf18E&)Z~w42ef4FKg+h4{+OwEawud9X^#J=C z;@(UD2#|PNx#cnerQl>yPnu61?;2rN2i5TjPkJrQbnyXN zZt+sgsz-kHN16pJJm6e`!+~&;R^3l8tTijjZmn{ILJRv%>|c z0Q_^jbK*xMGP#9T)RD^sz=7({XeucHuOO)|YSa*D5b*S5OuLh%M z7g04A`Q5LnhGSAxUmHJE%0&0wG|Ib?VCpE~Z=KS}TNe_yh9=N>r_V&kp44>MQL#Hj z79j8;4fGE8RO@)&@COfXRbNFT`@>y(RCnj_)ll7oJlEFT+Wq{ywXqUO-^ttnBJ%LGn=fX z-iPi_6VKe0>b#_nYz5Eitso)*2W}K&JhD3E_k&t*E}5w=Q>%K(acj_OhCX8x1g2I# z0cDkFs?|X9WgOVPPIZD#SWOJ0wOu*}Vjj@`L4$Y;muqfCG7m=1OvzjD+vrY%T^)lD z4V6~J_vc#=rZBC6bvIp^b#6>hV>XTfcem>UsX7a2Z|74H>Wr~-ej5mQ|J1TO5JKY; zi|Ij|NcV}VVx%_P$YOb6O)^=~)op#1tk>gtD~jmOQq97f1MkUF=T8LnQ=1lKeUsXW zXzYQZp>zb;N~TSlK|cx#36O_2atNOLMUmpqH*PC=(U6D$2I?gFDH4M%qlfsm5B2*6 z{Q+Hk(!<=e&UHF=29OJUxz|&KgYNLTCWw}!XgL#NUsygXXCZ=!(18lM7cVN(FFEZg z9CehAM8PFV3@?D|zh#8nc$(Sp--$$dA1BAdpYF_$BeuA%1>70IF! zhzxWkcb9LwzKa*fxpT)(wi_TWP(LU#-u;v-(V(&?&Kab1WAY9lA(d8f3Iu$x03DX> zLR*bu-y zG=5Zl(cN51pU7GI?a9lJ7x(NBm=70=-VV@WSx?)(W@Y4~$1|JYOI*($u^RM&*Qvaf za+@nuh8uI=VxVFr6j5I-o?l%1c+W41d1$MkbmzB+3eWkh4zXrK?n464xv#cMX<8KW zIs22dm1Z#wW&iZ+v)C$PaFccidjsB_BHopuAwcSvPYsTCU&-P;`JS-1e(S{A zOvCg!vz&(!YmvM`?w(6R2(;fxAIsV%Njr1%^DPhp)>ayPq*Z1v(XjPjz5Zz)i>#j8 z>>pFUZ@qf;v9;SV-NvSDEPDP#NJP3q_h+Z4q#3vjkxm%7?ITbjn%G)M&^a>DVa+K{ zz9#EOXyYDnji<~3^H~{?apwM9SNcOXvf$DP^38ebJ9tnMy?%1s@nt19(T(aJ?1EO4 zY~0pP=k8F*)1eu`=!6C;atr=z@ayZwIVASw9uE?kJ>l4C1@T{Va^Gf=uDYNg<4oDA zwX|ziyON4_Jb0KG?5@(g^P4nk^6ceR-8X4sibenjk3J&Kehu?={e3%Zp?v)AqRDQ{IC;b!4fJ3bo z0?(zhKxnc$Dyk%+|k0qmiH8}E8+|5r0Jr*#xOKKtI0J<1M zdDv>wV;eJt!=}8K%uX}ltT?Hc43}QJ?-D)8b#WY1Dn~H@Ipl&I#jG1-C7PZb{*JpL zxNo5&;t8)2lk$-(=Mkw^Dqx$vskoo>t~S)+C#t6#_mcq-E^uy|@fI#WvbL48+<0N! zT&Z7wXN8OphPbIj9L`{%TQKQ^FBw;f73ybL#=K}^s+`F47O1MqA^v@Hb1d!P+X1Ke z_c+X5D8|9BNsx9m#fV!cK1Op%dK3|wpVbtdnFUNf254LMxi!c}__Fd!Y==P704FNoqjFGtS&cwP+`c1|#YcO7 zGLIyx$3p9olG$z>>_VK9%?-ylkm8*$1deUwpQvz>x)+_Ik9U$keT=1&E@6}IAUj1{bXbCiHU zK2yLDra;7f#>`JYYMrYp9&9MDA$Hqw<&Bia5_@5r_r>Z9j7;}Zlr$j(AE@@BK%*0Tq;@4w67-Vi;;1QKk>ReSpbFM`M>!-RhX48P z(U{1{LVW7G?_DgZR$mgsMrA3R$62)Q&db^!6`RqPSf!q>1%_C`Wm|9%_ywVkAeteM zVe9hcMDEFkp-Cn0(;7lsZJ!)23VyO=n<+S{xBQiwmvkcbz9gfC<)t+lXQ-T3u(sFtesBmbtYkhO4}=! z5lrRETbVTm&aMrzYMmAl%rxY-KP+n_4#!i*0PM3FD&=>40ti5 zeB`!SXi5d_7qN27!wZPp#pCvY(hr+_I6MM~#`Su{P9r#h7ib~0du#38WPhEswDtRB}9DTBzMOo1?%W8&XN&A`CV7^a^ix1|HP7ieMOAM{PZbSaL` z1tr=Oy?g>>PIp}pu~G6XR37GZZAAF{;wwY%{g_5^>$!J==*;vxheO!xFEvkSz;DaC zCXnrYMv8)E6gm6>gE!Fbxi*`O9-_x(`6DZyT+D61d1cGld;X8BUd8-m6^a_fynz>& zEOyvtzsfz624t8xnyw&$b}6p`$cXQ2tFvOIu2-axU7|{RfwH^pj&*6(A_LM+{zY7CuDkh`y?Mw}Kcs~8r@XTeIdT%9RfB%? zzp?)-jE5IJ+(e~^USes`0tMPwx9{UN z>zmgSQ4fSj8uL|H8*`NLx30)na9_{p;pTxkyZ{<3G@*i+GV^YZYfnz@RY#Y6wbhRn zBrD2;?}(c}+2jqpJWHHsQWm)#MB4N9VvWi;LDD~@H>=-_m8P=QMofs5U(v;HwKL+P~-A_0NokWAZ{M@QnWJmPWC{&(r zzX)-XjAt?^aNIF_?en|L&lHb(@PbMn452DHWd#E1JzF{O+aRyxN%~7gk5R*ocYhMD z$>N>8@Upsp`LU?p0HS*hZT|3SA+Dq7Z69kFZjd3XC)xwBH)Y(ReWJ{vhAp)F<(Wnc z+}wF;W;Yb55i^j#dEf^T=z{iHW7Yc}MVDQ?74%~9CofQS|2V87zt5f~y&`tkq%cGf zP=V&2B$?e!rmx-4Z% zWNku5l}^E~I3unb`&tR>;TeKeD&iO}`lc_*yhb|FJu=X{G+RJ0o?_^NfwB>7N#PQr{qe zY|NkcaaTF4h~s*=hkB8dQ?ltD!S=T7+lfRHl7mQsJP~>X`5SDHHcN)dk<5i{nVDik*u7jUTBjdC>Yt$uB|G(%MfiE**`VGr0d0m)00L z*f%swB!Yy(&;31PSNp72XJ<&8@TU473Gc2A1l89vWzzhY%dC+f8B(zJ139E=tI4iL z-3sn*TnW>3Ff)(Kpi?nMW0LRssR05f2CWvuTt0_{6c^><0_BZE-~Q0QK@lCFESDuw zqi-uV6_6GHm}|%Vr%k%}d_-#*D^Hv$-0&D<0j(AHiv3-tg6H|?$X%ywAO-*~gzR5% zkjJ?Q^ikNx2i`-ZJOtkvbSM5Wt#k$OFrZ)x)~=2i)BF2CJywUgeds&pEivz1iEcat zl9EqG5u0#d|L#jiuQYtNx3@9a%bmSpdV9HGe_zBK@?hQG0VvUS+L_8h$I9~N*rGd)qq5v8I3tgN zc}hZ0b>rU?4WSoCxVnC(c&sam=rBu?sGraHzw?y(?ikmz-|L3tCQjn!98zTj0^QAl|nvI-u}$hMpR?)?k?vM@r2JKQPd+g zuZk1eS|ya!9|X<-y$wSC{T-%&3Pw7I&nCs3>Kku-o%-K%R#OW|*~&A)@}ibF#n&@) z+i#aLT*3+NScLuN=TY6*R}RU`%3O@+PaLKK(-zbe^ot;`cFLH~ z6W5kq0-dAJ^KPi-UqT+~Wfkryj%<)Rum*Cj^~w@uW!PWSDFi>xx%(T7dK5<|*Yr#c zn&9J+g%_TS^zQKIY>OZ}x+4f4hwC!|B@aQr{MYhV{0P^lgwy6JOABnceur$Q-j4Xc zjC{@`G8Ib&os6ZYWzAfZlfI^iC9i)w*B(lp)nuoivIP|G$vrze-TBo5d;=J3opmO) z5ZDCl8;S`LUCkF9d%7v!k`{HK4b1;2A3htHDLtwDbl19?KjE}k@J*_d2KNXML58<@ zU0DD}r9)}exxLp7v0B%4c`^Q;4~o0kvwhfG$r~#5#qzGh=r5f0RtL=++*a0Rde3*y zj-{pWN)iePWSfYjh73UcnT0o%d)CluIlrul=8(k{z&iT_P_admv9J)mQ*aF7OyJ?J zm=fw2&a~E$U4Sp|#r_}$!_zdMY08`}pOHex*+fuwk8AIOn)yS)n5!sjXn$4+Nsy$> z0^u%bHQ*tFx!2<>OGNrx=uWw{`Sb^h|;*j`S8_WI-dzbu~Zohag^e;V15 z4(IsedFPSK|0b1a9w9S7nl_$}N6Wl5Zl8xmM{*y#6^#%|qU|-V2WLO}Ev71}jHxm-EWJvP^QsAh zaGg)513XjDTk~i$6;NBl^Q6#KvXWqbFpNj2{d4i?Vt7 zT-nC|X@#*9AB3Kg2-5Xi!HZpM#Dek`{UMyB8x-qyO}e6^Cf}XC2MLMc;+*wjpSAmM zX05&YOrAJFFawyXOskcd@#x^#^dgudfP}IUJPs1>w*`v%KkTs8Avo#v;?Q;lb3z!|?nOAC6{3D`Pzu!+z`HHD#O8RcC zapOp`$hE?%J$V4USPt6VRD>@W+9h@LZ>0enCWmjBVkvS~1ZC-L7>_Q{Vej;aExtTI zVW~uJ&2UU%JN6os+6e9cK4Cu_y|Dt{qSh+v+I+6yG`&lqZ!Afkofj8G!PDI!lM4vfsL z8|(e?XUK1GR6im?`DbVQ@N`F2^&O4e?Z;X{|P%ouxN=>}P*Hg;x^=v+C6h-Ah9OkD-e>#k-i zh?IRUChog87@_&L*8yvX5T`sk=1YC_H;y1b2>oj|gWTm$CZdQutiG|G-_!pAmZ7}7 z_7?M?sa2gs=5SuOA{TP@Hs%7v;R9nk8yPV3(Zcp#%Q-O!xKLKRFGm18 z$X8OJXvzMvfRW0D9;O9dkuqV)-|F-u|wg`8RnAWp=z+zb5}T<6mS9&tByQ#Zb7xwj2!;v2<3C z6X%EHU;E&lC?KIlffDq;i2DFIT@sm(&}sxv!dCzN!twCEo{ug8|HniH3;)bcaweFI z_TRH7`YyN3b~$L_9l2}id9T-&T2!$KI*9H9{Y}Yd{M2hb#7@2toz5Kt=aD>#K~SJz z$mzBo0X^?Ov!W7={cVH_Ku8}S1w=?FvyMD2*TE*o7U-@>E@{%BMVG+s38PWio~Ddc z&QoHp|3_a$SO@5! zM`r7v3_-(6{opcV3u`w2(kn5FL{mkIbv`ZgGKaB{7-e&&e=uKTV$Qh`G^7YMJ&N4s zDtp_s_LJG(gh&^?={(R?|eLt?kvh zVG1A21qw@99s2$~7tpc%qil#I*ck)t4JGpua8O8m_gusXs}IElT%Oz#lAN>H+V8Sh z?_G$RI90d#Q_TvkV_N;F=KN4``iaAqRdY*!3;GA!iS3b|fgl3g8A#_xD1VUt!IDrN zkcWahR}&s>M>>Svr{fkAEekfe>wm2 zv@JL2va&qY=nmRTGvbDw?x5QNxvjk+dswZAC(N|T|DUkYR<;d z5c>qRQQLpi>Yl6NCbfvp7gz~A9BnhuWD82}g~ZO`)?aU?1}7b$d3LoVMqFee)M{Rg zZ{#WSrCOK&)c1p!L6)}JrA`82;Qdn5IV1u1;i$@_`+A2k8U%q95R%%zN;ZvuqE`8_hchwlj`?UY0+HeyWyC_w z=zxkrM8rP6yFvWx5@@jlY~cnzBWn>4ZE=B(Lw@qvR=WJp>2S*Ni>36kqsd-0zseH& z`ANC>j!Flag5Q-9>xfNW!KJbkZ8p;{qjoN+R?BzU7q}3*gf&KYv}71J`ywJyqfkFf zt}q8qbLFq{dqKM3Q?!TcC2RLwKj@Af@h?J~|6d!ZKu`Cpww^=i#;+S9CuRK4K+ycB z!kIA-#Ln5?iT}-5ka9=gWK&7G;O+MwuD9PTW|@O0?zP2*yBWN zEHw|T>xr101Cz(Vjwyb?Bq1n6wdq+|(rR*`KFE~T=!@(H3_rr;VILTeWS;^Ihy`pOkvZOTg-Ri%XgL{^LHYMCS9t1gAnb1x;hCy+pYX` zv?v0x9d)FQe>12$=@RtElC4+w3)x5)Q88jo++>+DIrm(&^qy| zXA*>si~q5}BDd~($pqrPx;tr_L0PWru+I=Kcl~S+YmYjE^{wm>d8%F9Yi_2q;YO^CGkdgnt0TO`pgSs*Z-$5b%Ev|7i zHlj+xo3OOU9!DTlguapiA6R2~^I+IQ!_|GDlxrQEd}EAl4ZZs{Se|XD6K=^Iiu%*^_ zOz)dH#j>(U37~HRkBuuZa_%)Mm1G&lM)<%0=LY^-2?n4EGHc_T)K$TFW_juiy}ySu z9dXM~ZR!wk+CPY*h&{DSvMg)Tq_fQO8#od>>T1xs8}RyS__;(iO6zi0EcKR%|K75V zC|l^horMI@%!Q^;g!>ooGH6TpDEPZiiH$=2#9ovAVZhLAT2o}0!o*3H&W7F0s})U4Ff0)T{6Io z0|MV3&b{Bg_s`=GJ^S5z#j~FEtcAwKLiUSYJ(|EKQgL7=|9zaztcU)vMqE|ENJcB+JVSBQ_wZFUk(vw;X1JA%xSrdGq=%7sNW^c6tf8_N zyv&w=EPUJ@+Fa~R_p|>dzxQOx=+?>Dm39)dFVE%jSb3=2)HN*6C5sL>GTPjjG*rHr zg`^wg?-e@#N=i{P%?P#q+lu0UPUXebt3dMH-vDL_q!9COpTN?Ao($+;x~YRwNX{zb z#?}^Es%UL7$EBUmfBkqYpYcl}`QF*7GaL9=pC$?jvZhj1lt_N>)kIIVaPJ zSHJ$OpW=@tLy*5*9$9`u39kh-eM?tO8?UjwrcH|_(vV^)4;*v0hQD#zpe{Okd}l%u zOaRug0O7cqc;dH~9h&J#H9R=l5V)<_H2;t8Ns>E$G$}-$U^ zi3;h*KQ?u|!SRM4u{|`NVi2D%-qbZd7;E?SulLUctc)vlcIt3nDJpc zQ*S-fR;?vL=bCl~{4x5r&0a#o;fUlW&xU`MsDRsR5ET`CQr$_S<26%T`Liu3X)dR8 z{y$6`Tjh(r*SA-bV~?xDpN8qiJ^!a%;@A!wX1wjK-wgUAeBwO781X$lvoPS)d#v1( z8}!7!Y_gi~v8{nZEnnU^UMLw1AX_L01Rk(#F#UbBC&gc!bPA5amSVf{R`4kX=$rIG za3r_mOR~S_Uj*yUm;2o2wGS$ZKV|@#^50p*@<^kaA{Od|7Y^Ej=~W<2n)PI;{u6|) zHx9Q}tZaSOM$H?&B$JjO$v)WMrUc`1OfAk`S07p)04}-V^ourRq#&UC?KK|~X;K15 zZgaiaAlGd_3N@2GHR>Z(xfIKb1c~dN*r6F0}tl<8FA_%S{ELoM$Gq_?6ik}tDy5KcIe-QAStEu=@GOF&^h0-q)YMEH6z2VttJ6proAy}d0 zKZy#dSv-=7S43+9e+Z?*(rLg*?3^}%S$sD3maMchN&bmM>F6~&^avvx#pfqk6H}6n zb&MfpK+8T*^{j@oDaNBDDD1!_?pxF3h%*5kRFD4^o%-IF_I`e`48%IFS+`f%q|+S4ciM?oGw^*aXga|F^U zBPRnG!q9`ecYqRf>=(K~=BY*w(x+!cZ2IwG6Ft~Ckx`_ZAefxPV9&R@4GA1GCGGi6 z?qbY$`_+twUvc*G^g4he1=$p^w^zq7?oSD!)Bn75OF8MlHMF zVHNB1=?5dhs>X4P+VS*!i(cizg4yrcT;Iy1S2^uA*r2@TG%!Ck(@G$o*1k2QQ>NqN z$#1deobMmfUYYc*#oHN3K0#JZV1DUVHy9-IO`gl+<-)9?&9!tRqIl4U`mY413Z_j9 z<~|a+t_x$SAwwUMm4T*y4|z@?LOXN~|B&Qk_TrdVIUSt^KE*$9q3E)-jg}LQn!wII zcft0n3*m}1C6v$eGojxopej@1IqA>{4ry`%M|`kc7M6@lQ77@tY$}>O3izeSd3zt) zcXtpZ@@j#$5V#b@I1R?)M6PYgajcJsQ!wR!@W}mlG^Cta6nTE_9XS^Z6T_lHGCkx9 zc=ZxNzchYY(k-Q(({qM>9G+@f6mD3P^WJc6$sSi zs!YYs3r?Bv>O3<_Fck{M$&I&|Pd*C;t=;EoRMQxmhm+C_X~FB_KA?ns+U4}YD3%sE zz1rpX6Z|_Y?REMd)f;c@Yr)c7H6tazCvUAD#3=&T1JIh_!N|)Wmz`+m6t1P0@~2wo z`XXWz2C4_kPCFySD=JHBA|d9-wk1`}$Z>xeova)9D(ne?AiLBc@6D6)KrIPTgaDRx zGD8#wGc{*5<=_FiBqc#l(lRElN2xv)Tl;5 zD=WL!es`@Vw+ETxn<=@fi;p5r1n|&Ynw^~eRa?KNxp#2r#afjVDLr*3``8zjI_I;i z7M9Q^PWx?&xivDV6ES{lBt-a*h?1D~k#o`hNK$xi>x&nf)}CM#ppC$i){5YN;sY_h zK71sw`qy!leE9i=nXqg&e%lLU6fc+{A&61kkk*Y;2@Xe5$RYi&m)JTKO|bYYaSjLw zm_78gcwee05|H=W)TwVto3?v1$)*Z+bd{FC(xM)m*LIcU=u9Zhbf?u-TT?KW!E%aw z=Q;k$#%?)~C2c7k{uWGW{iOBc^b3~ge-U2L?{1(x8rrnpT34n!Sx`^87VdT>c1Md- zCaqM_865x3?}wHJpbJyCAEC!Xm+94Sy`Ul0>UJtzQ*$MPn5En}5o-~9k|AJ2+NKQs zUKJ2s^4?6D@XZ=;)?Z4hn4E({s-d*V+7lc8aWB+YnxHOH^{QuIpC6|iT}w=NdQ1$M z{{O1gV%(&N?jP?9Zn{2ek*HExl4i$)3Rcsh`LjVH{9#)E0u;y$ zU|%$~ja_?tJ-hrx$2+(fhi;kdY-`T+SUQSKehY-FDef(f;U%1ZfJ1wfJ}= zRX5B98R(vnNR}}HvmSV}hth%hX!w`k@fyAP>N3Ip8vzFyj}NT#eabK)f9F${Gs;M% zPIJ+_f|B)a?WO>5=8kPGQPq@aNaH*2>JQhe!SKZ9s581Ee^i59kla0yHqv2H#ihOU zE@p(gDHML4`Ln_w4+sk*{K_!LJM^`w?mpUEGvvxl08CpyZ~zg`YoNOUenej7cI!>a z{}d>9`am)~;-Wq=S{p49u6ceiKlk#J{rMgnxKVQ?$JkA6ZnhixqF z7DXsfXJ@dOxzWB9TT-Pf^3^+^uGPKxG*M?|D@{irlcfWGr{+T2&ZyV}856+`n6I<}ybN{tM-jXuCO@9yC!@;As zQ+W@HKOU{8s1;U@lpe$y0?G6DN6cH}9vpdTx6f~d4QMg(e0%dD6wB(Lz_Vn2yrmc^ ziOO#DCVq0vH}3h*yl2AQ@^XW#W1%;MXl9yjbmBKGfZX;9ze^?hXw>YUVb8WwfhNht zT0SNiOdl}D{xh2F|7kqp!;?|8#HPRX-jb6a{I017N76~ZPWn()4Ur=gP<#(XxX@Yd zRqqvg4GFpRY`5&bCK&zT#YYrtq9M6#aE+`42*mxB@%UXKj#@@InK>6XvR^Vf(jRAU zoui1>q*#_$+602GtYFzK`5P=V48+wy%?1vKC&_|-oA34HpUcFid?;TSB@ZV#D{dmG z1%S^)njJsJN^ocU=Lq`QQ6%n8TPf6hF@Y@@&aT_8Z%P+-bnLnKX4vvs!pMqF#vF}X zku`ersm~I_3`p;uYHz?~@QV^i_mi`?xMMOOc={HFRe^|1uGSN zYQE<$(e|R!8NIYqawMC-f(IEHl|ZTSAA%9xi%%1F*`7B`DW3RCwK=*=hkwJ~CQ>S# zcR`Tge{R+W7m>>q=>#V|Zn;CB_+QrdArKHm3&HG9Y<06Lpc|Ic zY?IF2oU`3gPcwmI6Z8ugygm@e`^J{R-=cE!CQnVfHcz|%ieImtO3n`CW$tQm56w_8 z)1^(8b-H+vn6^&@l6`5Ih5Cur0hW)9*0dmzAnw} zeTB%4DBFwcxNGsqq%8v1aM$18Cj@bX)WLq&0Fyueb4+60sSkiEFU?}I-?414COuvm z`V!BWB!jo!7=8RMFWY-KLD_B!QJL`odp?jhn6?$X!PM)~*_lvyTv6)p^l0INNP(5y zYSM6}6=iKwjFz!{pG?b@;7JKSV|d;`d+?RL{v#lCkDI7meRS~-9-G&$C|bsYIF;l~ zG{5QvYDFJD$#Npic_g;Pu_qivL)yqGQ1HuSM8=n#D~oC6-kA}Y_0xJ#;wT_gP(@f0 zZB<9P8!5Tmn3;|167rUBb9~d4&S;~!DRZ(fBl)umJ?m4jpN;#ayp9(un-Hko{x7S2 z;K5Eda$83}Q@**otqQg<1q9PeMTqZ%JN+m?ff2mfIY1thY?VDI)+ZaS$?|zia$KXe zv9L{YK3Y$+629n^Wqbd}S$f1DJ`zbMH`b1yfUQ*P)OE)xgEsYh0PNpBFF109^n8}w zlay6y&gL`HVWOc)frgU4LHwt=@NkOurBl*oY01TiV39Q4$t1)==o?2gle^&TrC4no-^_{zG}fN@HSR>agV%nx6ze zjGYj~Y!M(At@-WHLnvvJUK%f?BYTx(k-qoHvd=9AhUKSE`TJl=j19fph+haZ`z0Z0 z4GecKmQRbl465{bqkNL^b$Git`44sgW&Uj$vxTxx*MXKWm3`AogxL#>7SHRPB_0}Ih6l$DV|tz|J^)hM)hqez-VA9oqOzGWf!XK(;d(g~a$Hfm5V zj@51WU=_OFcf;`>XdAH)gmV>A3sY#OM?wo_L;xp7t@Mhyh9bF%{1{g?)X~!CaAU*w z(b9K?OZB`uQ(#xRn39oq(qbZBatdSLBA;;7)1hBqGTd|8v!kUtpIRHyKYYeV{J)8u)AO1VBr8W>db5 z4@&_U zE#ApzU&K=&_3lVhQ$jMuPrlM_ui6W>a6L#e2uus&aSIfeM|>vyOjdnAV@W8MU!1;W zC*}`9Ab$r8?PW)ypB+eiT5oMiXhTg9tzt>TkK)@Sl&O3?PoNSN`Ob|8z@p$fpb2fG(D@R<{8}E#) z_lnj4S9=N8MLxUKdTb}XD(TqT^EG?lOWhGYRO0o2lX!}(GJc<+q2ZG7Kca5Hi$ z3cmcj=Dia!sUt(zjy&>>_7+9)CZ&$@-`LJ1S$37(snaP4-THr$P?nW&XwRitoqNv@*9_DJnS+C3(z7Or(sS{srp?wz(1UcY{^G%ib+Q}{PKf??sOdMigs;4tR>3A~LSHp(o?httH?A{%{rARn9Zf$QZn*4`aO?{Ir;%{7f zCVLYE*Oo<#=>Ivw=KCA`!V3||XFj7Uiz4#bLSlG8cuuvlZsn@J&LGUVOLs`xuF*gL zx>p5v?{?qRT)1Q0%7@d04;?z9XT%r`W<<^4dU=tEQC&;fd{)A$uO?g=%NltWm7c{6 z;Y2yK6?P$!$oOU`GvD_2RoZ>Tc;hxdW=UB|eX!Sf!ww40MbJ-0H)MBvlJ;QJu~8dC~( zYW@5iHZUViIfx3?E;61EjvMpmLHyy%nJ%pgz|-SnqP~S zlA>qt3mf&%BLgHLLT0&Nf$`ljuoKLqJp!`lt@S2ch`#0h2U!A*jgH^o0S*BpnI@ig zU>&j2F4XQZ<5a`L_7U%t5lbj++>mKz6ymN8h`yU>*?>aSMjlT9%tBlWWOy)82%RgjtAaB2Uc%q zIjESFS_Qw-fqaD9(~!hRK~2}nW*o`gVaoka)?KLP!VCD71@*+)>B#`@}YBz<5`et z2>ud9x^A5D*AeR}!gIegaOv;^G!d>f+nn%w9LW~C3N@Ac7-nM@=m%Zm+@7i%*r&g_ z;M<}9F^*#JptpvGzopLoap@zfXNwhd!`2I(mLy6oRHY%d+ETfrd zx#!pY2iLsy(gqCl^}IEjO*$Xvg0T9aV$2LKDohv{6=z~7XUh{(Y|pBOgiI_6gp`u^ zuTXO1ZJpSwJBmEsK&682(EC`zi&KKy!=QizQt2cHOWD=acFlKOg6(%H9v{HT{y2>v z(fM0obk?0(w`^hIJ!jv~r4^N$lSmSYTdIiA<9jUzIjJ2*@`wGA=sSJE7YxZL`&D1J z*$HRI=1(-UD|y9pu@(AEV`flVC&sn0YDa@5=2!8jHdPHIOgkvClH7>NRflY|ej{MTPRMJXKO{c2o9#^1?YpA~P=Gvqxz(p_C@mt46R zoko^CJy2f9u&NqIepBrJ<*sz#C+T@#`{Rxitr&)ne!DLW9`GdTBnx8JW^doM+{oJZ z&N*(?GX?GUd?!|hcY9Bg`zZ#o5?M=5w)RXXLz}l(AQ6kU>>Xx~Oo$_kGaWoYrnW9# zeY>d)Qie>`N20^>NqY~ClVd|W!G(oHSCot^!i*)Y@D;2o30m&n-)1-wZjxndJ#J>51zufGMni;=T`su79(h5K__daJK6mYzHt$2XuB_{#5=Y7$qnv)5(l;S=)kYE(Xq7K zX`i;UypR!Y-I*CJ^>Wb+oWqVT*2!J0zB9QmYIA2}r%GA1jW+CeiA+T|>g`DXoO_#K z0Lkq#{;4br@u^6k_=>8~66evqn8UP-4PK5@D)wJB5sbpZxeC^e2esbS<~!&^fjL%+ zTiqyLs%M!zVgsw=gZSqWK`zpk&q0C@LKEmctaeV1g!WE`$j~W_lvgqaO8+<>z@n-f~%Fpp=Kjg>X2%_}pj5BG@Fba8%O`h9n^e zbWj8BRmnNB%Crmk@ar0tt%EmyXBEQ!p+6J+D4&~T=$mRPoN_J95V>0F${y3-I~Ned zG(H-c)}yPZzi8AHQn%%#uRv=6#!Pw2#D=1mm(xO?QO0@GQIMVkIwswN@cjYgJ zfBu{jQ2W=nTpN0j&2p+!a*>qqVc}+hu_J97z22>?&wkz>&zk+bL4NGiE1`&FWXp;l zU9q&3%R67Yurl?lb!acz77Lt1QrgeWxDhJsDp#x6yF@y)w&324U+exgWH=$O8Hy46 zBzNx*mhTZglja!{C=NwkN%zHXADbAj70r5h9NSBd8gdP;4E~*2yTm)!L$M`@+u7L* zgp7L(($fu8SDn8dU-7&OBJs~25wT=t^xVtUw_Cw>k_6syu1)voYOh|M#kTxV=?hSj zjewG#y-qcH{mQG^gtEM}^pk#xFzW>jrp0d4v9I%VYOwwM3ghtw&}4#kD<9D=wezy<-uNq&bj_nz&`!K3ifI1h-Qa7cXQ(chp zf&Mw|-o>uzp`@J5aPu8P;tFLY{hc>%Ra>dE((mbw1 zPR`@(xKECRmTT6TYTdgJo6v9Xl=-m>Vx&sWLLydw_*+4K>yKIP-daG4?t)LL#|=8# zYSs6Zz{${?*d1%D(>0}>)Aqe80lr(A{b$EF)Z{K-$;nR8Ic}OM;oKjjT)f#`AAbgX zvtaPdx0Dn2=F_NHKjim|=!F@Y5kXwbTMlZ1mjKA9HMcmM3)MO&j^?z?jGh<8rg?A$ zn1&iQ6$?&E2rCl17wfp@|0XlwPVBQY9`Azal{OLSH(Sv}FQzDtcNmFf(x^`-iOM-p zwEX3oP?C-capu=Mv)faTt#48#PumV@nP$gT^(+kaj31>`O>gU@=!T#w* zft@G`3KiM*IojS+%@-o$k@gnL(>#<*9}lp&R1eo7cTX2YXXZ8j2`F=e$;UXDMa5A0 znu~sQ!@%^#SdM>+uW)qHsAtTME%Mfbim&(jd?dIeu*Wma@jl{NsphE|`SCYIZsbRp z5%+B;t*7nqKY2Cbka?W0*^Ubd<~c+yiFD>RaE?yO7j}ZC+)ejZPBr_tmtxN)>_wAb z5RlpIyx)o-A2*mX*U@J`4|DaxgxUHjCXiC;XX=`YGq6P1#4{wB2=r<0>yc1k*1$^n+sVIhQnjWANUiERpf64I z*v-wY;=rc~0R<{eUat{1J41|!@_;SY7v!Rd32}(?xA$oc$HIpDCSuN;1CpEeYqVr* zey_I6{idQ5Et6Dbo+qwErV)L&m5QK1Z=PIZXS$4fx9NsD+`7#Nr`0#J5LjjniKv&C z$YF+m_fu&A+Ao=$CrkTSGHlE3@KuiW@1|UuS=i3rp6=!{`1gT>nOoWIcyUrLiLV`Q zIPd9b`}u%n6F)E>uB|^^XU{J*T*}6ta2ZxU#aLK#*S!V%%_yzU{pPt&=PmWP&XvP#v%QHYJP#nNt+h%4{! zvbVO|;OmffX|_bS5zW8lR-=mG?J$9r!mDHO0M{ft{bYU`L6d)8&0aA2_l_#9yj$eT zzSFrgz=t5|R;kY+WuU#BlExaT9jqQ_?8EL@z=rfJ5TstvCi! z9R=YvU3j&Vei*@0eSy=rP0+g$OeI}Vn(8H*e3&m~Ig)!$#lm7OcxJ#-&HO^hYy-4rGrkIZ5 zD*8H=b7e&r9nK?AKuYc7izKsMXtFVGD1#~))g_drD8G{W1O~!q{~8@zo|L6V3Hr(c z4IIg+kbePXUP+u(mx|Ej4+-6mtDu3Krz}XuoH?28T-&4J$%9)tA`ea%;^Z5P4pB3X z6d}?J#vX7a8{%(C6Ii)pWx&1dNhcP~HzFrrez_KjACy4f1-e`NKM0aEMY<%=b16tv z!15iwJ0Lm9<#pNS4Sw#}c&m|KM$K}u~(VlrU!im;Eifg*RuC-o=yUUECdm5OYs zR5z|X8PD-DPVPH*$X+_euc?&&Ro`{r{7nQz7%*ru|zU6b{=_lq(!i(<^ zQdDfFQ?du>M>V^!!aso>$65}zSM$$$4f?jr=8?Cr@iW4+xKrC@A)sm?tPjBl)8!Pp zp+$P{xZBA~>qtnjru)tXlJH6=ws?Tw zIki{iOC`g2BOVkk*DZPO*Ol<>Ii1gb~6My>_&; z?*srSZ;SJ%&uHWoYWs%4bbz7=E#>dd6MC_rX6WL}d&RymX+?&&F>A4#&?Zm_1%E*s zZc43d?yE`i?{kMB{y;Bk#_g`-(C7Pf-WHM&j_Tt^`r83)>(R=Owd+_QFHOhHM)DR@ zSXe%%^X;Ghh%kDce4_sLqG%8!w%5oHih2iNif=gJU(NW-AT1b4blWj)<%vPK&3<%<*Xliz5z69O$VJ~G2<1HF1`EW`RC^33eRu{o__Iak+7uAxOC#AIEqpo zzbe=6kR%HX$2_%!!1nPRYZ0ikzxYJTDh5ertqIg*a92B6%U)zGpY+>__q(hM1oh9^ zw3Yld{NXZf%8=P8w_^h%rkj3azkfG#hGSm}N&s$#$=>v{nTNK(9?VlKisB>X_l79} zbaP>~O2zozm$<5EuFPkdV^`U6;oQ9(x4MHC#%2~xE_2VlM*2MD*i5rf^v29+c2<+F zYwDbb2LP$+%2B;nD4DrW;o-OX=pz%hB%c1Rr(y5AC6m$OuG~}takn#N!5t=_#5sL% z$ZYifR{8NTh?ywI-&yD>dDcQauS*_d!S>>#xydgG~Ue#N9%>$tjpltM4yame2!l#kuM~Pd;zv zdB``2tsHz^?!cOra?V7yW}^@!c@Z+d@LBON*NR!fDg{JJ*KD`M2>{KJ0{R6ftpj^1 z*4TG^3K1Glce-`3B5R4<;Ut;lk+NaH?itxn4`MBoma3P0grRod_J>MLk<8HGGqto9 zl?NYpKcE{-;|~H_)y$TOgLKeh62_JL>Z!XT$i20ogwZd39+u}wAu;y(TMhmmZZ}(u zObWYE($&MVZO`|l%MKFkRm<|KHIDel%r73gI$}Hx1xDOhWB~vxwI?mg#Ik?C^%&D_ zj&|_M+{`4^6d+gvreCua(K)k@kh-Ai9d^lc@n}>^JD2z+^OU}x>@q9ArXL#l{{8z_ z#B{Ucz%OtEh08C3W|^FZ9*i~qnhSHGc2ydet{LMo1Z3eC^cFAm^b>x5+L@Y~^d6}Q z)AC%DC?g0l@N*sepB$107o~n}3bM0WHYTfF?^_yw>Mq0|)%OQCs(^~LliYs${qmVL z3?qgs6PmVXNi*(#oM!deC1RZ0$F^BARNty&j7HXa=oBrKMi*I$5}kgdX+XO2d1%iV z_Gq$4{zu8g^>Ar}SA8|mC#NkQ$;OPyC>W|k-ZWz8z<&C*sU*eMW4CyC)t-CA#Q4;G zgSd{I7EOfEOpTOvTCw`-$|t!>SJz;a=j46j<=?gzZY_@8q3isc9*3Vb`l_7)iR3o2 zfO@`E&zfXC(KDJ5cN|!CK`A=o-?l{bJq6GFX*#L~&BkW=^Q;`FKVdT9tz_mT|CYb2J$hT%NY6(XXy`ntruoK^Nf_ zO=?gNMO{ggMtEr6d-c$IYuWzXx8y$HrG^*S#np{@}18j)F$gZU0^}C}9*{ySp zB+HwlU>HV#zgR}~qt(SU4PDxqVIGkLpq;S&$hLA1^HH*oyZpjpg`2O`vyM&=g`oVq zgW+ta(K2MU{zyH+>Wt?++mmb&u7W>Y<{7X(pQIaJ4I9ngo~O@W?D%Mz<%TlezM!I> z{e!C9Zv>f{-wt!ryxC&CoO%(=NRLpickbJtn4BzKND$d$kC-hOSUySLGk5*WyDvdx z?pl}@Ds6|<^DRmzk-d*@a3vSL?y{ch%72m~8UBpliI*9eV+UN655ZNvYgxSW^&P?= zn$X(WGb*q%y{G7LC3gYQRN2M)Qc8zkv%OutQ60Zo?h5+1XU?U-Mj zf8q-J&YvvGztc!m?MpYC(c}6f|D{exws!`|?t9Ayf#Lif;121tMhB>*YCGTgGQgM2%K7V}ogdm= znBHWoBvo70vOXdIYVH>!&Feq(;kNGCPnqdOzxupZz%PvfHB5_;ebq7Le zZ^vYJZgwcv&q6?3AT94-*H^f1nv!z9rUJubk!>D$2s(V|8tBI}k+1_i$?7%>Jf{1yl6PgcVxzMt?-O9D*rPYhJit}48D@3!>)-bPd zzqV)XUIl(<@u&tVHU5FH-{;P#*C)|&gF%8WnyfAC)oEMnOp`PP2(kOhSsEG_7x9SU zmAx-bX>o`J)`asTTm(@KGqRWzTD$}I?6t5MQ+1frUB-Hy?V@7Gg%3|}JOt(tUmst+f<&`Dq~`hve$# z(3h);DW$1S_YGb>=4f7VTT?{HZNB{@?=l(H7j^CQJCMgX4*i1A4XK0te3vp)ut_f% zW4ETq7!Ljugq&6}n>(+%bDw7L>x$AUtz?q_hFT^>{4h2~8ju)x4YnT+qZca>uRBcO zWLWxl2rnCDOhH6QHDoUA$B&jqT$zWZ-5JO)?;PEb@hhg^3eIiakixggY_jxhBO($G z6noXx@?82hp|v04Z>ajb{B)P{GDl#680mBTW{xh+PA?mo=A?xhV)x4d5lCeu zaTR*ve@f$(gMms`{F)fiZsmmtfzrV@bdzUL9JQ-6=%8$$S|M`R%FiWF)W4`EeWy=d zVAf91*9P>w7#bLIAS^E(BmE-jQ5s)5P}$e1F^wDkYkH zJtezw4ei8T%ght<(ROw9L-hwG;1)w58i^uJobM;@6zN-z47)GLsQcB3VaDTGRn>qkWr?Y zQVvc?5$5ouo{O#J9rlg_9IE&kz!JoEfK zE1t#rmpWt@%0ph?AhTiCw=EW2G_Xf|mWrx!I;&H8h1vS5hX)n{-n`fhc$d_BFx-xjbGBS;s%d0qN;!Y77NQw z;Y^vbrwBuP^J>kU&lW{Twl_4DgJxei?WsU!H9J)8-5iwKz=Owyz8wo_%j=75B^1Rs zgz&vX%4&t{yKEWSu2u#H`bF{(ntwYtZG-HjIhwmW1M7+8o7ILWH#8#^6WTa+a0M(w zv27FaXo5LQPM^J z1^+qL@BGyoDc_Sa@_5sJ72HXLk$3V5GN}X9T=s^_HU&J1rro=W;|;cEahgvU_h?^G z3#{-@$gysBC+R=;h6Y+j?}{Rsc+XqnCeW;iI$96*cgZO2Y2(D*pMj!DebGcU>(3ZE zbZs?}l}`_PX~ho3()8>u3|!rFI^8Yskl?|{m>Ij3^m6K;0qBC~gFtE?NYc9UFBh&T z9eJfLGTR=Y(exv`ZwfK`4lyiMUG%Bqsb;eU*ib7~Dn#9Imbv^gd)T5By@pc~!nE8hE_ZMzvait5oEwmnJ zA*?Fj$n^n4K)XqdTi&~VIqalPI1iOVVYE#Uszbjd?p7nhiCE9Jm~&RSUh+bTz_oaJcC#@CCeUT*@(X%LMa)STvW=#vRC*Nnt0Ue0e zmwn#5^S6CqLd`0Yh|8=gU*$jGW`W*pUI$u^DVhPcDaZh!CkqcDUKq7A# z{b=N8yoDZ1mcr3vMaO1+v|D8$LXJUfZ8g%l14|o%xUz{OOoSBWvMy3xrX%TWR47CH zBiEaHLNc5C5J+1y4O^&#m&o&#!q4t!ei5bJ%n2V%wJ%Fo+TRcV-!B_=pF*{B&WiVF zpYLtQTS)^myqj{+-c{ziWAf=dU-`G0lK*ct#Nyux-22yW_Z7UwQsaDWo6V^T_~oC; z^vci~ggS)5GdD8P8X!_kJrg8+7`iF1wdGw%&ewfN>71wTS`f8E@9wqq<;0e79>h?k z+H0$mO2LSEeY?uh;;c&V=k%xL3VmN~XrKTiX-2L$d9$cBN2+sqogS z?H7~~b^>O$^8g*qN2vywYGffCyru;>eyMAyp7XPHw>|wJMW(bU!#+s zk0cVw{3fj%T#5nI?puqiiC-IYs`ukp&Z9T>x)&mOf8PB6w;jDXz0+7_7dIYezG@gu z)#vty7xCr$o{J|BKlmP{;BF@nCxtq**m-@}NFE;^X6;L(-aSm#;H7j>ZISHvJPoxM z(dr-oI&9ONW>DMh)*7`IJb)kfrwA|h>74P>sr1w%Y{m!+< zIJuTt{H>rpsW|Q|S6IkRIKCAw_CR1#8?7nRB;x{{wG5!+@5N z;w623;q0?{o$31~|2Z5Bl&QMI&Qg;vHBgr1T1amuCq7|Cz{qSQL_O`IwQ|~?i)Cg% zo$l!XW$9cG^_F0Ow}C;WMiOaW$o#rHc9;7YT%P>>!l-i_fCMV9!Q}*i>(+>~%okfE zGu)BXjUs05FP6Alo=(QnZPC%Su%qbay*y^7ln8REzUW8rm;Kw98@)vLQU|T2!c6y} zOls4lxc_9+aZ3q%%Su4Ff&X2l@j#3^lY9ek=GUC|erd@0ay;FwKol2Mx+qv*XaQA}kVU#YKzRf)Jm7j}dFg8zHlCWy zC-=pW@KXX00%7D+m$4`ziM!oJR_lJtEd|TywZCS?Gs{~}u^4OF8EpteA41C0Hz0Q! z7U6S3JAMB~yeYsAO-=8{#kxIJ{QN^ILVnWx8UIrQQrzSJk8@9$;s`slO8YDLLWuWu zzHe5kJiLr0<7S=;@-4e%_QrbIP00Qg?g#;XCB%g z5THy(J!E8GdUg6DlPHxFFOX=LT^Ron$D?n#Hz!obk)NUqyCJU@aPysiDUwX;+K31H zH8LB=NkG+DbBAt>Wl*?ve|v(&b$SdOWjs%ImL6wQIRF3jwO^wWijbX~ai)rtb;N_r zYy6FBbeAq0O>}r;Iv)hqG?Yy5*i2fli7Dx>w0rdK(FkL9V!7ON%S3I|83=2JbNU3d@3 zv9_Yls|-%umGN|oG1><5x?$6U;#(b3c~9@HE7W{rQ)vIsIo(=r>~?Gm%GsS)pD@-K zzt4Dl=^zwjYvR*8-`M5!7xyE>)`sl%yxg>jZNB3qP0!;#tK1C zxwgu7Lisigm}R0|Dp19YH}~zW+9&YSp@aU7pI&EdTP?sq$UjtC<3>HUiMxcqP0oS> zAo&%4`DKUuZF+CtOF@b3w`y`3#TQgAc|7UuW}k&u1vC8JyEXI**08bR6^X(T;Jx%2 z1uS7$0D`408X@=sf}2CEv8!SKct#ees_ByRq#J(C2(jBXaXr_W<{7 z=x<{eW0};x0w!4O=;({dFOv(KsdxY1Up^$cXx@huJ~~~?81$5opw>Bw4@6vAB&w|o zIrUfhoM|X#8*MUe-3nu_QAzm~awkIb8RR3AL7w~9&wNo!TpKEwakgzBqnVyt>1jYr zkE0H$3wc5qg^+uNda)-J36`lfO;v%S=HduBtd0b!GbrX-xVXPL2(c5B*+l53EtWgy zfXs{n>kyUv&(tifVzLH>Ai;kx6|a`6ys$XILZW2Q{nne) z7R?~XWwNR5#Z#U$Z-DUkm6W&NMWKl6pSy+%wiMlTf9@UKI!Y|O*pl>>JwOYie33Kg z@7rRd-)u8OuIgj!U^!hpW|CUb(C2Lolt;JKSDBleKgqDkR{=Rlj;nD^DE};WQ^(aI zZ_zUGkGs0G608`7YQEne$anwB(Dsl!O)dceam64b$CoH^P!6R#(1W#^n31 zG`rknwF`ubiY4;H$=do;3lS@{FZ|=b}#<}R*-2*i@MAO+H zdMJTTWz$!eE0!Hx+e@;vgMl$B5euB_k_MZC-nRHQI`nbqkx^I)z=iXUU0b;=w7Qsa z*l=-8Fh! z*56+m=dFa@sjcJ^d^^ZW3(e{n^7N!Ry@&II=}fhy2`3WXrDT#IZY1A@QK@2HON1#b zMzI+I(%dmr+>0=oe^%s{gq7UKF*15+M>aJXuO{{Xo|S>4R$_B3pe&DLu|o)Z$1O%3 zRMOzAULdFEXE?%4@i^7Ow1~T4$ZHEcPP`ys-w@Aa!b-DXnO~hLV9dEzFh^! zm9A?_6Im5GyRn<9W4XQS06J8I!F#FJcRzXNhlfnzQ|Z6Y8}&E)HqZrz-&l#J0#XOO ziq4e-<_7BgCpNB=W}f4J6^{ixS)5j&-Jcw6ysJjv{ks>MERRvu1)XBUP|Tl()B@U~ zSS6jTqT^BSPwC%7{?<$)rTkQGMsx+T1@rtm)A01{BAOoBe--62n}y_;tQ3hj4F`qy ztBP@Ba8}~lZ6JwYXz}ww!SmgR{fE2b1O}@H-M(E@aJX!VXLs$8&<(Lt&*ne!En?_A z6a6#ZU@}x|xn#BQF+T633cHM%>E>r7`hA%<3EW z!#DFh-|r-S{9y3ZAJ(I;qB)qMlQixD3LtmHn9n6G2H2>#L?SP7W$}a!s@oh41p}(a zZh4(IUDPjO9LRRwAX;$G$~nblxoYpcYi34_AYYHLYKq;SG<>(jT zn|kW$w8L?{d~QqqIyZp3cG%QLntt2D`guJuEXMk$9lZK3E6Xwc-_XR-9Z9LMi$yWP zg?hfWxEx84u%foMKG{n~$vw08vsPO0k7Q`+fj&;9ljy6v)G1x38*0z)QZthB0>wdT z_rTyf@0RHRLg_FM|JG zK;0NyUjjhh)(6-MQxoyn!YJ4hr01$c!i=b!P1v~;Hkz}dQf1Qk}}nr|QnU!mc? z8ulp5*IuuwL=4U^Ag~fb21HxP^y-E3PAREg(7S6&VZ--E`zZ{*+Ofxxp_^JuY1o%0 zSFJvGml>llRoCRQ_yAgB52H7KobrpR+WA%FeJ?)NHd4PKBE){U`RWYr(8;#h#*Xa2 zE?3llE7BTBACQV;CtVu=%>;irK=v-Z#Z%2GiBLi6;m*vt84;AfOv1rpYlQeg8~XUr z=W8eWN@U;~zG*0m5!8Pgkk_as4Jd={e0FE%roXP}IstvCmR!%q7*oy{RB2$<^tc^H zc(3MlgWqk~-T9IRu%mN#eqo{L#*VxZAY|3DJtfW}T({#@_WGX_Wx|{PkG=N}YbxvB zhMjQ~M@P^BLHZ0xZz@f?qJVU1(u>l&A`m)`sHn6FE!0G%cOi5L$S5^HB$N;-~$AAQP}t00C<{34a?tAP!yq{fe6GQ__CSQvqh#e+C&jU|`Etm`u#kdnEoY-3US4)3MCa{M z5k?Z5jYm9D-v@1hMxHV~)RN+v0tSbUj^YKJO;FyudSnk~?hOzt2bi~{^f&Y)y7@aU zL1#YXnFz|HQVQNrFIl(x;rhpX_S(ib`P^i z+(b4R%3D*HQm-IC^|$gfYNhnETCP~{H2OdK;8j&?lop+56Y@%c$Mtp2li$oM;uk{g z=&Gs#@!nht?$=iLfum^n=`b4K2@pxQ=Y>b@xVx6`VGZIsS|#a@73Vob8qXb3=nggE z;q6yeEo<)bl(=??QTE{IZXL9nOF^7m=^5Zs-CyeY37^T_f$0iW>CRQri-bqqRFq7$ zU5_SG?TCeHbV|S~>)2tXyEFeDYL?M`CM>sfaSeTm$tr!m#7Cf z(H(suZx-y9x3VRGU~#p(tHp-_){L|ZjK^aEA(%h$5$g$$hQeDydp~s^?fsK%Y$y}e z=LUHnmg4s8T;hWOypG4I{EgPfv-`tx<|JGdGU{LtLEk#mvOC%&eFX) zZh6*=R-Cn7Z!iHnCMUN3Byx`lMCUkF*j9c5=$vsIH{mIKr6S;Tt(Ao#xNkD(>`=ku57ZSrCp7GkrihlVd;lKCodd_VA$ zZb3@Rt7@zIJVQJ=A?#uj^oO+rQ7yuZQT+L3ZYjfQB<6!6xw&pPVE#kh9&sSyMk$V`oxUeHj5h2cGq<5g}K7<19 zNpa<%ui_xkT3Xn}ZgYc8Tn9aC{)F@TXByzm1UB8TXT97{9!AH{4{*YM8KGI%KKwAn z{UHHli1}qC$fJDKa$m3a4mO{teL>uNM2cGHv$K|ti}F@^Zc?Kub2%n17h z9m`v3J%4VULl>+19EkHMnh!7Wi84TeTESDI!1)=RnLDcwq%z!1q@ENMeWzpztJEL0 zaB=*++**2+L~}(+iOX9l(K&(scH19bZ4Y0zU-u;dYZC_nL;}#+t5T8HQx(S6cJvnl z)`FrE*V%?S0`bdhc-<1*krw3kxy;eRmb7QvTFPlYs3pfy^(oE*Nb-@>yYI8gjfbKI z+a50JE-S@cnH@?D;7AgnU>FGQ$CGP7)AqPc~QPXBgT)he*?I?M)Mm#l?f7 z9~R-ADro#bNS2EC=KI>M?An5*yaQ6nPdWg6!}ABhg4yMeSCAwi^TA7&-*u}TUzYNw zA)j6VPVI`H@9>1w~ zbjb(e%31)7GH_)Wc7aUuQTh7GMVhf@%l+2RpxwvEC~!SzRxlbRZ^PZ;UVDF#Rn&1s z^75c^jrn|Hby-eK-ExFUzNt0ZdvyW3tiLPpD>)b?M^>8 z*vnfdJo0||KsX0TcN`4YGrPYSeLTZSj_n%{U=o^y-10_MGM%j=;SyPD<^AJFBExjv zE!^C_LQ>6=HHwqY<1BhOLXdGvxB)o$WZ!lBKm4%PKG)L1o`D()iT%wzl9AV6EQBMi z8txd|{$g4;qWl}TtetbgA#knd>b9HOu&wwMrg8-K_f0F|UK7P8_7~o@c zxVEBz4;az3daqU$C7SMU(D3^bF`r2BYf@8y?g54bFL3XnI^~5tw)>8`4HjDdVfQzLq)Tmd0A^son4`M}=b^3fJ>87 zqDPfhiwcK)SiOMUOqzFQtm}%JdIlUZ5~aTU!+@k76JrF?=N57|L5y6>PM2qcbn2UW zUiE9X%Oj3z2Ko4=hJrdl_#88ZziB!B{l|mLAj6Hh(2-9eGpA+lt{%ZHZxBr(O!d`J zeVh$skv0_0I@1uy_#+14LRS`U^Z#kVrMvBt$!H~P>teLi*tW1_e@*m6{*Wa+YVEN% zApWiVBEzOuL-rScGwBjX;=d#l@ZP%7bur9N7Y`c1)o zo;_7uu67hRc!#kD!*4 zcY<1Fcxzumj8{C-9{wda#B^+$lQ&8MGBalyDqX2MGvz58{hiL9sp}Z~rM3RD?aW+U z8IZh`aN?owp{H_r+gdzM@0|EX<{FEU@Qy;&{}8zvHTKs-23*6Vkd=!sT1N~qVwz6d z3a;`EtrvJNpjQO)hNc15;>zTlGM`PYfK0z!JU${;Dct>Y5VtH=HAK;8>j*va2?%J` z-mRL?9@C5~-ACmq`|p?@MEd~w7R=;WJO1e0SJE&@!EbEZ{X;#pnNiF5YJlVGNHRH$ zL;{VU<&}~-&BJ-+_am_@9sr145Rj*HVM$ffTs?h)Gls1R5gz3>XG z&0L~+R!f-X?M0$W8dz}-tQ|}R6n~MvAv$-K^O12@?>b^C_-zeG$xyhU1`w`Yy6_-6 z_T!s(6eyU)jz$gv{_m)Y{<>G<+Kun2)ul(dOm}PUYCM1bd}@l%T*+0uO{eHh45V{e zl|uahoMyJtgR@HcE6J&c2@0JGV8PEt#lCR)%Y!#7AO7{ATcEr(Nu73k-CDfMv}*xS z@#6HTBK%1@G#dS0>mF4@5DQQ8WO%8%Hta9-$hS+7&H?~t7zkN>+3^|;SW(Hmr}#$j zQ3(kh)GJaRg)!jje4SCd{+~BhOLiAi(Z46ES|qf6&+_Ts<-x)Rv`bi*h|}G(-I~>= z6xYI%OY&S%-la*;=X@TiVpE1K7!tjEI(dm6`QI4#Ck}?52&e)-I{8%vle4!+!-=O4 znW6UO+*j$bp%s+$y~t-TZNsxOdhWMT6na0g?lgmKlM52(>~vJ6#9Aa((|}Lh-c8xM z2>O6lzt9&X4NalUm^zv>eV5LPl0S=z9z54zYcJXiPJoK`%FOe&P%Qq8oa>e}HpHN$~QU3BX)!FoTxz5!Xp;K5>>tahw;U?e>`N z?XBXE2qzi>My*oTR;N9eUFSCQ^I4xC0a;cXp}m)5tt-+8Saelhq^x&+_auRJ0|29! z*?~;ksrT=%|H;yJxUqD7LJRzQuG6tts>qb^s28BU40fE`3p(K!#e&JQwC=llRnMQi zYpDEiDSr0+43BnhIYkvnpY4ubaRWR&CFzlX&p3^Jt2y$ql+7rVE;3{Gp!mSWwJ3%8RE3$)`|Yzc`ohhHUs^htS*J5p+sFDr8ah2{@mamsu-<6|d_Jqe zoF3us+z{0D307qp!tx2t+1CZKhV$diUA7eIED(NcR}6bH-V(Bu5!Oagr~TAWz=PQK zC2DJhtaFMnTFcU%MI+()UTPaXnGZ!D5ALx-Jf&gg!8fbr;c5ZYwKv8e*k*a&K52< zl6!b*LQC>?Q0y5pFYgfGJe2G$81Ru=7x4fx$`PrYi;w2sg;OOe^9&q&e);K8DX|=5 z%@Wlb=X|P_ktxS=tV3c-IvCvT?(eqSKRNn&)dyt{Dqx8PJtQy zPrb+77SYQmw>S-iBJmB|8zqC}RKo)oATaRo8vpO*^|MJJ|0BConi=g&$y4y!Kg?MB zcNs{U+2tE{H9m03>s&5P#vMl5{<}n4@Vh3^*MaX^?`&_Rro%RJH#OW3#qPh0gI!<@ zkYFwlcViD^Fo<%2#Kqn{bYlOjTt8FgshU%V++CPOcWW5M?TjR2(&(!Hv&w-e69K?! zSV=tQ;Z1KOYQqr0`h5_CJ~;WGz4f`*w0d$YU$LvZ7GNBT+u*Ex2C zublx>WB!@G-(3BGjK#Xc>>1Jq$Jw*YxGh}M)VeG#{t~sFEh;+Nd+NW8rfZ`4lUufM z(_lOi5m?gWkU#=M08?e;;bqI1Y{QdtEpqxp%c(IJ(`rfS#;gt0LZHQ=6_u@m9CRpkt9rU z#-_%9o6IGj%g6)3YE~u<_(NOh8x#L+Wq@csz{J*`Ib#kkXgh}xN4D_eTnDPHQ{FLsV{mN~!KG1$%tm6N8cJ$;H*g&Yw zU@uIx%{Xo@J5KArtXwW&Qf328jFn1S%*NwwasjX%K*g>yI1P2Cx&bSt+r0a3m#uL( z`@d)D|NZ6vsu{S>0cba`lufp$pCC7B3cmY5U$BM+yCbB68S?8`#v|4!Oe@Fp7 z_4&O-l-{jERH-zB4Nm?3^v{q$cGaQ3tId`Jk)-EzfjZ}|c0DK> zR_TNAd*Wk-GPN;39aT{y$e*0(bGat+^m{Gcz6)w~F`zxC@14X?08-|`-r_N!fumL$ z&Z;TL*8Y6-Y{-!Fse#sO*AH7i{4rT(y^pZnCVuqefRt*c{eL`ob)mHaf+pr2{rFoM zfY{kXc#exp19s>K3U$~ksT1`GAFR=BxMe%oWSW!c$IFxUcf*&mKqV;U?*jR8>4Uk4 z{TJBS*dR)dKqKLhI)rInkzdoy71JCbH}hX}75!JrRiIZdaEIp6_wwH3vwrT{X<(*q z`prqgwZ7={>W2SDp=+xly8n?q$AU7kUHCnH-U_BMn*4pBe>d=d*&hcmgvJkP#nml3 zaq0FK|1|wc?9xnCE$SGlNQ9*N`d7)%*G$lY z?|WiDIM3br;f4j5p7pI}`hl6P$eZ?Y(#m!oJq}9LyiwL+~N!AR|Ic7T}@B;2B_7y*Qq>7;%Vx z+QtIc7u_aQXm))q_zmbxl&)Xd{f z@n%2zdHzP}xL%sP2m?+&} zjHwZTO_4LwSvi?uTE7=7zNF2UZo)$!{Oj38nhiLtjPt$p)1S|o3G#)6g&&%f| zjYqj#PF(;8KK*mlqqBO%U5sh)_fy{{rnP_H#8k>Zcg*D%aTM+N{*>GAT*FU8CAbdn zx3qg-Ip8=kLzYMJxTZzkK5F&YnKy3Y#Tsu8Va0X9t{qC?Bx?)_-;`Wd%w)M7Re4Oe zxXg(zymJVaUZ)bkWtECW5bv$o0oLIx9XnQ@_$2qw^`}n`F>cuE>(HpxfS>0^_Z2Cj z-$y)g69_W^=^o0&$Lis)Osd*{3i8%;*vtCg9v7hJRvLc}@59{F);ntb81>FSZ)fKj z?zRX6T5omJzWKlY3@JZsUGh7We*c$b&d(&Xqkr8=JhSY2^lGQe@lOBq*;L0{U8O6( zwidQ&Q^fz5j^EWYJ9@Jdznbp<^7I8TvGVZEtY6y_zyG}QpA(w^P7tvzZ$A}e5M-?` z)?#4xeRmG0{WEoErqx0!E0LeWKVn>6WRBW+{Oq5xyZwL^O|w!D3u`_Xa{O2+skC9tu=*PWYx!-zW zb7C6$oT2i)DW9MIX^OA$riUs1z75aEq?ZPI@oI}3#X@qxS9^i-?(%6b-FD8?Ucle+ z@BHy}aFVq%mntU&>6)aeYm)N47UlIn8;f1&UZ*489vm!LIHT^!r`|Y;Qo%PxH0loI{w}+bfnv8RrEoyU z+F4RVRiAZHO_j1T;4ac~{(H;te>T9o+f^cLl7eF~5%{MA8loF%1p<-A_~`*fQ4VVd zSp}Nl_eIas|7W*y^Cnj(&q+79;!}+buHno`VfoI|48GCBwm%62NFXSF`d*?|#U06N zK_MaShh{E9!0nV%)%Ht*!pEF-|J~40U*0DJ=o)eQ*i0NKQl!Bxt3Ml5q&zxb+mwoExZr+ z_wn%|>b`m4(k$s>@;ouoe3T`0%#?q++4MN)tWxX4qHMv)hP$nH(CJE>LHijwDe_sc zabH=O@BTi)B<@!=1+f6BNb{|}5X={$y(rvE{ z74?YzzEuz3>lUqiN0MuFnET@+#YZUw8V3gl?4k~gKQhZesvp(u8JypSvx0a3a$QhS zjPmiW98B)dr2IzYmHg2BFtK^x&gz@`#!(aX`AuG-M(&38!RDn+_d1I`VjR+VVQA)5 ztQjqaE)n|KqRg+mNTSJhE;ubpEvg6zyr`HVmX!G%6ls@gqy(W6uf*ncC@&)RCDMY% z9`%3nvAK9wTx>o%z{vcfjK5Ou z)a)zISn;?xH7PP=$f%{ZQ%^SPaBKJ0&y{vC#PByCB9KA@-^C%64=0Bz~YkhB}KZ0&6>5Q6> zDFjZ$W0tC-@(#?8>%%C|A`XOHD9dhL+vB6bMsC7e*qRNp-iCX5P-YYx8TFoPw!BiB z6(7=l5x}ySrKfl0XHq+MaklN(QekJZ8`k7=_$?xX_?yt{6&_)Abl1{d?U3}no=;( z19tXa9}kjG4Hk}!!tV||ALtt(io%j&q$z(4%nWdfL{}&xJzdyXwdAnHuq~na#;(09 z8?QQDNdEEG_*?)ItaD*+`u=bzuU?-Aj!*xD?FK` z&jfI2u3(-~+EZq(H1tn5vYUug@kS)|8gmJ;SRE;H!zDq2qm7Glo{MCT|3i|1&dK|2 zL7NSxGi9xMG+xVa9z=(Y)oH$9+`?NP2a-?#8r+Z%Ax33&d$2f$LP0PjRQ1Mh+b_LvAsRA_T|2Khzq_5Oq3R!pOfz} zfR;A?$$Wwa2D%ic)By}MKFR6LcGE%FN5%D6<*U4EViboG^3Dx#Y-VaGpzM#`F@AGr z_eS$MsMIrJA$PR)LzqEdZ2Yfulj4g9jF+2RD%jZ{jHgu22F#UvLf51AP39@Ba_Z#~ zrBF**G8L+>E=3|PK^N2!`VVdFCj+9I+@NU&>d~*(>gC!|)0wF+JmVo}hyx{t4%b|H zd`ape#e(05>?5KhF=5UoS2cS)H2;VNQ!ar9g9R% zLhg07284g<_&ucDK_`#C0L~D>CGFcxcE?xro!Ax@)k%xFLixF5b|gcTQQ1_d1B~kv z4v=5A-bsX9r{bxN;$z0>?lQzeb)ngG^{kjxRDdOVvsbFnL6&TgrQ0^*>Dzr_nD@8= ztXMD=TRfW_G?mb2q%IB}C*DUemEv4-O~^CFBjmI{y}lnKxYMHc<&a7=xJNz(Ub3jW z8OwSb`jiZB+)W?rx7QTeyI3NceNeK3!}>VAh*P5klwf#VWa|_-lycBJHnJ!l9y&xu zYw$B1%$b$?ghuY)Jk)FfhkZ8i%S6uV>+8n^@*UgyHi0pKR$oBP7CUPisY&@>qCktQ zgSn7<#^^7)ji@ur`Lm^eEZW{j0GT)`WkvbsFNwPd5A`V-PeoGw5mej0Ej?Pl~Nlx(GP_-i@s?}ct>xN}b&NNJaBzp`NG3uXj7Xtlww3MY0&H04BkR!T z2U8x9S|MoiZu_ZGZI`M=3PaQgbE7C`Z5ibA5c6bVVJVE3G>|BomNuu$H3DopyA=Rm zWViKF3N)3XXWJHWX|)ew?Yw+^_lJJlZhRTYS1|qBhO9ykFA~$Lzg7Yg6N^>Nox+J| z*-E2EcI+;r!nTWd9CS+hQ%!AZ6PO52BWklae)M0}dTaP(|+AinngOaRb3Sx-P9!-lwf zMghli%oL&XG}o}5bhEG9lD^zlSXNSg*ukb$jZA6Ly@Nct^eDC2=pIe-i?a?*aq#u4 z4(J&>1>z+!<`~A$Eb768nmyll*~2T;M)ntIaravd(Db7+jSP+{ct8d+D}{>$H&2nw zW#pQ87H12pSNeZTLK48^BIaqUvOs6tr1*GwBW;^cK?lz?v=mld?@88Hz4E3<8RcPk~zVnm{FnGazwv4Z~{=?8R_ybovey|#O2rz!NYab zx2{jcm1nxcKkBWYFfuT~ELlt@-m0~vx;M%Qf#(L4-_nwtidPsJz5U}^FdntvLmaPo zssKI7&I52G#3RYAzxUBj^P>xrIb&tw&A#8tQ)VIq;H)A$^vq^MS7tHBrdB$2Pl{`} ziGJ(JOT#t3I;yD1hFK|f%g*%x=ts@zzxx4d(5Y-+^|xhl(}O38WTkGWNm`({X8Yc= zO4Kvr9lW{?4%R3RHDZE{4BDe-13awNfNlWjH!*P|U+#%FWob2#{{oHalG0z~rcVnP ze-D=M?={vu+nl8D>eyE8dI8z4?Z{2_m(1Z&X|#~R1fpa6OSgB5Z;hEa9N7?$p$}Wp z;9l(8I_HOAhIUC&CJ|nQCZ)rHesr>HSMC*gA%-{ZP-6|rTeN}Y0nUl(%oU&y*EjNW zaxThporZWL-Ml?KK8{}_==UVMeDO_}Q1K%m%_g;r9F@`|D)9|*Et#(f*gKb1gM4&l zFr}i?IBxPf&-v0(anr;@yY;nq=iNzyi^ii^e88l_+1RrSTQ;${@IF!R?%KvVDC*U1 z`$?ME+Dn61@yb^P+MWS#e_ZnVj%25*<4Kf<@lJEfYd8HCn^%ObrjY%B`QN3;VuOv% z`mAiZ=X=*wN4egrUJ{$XY?b3Gs3Vao=imKuWX5-!tzGY7M!4Z9I*8M;i4o9;nvm=7 zu67({9%w!b-Jhcmw7Tv)5iGUiK(qXec_B6@t?I}A@cXHUS zLftGMIsebd?H-+wT- z-ne@pk&)iqhYIdPZ4A$`5;ud1{qYAM542p+AZ9R7TTRGan$?Z^=pN&?ZGtGZLnkfa zpz3kW>of{#<-NOh#jIv z74%H^O9oaq!ptT1>zhP*)PjV6M8q!m;Vf*TRp*4_%#f%>Z0tNQu{KDUvn zDO7&cR>IPFyAr7`@I@$aw1F;bB|K3(d*abX|Ln+^k!xbteBvRrb7J4HmE@`&$o}im z;^OWJz?6(eA#i{~5?t(3NQq~Jr!asut}0%>z8eBhvkP#KpGrA<|5}MbE>X7 zx3OVSU3QEn4gH+~G6E&U-aSrTaga>`((f~Q>90_BiDwy zMI}zQeDzy~-aDUaWWNo0zt1%)KAkSbaR*R}hv-g%_*VrDg%f+*0u9Mn36?*iOJ94>$xt+GAQ5XrHsE`cL<$L8*%hqu$P|BSk{D|x{9D)ENt#6A2omII;4&qrL;s!WL6qj63+Bk8|#Fw;88lMdp@J%(Bc1~R-UvaHX z*1WkEFDP`8o`n`DhWA z7o=(R^{iAZM}%4fviXkYhkp0TNHzm);A_tHt5+wJ6aqhEg6n5lQ1F2jb%}O!KQ1N- zeN_z!OOl7w-K8>@k#z8RTwBV16vB>#%U<1pDa70Cb^Z7$Sv2+9{YgM}T>*r%s`9I) zXO#IvD+CCNh#YctyK?fmiXV2Y%olgxUO^Z(rJCMQJIbv&pKKs4p;!`v&v&(m8vnvek_N(;N3+$|UL?JN>2c@Pj7UsGHI55gGcN-FRfY5WLbwX~ zQGT-_?S?umUVou3^iqJrI#0C6I?Ng|SNIAS9B&O|sYBk7vr=C>2MlIFT=~0OI<*)0 z=?&-%2Zyk?&vD)I(^_GB-lF|dg1uymk+nH_?UGRbVR=-{=2ezXQ#`Z7jppOqy@U14 zQIH=pw`L&k#y5BPY#W|vG7~AkfLos!n73w7x0SK^Op~4F-8++UbKzUf-(qbPtVHR5 zpvO>!c=slSSNoQeNcf$YA2A&wEtthtw;k`eolVB?EX|#P4f^Tj78$wq!vn*TCuI1| z48jK^N>9NgvzW}SUI~-V8PLghr-WjiB)NoyBK`3N1Hy`)4Q1o3hj_SrF^A6nHw{nW z<34>KRn8u=SoMZl9d=V~OY&mTWy4z`P8xx=`4J{+gDOMcb5FfA=S< zMUSSceExwz-9|Q`bvDkgFfUhPk*eAyll5~FA634M4>T!5`LSk44uwyOPT`v7q#r)7 z{_)q{el~MlSzm1-IUWC@GA=p%BU_wKWnZb|j--h&U=y7rnX#%v_iTa{5T&yxw&r$c zh!9DwT)a<7(QS<@6h^a=0XFcC`r@dbS5fbM#m%kINUfUCnLzUk>*>XU0KcKav+8Q2 z{`PW*z*es(QFLO#Vp#qnVuAH$1*hX0LqR>tgkHXbynos&t=Wkm>s%OSTw?WCbpC+6 zl_*KSXBCxfl^L85<9D5UUsTKUXcYno@I&jQLa{tAvQ5C@J&P<=lG8q4!VKXDDfs zg?lkw_d~9nfVT|F8JXY8+1Q-z!Mxs4S{~_=Xt%h`pqzuo>2%1Z^v!mA^OT1PuIXD` z#vM}C*Utd9#UcHci@ph*%LvOUf}sLexNrR`xEZ);Yx`Mo@%;vS+K%<$T4!m9ORURf z)JRxwgM9cOIxgs?Lv$?>)#|gO@-7a(BT$Ima>sV7Y1hP$1}I{Qdf7hT72~Tj9BEhg zlPWp5o27;7cTOs+7)4}r++w`;hgw8LDr$szL(%=H9=1CgS61?61%z91)!XVH5RJlf zNhh`foRas{N4mtn#faX_ZwkhHf@_QnWWD1-5=%d#F!9uhIgY#jXQ(dnIcsr7<^mMM z6Ijn&1^F7MOU)r#Bkhmyp#(>79=+3*IyZZOUDPjek$%PRLj2n2ZvQ%~E~#NSDYOT0 zqog?OgPxiKT$$$S<^01_V3+xasQJ{ZrO~My015tL|Egh~uagZv^qML+vOO-w0m5y( z_kNmNYt$+nD_W?4}#P8hi#T|3gr z{H~GZ*59WYW8|{ELHr; z?MPB=rEs$6Sk>Ww5RKKE?+cDlR)2&Jv2>MLxg->kLyz5(>1iL(v&xxcmNI8WjW@5- zlnlw{1}$2bo$*qDmle|d)19+5+isJ@)be6E?)<%L9%%~h%#4T5E@r06W^b1iS9g0O z^Ub_VFLtWuPMM3;@iPmAzIB>z8o(3vWiSo+)5~fviBw30vx)(K^Ru$uUpa=G@2$K+;Mu>Pz!%$B4>@?|nPu!p|82-FJ-5CAI)T*N0)!PH zlQ>=xm=RY10qDXkA|H7>R` ztfyygmlm^?eqe#>ou)AQ64VArtP9)riqbSSfaAng_mVHNjQVCwN-zr0S=B-U&g)~t z2C&lDej|15Y`V80q~#I1>pP_=E4-~`M+(IXO-`EF;~7qG8Xrd{=gHJG#JnCC&DAOE zb;eAJrPUo@IX;&ph47Bl**ym zjnrT*Io* zfc1QLnI{OiY%~yCjaH1a=hrgMQSXSALNtDi{%$~+Rp6g z*ITby)|VRTPa|9z<^8!2}v=Y#0 zlnv`WkXFYpBYhiM@pa!a_agtLlbnx}Rs8y?j@$3<8^TQ5bp*pp0F!jj?4jjgyJ@?X z4i6IE+yUtMeVOJm;Y;J{&9>&hUIf@2U|tIi%C>8#*X51dJD3^V-?cQ6{=N(O2b&~< zwRo}w!_P_x(iUvw$cvgN=ZFXfywo~Iq=EP0-$LlW!RrcF-(uM+<7;P%mSWybvE7T! ze>t$^y*?{1#H7EtZ9!^(a1Z07X70el6DbeUaK?KoTU}=G^*}3W^JkZ1jmqk@j7jAv z%@cYm@;gqq)=T>$qT}Ic${U;6R&R-Kx6zNXxC`Qf%JfwXx+=HZJ8LAr3dE-taz_4{ z$KN!gZ~{JWLpQh*JsaD`4MMCOSV!ePb%3F^dh5C|8OR#_#!6t{s*b{g8uu>dn$KL* zq_{UNBhVF3=wFO*Ni}xMZJVJag*&WVam}|2MelXGUj$gRrx4nzpW%o))_ZE1v7P!$ zC^)fVr#$9R`IB4i_+jXkdMSiR?iAh7{$MCuQ4kqgGSSg&hgJ}&186j@*qXW3tF)@M zRyXK~jgXiVz{lm>enlz2~&^;g(TyCOnPW*V|o4 zToCOSUv-Drc45D^LD0wF7f#oGD_4h13!NZTSY!11M1l)m8ZR_~y+`NzO0f6!7nO%l z^P(bJa%&kP3fAqZF6Seih5JNnHSZ5wWki1@3TJKn7SYn6+>oXYmm4k1eS)2>H8_E* z1#Vky)Qs`*NI}!^Sfeuk;8HHi>Tx!|FVy89N3A3~rnd~mvHgRbkRe=3%x@t9K-|R5 zEVG)`+#h1*9Z*i6Ic@bbN4Y+S(0-Kb3fN&HVsSUl=n$*pq;r^2ZL(cN?vtG@dO)dKfK?>hZzF8^7f#)?VEqetn_>ra~F%lny6b`?l?vL z*&RTHGzArT5VNbJh_V^p=|CdhfNy%2)NK?J5#+$#vqs&<9>R5FyIaFBOw)ofz(YOe zo-X~P$=inp0QPhf^6+K@D=!o@u}lRUCyB+ntrZI`o}a|(t%JCR4@OG{GZ(a*^=PDC z&QoUE<}y>k=puK=0+V)4Q%zsf?<^nvfqgi?#*K z!`3)Oxz*)A$Eu~7j99(!SPG%>gE2B%Hwec{>M*(+j<9bb93_NT#u|_$OvTzwonP#Fo4$1JoDF}Z!I+qfkq+@YNG2MT1-7G0Q}G0Z^b2S zJLTMmjCzDuHMCdtIFrl1+~?sCp9IV3ZGbML9nZw~YycCjnq)8(f5m0%gG)?%kk*y4 zW(70TO-i!qO6q15LL+;N!w_WN^;^;}NAU@tAWkPEl%QuWx)w1wjmqRktwh44JBCkroulQvJLho_`w|F+ z!=;$66!x2~e0C8S=>%ZgeWtK0z?}VTCreWbW#ILDy@9CpYfXa6Fs)0&1Rn;hI3;Yq7WHCSqQ3$(eHZ`*RlYm1tsr5p?e zzM_X|->)&kpC-sb z9Oj(M>-}fdNSuDDSqmb|%z2#zU>ZeN%_uA;x*I|9H|W`C44lbIopSx9+tsO=AoZ2c zu;a{fzf575HY1vtq~ks%8Cx5vy(Mp@Ub#>bTn4yyQUS;kHSxZ^&bJ>BLl&~+xnd_N zv8vNK?8~rv0aso*UyphHwJ!vu`~z2jZ{;Zl6AS`ARpMpW!eb0uoLdY*uZa8Q5v;lw z#DnEsH6a~XcU%Va;i{L`p-X3D*LR+{+pu0=Tda{1Jh{@Q7M{dzWYo^swO5abwdZh* zE`?sZi#`J^S5#+p#u9Ecxu0Q?&OIjox~?X3bY2VmTd=%L_BOkYIqV$RxoIAc+0H?c zesH%^*UBEZYNw4y&95K%Z;r{T$?M0?yQdi;tvZ_&<j@9njBJqIC3Ej%Ck8)D|CIizvc2>9mDKf4^XSi0}kyEQX2N3VSb z4`MwF6fpWM)eyEx;##1c@9%}){JC-_TTaoDcQsA}UVSJFC*dQze38V=G{ZrOKc(rT zN1tF%tR9qaVvoh7EYoC|1z}g1RKAv61s9a?%Q^ePn>};a0QLM;tt)j^t=-)cO%{Q8 z7(>|mMFX{dq^%Ws&MysQI9^q@Xt5dcNHcNiu<5ANF=Yt1=y6GIJrW7}QHc3OF zUoo^ENh0}`SfQYfu<-0lRF~5*gq*zABv0u#g_q-a)iwSe9+0fZP zx5#L_ZTwZmU*e*`HM|pAa>8&2G{OTJOS25a5<>{4ezlzlk@RvV=HrgL@UOX+T@;Xt z>#I4(lnaJThs)7|TB;#`R6^=qqjHWV!reH(R3V?^heLa{|F=13QFU^r|HKPt@OJD%-CNR7Ra?;k~lS-UFTx19obWa+3HjnwcYFT!E0dv|8`1|+sVf+ zmbs~sNkWCip3W_0R79=alx@G!UOZ<;Rv{!jt|z$cFp6LqJSY?^NZwfhgYO##rx16a zy{H>!V0I6J%In$D6|a%%4;u@}>Kdl}eCP&heiJdmJ~7#pe4^Jk)~B<0D zl)~TvoHvyEl$q$+=7kv-eSisY=XE_#rs^vArw}BxvV|mb5N8##wv$#vT4b2NbqufF z7Q!-`MU%2(J6(o$L>Qfpg>hN2LWS(dwnc=Wf($p$mssJvIIe@#g>A^jv-;acJu#4h zIvZvOzz0=L<*{Q4Uu-i|?S>c1T%4=}??f?i;TM!1$t7tT`~I+WJ{?P_;Bl>+DS2yN z>k8b2512OPi2X>TX6#rgTct|8f|@SrHdP;K*l*RKb9clwO~brr75vdm6iHm0D{4l} zt9%$AW<)KgWIlI+>O+vewmqwu_s{M_QAwnMgjnwqiIQCw&s6Jt%;xPqjNXo=_rFBP zUn*w>;D#-L>!`iB+SM~DTON-ZY*cBTBQ^P^@h?i%srnIsIJf8qJsKcsafXH)Fkapm zz4Rit)zF>-!e5bqZ)WW)x0Z5q+Ch@%o?*HR+e{I%D!YYkv7*b|ffhNB!031OH+TBY zS!F`DnU@gI@NldlM@jyPEum;13;{`fy^AW_wt$|C^uT`_I4I;aovo@X|*`5Y92 zYFCrjO1Jqes@TBv%xC@Z|L zCD8sY>P4Vu*?f4FNfgxArx*zc(8t^uM1IT~v^m$DK! z81qKmHfVHG<^;UEsP)ewt7dIe62q_7`2#T)(VP_8trF>iG8RQy>^Z9EixBPre8t@IE>4s!*r(Y1G)x!A zCZCwej6%N%kAPOXedb+@jh~2Cy1%<)e&km+o3-X6XNO(lBpV%bW!gD62Tnoii?UHnQ`^=>IUv)re(r1x7BS6_x8j?!NxLY zUoIrC1$B{z0PBg-us^u}BBqu9#9Kqmq2Uy(V8ktT5`E5(T2OTLbZZbX4-#wjX@Y~q zL_{(xKV5xGWObWsyO@L%W;+hw)qB|*R~3`zQ#e@ql;~@bpYE#PlP}KRn3Pk!0pDy+D94VTZ4Y>EF3S~JoQH8GzoMjtM7Qei4nf&D z^-HpAZkH`fPhz3==EAgdTUPGF+wOabK`=%mAGNCr^fb1VJGfWmBw;&jaW)bs{y}A1 zhH-qWdw7NGL>RJ78Fyo~c30@fo-%f$z)p0kV0kckcAa*;Sh4BL(t~K;qb=p#wZ+a@8EePbscdAC9WVj?7WC%Ko8jgL5h<^@ zVtLp;>JZ1zv|<@zlw1c;qYwaP_X7xjnU|Nhb^{QI`Nu>>y`m6P0yHa-um`{L2O&QY zp%_8T;xCt)FCxg`g@XTZ0KRn22KC@w$BJlkW|E0%I{j&YU1R)g^^05eig(%lEMcv}a2ZX^0kir`@}es%k^$O-5F_7$~B% zG4i@D?d;pUA%iK!gAQ=C2=cM85gb3SBac+035xIds@)uwku%)U`@e$m)0rFeFYE5^ zT1-OjO~KjKJ^SWE>_+lL9hNM9E9ldK+cOyc$Wwe>I68;d=^c=~-ak;ypy_iGytVcG zTW_&}{v%e!1+#|0$5(rq`f9r564#gP`?jpyai)()s~ks+{Y9Xh?2-H4n{Qqk*a-8) z-N&b|d`2m$iO(K?Z@-LbMz$|-8Ma96TH0PTxe9hD3*zmV;E$r+_4_LsyuE>xRG#jk zABZv;+15_)qiD!vkZRXD8}Z4%1@2oerUyARZr=S>hZjCkY`3j4WKOxGqMLYXK~@c_ z6F?!WWigbPA3UnFSlOU0#~#BsLihMnJ61EWTdosNHXjLz4xn>^Tw_qhnvApCwt3!N zp3d>0Mo-EJv$Wa|dgw9?q}VQa1R!1e<}2C#vN$am{PVL|1Vo)TNrO2IO3Y>Js#Svyvgcg{jJ&_p^q+#Cu{7I){gp}1_FtM*1E)4KthV}dF7b(N< z5`8mPV5$O1cXLCodvaS%yE8#v>_&RfWeX9nviymD=%w0sQ|u%B&4~4ULzn&SS|bjF zWElPFPHMC4+m-$|8P2V9GJz0aLU#ylow}Uq694?xs3LT~+1A{$I)kz8YBjj%hpnaf zyEGiSp1&FB{15dLq6^HkO+|l4YIxH4=e(!)hZ7UgkvO^F!|=x2qrd{3^|~AFRwA5I z&E0^RQdXfegNH@AE`2t`EFpEnQXj0u#l((*>edU=2JN#hoou7an&VVC*{=p=K58x3 zkc>#;2eu1Tmpc`c%)1F6xAd1Bt_y?{?CVI9jN8Qppki1yJ9cH=8Jza5XaLou3A40A zubI=fHa~NWd06baCQ;Z~1UZz!K5vv8Vif8J%+KjY#BzO*V=(4u5uv~p0DOVlCR6LG z8_LO$bixv22Xv!}4d9D?U4Y8yw!B!e?b}0W$jNugcxGIGVd#Lv21*huS$#X&WR}@d zs7qW68)P0TpgP->Za!EA{za#w`fJ_OH^9y!5UIp}AaQm)U;}ZPlgK%$dr9w{cjeh@ zNs=3T)m+;*1~ua@aQW_R4&5j*Dad2q{eEuww|F~Cm6-rK$A^d8W*`)!xNF$=-H>9$ z*KaaVW#vwpb0WgtmQjfyv(buucj8lQLLpFmOnr2zMcT`}&s2x(Ht3g`>x&-P3g-|N zy6%&0%A6?mdqK`@mnT@~xtGWpn;!h-93tIzyO2z>tmp7&!}s@^146u&${vMlrIuhU zB~zhno&^6N?ZU@T@sK+lt{=*Rf|?jN(7DK@MXT*nGvB+QeQd$EcpDbfRA?#dSMqoJ zPxR%74uTU=sm@8n9WFJ8fZ&P9mXK9OG|ubTUY}-CP)^t^Om=sB#>B9tueWcq%Le%= zQKwCnQ%vW|V)@AY!@U~+!y$rugwf3mqQ@Z`KJLF_u;UupA@BG3D$+@*5_vOQ0}y{M z&yew0FWE?`{5j6(Q*WF0cdJK+`SlV<+O$fJC+jmUuo38qq}kDi9M?EFPkRN{HQVTrzuIe+{d2i!D z#g2{XLPB;g`Y6GpdF;acLoz|d@5nkOErM0_gU#T%%*;7DFo(*8$Zvh0)d%5%yc{8& z_YO#5s!CajE#_)nl84XdNaW_qKUc%uy;t7Ltc%&>PdTW`u@T~AR`%_G_a~VfzHPhX zZJl;`-aPPu!*%Ei_Wfu7Y@Wpm`5#+&+awC4DjpK)dn?LaleMST<8XKf)dqozIRjS7`q+E(MO1psi#HliH9(DegCPIH_$R?ZV_Pt z)*_R)4+w2w-G^v{!yCg1Bx%uELU?(iwK}wap7cOObF$Qwf@6%G=byvSTX2p5cgH)J z^{kr8qfEhauB3zRKHaxcP zrss<*Zt715}BtWBL40R=-hq?y)R zsv3}o$ncc`(f2owIcoatm)^21O7GJ-h~y&E6?a2|t^x+N5+NB`LM|Omw<3HKOnlps zx{dh<7+LA-DlphqDH)l8$7#l%HVc5iwM2ES%T=&fmDcXn7htUEr%JU$(~ zyb_D!kg2G2x`ExYPnL+)TIGe8>$dv=y>NoJshk~IbUXay+Jz-gA37elZQVCt`wx%T zYr~Bg3_!cf6PPZ2e0XK7*0EKe+VZt02^QSS|GsMCGF-$l$q?P%8A>`N=2(cMtXtg4 z|E}F1Y5SIc*O4jZhL-(|Pb*^KO!rshI#K2mEY>_u|Gd8|Gky@$O zcyt{`;Nz`3DU8*A+UuXpFYUnL8X+6)?P|oYIDPC<6(U1ZuiAiv$VgO_O!uI;_3%IB zdJ)So>hc)|v-^EZ_ey9;dS1H3upN5!bMj}_o(>SKWw~A3TQUs}k2X&;&pgZnyH<`v z+WJ)AVBH@8`ZZXPZW!s=Kd|XzWEM6$&B|X#hPP|h_{(0j*Ey?fIu?xl84H3T&plXI zJbbgXS9S3Jrm|J|1Ik#ynsR!dZn#rL797;n1`Gh5$sN7)^Ilb$0e{@D32krWb*Mdo^+ya9e3YsboUAqIHlV5fkJUqfzSmp|wS{5WWPejIm$$cW{bK zihhCy4HR2x&2leUxLNMP9C~JRh$KEab!`QyERM$?A|g37){&(4cZ&kDKu*fCxBwQ$hzOog)uA>C z{Ikx6pyf;KK%fo+ZG3vGARBvp6a0D!@_#|yw7)lmI1ZO4|3!75b@G~S%fat zs7FS$==Qd?5;l095xr8%4sTOj2>fq|UcM6+zCC+c;7ETAL1w0;Xdg*h0!~hyrTaVB z%|tjsP##u>@~q!Kxv`VZ0{UDh;6$tZ{yp;mjjg3@nYT)X6%dv3CfQ3?m5qFNy*@12 zLTUn4P}ue?uUWcmkFnoHh_!yCv}U5Ar^&}PQc=I5$`U&hyF<30!Oiu1O!fqj{FH$^ z#O@zu@N=$Gw_rxM_iCD1U&)$MUr*&q%}>=$O=x=YtaMYv5h;7w^a8nYkw*Z z+FQR8l-vYdh)WbHFd1>pl{D_3CyZrW`^`rO!3v@p%qL!*nQo;u&mY@K-s6j)ywhSK z%?jss0lQX_R-BavMEyCH%s?;I|ye4_UHF9Ko-|Sr_Z-a?x{}A-B&8& zCR8emT5FgtMb5_u{cH%Z5&vWnR_Xw3P>q&oAjbMIBd%f_;2kJ?ay$_ zL9DxNBLpOP#B~zC zWw@q>_g2KRLXu$SB-Of_L-Ty2K~O9f_a_$q>V9j@Ma1^Q0KkvF!oyZ9 zC!FsZ{K%xb(if)G4hjC2+xY*P@ppslSzlzr_*j@lu0 zlj=;RWXnce2q4@y9@+^)^9DDn+n7udDv{)#&r;nrusVEx`e4 zMl?AE1*}7vX-PZpd3!s&cK(zC@NRo%4zvI(maGnId3SQ%DC>Yxc1{1twT$ZFb)7>7 zWdyyimz{2`0JNIFJ-b;-A7Be~jV4P?V17ww{nKlw7RL6 zbTK&ch)Q-XvKKvr(dly!++2kW)%s-`SWMmn-`DM()91r|HlqsJev!7G`9b_! zlaq!n@r-%8sXnOGnt;u=3+Q)ca``mRy98taGv?{{F!?wR7LmctU^O=Bu5{fhTKE8Z zB6r6hbjRf|4gyEHGU-@-^y>_Qb+}pv>+3uI1x(3_^xC%Gt4AHObBI*FIt{PyldAPZ zKbTWQthO2ltMDv@PnyFlp9#uaS1s+M1j*P95&JitNLeMk^rCN0hIzBe;bTYPo|!Dd zEk5TbdiMU9HCJXK4a^VjEy}kP-u08rKV1$gdBH%Cy!?;vY;Ip}i0Z5{H}AUiPHZ>X z_)wk>Mfk-|WH7W+0(vB&iDnme)oXpNpH8C2eS7>9_vw|GheYZ=xjLmPoDKZMqaWx1 zTbhe)Lf5z};Hv?AS67LsW|b zC40Tq4pbwEpP?OOO@%h8-kkDH;Ci_=qse8{#XDuY2LEx<2gL$a?qq1C83>3KC}T2` zDOHFXs5Ij%CJn<_Rn>HqFXIi#u6l;W&}bn(&o?Ch-n%9Tk0kBFj)zcc8XTsj>$_D- zkq~s0rXumEJOg{`h)vH&pasG9p985ue+jhgwP{yS?oTf`LF+&7>W`dXl2-3k6N@;`5V){5pWg zLEeM@t~bUJ1+^KSAO_ppYbNj3@oZXw#fiSP4u-WJdEg6Yf8}UMk0F1S*8ND;=)DN! z?A?z$1Gucgj>tUj|MFHZpt*jSWeV~=*m8p{^09zU>tF+E&mhC>dL7a?v7dMI^UFrO z*PtWp$&vIK_4lXEE4@;-1hjlTYAyrUUJ_MhJSJBaWx8b8~wME^k!I$q2bp;yr2l|TwWVOtw8wx1Me|wE2 z?^W5{>73v#ni3qmY{_Z=s-9=r%OCIGk33RzK1BBfg2BR`>ic`U%f`WAPO9r|xo!da zx(Fgp@4zRkmgQdfD6Fatsi~pMKGC@PsiAEa6!cSH{tc(-G7UpG!n_TBa~-VuwWDo!GzAED?f}c^3Q- z`qWu)M!J<&w=PkTSD+^%NrdU*4Nz6Qxynomb4)=Qp_Y)vVnFL|IqNBGGzIft{f!B_ zYx0vrQD)7`wg_CiIOvDPB%ZCdAX41d{oYBHa)SQEq&Ks9^BhzW**~q zfLe#DPDLm-`Mh;Lse?%DA<=-0N=_+h)Q~?j2V58clyPgovv?y4;@ZowK~5vsAa`)o zU3*TyhecX60nMe|?xBH$S?Dm+bFxPEhw72J68%=YRD3O9r8ZMavi`lm`(lC${huvA zrRlVpQ#K?WQfG^g(L8q3S5jG$vT3?kgiH6y?OFlV@rZl47>C`J074b<&v>uUP(?8cp| z(LIFSvO9Nq>WF1|Fy^+V zU(nXS@H{ymOWq>3Hx@Ooy~(dJqM!@HM$pIEVqw)8Z^q)DF)qFH)im7Y@5EkPOL!O1E_hASfLxZ3M8LFq4%-^pdvy=p$QX z9DGIX+;lDyMVFO5OWGp;6MV6^9{*t>Ri+^hFmR$r15;A68KxkSh0COWS?SO}d4FSU zvjq?|wawa3$C#Rze;O9#00!vfyE4!MeGnkF16b(1_XTPusrSE$=JFIb=5{Bl6jmzq zA)ayr{kE6+b(TA#nd?h*2^$?AsJdE4hC16V%TM0KjCBy>?;4nHA0{(Bh?le;f83iW*UpigZbyH4zE3W|b%LeAp;x+& z?jd@)LCXhl2=r-2S~7JF+2AEO4&w5*(Z~myknpfNEOFd5qA7;3t3Z9c&`twspr5e< zi=yu{zeTUagX+S@8%;O4-)WB4a#JRtT5M1MsjOFMV^zw7umFwtT~*c0Za?{JLGn^ zRWJPN*7xKdRCk{q?03vWJQRApgd*uI+^WGB$df1xFLs@+xj)I6=iV^?th6B!I?6=k zP37DHYu%AIS8RbQ=M7|pg3#z?k%3p+q&(H8j@JK5zxlg}ReNBejrNqKcm?o+L-xP; z$^!BA&Ge7B_{gB4Fu7L+EF+L^jsr0#W9bhw&`0;4_|Wgp?#wl%&ej2w(F*O!!poIB zU^~|Kzd=oH)rtAf99m;w@zz_#y=bQgR)laxrOIu?V94>jTHIXkhN$&&YI6@EC8>XQ zy;kFg*twHC!sND@y@usa@`#4m0jNfBr558qdYD;p*M6fN0d-IPG$PT}YPODsD%%=i z-Q%6OnQ!nd1Ku5Oxx(Ek($y5uYn~PVQomr$c);^so8nnrN-#IhR<1?S03Q%h%8ttV zGHn$B&Xnyo9dmE?6idaR)2@6O0$oHn0r$1kx(vY^#2CSP&04tb<{p7-9D&S(%*>*@ z&_*!42q&Z3f77JyrUmTA7ZwCN_UNcdRGbr9aZBEA*4V@uerTJW^E|gYcSvtUno6>N zI=L@DcU{N~vC2Wx%eR5u3IBG_Z0TM!@xJgcY<_gQheWC$OqK+}d?dQb5@VJ|;T~Ma z&6l;4MDJ{T`S;Aa_DvnL)Z0Xp(1DffJ^0R-%^F^t1G61br~VtI zgH2OhS>_dmC;tm&$bUjf?dPeMCu;{dX;=3*1pc`mhvB3LT=gp6fP=;DQR~)fy|#+9;NyhU3GtW++wwp;%SpFI*YeDWZFe^Cs}=?_s#O$ZQT=`#sCl3 zWHqdbB@-39vCTY0D#8jYTlCmFw<;hS|8wvncK&>CA;ca|f4GycsO_y=@S*sezJ--# zZ|iNFNRF9<9#FW{h4I`}TDFB)eJy_M$ClhpnHjxn)Mwmpbs3OV#I^D&PE z>c3>$B4K3#UhF-mkn3vA-`L~o&}=Av^~-AELZ1`aXlibwptPN}{Yak<7&xUVRnCj= zt>10OnZo=b()Xkt8&YofH3U{9WTV@q&_xGJ{YReHs;>R_z>GpupR@@KO&|p|36Bhj z`LJ!YCP!ViEO_57Lk~+3GOO3RHSD#dEb&RuE<3m-DjYLfffCS%^CWj1_#No!aC&E5 z*vrW>S|VFg8sCfRo>oRGl8nMF^@*->N~miL^|8J6JeXTjHhnn+lVuEn2i`8X#sAAt z7yvli11NR>cE=VHBmv8p#JGS;mkLCO4cPmXXHKP@J~{O1lm9sBYlEnfEtdg#XnN7X zIJ-Ne0$_T~Q-eacbf>49oBO%lx&7=FE2DDZCBBUHd~Vs-7Nl=eO5-r0(%x)AAGDS4DeC*Dm#9{=hmgQk9d%@Nnn&;egELsCd%p zzwS0KFkR?H!H75((d;R!3gzb0eWEw5cI@=kv5V)u-cxe|r*0!Z1PLeVw}W(cn@=wm z|DJ4A9>b{?jro^Vf)m{qV~Fg9d%hIawsZvCZ~B(8mB8y4DX2e)8SW&^$jSa}xaM)s z0j6{GN~Pz(_&{Q7L{63n+Pu&jGUh_tp>e*!p5QWb1$e{uBWxVb4xSV+et2u<4d`e< zO3E&Ke{RU(VB;}t}F z;{BKv=6{*w165#MRZ2QDk`6A0{T8!Txz%*Pv!WN|fzujElbraZ54nnb5 z_V6C+4Cg2o;YjkW^klD8XjbQz^`ojhJ{7_9c84`H*Wa}aKn2)#Lzvf+wf})XpI^P^ zf7zz9?H74}*`+%A+k~k;FI5HW3L(q%2=M><4vP)bDX~XbZXz>3`zvLG zD|#)DI%u4cGS&YW<^ihn01cr%!Vyi)!o)N2^0|S%yS2;Rcs3t4KI&gqd+y6%A2v9D z$&jt<;)O0JvIWvw`Q-e`J3oUq;j2ushp%5*vOaOB+$c(2ncik@?|xgtMEi|%>vben z0YE2~O-GBj2$V0v-PRnqnu=n@ zKA2{0p2QEVwC7JWTywz}-bm#FMxV3Ip(?laiHxG+cQ>d1)p#uw0IMUKWeE3!yd;4h zHv({?ie~a~bFT;ETcInJwjQ2BJ*)C}%>YwzzIBGt+r3nfc)G!%`ziDjV0U-YrDoyN zYOQ~B+#+Ify?1;q>~ZG0+??2VQYKA0y6c?8!iaur)mr8@q|@wM13X%pHg`O4HYdaF zy>N~so|xomt{R&dSX^584E^Y&I(2+~U)t{+&rm}}JPNxEYg z2{24Qbu%Si{uF00O_9N#a>w6)^9&AgymE}0%(ZKqL<)|Pj?~&JL|Lr#3wLpM82aWzM)NYKy3&NY z+gy3c;eAZUXW?0}*Zt0k#9a!)D%E}|R z%0=WAPyadbs%}8ihIf5*UwbP4EB37IqN(?k45Q1EPaQI-`5@zFOODmzd1Q%4M&nrV8>3C1&;5~X7Ke*uT;i(jH9m-J(^ zvz2=vU%>32!yi9b<#T#GyA79%aQtwbnCT0z|1~y6Nb^@QqgWc;PSmfL&@Y=;MbnDL zK+F}*$9(Unw9~odO}(Z^C`^3uF`H}+s-EP{I~iumHu~ciVn;}{)1?+fPPd%huXigd z4eE$9(v=2Vc&q#(s3tYTHLd%nTPmL=S`#2Jbp8ZQtEneOt-cZNnFEK`5}l zC3zjZ?(F{DK=JXMkhI+qHnr1tP!H_!=FaDcYoi~5okzVQUa#U=SD!FuLcQu5!iqML zsy~D8@}A;>estan@_(c>OlDi>`GkYoCu@3a$LQv)sQ}-jOczc%ujmHx3D4SM-mK@M zwbN|fbbRLuY*-o&uzMWn)#gY#8YKL-6~U}i$O^WPVC%P!Kov|mjCbyV@!5kwgzZiBUMxEpxjHn54MTS`po_wvc&Vlbtex`ZmFM7OCUPZf&~e7fCyVlfEow+WW;K-#aC-> zoHLHA(IK~UxQgg914-nQn?lhwvMlqce`+U4atPp!Zv zK}rL#1$7EXD^}v%)9yv%1)o|`b3HJ^$B|gUt98zXcrq+Y#c*%oK>`y&qa3J{^DA7Z z#^SD%^=b0u_oHAqQmbblRwKr~;%}a^_e}?hB00~2Fbk4H1;f{?kC>SkDR66WHv|Yt zhOd&8Ch$z!h$P$1p=={7i(gI=Mlt--^z6FNQ%2yUD7Q)p)HC_2&%O2(*rXSxMRtT_ zgD%1b$37QVLDOq6oLMjyq-p(24RP8~>#+v&ieyiM4#hV%8qTRbdj^@6#;=&;JZFum zKNMRi*C>@2bL86e-{SJRQz*VqbQa+#OVT=Y(qq`Lbur@CuRJAA>Vorxya1&s16jg8 zuqkRffqA~U98ciN2Wvk>i8=$I6^M z$$sNus!&Y?Zqvo11p`8f94lT&rAEqq%3PJs!pGkrbOO@LtIdf|_%#u2Dj)ywm!Lkg zq47k^#4nLGUEHQSQrYmNn5I<*5K>zw7|rR{V;Baj_$rdZgBGqywjW0npIu(ykffB> z{K2#c>K{5ERl8ko>h=J;&XcAzU6@fm*{%FUw|6SMwx~?44!$5DNg=^bO9AdrJ&;cQ z+{sl^d<^fSu}0`5+C9`ieY?2N^l40TT#Sh0dcd~JWL@=7mw4L^`&x3^u_*1Y)PohfrqUQfb^pi8i);^E4QTBo>*CmTTsNnn!{^wCJZ5+8;12 z59a-$@P!jOi%90L-?7^#@547{^y(YG>BW4`|E%PuaOnu~N_-4MLp#mrR_a;lf2ZDP zI0n2gI1%~W*RZ7ne0Hm9=vXdEkdz$?5x?S9NC7Vz`lKTX0*C6h*d(>h1~-tylrFW( zws{hm7Rf5lM%mxX3`7ld{Y(%dn1O;da40fk&ncdkGjO)h3XAyNQ6FKhEvMp&Von%e zCwLf3G~@X`b@wFtLNMYR%f9tYi|Hkv@KXM9dbvOt8U-GDlb?zdmW*8sS>3aQ^Y8F3 zm9fw=XIQQes%j1B|3|>y0b)9lF7dO7( zPKDRsC15?ptufS-bbk1^(h9$rIbD{mM?AT0CRd|Oi!=QS&}#gPJIj>k`+;X1n?nh| zhB}`Eccw-31~$=N{~maeXTdJ1Yo^EN;oUW1F-cdKPrD-F0M5f2iSW7^gis4r)*ICn zxu>g*g(fXk6tK)>H}Ix$Y6?|l2eNc004G-z{Ml})X68)3eBU-nM!HA#m{zL9EX*lA z;lY9tKlTC*G)(Haeq5S6Au0MQMXkk~BqqVh*=1<4J$G~%{4eu~D1_OGQEE|sjHZgD znzX*f{Sz_zFlu&mWj%!^!oTeY73WOIKtYX9NPfni=9>w1v8PNSM}DPg{aEXYk$!rG zt^szZ_}Qs2ni5!FMdS!(*+OVXNtq>im&cKU+511pK!6Z=DD+mSYT+^;vYEDRzN)Rw zLq~RVerq}<;*=4r?@gk{DFW`0u;ciG=B50+mll_O7cB-+BJp|f+Mq27|c9z7@ zsS!Jito{9{f92|ED$m3*T%HhA9qiel*13@XRJsZ6@L(#Vvpr9ixMVR zYhNR)#!Qc=a&-CFhaW>?-4QFFajWxpGtqdsv@8(FaFvp^ud72PZAQr{WEo78?WtYHonE+YyH*&eWy*FPL#sBZFh44Y6=qLisr+?eli(i{vBiamOQcCzdU zE1J`D-qcj~K#^edh&imD_1hw4ZHyZ>f?a0XkgIm+i~dU!R;FBx6-nM8+#0sK@1PLe zKz-E9Va6XCV1{9M#(9J$u@&UYkjUpM&nF6^yPv@rmKVv~4FN;^V{Y_4##50{k-y#^ zs!!iOMSbXe_aX>qbcvcXce1@3r9(4iY!|#b!SzyC2W%lGOw<)!f8{H)awL>wk3G7- z$eW2WogLyeu&0@b7BM&fHmGZ01C!C!?;HLOpdvz zrTCge$8J@HQIaFJq5yv{>Dc!vBO5n3l~Ln8iN;mlk(b#^H!qDh*J7FXt?-kVKZ{T6Iz=w{F^BwvHY{Txli0n@JnCgx z{Qk>*R`cuV_}26TyfM<}Da?wlT@U>;q>a1l;yo{==)m?0MOEa)^}&HxbL|9lo$C5L zQYRnQaGrLZdSL9cwLVEi;YU*D$4r2PNEhiafCI`+8km~GCHeQw#@F!{yu>Z+G~w1O zhS9D(NbUE|*4@H+2~BFtt{^P~mXMCx=q_1hbKj|%keGVD^oWHX&X|5nv%|q5qWshD9mh{SEL0dcM7JB|?VOp}{4|%2#3vW%Qg5#~S8J=nM zhqx5NfO(ni?x)1Oqk@Dot2<%5&9XPgyumDIT!ttO&Ge zq8&wJ7BbD>)K+&Ya1M{+Jw?2p@KYe1=CFG<$~(DAZo={u`K}~R;w+I9?dmw`lS(2I z9YP^PyB!{{>@B7h2oqBWYcl0_M^W%BSd6D%l>^A5O*jg?pUi>nQoM{NyGH%m>?Lltz&?slfc)dX8OuwTkQuIvYTN^6Oy=RqhI-fI#mn# z+2W``Y;l%TUPO)DV_WBDwtTfVIiyvf1plEI+=IZw(A{5rjES0=HyEx{xLo4g(wOZ6 zf;dM9e-5h*H2hwTcTKBcXay0Fv}6f3KOoZQpj+9aNUAb@E1D*^MvCh)_Wa63Fd7Md zRUeGW*_yf5}W{ym-tBte08kw45I9CU$}c2qk~=#I4d;=3CaO7*j5&9~9)6 zh3DNpA_4#oF<$09ud{FE^fcx@X5>wS8|hrwDK8&VPfWI$-{P#mp(E zv~;f=0EG9G0Q6udg41SYvEd9COf)E~Cjs)IbOE(;3)4rK?U}+cP7#e$tUkS++fXbg z{S{q>vm_pc-;!_jdgq*-zC7Vr?b9c`i)5;(D7StL#w5fUEeq9xMqWy@BfnxsQi(__ ze7ko{s2y7g;m}Ip7ZhbPT^%VZb0X8IGF|KQjI8}LQBa=wvaoFU`8E1f@cM*qX~^PpB1 zps7m52uw}$fKDABb?dcrehNHx5y$A)Bup`O7OapmhyA4|0JcOo5z6*{3nTI)_!Ruz zJSRYe1Y3F|_>_ErEd z@~MX&3Ogqe)iS+g`AV5}*#Xv{j`lN+I@9un#p3-awTh3Dz`zJ&FYYaYg{vz#Ssl9+ zykhz#^qDN}&e}3=t@*;12lHN&RnuC|w+2iJ3^iplZijImD8v&{%y9oUK;V7Gpma~XwG$iBXAoazU3Hc0vms`&Uj@XELzI`^AbDI6J zne;r-h->_5l885fzFyxQmDU)IzdQkb{eJd7ud@nAp`u?o*PqD-ZSTH~Gq+<5we)eb z%?t5jE3-xe!y?GkF6P@$(DygZ`1E+?HpwW{pG2-=~sh@>G?E>YeQ_WLU(Mv>#rf)r^QQF`z_v zE0ovTyj*kN8%J2(1EI{N+)^c-uW&p$J2@Sf z_Ps|a8L~bXRe?`7e{?VNROTLV!bU@`r?^a)e3XoXLTy$89wY-h6$*|zjK2;r{5#oC z1HFcccO^#&9mL2^Q#nCC?Z2_nP8rg`@~LE=zsxr%uIzlMFLh7t+XeWN{f;E(nQ^Wl zUb9R2k7S-;he!~j!Exg)rw~w6-pP0ob#zH;EBe6HZ1S#;;^>@)@#0_D7B}yMjNO!o z9AX_YfY|=$g9ceA?GTP80E(QK3WjUhPl4`VJDeM9duJh6MqUUammxGwNmaPHfbz)2soR@nCC~2964m-H{!#;v-3Er)tP1VdK~f6 z_06R14-=e_5T-viXguO;?*8OC5%5etJlVVN#<1O?D@^j&jAf`S?9mxm6dI5JsbGmp+^BrwrnapTneja`91m&E|4ZQ5eOB7P zh&P-uwZKtE>ce@BV0yUiVmwcptQPaO194{Q1ma|nok_}pc^}8=*(klkAl~ZUDF=#- zyULKWa-}=*viJxW@mB^2ZT9xso-s1Vhr*xSIN_02tfmK=_5|la{qAYNev8=c5`_wExa4d7#&= z=WS@MtXL3L1%?SrNNGO(MaTsDcMGzVhDF8M*VaB17KTSjrG}ym`ZTzkY)gLvcPm~8 zwE6uKjqf5%A@%iTC5}i!myQ?UwB2azHUAE;y~(bx`zT^14IJD6Av~Gs?RHjnh()_B zGH7V(UYy)C6kut9VbotcnLrprH*t#fW|y0ra-K%v-!)+hEb_akrmQt@eIk1IxfF7n;l zED81hDj@ar9IOruIKqJ%hL1r}lA6f}cmCR!_GOgpuvFxS0ho0Ek;{iy%_#t~oUk`F zTYAC^VhfQk+8LAl9kKWI!+50_sUmPdmFLk3jw#qvjl=CL_HK`qy2}YgbOA^c-2G-Q zKw+Y5sY2!17_Vm=7Q6`|dbihDa+^L_z!igoB0#vQ$8p5)+d5`e`Lcxtkcw+d3 z_k>-DrwDrsj9MB?g8zTv*RW0xd&!H!sNWAgrMN9!ve}P%-s2AK(jRO>Yk!OK9`yE? zZ)MZ#^{0Q0TTS-td5Y1{R#mGv$wl_Bbv7gN?0~nN7~FabWMQ*7LFU&HlvyHG=3wI(hri_vnjyYG=`R!fRork zQ2iQzRDBqakW!91{k;l;N6iBCLt}{*<3#zw=gX`AjQ7kX#hX9~ z@Yq~)*$^f|fnh`DbN1yLn_AoE8edQF;g{9bA4i-i#ZSfYVL?aGl;Bp~{sQ2;Mm>S% z9UGi#y`hsj*?r3I9BowF+^PQrb-zUUC+yIJQ$^D54Cmzz*NYc(^`{}oFUxfRyD{?< z&4u#|Gbc6Etq6-h&kH26dsocsuSUP0f3e-pzEK@##_IBSMf?Ay=_n-n<9S&pRtDPr zCW*Mos#r7D(N6*SeZ*S}xL(s7aw|3O`AjB2SNuGE@+-07l@r}#G@h$`o-lpX@X;w` zJIPefdJj1wa=-hgOQ<1WU<)}%N@~7l^+_3p^E2(U-1-SsOvFfB4JHQS{9_>&&j1yH z-l4QP@I95lt!U_`3ti;#4gXO0?;pd2fg%BVg~D=qM~uW*E3NdjK?T zQHbi)?f z`Q38DzTIml^fyp3y21p6!z?{#8%2_b7>%9L=Bn|3lCf}h5EB0o!yv*&sgj!(g@U81 zThCWRdAp%&So=1_YO^AhHtGG<_+qezkx{Q7NRs(s%v$(wVW?cK=d!pTnatFJzD z#s9%-HGdVpZ;Kyg98dlK^Js|Cs6o_m6RqE7FS75}8S;2#7|%oxLebNk``9j#b=A_j zqbQU)7|#$v{40%(V_7%ud0=Yy-Wbg9maGjpiDe|X@`t!4;iee-mwj8bnaQFan(p-Q zSu##_vw5(U0|k=t9Dm(iwr@+j7|o^Z{Y%92emw-|mHhO!{m7EiT<%G;@plk@TQ{3B zR?3Pf&_Qe-xC^l$39;3f^Y2zIJuZpE@+AAgFDfBZy@E;+@;i%>pR@u=I=e zU*8HwahcA$*p}xL(nurUBbw2{Unph9k4Kbxp3;oric(J%bD3kUxJ8DH7|%Wsk6S&J zTT5LR#$)@0{c2x}SmXZ9+ir3bUmOen9uM}6m))G8^T=0G4Ydt;8|x(9l7#IIqH~r; zFW9BGL`siMq#F9Of6Gm1K`6d%U~)cT%t4m^#Xx-`Zif}MnS)|1jW4bA^{~mhzl5Uh z3tuL8EeSpQ%GQEI;WVb#A2)dZ_NHisDSUq-i^%Znu&u_%Rd=v)rPvhHrgjR~ew)WT zXMa9)_b#Vym!}@?xXUCpdl}^k#O}_4yu-fqdK$iBta4-YnC} zI09Q6d1iXClsL4&L@xtoH<4tI?ISi)*$y(7pc;@gXL3N zozF6l;B>gEX15`ZmeW^$hCf< zJhL?S6EMBKyvCJTT*x;nbbPl@L0RS^`Q_%!0@!>X!Ls`JOr3l~F5-)LYqwp^{vRD% z-f*b6X+=Yi=kzuG%0$&mGg;gUf?cn{Hgrs{ue$|BG-_XO#ZunkG(9b3qX5(mpo@Ux z>y3riXYZ<&S}6*b;CxY$OB}yF`Rw8{?&54uXeNgJ#Nxza9>sr|Qr7vpHaJcHD%t5g z)duWkMbmZSH6r}Vqx0x|q{)GWr9|b||ytybp|d^_5rQLEBas(X$sR%#F)w2Ln}S73WD)9M`iZb|{wr zN7PsNMcHj_BhAnfl7n>1&>$t9(n`mWBF!i@Al)6p&@K9iq?FXq0t1LB-7!da*LVAz zbKdU{@P~8nz4p5H6>Bp9`o+^`wB`c5M=5qAGrtuRJ|mKSfaNGEmR6ga&bxBY0wS%d z==vAd6oFBzeb9n*i_XvrP3yil;z~69Rr~Vm_1!EuXU?-T)l6GcT0U>Azy0DQHE<^0 z6{lm;EFWu|cJLPa`kw_Pf<5jRn+_hVjg&vT-ADe~{rKu-2yI`}+GO?kc~*bro)7Y3 zz&9=ao~c^}-@TjID=>0(mgFxSXAsdY`lwid*5q@UF zRos_@sc?WXPUC=#(?>$5Tx5h3n7OdEB1lC(AyMrYv=a% zTwC6~)~8;JjE|vUB}ltXom*}B_#5sH;&{9pxdX?4KS>gYqHtiB76ZHqL!|_$0Q7PA zXi04a^pF9{8BnN><4{?(*?i5$Go&wY-}?~@()_Cn1ExW3JzA2d_t4)(SsfteC`FnI zJ^2)Myb_S2!!6qcE954~t^D`iZ3uX5W#PN*x$UCZYqP>%+x162ayg@v*aVb_>Al7i%7a5$ zCUD0|{{4a&9%vZ%amnO zxId)Zm){bzCDdjfv#yXePeuD~A!%?ss@KSX+sMU{q!H(>F0#o`~NG-ktV*$_!~8BeCmYkFfc6+7+A#RjneY-T@fo$T;oyZpIX66H@7Y6J_7Cs^5r5cb2}N5A(qt0xgr0-3#8m!zlNVvA39$SwP#a$W(E4Vx<6nt z@nG!p1HO?quZ=UePSt@n(8!haaL~q`2Q7~}D+_5Nk-4wwNJvOE zkj}fyFSA*DPf+!)@0*(e7YpvWiOAB7g>O@}Q4_X9!gt95G(*MLQF!=uQA2&y-*e(W zAK+Kw9LAYfY*Qci5>*xCAv+9*Xzl7SzrB4)((ks|9V6$A+T)w8v^DP_*;7Jev%vxS zSVvVEwNj)@)0518LDc6Reqs52hfn>A8j%l1Nsq5DB%(Xch*l^9d7X!x=%{ONr#>`B z3zur41S?m(x&W#Uma1qc9*d0kTs@$^gfZ{L#*N}LA`~4K5rSB*nn z>t$wF_*%tl7efKyV)zO382^<*h+p=B&D0+Q?m5=avn6`Amglek{6R|nSS+%7F$#dP8i(-2SVbMhFv2t0B&RPRYN&ewnHAz!;eckMsS( z8?S`wul3_It`?c<^wG5=oD%mEK!;qkAt?AD9Xz)JI*NEzWQ&c|6lHhl?>?2I$|+J( zG(r0neaxP5LjaNU6z4{F@VGjSZPabu`CkDvb-NSQeEz7K(=fRRA2t4=`Lw^=3jO1F zft9a4S9^61;B2Z9?Sh`gW=W2O1q$n;-Af&1=50AHE9lsI+`lB*b8Clook-jIOB6ph zWZYVKJVfVlL`QKg(P=94IiaiTo)m|9N%9v6xs$lzzT(GLcP_iH_}te~z6-c%Ql=Zi|F((0AAp?nulOh&{h&PhQQL}|9YfD&RIgUi z*gubsnQELyd<9k0;<6T&Z>MzfKV@{IeK9c!xv*4%6z2ZHDTf!`?#V_Hk#Y;wH|?R9f+CcZT* zBaTRO0f^A^T)6)KeSxtpk8ZL@f}`Blc}5H|sm=1zDfG|Ii|v6ElBU6Q&*wcwg3(S# zgjJg3?1Wh&SBghS*2*7ZLZjs$?d&uyOI|z4!>cXLnBed1>Jp+WM@$h+al#uyq*m}F z-^}z?^W~DVtIvE@LgfGL6t3`vR44&z9WqThYpJpx*tOCP=%XQ{Hzj4cANvRUrF8wi z=pwXRm;-#2F~(Y`|58kPm@v4McbeR1>#9)$V`%=8_Qf*_0u=YB+4I3@p030uC3m%v zYsTu}8r%7U-yOkikoFz-j)&S&3S-h!O1{Ad*N}Y|GhDhsyX4&#YL2;%-=}|J?tkk) zK6dY&)-ct9vm@E4A5Q9bnv_S!p=C6jqgxUjj;{8S3J&h%;{0?ysvDN>lTyxXY^K&v zzU40n*b_>K=cs1h+!LK3O8#Cw?)%yb*ecr*e`V-)Cs1>_G;@@T33DXMv4Yl$C39H?`n=myXWYk6K zKP~g$`^yv)w>hyC3)f}pff?kj6i+r_8v7ndYt-MlW_r5NVcE_G>uNqa->nYc93Nv| zFA!h?0NJe~l!tvcxpQOf*qDnlfp{-VDuUs-BP{Ej=c=`K)3@Wm!&vAK^Tfc#@vRPH+4RP!sPQ}p2dbhp8$u(7YT%W@p%e*^jtSe8 zZzQCG83Aw!Qh$Wdw43I-l1t-SenUoIYK4aRG0>DZp%{Ko%kK!>dN-$UZ^n9YM7c;M ze$I@#Y|JPDp=xXlM3Ry5(Oq`s`o@vot@N@GDCR=mU?Ee30!_KOz~|A&p?4+!xyV7H zR)fN1bXqpT%LzEU@qn+e5CD5K2;&RM%l({GIxaz*W{w5sEflnvmDpiD?tVRW?B=+5 zK@vbW%SB0mlaRT{DQ$28;kjoXuau37+|QvP>C#P)Rpt^`LEptqG|9xZk( z-&PhMLOO!Q*FhId{k};r@!3;6$g0k$52d*K9|Sr(KP^0s@WY}><6XgCw$O{t@+xSl z^Fzh*y1OglqdqWJG%7#)wo-dDpH#Hgc1lNuexd?@lGI(s5ah9fdN2EQ`W-3$Xu4-W z)=gjlV*e{8fFQKJqIXm%5GHXVO2zoERey-ybZFs56%*3N6M;?NVX9!9Sh7-n&~MVe z^9nGQd;9{B&r`7-8ZOOgI)9suR9|R)BW_lg?fn7xGc+aRvw}|j4HsJ61`%zQU%sGa z_vk4&tU*63UpesihDZ;&ubar?uRi!kSA>oOlvNdgaaR0{D^0aQbT)TeIj`lv2!S#I zhYFFyK%X*rx~eG2YSX(B_^Rtokg$00ZmTj81#tGCk*s8r$T+mw;}@V7;aLVqw+csh z6PFTZZ1mcp@@CxU+&kaibw8{rk<9*-pFVe6h<9uJj{0hzm)f7|(kyJLXgj7cwNtzn zmwO}&dQktnW8}C-s&9(C3&(wkprxaB3V0!VNBI666n7E;UCSC4#B7+SUWJO=oyX}# z{D%4;bByUw>@@w+NWKZo-&%(7`C?n5y2`!$_)JBDzqH!d z5K|$ryvRoF@jUKscn|hy14RjNiV6XQp0?luQ_|uM`R)-S++_qAngJe&*ZAe$B9Ysm9;B6h&Y zvE0uq(2Zzja3pc0xTZ=jI8hY$QF{IS9P_Y2Hre~*Otc$Q$t(-uc5NM z`G}mOE9`gh#!x+{_GmHUi$R=A;4q9eP7DLQ5Pizlh^E9z8E?my0V3>x{;16L(r&9~8h zn`Q7};C%EuRrQE^t*UqQ|1j5FGUjnS?W?ru4R|%Lmkgh@g2YbK?v?^aUY|7L?DS5I z=%@4PY?muJ`G3^0tXs`1Uva)TwojC6!(q2eENwg@3 zLtd1wb2WZ6=AabiIG*cXLU8>>_ZL>B(}gAadUiJH{qXY-VwVxgo82r@a{ueDTnd1o z^(D+;!aCNVM^XV~PF1W7)IOJF!LAOqwIRmgH-Ps;(eN=recnQ5DK>Z7*e6*QKNyK~lh5RtsFC;*R`% zPiT;LLby-fm=?+brNTrfhzFwuoCKK~%VLHL0(?RNPh_w@6SSVBni5GVQ27b)#kl&Ae2$@{Qb@BAI!QX-R0Adt&a2Q-&#%3W!=!hVV`$wJAaTPwOCCw z)cq0Cv!Vb5ZHji>E!T}tJcJzgDbjo(<;}?+C9ERbBN7()%NhQAXe0oxQ!{+}6fcC- zTQcXoSJLp$DSl>f*A0Hl>WA*$GAe|={s^I|CC2G@0Y4oQH;Z&b{Or)NO`gj<0ekf~ zor1wBSfzY;gjF^quiR-VdgbQ?-Zp%EspAg%d7NSMdGA5M#PV@=_1gP$C(MRmWbPW- zbOIu*nMkGid$;9UZxN_R}SJD#h-XICPn%>sllZy1~9sbcPdQLj|z_2-I>!P`|qOi7g0>Iy6w2q4= z-Q!;g>s}{K1QB5^ru9E6D_C4%lYa9iv5#DtL8pW?k$%4pJD6TN= z`!7HL5l@&-L`kfsAAHoVx!Q7c=w!Gc%qMjIr~e7D5^uXs4Z-2-y4EBfK~w7@{VBPL;T`_m#+cUcUYQ_FL)Qqc5G>LTByF=O&!zYF;wf z#Q@+chT@gX4#FdqBQ2y&BpxVM&wJBEeWjP3ec3jjIk0q`mp7(#zy(PBnKdAk z+unM7&b1V1e_ge-fRVnmKonpr0-rwp>BIm4O@;N_bXkPPviGKddSE8EDTTSCJ8@cN z*IB?PEo!G=VC)2=)sX-HVQw`*mv@tC%5TH^>oe04jFTk=+)E?GP#1Ed*&IeBDQt|O z=AQa&q>cg890v_r;Jm%0bQE3K5)bm2Dx6%pc`=pMN72=v#}+rlVRx>-ydctZAgf8U zWG?K(-siJXQ~nF@xMOjHZ7ye)6u?v;FlHjK!Gpqo*B?)KY$4HyHG+i?%m?I5bWGhi zi8`lhrsTI0m|uUvulYm?dIh^id*qK#{5=_raU41=Aw`R>e$yoDi{Vj^pBay-P$Bvg zy3OoFZp~$7!v?RpZx2nfNIQ}|eR)|h#*0yiu$oe5-y&VZ&^|${;Kc2htgMqB#0_|u ztsVb65Mm>N_WXswpZBRB-;O9ag9=jvI2Gr0rziPL!vZsBD6y}TEvqrdVK{u5*KJGu zQB))=clqxa-gfDW2jx?JMBdPCMqE$2kgFQ}s(MH_@$^s4tVPc|{d_9@d`FFmi4vu4^ASuCz9$C>z;o{PagFzxT4KLN_+Et2*o8Pk755rd34lQT(~PWqXOXf zP*Q@bh+EyC&!2A!cepyk`lI$`S09}SWeWbt8dx$o3L3>Y)*KJ!ijaS&U4Hodvazxz z2MX6p;{PX+MRMsb9CP(K&4((UoQx!7X|k^ri&)qHRSHW8@SWmtGHvn7qvHUcVuH6& z>H9{lU+#1r<}7^Z5eHZC`pZ=hzljb&_WZFKyMZ&eAQfGSqd6~)Ec&~51qh7PWEiFl zda%Q(RwN(i{+{BSOj<3Szvo!@^8_j;=3K4gjW+)ZzaHFQSnl|5SYnhXKzr*okaE9U zIAYKLYZZ=){NBI<>5gV-=(f8TPV3C|qJd8S;UHF(m6bsGbX)WNhotIbf#~GNyN6x2b%Q#ar0Z1mW2}8>`K>)uBnfuM9Lbaj+D+gs-^MBR*X;1+6#V?RA(~rWOLgPwBPDy+K(Du8zx<5L`TW3T-N(Ek=XcgKN(-iV4Y~CD%u0 zYuTUX&^wL^Q)oWnYu?f82C{aOrjq28(huEV#pRAG(zcD-@h*1sPCO?*H;&Lp@WJb^ zp!0r!OffymB6ECX{fcQ?zlo9OI@;$6&F1B*f}i%P3DLFWM)iC+yi2K$=UAr8r%Rft zqhHp_Ev!@qxNPH7@IV@$T#2#F*MacXV=okQi)!I zn!qDz5sTj&rniBIF90Y++l<^H&vf6D9srXUSgp+rbMJoXiyTE?;SM&!@&0kVL>+Ow1ogUbUDZ3x_pY{aFzcBU9#c=? z)o~1UC3(Y}w5}w4IgH~S$}-~&3FXcdWcznn^{|k(2&Smbj=1neswdP>$e&PI8eXB^ za+S!~L-TV2Zvr8=IdC)j(QgF@#)cDc*5nOFO4By$`ML#k;gR_73qOP(pGNvM{=V5B zt4o}Lb-eww>c}HY%yCr-agQe#u?G^%%aGNO4uR1i&tSOKLV?W@(XwOsG4x7usKeZs zN~@<#XcE6Fc>4YbE(38z3XU8L=WDY01psCh(;`fm^S?R;|B_O9bdaxd`gda_Z!=4! z_t8{;gQ~roWWzA=3LhtrUPEvu9B&M0{D8q}lV3;Xm1oH1mH7kJyjli>E3rP-^jevg zvQdr2+xqm48vXA+?viN=tDEylq|K2Gf`0zMD{aD>jETEoDZ%SfNq@9xw{vwW_@MQ3gq#U=_LPd znk?iF`h8hQ_yDoi=#P&*_DB1W%S^1cWBTXT9}bNGhqB?%AN_D9d*bxV{g5vO(p*X z!9CB;Bd<2CkkC-VbITLlN_!axLKoZE!IL>#3(x1Rm{qEc2Q6pl^NStxZ4V1gMZLY= zKg2Y@g?+k8#}6}xshhhv(Bc`=cVyTk!8Sr})=Q zFMPV-82#+_eYhX9hiB|m?N-Q-$C9|pi%fA zU5wqdwp7+vt*ycGLMgQ^E<2SYMs~jMRMO}%soW>kUsa?oS*C}lq*@`DrNhM5b&JABkYSCDph92gI48tPCr~dWbz{R z&#tzx)GqUgy1B3VG0TAVh(E@{u}!2(EtvhF)fo;%YlS-qg*T3^_xv`~GQTGE!wXqp zyupECD+tjNA$u0J!zKUa`>?|wuQO^G-y@|THb)je6MiiH+!vxXbqKuj3N6CoK=DVg z<>y!u+Xhe?27FSn+>nQo_kBL>hJ@xkFNx4r;)NKoPG;&5xCbBZl#VgBO|Oz=`^iO$ zewf^e>579ctlO6ex=%YpFHM4Yr1dY{!dbt4Lb|*%vv!ag8#-_65&#JVlN)r;@E$&G z?AqaMCM_8w*f(;&ryp-T~2|8E%^}BdwU^^HXZU%uAOxdm@T}1)Km&|L3abtpaNx6*~vnSMFJ_ z2VExYlW)V7J+r0!z#qIy`se=F;9EdH_uQ@!$bWiFm^h^DTwRua zX}xUU#Tn(7uT+hL?GT$n$1)4nU+uRYH5`-?0c}4X9CG}*i;(k%OxcLW9FT6~6If!SsQ6bFtM|=Yjlfk>;*)*l z449*JouVrXA$9+te{ z(*kYH;Kmd)%RgnqM=1_mreQMml17@_zrm0@_Ap*D_2ALs+U$kEIdYtJQ=Px(Koz!+ zWV-6@`JI1`{fMyx{*AiemLNhhT|rnTn|p5-cf+kxGRrCheBw-wVr`@Ln(u!rR`9-f zwnew#VI3nkvL zA(}ecHf9mLxiy!obmifW}8fJ*5O(lOd3!2aW61W^|)r3oWZ{?Ts71Cm(y*|1} zD%Y|5w`FUumj4Z(o2f+7d}VprY#G8~WXkvV4mgE*i~x%6LxY$&>5>zq`Rg44Yej@p zCpcXECo7Yvaf3Jli3;nHMPRAy%cP$kG9w`A6}F30-e&Qcer^x6Bs51#7)bH{x*=|S z(E8>=M4O&(zXfafvp-bg}WDcBu=T}gbU>u816ybS_;lQMj^x8~8U-T$zbHMj0>K%kgV6y0s z(h)YgsI=*f0x{QhieFU{5*Ty+EVk9CbMLB#&gn;=`Mk)1ol>~z*<&6E{R|KlCMQaa zB)HZRc(Whqn(7Q{hbKl52wRNag{?*}bk|w4aQu*3gm-X#Z<974gcx0hKyXJw&I18y zT?GhXa@j6mG!#2JR7OX&g=&NcG&e?DN%GDmgnm&jiEG~$w9G%(^cro6bQR} zo|r)UTMFJRj#?kRJ3L5dw(yg%FS*BNCLQ=tgewAAMRu#>T5AL%=I?&~V<-0^YPk|0 z7i?!>xbPUZWdQ*jN-xb}^?fdYdO8INrspPIEOHN;bI&okQ)c-+{(cZs)s(_FbMQcE zJET0CWYrp*9C-3w?1^Ni$8Mh*ZX3i;Fz1p?8qf=~0vhiXnv#CJ{6;-8I!l-oWkS(+ zn~1)SP#{wlrt^#Zeg8DYB_wN2DkBtJ50`emv_^S$vU!)h`lDY_b!jLCm<}GS8%#817`_w?A`lxTUNS5Xz6REp zUtg(%+YDI~m(dIz4}F4dF4By=`S^99nP`4NJox$Q5%O*Krz+%$Ir(CW(EKi&+FC_d zdFjZ==D?~2yL@|5r*{G8Zh=_@mYw!RR(uX#9(MFKu(ZcyGAUrxFbjl&XmYUnOLe1Q z+2rO^MifcANRrAI|%UYc+M$Li_5DTI%`|dr7!DhwEHPbS}a0 zRPfKV=lHJ5u#j6j9@K+3%D@6MT!K3&9OitwX+D2dpcySCM6qp{H4rMJvlqKxJUjIE zK_t(iVi@Wty+n_0yUvG=tk3wMC%xKiR@NNTxJKRKrRC&0#!D?(3T)k{`fEoE;!nJ8 zziC}~(g^r>02>*i6_VxHD9u_F67~M}Epci8p(vy;PDFyBR=_bfM4(ei<-k&0+v}Ze zOQ3}WE#Msz1a^fD7h)DjZP<3nNkv>JU~GVl7sr#PVUNs4ZPT+GDb3c8DuZeAHX45M z7wFyPuT=DyIg{(=7+Sv@J3X*WDADF#dhWSy%7L!zxo~+taZMHC6lkhFjfp>UD& z)zd`PN`dBrfliuB_RhF*%}UWb4Ayk7`#+A)D}c(R!4%$xn<2Px%}F`FBzZ{BG2aMj z^>E7BhJp|4p!u9JFnVI~4qS>C&x&+KFoA;f?ffxZ_G9e+0K`jv^xmAjV|&0h@@F!7t73}BZF3!%NmK)H-tAuw5Qx!bY<``6>-oXHYk3MCOU%6 ze?_a1A)5EBm9S`-g`A>Z4)+*s?k+kg=qG*aOW*gL6E?pYs;ymtLmgZ1T8eqR&4 zMvP$!u%E`MYNTifP|EYK^~;6&A2&a z@EGEL{w`j#v6&^3-b%jY}9#IZkW2YFPoCd5Z8`P0Cj zF@EFNNNl=?IKjA&9^2v42fVh&rjt zQ$tMuM1$?eLKVsyNqN%b!T*fouUSEgA~$31!G>+?cy(midF45Zc_RUcVlhUn8nY8nCc*dcXllBiV62}%GK zNk25S7OPOTM&FEnO$gu=(E!o6kAGZmrTtxlqt(&ahOT@+S64&o!Sn@?J#kp^QM~K> zDe~MM*XifrSX?EhpUp3(rnzlC9hg)hA2JsVQhDOa#6$hUHeylE)nNw6X|F}q;uF*N zjsYfjl|xhqw-LNGvvb?3qb1|tfps*#D^Kgkk-=e5faXDyq0I@OL-1mz<#MH+{3YZhXD&;U3I-4b4)l3)|_TqFlD zj_skd&Yjb-_)@z7l%n9#3j*}{>~r9%Dg7GNX08JKhS0|D=;W7Io;>UR=BODPLYJrZ zAP%vOiVG$Z3mC=naE@(7827MvlC+$1i0v^1FQmw5`@oT@9eC~e+-IR*QInJhaon< zn4m|EmEr0JU11li*70a>N-u`KTBhe*bU-+JdIXhYu4#x5%!z|u;U(0yPHGD^XD(gk z!V#wVZ4{k24(%HfqcxQ`sp~{T)fw9y?VqFQf-ig75Q~*z^KYYw7ceMX<3pWAZy0zW zX{P{f<0J9Xmx8W5$s?XWB<3Gs28n*gXpfOJ%f9W^0$aff&*3YF`$~H-z$kkbWh2db z9Y^y6lYo`&!#-|8gCvl&J@xDlzAC(`8IfW?_tEA@n0yut{{+CR|gW}r5eY_$P9 zUtVjonTupe;FxKej4D)zbuVcxXK3LTJTp2Ctj&F}I$r};v7?=72iDj!Gs;C; zWP_PrX5cT2VEcg)CO%!dbr(^5ng@YxeF8kG{^?xVSUbGs-LvPZif6M?5tD?+5J__# zs-GFo4kX4NdEnaQss+^ zB?hhKPn{x0{3uQ7;5u5bLOZ97XF05WDK<8fw6meXZQ*6)yTe* zN64k%ve&ZTg9}1L>qI=w0Uq;c(&b&n>80P7*EXi2kR$p@SIXMgyN-$j&eDVwF_F0Z zB3@jL!g7ls+lsz=u1Ug$MLhQHSlf7*X?^|1eb{t&_2_SnJ)N-FU+10Db?2t?Q~Yyu z@1ymt9ooPkVS(SX4lY$k<{sjx?E9z7_3S?nVggeF!)==;t`EVj;313M`Mz^YfzZ)y zwt_H62+{A6yZ#yGWiwIbyXA$GV2Xf`!j}DI~ z6>R#AgJME{$-7C4rCdpN3NCC=y?rG1R|+#u{Z2OhN+@Jn88-^afD!JAB*$?dv^&s? z&%Yje3g~hg?SLgBG?7HS)MGxd;sKz5E=W-T$s71QMD0*WbKjngVf+I$KK*@uI3;K6 zC^-i==6G<(D$MxJ+oF=;aQ<>mq25GRJqv4e2t8@PpK-tUTIb{YS(#0-Trsy?`cRm} z58lYYjj=O938$l3)e|Ls5o(DAT;1vO6^?5T(tGZmT#h+X0tmGM8(lp<>IAfCskTbj zQTlkWwTOv2pNQ31_ti?SY21NYXXGSdZ6X4nbx<$)$Wj2mIe$ZT-GN5u&wh8Q`I3Ku zt(yR%bs=CvQh`p`0+)5LrqY=zbFh?40k%bz9fXi~mQip(1NXL%Qr5)hgw zTIsX@@XpXzB3>}jsK+7adBkC|1C7ra4jtLyC3odDdCnw3N3b=l5da{6kzzb9x_6jr zY=iQ!(CAf6GNr}j&ysKMPQ!lo0bwhvbA$&Rk&nG`J(DPEzVF0t5sjPo+%`+UL;I%+ z%N>#xHIrkbEhCKtma2$sa~XT^{HuD|#B*V}T_5MJd+ew5x6bSI+ZQz?3p{Ov^6{T# z?2|wRU=fYhYCHcd8Sf6P-U?|8q?`r3Mtmdu3l)z&3czo>U3XTL>mt5W$1}$5+Bl0s4PZQFS4|I%@he~PfOv}M5>uG;pieYcx5(@n~nh3 ze&vswnl^E89=5k|H5>#8{*g+BL6qAbA8&O+FrWW``|V#pLVUz12q%ZCn8|tZxv}2h z$7A%Ki=9i#;}i;ACaxNnH*Hb{t0-_5Qy`*3M|Et2>!2*WzWai7o06z+$5Q34coZ6~ z`E6{A*XB$=;5mAETx7MQi7#>elk|;qIn8lb*G)#jXhCLHXhKF(GxdRqw&KBIL4=<+ zeKfG00)Og$0NYZ~k$K22GxW)HogIjSr;})$!gdE`$Rix&BFRWYKAEaO^7)n(A(qn% zi%Ci&+?1InAI2)>C~YI8I%zBpZX%uCM>c+sNJ~_{a#3WpjZheS1&}Kbt5W($W`}4+srfu1kvyQyzE)$>xqc~9sa?(t8F6$k z$NsjOzd)`NU>&ZXJxS68Op%*URv1qp3Bvtev?o{ZYj^pj7X^#HtrFaVgDE%5=C9X} z`%CA=nO@ud*s_Le$VnM)p?Uh(Vv~BvO8+I;Uq$Z>i*>WnK6uXl-{~RXKEaCYMm}{` z(h-FC*M+cd-9iA(rbK~=err@E{Xpll5u$`0)Cx3O@H|h%jx2?VgsiS?xT(53`@Y>B z#l=v}L#E}TZUv8@ajg2Q#Z%J8xDIy9gTu#$a-+iRiKq~M2j_&#PauK8mQDdW1`Jcl zz&OdTEs`=;{n$oYOAo{g(#{LXRyLOOQUW~kv>$Y$b1BlLeLtxF$=9uVtPJU4hh%m( zr%sk29vOPvipBeUWr8pW;K;=)ENoveL{R1tc2{3QKB8h~1q1e2&fIM~7sn zCJE)S4FqUobG8#r2L&Gj8D$5iqNpeR3jAR74e`FZZTDy=3R>Ul)0{u|qDk!n9?!5D zecx9vOf0H`IV6bJc`Y~D83#p2o60ZeS}uz$teL|(dHSDD^6bd5ei;U4edr6q&?xO? zC#WYd`sujsTvz0Q7)$*}CMiiA^A#HAa)mcB(I;XujgC~_WgEqfh$6-O97+H6d|{Zf z`3BA5FEfs9z6e!x8!hSz86Bv6^e$zI1diBJ{UHt30{u?%V zGJC55k`>pVK^;7&K56OulAJ7pwJ*Q9%5u4yA*Z|MOPRbNBJ5pmp()J0;J!-g9esz9`BuZdF!}jCasq1p_O^jelPUIo8;D^LHu~* z&@}tP^YKim7YQ$=Jb5Eh>wvMZ{+{Av>!cbmrh!uhuYX7I6pZmVvk z83ILY+ppkA3bd#*G5Lt&r8|xLC1mU$Oc-bUgU2$fZIg5fE*)@dG%p=>B=c2WK}}LF zsj#ZwHGVJf*3fzPpRrg8m5-Cy36#iv0~+w|)jQba3(T(o-&(OGIaUtdEo8m zzwWkI8Yiww-za0fT@#rG@8>Z1jI+R8k%jl~U-BBiSN{A*MvoK$k`^l}o2 z*$9)KrO~pq(83_A^+4Pp`?ZWxY-m;Kb2oEztOhoKbU?D1BTJKIKfV){QS&_HgTNAg zvEN9!5a@A8izzPu1~S*|`n$VR27{L2U;O>@04YyG%d}{QE-rK~$(lrnsn}SKP0Ra5 zhzU}65%0Tj`r>Z^QXpa&(f>hpP!5WI0?u$VyZTam*okG2Ha1?sN1lV9#_SB^Qh4pPW%~ zQ%179Xd`QmKQ#kaCku{jN0QC?bgp^Yf{l26<8yFgIlCYm5sJOAu6%=O9a@%LaBh7? zAY%0l5}t1PAsm>wIUSW4{z+#anAjJw_!i$>; zn{sZp#dah^3^tKwo>@ZP`t+z*e50E=3oJ`OBJAR|4*BePWhV(>aAeE$f!SA)E$|1- z+$NGQZE^D+TOB{Wr(WPb=d&ZcuoO$G#NmbHUB;KW^?fV$5(&NklkAmS4Fr$0@8XKS zF^*eOy0(pGh_uf*Z(W80voa;2+#D))N@HY*I&9lIWv6kLBYjn!_tMvGZ(sd?l1g0$ z(Fpj($DMo(dbs6`y<^`^2g$g4Eho3FK%Ft zeoK>mu#0xA@)JCsxevYEy#+EZ{OcwQW=(Wx$dLm=I`8FG2Me_aSc3TdE&pp-5`#oY z>kj3YxKeynu1^POysGW|v&u+KuKQEl? z;!vjL8j3?gl)1PSU_^^o^3Oh^RqdX&ChC4YEnK~*hk=I6x_CAd`5OsD4t(BeyMMJN z97wwCFW6X&MB!tbkN*Ct`l<;j`I=`ZWHk)#30k7ek^~}G1Oxkc@woCSGxXX1BDJJz zWYz@~7;{!I^TQn{fzgh?Ht^ys`IK_X>@y}$0%?+nCVBCwO4w2MKX{5oB}ofuL)GucH1b zv825mcyt+)dl>odry$EtUbFlhS4ZOxB*yag$V+RJ+xp!| zxI~a(9~b7AzhfW)*+|@$#GxxsQ}}{L3;e~DZ?a@50k93nVh>;QK*afmUIG)9qM)pd zcM}n%Ak^-zulu0yroZBRgmPrRtmj~IH7X$#2;Dr0Oc%4HTi5`lJ%! z1rUP$ROf?()Z0TGr;<8N6^z$fQ_|LKxc=?%YqRvV&SQb4`yVDnA0vSc(*p!vN#rL6 zPPQ1hpMnxNoQK;2NaN2frt*g@b?x%;SUGSkgnuAo`n2EW3Oyz7K%#uyegr;Ybr%GU zs4Xq5bNy64|i+_bEJD2+q;N{WQ|^XBK%J*f%!+Qh{zNX zo9edw)oJlwOaCk3(SQy5ySH}L762%fAwQpfg!J8?^_R62uW0|9$BtEzXF7gJY6Bhd z9qeO2IcPtZ#L1m&qfTqH{~8HQ=CDXQB*d-mn7dyAf)q?2TqXcZ%^9^`vW>C55w>Mq z%~2i!WxkFyli9mX8yCPBn%FG8uwc<6MNM#-c`w)U&^_mz*QI}7@LVKFb*MbRb%IBD`Z?&6_bXm^torBc%SXs863LO^Kee$S;!b zMOR)xPXjZRLj3xOHZ`5ZGpGFxEqQ@-j`1v@AKw*!a71U%Eq3brD*i!~UYW ze=t%qY8k#?g_G}sVQqVyHknT2b7$y%H4w(aH;2U!lQj2%3^U9BI+eqlOR&t zIlw?f-T;v1QzY_NlInWd3l-3WwwFL230=i}L9;rOj9YTelHDAJ+K{X!+SxYD2}h>+ovF?{f$Z+} z|1y72PPiX8Q{qJ#;>T8Mp0vTE6so+o{A?KxmGdqxum9RjOd?ZD&pIlku5)wR{2+Ix z1tg`bbt-E$q;OUAYk=)j!K$6h?eiItmsRUU|A{})v*hHUKTskxp|v`yt~s)^rKhrA z$|%-}%P?Wx$)WwQPn4BIc5}MvC%UxS$%KsRln7|oV@vFo+m((nq+g);G`87bz<2M} zxz)f1$iUo@ra4vtPhm3Ot#?Df4Lu4fEc4=teg68c*7t34`J|oHsUU7tOWbP6Wr1Uc zf&*_hp^Jfkq2INsVd=qJX%>VP6@LgD0m?kgGQqm2c=OV1xEoNE1ano-pjvhn-0j5Xinb1>1X4m;J@!GE z3Mg-mbRtzO#(8M0$GhVdP@|U}mwO~UJBwK3sw(tW>KNy>R?n&h#nR(3kPIWa*B7nd zM*eNx_*2opT8C-?1->_tpvIiJM@b2d-_CA^BtNM*qaNol*UM;rhj&n*A32nZzgGi08Z+BthV8 zM1`N5%do5-$ny+apVxlsjYhBe*)>u$(-uQ1&h5>KENq`=b;942LWr z5@==UBpPaRe2QNJe>56FAh>sXtF{)P(Otb64c;fOl=rBqGiQQU)S0PUqwByVb$!Qo z@7TO#)btASdlEtwp)B&g1-%0IILAOiL-awjcBQ9v|Jvb8!iuL_d8iRD_f9& zY1;Vyv@DNfrmCJC7!E44c8+fjqD8A{{}~w13p+6$S@+ET)t#Vi>&Hh=vcjZ)#|Pv8 zJb6T)oZa#;t<0+6@#&ke?fP6KWCP$_78AoGzdMki-^>iVP60F1o<6O1=2-`8!MeBj z{~vqb{npgBwTp$V8!TIC3IcnJA{~?_T~R;XZ{X z2~=A7jANqM7Q6lGZwb1GpEJ|wH@_bG<0fC$>C!8Hvsy~wUop3(UTAn;u@$5lBotso zY3V*5sb7?y00P893ZvRxY5IsO5%wt`bwB@pl^I5i-zGIB4P{fqd3sTFesLbFKO=wl0-Sierc;(?g$OsHsS z9DAJ*rES%O0QTw0BFh7r)wdYyWyWUy%Y%!@PMK{dn(r{vKhuzpqIPef#*a#t#|~*Rj6@#DpR*6!q={*u&ZcPG<%U*=_g=HDkg&;Dib>FQLD=*QQW zuP>&Eq~B?q1J=Q|jC3-9Wos~l)7L!9e(!@C2&k4OEV4{%BF?AL5p0tX%vde^p=#3R!qOH3|#QgcLk zSkf!_4lT)( z)-F?b;w@>_t1)sz}>T#!AP8^Fh5N9$L1JNh5xFg0_+RdVZ*l-;wI5?9bc zGPgl5(o-?)iX~jLDPx(w9NE@?*2!m^BnVBPs9_wGbe84q+m$1joVZepwu*NUDs%Ch zQ0N%p_!v4ST@f0dajzqeBRCI64B6uC2L za(J4Q%njeKWQcaM{2r+oe+N6TPoUps+;U$NqF>uso(Xc_#Fo_!ypnGfOA+HU=rVx& zV(dQoOA2I#r!Jj+C|5uha0&P>{K|2|IXu;qb>wF9fGLZ!(tzNT+jF}?>n7W84|vOQ zB7fuR^K?AapyXM3<5ooAP|w-WZn5E8OlD{l*05RGZ%10DhH-41zURz-LZ-#N zp7cg7qz}#QuO&Pkf<2?F<3H}r_aCK*TMi{!!LXcof$| z18i0H`;8>u)7%tu{E+%h&(*gMsv-;f&Y(bwzHf}%go*h&8bjkn^>E(goNz*QQ!P_O zGtfVvsSx~@K9jb|+*8#V?vScjVKlL0JHIhIiRA?y-vv!1E?+~xYcEf>Rhd>CG@)9% z6FBkgI}-|nG0E`cn4#FIno4XehCHfPPx}3p7mQb^zLROI*!=A#wstuZogQYtwZE2U z%&p!$40jSW|Ly^zNE>HqZ)<&>l|arVjDNPsRo80>NXxskaRH?PpRAtz6k6|veYDj= zcpaYQV;S$Dd~)f*LKHCuPkx$l#dksDl3jmxJiY?i ziP&@foog^v#WXArRB7Vq;;Aq>4?W+~&6$c^O`28IcJjzbdX$*!k6UsGqGb}@=e z;fu?z?z;6LC+1GreZ4VWZQ-Nrc78dzGV>VdB~TYbp^h_jI5H(H4M{noYD`P(cq6(} zN$EM)s#o-pLhRX3w{@EMn^LaaD)_?C(e%dOM&i1|^=P#-9#~2R8~MB{m9q9jE0Wj} zBcFu?`SgeHGyPkW0lhGuV}5`3eK((a!_9rknBPU-rIyzJ2rKUDZ6?A_3t7aiiAGd~ zkGVu{$L3VAUOg(u#IrJCzqNvr!QigVu?DJqY^FeQ-s5Oo8FTX#4@evvpa5wM>k0UU>P<%QMgrOAsn-0sm@~D8G#i&Udk1hA1qr{6MPA<3^K4-wPjC$?SbMIWMo++% z`l+lC5APbw!*C1?n8{>_!YQ`dl`{5;SB0gpv|R+aF1UTh;V^trE9atqsHR{RYtO+9 zZm)NnGmoRHKTfsj7E{0?RJ-2vhhp{81mIU8jQmh=Xi7jDl4fFKe@8^<@72w?*fw(4 zvNudmd*}({qi5kuZf{>VB6>47ng|`w)P0eiGWVCE@6Lv`PT#;EwwJ$KTUeKoN==g^hP6#b zqU@Z5&|ZmkLGcdU_xg|IJG5@qnu7vHnDWd=K`9+my`LD6tI8k}$GeVcrwBuv_lYQC zf>LW&X`E7E$MP2Py|U?gSCv-}y!o<{HYQj02+wqmJ5fXZBQ_ku>&QoN+Pp%kD|290 z+YzoS&1_k4F5($=dgW~B$)slufZTsKQmoB&bo}DvRg3=n8=gE)(CH0uBUM^yk4fen zYmC5(^n^((`M+(@OCl{DS>{rnbaW@pWVls(4H< zZbliu#}_aS7a9+Yd!5SI>rBHRuv(vs7Zl3c$Hg^>0Kj*`WED>RP19svdwHpi&F7|> z8q?6$z79>S?*^;8Q*cIoJwn33VBiC)2?v(5-Z;~%*_TsqTRZgR?T5+A_Hy4xs(vgV zM4CgR`=6AJufjT|g)isYD21LLepK7xlR6G=d@lBR50;~n=aoy_%j*(20d+(|@<2DH zZk@j{yJTahV)J=z?6K4fyL)ZK4p0b2QT4+^@3W_9O*~v#6^qBmn`JItFmTF1-)mkq zZ*3-q8oG5yfOjSv$~qo-r+`LpOnVOQ#$pxly590=(}n$^Ff1y3#FFS*0D&ZLnZm@d z#(%G>!Ca4@xAM&S`T~RvT9u#pz3a%hm~bHxo8*>pT_|z`RYey3J0K5Bz^)B*AG8W; zreC-gf0~PnOZta|tg*wsF|p`GTcNDFBk>uX78frVpSTWx631KcbqMr(LiwTu~rrY-7H5wqs#yb>LCczW~&H!cq{nFdWQQ`NP zp^l|FIkKa2{+N-K4;D~e=y9&Bo7SGUZ*9FhSFTfj*4eb$`y~AlITLeDE$C{<$1;Zt zxkglR$g5_1@m00zn53Z;x=fgr-Q?DN`e<|Lj=$!eNl-}*HHAJN} zlpOl_$k$P?UIw+Jmd$dGXVe zM~ob|9*kSdE7|4anndJGj_VRT$SxA3me}sl%+W17MXRRv*jHqz8asUpm{YMYys+-q zDDh^A`)ik+v%wz1(3GzOF;{U>1>tWLx56B=E{Sm6cO^ddf?EK?y2wj~0M&7n1ZS%WCnVSl=YD)o-)7UDo5u{J32#eWj z<|Nhpi8a#eOAzy)#Eyifd&w%10z9s-MB#>ixJZ?L4jND+FHMtl7t=}x0g)iTcPum) z?jTb08Zv)#0g4LEBzbXhEvx7=mI}ArFbNUfCkfXpq$f>mtyjNKSx8Nm%ABl=by*Cn zwXPaz6Kx(*vsZCTgL<*q;7L2Q zXsUxZWHVzmSTDnkF%L;6;~pDIXRhiByyr`4M|2Fk8Ck^d<#fD(=J_;HXY}07hONo# z7jqtm$q62vaAIvQ>BM2kdCRu;6%Y3-12VKU2llnRl(9dwjD83xuWqu_+EU15gb^x& znV#QKN7zq*w7#@HyxZ!9+;X7s_=j!Z&*qBNxSOI> zk1q~Fs1n^SppH&+c!}jzL%_)gODwr+yA1_#*9*IU;EH(@wsdfvac4MRn=bw?bW}SF z^f2m_ht4!l@(1{W=iqHAxmrw^NiRh%Eke6kM<9c@mzu(M)x-pSW~V=-{~7McSU&l4 z3SW&sJ=|?A3#4f-X`|v8xtt`(=NbW1>piLQC8(JSN-s7CUiWw&TAm3UazU@75+LyTOs&W|`(s#IfY0W~!3rX09OOE)c4Hx5GJs_efU#ZvorrJrMJnGdJNT zVrCV?YS?J)q&x5;Gh+t$TmlHs4$B1i$84`7K5$81(?ycbX7+}AcDF{;9a+8nMVC{y zR-L?Y^88fe?!jP>no+ovX*Se`_GZ%;D`=L7FIm_`=~0^M%xe<&$Sj1G4(B`8?bX9M z+5(%5jLv|xQMy=Pzb}!WKg)*}R(iUb@6j&UPRAt$F|Ki%YFaTxi*1s>Q#sI~MYE$jh2&>mF9Od`8v4)recZiK8QtI|o*RRLpQT0_ z?Mq8+3)-zBi`%xqHt#jTH^aJqB*vt#JMhs!C&fsoEJsLBEKK`YbBPxON7P1EE9o@O ze8@R{1-Y+zTT)kd{_(DM@J2=H%oXcEXJbt6HMpgG- zI+*BG)ArUAX6)$pVrXfE$a^g!!mWFYurwWoBwBD@)~C|wsOWRm2x7rP z={p;K!qU(!v2SDu*3wmcr<9qrRaGw=RB6&>(JfK@u4+oz9fETUaI&;N246sgQcuU} zV!G0B44pAX|NRraAyP^QxVZl0=JqzZU{%;&zQ2p6Q`zvT$aa*oYz8clt%Hsx6AnWy zqM5eQaB^A(>d!KZ_(Xfw1JfT6L)ndTi+ab(M*Qm6=tB6|EwWvqdtrD(SIuHs(y(w{ zTXrF_moD-n4_T`<*A7_ldDr%Qq=a5hUb4Y zdA^IoVS~OL{eg3aomK+wFp?b_o)gzRZKRxL?Jhb0`KgYh)MTB`frzsb8OTf8s!U5_ z#Oyt-D^@kk>SpQePyTXg{|Z2U&Pyq!vNw4aXpLUmam~rlvL9|SGJ3|t<6xNVlGfwn z4pG=HAitK`1HB{GfjvbtFzw~}amsA7^0{viZL&kw19i%y&&E0s$6cvKaMM^Ba@kSvT_Z}{(3jPeWwFa?_KOYjQDS9RPMX|LxvgsK%@YF?e(#IGOoKrWfb*>T(Wsnbx3`tAqLNn z&oOL99P@XHZ@OcIYmfti%2oxL%W>^MQI(?X&?VRVVy@?<;6S?V5lwugd8pizKhhXw zuGS;NnzN2~V_Uree1Rs5Qhptd-qw@vJ2Lo=_x5CpYa~<*WVla&WCJ1$aj%E?pNqjF z+$C@(TyI=}^;G3kgwfH$vJdy=ynpyepl=l3Yab*eXer4W@;5d?i)Lb4pcW8jKB~(p z1>i&FFTYomf3XVeTIGgs=u`9hScAQQ1&heFwntDztJ0VkcOR2U3%&%OFps8RO!Unb z!L0BBf0b&(qBZ}!vLLWe-kY58k^H2%7AJp00%m~jQ#M_U|9(vbsuGx3*VZnV^T2sn zTMty1rfwOg8#~+)dV_wG7yc=#CC0*I)t+~FpP8D#BP2!eX$-o1wDrC#GzsLEA+7PtOxD;n%{b(m1rKBMj#^qnzl$9tZcAYK6J z=}PXnXY;Fi*t^?awU@Z3+H4BXt!9h6a_7~`0bnAAlv>;E2C?Z>6|kVyPeR`bi7KW@ zodH|>C)OFoJ5=_@@)lg1?<&hgI@lvMQG><4{T$Ca;uAqrj1Ezfac6%nju{>2U&mB- zRH$AwozMn?^O{WZg$(f5R=~k&<95};mp1XAzdRPZUPww**~HAelKIrt6^P!Oq8lC< zoH3M95)W?QhkH!4JrlE(=N}m!PMxR5i3Zu-RLIo2G;<7eoqWfMK5iU9`KnJbz7>%| zUT>@#&If&6JPJL}3=G20+}rT2?|!FtYW7yVMku=NdpICSdh5Id5H9cv5_dIeb9c28 z`c}p|Majen-sFh;;su@1Yg@-TJ6DEw!|_Bl{vQeO(+B&Ni=IcwDUrw;eL10R{*J(+ zU17aXpr%j2xjWnYP2p{o=IPe{ratobr|;z5unJ;%Emv(xDJ2^Mj5I&-N>`QLjs6VR zBLvXqzFu9I%A#e~10RU7qO;jSD&@4`06hw}V&HEAo1n}2r)Jx_6GDcCI~>N25kmC3 zYRd{M_vxP4xSW##K{LXH!A!@r6}8Ih#}JeZ8hOZJdo?L-8r0N5cLhWSBoP(nc@sp0 zNRZQjX|vwUZ=i=f4Z;RZH##fwSu($OPUq~$c@}>gK~Icr92>vMn>p^EX0P39+vUm1 zcSzVzUpgH({rBox+cQ=NEUv??#m*n2#==bb#Ul)m{5VQv(4u|P1E|BP{*-I9}(u^6*;up`bpdY+ZM&me3tfD z2mK7yKHQ$kpM|9El#c4UVnCh^MTxg%cPr<2&|XMMr>239!=v5Xv7?M+BZsZh908q% zrVRF8*PS8&)%JJ*0PpfC%v1834Bhz&f*}l3PKFTo%?Tinb5rGcT>w`~Hx4Yjp$m;*4we!aZ6N@xbZ66*phX`STE) zOP+crNn6Oq_TdhY_2vQiGu8xyLU(LvfGvL$`kim*_&ph(zGZ2l8{!+GZ14#ST-eqWis6mIyc=o?g11Y7unx}!BMU8j( zlix?j0{mpPLsF}7_+A8W!ThIdo!NXk414O`CxQYH8|$IZU60Q+m8jlVy`)N^yaDaf zB(%*M@IS@p;}J8py}n{lkP_aO8g?5LR;wWS+3~9-#B{xkYP8aF+WH`AEHv8-qG-Jp z(ge3a_wQEt12SB&LGa2mHS$5W3ET)Dd%9~vmTqN4)wiYsul;TF(bcMP>B(CZtj;w- zM8SYEDt*s`w_qdu*zJRuAYH#%9bs|6ZNLR->ReQCE4TOh7VkW@S3@U|*R$}>mvp@v zve2!q>{(w(GFaKGK7ToZX8ew)U*|kA_)_seQM>bVBUW8wtvOl%bKa@y+kPS#e;=$t zQ*o+n6;*470?K&L=vPGhCs<$fPsilNdoD7}KoGGu_Ilj?g;b?7EYH&F` z`TjeG)9_LmY0U9d|I{k(lE9~MS5FrjJ4mo-?6<*z91Hig)zvB8f3&fA=-{aacAQfI z7W7IWgUH-XiijSPwDQ)=Hs5Hgtn{?oL7J^Ocn4kH)h1qNit1&07qn}??t1oDOK%#d z6Mj{z!l!+U{n?Ue+sW?q059B>-EMfrwyFP=2xLm(w|7G{^UP~V+ttneoW0-<&_W3O zzcR&Io>LCEPO#jQcfFT7OexELx13COG{t0Oa#sMKCti?V@|k{-SAw_pww=~VXj)!f zRJdGFRRElEOKgK*j^9=U??JV2C-CFC9He48)9e&w`UoQL<(N+PW8rdLRs}jXo`jK) z!Y5|RY1tdDc!Oij?q@0dOG$`c9$q0o6}r~vYV}Hd+L(IPvzsyoTy0j%UzTd()BTq-}zlH zHEmOXieyhB=QWxmvssL9O>gqQFVt^&-Zq^{{Q*1~$<_O89dj%eM_MHsjg%dBLnro< zJ!4I}FYEtAVSm`uY+w;`$>sbG!wmgbJPJ9_oG5>$k(pcqJZX$6-?}tB$oh{_M~qBg zYkSA%B}3l+$w+8~Ht~6F)v*A=vS(Sr-1uJ^)bOP$f6{yVC+MoiLL9 z+jp00EDzb&@~nr9Qs6S*XEFR&S;_S0onkeaGb_$^f3b`au<_6E5BPj?FoL{5h*hp@ zFDIkMY?Ni5Y@V@D5lNUa1Gacp=M~}u?M6T)-{#6To02P1a}6c@ukW74DWW1q?w!ef z4yy^CP0)=T0$G2bAdEK^vBPE`By||sN4W)hc|_btL&YD@2swVbf<&z-#=XXWm%!cr zIRLS)Q$`xjz7LA5{#t+3Sy3Nf{;=>&>)7ZliN3u`XySSU0PM3Q~6`lbL^n>uSz zKf(66t(wByXZ9jFpCJjXje83!jyWbR*I;+1?qmImo1e(iodd6C4ZJWy*6uV1KgjO- z4qCjjcaMzabNMppN_lD4@~d9gw#(5r_l9dyCNV^Pi-=bL`FB#W0K67lYyh9#hhxf@ zXE$Tu_(B;4U;ex#g`^}^VbPL1L&nd+=lO4{OG9WL>ya;ut%P{MQRwt~} zETVHabIO*AH_@soy8*ajIsSvSCcldtF)QjmXrb8XFLzaeX^=m!K?==Hp`EeV5T?}W zzVFbe@O>9v5oRAnqs*Neb+^7T3R+0eE_SeoUG9yUnlv+|vJ}d6*qVoq*M5tgqZ$JH zJ#s+600Ah1%hdt~fJOUM41{1Z!)LEA=%8?_P~hmeRGR%(Xvz0R8Iv+aE^0Y&R1>We zDg`V+h<2J11PKcGrfHDshe3;NYNGwl0scaV7qSVWX;@*VcwmH(%YzuN6=^91U%JEM( zYX{X;eJacE8hTN8!AWYw8#>^NU;5}aFrSOyMPd1O zCsOaqFD^%yoht0GlNedE2C}6tXv+DRw32qziEd#H_A$sx_zbRNgT}e*anwaXTjaEX zrek1j@T$tCh_iiP0f_pH2EKz^E(Ccu#qhen=_WE}pw9e;?sRAyymU;pZYxR`fRUCl zZ`1cig+xoDST2C|3NR3YfsWFZ<)2g#AZ|i-OPF%pYmD4$rpy4+V_tU9?d~i_1%V6W zdj8|6EZQfiRFm^C}D?p(rB8(Luuq8-UIdDvi1?@uaPGg z9S8x4IqtFuMj&y9ZNs87QT^j&38JSH$f$y}=uLR1Q{-IIn(EAQf#} zo0QWNm8=tj#*R5j?LJX44b=IGPc#-4*;?otTW0~qr1$SmckS5na_`9{sH<>SCxy(5 zRwD#;Dtjp9dg=vloJE0+RXaO`n*bH3WG{1j>%ej)j008+R-8_xWZ8x=;DSr~&lBXF zS5G#G25p=!;=Q)vN_fI0^OQ1mh6Zs&zSLZ65x&1Q_HjRbuJL#$b8Ixa{bAV??=_&f z!DGNQz2uqpkvmTpDz_)N<9Z3Q%y^*Sm|{Dal= zs*3Nqh(vq4rn+AcLv((7`CN(N=V_lh=vcC0D`uwS1q$#w4rVn<`eCi`XWdC#R-K{( zjQXnTCm&e;1lab4~p1gHD2(1sDp%EnuB-ciU|5x z%GxF@!lw?{o)2`K88@>CW0#T1Y=&|yhsmlx5R);v3MUhjRWzgVP4!KNxeUen@Qs|# z%6XGw3u3n=aRxWfVqHeeRdQak=_EEi{@jzeN}Vmwp2Ru=H1(&ox^i8N|D*2v2E%Z9_Kn%*-nc(>KC9d66Tf9c8E?l{27P$m6j2Cyz zx+UIjJqTzHa$fg^v%=Vk25!k5!}ki#eok`2H4T#2B8rR*a5?)eh!@HW%O2DgT_Nl? zH$VdAUaax}2#0|dkrNk7dYU_8hdzHZq_L#zM1{Iwha;~4RHtYW{aDvGO&pSi%iNtm zz9mR4@3;@`45C<^m|)DxC*P`v(4Oj$#9^-tWCQ3OCy9-)LR4}7a`46I(JW4_GRpTL z+sJt9^;dmJr8tgHJ9G2psw9rZ&at!({P2r21IoI#7G$De(Th}OrI5e{YbEQy{8|wU zI~njfaEoAeom&o~-qKkt?bxdrZtq-ixAlOayT!hEvZMWhhFsp@oEUrm%eeZ-iVD2k zi^WTG@C3P5J;^(_HrEZUZc#$N_zN0-?;^GM**;>#*xF~+V_bZ^2kG0n7kuWiHx9RZ z`WnVZ&$LEUcGQk{L8I2FG#dH9K2&v&cfWX5c%3(xc8>{co~CzOKfS)lT&2@eT2s$b zYU0{sp6>HZYfE%)n)E~jRCcxL2V+3c)xG7s(BvyfV)-yl3)p4P^%Pn{fV4RNT@AS; zQgiNi?zw_q2J|yir=-Et1<|mBB#qaOY-#&Frq+O(s3q*p%NSW|Hm}{JV9sQ-TS2b(W1E)&zCFTE7k z-W`5hr)A{qCzpWIcKhb+)9B7xf*kK*IYJuOp_$!B(>F*HvA6A)ZOIDue#Cnd7)x{j+-=l zd&Q>dBDh_ML+=?mw9<-jyEXpF{#wTR-%*gxps|-1uNaq(PtalYvk%VKUkk$Pz5uOw zn_kVeRLV(`eyC3m(K*jK-YN5{?$)q3Gn60|C=hGoDXzd)s5>g7ai`76?k%_tM5*@}7 z{`u)W&B1>@ajcBay~+F~{~GE6=HW%yXh%-|`rVOa9sy*n`I*2^3_-`|(QWYba2db) z=IxR$yA#&_haw$AQ|rRUN2HYO5FAVY!1p!=ew&N~yu*PM?IdwXO~KhWN%6vknA#NV zQv^5nqNC>6jJrpFkZ5MP5LQJwMjWK_y;IQei@N2DQUB%?xO8n@#fA$(jNGJgvT>2iZVO#N9A zxER8joZOHgTod9|d3XUw#c};NT&W;I3Tzub4;%b{z$#)*hNhuW%hfLssf|*3(1!g{%?w6{@b&`R%x)rYe`l!^sHlA^!du=xfbtKyF+AFb_6AyQjyB$_YbJ#He7Ck}TC6)~ zCHqV41rS73QIrevCMVA54S?{6$H-2hW8X&@uZ2zMR=n`C?i@8IxR*dbEMQjE;;*6! z?yh70B!EugCe!H0Nv&7nshz-Kb9flFIvjEnLH|U+CBw3ni`Lq#T5=SxLA$r>^{2ov z?{1tSdClhYrCb`D?BjC)*^(S3oH+!=_13PARi630%`OI7$?9QJYYgfFW$rYzX!(w) zC>APT9(vSWM%WDKJv6ZaqdH@|&b$raV$|!yx@CjT_I{OeN5(Haf5s|OG_i8Fy5UDQ zcMrq>Foi$+K6sgo7sDjfx4Wecv+A1qLJP=x-Gkr!KT0k5{!*5?Sq4NuXV-(|n1{6l zZm9^YMkOm<6qs>c+R1{SD3aN`eLbY~lBI>gDS?c%8uNn#nvT^Lq6Am&#amZRhi%-} zc3R<^88-Z{4N6UW=uDpx!QsuNSl1+}&G?Df0*sG!EdSOj=T%Ttjed(_M$ zwv^mfS|g|cthXx;FFEddM?}2tW5n`lbQ4?i46R8@dXlt97L8j2rO=F|Wz1;5I2&|5 z87w$ZZCLv`2cqz9`nP=2DplU`L`*NP zl8`*y%>wYNWafqwu zb0_=~keXp1D#` zWrU%=j(a8r3pTAYq>c?@W^_eEaC-cfk&wQ%Zo)k4cJibza62x@2^<%(su1s?eyLS71IMsg>tR|{*pqI!;p-LWFRmoH?MjB*0Ui>ECqaxs7-xxcT5cDm4|MR4$c1}@l@2(W<=NlgMGbP>Hh)i)D zWeM+;Y&zQvYK(?v`CQ=jzhP!uZNXjBX$v`W;gSr(HwB#Xy6v<6U#1ctNK|}Z&hwo; zkv#o5f?$y$yT%6&Pd-&qt0ZI986tovbMt38a9ap0k1RU!Qf7`t>4NiuF>up>*$kWDzd7+W1~*Wz6yB;JY5AUW*$i8Z>oE9z8UbW# zsT9UZo}TtF0ucBf{h8nEDcO{M9>)$5WaX;C&z@ljbbQ-0mpMIJU~y@hv{D+kif9M*EL96r1?lb`!l54O^^opXKIH8X1~r(EpcWD|hP)4riTu%FI{aQk|%>BH89 z57HI|-)B;8qedC*1%pkInBaET5iQWp%rmI0^n|z$qptbOjd%^M6iY?9>Xhe&^-$7N zOsNtG)BQ9TK;p=8CY-gVX-+Jb^a(xY`SIT-33wD&5q52DEs}h%X4&*B36MD4D=te*i0U!5ISiSnmwj-NNs0-kDvU_KM%mjHU_NBF@lH8@c3 zMY{)a@EDw#Rt6>SjYCOvW8Bf3S>I!#9^M;zF!t1>|Gys0^`{HxmQz`=r-*{RA5pS* z)dpjr_0Ak!3vdK-P3}}@@2C6y69zK@=2+Kje=Wh^sGD$J>IZgC>~NZm^zQ`&LAUg; z?z}(8|H4Ugf3C^&e>d;WpQFzt*4GohQC$LXasb@5ab)rk?|H51Py@@FmOb*_kdSu{ z+3&d*9clrx(rjskB9M~Wx5`LQ#sfLr04KJBe2>FC8V9V})ql^KJ=c1S|HVzKeF1QsGtE1eJTJZfck~35Cjo^R-vqcP zDqf+S`#Pppz6?~=bW9Q6V^qu)@w;!~sm_qQq z4F;+}$sKa;np%SrC^;rMB1ez(OmB?D1gq~NX{)jmn48h>DEm7-FLnR-Gp{_i7BGL# zOI;Rcw}C_ZEFr$QHyGK|RS13jZPTQ!Vf}7)HYnvw-fYKmi2=D3C~AVfM$3XRI|sJV z1;| z8gxPW4Y8zMyR3GYFcLFzVLNmvXC!B6_d_yO1E`vNK@ZeN=7A1vWR&9=OiuywGo`vs zaiEZ*Yw?$ci8%W{r@TDV*=j`Mt;_!!-Gavl%lJ6x<;R7$*kO&v6V<*3K0!?<2)#3QP3p-<_<=(>J15D z72m10la4D!tfQ3)t1Q^k5n?P`W2^iwP*;p2u64ufD{00JG-5h@AJa1r#3}2D%JahJq~wVN2mnUTToMmWoc~*224|#{_=bSPcK=m+`A3P~U@Y7v->Uwr zB?=_N9(*F|?9bQa;!;W7ulyJ4UzsaVn`p6hI*9lToKj`W~Vse+Kn; zTyUA?^@p|7E#h|?1e1vW+`+Z^>l6GTx}Z9PFOU1?5uw`t!vEaS4*KQAl2o-TH?%=@ z@Gp;h3J@QEHX(d9KKm)*Uj)v+@7lv1FGfTDipsy&;B)*RNpgV>a(nAL^8Mo-PQ?>E z*l2iN`uv^X+Jfb3*xbb6|J{z^8{ZnYm8J*xdq1z- zmrndoe}7&w(fCiteqM3!$@`D^e_pam<>~8w3T-y8apJwUb@(sOd(U31?zQcMMDHOE z{=5bFJ828hWNLi|w^l`Kj`J&^kMrqEUP%6X74?I3x2^O0zi&j>?Hs6IJ0S}$01&gR zKQ3uF0A7OT=H>s9X7uly{{KJ!UjqMcO5lm9j}Ljb$+;rI(+uER55oo|Cx%8x>(azq z55bItEUX0NCa zC-u<3e!{2kcH@(qzaJ@$zR$yi^RdS+0UN+ zc)~-IT)<;aCSxx|_AlHkPPxFI(GA~Po$&93`Yf>e(wIMZDr$l1)7y0I>Rk<{|M$(t z{;=WE(M?Gh=8#Tg1_v575?ZIn3EkU)jk_`W=fH-Sd>+i|O>f+)=O zfyQa;Dx5B}oPuMDwsG80x|w@Eks0&w6t%%cp-d1ba6xEl@5RwWM!ryf$8*Pj3n(2Z}bN>|k#ub`oP?xgjkPWZb+viQzOywtNZM z45~r~`F|qr2ZYy-CUc}?T!68WPoWK;#a%rIX>M-bTEBbwm1nYeiw?`@P&Z;=U|@3| zCjg9Bb|0*v^-njaCp|gJ^KrG`NyCUWmbTa?lhQaHHjgc6(^-g$lMYmO*$#!|k*i;j zopWX9sVnPSZnu}O?cA7BTLj-uX&B~+%tcW97>tkG8YA7&EEdcEBlO2e{`?&6Cezi6 z`SWVLf0SK(mMVr4l=wVD1I9{lL!DI0}Mrn7TY zkI!qwW!V(r%`WQY?Jo)HsWcJZ6n7g~5@#oSoi)Dz4J>U_byR7q1kOtCC%&zLtwU$X z^!a&O!_kk_JBea3OOr2kdvTD0#{TPr{Z2#4+U7}zc3 zXmlSVvL#AuohkTTSnP@=_EevuG+lIU!zM^G-K;KeL1XQv2Iy^#qCej8pO3kn zE)pxHpuKRfX|2&k5EyWuXgyik?w3Xncd587EN74o+NoAiUGEA<@_ZO2O3kp7%NTq7 zL7cFl+CgR;ddh4ww6Qygvv|XxlgIR$s9q5{w;2apTh*8dH6CH$bReIgos0di8W4JM zX$>r6Gz)`Jmg)3{rH1A+ZT?(!!!)=LywRu z(w!9=S~#r|apkd1_7nzIr!DC1{!m>L3aZ0<%I-BM3}7Ae1-Yf$hS7;LU-YoAE9D*S z$R036Wh%4m+dShzEZ9S1V4D4!Lxjbtw&8+E>TAP6dL8sDQ)=?;GiwYavkU5JBZi7~ zoZ{TD$WsQN3)e02MGDg9IdfDaD}@SMM!{y*yl-RBYaPgz<9dAv-WirgyrEET<60ZB zad;=K0S28)B*le{thpu^)l?L9#IL772qpIx49lumYPe~g+*@5yn`;0I2<3}> z&RwTu9T!q4C)_3*hrjZRujGtgZq794*9<*`RF4Qt{iG50*Y7{5okTwjf zSqAHDpwr7FSiI1@a!l2+PV32yia-yW#scMnl|W(6)@x5-0$;xscdnA+Uu#Jd>4QOyb0P^sr*4(rg%+$Kj(d zcY;mkw`6K4ZL>=nHbGiBvAa0~Nb1T;j8zXcVU*|>2ATSl=4BQxvQC8YH_-Qnh+>P; zEk5xa)~Cjlz{<5Q&Wvb7w;krtyM=^C>OxNVpTJ=WLA3@7n9B%Fugm`<5iX^C0GX>S z=0{xWWNurBBX>6LI2WP}Gu9}}gC#wnmZ*nxY#9xy9yBAl1JdynaBZ<7us4}){Cf31 znJa4l*r=Ti>0)uZZrZy*U}55naKk3K>Tb9eX^j;k0;_-x(@}wBfE(?m1rI%+Tt0mcsBkKN?ZkxU^*R`R&!n_9pSfX}fX{i{>{R79wl?qV^ zh97I?%oC#5Y}eN37rG>H-nh8i__wG{1Ky_K`0K4yKk{?&F`d^^Jyyk)1W5(`80rrY@0b@gU|X-$6TR8KERHyn zbS^wOaz&X;KY@*ogutby#)R@F+84;aWR|AR;g_zo{I~3VcLVFG5CAItez{tCLHsy>)hj>O+ zH{-01`S`Ql-KMRftP}a|y*0mmN4x`ig}8GXz(zd9_2U15EIp^z`Q-DHIiX~y*ghm! zciusv_}kBx7mcd{6DqqwXJq5~PM45Q+(Qr1;35n-Q@AzJppt#!EL0s;>f!&&H;Y=U zk_9@Vx=u=sS4G*Z{j?j5SaLw&UhLGZt*yiZCpFd^#= zBx_kTJG_=i2x}co@ zr^n6BG+T+IS6Fu>a_^f!SAQAp#Ut^R$d}lD?7k(66eo=7Z#CC~ag_*gD2pERm1vOnN{uJ?tLA=#?!`_BlqY*S|ymYm`wi8MD2) z%~-(Di?83tNB_Dr9G4!I4;UsyRiu^4eBasWPBU5rLzi+YHZEx+%YTTNiZ>hCB0o_N z)2WfK)@vp?a#kyD6;FYBRCwcZ8K9NCjNB7Z5l*Cp*auVo@>m=#ds^GFUtI{?yr194 z1iEt)W`gS5C9O%A70bJun9O7q*f$&ljkcR692YWITR~v|>V?lCxt0u24K-LzJ)wWC zgMVc-hy1p=T5;1F>$F(=aWi-TjEM7OcRD8d1k}Wm59F$BgHUY$U8Mm|0Q?%Mtvo&g z00u(Q?gx6wH<-Jv-RrWY&?Wn0r)#fh?x#uL{^aeCK zFe^Wx&2ow!hm{bo&38BhW=MLGO}9^c&t5pP#3+e@73iJpZJATOGn`uLg?l3O*zgvZOrV2s@}YxoSm^O71C&+^n#cWS!uhr*(tZ?kO&~t+->D+Tr zdD%?_G%ygQ{VTbzpxI49^YKZMm&il+BpK!U!x!!H#V1PUThLakmIp^Nv98l1WgWGd zX#Z#GVV$u^@q6Hh*Px20-phVBPrqv{ALMQ+kBB)FYsyB1^s+R?yqe$igAx@Z*ozu# zN1a{5$)pAg^{fy8ytabxxK}2SJlm){&xZ8KRLl5wgk(Rm7tW}7wGSD@wgVG!r}=|v z&H)UX#$S(ygEMGMvU*J7`OdbpO9jfuO9KDq+CRidAsv!fGEVfDmvLYdNzMlL?2t=- zA|Avx$F~0Ev05zcj3=!&hmQ;O03e}lD`2MT3UJs*RUVvkDP8Czm&Yd1@@?|9=|#2+_XafBc}iuZiuqB1-! zSRPf#uj0m5maC0q_Z|vyd%TU)ksn`E2|%?k`-LL;`0%HN1x3`DD57s3`k*%1 zPv(?I<)k=P^Q4{n=M>&6zuB@O*H4%~T>?%HGwV1wEGx4nfP;fOSx?;#c%%B*0YyiWxpqqsU7Iiv z--nkAtKJllc+%aT7<_!ooz8=9*Utjuq8cul>Ctm?F5TRoMAa*4uz)i2iVSm95Ze4t z;2LlM#7GY;?2oN>b3NNsoc25b^Z7(CY^E1)3)lcgJE4berM>u`Eo6b^VlGKsq@UqLbO%(3cBOgKJjNL84rDosxeov!{fa+>*vO{ z`JdH7`n*3J-&+$X>DW@6)y8$}c`l1BY<>?wsw^W%qsbQ@gdZ}KIChwW1;jG^`kztsA7Td`(;Qhe|%6Z*^&hsU7ns=KTrEhcs$ZVmK)wUzg#_Tj{oH=pr$?6 z|q2u_|4AybDQ|(BbZ& zzVa6bzcv+4LrR{8&h8=spMC*%*ApCSp@R}$!FMow%mATA3slVK_6;O7v;77eY2 zbDbWx^&_LuP&s$>{QSvrbB?3U5+ql2$!`kIp|QMQAkYFsl^%2+9ki)3c~-5q?>?7V zYb;N%^p00NU{vKN*cYDwatJ7Von_0_{#Jp7jweGQD=zW<=wH|&5@HPx&1QjWEF)H{ zlHC;P0O7?!?tt}&c0xCaWQB?`G6|>$sj!$Sb*A{baOK7aDGNKk-%FN$gT~xhTwvmo zy2Nn~H7##GR^jVGTQ#k>zGhtM`>+bqIX$hdN`z=ws9G?FoS|_PXRj_RRT>ZBPJ%$z zjEQZyT$Gg{HVY>`G&X56boAxJ-LN2h0TSbtRh_(U_H}*Q=m00-)l%egje_m`@!ebx z>^mW^PiLO46_#l3F!+16Y;R)-t#l#kzt})Qk;mI^y~V`JS}nlzRgq+2$-LYAL??qUSM!(Td1tTz zyfX$%zLw33d@##FGoGkX*ws3|?>dcGvU|Scm-ED82Iz!IW3Sm)r0XKF)%4wAfUmUpIXnk=^~r07U-} z25Grhi(M-4{r_6{e~!z0`|#FPx+?m#=#>CX&0$V!2|f4!^T3+}-}04Qn6G|7SJ9_d zD=VeknE?QeLhb2eLsV^`gO87om!@V+TfNY~9!zl<9~~JPDRJv+pfNSP_yaUJEiHbh zzNB93{|<|ai(_+taLb)PdH_3YH%i}bZKFIZ{O?i6RJX5w_+#|4040X7@<%+I{6-4? zR{;2*PgmGv*P9EnOjkctXA2ld4cKA1?EW$D{~Wi?K2xm0s0F<6`|dx|+3DzZCGLAy z(|RxFhCV6 z@$V7apMaUg{fLpgb@hr=mQ+UeK73zYFLFlld2yGfh=|Bzc*;L(k!SlcE-p9!xJ~5k zoo9g@r`PmO+s;$aP@KLBEjjM;622X)Vu5Yt62UN*rnr6d`4?B*yg)sC>Fse+Uf0#_ z*Gn`%C9qV+oZQ@fWtLFR561}z2Dfdh&L%Ibe_pTbmhK-azhl6_cJ*tjWL{1I#m|(a z$F(zx6_z$m1E22Z!Zz&$khrK|F@c%Cq5eO=ejPEH_xN1}uo@c1)IImuch+N5kn~ZJ zkxqTn?oA|05k|W$EeZHNeO=;9f>{w6p3puONh@yKuih zZ}Q)-ytls-?Sa*FcYAQlHc&c8ROx+K?!eHS>=l^yP3->}{NG>w|9XKPcOd1ee5eM; z#mw)oC%%6drlTWw?4M2Ao{AgHm|?mtI_Pv9>h*1_h#!upSlra$s&G|!d=ME?RwJEs zOc#gx_)Kcg-}U%SXX*9X{Ru)hQZeV7M{oBEF#3N#o6*7o2hK-T(#EA*@QvIH5};;r zKO*Tqov25ysKbQ6nzT<}vewyhe{fR0qmtM45fR+Ck43I)%wT1=Wts#(Q*I-!0(H3G zxi0F{su+1~zsvmt^C9oevqa0G($V^d-UpmvHPbr|ZZtTd&`q(k<7#P9Vzwu`*MrLS z_$Rib()(!L#6cz!QB`mDzwh;$T%H&@sNL3aTY6Ma$8~kWcjq+i8nP4i>D9J#jdZko zX2WWxbi}D9JU<#Hhfq8lCcW7$=6%0IXy(hZUaDG|Ddo1)v-G;|yM$w=8RF#8d#}x< zAGwt2)lYGDGpK-H=^#moAX4!n=-qkE4EjOv8`D!u%_YPrb?EUEeTnw&Ap_X)TSXo; zV@PU`!`eNZjx~{~6L90UV^Qh2&UO@NHeu##se9CF$4awH{N(%rj5*}P|IT2sJ72V9 z&QEK8ankQ_Y4f>3?(CS$hy`Oz@cl&TEOqr<-j5j#KP&j6YqkkAp_?Y5+H90=qxpy= zub;muE+FD1y;qoNtk~!A#ok8;h}>(J7xuzEkiO`tal1tIS;p5?k?H&jhb=TN5YU15 z);9+o=z8PwdZ=eaZTti5H_MI=NrG=je40mA{i-Nw4smw%7*5LZ&e(+>oBcps4ZBXD z2Xjd8P@NVntZQ42YoTFnzT?NIdZLh)#;N!wgM)vG>EfHE`Qqpj>}SK$lDY|5$OFVY zi!^S^hN?Y87?GUfqDL@4v-5lw?goJCE@5T$^Jb+LP`v?J+mioE*k@pGbm7HKcq-3UrMZ_Ja3KsKX9Ksb_sY zJdpqoUYYfgNMlE1EU}iCfp?*?K4pOI?CIRiLWK4!hV_y@v9qtZE(`v^bAND^7L@{~ za{ULh;+0E-QdpE9&fkys(L2fxZXf23`kTGW-$uX^mqHI3g*Rp=J}izn^aImx;|-X| zz#SgR^vs~hB%1)KT~-{6&5KS#6DfG0WMU~323JIXsx=~I$}6=xC>Af=KYQs3N|TIK zb^q3dw^^aonR}Jr{dx>}{^;sD%eSeY82mgX(e&c$ab;E2T8t|%6JXaQd&&Pph}U6S zk6zF56%7?y=Y06!B705Eg+XyW!o6}~AUgP@Uin8=BPUCX+Pux-nxVcKPVem1!|e zkf%vyBNTmgAz+QJ!?*)j33E%)r8(M}Z(MQBB{ftyn-}o)nx2m?&AV|P7#H)voU~K` zOATsEbui+hBl26bP6OPCxOatXPxq<>I)?K@yeTM*0o96@DjK+r4f=-?6lbk@cLv8g zjqpc5K*%;qqWLD;10%_5uK@#hJ*)oErBe zKZ%3%#zH#qj1*B#wxm^Op(8O3(WZksy$GadP~r}QM|DEt!o1bZ_am(OlL6_m^xaT6 z3c~+fomuCqz0=8uESr7%Zj$@Nih3aczI4=@^VIz$@nUCa?~;s(isn0cA4FhOkh8!0 zg_CqJ>TR%nbHx5Ne`hvA*&*Qr!R-P?GWDOQ+y0_kz|WsP70&MGnk+3;A)e0jP6@%2 zd9@a?W+}3ZEeK3`SPCWN%TIrsyz3SUP~ORuRKIn_B8H(j{jWUMobd@RWt*R74GR&! zRm}Nv&ibq0ZQ~VnlIck@cSz=7n~Ah|#+C#TsOLa;ygE#AiV*a3njbh^;4av7@TudK`G%?7prxr3(@1?IV1ajX#_R5e|lqchSHd zqrEdr<ArFRu~9PCoOhvM?%PEVV9)5Md3e1km8KT|dTqUq}h zX3O~#9tY24wLPN}aw0QYCU=Xy=^>;l<$UeYzKKcq`G`p` zl8CdI3!_ti6-Vj!7Q@1=r(PQpQ7kevNzsE4+RH`PE1!i&g0P zJP3X>fh0y;B0yM1Id1%6Mw+5ndJB2zbvaT;u>gD&XU+&UVYRoco$ggAzbtxv8FY~9 z(wDqBIAwt*&CW* zD1%Dk`!n(E#(l%Cs+o@MbU_vNA&ybR?s7CGZZWg}si(H!m4V_9h<1aehtcZ=riV=9 zKF>bY@_D)$VO=ysJo7id&0<9O-<`MbxEEHJKi^7&ahX^O!oDXoq41|43z}^LDFFby8B@VOy{b*_=Zxw;|`I+pc#A*-gBP9{{ zsc@2N4#$yc=*q9LHf3LJ6&JyxQ?1`|Tvi+E)*cn~49umMIxA5o{h-G3DPh1n>5UqydkyG_uVlcC0wEIvi?m056%r!WZ_kuWP zSb6r+E6(PT^|FL+A&-P;c6Uo-~o zD?_kxb#$;!p(xuDwxQ{ww$1MyM`16tGU#)XwenfO?`O(WcLeIEwu;CKtp5CZb}zVR zy_}0!xZIvxZ<2JFpY%5;cmHgCrw`T#_Jk+j-zEZ!w?!aJb9C}pZNyVfV!p62RWVKD`19wK>y!P9Lg>nADU9zAs&3SDhCH|=} z*Cgd1bud~Er!0Bj*Fml)Q883!K&2&NU(?WJwpH0NTO0pRa(V$xv0_%9rEg&OP zJ!Khvr~my|Om0B(+kminO|zFva^3jaAE3_cWG#>FQ-vS>HoF8sZ+(~%KAp4gt=koj zj21>Jb6E-Tvf<1E!=Ndd?QDeyyVhx?8F8`!DM4F@ap!UDsfafOShD1Pzr05L)eM)q z+P0fJ%9ljOXBAu@NH=b%Ol7{GFWW>P`G|u{;$;IaidFykp{EpbF}a_OVzK7YpXGD@ z;?L8s{LxPu3L|Pe-$iVh`pS3u7ad)zRqv>N#yS~0dH0=Ql)pcRIF-WV{XW;vymF~L z3KKR(i$)$3T_$0L?>QtfnH0=RRMS`!<0e7bP8ix_I1&$k7;vpZG1-phus&$+h2oIniI8Oa&9fPlLYk z+AfzHo!H3un>Y62!OI`d6SqnP18r=0(1&iQ zCE8f%w@_J{%<=DItS7C{T2Nrr`g@LXRl*SI1N@ zR2c6P2!2&tF7>|q^878N(`tg_6a7cG%8`4W0^uubAfBZ4fl?vrc&=WTwJVc;B+v2A zJy9-}4(qDV{3ZSFlK%IN)@8ofDq>^P^;@Q2J7LZacPE2JE(5cUdLogNFtLsWWA)nL zZ{5c@*;*dUO9EbrCTP`umqg`-RNVEn9_SP8jBu9|mFHc4UnDocHD;H{kC|g^&3U9A(b=o6G*Pt$jI3boiTYS`IiPRULe zCP_50Vw%WYytB7USGen@3%DR;ATReHeNgtAf2tbU(>?ta{k40_|6|`2?lopD*vzOi zUvB?%t1{xa{9_7br&o#j)@6*$y{`q^jzZ@etP8c75#K(|)SA*uDHqtt@#y>rDV=z1 zf|rPrQ?b|mR$n+7dZG%Y9=i9-J34I}wbEfD|MjJAK8)l-J&C} zuYs82BGz!L-MSr3AAOQ6o3He2zCu#%6#uM)+X{51-*&_T_1_gY@+a=n7w-H?s<12n z&0Gd3ru)Xo%ky%5+LaOaQxS;!LNFI2Sc6|OED>h$X|k$8PP|U}+~*jn1144Buj2q~ zDHrC{Cz%ULtDjgOCM?m|Bt^Htmr9;ZR!Ek|g;w+`z@yxr-kV~5n8k!xP;#5eEn18% zjlOBGTmT7G`_RrPbij8bY@6TL-1}`~374Txt}!{!a#(1(Z)GC*i6m&+GEi6JMk{IJ zB5b}v8F?vmg)Xqwh4@@xP(JjWa#g^)rR&FbW9$jtwKn;2$d38|_NDfw;3JUp(d0U2 z*zLPYreK_^S^2!f`EVf_+d9OTk7L6}X<_*g0iZqbBu;45q3--{nXh3r;%PJ}Ipfn~ zPD($n!BVdBwH@)FYbR-aBeKZuulKbL5J-&>zPB_lxUim-6wS5&s|zUx?u#K?0;Vd> z(H^h+M#wh@d)ME>rzFFim->DbxtHE2?#&vt#dG13#iGBwc+OO`Su(KCKC#%IhA9W9 z^bUWyMRUxhGw&KEOF6MERWTMU2SB-IwQ+}&8NG0#uxw{xew1y^t-8vvQ(0#Tl5|iJ zU^0o`FYf9!qlf*V3(Wd9;=t#%o;JB&4EB0)U==EPy4|Dze`l7MAL0I<*}5}vf{X=w zD>D}ewLF6Tpl>quOGZW1mdu@S8+5%`FTdYe!!pJi3@k#}52|RQXXUqHkZaRX7^c6! ziW}-JTiAg=yd`<7AvK14)+j{-jk`uvjS<@#COb=c$M*&b#jFoBVZM83_bODW?OnCQxS%nvCjw|_jRlUb)HuV(lbOV%_Lxw8^;T_c}q;(>mEc0Z5_ugUAGeQ zm2pg1uuw=UbvK6C=x@jtf2x$5JN&)Lf_N_6^mdb_n7oag>W=aziG_S*M{Sd-w}w+Yw=AWj;&?Ab@ArOm;2_HX7|%5JwOGz~p>Nnq zI5s7L>2z2U}r4YRYY{hnuX!u_3&{inA za!LEJ*?VTIM-Am=OoG1lGvM+~53?g_aVLkSjn-a_o`h?=hx<@}vgcI4h063LU* ztpI$)qyz(VEm*v-XzR*xAV_m|Pu>~Mlx0%dK#YkF6@xv`{a*=DM;pbRb zyJMwk9jO=aCO0n-Zg=VlKQ!4=hzbFCk&Rg)AwI)2tZVZMinv644q@=TI#<-GaZc1G zU-gAP=@yqMi=-V(TU=hM4vd#EAqDs3w&!rqrMeqn)$DxQLe zO0shlQlr4k>44Yacc_(1$zm^W98q(=!KdSC>2u`T7B^@p>A701H#CA{EyzW7a4&b) zs|qpNf2%>4{rK+dwe!8;nOP&Rx$f2L=9xgK(yp+!>sS zi}ugO6v*FK8AQ(PuG?)bbj|hwLV6K!0|LJNd8G4i)v9|vJbdNoT7m043~Vgx5@smv zvWp>$1&eW)KfeT+AxWhQkXSK;ocCN9(GxCeHQC2wZKFfI26k`i8+}Ft(z36K3P$CH z*TrfUwJO;gEYAj);pdX*VRajNL&|h5SZ`{Zz!(_aO45sgNBWY~NzvfzTD}-XXL052 z_4(Yh+&z@Po}+N_KuFAlUSM-_VttuVEfftu@In?G3aju$2Memo5h=xU>oY1O;*+Bf zofRNP$bAmPT~R()zO4-j>fw9cK;H*sDY~>|*O~`+NJ%(JP3doV5Py)RNjrr8{PTqq zZDD2az}|Kf`=_nt`$^se=la-(IGuO%#ya}1<7yMQIc)?+ty%Da7LwrVgUt@BUfw_v zbL&7D1qGYwzp?JaYYJZ@o-NhN)}wG26wIU|r^%)=Th1F>9=9&ZIS9SxWKO)hMe9X+X<4&R%XwribE`00*> zCaHbx*AEQA7Y-v9b%<7(WzR`UQ($5P zP6seQ)>+rcDl!2<(>HC*b=i0*UQ_+2Qp4X2=>IFM{&R`^(M=xxdu%09zvbJ;MnU^Hc2Mq`Yq{}Rfn^D8J1caf5s;_S83paRTmX^ zX`3uV(wRQKtv?m1U>%QOVWvvT(YfP`tU#%NR+rdQmsK- z)0Tx$50!^hFF7cUX=F}0zHb=wBKy^P0HC`v=j2+DOE6Q7r622JKnS{QKivp(V=k@Y zsEJccUXgUGGN--cW+94oo%A8^^Hqwo+y4dxN|~IBOp8ZC>tsLs=I@)V;!6 zT&}fl>hZrR>wQfhoODyZ-rF8JTcB%}4*1vl%R9{2f_h#*<3HVy5`%B!EY6*$g-ev! zeRen{_Tr0)-7D~JP?>Y#7g~5hUWm(kuUz=-uH>Luupxc&)M)Ozz}YXO$`YQRznp{$vLF~fvU;9hAsh`i5Gb02b(BSP8YUV+<=LM4$&bu%)$Y-Gb~@_~Da+?P!9 zUO1*mtIpHAVR^FNd*3g~QXXi>2)h{dRanx{31y+B=v3TOTEQo(BvOgyu9&+bNCdFWYDulp7;gd)Kb{!ShI6l#XO8E`fWXL z$6RykbZT^6)Z2Q>v^&A>FJz#;y=^8@C>}lCSVf=Mi(3jh^D|*jwOVwV$eMRzmlnPy zjvltjprleP%8Oi6jS_w8F6*c7JQ;I)$}AonTl~6z+90io#|g0GcuyCN0>K}0(7IiD zd`qAcKIy=k&w+bm6>ycC{K$ZS@26*%91tbWCR^u1hOekffeoYsO>h4IXgo-XJEk2S z!F8wzrP?Q<8(9tgziB$lI9&l^F4`p=l30bNtmfP`<(^N4VFKfm#QVG}E*@o8jShhQ zWYC*N-NWnmD+Z?cui(Y&U^ScK5@U<`?vc*AzA2Y%OqG1T*R(ZVuXa-Mz@PEw0T)K>J@+xtDm0r5-NB(&u}-?p z^LS5d*7Y`qcC_HTK*_l@OITK=Rr|g(BR*tsR@A_2{ItM}@OvRlsC3dD`7S${b5}ZD z`&xgILC=?yNz^g@lp8XK!8H$>4$zu!CX*DZd;~G>Bl9jOK$ht#C~~capdk@sxv#24!~z1u_>SaRn~1_2_YT%PVy^M2TNGN48bZB?r88c@3}B*;(= C``0ZJ(? z;iz>m#~nWLN3?>KL7SrvK|1^A;>yg^82w)!H9yed>z}kUip@%RyxbD5%yVZK(Eps3 zIZgeX4v0!pp>1@JGPw<-|KQ2&Z18789VCH0PFFZ9D=P;+>+L)*F<66SjXf>PQb+KY>uV3#yUW%zRXB%dI!?S(#os zki$0%8gW#@%JVfRiBjN`4WyyxlM0?PXmesl zwvhJd44iiZXA#mxp1VxlxW1V_WLqZe^um{PH3*Pdb(tNSULb*1j1%r$^eQRx1s49?%YeQK2Ax+dZIxfX}J7nSApcouNYRzev> z07zCHs?nZX(G#*f|29Haa%B;JdA}bO4k1x@;noe`M*0gm(jqa+$|Z$VndL z1U;c5)*=2j}JbWW5!&-9M-Yz7SJlLka64ntRbT~YLAB&W`sr(Xb zoWrX-lO;opF79}jR0c|W1En5OzB0VjGOc$Kz$)rH#>`iy#7=OVYB9CQeWM49k0W$o zK#)y!wh@k6FPqSVt1*Y_NI9=c-cSMZH3^CGaziuvj1g%}cDk0*$n0JmUs5L5R;f&+ zYMF_?1dy!GDrz_J8pGn;s|a2ME3RNU?JWLYu|NNAd;FB@c}&MPqc+hkMaX^1DEY;h zF{>*+_}PygEw_6kOQBupI=ZRx(2eBl+jB&Zc~xw%6r9|7nb;*A4+8&9|~s5 zhS3UHx5lIjTRaxEA1PLNH$0i=He*3)e>QDZR;dtIGLkM-+Yqqo6%+-{kXcrH7@z$} zzK{-xafT6Gss*JiF!J#X3GK-zkiKlScuqS569a}=7*fPRPaW_8IqeN1-fI%3w>U+{ zkJ;5u-cPEjmX%9KsPGaU#53rHqWa-}Dw|x_Iv4tZ?KEx{4*%WDiOumjE%P+ZXpP}n zpKNvn4$Ee}`SgFW7(nC4`OL;f)X|cazI9uUK7BTuYF}a$D}DR6q`@veo~l#N`=k>` zzYnXVRp|Sb3IZ#86#Sbq$g;6aAgaSn_Mmj(oo2FJ&^;}%NY;vwsisD%aOq6}6TP`i z@#Nfu$G0iXzAE0ggc%C6K=Eaz#tA0_=?_yG1kLZ&S~Oe#XcaK2F5wzVoq&Z$ukK`c zJAF?dByr@+(&SxqYo!->5d51;=%_|gJ$jmxt)MkBL#!`bnH|UoOl!Msa7tjoSu~^v z$z&Z285pp0*|dHo-yRD8p&5mN#PJaw5(JM>$;#2O8JL$%tjcd@la+F$GFDjD`lK_H zwIX_-*@wbz|0`ApxUeeDc3F_iO_R^-M6XbH`_LqnPWLV>Vz->FP_p{Xp6OaW-{#^$5e#J|lu9 zc?^Z`8hE)*uiYRzb;v(W8RjVq(r4)PlXSdVf}4jn>sV@+v_6N zBlH82)+0LotcT^YL=gefEpheX{8Lo_)ry?dO(U#J?3BV#c>s=D|c&Znu zB~3lVWw(=PC-%Vodv&mkcTK=WWx<2Zapl5|PH_S#vVkwv`>T5Xf%Vf3+?8FuOcBAP z3VyNygWdxPJ3U5H=wPZFqY8aG@hZ6|hW8+_O3sL zzne1L#twLMY>9NlsF%LGf9uBkWkUgx2<`zlQ;5Ya5!<8XqQXhD7SLTiLv27w{5Vz4 zZ~uuPe6))T(55encKe_72LNx*YR0b&*D+2$@1rStuw3V*>=2R!l^sNebhi|xmi8G# z0tIHoWnQ$pMcneY11G~Q{5^NC##mZNvHCu(?M^T59pgM}HRO0#E)oOW8wM)4k=bQ8i~zl&HCK=aZ6nPpj2#db`thS82li)B{^BiWnWgU z+V!7f=f9wn&8rw_dMvYiSBvTe4f6WsO>ETY&*#i6g;T%L?5BK*5fX1b^j!P=ou(Ni zVmn&^Y7#zZ=9a5Ts@G8mSV;?Dew*KwEjy=koOG9-k#dK^!xvhjO?3N<_%JhJoV_tw zYFARL>v?aWofv9Om3NYIi(a2APpLoS z;se@iDp8U48GsDs_QtC?PWvQ>C)|Ohu*ab*g_D`0QOE$KpbEVJas&Y_5e%w=5hW$q zi`HNxuSU_vbNmcR-yIm*5tmIMf6bLf(n3~N)?h zzu9HvNmHV1G2Vs+oG2|EJh%__lD!fjU8SDFKY!>+r>fdN2V+kGvXLohKB^v~YcHMp zyEq1ZJ%j9zIf^a7KPSQTM{#;L5eNwscN4HDlMbmi$Idoh&p{PO9mhV@%vDFte~1WvYK*X!UyB zkZL;1rNg|&zvYSr-xZHz)AD0o`k64w?JRvL!bIwkGjBOMQ)NcG_dLUTHZbTTzwhih zGB%(f9-XveGQOd8`z6JrCEses!VA;UV;7bE3=TRu3G}nlKsS{J$C=NXfHW8|h*a+l zK+7_vlY)lAt?k-KZZ=q~_cGC-B^0M7qpsBgju4#VlV&8fSC56g)f@g(<5JMbdTte% zCvs9oD&|#At&y^=01b*ONVbs@HhWi10aHs_1(#jYY_gU~RnrTIpUw))0*{Kwf7noNvWIu6l|QB8g2Q199CRE-6JsPG5p#&3N{I1YnSWH^Rh~r;bv<$ zZ0IoRK$%a_uj&`2x~{7LMvzC=hl8SIk))`bF($QUN*DS|^qb1w+q$`Yi6wX|fK+vd zn+?tD3pSh@(rPTVJd<)c!%m)6EQsj27dmFeC0w2qx8vX1JtKlgL4mI0%k*XIS^yy6 zn!$9*C->FL4PKsoJ>PIk-W8tj=)Rt)j3g;9LN(0{S6Z;X%-%K!X0G>-a+KJ;ts#WW z0p(Dk>LKfKUgUr3{=KG3YfjVGN>RVr7if9hoxNL`Y;$aM`ex61r4@9;ao)`|ahz!)fdu<83|Rzk|Ua=KT(5;)4Wa?Bgvo0)>-b-KXO zA9PX0I&w`k*?uI$q>2~jNa81*4#90-J$L=Oj3M*H=a_{!ySQXL^rxlli%BW{Y7F7H zcQ7XGCnsbIssHZhjT0(jyFk}NKO5%7z)!YG3>H!LyKBW=uBlp11NH4Lz#qeMl9k<3 zkT>msBOYqAVw1^szIy~Hsy{MPb+9Y`>~nxsjO}PiQe;Mv0pzcvV>H|;=GE6faXKZd z7th_t>R9DCU}*}8qAfr%4yh#tL>&YI*_0qn_yMUZ{yyp&HX@S z`ONEmY|d62vc_}V3tMMmKl*Cmu~CF?tFH3z?t%AQ=DGYoI*C=A=NMNtw*~a_kH?3; zUGvkr7h8Ywc5>CZ-~Fkp+yZDt;L!Rybo%%H3~6fbc3B* zGnVmP13;5xIPv*Nd-lCxK#M=Xeu_liAX-3N6|>^F9P~M`e#%_-1{d6yZweq6G~p#* zk6U>>vr~hj54?QIqZb^P8V#chKBo&?&}Z zU)ZDTFm2fEoFV#F?|*EG?XJp~9v)kQYKaNE7jgFm!Y+Y65z>J5FEp;CdWB}EJu&IX zZ;K>Oe4Ma3zT2F=S~}(!;!4A=uxHJ zU@_?YoRS+)`AJ1E>6{d2^RFpqZ&3R64GmSCsy|+jaAq?ZUfw>tzb=L5)w~BMqSLfr zV}hAZI3K+jN$;qAwT47zzsWksD-nDRi~s*jgc`p9VnI7<;MU5kwO2d#78bwGhue%h zYD_6{HgZos^piI^vGIc%pQZ&3CGMIi9WBYb?%1hm@wa_7g&ZD|nshx)0P&k>0`3KH zxt{v4230=VbU(KB0dHCzy>IlDV}hT;2@^`*4>UMU_SiSZ&pllV9d|lU7DMo>WHlGS}Y?t1B`!krYp$-WM0cY>`si0 zhc5XM`Z%--^BmSLdUu&N9z7usAOR`qN3G$qyYgbz!>dhO4j zPuf<{yN{?LzefHhq-m5lZ>_^vb>4&;Q(4E?Zwi%X*7Hv~Mm&TaB?`iY@fEjdl@@*^ zj~Hh(N3QdmswNGaJR7ssb8>awyal>|Fo-z!%Vf6re2}qk<}&1-;^xKD@|13z{3>gF zN4a)}iI7q9(*z#5YkR-s=xGx(&U(A{!uhbz+vQXekx|7r6CHb~$YRx?JEm_F;wzA z97EOLYYwDX54xMeWr9X^^)fp@ENwPCRzZa+I)`@B)rM)db<)%DDyuRH4;Z$Yn~}>p z4;FGFCu4t{;%q{ba7&tP|DKySAC~sh`RJNz@?zTFNaJ*&M{ov~4E=~RYiSDtY((G%zS#CCnF4KvtMq`yTy<1e3{QomW!tM07l6X;TsT2w4*KQ7hKq=Pa( zl;bpOOSrGh>5VVwSS+KRvmff)T?%N+p3>uP`B(eeTYOovNzJiQg?_DC@?lGweBfvC z!Y_Cx^rM!htaNUPqALB0A5mfC>j(`|#sq$ZDNjJ2#>we%$Ij3Y;^fF@L}8@thdjSn z9OVybN#4_ov=jLb{~G`z;8Ih3*QWRpxL3!gbF;JUSV{F?OSbK^b92&h=v3~s@e3}2 zsuL6M)uq}%57Tep19zGm*F2WeOsvSo0ZwHk(mq`_MCJQto@0c35yXamKEk$j9>izb zToVVY2HGjO|AwZID?W}nHs-Wgjs2#nGBnqv^^O}}-#W70O~t5G#6PLW zC?6n=eKNc!QZZUlTwrP%ePi;%0?&!`SLk|xQfoR3_fKhH_XHcw zk%HsDy`Xz9eS8{;93q7XBMKt^)u7zkr&D7%`a8SffN1pKg}N_qY`G-BZxqs=8U%W0 ztx#+|z8nP+i_AwU&nLz-WMC=Lv1ve~eV9j(R;+yMQ~yJ)zqS2Js(?b={_9mVeC5KP zWMi}Sf`L(F>1&k+RfezHY$WH0Zg{5wzsLdLh-qYQbk%P}?X&^WyYE8(^VT(-xzjCB z=o@87ljaTU z9pREu&Dhno`OELUJh5uuAGu={DlL9APJg&Zo+9nu66-x)y`x2&qd8dGRd_omQ}wBf zAciAo(O-Oof_4sF=0WY9Q3ShwZIBumrU3L>7n91%tF-;oK>z(|j81Rzqs|8lGa>1H zBGc{wuaWF<1*cfP;5`Zx8B$QkZ1jNpJ(hCO=l2&*8y7g+a^&VMGL}yG`2T`2u75+7 zwucoxXy`38Bvn2u_WR=}SI123ed)hk58S(T7MJ|@fSqXw?Q?HH-sJ1sX^4j>I*SyVu78rVm{Gj)T}MpbL}=IA%g7zmY4c7lQpmF z6dORpnR1((n^z6Gs1VeFAgABANHSU+S99sa4R3N55qq7X-|7dgIgq9Nvw^4qQ2?Sa zoYESkloj(8ec{;4E=Bo?8smAjU^EF0=&_W+>cPxr6t)s|s} z_(7eenGJhE#S=iaDi2rudZTlN;07UCkKEvOY9)cmIA4>&yknD@sQQPO(`Sv!Mf(j; zuGqp~{a>p?z2g5t>O3Qt!#K2!w`CbuvfIJz=;E^Nq}Qd>;}2|KJ#*j=t^EaFY0ZO4 z*rYZcG(Ut#b>Fjo*Y?cWUIS7`)N<6EcB}+UDqA7sZh7k57fbU~NJuEs zyX%YYL}w9?MO`f5ik$Y(<-g+q0gaFU_~HB)uj^vEvz1_x_Q@$;SwZ%%#eTj5KncjD zC>`S#sx??@Z`0dQ4>-`4TmOU=-_Efsw|E@CYO(C-?3s%h>noU7Z|l;zppdB?gsWf? z{wS@L(9n^wx%raN!vFJ*KJbR+N~@j1y}3pmta~vJZJut~GbWVk{j4doLr5@e8P^CqxFvndg+uhlw zs;O$@)u(5bJHe`~sW%#O%hd*TVt-$RI*%p6^5%< zKJBPU9>l@=EwibD&DGaRxFD&AOQ%94$aDAa{w36qK2kx^H#v7L95`yjbe~#Y^7|wF4(ghip2x~SI3&ruTrA9|TEh#BEEh#Ij9s2&g)w$%m zDU`>wDU&cUM?rHTxm?po_=sLE;dAwCaNQ#KHzQhU&ot#=-oK42Aa*A^4E~k*im>gE zT%J(6h&gT{DVQG=Z$tPt44CQwu#vZOD*zL@mk2S@IaL|B2cU2gm6>^r6P@{+t5=e6 zF1&uCou^s{-PG>iev|*A1nwJAz;k$k4Zu$hw(;<$lRy(BEY9YruMW&F)4~R!tS_{b-c@z34(O`J#8obN7?_ za}H#(r5@BW@poxi8QP=p#Ixd-m&@OP#l=$rDg&W4ZF&s0QHkv!ZVAI-KmKTZmm_NZ zpc%nCi*y%HU&6-}t2-C$kY9V&_OB{L?NESrvOZ1QvR6%pnw%EdsZz3odSw$j({>jq zIxu2e=TACojW${D%)!hWgj-h6T~EZFuG$f7Q%rSUJQ*r zNVsuro*UNzv>aBI{AtzM5?G}$oTWR>#aZjR877l4iA@8i#tnb}{sy7e-7`F!`#Fuln4UW@zjMH{|XJR_uDmDO@91pC-s6SiO4#3r}w#jIxgL$ z=jB$d#5aVUF4-zLa?V@KUQY&|#BDfBqqL4ym2A|8r(Et|VF;ex`d7uvvs2aNiDYbP z>XnMl8r$Pnu_vpWcNga^W)?$i%5*FGUjg}D{o|U(-<3bNDmp@V?IT)9{tqO%eL`JD zaOYB*KUBW`ep+zSYO+^O%T;*#kOW6)2LMi4)6xFCbt50b!@cfsCa{HBj)3EogBku9 zY0|pO8>{1Mf{U(Q!wt&v2pHAJ(3_b4Ak+ALytLNrX5wV|n>S%(+PKZrso8Z#mzSO0 z_9mL!eypW2y5b9rB8!7AEshrQZH4nk;aU~XBtN^n2dmbrS5*}|mH`)YdUj={x@)~W zcYa;uG){++o3CE(Y9foJVc;}+hLHC+T5Du!!DuuGdbhWTx_F-Yzn!mK@(If0&y$Oj zs?P!I(NUyZG5d6`J?}E9v*B7wksAC`quu@J<@=k&H;G|i`S>1uyiYmrZ~XaV2C=K% zgJ&O?>%$&>?}_5!BYx02S2$!NIB(2Md;7~x|L|8~Xk^Vp(Uz+As>-UMK+xh6HoJ^7 zqmsKs7B`RUbo_RIgVkK-9@k5{f>G}2wLT?Mkiy+_M?nberU~gf^v1X@u1B_0aAYX} zg+&FkjQ(D0UMeKzQ@A&kUrHZv-iCL&f>3U}WZrwTywB007x zSNmW5_)`b_l zrxW7Tg37+LigUs@-b1vYS zk6WZ5R<_GuTKh@f@RP8G1+bL#qURr6XXn}I*=u){WZkHSL*Z-q+_o8YexH?Q?A1A8 zjx9#U8)hOg`cn+D>+tdFjSpe?NLY}Z19&>J&tt^YgSGY>I!g*j>;2TNDj*Z|I;&Ub zXvh&_FrCHI-w8+EdSWdQmc=Bv&VC+h@hE{FpUWzD95Em5$@UA)U%+-_@NnDMp-50# z$vA8Vbnts%p-e095)a7H;^xI&s~bdHf2b}$SvCZ~Ey>o?l=o8P|4gTlG;=?kJQ{tX zS6baIHoY7BJctPyB=?amyq%T5e6D!6Di=W}Xp4xD_Mmu2YI?HT3p$Pr%;$6mH;{um#p)F#G-D&_d)Zg3%-<(G9 zz0_IuW8C`YQ@H0zzj7SZI){7Uc4f3VR)nw_q<@h17CfL3;tA&+UL6h`i#(b?J{gVk zcboj?R|Ug4xZ9uIYr-^zPhma;kfZVpnvCH-1WN%{VNnN+A0}7oJnxJKd-^f+2J?^qh%qzJEk=` z6V(g-lBwv8{ zr+QyK9L|;$mIlu@7U-2}UeFzSzhyAXA0Lt8gb(*#xrn9*xk|~&`5>W#?2tYCNR z67dDY4?_L<4iLj#uP`m+|Q&!!qfa5BWG!JwGSX$zBK^XT^^y_!(O(27T7< zzh6y#B$MPgp4n#RMiQ*qTW6zxB05{lhMrBidS~(0!l%z?OD3^ltUqf%;OQaVjyO^< z68o^S9(?@mdPJY2_6(pIzP`RgHhASKQVQ~3T#p}jJHjT+QR*^;PL9nNKfL<23%j%< zPjrCrmWO>2vdRlAA{#2$c~HJOD$z`|g7*F+JhhrlCQB|`MVCz#3%0#8g{bfUEkiU* zCGXz9TBOe8GUK{@F-?GWyf)iOe%4Mf8_E^h^;OWAh;@Qvp~|0i+JQAfC7)q>odZ1i zMD{&`RGz|fxaEWX8ppLpg}81rQi~um5#zC?cM_VWE8Y)%q(-KEPl~N^5HVc(RlutG zoYpgcTR7970I`wXcPO?$*!!6igY=&b+PZx0NkOCf>sSaTTE3t*Y84$<0BZ_Ze}n7r zU%+0~_BL}ad&@L0eHR?H(yY&CFnRSwHsmzecZr7gL`E&kVW(zRW-51rWKsOwF3+J2 zchz@tE-mNpU7ORifCfq%6fg&BD~`eyYmdMqxAb%nLYdo4+2{9OiLX!5&vU}NOXGe| z%>hNuTieG2ILlH&OCvP3tEHkkun73@?yOI>ZI`q@9s=kE_1DJ95ugW_i2iHZL{(ct zKWn~ne91eLNnAKE(WEAHYoda^fRljq*A0yfp~v!0+Wbd(3wxvP&Y1L@Q0)1Xl>aqFQpPv28IK8vs`_+iT#soR(cBwU2+wsV+i6s>Rk6@; z^!R?jwa^wSIdN@{mCv8tZyoN;cw4)XEWF>vaB-yKV-wRku+kfnJ9u|kwSYA~#?eq7 zmSeBjP(v|j*(a#XOtwPQ#E_pT`f`tolci(W`#KA0f=6wV6zm{%vqB@*ztojqBDDF- zg43)z-xnv3A})kjj8`@epmHI^QI77;J%k+Aw$2)R7zT)&9 zFCJ~gBKib=CCEv0F87k_N;a4^WHA7JRJWZpG@WtUZtk!awI?SXHvWF*)bfV<)H#3; zrt&XZHS0UWBn1lJv@o3VY9kV;!i&-?lJXlkpm z_78bO<%wpkdt?JZe)n!Fa3#GO2hy3s}DyrWrYQ-q;LO;}P_B#CJ_s6s5F`PPLSQ4U(!spR@qG`by#{3E|BD8mJB z;LF|yrVKLu0X^E4jK8UzqyE7BlLE$~Gf?p1-cMvs3=vuV+hrBy+vR0xX2ww2f;}dbC`RbwTd!)`QJBJ z*JupR;2Q;5R#~rX4(jOzwo<4x#M~Vntqk9OCFWQw?6W%lhMk*|<%s_ZH_F0`3}d%r zMgUgmDrIw5~ z|LyRPPq#0c+}%#5BfQ!B<(5g=@N7}r56YmPNfPY+^QBQqvPMbtFcrV))+46Ky^i;@ z&Uq7@RGN8momYTvX+i+qa%h%x-JTF09k{Z_upeaY_`SaTE&Q+qad|H@@Ye@A@-N#O zJ*>jmAx%h%yjRc8`EyjmgTQ<3gmYk9j3v1lRRG{cN&ND1!X)xFwY0P#X>g)h|6XM9 z3Y@};79+>K6n_AEc12u{aMaw!w9;bjgODTcuIcOm0FC~yMh(~r#oLrzx23S59rvDb z^<&?2OEw}`&u}Ma+G^5m%UXG3u_B?)jJOEFPhKy-$(ZTFWqVvE zbuIU+RVi^(p2-)`;l0@xB*F`>?eQ&WQE;Kyx=UNX*GET1xg@E?NJG7!f)=M{ zyJ@0BMgr224m@+pt$z1rfvd9mh*%;$?2X&> zG|kh}1O$%}eADu?PS(z>7FeK*v#4|zRNVJ_AO)tCB?c}5fU;&(7llAf7>%BduvY-? z3LkWNj*TlrF z1;MgpZZJO6u$&Cb&?%LJi@^k|#qGuO9={oD=LEmcw*g*N_ILJ#$ z67eVocwlOh=c1k6Ii5)E; z_icDU`Q;2Vd`>G!Hz)xo;_~?>bA(2tvGfUn`NH<>_^9JI8SoEJ;Y>*bTZ4250c_xQ z)J0ZP8+nHD*F`an{gbf7Gq)bWUySdapmgpj)|p`wO$}lkVI`c%o0~)%N{2@hjkX2` z7sMjIZp!g(esheB-lx{4e3^MilZ3ZQy_hcQJuji@Q$rMH@Y)6O*s(J$Y*1FEHU}ZV zCJH_Rx3Tq?l>`IaPUM%jnIMbzV8&{q#IMHis}@lJ0E1GcKibb75d&s-_kTT?H7{<7 z#OHeN2^x;AKoAK>**N7-TQ4HAb5K@$eT@YY@D?ZA>X|j8SIpFCsZS}W(#xkM(N#AI zh3C4l(l4{V+h-1~F55{cV zlt1Y?GG}WGcvHr3YX)i@4STbM!lV2cm0U|@UPM5izMADqFzPi+sjf(duVMtl=)sae z%8SWjQU|-*PL0QX_}wvej`3pk{-nkMAsZPNA;S(@?XV^#y$i-hht|sa0d-qbqU@y) zw9uiXMVE|oVap^gku+Y}KYNjlx_!s*u$Mm(2VHSTyRH4!<)2dl1w zXiD~dzYH_waRFx8)5LYq0(9cufAx;1m3*shwwShwNH{L0fBFL|voZyO%t2c1?MjSj za;=6gbb)fqESXb!QlC_|@p;d1c;AS~$V>=H9A9sphQBJ5AoPwzQysC@Xo$3#8wN#J z*khi-#B?}(-#m5{Wz(5@4W5KR{U*F1^wvRvCV*(#0nuQ3HV}NX*_N=R-HKBQ&X!in zybAgRsf=zUvGKQj_5y!`P)oA?oMHWQSh){-hHz`tXWI#ZL(gZOyN|nY>vqFltQFaK zuI1U+8bmTncplw6wuYs*=iWwgSrxb}lytG{QzsSvFs zUUS5HcUV41pdpo>Cg{4zYXhr<1?TY?(skBE)$X%$x24-N_s6ue%GCpp>Y?fH39(U$ zsuVef@9p&?+F&kxY$Tmj+L}RIDvg_#&;hfUmmp0)tJ!&k?=EC0*D*RLXJ{=n%I`Cc zQXvd*zF29Ktmt4^SW~{chXth1I$F))p~Ah0(|`@L#?^0cmkjiR*<^AC>@p3csMJo( znBK1L`={aqo`vl4W+HK`t?uQ69dPz!rI3iGfyA*=UfCe@!JG*1r?B5e1-ByWYckxS zc}rf1zTGbE8cL){ok8r7#y{~30E;aD_oihUCtVbTeT0M$V6I|8E*vSRdLbbfx`Qw7 zq}ek!)8+J9xp^=9Yc{;aBA{b|Ah{yF$(i zO9fzY*r!}4(4%sdwz;Bnq9#F=oj?}_k&D4ZyGiqLtM$wV(*g=_pVQ5C?k7-hIhI}X z$-QT0K0*;0m;n<(E6KKX>s)bz#m+q?s8)CvDNqu9C^|Bwfl_nJ;=Vp?0g7OFAE-$h z`+H<9`}`>Z-JqqY!|wSjd3SxQr$K?gq7n|$N0}iQxO&k7#g;?rl|0V8N3=Aka_~s? zpE!iV-F8+R0g`|4Sa0c=XLb<_)r=E`qcUYeQQPbbM^D))`&5P#VAXjP!?~-Y<3^I4 z*;~2b;)DS+b>`wE+j0-nJ*)<4&cKEMEJw)$*zU1Dt4_-$u9&`CqA+}0K#L~@Eu{&M z=;fLu^60$KNuyMnQXmCcTy@qhSj<)rW%SoIjFMdCDBB5W6vla~8yRiBKuD@<#T~d! zZ5BH@umzCKhVbJcLLqo*)V?G3$J1ZJul!{r+N5WJiI`1%SLX-Jk>+zwGTyCMa}x4V zl|s3aFF1uEtFgQG@ZD|M1Y3mwoduVQ_fs$-AbK;&AvMP*4}E&tRRC#QdDPgJv=Afo ztIp+X5Dr&vTPQ~5)J0MbHy}Bx8Nx_}R-DJTZKEyE>ri%~m-vK(t3d0Qp=IXjgXpd7 z@C)<(Hv&OObw{I#QOs>KTba!O>VMwN-J9Ld|3(9WU*1m(XdK`7|5~42ZbVK9CpRa* zpfNFG_*U8?^l3Pryn03fwb&Vi8{;rPQ9{u??rq|M|NMZsuReb~;3_u6HO5qUdk#~I z4D8eSx*nLnDlyNm2|Hi;DoTWqe`gWF`dk|H4EGG@+~6jNmz`ROoa10QFAMNs5qbGo zM3~!7VEnfYTuvo#De5vRZ|M#dCn*0($ZqrLM#g}hvQr9FX0y&FOQPae$j0Lh>&9(4 zTnBO)UO>k}#iEfSQMVZ@w5XJ!Qn4{*PR{^Fs>qQjlBM4}P;aiC<^%s2k^2qfa9CN= za`dhdx|5M2l+3tW9S7o{x~*lWxXA|+!2P9&hq(LEqc>odI=!|d=xZ3!MTgPN9_)|{ z-WZ%K8GmO@Qj?K*)Fr~@09rfvhGKJ&0qM$?w~)Qu>vBfin6|rC*Q%0*6K;@4{#?&c zp%NPl*^9N$u0nd<^4#o?4%?B};Dn>kN1Kcq1C~5$oR4vG=lJVjfWd2a+xFP%X_}A1 zQZny#y7RobkU-9c3#qhY7DjJuf!Psbr=hRJej`}ExL)RIL9+nPRdDLCPBAKf@$=95 zb2idpOYCy~IZ!yru~g-6-raTGChv_I)URlaE~@dT=0A4}T<^;L|AcxT(u3c8S(OkO z8DwZY?!C>#NMM9|{~g!@xr}a-Q!0=`IMUUVKQE2Y7=QpNyXi=aCXPtMn zgolEhU!^{8cr?&U#;?0;zrpC}o+?hdRR*JQXKSl|U9~JXkhJSC6~!WW2884L z*H*c_In(kn?Jf++g|VrGv11jVdfSUmTaFjVa7}dP*AwQQMXg0)2L^E=pSz)OmMv*! zyjfBhJU<~Lz1Q{pyWpp4L zj^#9OSG(-p_BD++KdrV_xZP8Yy|!%GX9a2 z5gzzXmBHn!NH~3fGB)bd7xiyJJaU}CrXBFUBqU6&h?*1_R;Q*id`b!t;&Ea>Er$&lu4$T3ZqWRc}t>`V-JbdOT;Eg}kS_G^3st5+UUDnf=?^Bh;SWjX~}b zwgwK93*F3(L3N?H8>0s9I}HrSIeU;bnHA-F?8V`YJuoZ!(I2VZckM<>(&Uo^x$bGy zm|Jq<6ff9}wCzj7>HcMn-}9+Lx=BOGhc)tvcBTIHH!1GfV&g6)rWDSBx4!o-mKncj zNpPrb@{lL5pm+DNnMX%Q@s6f1GP*a)bvkMKDp(>iKE2P%-;o5c*U(|JUV*5=IhPoP zvRK|G`56NIZE70R+uyIuI9K;_z-m4J+!n>h^8;E$8d!h~X;k%P!pYej?!A(zCCbkZ z_3Ne_u)5M6)Wf>rDeZY_6~BMDTszfBbpDfObrAmfFLnXI2fvo@`j8(&Y&5cs?y z^*>^!jF9|fVq&sbzx^+0vC->OWW6atK1@K~-!F>zad-Ro*L{CSlJVbOEF;(g**_Sv zRMmpPXidgvYY^&~iU$!H+seYCpn)Scg5D6#p*63essjyt$rvK#K_=3(HiO71vJwJ* z*=<$&3GV?QGvU~(mLYxuMvv@r&zeLyt5`xDy1ZEWLnJ)XZa8q!lRd);=qnb! z(_27^*LbnCS~_xsv{&X75)Ep@`LYkrsAf5+n5CT3F*lgb`@QJm@CBsn?TF>u6CU2v z65J2*dYrhu^|arUH~d?ZgU@wr zWM0pG-dY^J4&K*MoHMMi4KY*NqBGk4^s+eZeqd3D=LROrZN@LedIc9tgqm8KxkdPO zwUUX62`{)cBe>1OsXDrFX3o(aN?q%+$29fQ!918>NH?27v3106g81e?K<#!o%J)Cf z+XB~mtMbV+ld0td;Ww5~Jin$A{4(?QDqWR82(Y-Bn=iPh34+Jz8xz%Q=#j=Le4n== z{jw_YUWFMg^=gP6YX)`VkWYzhg7_vEnO-6NArVM`tYF{XOqvD(UPFw}cTXjzTMgt=MDiYoJxd<8v-KY?jSTmvCK=`?RfDEQcqaf;nKm3!*A zo*C3k-l2kp8weYbRMZL_99eb;VIS z*-XM6ak+sZmRh`bQwDdXWa`&Q(y%N#m^#00iyxoIuy{iKW9P8uCpWfW&$Di0%g2sg zITO~}%JG^zqdxOH4%s;3KI)xX1x}|FTDeJSLjb`MEl~tV3fz+C{BQspqC{~#~2TFR;#x{GDc9$%XVcMTPZEt_D)x}xZS!A!ti#Ku8 z+3#H+*SOVXEWQvTLY8FM3au7<;Uvm4Hw zt*9m0hKM3+C-*rh|Fk9R&OZFodIjW2HF?fmrt zntnT2Yae#{dc$nPZG&M$)RFa2@bK{=?;-nPgO6tMwI>5g8Ga>FpQ%WJ=T%bA?;bJp7vA;*-7Gzm6`@VikaYlR-qVr}Nt&Av+FmikDxiVT(dE)Iy$*j_~y81#zPo!uG(Is94M_w+A@0>Cl z>tx|<>mHLh^5yl$s5y6E^o+`Jd8dkDJ}3Eh;7ITn4-$X=wlw`4bR}JiGaIzI=R)wCMy94AqHg3O(@tbU zEh9*Nwbg8?NQFX~%iw0JJoAwZi?%<+QAl&`Jw2>icjGsqa1vF+JAtFXJ`b|x=f3Bp zcf1SCcMn|W4>BabEy5v?(zXFU?ps^hd*rirVPCd?+cC;nLI&}At_YE-S|_T3q1y*G zDJ(+MZW|-m-qg|(UTmHZL@!7D4sHe#fM(LU}!isv`2zVSD@2Np8xh6 zf734dd6NoLKx~6qE^mUvCcfgnt&))9(arlgXCI>M>5=Z%@};aAIk~byeAOBz0puHVN0Biu z{7VF2$Mp1v@iGhdd}XP%!vq8R{VSTJomLVjKwx87yiFnH=(b=@lOuuW_-Aa!U37;4 znLK-|QT-5!qCZ(ghSQ(6kz+YjA1XpZPDG=PP^f`cU?l}H9flcSmj1@arJ;Sv=!mH4 zl6n>MsaL!=VDZi03)$}YKzZbs@#LF7P@&WPR*ae|uc)lz2f`0nbsO3lGRw8<*Z`bFIUW1y(b^m1-xroG&sV?0COfB^qdvb{uy5Z@AaL3?4rV78kXSs_LTML*7EL{e~?OC4Ivlo+~+Czqg$3t_0Is~ez zCipeR!a|1oP7Fv^U*iVyqo!H)gWD#AZ>eOUJhzU^N>QM*or?#W%c?=i$$xeJ-(S18iNH)Oh+pmDB3WflDWSBLY@UsYxb_WcS{?Jd}D|d(&<49SEv6v-EQ! zCgyjFrgGlul?PpZ0cqEK$rW=t999m)_(XJ+S^)$q1c_M2rma62@8C}eC41NJxpKYn zLld}i`OHj{sb~}s{fg*U-{Ps}p{E}--2~)6tbS=TxA^eg)8>7mctJQO8DF5_XH6@j z>OYw2O7F+e*Bj4?=Au$UZa=EQ31T$5jGR6fgXJVP(4g5DFM=+XiW5s+yq+_#xS_eEaGm2%0)FNe(}F|vtX#lflye+bJ!MId!AOwYdb?b6%xwS zPCTn)019CGUv_?$ft(h-wY}XYw@hfVy&#-{q&`Q!dz0CrzNXIpaZJPvmh#DfxqR&! zSAx~k#C<9Q9_$nU`w#+D1!{y)nB88*(Uy>U!r+A^z?2CL)+SFcX#BM=67TOvI{SLJu}M#5zda_k5C{GRE+4q4%!muIIudMm zYKMBx=utX*o;#T1e!Rih!>b=w#JE6fHB%U`^%?Vpl&Vtn<+zPNRQGm!;glZ`zYnBG zyM+9;^mc?;+%(#-d7Q6SH^1xWy+*A4&bRC5Hg@$KHWwLhFJ8rDXwo~W7lja)TV&w# zB2|=XKM7eie;#i-9qEbjPI`vtG#hQbN7z7=wCV*^(l~p&NpxdUs*P3Ten=bKeXmK8 zj$j~JxD`@8D^BBQ<|(^@egHbRKK|6mN&Pot^Y1Th+eT#xm=i~oL?V_mcyH*s7I<=_ zlPHimkUVf$@YARnLU>nyPTo6zL6k~O`Jr+_4jD*!(CcF+q9z~uuy8=$Fhk)YHau|B zQ@wItV%ui~A*W)C`>=Zu{?buk{Qk67#zckFILYp>CKhgRn~NHGGfCAok#NLw_c<_E z0UA~NX?}?h^`ZX=G`;ukZAe_q=B#)?Ar_b=>~UzL`i8~V5u7Vl#Q4%f3`TWdG20iwdyGnZL2fygI6Ci(^kIesmn0_VJY#9 z{DZPUpJc4LS;l}?u)L?nv58==@NCEE-m*VkFm&*$K|J>5V=@qh9GXzkA-}Uln)t_8 zzz#eywqWo+RW`O-#UwY9S>VIWru2pJ6J@4WIs#!y1Xg!FGQBT|2=Fhyjzl+rb_t2-{4 z1@D#iXwYcBSw8Ep8~gz64jH{ZTKVp*d3>J(^GV(GpCJ)+C$3ycghql+!k^nKrtUOU}2By02xnF#WK78JV~y3v-yFQ^Q?$ z%YD*C!jMI#sh`9r*_9fDzfE^sL`y-=DFxkfU48nZ5e$KkACC)=A8DR9C1(ucO5=ZZHO^W$wM0vT6I3Q>KMPmm zlg^~%Y_+|)wh__PVYyBXkVK*r${;10(dEBKp(Z6+{NO6(<(Mu(MIGH5T(YPG?C4Y+*h`Rm#A-HXj1=|ekf8p+JUbvER&-+ z1i36m?S$s4g!Igt8@lHS>@~*w%b%22MQnR9&(Q!XpyNU)JhBg@^E+mJ{d_{+cd=9; z&&m~k|G_`^jVGp%aK~8ZMWhM7uT=gU#_&0B3d~aq@~4pu~=U!T9~l3vHKCpy=vf z!9(D?bF^E$$4`?yl8_B@zBz)%zC(cG=TsvDV`H2gBHB0y+tm@6AQf#DF-TOwIm7k8 z$BSPLo>2U{*FZuB0@3Ava>Oukr6PR#gSe@z^)x=e=yY(Tx@C-l-tByQ+&q12W&;Wq z@P5`pmphzQAaArP@hCvd$n>WO1cQ*{p0PJz1W%TB$^Si{jtmuy51dYOgEIvDF2uqM z*ECesJRLb&AlXXG>8Thaz|{EAXmPS97-H^J{7T(u5uL0D}0pvuWICfj`m(x zfTeUYFgDSFuX#|=DV{;&^PA5>(oD!s?a4JimYf$h0#mti-JWu#{+Pv(9XZ$|K?uXl zAikhl{RZ*t8@_qf8nFvNb>d6X^%W0+pn$^*u0wmbXKXG8z{hr&`1zC9CEdUYHDX}f zoJP3oIt58kW6!M!o8VA`eXe)@6ClE!J_L>sJO0A7p!qj|uK4)Zdq$Awo0q{Wcwh^i@-SB_nc=vD@I* zuGy`2c0k0=q7d)4c`rZX$KP$>qWP~1_uEqJ09@$iebGl#khwJMj!Ul(Gznc-Kk~`yebaq9s-0teJrD4=1kuSJdC6QYY zLehtosET*owkUUhH2CH_Zf7e~&A1Ri+W^KQBrc1+EYpyDikr%G4aHRG> zn*6@H~mT;f?Ke zM?96(dP7U3zD7g<2-!GZ@eyU!)lyeimuGHBdUEk@be%v{MMQWCnpk_UTW@%5sGZ{(7+;;7 zn`QaZgbjciqHOUWc5low5P`Fxt2GsB=IbxwQ^^VmN!PJHq|a*!Hs{aI&Px7mjs`8J z1h<3ceEl2?w64B!j+0H!g!uiEZIy?5%5mR0rnom4%#?@su!McN(;%@Wr<27)cx(60 zSWzpextXMX%p74=+9so)H9*~D#mr#<*du)1sG6T~TEA*DAy#(UR|i&o(?dHiMK?4` zY$x8U%!z7uBq)zcrZQyrOPA5uXArEw;KkqM@sG%q!2W0a&*iHW8=9)Nyf=94AHr_^ zj|qC2qRt_#<`N?3!*=-a1wm?LN%~~H)gSS!;oNZZ^u{4)cV>j7E-wdnXr(dA;;9YeIHL%}31I5l4uWHj0mSW=bgW64ch7vl zz?OA#bL4c0UpFXF%Pa-6*>m|JW?M>l*RN@ujxV8obaG!;O8#xLoAY1gjP6E~5;$V1 zHxO?xdnre+Cp1sxmo=(ZnR#3&P1p+7%2#F*V%bsce@!&g_QZPY>@M-R*2WxM|4gT= z##kpcBft5^7DGJxPoAWcMi#LRQt=>LY#nPPwTxF$J7e{|l-_z&dPkc`%oq9M5uVYF zCe)u`uWopU1rUwmYl3#VGfkSzYIAe3>wc`?*U98Ih@PbOv)_6;P&t z*{z>tYINZTBlTdN1%sdl+_EIYAi3H!+q}u zWiCy-3q7(EwHUL3j=CNaQ^@8agSNgh-N(wEF#js;MSI6k9vnB(sdBCQ&%XFRdqkrL zXpV#S)Mr3W97C&d?N?N&T!H;_Gk3aFq2SNj!IOHyU4Q1i2VxDz);0FyStCYmn@)2T zBZ8q~qo-b+qUS4+9b&2lu|}fmmSx7{iV5uBn067-A;kujfg?0l{RM6TCGdFE;J@Ng zcu7%nq$FjL`8rm|X1j_J&u-4-z5Vm;G3|K7#t@;Ou@2zaG9nkdq)IEub4mwa`?pV) zi$=6LjONBU0u>`b5LzaRO8-btsZ7dI7do)P*CL$>PNN&^!=~TKw8b(RyB!`5P+JG_m+&=oe@B1fwfB5c)4bFY<>^|qZ z&egHRs*p%eQ}9tK^z#l*g)haJa^38vmYbm7xCMk5zvG;uXUVjXGH*|P-?ffIEt;jZ zov-l4ag3cABh9pZ!AbMg;mOLMi%pmatZ5hmHP%10fvLP0a%}(`q89<_0H5_I!BB?2pdCwgU5hE_aoSPa+%#YrDNamY|-tJ+*E0AK z?&3_xdi^gEI3MwKwnK!hWIU4J7EUyFL=+H|n@k+P>e z6gcELY!&*^0@V(4QB&1?3Vpe(+LCw!rHNFWkjgo(yVr*EysameMEgsCY*>$aBXt~4ve>K}tu2CZlMGLLKFC#TM`GT6&)3A^%bs*%x zaR(dDoi^k#)Z67`1;~)dg@R5mH3h0vc$Zd@p5v$m*yd!(ejG?_=xo9o>6ij6nx{0uIn8sjUU#-81ti#$ONVYwgx@||$)a4r zm^3?X`iI~2!||n&PV|zi#BVhFcxTf)X#p0@ICo>NKBJnrTBiE37r7V3VPrAV=o{+E zS-Gjl7mKH-Pls-z4z#`ax=MAF<*gG9m8Bf@V}6dtk5Z2Ajna-X50rKW-}R#Qk`=yg z)dQ=%UfLE$X|Pf6CwXP%_U%0O_=Cj;9wR{;N=-j>FSneGt(`S=&!cI$t z1E+xZA`y{%w~C_tO9srXN>i9$DO~CN`3JZS?Bj=CEx@| z@-z63g1qUoL&>?JOI*X^73}FE!y(}>E8qZIY08yRqaDHzl#9I-kE{FcnPvJaZ21XA zMQGtivOFN1EWIqo(rmQ%-twz4WHC74SGN|&w6`t8_qW)q*XKdB7zp>*ni8poj_6jG zH?>QwqwlRwFRwg7Tlx4qygjIvob&a30zgY0(6kv*9W^<-``pA^#@AP>x?NRa$EI(b zp1FZj^g8XUePyZx^?!TJG10nuN2o9WRt}W{UM)gBMK1YDlY;|v|Ljt<#eEYtQKwJ9 zI&bR4`lIgCi7b3lliS61kJSxSk4w3! zc@Ia|V12sRn78j{JKaB(Dms(lyY`eLr>MvwjYt6&;JeoM@uN9Q)6N%FYgN_3=}YTD zpn${8_^PQt!hj?hQ_z$VD%bkcf%lP~Xc|FI&$9C#Ni>6uX7BSWTaJ>sOMp-H+Y(8Y z=$mIt^4WA)v=ABy5_knw?P3UMN(xB=Jk@j)=X$!6$O}l?rXV^qlYu zJ+a_N^fw)`*;XI3*i7Rqd_Gzzbum(WPT}9jg2QFX5)7OOcGOy-5 zHprWwDwg!b{K4x&;u?=VTmk|^6Mw|`c)Dzeqim0N8g!CkzX1fh@Y(q_g2AIWvwX+j zNf!M<(SR)fiXnux_^S^Gt?pYy4$^nAnm%iV5eXT)nJ+Qu%x?+J-2+05anO=YhcSoJ z)*`j5{1mow!S^(>K80+f>{z@$aLay<@BO7Xi9KC?_hvpZVuQWLMgZT9{WXWu)x%-< z0EI8(7Mqd{P+?n+Tp%1i7r+*X7pNp?V9(2st*HMMGB(u&S{~{~dSp$q1o5&{Cdv(6 z3f6-ge*X+ai_*G8?~CV;@!QLd`yEvcM!le*Lkde`!k>hSY<-4F>CXZJW&*|c=gaaD%IKD?J8 zGIoUgV1eUOLs=q>lOj@q&Dwk}5a5+c7H1YyED#DG*>)_X3(_p7$oMp%dd1Z#R_I5= zIQR|sh($gmoW-C=u{Mrs1AFXxP<4SqF4nC4vaW2vuaCh{u{x;benYqH0}o ztQ5zlaym+*XWjpaweuP4OTR=>ccbKHu+}u{-o?@2!BgGz1R~hf@$b+)R(o~Z^7$O< z7nO@Q6Y0eQ@Dv}Miu5G)c6AETtUwS-&+1KyuSUMEp$(*S4IHO;(T(S~SLS@pgjJul zgTN9KAidtS33D8cHe{0#Md8EvG;9|YLJ0&(^i57r^LN^bU}uff zR)?>fRoH|4KTuEk#ksGLAr6Em>DOPX=w=X1bs0fTS?2doS%T|L_1x8+flW+&WePv+ z6MpEj$`kt*@L8|63s0Vz>8tEvvfXdC#f`673zxYR@1q8vB2$l2$;32QH?2Ql8opF< z8j@>;ksMGBz+eVkRT^J7z$00f1Br`1k)BHIp3FA+U$Ip}Ue^y>9Ghe=2*pA_zBMrQ zhYgf=J1avDW`^|Gt!6KR({?u)`p;dsYF%_uJ`g`3+&Y4*fUquChD;qi-*pa!&l9L5 zP2v4lv=4nZ`GIt=TQ&j*;?mi3EOr;4&*Qk8&HYLxerVpjYIzCZf!nh^l_ha>%g%0Y zRf|6JA{O%}m+(+&kF~xR=kgE#utPrkGEyKe{4B&j@>Y=vfAOM@nj@$%s3O*~veD{= zRlZ}ajSY$R4H8d)B*HfQ8iABZyj}G=rArR%@e2ioE7R+?!fu~M++?g1ijo}6WGLN7 zi#}a4%OwHDT<~g-C|vS>PlgX7bI;0M(MB3lw;=JYGXee01x6f~o?xsIj8%`wfA#eA zbi2!HjO~51sfsPpv)pPG{;`pNW243vaAOO%;a=WCP&axqB4x&gTl_Of4)3dFb|6Dm zUxetUov;m!y*X7a0x~W{?#|8gfz$)AI}NY-Qmjt{HU6pGrlQ8+I9^MK&#s@eS5&1* zfp@($zO7V+U|3T7EivESK939m@~P@5)=Tskn3@kGhXSP%nG>J{kI5?rP`L5USAy@lyzHPs|rrQn^11J@DAXahsA9J_Vxc z>V(}4-opC3snvtPJ+t(UsLrUxf+7dJ1aGn{*Ry$eDn2%Y&uc*_K?}M3 znGK$Me~H5L+^JJ?=8>!eMeASBdfj0ICBuC6-vF}~K`D&}M<@(q4B6dlBKDj=2>tu@AkOzl&VvSOoMxHio-M`uZV z1k_o&#a1vf{+o<9Sy3IvX&3vje(iGF`9_u+6>VaA10699hIJUK?OFb-~N*tB$HtwplXI;(Ui(6QK`>9VSb=y?BC3|HL zpVb1g?G1=#qY7<#TAHFf38)PUdXTKNBWt5OyV>0T39qb5vg znRtLM!bff;@?)*ML*bz18*X9Ptk`)OEjA;Qx|&KSOdBa2LyE7>)gI`xfnKdk(MW@i zTqW*0dLR2%R@-H8LlAwHxGkbBSxBh_DwSH{%W2JyUxuV-A+H5oVBO@YgXTX9g!z0B@FLNxZ>Y&uS3wOw$_fr?@rv<*syjEg*iGpHqINI*xouyW7xKr-z; zN^5YG{KDLlHWS{u$ea7A%!WwlKQqh`{~Ybm=RZuCZ!L@t*?sTAk~>#B8}-6$td99Q z2-ZL;+D0`>$Dd!>xAKYP;8yXjtT4=6YZ*{r-jxp&YUe`kTHMq{xYSJQW62B6=_NdD zWNJ?amMV&heo!Qx-vd-%0L)K$#|)f;8)NIhrRHiM`zI2cDtYu~F&c}^y@nLt8R%3S zcQqbOO)GPT6-#Kn(&crvZ(yw@J~=ftuGY2}a*yn&m=f4lVT8u8=5?SJv z+1ifI9^oe-<|#O2%rT{zjk%6IuqO+Q*@q@RYFR!wBt;=ocHlNNDj_n%O#T>d)$aXYi%j zSVgd-dnUr_ms^p7p7AOy7*RBre+?b@4{8s6TAK?KP20sGLT!^G9^%}33qAPWTPf?1 z(j#}aw+CP?!Y7@Is~KG5q1S|9a-p&ME^$@Cr4G(`+_F17Z!Pf6y=(G-fF})R>@GKC z!oFUSm71AvvZ93krQ_t|(Uc(@n|`;RK-}9dz*Vyei}G8-Ls!3*X#&~Ird1!D_&^W1 z%PkcNiV8Y#ImyAxwlUM-(S>q0HMtzuVNtueFTy{xDSm6C>?;Jb;&-n84AivkZ*GbA_mOziwf%kB`7nZ8 zyKf&);#DMyD>bzfY>6O<+XIQ>quSqnty5v<#kER?IsmWR=?FMp#PHbac#gb3mO+Ay zWTrxXz6{HEHW7RQgSvg{CepJPfKtg6BPEeLDFs#8QHh4zsqEEIR&3h5pLWd|q_RSY ztAsGWScXJh>&|i?5UFu!J;m8_dq6l26sVIwuAT4NlaIW-F%`OTR402FU$Y2JD(YqL zv&i@R>E|37k$;rL4Z8=(60>S8yK=)zpED_CO3CIsIGxXffjC92=YZb)i6|G=IIuKz zrL9TQ0)GaO4gD{5w0{)0cf$5%ICPd%`xEDvV+)_;g&F4(oLaa+X$?T!GZZQGAl{*w ze=0vX`dW;WiS`0odwP>Iu>D~||4!DBWQq^a!7IifU*<6yc6ICuL6YVaVQP1E&rg;l z#-K+_^;>PU(pZsFjo(|uPO5S~DcZRsupskHeM_`*G~-+Hv-80CjW zN00GUkz;l_zl|i;UvAF@gvI*1DIECoIwhRSep~x^bIUzQOi?05f%V5ea(&87j(fE1l5Ns$ zM5yP&%j0#MAqy!+_l0oVp?EUnsl~M3i;*lUA4$#Mydzu{KT21lOV6Rl3&d{q<>;NI_wTuEnFjAQV>NLT-$iRBf|EPJ3p0_4*)yLF9hW-kC18cuT%f zZK`_?ucopeVB~%7NSmQ zj3!BrbkCTm?@$w-!zsJy^v&;bJ~A_qP8rFKrp}(!I}DN4prhY`c{PkUcxrMq_{w&9 zLq0`Xo;G>)wuV+>hA!DA$4_JKE@HqO!+9FfOxP)~semYmMT~VUfa<*sgQUAMbjv9tn}9Z{O(= z48q$d+`1p}Syh)nT#e`KmB!>Q&A&^aKD8NoS9PQEVq0<+A3M@H_|ozZa)3oPC6b0u z2Va_m!coLx?_fuTChj@6axEnq2Fyt>Na(Wf&;i9h3=RmHqt$Efm3V4p^CzT5hf7zk zy!0mlsT-I3BSqbVt*BT$HQpT{JkOC6bJ{{y?ka_1dh?Bd7AQ1F6(?0etYm_(v#pk< zfP%#h&EQ9Agtm)UaL(^p!s9iLK!t^sxxr|1D#toNGRSUdI6>7~?xgmxU8!AMT8af^ z#1*1Xe`E%Oko-}jIl3@+-2sw_D`<1c*v^`GL?^l|RxlddfgT>!7=2E5fxBye8zLJ4 zjuO4H!E~JO4imPT&99 zaXlEH_t@~`_mGaYz6bWz4vZN{oz8)K~ALV?C&*JLCpLW0blH0e9E3xmKJYJwCFf6Br?0_nI zFCAZqjA2}6-Ohr1rxf=%gyyqY7p!{&`F#-HKzeeI-27laN6o{fY3edQuzzVy1bH3) z*0UhWk)hNGQv9+f9Y-N2C_Ah-ZN-8=W@nP_#{l{t>nTq}NdkY&&HO2}-~d`8?ZZe$ zbpzNxj^fC7Ax>l3BHxHZPn>ELBdKSzHb<9-F5Jc6^B3W zS0vk#O7u+-x^m|JJz$|kUW_=A{#kQfi&J!heEmX~1rEN^;w1hC*{|y4F-u&XkibGG zbHUmhRPbEVA-p$rM2Y`_Dj?_NwqyF;3ZHiJ6s<5IkzVdKLR|5KwCclwS^c97#k)AD zM)k@Cv``J|tK%}?5%K;)CyWrmmYP|>U8Uj9K(5t60vfU~#)_hzQgKtuBYhF95IIRL z+SKYDISQ23FN~=Y_ks8+F4zd(2WEtfe7~wHWt3Xf3~vpxww=<%raa3{X7{-XC{u&h zUXmk(jAx2h;2-DZ-_awn?v#>KYHc!CtftEA69E6_rlYWk$gUM*Pq}Mlor{A*gOEiN z!e`0f4&TA|$3!tZCVW~g$dy28L>h6WL-?*e-B@%GBD5>BS|x8V#N#~kmWqn{=X(U$ z5cuMHS?~EQGhgTuC!WV;&UxDKg)jzo86FIc@)#mkGKIWDpcDeB^!G?*1FSAoB+nb$ zYW>RnWbOCI?*%ag+zwDm^Hzlyr*k>BjrEh9K$EN=Y>G!o``GxC3c^}m&fazOY~H~t z(#C;s=$5CU?>_dYe~=gCJsB)-7_ja*Na?aTnigT~b$Fa~mYHohL**iA#?hpF=Hjqh zXZ_$#3nXxwjm^lP%0EGShXCZ2M)iK|(M_zezcJcRzLA<}{YB}jdi{n?c$N1)PN4)| zJaiB`!j-AOXZnjM48i&hoM9*Hdz`-PS-7y>0BgnuZOX=-kZ&Aycl18-Iwh&%s13t} zYc8&iIHmQzpO&2Oazb!T&h~r}3b6M)_gj$YOSk!^$2K?fX-MiTpH#6ChrzGl_ag>1 zKM=U`lcRGV)U9U90SL<8TFuk67vl3CkRu$^30b(8*$&Asfm#?~k?dLf6x~?5`-38p z5*>YVpWU1`1#QVY6kZyG{uw+mDSk`QCElpW`^voDdP@f^TZw2JrQrEQ_h1i20a3`%U9*jgAYR-n+V3E7xHHs zo0=oT9u9}$gfa%e@L`vK$?i~+G zT{BJk$fk_7cXiEVwP1pRAZLEVM2@y4Wwis#7p>Q3e!4>a|ES5P*C?6l>_L5q3B^L% zu|lxotMrLnZObmPA(K>NpBC+B3LX5Ii?&_~aWZcnD+8mqQ!ml65i|uM*3)+loT*6< z{h4I;P!4bz;c-om>Fro%!8xE1z*|*;rb}K?d?QznUiKe+^|1eWM!fse*7qTMv+~p^ z`w=AmWo<3@EJn;7LaC5;w@T_3?e8=V$pty+R1Z1N41d1gQu9HdZ%n}_^duyfot8sr z$JKX1!C=?|`*_EQf7-%@cRr)EBSJ<66%}O0AF)k%WxCV_pTceu2Or?Xet6$xPsXY7 zrR2JQ?0O00GTLj}M+=^gyTOujjRast{sR-+ng;5fC;B*?U19Au#dy86agFH>@d#Jl zd`*XcB^cq@i*jV+*bZYiglYSHcs^E1Lfu^H8YzLd%QxBOMO$w4o|*G)PSE-22OOr? z+9#Ln0`H->=`-nrs7MmT?-shJ*1b<%ybK64b|sstg2cZKSFIMG>U`6=Acz8YOa+2O zg2L6z8~{Y#^$0a^>dqKYQbt`JS_#ECMz`_&(QNpX_eJ*A%6cHb6+7CvVjJ=sg$|{wh2NE-oz-3$0*l8>9|u0t+KGB!&ZLBzv@JG zG<-)aG~CghMxxHW^2w=4dR6Uz06$4r`w##rUYn;8>B-F7Jmdhku_3y4}ua5`Ds z_jPx4VEo6`C0S>V3Q}zE1ytB^TBM0sM?Lg}+CCo2W_w<{CgPNK5KST{pI3JdSiCae z$;ruOSE8-U%aDdI%D$sg=G%H9=J?$7Kkm0i&X$GeHSfK585As6=HkVkGKqh;@L*6f zycw)LEmtk5x+|KP>p>3wDpzcvB!S+Z6NWdOZ=A#$q8es)@Ht+91LW{Erbwa@`;&`7 zpkg`GQuy+;rRqVZgV)dzeIxc15Ogn_D4Q4yj46^*0hkYt@5YckHDPSJ6aB1qSyA1OlWJx^ADW9IdBPS;L?eQOo3$RdxqOSa(C_Q>o_$E_s#T z8aT?kU6#iX`m@l@bK>ZO#2;N5pB} zvnI^9AD;#_R7ai$a#G8D4BxX+@C-JdaIYw5W{ad&81}B{1}f;~G{ttP+4E3#`qcfv z${^GN&#rL@WU0689o*c^e6zd4=>mAMIPx9VPA3DOxLtMDr3fZAjjFB4CnK#K%%+_F zdM$C#sZFLLOu(IhwN8YK>qgk60VXMtEXz%??EyU?FIS%Hi^TOUFb<~%^z+2{3iF+4 z@J>5J@65^PbrR7oTCiV9QqkL$LqzwrD$jR2U z+p@@}3(ud^TenW^i?xO17k?!X0(9YxkpMxdA~d(wE0W^k9w=G4mETbdim?_r$heTQ zjrP94qMqI@s&xtk%D`M5pP2CSc@u)<+}O)ij$4{Khelqw{VuWw$i$;z?l8$I_w@d` zPb2GZT4mlC->|ZI7-Pl&$mhRU50fmiokj6t6L_B|Y4O|ug%}k!X4sXwX4{%GF4D0Y z>D@MLt!H4++Y$AJqJ`2?Ac3UX+H~_P%%$R;y~jwG`+_#SFjAN;#bw5g;mvq9|K&Ly zUP1Les6TIx`d}eVIZ!4j`8Omy;6zG7 zF$ri6$LIAS0GDci#454&{19-q5>zZ2g_LT^R15C7{HL zQFKyJEs$#QGFADd`#693+`I+Y+@Aa!Y+X@KPMC&OzejPysPmjB_iTRiw%++?iwlQ0 z05PHk+>|GhKu3kSp9kh2P;%+!b;6@GEG23-?(q;1ukg5YMc#`}jBYcfz1jS_mKlvu znP6*yufJ=K+vW1g{KXOcEr61hN3 zO=>a|K(UL)$I>@kENm2Oz%OjOywXTPUh5rgot)p~5%4xML@|my^lN=_P-)8{iU2BdE7y z9U^aa^V_O#;q&wwKMsnfCX8vJ&PQ)taw$qahFJT&Eg8e8CmBZR{N@n{Fm7SgfVKq5 zLCOFud*smsG*OU?J_BiQ29*)MDskzTsqF*Xli;C?K)#AjuVo+TO60Da_78z4-5}WY zaR^8U);l+kR^HVA05q7fFJ&o2`mg%yv{a7$Y58Gf;YS`-QPrM?SFY_W=Q%AlCl;{MPB$^9z76cA@M7@KZPfo^AL@3vpx6YIqG%I>jQF`P=I}bx>^NlRPK-rc-H-XGSmnv z#g4KElrwORIPi>2^t^r*>hgL%o{V_`fC^9c2};tvQzU4x#plHjj)?<4*@|Z^LqHYZ zD=&{QjMygDEfnQ${motfgk3Uwr&Oy?SWt7tul^7a!&Z@Ll%g*X7vtBnVm3->^vHK8 zasN=ec+I^XK5~|2zd(Xx?vB2rqP9^@v4O6XA>ATOR56+GE3X{LNfIW$?cjQ)^<7V2 zQ)cA{w7hQ*47|m#SqLTT3Y6-Xc>chQHQEG0tllNkUky9&Ck1wgnLhtS{dNmOz6be6 zU6M-O0y#kfSfoM zCgdxcUKfQ#sPLBmwNteMC!(`AUr?SgwJJAB|2b{+E_lHq08`l}bX6}$|5C!|=W04= zE_|2izfR2KE15fMdJqBi4q=qtWimHq`RQuXPivlg zO^d*;BcQ>f7e`sE)e!@TigAC|*ZY?cx>eaK_Ve7u$2PR*P&a2BM{lV&3oiA=yaj}A zrM;P=qO;o+gjM@64Q+sv`wc7dlPVX! z6pGc_2*z|^VuW2BIOhlvkIQwLx;bMmw;8j1Qk$qKkV;Y+GTD)`gW6)#%I@rl-8h97 zzvcx~oevFqcC5BbX6p1D244wKheP(HO#!(XDQvU))l>2*+~;$UrY3ilkKnv1nZ_@x zJGYdI9TxxU$DKr!|EM%yJ>=xP=1{*d6*Qg?L{S54gzc1B%E5V7d= zob=l(Q?aY1rASs-X*>H4|ZJ6+^1URiXo%+k^0^54?_yWK_k=@A5S*X#yddl-)Sr0-N`g! z)eEx7GYQBkcQ3qSs z!t3@sCf9f0?<;XuZ3vKVH;1HR!*}hUv`JWo5oBo^pQWi0so;mUVcOZqFO`g4_H>lz zdWZhYU_tSz)(y#=*GRrxc_*CUWv0ZP_d-+3^nnTnx#`nh&7MDG433?HSQ@Xb1h?i3 zjnG`Y@ue#pvDyJWbRx%aEbPB3zc>MGD1M8TF&Jz7d^YdyWf{Pw1c{Pmwqvb&AgK~Y z)l-}Lc~r+RK@?Bp@}Q!nR!PFl`C{6h8Uufvy?5-dXG@}+%T)4WOfuqXr5j_GDgLR! z6Mo0>HgODt=2A_^^L4SsRVjMh66^7j-bRLDzi%u6xj^^3hoRiUFA|EGLgA+jlGLXy zHKwT3Jl1+p2v(-U@6uB8-F1DiatfMBXuKu*l8CDG%K5R=u+iFt) z@uUyRR&U85f-5Wuwke>d-fz9@tuks1w+xbej zg-nN`gh)Jp$(`TT5#Sv?vQuY}SLC(tsWS<9?Ln^JSu`J>0`3IsOW_`jA|fKpP8g1V z`SCr)uZ#~d#s&s;r9e)KXQhdg3?)LXA9)nvaCs?LUHI-0E2U7|8g;u& z9C`1Hk&Z?QI_`NmYbH3FixD3gxiUCYHdihfh2hBO>nf++s-ZNeUYrnFMugaRPm&6` zmhSlILCTkw##;+{k~vfV;Qe5Uc{;9kaHXH7$R z!yV}=j$bn0WiDFmZa{loC|9d)%T;uv0mELIO6L3K{5uK~PB|1(SqlnUKl_hyhUFTa zZE+oF+2e)lZLE>!o|Wm->U0f&H?$9J7*?>4T~(hkN}uMNJ5{col({2(#ySaJxf4f= z%2?W4Ir#2nFLov!4ZoS_5Gaz_=5BF;|7EzA8CAB|kYX*QWwMcpBdvySu3eao1|U{( zpar{jnjn^Ff=|~-=;G?&Au0$>!`KBF2{t!PO4R18=Q-7jJt)9iy0#A-P8KD1S~~4K z|9K?}a(->D)aW5&rNld4e|}eZVX-H45c=c6LH% z_-?Sq{~=ue`>u6EzzF8lGpFRBlV>TQD;x&jfZuAyDzg3@iFjfX>!E!y8tIhsvUQnXR4r5=gY4*dF*~S36Dvsv5j%I~A9Cqh&o(yU)Z9&eaADX?@vaBg@E8 zNLB^m$&0>4fOD5h6_tnAul<{4ub2y%(>3N_Vd;?xJG*~Gqd!{P@Aqux?2|P80DEpg zCJ7*6$RnGk+>q=j;IfV#SKFvHvG!* zl6Pf16cpx*A#$IM6jvo3GeJY7U1^}T6uyl7i}j|y3#as4!;dt?wX@oUdJ86QKU!ES z2R(NtK`_xQS%UXANAP@{j4_%++Ew_l`|)ta=A|@d=VjbPUe8>3}UL& z=l1K9o2Hjgfthh^CFa&ai|#_5giYBUp$2efOmpV;8ojyZ0Gid!(AD2;FskI@*LTaw z8>>e@)sv0d6pq$spiS$VMrKCAau~c`TgAVPc!?@kZA5>(cZ3Aq9BH!9*k2khHv2${ z(~3nnpByA#l$i+^JZyfp8w_><*W}kDzkElO$$${(q#MO|Qv;i@;7<>Oy~|pLc~FHA zj0Y5y;KQ?S4_?bZM8;hUNA39*^Ru2;Cs|`RGA+hxyXRAhk8Mr&@6B2V>U&Vh zDPxzW~WPPPxP?hq7E23dN569IkpJf|6l8U(Ww zwoC4wG=PUc&Z7Q<<|m7EgCC80#Gdhc&>4>=qu^MYe)wMM7r`)8!(_@oEc|Wh@Gm3f zHB}DiB$^{bQGc^=V$XqX9+iyQp7(VNZRjfHB4js zYg>=(%~UO=&A^i3#0O2qZ3raa@V8Y7-^ktOzf>@At99*42L!Zgy55sQzo|H?Xzt7kz$0@$WrUT49#3z`MCsO z1Uj4KulNmJ{NuKkQ$h6PmYwKylkw3v*}QWj+Y z|LGs!PU*Rt>{)!bYIVg6S~UrPH(s!+9F*YoDiTcM@M4H2nM>oMbv^qrl=X#s+M}4N zuEXPnH1*^P+3cz0YEr9L0(S82#8iG4f5XA~Vt&%h%VLNF`QSd=FB}KDCC~!6Z5m!A z@r$p)k!`tdd~0EVikvVHtm>Ut>pYKYM&2jg7X`o68!~L`d#!cX5c5B+O(KcUkNxur(@U-@eUC?mQ63>ZrqQ?Pz5+fh00+&jhMZuRdzKY`A3aVL9 zxt1O2P6b-(h8gPK-z1}iwb0DQ z?gZ0}MslCG7_}T8sU_RXHk`WCH#O-)&zsNRC0FS2M`@N#qErEbL{p?$A?t~Yn8di9 zC!-&M-t>YBK}}~3ljd?2r#0bnSNj4r30%`{PXwg zq*XifTG$ZQwP=sz&S8(`hUpW&FLs^~qJPjot*b8mUC;O@EvXX9W@i}~vFAQO3xBUC z&feeuXkU1G=-W4VjbyV=WS8PD}lDE^}a2%I;E38cEHJS zMRL%cDsOF3FF4%q#m=-oe}?WQj#FiXSUsd87{U8-1826{oFp*E`PF~tNq?dT>e9hu6 zlIt2uFIaTnFaHO#@sd`{8dA2C>xP?lNs5AoWm-!@)r2QFBX$Jp-w!j;;}1o<08iT% zP(%+WG&Kddr{%#Ax=wcP%CgYNMP%X7KDwevc3j-nl?=BdpYaXL%Ufqk4+4&n?rT)V zY2b^9)B~G{y=EWCV8!A65*zycXw{C4yqYQ-pVor+dI-HtToPvEXfj3Ad_@uS?OQZk5?+r6o z_pIE+M&y(srB6rtr*`S8fNTjf61*9&TZK&EH9I((Cs;atFKu>&>$#jU!DRIS^O$Q* zv$$p*D_v?J(5qR~ToBL?$MEFs`Q7nc(oJ?d@7+Sk_2vs_>{6$<+0vtF%2q#rUSdJQ zv(wfaJY#vNGT+LfR$slq1mP~U35`|TBj-|qa&{^|@a0TxnZR*ktAdRbnoXbyYfXq< zw+yJ9K`>(TbNa>IVhpp4F{Kpd@yOGky`@@mwxWMq%V zJ-xlWssmvkw7+mTdf@FQ(YCHW*@kJMo%jgvzcHC|e+1oEqk9Ve@e}z*7Ce%@{i5Rx zG?|h1Y0>?J&2vtrzO#-vbbq1YA0X&^;-q+KO+kTPToD;QIJpE}U*aLY+-JjL@df_x!<+%F==<@vgRk`|U0_i+Et2Rs+dNhe6h8*3KFh9?PXF`ozs?%GN zSG;QNc0<@fRwLzR17L{_LrB|t?xfxFM!jbVe};@Sd%wpwf0v-8qj>rfj;Sf6S!^P# zu0*y|49`>W4{PJt019Io9I??ti~RWDh-A_(nZM$pwN7b;0eP=?iMd>FtY_U8-lX8H zMcOc4dQc7Bdo`{|wn=Ngv1FtgmBNHz6C2fyCPhzH9 zf2yw?A-@gd2jb{F%vp7U!H4THe_MPr-|wF3_x>Izh&lZ9MlScXwdv1#iQbnY?*tnk zJu2(%EHS4z1+(N+^@!BqsNVIh?97Tf>9$iLgCj7FI?bOYGNtMWwPmeG)zn5Ws+^b|!3S~N>q11N zjyV=2zaRMfsCPzkL7j<~Q`Bt6KW=sDvmPlrd{+dh61>SafNr_n$!wwt)EeT;m3!X* zF7W${EhFCXWN4A>ysybO*J%@-VESLIyuh3XU(7ldJa&#>{d?a`cKMhGCK*>7R5g`c zGtY~zOJDFv_&v2I+3$Y2L`3xylSYtF>xan~;~XN9%1BIz<0_lN#CV zcAa$ddU~?k#N2J%0PMm^qGDal$W<>`Nt6hQcuW89WK;Fv!DU`e#}lt3c*m*^ZXlk& zE`7{HZSZIyeul{T5i#iB+jjK8AUpVv`8w%>bx&SYSq(9UHtE8_-+EBN7*fB!MNDMu z!b*G~1?cg^Gbpu!ann_&f4|r+noQqeD2n&t)pR+rH+5IFv*X$ssXKEYykbmQB0E24 zHb}(8gy)2br5Qw5{J}h_Cy^UG^1*}2$~DbjPD?l3rsp2`WvUdV+g75+_t%n}su${M z28m2=vH#tX8CEXu3cZ%Kq0$ZIy7Z;}kmRVXcAS$&_SsSLNOg1edIT@7w3WjPtYcnA z^gUAOFAB7SZS_3|HW>Bz-(V*8`;rT)n@iVScv)Q~>eg4by7$CN_&*1$42JO{ie;rv zYIsMS{GA8KcK~Q4)VW$hI7LHtej}(=Ks$27t@G{EEN7CB@vPHhre(m zdP6a*+!6G|(9BFWAc*(xkJNsS_@C=Bu>YO)!~Y#tW7l+&a9e_F6!-g;NWA5C1OuUCfCmtBF|HU?dfL}p2 zSY)nO|2=iUzHihPT4=C>+9>eJ-x%gl`}0y z-!3o7U>hlH=<4UtnYce^g~*~{My*4-y0Y^1P;er$f{qpFSpNIfF6x~{>{;!3w&Qp9 zVo65!&Y$5oE{-h32P-Qp89l28`>lJQ{|pm3>mG2z3dVn2`90k8e}+A|Vdi2iZSi)o zaeqZ7i!{l9-Zn5FgznDVjq5F63yg}2s-utli!ByuMisvij@98Jv&w9)-g6!(^ApDy z4IMf*`tP@_w`q~2Fio(}!T%XM;DgPdELA&AmorBHC9A+9#0uU5+I5B5zbFOyJAu!K zU>fAz>h$S-M4-P545v{r&KNuL9}-hmnRPTbHwR7Zz*b|Wev;0iSY&>L9i&J{M<^o`ljha`nR9*yd}9NqQ82jb9vbu-_jA#J`G4mGc3fiavm1R}MqUQ~ z`s(U`M>BszO8`~9p0jtH6l7~@xeQ(v{BM&LNR0$~y(CQ;;t+W)J{!k=e=pQ#`_ll= z-s~O}E6*Y%%kpRVjSE-^p8m~aSezsM_1BN9*0|r(vAZlZ^`H&=OXlty{11fx&h!6& f{Mmu;qx%<&uar*v#WO~JkElG;P%M9H@%H}#>|hD0 literal 0 HcmV?d00001 diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index a590eee1f11..c04d8c5f578 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -35,10 +35,10 @@ #include "nav2_util/string_utils.hpp" #include "nav2_amcl/sensors/laser/laser.hpp" #include "rclcpp/node_options.hpp" -#include "tf2/convert.h" -#include "tf2/utils.h" +#include "tf2/convert.hpp" +#include "tf2/utils.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2/LinearMath/Transform.h" +#include "tf2/LinearMath/Transform.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/message_filter.h" #include "tf2_ros/transform_broadcaster.h" diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp index 0591f100b3b..0de7da7925c 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp @@ -23,8 +23,9 @@ #include "rclcpp/node.hpp" #include "behaviortree_cpp/behavior_tree.h" #include "geometry_msgs/msg/point.hpp" -#include "geometry_msgs/msg/quaternion.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" +#include "geometry_msgs/msg/pose_stamped_array.hpp" +#include "geometry_msgs/msg/quaternion.hpp" #include "nav_msgs/msg/path.hpp" namespace BT @@ -112,7 +113,6 @@ inline geometry_msgs::msg::PoseStamped convertFromString(const StringView key) template<> inline std::vector convertFromString(const StringView key) { - // 9 real numbers separated by semicolons auto parts = BT::splitString(key, ';'); if (parts.size() % 9 != 0) { throw std::runtime_error("invalid number of fields for std::vector attribute)"); @@ -135,6 +135,38 @@ inline std::vector convertFromString(const Stri } } +/** + * @brief Parse XML string to geometry_msgs::msg::PoseStampedArray + * @param key XML string + * @return geometry_msgs::msg::PoseStampedArray + */ +template<> +inline geometry_msgs::msg::PoseStampedArray convertFromString(const StringView key) +{ + auto parts = BT::splitString(key, ';'); + if ((parts.size() - 2) % 9 != 0) { + throw std::runtime_error("invalid number of fields for PoseStampedArray attribute)"); + } else { + geometry_msgs::msg::PoseStampedArray pose_stamped_array; + pose_stamped_array.header.stamp = rclcpp::Time(BT::convertFromString(parts[0])); + pose_stamped_array.header.frame_id = BT::convertFromString(parts[1]); + for (size_t i = 2; i < parts.size(); i += 9) { + geometry_msgs::msg::PoseStamped pose_stamped; + pose_stamped.header.stamp = rclcpp::Time(BT::convertFromString(parts[i])); + pose_stamped.header.frame_id = BT::convertFromString(parts[i + 1]); + pose_stamped.pose.position.x = BT::convertFromString(parts[i + 2]); + pose_stamped.pose.position.y = BT::convertFromString(parts[i + 3]); + pose_stamped.pose.position.z = BT::convertFromString(parts[i + 4]); + pose_stamped.pose.orientation.x = BT::convertFromString(parts[i + 5]); + pose_stamped.pose.orientation.y = BT::convertFromString(parts[i + 6]); + pose_stamped.pose.orientation.z = BT::convertFromString(parts[i + 7]); + pose_stamped.pose.orientation.w = BT::convertFromString(parts[i + 8]); + pose_stamped_array.poses.push_back(pose_stamped); + } + return pose_stamped_array; + } +} + /** * @brief Parse XML string to nav_msgs::msg::Path * @param key XML string @@ -143,7 +175,6 @@ inline std::vector convertFromString(const Stri template<> inline nav_msgs::msg::Path convertFromString(const StringView key) { - // 9 real numbers separated by semicolons auto parts = BT::splitString(key, ';'); if ((parts.size() - 2) % 9 != 0) { throw std::runtime_error("invalid number of fields for Path attribute)"); diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp index fe5d2e9dd25..6a74de1bced 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp @@ -75,7 +75,7 @@ class ComputePathThroughPosesAction { return providedBasicPorts( { - BT::InputPort>( + BT::InputPort( "goals", "Destinations to plan through"), BT::InputPort( diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp index 44ad055ea24..ea24baadae1 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp @@ -18,8 +18,7 @@ #include #include -#include "geometry_msgs/msg/point.hpp" -#include "geometry_msgs/msg/quaternion.hpp" +#include "geometry_msgs/msg/pose_stamped_array.hpp" #include "nav2_msgs/action/navigate_through_poses.hpp" #include "nav2_behavior_tree/bt_action_node.hpp" @@ -74,7 +73,7 @@ class NavigateThroughPosesAction : public BtActionNode>( + BT::InputPort( "goals", "Destinations to plan through"), BT::InputPort("behavior_tree", "Behavior tree to run"), BT::OutputPort( diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp index 8992b4d516a..5ed0e213ea7 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp @@ -20,7 +20,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "geometry_msgs/msg/pose_stamped.hpp" +#include "geometry_msgs/msg/pose_stamped_array.hpp" #include "nav2_behavior_tree/bt_service_node.hpp" #include "nav2_msgs/srv/get_costs.hpp" @@ -30,8 +30,6 @@ namespace nav2_behavior_tree class RemoveInCollisionGoals : public BtServiceNode { public: - typedef std::vector Goals; - /** * @brief A constructor for nav2_behavior_tree::RemoveInCollisionGoals * @param service_node_name Service name this node creates a client for @@ -54,7 +52,8 @@ class RemoveInCollisionGoals : public BtServiceNode { return providedBasicPorts( { - BT::InputPort("input_goals", "Original goals to remove from"), + BT::InputPort("input_goals", + "Original goals to remove from"), BT::InputPort( "cost_threshold", 254.0, "Cost threshold for considering a goal in collision"), @@ -62,7 +61,8 @@ class RemoveInCollisionGoals : public BtServiceNode BT::InputPort( "consider_unknown_as_obstacle", false, "Whether to consider unknown cost as obstacle"), - BT::OutputPort("output_goals", "Goals with in-collision goals removed"), + BT::OutputPort("output_goals", + "Goals with in-collision goals removed"), }); } @@ -70,7 +70,7 @@ class RemoveInCollisionGoals : public BtServiceNode bool use_footprint_; bool consider_unknown_as_obstacle_; double cost_threshold_; - Goals input_goals_; + geometry_msgs::msg::PoseStampedArray input_goals_; }; } // namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp index fcfade6d17b..77c2fc367e9 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp @@ -19,7 +19,7 @@ #include #include -#include "geometry_msgs/msg/pose_stamped.hpp" +#include "geometry_msgs/msg/pose_stamped_array.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "behaviortree_cpp/action_node.h" @@ -31,8 +31,6 @@ namespace nav2_behavior_tree class RemovePassedGoals : public BT::ActionNodeBase { public: - typedef std::vector Goals; - RemovePassedGoals( const std::string & xml_tag_name, const BT::NodeConfiguration & conf); @@ -45,8 +43,10 @@ class RemovePassedGoals : public BT::ActionNodeBase static BT::PortsList providedPorts() { return { - BT::InputPort("input_goals", "Original goals to remove viapoints from"), - BT::OutputPort("output_goals", "Goals with passed viapoints removed"), + BT::InputPort("input_goals", + "Original goals to remove viapoints from"), + BT::OutputPort("output_goals", + "Goals with passed viapoints removed"), BT::InputPort("radius", 0.5, "radius to goal for it to be considered for removal"), BT::InputPort("global_frame", "Global frame"), BT::InputPort("robot_base_frame", "Robot base frame"), diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp index 12344a5d3f7..5e730017d92 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp @@ -21,7 +21,7 @@ #include "rclcpp/rclcpp.hpp" #include "behaviortree_cpp/condition_node.h" -#include "geometry_msgs/msg/pose_stamped.hpp" +#include "geometry_msgs/msg/pose_stamped_array.hpp" #include "nav2_behavior_tree/bt_utils.hpp" @@ -59,7 +59,7 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode static BT::PortsList providedPorts() { return { - BT::InputPort>( + BT::InputPort( "goals", "Vector of navigation goals"), BT::InputPort( "goal", "Navigation goal"), @@ -70,7 +70,7 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode bool first_time; rclcpp::Node::SharedPtr node_; geometry_msgs::msg::PoseStamped goal_; - std::vector goals_; + geometry_msgs::msg::PoseStampedArray goals_; }; } // namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_updated_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_updated_condition.hpp index 22893e33ee3..4ea81d896b2 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_updated_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_updated_condition.hpp @@ -19,7 +19,7 @@ #include #include "behaviortree_cpp/condition_node.h" -#include "geometry_msgs/msg/pose_stamped.hpp" +#include "geometry_msgs/msg/pose_stamped_array.hpp" #include "nav2_behavior_tree/bt_utils.hpp" namespace nav2_behavior_tree @@ -56,7 +56,7 @@ class GoalUpdatedCondition : public BT::ConditionNode static BT::PortsList providedPorts() { return { - BT::InputPort>( + BT::InputPort( "goals", "Vector of navigation goals"), BT::InputPort( "goal", "Navigation goal"), @@ -65,7 +65,7 @@ class GoalUpdatedCondition : public BT::ConditionNode private: geometry_msgs::msg::PoseStamped goal_; - std::vector goals_; + geometry_msgs::msg::PoseStampedArray goals_; }; } // namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp index 63a7f606558..49215ae9a14 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updated_controller.hpp @@ -50,7 +50,7 @@ class GoalUpdatedController : public BT::DecoratorNode static BT::PortsList providedPorts() { return { - BT::InputPort>( + BT::InputPort( "goals", "Vector of navigation goals"), BT::InputPort( "goal", "Navigation goal"), @@ -66,7 +66,7 @@ class GoalUpdatedController : public BT::DecoratorNode bool goal_was_updated_; geometry_msgs::msg::PoseStamped goal_; - std::vector goals_; + geometry_msgs::msg::PoseStampedArray goals_; }; } // namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp index 59a9fc55210..3d1dcff2962 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp @@ -58,7 +58,7 @@ class SpeedController : public BT::DecoratorNode BT::InputPort("max_rate", 1.0, "Maximum rate"), BT::InputPort("min_speed", 0.0, "Minimum speed"), BT::InputPort("max_speed", 0.5, "Maximum speed"), - BT::InputPort>( + BT::InputPort( "goals", "Vector of navigation goals"), BT::InputPort( "goal", "Navigation goal"), @@ -120,7 +120,7 @@ class SpeedController : public BT::DecoratorNode // current goal geometry_msgs::msg::PoseStamped goal_; - std::vector goals_; + geometry_msgs::msg::PoseStampedArray goals_; }; } // namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp index 8a75712b56b..a65334e5b61 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp @@ -23,7 +23,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_msgs/msg/behavior_tree_log.hpp" #include "nav2_msgs/msg/behavior_tree_status_change.h" -#include "tf2/time.h" +#include "tf2/time.hpp" #include "tf2_ros/buffer_interface.h" namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.cpp b/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.cpp index 78e6c2e35df..76b50ac3f51 100644 --- a/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.cpp +++ b/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.cpp @@ -18,7 +18,7 @@ #include "nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp" #include "nav2_behavior_tree/bt_utils.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" namespace nav2_behavior_tree @@ -39,7 +39,7 @@ void RemoveInCollisionGoals::on_tick() getInput("input_goals", input_goals_); getInput("consider_unknown_as_obstacle", consider_unknown_as_obstacle_); - if (input_goals_.empty()) { + if (input_goals_.poses.empty()) { setOutput("output_goals", input_goals_); should_send_request_ = false; return; @@ -47,7 +47,7 @@ void RemoveInCollisionGoals::on_tick() request_ = std::make_shared(); request_->use_footprint = use_footprint_; - for (const auto & goal : input_goals_) { + for (const auto & goal : input_goals_.poses) { request_->poses.push_back(goal); } } @@ -63,16 +63,16 @@ BT::NodeStatus RemoveInCollisionGoals::on_completion( return BT::NodeStatus::FAILURE; } - Goals valid_goal_poses; + geometry_msgs::msg::PoseStampedArray valid_goal_poses; for (size_t i = 0; i < response->costs.size(); ++i) { if ((response->costs[i] == 255 && !consider_unknown_as_obstacle_) || response->costs[i] < cost_threshold_) { - valid_goal_poses.push_back(input_goals_[i]); + valid_goal_poses.poses.push_back(input_goals_.poses[i]); } } // Inform if all goals have been removed - if (valid_goal_poses.empty()) { + if (valid_goal_poses.poses.empty()) { RCLCPP_INFO( node_->get_logger(), "All goals are in collision and have been removed from the list"); diff --git a/nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp b/nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp index 723e704e437..9b44a0635ef 100644 --- a/nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp +++ b/nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp @@ -49,10 +49,10 @@ inline BT::NodeStatus RemovePassedGoals::tick() initialize(); } - Goals goal_poses; + geometry_msgs::msg::PoseStampedArray goal_poses; getInput("input_goals", goal_poses); - if (goal_poses.empty()) { + if (goal_poses.poses.empty()) { setOutput("output_goals", goal_poses); return BT::NodeStatus::SUCCESS; } @@ -61,21 +61,21 @@ inline BT::NodeStatus RemovePassedGoals::tick() geometry_msgs::msg::PoseStamped current_pose; if (!nav2_util::getCurrentPose( - current_pose, *tf_, goal_poses[0].header.frame_id, robot_base_frame_, + current_pose, *tf_, goal_poses.poses[0].header.frame_id, robot_base_frame_, transform_tolerance_)) { return BT::NodeStatus::FAILURE; } double dist_to_goal; - while (goal_poses.size() > 1) { - dist_to_goal = euclidean_distance(goal_poses[0].pose, current_pose.pose); + while (goal_poses.poses.size() > 1) { + dist_to_goal = euclidean_distance(goal_poses.poses[0].pose, current_pose.pose); if (dist_to_goal > viapoint_achieved_radius_) { break; } - goal_poses.erase(goal_poses.begin()); + goal_poses.poses.erase(goal_poses.poses.begin()); } setOutput("output_goals", goal_poses); diff --git a/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp b/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp index f002710be6b..271e64added 100644 --- a/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp +++ b/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp @@ -24,7 +24,7 @@ #include "nav2_util/robot_utils.hpp" #include "nav_msgs/msg/path.hpp" #include "rclcpp/rclcpp.hpp" -#include "tf2/LinearMath/Quaternion.h" +#include "tf2/LinearMath/Quaternion.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/create_timer_ros.h" diff --git a/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp b/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp index 1e1e557e5f3..fcd3a665134 100644 --- a/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp @@ -38,7 +38,7 @@ BT::NodeStatus GloballyUpdatedGoalCondition::tick() return BT::NodeStatus::SUCCESS; } - std::vector current_goals; + geometry_msgs::msg::PoseStampedArray current_goals; BT::getInputOrBlackboard("goals", current_goals); geometry_msgs::msg::PoseStamped current_goal; BT::getInputOrBlackboard("goal", current_goal); diff --git a/nav2_behavior_tree/plugins/condition/goal_updated_condition.cpp b/nav2_behavior_tree/plugins/condition/goal_updated_condition.cpp index 962eef70dd2..06ddf76ae95 100644 --- a/nav2_behavior_tree/plugins/condition/goal_updated_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/goal_updated_condition.cpp @@ -33,7 +33,7 @@ BT::NodeStatus GoalUpdatedCondition::tick() return BT::NodeStatus::FAILURE; } - std::vector current_goals; + geometry_msgs::msg::PoseStampedArray current_goals; geometry_msgs::msg::PoseStamped current_goal; BT::getInputOrBlackboard("goals", current_goals); BT::getInputOrBlackboard("goal", current_goal); diff --git a/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp b/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp index ab589048c82..4f84e3e9fc8 100644 --- a/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp @@ -17,7 +17,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "tf2/time.h" +#include "tf2/time.hpp" #include "tf2_ros/buffer.h" #include "nav2_behavior_tree/plugins/condition/transform_available_condition.hpp" diff --git a/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp b/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp index b2f235dbd1f..d78c5d1e1fd 100644 --- a/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp +++ b/nav2_behavior_tree/plugins/decorator/goal_updated_controller.cpp @@ -44,7 +44,7 @@ BT::NodeStatus GoalUpdatedController::tick() setStatus(BT::NodeStatus::RUNNING); - std::vector current_goals; + geometry_msgs::msg::PoseStampedArray current_goals; BT::getInputOrBlackboard("goals", current_goals); geometry_msgs::msg::PoseStamped current_goal; BT::getInputOrBlackboard("goal", current_goal); diff --git a/nav2_behavior_tree/plugins/decorator/speed_controller.cpp b/nav2_behavior_tree/plugins/decorator/speed_controller.cpp index f5b4eb3bd86..347f1ccd25c 100644 --- a/nav2_behavior_tree/plugins/decorator/speed_controller.cpp +++ b/nav2_behavior_tree/plugins/decorator/speed_controller.cpp @@ -66,7 +66,7 @@ inline BT::NodeStatus SpeedController::tick() first_tick_ = true; } - std::vector current_goals; + geometry_msgs::msg::PoseStampedArray current_goals; BT::getInputOrBlackboard("goals", current_goals); geometry_msgs::msg::PoseStamped current_goal; BT::getInputOrBlackboard("goal", current_goal); diff --git a/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp b/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp index 02e7c865d8d..bb813205456 100644 --- a/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp @@ -44,7 +44,7 @@ class ComputePathThroughPosesActionServer const auto goal = goal_handle->get_goal(); auto result = std::make_shared(); result->path.poses.resize(2); - result->path.poses[1].pose.position.x = goal->goals[0].pose.position.x; + result->path.poses[1].pose.position.x = goal->goals.poses[0].pose.position.x; if (goal->use_start) { result->path.poses[0].pose.position.x = goal->start.pose.position.x; } else { @@ -137,9 +137,9 @@ TEST_F(ComputePathThroughPosesActionTestFixture, test_tick) tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); // create new goal and set it on blackboard - std::vector goals; - goals.resize(1); - goals[0].pose.position.x = 1.0; + geometry_msgs::msg::PoseStampedArray goals; + goals.poses.resize(1); + goals.poses[0].pose.position.x = 1.0; config_->blackboard->set("goals", goals); // tick until node succeeds @@ -150,7 +150,7 @@ TEST_F(ComputePathThroughPosesActionTestFixture, test_tick) // the goal should have reached our server EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::SUCCESS); EXPECT_EQ(tree_->rootNode()->getInput("planner_id"), std::string("GridBased")); - EXPECT_EQ(action_server_->getCurrentGoal()->goals[0].pose.position.x, 1.0); + EXPECT_EQ(action_server_->getCurrentGoal()->goals.poses[0].pose.position.x, 1.0); EXPECT_FALSE(action_server_->getCurrentGoal()->use_start); EXPECT_EQ(action_server_->getCurrentGoal()->planner_id, std::string("GridBased")); @@ -166,7 +166,7 @@ TEST_F(ComputePathThroughPosesActionTestFixture, test_tick) EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::IDLE); // set new goal - goals[0].pose.position.x = -2.5; + goals.poses[0].pose.position.x = -2.5; config_->blackboard->set("goals", goals); while (tree_->rootNode()->status() != BT::NodeStatus::SUCCESS) { @@ -174,7 +174,7 @@ TEST_F(ComputePathThroughPosesActionTestFixture, test_tick) } EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::SUCCESS); - EXPECT_EQ(action_server_->getCurrentGoal()->goals[0].pose.position.x, -2.5); + EXPECT_EQ(action_server_->getCurrentGoal()->goals.poses[0].pose.position.x, -2.5); EXPECT_TRUE(config_->blackboard->get("path", path)); EXPECT_EQ(path.poses.size(), 2u); @@ -202,9 +202,9 @@ TEST_F(ComputePathThroughPosesActionTestFixture, test_tick_use_start) config_->blackboard->set("start", start); // create new goal and set it on blackboard - std::vector goals; - goals.resize(1); - goals[0].pose.position.x = 1.0; + geometry_msgs::msg::PoseStampedArray goals; + goals.poses.resize(1); + goals.poses[0].pose.position.x = 1.0; config_->blackboard->set("goals", goals); // tick until node succeeds @@ -215,7 +215,7 @@ TEST_F(ComputePathThroughPosesActionTestFixture, test_tick_use_start) // the goal should have reached our server EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::SUCCESS); EXPECT_EQ(tree_->rootNode()->getInput("planner_id"), std::string("GridBased")); - EXPECT_EQ(action_server_->getCurrentGoal()->goals[0].pose.position.x, 1.0); + EXPECT_EQ(action_server_->getCurrentGoal()->goals.poses[0].pose.position.x, 1.0); EXPECT_EQ(action_server_->getCurrentGoal()->start.pose.position.x, 2.0); EXPECT_TRUE(action_server_->getCurrentGoal()->use_start); EXPECT_EQ(action_server_->getCurrentGoal()->planner_id, std::string("GridBased")); @@ -232,7 +232,7 @@ TEST_F(ComputePathThroughPosesActionTestFixture, test_tick_use_start) EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::IDLE); // set new goal and new start - goals[0].pose.position.x = -2.5; + goals.poses[0].pose.position.x = -2.5; start.pose.position.x = -1.5; config_->blackboard->set("goals", goals); config_->blackboard->set("start", start); @@ -242,7 +242,7 @@ TEST_F(ComputePathThroughPosesActionTestFixture, test_tick_use_start) } EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::SUCCESS); - EXPECT_EQ(action_server_->getCurrentGoal()->goals[0].pose.position.x, -2.5); + EXPECT_EQ(action_server_->getCurrentGoal()->goals.poses[0].pose.position.x, -2.5); EXPECT_TRUE(config_->blackboard->get("path", path)); EXPECT_EQ(path.poses.size(), 2u); diff --git a/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp b/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp index b296d706dc1..3596af739c3 100644 --- a/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp @@ -21,7 +21,7 @@ #include #include "nav_msgs/msg/path.hpp" -#include "geometry_msgs/msg/pose_stamped.hpp" +#include "geometry_msgs/msg/pose_stamped_array.hpp" #include "behaviortree_cpp/bt_factory.h" @@ -97,11 +97,11 @@ TEST_F(GetPoseFromPathTestFixture, test_tick) // create new path and set it on blackboard nav_msgs::msg::Path path; - std::vector goals; - goals.resize(2); - goals[0].pose.position.x = 1.0; - goals[1].pose.position.x = 2.0; - path.poses = goals; + geometry_msgs::msg::PoseStampedArray goals; + goals.poses.resize(2); + goals.poses[0].pose.position.x = 1.0; + goals.poses[1].pose.position.x = 2.0; + path.poses = goals.poses; path.header.frame_id = "test_frame_1"; config_->blackboard->set("path", path); diff --git a/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp b/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp index 9ffd637d66c..cf0c1079068 100644 --- a/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp @@ -74,7 +74,7 @@ class NavigateThroughPosesActionTestFixture : public ::testing::Test "wait_for_service_timeout", std::chrono::milliseconds(1000)); config_->blackboard->set("initial_pose_received", false); - std::vector poses; + geometry_msgs::msg::PoseStampedArray poses; config_->blackboard->set( "goals", poses); @@ -132,10 +132,10 @@ TEST_F(NavigateThroughPosesActionTestFixture, test_tick) tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); - std::vector poses; - poses.resize(1); - poses[0].pose.position.x = -2.5; - poses[0].pose.orientation.x = 1.0; + geometry_msgs::msg::PoseStampedArray poses; + poses.poses.resize(1); + poses.poses[0].pose.position.x = -2.5; + poses.poses[0].pose.orientation.x = 1.0; config_->blackboard->set("goals", poses); // tick until node succeeds diff --git a/nav2_behavior_tree/test/plugins/action/test_remove_in_collision_goals_action.cpp b/nav2_behavior_tree/test/plugins/action/test_remove_in_collision_goals_action.cpp index a9fd10dfc1f..307bd6e317d 100644 --- a/nav2_behavior_tree/test/plugins/action/test_remove_in_collision_goals_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_remove_in_collision_goals_action.cpp @@ -147,19 +147,19 @@ TEST_F(RemoveInCollisionGoalsTestFixture, test_tick_remove_in_collision_goals_su tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); // create new goal and set it on blackboard - std::vector poses; - poses.resize(4); - poses[0].pose.position.x = 0.0; - poses[0].pose.position.y = 0.0; + geometry_msgs::msg::PoseStampedArray poses; + poses.poses.resize(4); + poses.poses[0].pose.position.x = 0.0; + poses.poses[0].pose.position.y = 0.0; - poses[1].pose.position.x = 0.5; - poses[1].pose.position.y = 0.0; + poses.poses[1].pose.position.x = 0.5; + poses.poses[1].pose.position.y = 0.0; - poses[2].pose.position.x = 1.0; - poses[2].pose.position.y = 0.0; + poses.poses[2].pose.position.x = 1.0; + poses.poses[2].pose.position.y = 0.0; - poses[3].pose.position.x = 2.0; - poses[3].pose.position.y = 0.0; + poses.poses[3].pose.position.x = 2.0; + poses.poses[3].pose.position.y = 0.0; config_->blackboard->set("goals", poses); @@ -171,13 +171,13 @@ TEST_F(RemoveInCollisionGoalsTestFixture, test_tick_remove_in_collision_goals_su EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::SUCCESS); // check that it removed the point in range - std::vector output_poses; + geometry_msgs::msg::PoseStampedArray output_poses; EXPECT_TRUE(config_->blackboard->get("goals", output_poses)); - EXPECT_EQ(output_poses.size(), 3u); - EXPECT_EQ(output_poses[0], poses[0]); - EXPECT_EQ(output_poses[1], poses[1]); - EXPECT_EQ(output_poses[2], poses[2]); + EXPECT_EQ(output_poses.poses.size(), 3u); + EXPECT_EQ(output_poses.poses[0], poses.poses[0]); + EXPECT_EQ(output_poses.poses[1], poses.poses[1]); + EXPECT_EQ(output_poses.poses[2], poses.poses[2]); } TEST_F(RemoveInCollisionGoalsTestFixture, test_tick_remove_in_collision_goals_fail) @@ -194,19 +194,19 @@ TEST_F(RemoveInCollisionGoalsTestFixture, test_tick_remove_in_collision_goals_fa tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); // create new goal and set it on blackboard - std::vector poses; - poses.resize(4); - poses[0].pose.position.x = 0.0; - poses[0].pose.position.y = 0.0; + geometry_msgs::msg::PoseStampedArray poses; + poses.poses.resize(4); + poses.poses[0].pose.position.x = 0.0; + poses.poses[0].pose.position.y = 0.0; - poses[1].pose.position.x = 0.5; - poses[1].pose.position.y = 0.0; + poses.poses[1].pose.position.x = 0.5; + poses.poses[1].pose.position.y = 0.0; - poses[2].pose.position.x = 1.0; - poses[2].pose.position.y = 0.0; + poses.poses[2].pose.position.x = 1.0; + poses.poses[2].pose.position.y = 0.0; - poses[3].pose.position.x = 2.0; - poses[3].pose.position.y = 0.0; + poses.poses[3].pose.position.x = 2.0; + poses.poses[3].pose.position.y = 0.0; config_->blackboard->set("goals", poses); @@ -218,14 +218,14 @@ TEST_F(RemoveInCollisionGoalsTestFixture, test_tick_remove_in_collision_goals_fa // check that it failed and returned the original goals EXPECT_EQ(tree_->rootNode()->status(), BT::NodeStatus::FAILURE); - std::vector output_poses; + geometry_msgs::msg::PoseStampedArray output_poses; EXPECT_TRUE(config_->blackboard->get("goals", output_poses)); - EXPECT_EQ(output_poses.size(), 4u); - EXPECT_EQ(output_poses[0], poses[0]); - EXPECT_EQ(output_poses[1], poses[1]); - EXPECT_EQ(output_poses[2], poses[2]); - EXPECT_EQ(output_poses[3], poses[3]); + EXPECT_EQ(output_poses.poses.size(), 4u); + EXPECT_EQ(output_poses.poses[0], poses.poses[0]); + EXPECT_EQ(output_poses.poses[1], poses.poses[1]); + EXPECT_EQ(output_poses.poses[2], poses.poses[2]); + EXPECT_EQ(output_poses.poses[3], poses.poses[3]); } int main(int argc, char ** argv) diff --git a/nav2_behavior_tree/test/plugins/action/test_remove_passed_goals_action.cpp b/nav2_behavior_tree/test/plugins/action/test_remove_passed_goals_action.cpp index 1ddc5c45f3c..9ed40d8bad7 100644 --- a/nav2_behavior_tree/test/plugins/action/test_remove_passed_goals_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_remove_passed_goals_action.cpp @@ -114,19 +114,19 @@ TEST_F(RemovePassedGoalsTestFixture, test_tick) tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); // create new goal and set it on blackboard - std::vector poses; - poses.resize(4); - poses[0].pose.position.x = 0.0; - poses[0].pose.position.y = 0.0; + geometry_msgs::msg::PoseStampedArray poses; + poses.poses.resize(4); + poses.poses[0].pose.position.x = 0.0; + poses.poses[0].pose.position.y = 0.0; - poses[1].pose.position.x = 0.5; - poses[1].pose.position.y = 0.0; + poses.poses[1].pose.position.x = 0.5; + poses.poses[1].pose.position.y = 0.0; - poses[2].pose.position.x = 1.0; - poses[2].pose.position.y = 0.0; + poses.poses[2].pose.position.x = 1.0; + poses.poses[2].pose.position.y = 0.0; - poses[3].pose.position.x = 2.0; - poses[3].pose.position.y = 0.0; + poses.poses[3].pose.position.x = 2.0; + poses.poses[3].pose.position.y = 0.0; config_->blackboard->set("goals", poses); @@ -136,12 +136,12 @@ TEST_F(RemovePassedGoalsTestFixture, test_tick) } // check that it removed the point in range - std::vector output_poses; + geometry_msgs::msg::PoseStampedArray output_poses; EXPECT_TRUE(config_->blackboard->get("goals", output_poses)); - EXPECT_EQ(output_poses.size(), 2u); - EXPECT_EQ(output_poses[0], poses[2]); - EXPECT_EQ(output_poses[1], poses[3]); + EXPECT_EQ(output_poses.poses.size(), 2u); + EXPECT_EQ(output_poses.poses[0], poses.poses[2]); + EXPECT_EQ(output_poses.poses[1], poses.poses[3]); } int main(int argc, char ** argv) diff --git a/nav2_behavior_tree/test/plugins/action/test_truncate_path_action.cpp b/nav2_behavior_tree/test/plugins/action/test_truncate_path_action.cpp index de0ae1282d4..56b1b4b0567 100644 --- a/nav2_behavior_tree/test/plugins/action/test_truncate_path_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_truncate_path_action.cpp @@ -23,8 +23,8 @@ #include "nav_msgs/msg/path.hpp" #include "nav2_util/geometry_utils.hpp" #include "rclcpp/rclcpp.hpp" -#include "tf2/LinearMath/Matrix3x3.h" -#include "tf2/LinearMath/Quaternion.h" +#include "tf2/LinearMath/Matrix3x3.hpp" +#include "tf2/LinearMath/Quaternion.hpp" #include "behaviortree_cpp/bt_factory.h" diff --git a/nav2_behavior_tree/test/plugins/decorator/test_goal_updated_controller.cpp b/nav2_behavior_tree/test/plugins/decorator/test_goal_updated_controller.cpp index 4259e87a53e..d1c3c5e4207 100644 --- a/nav2_behavior_tree/test/plugins/decorator/test_goal_updated_controller.cpp +++ b/nav2_behavior_tree/test/plugins/decorator/test_goal_updated_controller.cpp @@ -32,8 +32,8 @@ class GoalUpdatedControllerTestFixture : public nav2_behavior_tree::BehaviorTree // Setting fake goals on blackboard geometry_msgs::msg::PoseStamped goal1; goal1.header.stamp = node_->now(); - std::vector poses1; - poses1.push_back(goal1); + geometry_msgs::msg::PoseStampedArray poses1; + poses1.poses.push_back(goal1); config_->blackboard->set("goal", goal1); config_->blackboard->set("goals", poses1); bt_node_ = std::make_shared( @@ -63,8 +63,8 @@ TEST_F(GoalUpdatedControllerTestFixture, test_behavior) // Creating updated fake-goals geometry_msgs::msg::PoseStamped goal2; goal2.header.stamp = node_->now(); - std::vector poses2; - poses2.push_back(goal2); + geometry_msgs::msg::PoseStampedArray poses2; + poses2.poses.push_back(goal2); // starting in idle EXPECT_EQ(bt_node_->status(), BT::NodeStatus::IDLE); diff --git a/nav2_behavior_tree/test/plugins/decorator/test_speed_controller.cpp b/nav2_behavior_tree/test/plugins/decorator/test_speed_controller.cpp index 903b6385ed3..ae07ee3c21b 100644 --- a/nav2_behavior_tree/test/plugins/decorator/test_speed_controller.cpp +++ b/nav2_behavior_tree/test/plugins/decorator/test_speed_controller.cpp @@ -42,7 +42,7 @@ class SpeedControllerTestFixture : public nav2_behavior_tree::BehaviorTreeTestFi goal.header.stamp = node_->now(); config_->blackboard->set("goal", goal); - std::vector fake_poses; + geometry_msgs::msg::PoseStampedArray fake_poses; config_->blackboard->set("goals", fake_poses); // NOLINT config_->input_ports["min_rate"] = 0.1; diff --git a/nav2_behavior_tree/test/test_bt_utils.cpp b/nav2_behavior_tree/test/test_bt_utils.cpp index 008e0a36b77..3d3ab54aba9 100644 --- a/nav2_behavior_tree/test/test_bt_utils.cpp +++ b/nav2_behavior_tree/test/test_bt_utils.cpp @@ -258,6 +258,70 @@ TEST(PoseStampedVectorPortTest, test_correct_syntax) EXPECT_EQ(values[1].pose.orientation.w, 14.0); } +TEST(PoseStampedArrayPortTest, test_wrong_syntax) +{ + std::string xml_txt = + R"( + + + + + )"; + + BT::BehaviorTreeFactory factory; + factory.registerNodeType>( + "PoseStampedArrayPortTest"); + EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception); + + xml_txt = + R"( + + + + + )"; + + EXPECT_THROW(factory.createTreeFromText(xml_txt), std::exception); +} + +TEST(PoseStampedArrayPortTest, test_correct_syntax) +{ + std::string xml_txt = + R"( + + + + + )"; + + BT::BehaviorTreeFactory factory; + factory.registerNodeType>( + "PoseStampedArrayPortTest"); + auto tree = factory.createTreeFromText(xml_txt); + + tree = factory.createTreeFromText(xml_txt); + geometry_msgs::msg::PoseStampedArray values; + tree.rootNode()->getInput("test", values); + EXPECT_EQ(rclcpp::Time(values.poses[0].header.stamp).nanoseconds(), 0); + EXPECT_EQ(values.poses[0].header.frame_id, "map"); + EXPECT_EQ(values.poses[0].pose.position.x, 1.0); + EXPECT_EQ(values.poses[0].pose.position.y, 2.0); + EXPECT_EQ(values.poses[0].pose.position.z, 3.0); + EXPECT_EQ(values.poses[0].pose.orientation.x, 4.0); + EXPECT_EQ(values.poses[0].pose.orientation.y, 5.0); + EXPECT_EQ(values.poses[0].pose.orientation.z, 6.0); + EXPECT_EQ(values.poses[0].pose.orientation.w, 7.0); + EXPECT_EQ(rclcpp::Time(values.poses[1].header.stamp).nanoseconds(), 0); + EXPECT_EQ(values.poses[1].header.frame_id, "odom"); + EXPECT_EQ(values.poses[1].pose.position.x, 8.0); + EXPECT_EQ(values.poses[1].pose.position.y, 9.0); + EXPECT_EQ(values.poses[1].pose.position.z, 10.0); + EXPECT_EQ(values.poses[1].pose.orientation.x, 11.0); + EXPECT_EQ(values.poses[1].pose.orientation.y, 12.0); + EXPECT_EQ(values.poses[1].pose.orientation.z, 13.0); + EXPECT_EQ(values.poses[1].pose.orientation.w, 14.0); +} + TEST(PathPortTest, test_wrong_syntax) { std::string xml_txt = diff --git a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp index 23a3640bcd5..a8979910e61 100644 --- a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp +++ b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp @@ -35,7 +35,7 @@ #include "nav2_core/behavior.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #pragma GCC diagnostic pop diff --git a/nav2_behaviors/plugins/spin.cpp b/nav2_behaviors/plugins/spin.cpp index ce89eb34f23..bd0ff1bf4d1 100644 --- a/nav2_behaviors/plugins/spin.cpp +++ b/nav2_behaviors/plugins/spin.cpp @@ -19,7 +19,7 @@ #include #include "nav2_behaviors/plugins/spin.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "nav2_util/node_utils.hpp" diff --git a/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py b/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py index 6bd6bdddcab..ecffa7771c8 100644 --- a/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py +++ b/nav2_bringup/launch/cloned_multi_tb3_simulation_launch.py @@ -37,6 +37,69 @@ from nav2_common.launch import ParseMultiRobotPose +def generate_robot_actions(context, *args, **kwargs): + bringup_dir = get_package_share_directory('nav2_bringup') + launch_dir = os.path.join(bringup_dir, 'launch') + use_rviz = LaunchConfiguration('use_rviz') + params_file = LaunchConfiguration('params_file') + autostart = LaunchConfiguration('autostart') + rviz_config_file = LaunchConfiguration('rviz_config') + map_yaml_file = LaunchConfiguration('map') + use_robot_state_pub = LaunchConfiguration('use_robot_state_pub') + + robots_substitution = ParseMultiRobotPose(LaunchConfiguration('robots')) + robots_list = robots_substitution.perform(context) + + # Define commands for launching the navigation instances + bringup_cmd_group = [] + for robot_name in robots_list: + init_pose = robots_list[robot_name] + group = GroupAction( + [ + LogInfo( + msg=['Launching namespace=', robot_name, ' init_pose=', str(init_pose),] + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(launch_dir, 'rviz_launch.py') + ), + condition=IfCondition(use_rviz), + launch_arguments={ + 'namespace': TextSubstitution(text=robot_name), + 'rviz_config': rviz_config_file, + }.items(), + ), + IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(bringup_dir, 'launch', 'tb3_simulation_launch.py') + ), + launch_arguments={ + 'namespace': robot_name, + 'map': map_yaml_file, + 'use_sim_time': 'True', + 'params_file': params_file, + 'autostart': autostart, + 'use_rviz': 'False', + 'use_simulator': 'False', + 'headless': 'False', + 'use_robot_state_pub': use_robot_state_pub, + 'x_pose': TextSubstitution(text=str(init_pose['x'])), + 'y_pose': TextSubstitution(text=str(init_pose['y'])), + 'z_pose': TextSubstitution(text=str(init_pose['z'])), + 'roll': TextSubstitution(text=str(init_pose['roll'])), + 'pitch': TextSubstitution(text=str(init_pose['pitch'])), + 'yaw': TextSubstitution(text=str(init_pose['yaw'])), + 'robot_name': TextSubstitution(text=robot_name), + }.items(), + ), + ] + ) + + bringup_cmd_group.append(group) + bringup_cmd_group.append(LogInfo(msg=['number_of_robots=', str(len(robots_list))])) + return bringup_cmd_group + + def generate_launch_description(): """ Bring up the multi-robots with given launch arguments. @@ -49,7 +112,6 @@ def generate_launch_description(): """ # Get the launch directory bringup_dir = get_package_share_directory('nav2_bringup') - launch_dir = os.path.join(bringup_dir, 'launch') sim_dir = get_package_share_directory('nav2_minimal_tb3_sim') # Simulation settings @@ -61,7 +123,6 @@ def generate_launch_description(): autostart = LaunchConfiguration('autostart') rviz_config_file = LaunchConfiguration('rviz_config') use_robot_state_pub = LaunchConfiguration('use_robot_state_pub') - use_rviz = LaunchConfiguration('use_rviz') log_settings = LaunchConfiguration('log_settings', default='true') # Declare the launch arguments @@ -71,6 +132,13 @@ def generate_launch_description(): description='Full path to world file to load', ) + declare_robots_cmd = DeclareLaunchArgument( + 'robots', + default_value="""robot1={x: 0.5, y: 0.5, yaw: 0}; + robot2={x: -0.5, y: -0.5, z: 0, roll: 0, pitch: 0, yaw: 1.5707}""", + description='Robots and their initialization poses in YAML format', + ) + declare_map_yaml_cmd = DeclareLaunchArgument( 'map', default_value=os.path.join(bringup_dir, 'maps', 'tb3_sandbox.yaml'), @@ -93,7 +161,8 @@ def generate_launch_description(): declare_rviz_config_file_cmd = DeclareLaunchArgument( 'rviz_config', - default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'), + default_value=os.path.join( + bringup_dir, 'rviz', 'nav2_default_view.rviz'), description='Full path to the RVIZ config file to use.', ) @@ -121,60 +190,6 @@ def generate_launch_description(): OpaqueFunction(function=lambda _: os.remove(world_sdf)) ])) - robots_list = ParseMultiRobotPose('robots').value() - - # Define commands for launching the navigation instances - bringup_cmd_group = [] - for robot_name in robots_list: - init_pose = robots_list[robot_name] - group = GroupAction( - [ - LogInfo( - msg=[ - 'Launching namespace=', - robot_name, - ' init_pose=', - str(init_pose), - ] - ), - IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(launch_dir, 'rviz_launch.py') - ), - condition=IfCondition(use_rviz), - launch_arguments={ - 'namespace': TextSubstitution(text=robot_name), - 'rviz_config': rviz_config_file, - }.items(), - ), - IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(bringup_dir, 'launch', 'tb3_simulation_launch.py') - ), - launch_arguments={ - 'namespace': robot_name, - 'map': map_yaml_file, - 'use_sim_time': 'True', - 'params_file': params_file, - 'autostart': autostart, - 'use_rviz': 'False', - 'use_simulator': 'False', - 'headless': 'False', - 'use_robot_state_pub': use_robot_state_pub, - 'x_pose': TextSubstitution(text=str(init_pose['x'])), - 'y_pose': TextSubstitution(text=str(init_pose['y'])), - 'z_pose': TextSubstitution(text=str(init_pose['z'])), - 'roll': TextSubstitution(text=str(init_pose['roll'])), - 'pitch': TextSubstitution(text=str(init_pose['pitch'])), - 'yaw': TextSubstitution(text=str(init_pose['yaw'])), - 'robot_name': TextSubstitution(text=robot_name), - }.items(), - ), - ] - ) - - bringup_cmd_group.append(group) - set_env_vars_resources = AppendEnvironmentVariable( 'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir, 'models')) set_env_vars_resources2 = AppendEnvironmentVariable( @@ -188,6 +203,7 @@ def generate_launch_description(): # Declare the launch options ld.add_action(declare_world_cmd) + ld.add_action(declare_robots_cmd) ld.add_action(declare_map_yaml_cmd) ld.add_action(declare_params_file_cmd) ld.add_action(declare_use_rviz_cmd) @@ -200,8 +216,6 @@ def generate_launch_description(): ld.add_action(start_gazebo_cmd) ld.add_action(remove_temp_sdf_file) - ld.add_action(LogInfo(msg=['number_of_robots=', str(len(robots_list))])) - ld.add_action( LogInfo(condition=IfCondition(log_settings), msg=['map yaml: ', map_yaml_file]) ) @@ -223,8 +237,6 @@ def generate_launch_description(): ld.add_action( LogInfo(condition=IfCondition(log_settings), msg=['autostart: ', autostart]) ) - - for cmd in bringup_cmd_group: - ld.add_action(cmd) + ld.add_action(OpaqueFunction(function=generate_robot_actions)) return ld diff --git a/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp b/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp index aee07de14c9..38f7228c7b5 100644 --- a/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp +++ b/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp @@ -21,6 +21,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_action/rclcpp_action.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" +#include "geometry_msgs/msg/pose_stamped_array.hpp" #include "nav2_core/behavior_tree_navigator.hpp" #include "nav2_msgs/action/navigate_through_poses.hpp" #include "nav_msgs/msg/path.hpp" @@ -40,8 +41,6 @@ class NavigateThroughPosesNavigator { public: using ActionT = nav2_msgs::action::NavigateThroughPoses; - typedef std::vector Goals; - /** * @brief A constructor for NavigateThroughPosesNavigator */ diff --git a/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp b/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp index 98d86499800..58f66b1fba8 100644 --- a/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp +++ b/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp @@ -102,10 +102,10 @@ NavigateThroughPosesNavigator::onLoop() auto blackboard = bt_action_server_->getBlackboard(); - Goals goal_poses; + geometry_msgs::msg::PoseStampedArray goal_poses; [[maybe_unused]] auto res = blackboard->get(goals_blackboard_id_, goal_poses); - if (goal_poses.size() == 0) { + if (goal_poses.poses.size() == 0) { bt_action_server_->publishFeedback(feedback_msg); return; } @@ -173,7 +173,7 @@ NavigateThroughPosesNavigator::onLoop() feedback_msg->number_of_recoveries = recovery_count; feedback_msg->current_pose = current_pose; feedback_msg->navigation_time = clock_->now() - start_time_; - feedback_msg->number_of_poses_remaining = goal_poses.size(); + feedback_msg->number_of_poses_remaining = goal_poses.poses.size(); bt_action_server_->publishFeedback(feedback_msg); } @@ -212,8 +212,8 @@ NavigateThroughPosesNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal) bool NavigateThroughPosesNavigator::initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal) { - Goals goal_poses = goal->poses; - for (auto & goal_pose : goal_poses) { + geometry_msgs::msg::PoseStampedArray pose_stamped_array = goal->poses; + for (auto & goal_pose : pose_stamped_array.poses) { if (!nav2_util::transformPoseInTargetFrame( goal_pose, goal_pose, *feedback_utils_.tf, feedback_utils_.global_frame, feedback_utils_.transform_tolerance)) @@ -226,10 +226,11 @@ NavigateThroughPosesNavigator::initializeGoalPoses(ActionT::Goal::ConstSharedPtr } } - if (goal_poses.size() > 0) { + if (pose_stamped_array.poses.size() > 0) { RCLCPP_INFO( logger_, "Begin navigating from current location through %zu poses to (%.2f, %.2f)", - goal_poses.size(), goal_poses.back().pose.position.x, goal_poses.back().pose.position.y); + pose_stamped_array.poses.size(), pose_stamped_array.poses.back().pose.position.x, + pose_stamped_array.poses.back().pose.position.y); } // Reset state for new action feedback @@ -238,7 +239,8 @@ NavigateThroughPosesNavigator::initializeGoalPoses(ActionT::Goal::ConstSharedPtr blackboard->set("number_recoveries", 0); // NOLINT // Update the goal pose on the blackboard - blackboard->set(goals_blackboard_id_, std::move(goal_poses)); + blackboard->set(goals_blackboard_id_, + std::move(pose_stamped_array)); return true; } diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp index 7c9785588e2..a3a429b2daa 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp @@ -22,7 +22,7 @@ #include "rclcpp/rclcpp.hpp" -#include "tf2/time.h" +#include "tf2/time.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp index c6caeeb5b2d..69274b06fdb 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp @@ -25,7 +25,7 @@ #include "visualization_msgs/msg/marker_array.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" -#include "tf2/time.h" +#include "tf2/time.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp index b81571765b9..1cbd01ba163 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp @@ -23,7 +23,7 @@ #include "rclcpp/rclcpp.hpp" #include "geometry_msgs/msg/polygon_stamped.hpp" -#include "tf2/time.h" +#include "tf2/time.hpp" #include "tf2_ros/buffer.h" #include "nav2_util/lifecycle_node.hpp" diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp index 4432ec243b1..3384bf8d333 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp @@ -21,7 +21,7 @@ #include "rclcpp/rclcpp.hpp" -#include "tf2/time.h" +#include "tf2/time.hpp" #include "tf2_ros/buffer.h" #include "nav2_collision_monitor/types.hpp" diff --git a/nav2_collision_monitor/src/pointcloud.cpp b/nav2_collision_monitor/src/pointcloud.cpp index 77daab68055..c54c0524ea0 100644 --- a/nav2_collision_monitor/src/pointcloud.cpp +++ b/nav2_collision_monitor/src/pointcloud.cpp @@ -17,7 +17,7 @@ #include #include "sensor_msgs/point_cloud2_iterator.hpp" -#include "tf2/transform_datatypes.h" +#include "tf2/transform_datatypes.hpp" #include "nav2_util/node_utils.hpp" #include "nav2_util/robot_utils.hpp" diff --git a/nav2_collision_monitor/src/polygon.cpp b/nav2_collision_monitor/src/polygon.cpp index 19ac5053de8..a528c74d640 100644 --- a/nav2_collision_monitor/src/polygon.cpp +++ b/nav2_collision_monitor/src/polygon.cpp @@ -19,7 +19,7 @@ #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/point32.hpp" -#include "tf2/transform_datatypes.h" +#include "tf2/transform_datatypes.hpp" #include "nav2_util/node_utils.hpp" #include "nav2_util/robot_utils.hpp" diff --git a/nav2_collision_monitor/src/polygon_source.cpp b/nav2_collision_monitor/src/polygon_source.cpp index 149ac43153f..a147529670f 100644 --- a/nav2_collision_monitor/src/polygon_source.cpp +++ b/nav2_collision_monitor/src/polygon_source.cpp @@ -18,7 +18,7 @@ #include #include "geometry_msgs/msg/polygon_stamped.hpp" -#include "tf2/transform_datatypes.h" +#include "tf2/transform_datatypes.hpp" #include "nav2_util/node_utils.hpp" #include "nav2_util/robot_utils.hpp" diff --git a/nav2_collision_monitor/src/range.cpp b/nav2_collision_monitor/src/range.cpp index fe555b171f3..d871c795082 100644 --- a/nav2_collision_monitor/src/range.cpp +++ b/nav2_collision_monitor/src/range.cpp @@ -18,7 +18,7 @@ #include #include -#include "tf2/transform_datatypes.h" +#include "tf2/transform_datatypes.hpp" #include "nav2_util/node_utils.hpp" #include "nav2_util/robot_utils.hpp" diff --git a/nav2_collision_monitor/src/scan.cpp b/nav2_collision_monitor/src/scan.cpp index f891df69a0a..0bdcefcd66b 100644 --- a/nav2_collision_monitor/src/scan.cpp +++ b/nav2_collision_monitor/src/scan.cpp @@ -17,7 +17,7 @@ #include #include -#include "tf2/transform_datatypes.h" +#include "tf2/transform_datatypes.hpp" #include "nav2_util/robot_utils.hpp" diff --git a/nav2_common/nav2_common/launch/parse_multirobot_pose.py b/nav2_common/nav2_common/launch/parse_multirobot_pose.py index 9207cad5f79..ced8352ac42 100644 --- a/nav2_common/nav2_common/launch/parse_multirobot_pose.py +++ b/nav2_common/nav2_common/launch/parse_multirobot_pose.py @@ -12,66 +12,55 @@ # See the License for the specific language governing permissions and # limitations under the License. -import sys from typing import Dict, Text +import launch +from launch.launch_context import LaunchContext import yaml -class ParseMultiRobotPose: - """Parsing argument using sys module.""" +class ParseMultiRobotPose(launch.Substitution): + """ + A custom substitution to parse the robots argument for multi-robot poses. - def __init__(self, target_argument: Text): - """ - Parse arguments for multi-robot's pose. + Expects input in the format: + robots:="robot1={x: 1.0, y: 1.0, yaw: 0.0}; + robot2={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707}"` - for example, - `ros2 launch nav2_bringup bringup_multirobot_launch.py - robots:="robot1={x: 1.0, y: 1.0, yaw: 0.0}; - robot2={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707}"` + The individual robots are separated by a `;` and each robot consists of a name and pose object. + The name corresponds to the namespace of the robot and name of the Gazebo object. + The pose consists of X, Y, Z, Roll, Pitch, Yaw each of which can be omitted in which case it is + inferred as 0. + """ - `target_argument` shall be 'robots'. - Then, this will parse a string value for `robots` argument. + def __init__(self, robots_argument: launch.SomeSubstitutionsType) -> None: + super().__init__() + self.__robots_argument = robots_argument - Each robot name which corresponds to namespace and pose of it will be separated by `;`. - The pose consists of x, y and yaw with YAML format. - - :param: target argument name to parse - """ - self.__args: Text = self.__parse_argument(target_argument) - - def __parse_argument(self, target_argument: Text) -> Text: - """Get value of target argument.""" - if len(sys.argv) > 4: - argv = sys.argv[4:] - for arg in argv: - if arg.startswith(target_argument + ':='): - return arg.replace(target_argument + ':=', '') + def describe(self) -> Text: + """Return a description of this substitution as a string.""" return '' - def value(self) -> Dict: - """Get value of target argument.""" - args = self.__args - parsed_args = [] if len(args) == 0 else args.split(';') + def perform(self, context: LaunchContext) -> Dict: + """Resolve and parse the robots argument string into a dictionary.""" + robots_str = self.__robots_argument.perform(context) + if not robots_str: + return {} + multirobots = {} - for arg in parsed_args: - key_val = arg.strip().split('=') + for robot_entry in robots_str.split(';'): + key_val = robot_entry.strip().split('=') if len(key_val) != 2: continue - key = key_val[0].strip() - val = key_val[1].strip() - robot_pose = yaml.safe_load(val) - if 'x' not in robot_pose: - robot_pose['x'] = 0.0 - if 'y' not in robot_pose: - robot_pose['y'] = 0.0 - if 'z' not in robot_pose: - robot_pose['z'] = 0.0 - if 'roll' not in robot_pose: - robot_pose['roll'] = 0.0 - if 'pitch' not in robot_pose: - robot_pose['pitch'] = 0.0 - if 'yaw' not in robot_pose: - robot_pose['yaw'] = 0.0 - multirobots[key] = robot_pose + + robot_name, pose_str = key_val[0].strip(), key_val[1].strip() + robot_pose = yaml.safe_load(pose_str) + # Set default values if not provided + robot_pose.setdefault('x', 0.0) + robot_pose.setdefault('y', 0.0) + robot_pose.setdefault('z', 0.0) + robot_pose.setdefault('roll', 0.0) + robot_pose.setdefault('pitch', 0.0) + robot_pose.setdefault('yaw', 0.0) + multirobots[robot_name] = robot_pose return multirobots diff --git a/nav2_constrained_smoother/src/constrained_smoother.cpp b/nav2_constrained_smoother/src/constrained_smoother.cpp index 6ff2f504a25..6b5bef4a303 100644 --- a/nav2_constrained_smoother/src/constrained_smoother.cpp +++ b/nav2_constrained_smoother/src/constrained_smoother.cpp @@ -30,7 +30,7 @@ #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" using nav2_util::declare_parameter_if_not_declared; using nav2_util::geometry_utils::euclidean_distance; diff --git a/nav2_controller/plugins/simple_goal_checker.cpp b/nav2_controller/plugins/simple_goal_checker.cpp index 597f843eaac..30b90f4f4ab 100644 --- a/nav2_controller/plugins/simple_goal_checker.cpp +++ b/nav2_controller/plugins/simple_goal_checker.cpp @@ -43,7 +43,7 @@ #include "nav2_util/geometry_utils.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #pragma GCC diagnostic pop using rcl_interfaces::msg::ParameterType; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp index 97a9c0a4ff8..41041c44b6e 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp @@ -50,9 +50,9 @@ #include "nav2_msgs/msg/costmap.hpp" #include "nav2_msgs/msg/costmap_update.hpp" #include "nav2_msgs/srv/get_costmap.hpp" -#include "tf2/transform_datatypes.h" +#include "tf2/transform_datatypes.hpp" #include "nav2_util/lifecycle_node.hpp" -#include "tf2/LinearMath/Quaternion.h" +#include "tf2/LinearMath/Quaternion.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" namespace nav2_costmap_2d diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 3f514e9ad26..797b211666f 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -54,16 +54,16 @@ #include "nav2_util/lifecycle_node.hpp" #include "nav2_msgs/srv/get_costs.hpp" #include "pluginlib/class_loader.hpp" -#include "tf2/convert.h" -#include "tf2/LinearMath/Transform.h" +#include "tf2/convert.hpp" +#include "tf2/LinearMath/Transform.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" -#include "tf2/time.h" -#include "tf2/transform_datatypes.h" +#include "tf2/time.hpp" +#include "tf2/transform_datatypes.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #pragma GCC diagnostic pop namespace nav2_costmap_2d diff --git a/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp b/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp index 3ac785296a2..74277fb58d3 100644 --- a/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp +++ b/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp @@ -38,7 +38,7 @@ #include #include #include -#include "tf2/convert.h" +#include "tf2/convert.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "nav2_costmap_2d/costmap_filters/keepout_filter.hpp" diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index abc6b57a5d1..888028f3662 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -43,7 +43,7 @@ #include #include "pluginlib/class_list_macros.hpp" -#include "tf2/convert.h" +#include "tf2/convert.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "nav2_util/validate_messages.hpp" diff --git a/nav2_costmap_2d/src/footprint_subscriber.cpp b/nav2_costmap_2d/src/footprint_subscriber.cpp index 2c269fa3b06..7cd65781e27 100644 --- a/nav2_costmap_2d/src/footprint_subscriber.cpp +++ b/nav2_costmap_2d/src/footprint_subscriber.cpp @@ -19,7 +19,7 @@ #include "nav2_costmap_2d/footprint_subscriber.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #pragma GCC diagnostic pop namespace nav2_costmap_2d diff --git a/nav2_costmap_2d/src/observation_buffer.cpp b/nav2_costmap_2d/src/observation_buffer.cpp index 8a06823df38..a3df54e080d 100644 --- a/nav2_costmap_2d/src/observation_buffer.cpp +++ b/nav2_costmap_2d/src/observation_buffer.cpp @@ -42,7 +42,7 @@ #include #include -#include "tf2/convert.h" +#include "tf2/convert.hpp" #include "sensor_msgs/point_cloud2_iterator.hpp" using namespace std::chrono_literals; diff --git a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp index ec6748f980e..a069bf1f1b8 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp @@ -35,7 +35,7 @@ #include "tf2_ros/transform_broadcaster.h" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #pragma GCC diagnostic pop #include "nav2_util/geometry_utils.hpp" diff --git a/nav2_docking/README.md b/nav2_docking/README.md index f5259338c76..0352ee95aef 100644 --- a/nav2_docking/README.md +++ b/nav2_docking/README.md @@ -17,6 +17,11 @@ This is split into 4 packages Click on the image above to see an extended video of docking in action. +Want to learn more? Checkout the ROSCon 2024 talk on Docking by clicking on the image below! + +[![IMAGE ALT TEXT](https://github.com/user-attachments/assets/468bb49c-87de-4c9e-83a8-ad6f14bbd6d3)](https://vimeo.com/1024971348) + + ## Architecture The Docking Framework has 5 main components: diff --git a/nav2_docking/opennav_docking/include/opennav_docking/simple_charging_dock.hpp b/nav2_docking/opennav_docking/include/opennav_docking/simple_charging_dock.hpp index c9b46e4a400..65a5596c18c 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/simple_charging_dock.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/simple_charging_dock.hpp @@ -23,7 +23,7 @@ #include "sensor_msgs/msg/battery_state.hpp" #include "sensor_msgs/msg/joint_state.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "opennav_docking_core/charging_dock.hpp" #include "opennav_docking/pose_filter.hpp" diff --git a/nav2_docking/opennav_docking/include/opennav_docking/simple_non_charging_dock.hpp b/nav2_docking/opennav_docking/include/opennav_docking/simple_non_charging_dock.hpp index cecb5299150..d037e1aa79c 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/simple_non_charging_dock.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/simple_non_charging_dock.hpp @@ -23,7 +23,7 @@ #include "sensor_msgs/msg/battery_state.hpp" #include "sensor_msgs/msg/joint_state.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "opennav_docking_core/non_charging_dock.hpp" #include "opennav_docking/pose_filter.hpp" diff --git a/nav2_docking/opennav_docking/include/opennav_docking/utils.hpp b/nav2_docking/opennav_docking/include/opennav_docking/utils.hpp index ce0b5660036..1acd623f3ee 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/utils.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/utils.hpp @@ -24,7 +24,7 @@ #include "nav2_util/geometry_utils.hpp" #include "angles/angles.h" #include "opennav_docking/types.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" namespace utils { diff --git a/nav2_docking/opennav_docking/src/controller.cpp b/nav2_docking/opennav_docking/src/controller.cpp index ec2a1de9ab9..8128ba82253 100644 --- a/nav2_docking/opennav_docking/src/controller.cpp +++ b/nav2_docking/opennav_docking/src/controller.cpp @@ -20,7 +20,7 @@ #include "nav2_util/geometry_utils.hpp" #include "nav2_util/node_utils.hpp" #include "nav_2d_utils/conversions.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" namespace opennav_docking { diff --git a/nav2_docking/opennav_docking/src/docking_server.cpp b/nav2_docking/opennav_docking/src/docking_server.cpp index d7af36c9ebc..1497a2355f5 100644 --- a/nav2_docking/opennav_docking/src/docking_server.cpp +++ b/nav2_docking/opennav_docking/src/docking_server.cpp @@ -15,7 +15,7 @@ #include "angles/angles.h" #include "opennav_docking/docking_server.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" using namespace std::chrono_literals; using rcl_interfaces::msg::ParameterType; diff --git a/nav2_docking/opennav_docking/test/test_pose_filter.cpp b/nav2_docking/opennav_docking/test/test_pose_filter.cpp index f010c9c0108..207fff3f8c9 100644 --- a/nav2_docking/opennav_docking/test/test_pose_filter.cpp +++ b/nav2_docking/opennav_docking/test/test_pose_filter.cpp @@ -18,7 +18,7 @@ #include "rclcpp/rclcpp.hpp" #include "opennav_docking/pose_filter.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" // Testing the pose filter diff --git a/nav2_docking/opennav_docking/test/test_simple_charging_dock.cpp b/nav2_docking/opennav_docking/test/test_simple_charging_dock.cpp index 7193bb188b0..44ac7442cf7 100644 --- a/nav2_docking/opennav_docking/test/test_simple_charging_dock.cpp +++ b/nav2_docking/opennav_docking/test/test_simple_charging_dock.cpp @@ -20,7 +20,7 @@ #include "opennav_docking/simple_charging_dock.hpp" #include "ament_index_cpp/get_package_share_directory.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" // Testing the simple charging dock plugin diff --git a/nav2_docking/opennav_docking/test/test_simple_non_charging_dock.cpp b/nav2_docking/opennav_docking/test/test_simple_non_charging_dock.cpp index 89c423f5ff3..9705082af1d 100644 --- a/nav2_docking/opennav_docking/test/test_simple_non_charging_dock.cpp +++ b/nav2_docking/opennav_docking/test/test_simple_non_charging_dock.cpp @@ -20,7 +20,7 @@ #include "opennav_docking/simple_non_charging_dock.hpp" #include "ament_index_cpp/get_package_share_directory.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" // Testing the simple non-charging dock plugin diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp index 910361615ef..901e9f0a1e5 100644 --- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp +++ b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp @@ -44,7 +44,7 @@ #include "nav_2d_msgs/msg/pose2_d_stamped.hpp" #include "nav_msgs/msg/path.hpp" #include "rclcpp/rclcpp.hpp" -#include "tf2/convert.h" +#include "tf2/convert.hpp" namespace nav_2d_utils { diff --git a/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp b/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp index 42fdff6bb3f..5abed18bdcb 100644 --- a/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp +++ b/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp @@ -48,7 +48,7 @@ #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #pragma GCC diagnostic pop #include "nav2_util/geometry_utils.hpp" diff --git a/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp b/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp index 8f2bd171b2d..c8424038a16 100644 --- a/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp +++ b/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp @@ -33,8 +33,8 @@ */ #include -#include #include +#include #include "gtest/gtest.h" #include "nav_2d_utils/conversions.hpp" diff --git a/nav2_graceful_controller/include/nav2_graceful_controller/ego_polar_coords.hpp b/nav2_graceful_controller/include/nav2_graceful_controller/ego_polar_coords.hpp index f0f1229a103..00b44d01617 100644 --- a/nav2_graceful_controller/include/nav2_graceful_controller/ego_polar_coords.hpp +++ b/nav2_graceful_controller/include/nav2_graceful_controller/ego_polar_coords.hpp @@ -19,7 +19,7 @@ #include "angles/angles.h" #include "geometry_msgs/msg/pose.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" namespace nav2_graceful_controller { diff --git a/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp b/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp index 209ff616f30..8669aafeedb 100644 --- a/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp +++ b/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp @@ -173,7 +173,7 @@ class GracefulController : public nav2_core::Controller std::shared_ptr> transformed_plan_pub_; std::shared_ptr> local_plan_pub_; - std::shared_ptr> + std::shared_ptr> motion_target_pub_; std::shared_ptr> slowdown_pub_; diff --git a/nav2_graceful_controller/include/nav2_graceful_controller/utils.hpp b/nav2_graceful_controller/include/nav2_graceful_controller/utils.hpp index 788656bd64b..65aea70d87d 100644 --- a/nav2_graceful_controller/include/nav2_graceful_controller/utils.hpp +++ b/nav2_graceful_controller/include/nav2_graceful_controller/utils.hpp @@ -15,22 +15,11 @@ #ifndef NAV2_GRACEFUL_CONTROLLER__UTILS_HPP_ #define NAV2_GRACEFUL_CONTROLLER__UTILS_HPP_ -#include "geometry_msgs/msg/point_stamped.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "visualization_msgs/msg/marker.hpp" namespace nav2_graceful_controller { -/** - * @brief Create a PointStamped message of the motion target for - * debugging / visualization porpuses. - * - * @param motion_target Motion target in PoseStamped format - * @return geometry_msgs::msg::PointStamped Motion target in PointStamped format - */ -geometry_msgs::msg::PointStamped createMotionTargetMsg( - const geometry_msgs::msg::PoseStamped & motion_target); - /** * @brief Create a flat circle marker of radius slowdown_radius around the motion target for * debugging / visualization porpuses. diff --git a/nav2_graceful_controller/src/graceful_controller.cpp b/nav2_graceful_controller/src/graceful_controller.cpp index d6d74cd568b..a4be973a55e 100644 --- a/nav2_graceful_controller/src/graceful_controller.cpp +++ b/nav2_graceful_controller/src/graceful_controller.cpp @@ -61,7 +61,7 @@ void GracefulController::configure( // Publishers transformed_plan_pub_ = node->create_publisher("transformed_global_plan", 1); local_plan_pub_ = node->create_publisher("local_plan", 1); - motion_target_pub_ = node->create_publisher("motion_target", 1); + motion_target_pub_ = node->create_publisher("motion_target", 1); slowdown_pub_ = node->create_publisher("slowdown", 1); RCLCPP_INFO(logger_, "Configured Graceful Motion Controller: %s", plugin_name_.c_str()); @@ -233,8 +233,7 @@ geometry_msgs::msg::TwistStamped GracefulController::computeVelocityCommands( if (simulateTrajectory(target_pose, costmap_transform, local_plan, cmd_vel, reversing)) { // Successfully simulated to target_pose - compute velocity at this moment // Publish the selected target_pose - auto motion_target_point = nav2_graceful_controller::createMotionTargetMsg(target_pose); - motion_target_pub_->publish(motion_target_point); + motion_target_pub_->publish(target_pose); // Publish marker for slowdown radius around motion target for debugging / visualization auto slowdown_marker = nav2_graceful_controller::createSlowdownMarker( target_pose, params_->slowdown_radius); diff --git a/nav2_graceful_controller/src/utils.cpp b/nav2_graceful_controller/src/utils.cpp index e6cdbadd569..0e79879efcd 100644 --- a/nav2_graceful_controller/src/utils.cpp +++ b/nav2_graceful_controller/src/utils.cpp @@ -17,16 +17,6 @@ namespace nav2_graceful_controller { -geometry_msgs::msg::PointStamped createMotionTargetMsg( - const geometry_msgs::msg::PoseStamped & motion_target) -{ - geometry_msgs::msg::PointStamped motion_target_point; - motion_target_point.header = motion_target.header; - motion_target_point.point = motion_target.pose.position; - motion_target_point.point.z = 0.01; - return motion_target_point; -} - visualization_msgs::msg::Marker createSlowdownMarker( const geometry_msgs::msg::PoseStamped & motion_target, const double & slowdown_radius) { diff --git a/nav2_graceful_controller/test/test_graceful_controller.cpp b/nav2_graceful_controller/test/test_graceful_controller.cpp index f00fda6ab54..de95598bb0f 100644 --- a/nav2_graceful_controller/test/test_graceful_controller.cpp +++ b/nav2_graceful_controller/test/test_graceful_controller.cpp @@ -59,12 +59,6 @@ class GMControllerFixture : public nav2_graceful_controller::GracefulController nav_msgs::msg::Path getPlan() {return path_handler_->getPlan();} - geometry_msgs::msg::PointStamped createMotionTargetMsg( - const geometry_msgs::msg::PoseStamped & motion_target) - { - return nav2_graceful_controller::createMotionTargetMsg(motion_target); - } - visualization_msgs::msg::Marker createSlowdownMarker( const geometry_msgs::msg::PoseStamped & motion_target) { @@ -345,34 +339,6 @@ TEST(GracefulControllerTest, dynamicParameters) { EXPECT_EQ(controller->getAllowBackward(), false); } -TEST(GracefulControllerTest, createMotionTargetMsg) { - auto node = std::make_shared("testGraceful"); - auto tf = std::make_shared(node->get_clock()); - auto costmap_ros = std::make_shared("global_costmap"); - - // Create controller - auto controller = std::make_shared(); - costmap_ros->on_configure(rclcpp_lifecycle::State()); - controller->configure(node, "test", tf, costmap_ros); - controller->activate(); - - // Create motion target - geometry_msgs::msg::PoseStamped motion_target; - motion_target.header.frame_id = "map"; - motion_target.pose.position.x = 1.0; - motion_target.pose.position.y = 2.0; - motion_target.pose.orientation = tf2::toMsg(tf2::Quaternion({0, 0, 1}, 0.0)); - - // Create motion target message - auto motion_target_msg = controller->createMotionTargetMsg(motion_target); - - // Check results - EXPECT_EQ(motion_target_msg.header.frame_id, "map"); - EXPECT_EQ(motion_target_msg.point.x, 1.0); - EXPECT_EQ(motion_target_msg.point.y, 2.0); - EXPECT_EQ(motion_target_msg.point.z, 0.01); -} - TEST(GracefulControllerTest, createSlowdownMsg) { auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); diff --git a/nav2_map_server/src/map_io.cpp b/nav2_map_server/src/map_io.cpp index b97342cf820..11a9b9b895e 100644 --- a/nav2_map_server/src/map_io.cpp +++ b/nav2_map_server/src/map_io.cpp @@ -46,8 +46,8 @@ #include "yaml-cpp/yaml.h" -#include "tf2/LinearMath/Matrix3x3.h" -#include "tf2/LinearMath/Quaternion.h" +#include "tf2/LinearMath/Matrix3x3.hpp" +#include "tf2/LinearMath/Quaternion.hpp" #include "nav2_util/occ_grid_values.hpp" #ifdef _WIN32 diff --git a/nav2_mppi_controller/README.md b/nav2_mppi_controller/README.md index d061958135c..f77d25b1170 100644 --- a/nav2_mppi_controller/README.md +++ b/nav2_mppi_controller/README.md @@ -12,6 +12,10 @@ This controller is measured to run at 50+ Hz on a modest Intel processor (4th ge It works currently with Differential, Omnidirectional, and Ackermann robots. +Want to learn more? Checkout the ROSCon 2023 talk on the MPPI Controller by clicking on the image below! + +[![IMAGE ALT TEXT](https://github.com/user-attachments/assets/4e091c5d-9687-457c-a7fb-d0e0689fbaea)](https://vimeo.com/879001391) + ## MPPI Description The MPPI algorithm is an MPC variant that finds a control velocity for the robot using an iterative approach. Using the previous time step's best control solution and the robot's current state, a set of randomly sampled perturbations from a Gaussian distribution are applied. These noised controls are forward simulated to generate a set of trajectories within the robot's motion model. @@ -321,3 +325,7 @@ Thus, care should be taken to select weights of the obstacle critic in conjuncti As you increase or decrease your weights on the Obstacle, you may notice the aforementioned behaviors (e.g. won't overcome free to non-free threshold). To overcome them, increase the FollowPath critic cost to increase the desire for the trajectory planner to continue moving towards the goal. Make sure to not overshoot this though, keep them balanced. A desirable outcome is smooth motion roughly in the center of spaces without significant close interactions with obstacles. It shouldn't be perfectly following a path yet nor should the output velocity be wobbling jaggedly. Once you have your obstacle avoidance behavior tuned and matched with an appropriate path following penalty, tune the Path Align critic to align with the path. If you design exact-path-alignment behavior, its possible to skip the obstacle critic step as highly tuning the system to follow the path will give it less ability to deviate to avoid obstacles (though it'll slow and stop). Tuning the critic weight for the Obstacle critic high will do the job to avoid near-collisions but the repulsion weight is largely unnecessary to you. For others wanting more dynamic behavior, it _can_ be beneficial to slowly lower the weight on the obstacle critic to give the path alignment critic some more room to work. If your path was generated with a cost-aware planner (like all provided by Nav2) and providing paths sufficiently far from obstacles for your satisfaction, the impact of a slightly reduced Obstacle critic with a Path Alignment critic will do you well. Not over-weighting the path align critic will allow the robot to deviate from the path to get around dynamic obstacles in the scene or other obstacles not previous considered during path planning. It is subjective as to the best behavior for your application, but it has been shown that MPPI can be an exact path tracker and/or avoid dynamic obstacles very fluidly and everywhere in between. The defaults provided are in the generally right regime for a balanced initial trade-off. + +### MFMA and AVX2 Optimizations + +This MPPI is made possible to run on CPU-only by using a very well optimized implementation that rely on CPU vectorization through AVX2 and MFMA. All even remotely modern computers support this (2013+), but if using a very old computer you may not be able to use the plugin. Note that MPC is computationally heavy to begin with, so computers circa-2013 even if it were to have those compiler flags available probably wouldn't run it at a satisfactory rate anyway. diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp index 72fbaeb6011..a7ca647aa88 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp @@ -36,7 +36,7 @@ #include "angles/angles.h" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" diff --git a/nav2_msgs/action/ComputePathThroughPoses.action b/nav2_msgs/action/ComputePathThroughPoses.action index bedd9396797..0e07373c338 100644 --- a/nav2_msgs/action/ComputePathThroughPoses.action +++ b/nav2_msgs/action/ComputePathThroughPoses.action @@ -1,5 +1,5 @@ #goal definition -geometry_msgs/PoseStamped[] goals +geometry_msgs/PoseStampedArray goals geometry_msgs/PoseStamped start string planner_id bool use_start # If false, use current robot pose as path start, if true, use start above instead diff --git a/nav2_msgs/action/NavigateThroughPoses.action b/nav2_msgs/action/NavigateThroughPoses.action index 898e4540ef7..9b2896398f6 100644 --- a/nav2_msgs/action/NavigateThroughPoses.action +++ b/nav2_msgs/action/NavigateThroughPoses.action @@ -1,6 +1,6 @@ #goal definition -geometry_msgs/PoseStamped[] poses +geometry_msgs/PoseStampedArray poses string behavior_tree --- #result definition diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 6359721e348..c227851f07b 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -394,7 +394,7 @@ void PlannerServer::computePlanThroughPoses() getPreemptedGoalIfRequested(action_server_poses_, goal); - if (goal->goals.empty()) { + if (goal->goals.poses.empty()) { throw nav2_core::NoViapointsGiven("No viapoints given"); } @@ -409,7 +409,7 @@ void PlannerServer::computePlanThroughPoses() }; // Get consecutive paths through these points - for (unsigned int i = 0; i != goal->goals.size(); i++) { + for (unsigned int i = 0; i != goal->goals.poses.size(); i++) { // Get starting point if (i == 0) { curr_start = start; @@ -419,7 +419,7 @@ void PlannerServer::computePlanThroughPoses() curr_start = concat_path.poses.back(); curr_start.header = concat_path.header; } - curr_goal = goal->goals[i]; + curr_goal = goal->goals.poses[i]; // Transform them into the global frame if (!transformPosesToGlobalFrame(curr_start, curr_goal)) { diff --git a/nav2_rotation_shim_controller/test/test_shim_controller.cpp b/nav2_rotation_shim_controller/test/test_shim_controller.cpp index 1d63a77b47e..537f344d746 100644 --- a/nav2_rotation_shim_controller/test/test_shim_controller.cpp +++ b/nav2_rotation_shim_controller/test/test_shim_controller.cpp @@ -176,15 +176,16 @@ TEST(RotationShimControllerTest, rotationAndTransformTests) auto node = std::make_shared("ShimControllerTest"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); - auto costmap = std::make_shared("fake_costmap"); - rclcpp_lifecycle::State state; - costmap->on_configure(state); + auto costmap = std::make_shared("fake_costmap", "/", false); + costmap->configure(); // set a valid primary controller so we can do lifecycle node->declare_parameter( "PathFollower.primary_controller", std::string("nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController")); + node->declare_parameter("controller_frequency", 1.0); + auto controller = std::make_shared(); controller->configure(node, name, tf, costmap); controller->activate(); @@ -193,8 +194,8 @@ TEST(RotationShimControllerTest, rotationAndTransformTests) nav_msgs::msg::Path path; path.header.frame_id = "fake_frame"; path.poses.resize(10); - path.poses[1].pose.position.x = 0.1; - path.poses[1].pose.position.y = 0.1; + path.poses[1].pose.position.x = 0.15; + path.poses[1].pose.position.y = 0.15; path.poses[2].pose.position.x = 1.0; path.poses[2].pose.position.y = 1.0; path.poses[3].pose.position.x = 10.0; @@ -204,14 +205,14 @@ TEST(RotationShimControllerTest, rotationAndTransformTests) const geometry_msgs::msg::Twist velocity; EXPECT_EQ( controller->computeRotateToHeadingCommandWrapper( - 0.7, path.poses[0], velocity).twist.angular.z, 1.8); + 0.7, path.poses[1], velocity).twist.angular.z, 1.8); EXPECT_EQ( controller->computeRotateToHeadingCommandWrapper( - -0.7, path.poses[0], velocity).twist.angular.z, -1.8); + -0.7, path.poses[1], velocity).twist.angular.z, -1.8); EXPECT_EQ( controller->computeRotateToHeadingCommandWrapper( - 0.87, path.poses[0], velocity).twist.angular.z, 1.8); + 0.87, path.poses[1], velocity).twist.angular.z, 1.8); // in base_link, so should pass through values without issue geometry_msgs::msg::PoseStamped pt; @@ -237,8 +238,9 @@ TEST(RotationShimControllerTest, computeVelocityTests) auto tf = std::make_shared(node->get_clock()); auto listener = std::make_shared(*tf, node, true); auto costmap = std::make_shared("fake_costmap"); - rclcpp_lifecycle::State state; - costmap->on_configure(state); + costmap->set_parameter(rclcpp::Parameter("origin_x", -25.0)); + costmap->set_parameter(rclcpp::Parameter("origin_y", -25.0)); + costmap->configure(); auto tf_broadcaster = std::make_shared(node); geometry_msgs::msg::TransformStamped transform; @@ -254,6 +256,7 @@ TEST(RotationShimControllerTest, computeVelocityTests) node->declare_parameter( "PathFollower.primary_controller", std::string("nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController")); + node->declare_parameter("controller_frequency", 1.0); auto controller = std::make_shared(); controller->configure(node, name, tf, costmap); @@ -308,7 +311,7 @@ TEST(RotationShimControllerTest, computeVelocityTests) // this should allow it to find the sampled point, then transform to base_link // validly because we setup the TF for it. The 1.0 should be selected since default min // is 0.5 and that should cause a pass off to the RPP controller which will throw - // and exception because the costmap is bogus + // and exception because it is off of the costmap controller->setPlan(path); tf_broadcaster->sendTransform(transform); EXPECT_THROW(controller->computeVelocityCommands(pose, velocity, &checker), std::runtime_error); diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp index 471dce5ce5a..3e07ba8c2bc 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp @@ -102,7 +102,7 @@ private Q_SLOTS: std::vector orientation); void startWaypointFollowing(std::vector poses); void startNavigation(geometry_msgs::msg::PoseStamped); - void startNavThroughPoses(std::vector poses); + void startNavThroughPoses(geometry_msgs::msg::PoseStampedArray poses); using NavigationGoalHandle = rclcpp_action::ClientGoalHandle; using WaypointFollowerGoalHandle = @@ -196,8 +196,8 @@ private Q_SLOTS: QState * accumulated_wp_{nullptr}; QState * accumulated_nav_through_poses_{nullptr}; - std::vector acummulated_poses_; - std::vector store_poses_; + geometry_msgs::msg::PoseStampedArray acummulated_poses_; + geometry_msgs::msg::PoseStampedArray store_poses_; // Publish the visual markers with the waypoints void updateWpNavigationMarkers(); diff --git a/nav2_rviz_plugins/src/nav2_panel.cpp b/nav2_rviz_plugins/src/nav2_panel.cpp index e10f1eccdb4..36b74a3dfd8 100644 --- a/nav2_rviz_plugins/src/nav2_panel.cpp +++ b/nav2_rviz_plugins/src/nav2_panel.cpp @@ -675,7 +675,7 @@ void Nav2Panel::loophandler() void Nav2Panel::handleGoalLoader() { - acummulated_poses_.clear(); + acummulated_poses_ = geometry_msgs::msg::PoseStampedArray(); std::cout << "Loading Waypoints!" << std::endl; @@ -699,7 +699,7 @@ void Nav2Panel::handleGoalLoader() auto waypoint = waypoint_iter[it->first.as()]; auto pose = waypoint["pose"].as>(); auto orientation = waypoint["orientation"].as>(); - acummulated_poses_.push_back(convert_to_msg(pose, orientation)); + acummulated_poses_.poses.push_back(convert_to_msg(pose, orientation)); } // Publishing Waypoint Navigation marker after loading wp's @@ -731,7 +731,7 @@ void Nav2Panel::handleGoalSaver() { // Check if the waypoints are accumulated - if (acummulated_poses_.empty()) { + if (acummulated_poses_.poses.empty()) { std::cout << "No accumulated Points to Save!" << std::endl; return; } else { @@ -744,18 +744,19 @@ void Nav2Panel::handleGoalSaver() out << YAML::BeginMap; // Save WPs to data structure - for (unsigned int i = 0; i < acummulated_poses_.size(); ++i) { + for (unsigned int i = 0; i < acummulated_poses_.poses.size(); ++i) { out << YAML::Key << "waypoint" + std::to_string(i); out << YAML::BeginMap; out << YAML::Key << "pose"; std::vector pose = - {acummulated_poses_[i].pose.position.x, acummulated_poses_[i].pose.position.y, - acummulated_poses_[i].pose.position.z}; + {acummulated_poses_.poses[i].pose.position.x, acummulated_poses_.poses[i].pose.position.y, + acummulated_poses_.poses[i].pose.position.z}; out << YAML::Value << pose; out << YAML::Key << "orientation"; std::vector orientation = - {acummulated_poses_[i].pose.orientation.w, acummulated_poses_[i].pose.orientation.x, - acummulated_poses_[i].pose.orientation.y, acummulated_poses_[i].pose.orientation.z}; + {acummulated_poses_.poses[i].pose.orientation.w, acummulated_poses_.poses[i].pose.orientation.x, + acummulated_poses_.poses[i].pose.orientation.y, + acummulated_poses_.poses[i].pose.orientation.z}; out << YAML::Value << orientation; out << YAML::EndMap; } @@ -836,10 +837,10 @@ Nav2Panel::onInitialize() // Clearing all the stored values once reaching the final goal if ( loop_count_ == stoi(nr_of_loops_->displayText().toStdString()) && - goal_index_ == static_cast(store_poses_.size()) - 1 && + goal_index_ == static_cast(store_poses_.poses.size()) - 1 && msg->status_list.back().status == action_msgs::msg::GoalStatus::STATUS_SUCCEEDED) { - store_poses_.clear(); + store_poses_ = geometry_msgs::msg::PoseStampedArray(); waypoint_status_indicator_->clear(); loop_no_ = "0"; loop_count_ = 0; @@ -935,8 +936,8 @@ Nav2Panel::onCancel() &Nav2Panel::onCancelButtonPressed, this)); waypoint_status_indicator_->clear(); - store_poses_.clear(); - acummulated_poses_.clear(); + store_poses_ = geometry_msgs::msg::PoseStampedArray(); + acummulated_poses_ = geometry_msgs::msg::PoseStampedArray(); } void Nav2Panel::onResumedWp() @@ -966,12 +967,12 @@ Nav2Panel::onNewGoal(double x, double y, double theta, QString frame) pose.pose.position.z = 0.0; pose.pose.orientation = orientationAroundZAxis(theta); - if (store_poses_.empty()) { + if (store_poses_.poses.empty()) { if (state_machine_.configuration().contains(accumulating_)) { waypoint_status_indicator_->clear(); - acummulated_poses_.push_back(pose); + acummulated_poses_.poses.push_back(pose); } else { - acummulated_poses_.clear(); + acummulated_poses_ = geometry_msgs::msg::PoseStampedArray(); updateWpNavigationMarkers(); std::cout << "Start navigation" << std::endl; startNavigation(pose); @@ -1030,7 +1031,7 @@ Nav2Panel::onCancelButtonPressed() void Nav2Panel::onAccumulatedWp() { - if (acummulated_poses_.empty()) { + if (acummulated_poses_.poses.empty()) { state_machine_.postEvent(new ROSActionQEvent(QActionState::INACTIVE)); waypoint_status_indicator_->setText( " Note: Uh oh! Someone forgot to select the waypoints"); @@ -1052,7 +1053,7 @@ Nav2Panel::onAccumulatedWp() /** Making sure that the pose array does not get updated * between the process**/ - if (store_poses_.empty()) { + if (store_poses_.poses.empty()) { std::cout << "Start waypoint" << std::endl; // Setting the final loop value on the text box for sanity @@ -1065,12 +1066,12 @@ Nav2Panel::onAccumulatedWp() if (store_initial_pose_) { try { init_transform = tf2_buffer_->lookupTransform( - acummulated_poses_[0].header.frame_id, base_frame_, + acummulated_poses_.poses[0].header.frame_id, base_frame_, tf2::TimePointZero); } catch (const tf2::TransformException & ex) { RCLCPP_INFO( client_node_->get_logger(), "Could not transform %s to %s: %s", - acummulated_poses_[0].header.frame_id.c_str(), base_frame_.c_str(), ex.what()); + acummulated_poses_.poses[0].header.frame_id.c_str(), base_frame_.c_str(), ex.what()); return; } @@ -1086,24 +1087,24 @@ Nav2Panel::onAccumulatedWp() initial_pose.pose.orientation.w = init_transform.transform.rotation.w; // inserting the acummulated pose - acummulated_poses_.insert(acummulated_poses_.begin(), initial_pose); + acummulated_poses_.poses.insert(acummulated_poses_.poses.begin(), initial_pose); updateWpNavigationMarkers(); initial_pose_stored_ = true; if (loop_count_ == 0) { goal_index_ = 1; } } else if (!store_initial_pose_ && initial_pose_stored_) { - acummulated_poses_.erase( - acummulated_poses_.begin(), - acummulated_poses_.begin()); + acummulated_poses_.poses.erase( + acummulated_poses_.poses.begin(), + acummulated_poses_.poses.begin()); } } else { std::cout << "Resuming waypoint" << std::endl; } - startWaypointFollowing(acummulated_poses_); + startWaypointFollowing(acummulated_poses_.poses); store_poses_ = acummulated_poses_; - acummulated_poses_.clear(); + acummulated_poses_ = geometry_msgs::msg::PoseStampedArray(); } void @@ -1116,8 +1117,8 @@ Nav2Panel::onAccumulatedNTP() void Nav2Panel::onAccumulating() { - acummulated_poses_.clear(); - store_poses_.clear(); + acummulated_poses_ = geometry_msgs::msg::PoseStampedArray(); + store_poses_ = geometry_msgs::msg::PoseStampedArray(); loop_count_ = 0; loop_no_ = "0"; initial_pose_stored_ = false; @@ -1254,7 +1255,7 @@ Nav2Panel::startWaypointFollowing(std::vector p } void -Nav2Panel::startNavThroughPoses(std::vector poses) +Nav2Panel::startNavThroughPoses(geometry_msgs::msg::PoseStampedArray poses) { auto is_action_server_ready = nav_through_poses_action_client_->wait_for_action_server(std::chrono::seconds(5)); @@ -1272,8 +1273,8 @@ Nav2Panel::startNavThroughPoses(std::vector pos RCLCPP_DEBUG( client_node_->get_logger(), "Sending a path of %zu waypoints:", - nav_through_poses_goal_.poses.size()); - for (auto waypoint : nav_through_poses_goal_.poses) { + nav_through_poses_goal_.poses.poses.size()); + for (auto waypoint : nav_through_poses_goal_.poses.poses) { RCLCPP_DEBUG( client_node_->get_logger(), "\t(%lf, %lf)", waypoint.pose.position.x, waypoint.pose.position.y); @@ -1384,14 +1385,14 @@ Nav2Panel::updateWpNavigationMarkers() auto marker_array = std::make_unique(); - for (size_t i = 0; i < acummulated_poses_.size(); i++) { + for (size_t i = 0; i < acummulated_poses_.poses.size(); i++) { // Draw a green arrow at the waypoint pose visualization_msgs::msg::Marker arrow_marker; - arrow_marker.header = acummulated_poses_[i].header; + arrow_marker.header = acummulated_poses_.poses[i].header; arrow_marker.id = getUniqueId(); arrow_marker.type = visualization_msgs::msg::Marker::ARROW; arrow_marker.action = visualization_msgs::msg::Marker::ADD; - arrow_marker.pose = acummulated_poses_[i].pose; + arrow_marker.pose = acummulated_poses_.poses[i].pose; arrow_marker.scale.x = 0.3; arrow_marker.scale.y = 0.05; arrow_marker.scale.z = 0.02; @@ -1405,11 +1406,11 @@ Nav2Panel::updateWpNavigationMarkers() // Draw a red circle at the waypoint pose visualization_msgs::msg::Marker circle_marker; - circle_marker.header = acummulated_poses_[i].header; + circle_marker.header = acummulated_poses_.poses[i].header; circle_marker.id = getUniqueId(); circle_marker.type = visualization_msgs::msg::Marker::SPHERE; circle_marker.action = visualization_msgs::msg::Marker::ADD; - circle_marker.pose = acummulated_poses_[i].pose; + circle_marker.pose = acummulated_poses_.poses[i].pose; circle_marker.scale.x = 0.05; circle_marker.scale.y = 0.05; circle_marker.scale.z = 0.05; @@ -1423,11 +1424,11 @@ Nav2Panel::updateWpNavigationMarkers() // Draw the waypoint number visualization_msgs::msg::Marker marker_text; - marker_text.header = acummulated_poses_[i].header; + marker_text.header = acummulated_poses_.poses[i].header; marker_text.id = getUniqueId(); marker_text.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; marker_text.action = visualization_msgs::msg::Marker::ADD; - marker_text.pose = acummulated_poses_[i].pose; + marker_text.pose = acummulated_poses_.poses[i].pose; marker_text.pose.position.z += 0.2; // draw it on top of the waypoint marker_text.scale.x = 0.07; marker_text.scale.y = 0.07; diff --git a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py index 0e59df8814c..079481444e8 100644 --- a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py +++ b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py @@ -557,7 +557,9 @@ def _getPathThroughPosesImpl(self, start, goals, planner_id='', use_start=False) goal_msg = ComputePathThroughPoses.Goal() goal_msg.start = start - goal_msg.goals = goals + goal_msg.goals.header.frame_id = 'map' + goal_msg.goals.header.stamp = self.get_clock().now().to_msg() + goal_msg.goals.poses = goals goal_msg.planner_id = planner_id goal_msg.use_start = use_start diff --git a/nav2_smac_planner/README.md b/nav2_smac_planner/README.md index 5afe2238e1d..fabc20b29a2 100644 --- a/nav2_smac_planner/README.md +++ b/nav2_smac_planner/README.md @@ -19,6 +19,10 @@ We have users reporting using this on: See its [Configuration Guide Page](https://docs.nav2.org/configuration/packages/configuring-smac-planner.html) for additional parameter descriptions. +Want to learn more? Checkout the ROSCon 2022 talk on the Smac Planner by clicking on the image below! + +[![IMAGE ALT TEXT](https://github.com/user-attachments/assets/95717450-2ff8-4576-ae38-88e7f266e8c6)](https://vimeo.com/showcase/9954564/video/767157646) + ## Introduction The `nav2_smac_planner` package contains an optimized templated A* search algorithm used to create multiple A\*-based planners for multiple types of robot platforms. It was built by [Steve Macenski](https://www.linkedin.com/in/steve-macenski-41a985101/) while at [Samsung Research](https://www.sra.samsung.com/). We support **circular** differential-drive and omni-directional drive robots using the `SmacPlanner2D` planner which implements a cost-aware A\* planner. We support **legged, cars, car-like, and ackermann vehicles** using the `SmacPlannerHybrid` plugin which implements a Hybrid-A\* planner. We support **non-circular, arbitrary shaped, any model vehicles** using the `SmacPlannerLattice` plugin which implements a State Lattice planner. It contains control sets and generators for ackermann, legged, differential drive and omnidirectional vehicles, but you may provide your own for another robot type or to have different planning behaviors. The last two plugins are also useful for curvature constrained or kinematically feasible planning, like when planning robot at high speeds to make sure they don't flip over or otherwise skid out of control. It is also applicable to non-round robots (such as large rectangular or arbitrary shaped robots of differential/omnidirectional drivetrains) that need pose-based collision checking. diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp index 059871d8677..b386f8d6edb 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp @@ -32,7 +32,7 @@ #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_util/lifecycle_node.hpp" #include "nav2_util/node_utils.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "rcl_interfaces/msg/set_parameters_result.hpp" namespace nav2_smac_planner diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp index a4b7ed180bb..4469579f178 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp @@ -32,7 +32,7 @@ #include "geometry_msgs/msg/pose_array.hpp" #include "nav2_util/lifecycle_node.hpp" #include "nav2_util/node_utils.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" namespace nav2_smac_planner { diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp index 74be801ad2b..e204c8e01fb 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp @@ -31,7 +31,7 @@ #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_util/lifecycle_node.hpp" #include "nav2_util/node_utils.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" namespace nav2_smac_planner { diff --git a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp index 89cb2f8dc77..c2edd13b6e2 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/utils.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/utils.hpp @@ -23,7 +23,7 @@ #include "nlohmann/json.hpp" #include "geometry_msgs/msg/quaternion.hpp" #include "geometry_msgs/msg/pose.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_costmap_2d/inflation_layer.hpp" #include "visualization_msgs/msg/marker_array.hpp" diff --git a/nav2_smac_planner/src/smoother.cpp b/nav2_smac_planner/src/smoother.cpp index 298efa51e2f..4372c10127d 100644 --- a/nav2_smac_planner/src/smoother.cpp +++ b/nav2_smac_planner/src/smoother.cpp @@ -21,7 +21,7 @@ #include "angles/angles.h" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "nav2_smac_planner/smoother.hpp" diff --git a/nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp b/nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp index 090aa07af85..170d31d7cb7 100644 --- a/nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp +++ b/nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp @@ -31,7 +31,7 @@ #include "nav2_util/node_utils.hpp" #include "nav_msgs/msg/path.hpp" #include "angles/angles.h" -#include "tf2/utils.h" +#include "tf2/utils.hpp" namespace nav2_smoother { diff --git a/nav2_smoother/include/nav2_smoother/simple_smoother.hpp b/nav2_smoother/include/nav2_smoother/simple_smoother.hpp index da0f98bf965..3686f433376 100644 --- a/nav2_smoother/include/nav2_smoother/simple_smoother.hpp +++ b/nav2_smoother/include/nav2_smoother/simple_smoother.hpp @@ -31,7 +31,7 @@ #include "nav2_util/node_utils.hpp" #include "nav_msgs/msg/path.hpp" #include "angles/angles.h" -#include "tf2/utils.h" +#include "tf2/utils.hpp" namespace nav2_smoother { diff --git a/nav2_smoother/include/nav2_smoother/smoother_utils.hpp b/nav2_smoother/include/nav2_smoother/smoother_utils.hpp index c7a45f383c0..c9e326c7f36 100644 --- a/nav2_smoother/include/nav2_smoother/smoother_utils.hpp +++ b/nav2_smoother/include/nav2_smoother/smoother_utils.hpp @@ -30,7 +30,7 @@ #include "nav2_util/node_utils.hpp" #include "nav_msgs/msg/path.hpp" #include "angles/angles.h" -#include "tf2/utils.h" +#include "tf2/utils.hpp" namespace smoother_utils { diff --git a/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp b/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp index 626588bbd09..ebfb1f53a64 100644 --- a/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp +++ b/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp @@ -34,7 +34,7 @@ #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/empty.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" diff --git a/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp b/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp index 18e131de88b..cef62bdaf56 100644 --- a/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp +++ b/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp @@ -31,7 +31,7 @@ #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" diff --git a/nav2_system_tests/src/system/nav_through_poses_tester_node.py b/nav2_system_tests/src/system/nav_through_poses_tester_node.py index 2bcea319313..ba65fccf1bb 100755 --- a/nav2_system_tests/src/system/nav_through_poses_tester_node.py +++ b/nav2_system_tests/src/system/nav_through_poses_tester_node.py @@ -94,7 +94,9 @@ def runNavigateAction(self, goal_pose: Optional[Pose] = None): self.goal_pose = goal_pose if goal_pose is not None else self.goal_pose goal_msg = NavigateThroughPoses.Goal() - goal_msg.poses = [ + goal_msg.poses.header.frame_id = 'map' + goal_msg.poses.header.stamp = self.get_clock().now().to_msg() + goal_msg.poses.poses = [ self.getStampedPoseMsg(self.goal_pose), self.getStampedPoseMsg(self.goal_pose), ] @@ -164,7 +166,7 @@ def runNavigatePreemptionAction(self, block): ) goal_msg = NavigateThroughPoses.Goal() - goal_msg.poses = [self.getStampedPoseMsg(self.initial_pose)] + goal_msg.poses.poses = [self.getStampedPoseMsg(self.initial_pose)] self.info_msg('Sending goal request...') send_goal_future = self.action_client.send_goal_async(goal_msg) diff --git a/nav2_util/include/nav2_util/robot_utils.hpp b/nav2_util/include/nav2_util/robot_utils.hpp index cb7d2b9fdfb..e76a2cce708 100644 --- a/nav2_util/include/nav2_util/robot_utils.hpp +++ b/nav2_util/include/nav2_util/robot_utils.hpp @@ -24,8 +24,8 @@ #include "geometry_msgs/msg/twist.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" -#include "tf2/time.h" -#include "tf2/transform_datatypes.h" +#include "tf2/time.hpp" +#include "tf2/transform_datatypes.hpp" #include "tf2_ros/buffer.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "rclcpp/rclcpp.hpp" diff --git a/nav2_util/src/base_footprint_publisher.hpp b/nav2_util/src/base_footprint_publisher.hpp index 25d58d504bf..67f50625101 100644 --- a/nav2_util/src/base_footprint_publisher.hpp +++ b/nav2_util/src/base_footprint_publisher.hpp @@ -26,7 +26,7 @@ #include "tf2_ros/transform_broadcaster.h" #include "tf2_ros/buffer.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "tf2/utils.h" +#include "tf2/utils.hpp" namespace nav2_util { diff --git a/nav2_util/src/costmap.cpp b/nav2_util/src/costmap.cpp index 91f3b2fbc82..5ab609634b8 100644 --- a/nav2_util/src/costmap.cpp +++ b/nav2_util/src/costmap.cpp @@ -15,7 +15,7 @@ #include #include #include "nav2_util/costmap.hpp" -#include "tf2/LinearMath/Quaternion.h" +#include "tf2/LinearMath/Quaternion.hpp" #include "nav2_util/geometry_utils.hpp" using std::vector; diff --git a/nav2_util/src/robot_utils.cpp b/nav2_util/src/robot_utils.cpp index a9f4d137fa2..736709ce641 100644 --- a/nav2_util/src/robot_utils.cpp +++ b/nav2_util/src/robot_utils.cpp @@ -18,7 +18,7 @@ #include #include -#include "tf2/convert.h" +#include "tf2/convert.hpp" #include "nav2_util/robot_utils.hpp" #include "rclcpp/logger.hpp" diff --git a/nav2_util/test/test_base_footprint_publisher.cpp b/nav2_util/test/test_base_footprint_publisher.cpp index cd788831325..c85a4c931b7 100644 --- a/nav2_util/test/test_base_footprint_publisher.cpp +++ b/nav2_util/test/test_base_footprint_publisher.cpp @@ -17,7 +17,7 @@ #include "base_footprint_publisher.hpp" #include "gtest/gtest.h" -#include "tf2/exceptions.h" +#include "tf2/exceptions.hpp" class RclCppFixture { diff --git a/tools/underlay.repos b/tools/underlay.repos index 005f11ec3f0..e443ce12489 100644 --- a/tools/underlay.repos +++ b/tools/underlay.repos @@ -35,3 +35,8 @@ repositories: type: git url: https://github.com/ros-navigation/nav2_minimal_turtlebot_simulation.git version: 091b5ff12436890a54de6325df3573ae110e912b + ros/common_interfaces: + type: git + url: https://github.com/ros2/common_interfaces.git + version: rolling + From 98966070926ad08959c1b9302273d7449c73d152 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Sat, 11 Jan 2025 00:26:58 +0300 Subject: [PATCH 04/18] Called off API changes in costmap, added "restore_outdated_footprint" Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/costmap_2d.hpp | 32 -------- .../include/nav2_costmap_2d/static_layer.hpp | 15 +++- nav2_costmap_2d/plugins/static_layer.cpp | 76 ++++++++++++++++--- nav2_costmap_2d/src/costmap_2d.cpp | 5 -- 4 files changed, 78 insertions(+), 50 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp index 8673fefb51d..927e5806122 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp @@ -163,8 +163,6 @@ class Costmap2D */ void setCost(unsigned int mx, unsigned int my, unsigned char cost); - void setCost(unsigned int index, unsigned char cost); - /** * @brief Convert from map coordinates to world coordinates * @param mx The x map coordinate @@ -313,36 +311,6 @@ class Costmap2D const std::vector & polygon, unsigned char cost_value); - template - bool setConvexPolygonCost( - const std::vector & polygon, - CostSetter cost_setter) - { - // we assume the polygon is given in the global_frame... - // we need to transform it to map coordinates - std::vector map_polygon; - for (unsigned int i = 0; i < polygon.size(); ++i) { - MapLocation loc; - if (!worldToMap(polygon[i].x, polygon[i].y, loc.x, loc.y)) { - // ("Polygon lies outside map bounds, so we can't fill it"); - return false; - } - map_polygon.push_back(loc); - } - - std::vector polygon_cells; - - // get the cells that fill the polygon - convexFillCells(map_polygon, polygon_cells); - - // set the cost of those cells - for (unsigned int i = 0; i < polygon_cells.size(); ++i) { - unsigned int index = getIndex(polygon_cells[i].x, polygon_cells[i].y); - costmap_[index] = cost_setter(index); - } - return true; - } - /** * @brief Get the map cells that make up the outline of a polygon * @param polygon The polygon in map coordinates to rasterize diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp index 08c9049d637..601e27bfeff 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp @@ -154,6 +154,17 @@ class StaticLayer : public CostmapLayer */ unsigned char interpretValue(unsigned char value); + void getCellsOccupiedByFootprint( + std::vector & cells_occupied_by_footprint, + const std::vector & footprint); + + void resetCells( + const std::vector & resetting_cells, unsigned char cost); + + void restoreCellsFromMap( + const std::vector & restoring_cells, + const nav_msgs::msg::OccupancyGrid::SharedPtr & map_buffer); + /** * @brief Callback executed when a parameter change is detected * @param event ParameterEvent message @@ -162,8 +173,10 @@ class StaticLayer : public CostmapLayer dynamicParametersCallback(std::vector parameters); std::vector transformed_footprint_; - std::vector cleared_indexes_in_map_; + std::vector cells_cleared_by_footprint_; bool footprint_clearing_enabled_; + bool restore_outdated_footprint_; + /** * @brief Clear costmap layer info below the robot's footprint */ diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 888028f3662..33af82e3cd5 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -138,6 +138,7 @@ StaticLayer::getParameters() declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0)); declareParameter("map_topic", rclcpp::ParameterValue("map")); declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false)); + declareParameter("restore_outdated_footprint", rclcpp::ParameterValue(false)); auto node = node_.lock(); if (!node) { @@ -147,6 +148,7 @@ StaticLayer::getParameters() node->get_parameter(name_ + "." + "enabled", enabled_); node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_); node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); + node->get_parameter(name_ + "." + "restore_outdated_footprint", restore_outdated_footprint_); node->get_parameter(name_ + "." + "map_topic", map_topic_); map_topic_ = joinWithParentNamespace(map_topic_); node->get_parameter( @@ -322,6 +324,46 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u has_updated_data_ = true; } +void +StaticLayer::getCellsOccupiedByFootprint( + std::vector & cells_occupied_by_footprint, + const std::vector & footprint) +{ + // we assume the polygon is given in the global_frame... + // we need to transform it to map coordinates + std::vector map_polygon; + for (const auto & point : footprint) { + MapLocation loc; + if (!this->worldToMap(point.x, point.y, loc.x, loc.y)) { + // ("Polygon lies outside map bounds, so we can't fill it"); + return; + } + map_polygon.push_back(loc); + } + + // get the cells that fill the polygon + this->convexFillCells(map_polygon, cells_occupied_by_footprint); +} + +void StaticLayer::resetCells( + const std::vector & resetting_cells, unsigned char cost) +{ + + for (const auto & cell : resetting_cells) { + setCost(cell.x, cell.y, cost); + } +} + +void StaticLayer::restoreCellsFromMap( + const std::vector & restoring_cells, + const nav_msgs::msg::OccupancyGrid::SharedPtr & map_buffer) +{ + + for (const auto & cell : restoring_cells) { + unsigned int index = getIndex(cell.x, cell.y); + costmap_[index] = interpretValue(map_buffer->data[index]); + } +} void StaticLayer::updateBounds( @@ -374,10 +416,17 @@ StaticLayer::updateFootprint( { if (!footprint_clearing_enabled_) {return;} + if (restore_outdated_footprint_) { + // Increase the bounds to make the outdated footprint restored by layered costmap + for (const auto & point : transformed_footprint_) { + touch(point.x, point.y, min_x, min_y, max_x, max_y); + } + } + transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_); - for (unsigned int i = 0; i < transformed_footprint_.size(); i++) { - touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y); + for (const auto & point : transformed_footprint_) { + touch(point.x, point.y, min_x, min_y, max_x, max_y); } } @@ -400,6 +449,17 @@ StaticLayer::updateCosts( return; } + if (footprint_clearing_enabled_) { + if (restore_outdated_footprint_) { + restoreCellsFromMap(cells_cleared_by_footprint_, map_buffer_); + } + + cells_cleared_by_footprint_.clear(); + getCellsOccupiedByFootprint(cells_cleared_by_footprint_, transformed_footprint_); + + resetCells(cells_cleared_by_footprint_, nav2_costmap_2d::FREE_SPACE); + } + if (!layered_costmap_->isRolling()) { // if not rolling, the layered costmap (master_grid) has same coordinates as this layer if (!use_maximum_) { @@ -444,16 +504,6 @@ StaticLayer::updateCosts( } } - if (footprint_clearing_enabled_) { - for (const auto index : cleared_indexes_in_map_) { - master_grid.setCost(index, interpretValue(map_buffer_->data[index])); - } - cleared_indexes_in_map_.clear(); - master_grid.setConvexPolygonCost(transformed_footprint_, [this](unsigned int index) { - cleared_indexes_in_map_.push_back(index); - return nav2_costmap_2d::FREE_SPACE; - }); - } current_ = true; } @@ -496,6 +546,8 @@ StaticLayer::dynamicParametersCallback( } else if (param_type == ParameterType::PARAMETER_BOOL) { if (param_name == name_ + "." + "footprint_clearing_enabled") { footprint_clearing_enabled_ = parameter.as_bool(); + } else if (param_name == name_ + "." + "restore_outdated_footprint") { + restore_outdated_footprint_ = parameter.as_bool(); } } } diff --git a/nav2_costmap_2d/src/costmap_2d.cpp b/nav2_costmap_2d/src/costmap_2d.cpp index e191ed3cd5b..0302801297b 100644 --- a/nav2_costmap_2d/src/costmap_2d.cpp +++ b/nav2_costmap_2d/src/costmap_2d.cpp @@ -276,11 +276,6 @@ void Costmap2D::setCost(unsigned int mx, unsigned int my, unsigned char cost) costmap_[getIndex(mx, my)] = cost; } -void Costmap2D::setCost(unsigned int index, unsigned char cost) -{ - costmap_[index] = cost; -} - void Costmap2D::mapToWorld(unsigned int mx, unsigned int my, double & wx, double & wy) const { wx = origin_x_ + (mx + 0.5) * resolution_; From 39f1f6202c4cf48f6e8c0089d0a0c1b48b989334 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Sat, 11 Jan 2025 01:04:32 +0300 Subject: [PATCH 05/18] Added the documentation for the new methods in static layer Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/static_layer.hpp | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp index 601e27bfeff..28ec4d5a6d4 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp @@ -154,13 +154,27 @@ class StaticLayer : public CostmapLayer */ unsigned char interpretValue(unsigned char value); + /** + * @brief Get the cells occupied by the footprint + * @param cells_occupied_by_footprint The cell coordinates that the footprint occupies + * @param footprint The footprint to perform the operation on + */ void getCellsOccupiedByFootprint( std::vector & cells_occupied_by_footprint, const std::vector & footprint); + /** + * @brief Reset the cells to a desired value + * @param resetting_cells The cell coordinates to reset to a desired value + * @param cost The value to set costs to + */ void resetCells( const std::vector & resetting_cells, unsigned char cost); + /** + * @brief Restored the given cells using the latest map buffer + * @param restoring_cells The cell coordinates to restore by given map buffer + */ void restoreCellsFromMap( const std::vector & restoring_cells, const nav_msgs::msg::OccupancyGrid::SharedPtr & map_buffer); From d7bc96c41bdde554dfcd344c1b9d538486ee93a5 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Sat, 11 Jan 2025 01:28:18 +0300 Subject: [PATCH 06/18] Make CI happy Signed-off-by: CihatAltiparmak --- nav2_costmap_2d/plugins/static_layer.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 33af82e3cd5..23bdcc35bff 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -348,7 +348,6 @@ StaticLayer::getCellsOccupiedByFootprint( void StaticLayer::resetCells( const std::vector & resetting_cells, unsigned char cost) { - for (const auto & cell : resetting_cells) { setCost(cell.x, cell.y, cost); } @@ -358,7 +357,6 @@ void StaticLayer::restoreCellsFromMap( const std::vector & restoring_cells, const nav_msgs::msg::OccupancyGrid::SharedPtr & map_buffer) { - for (const auto & cell : restoring_cells) { unsigned int index = getIndex(cell.x, cell.y); costmap_[index] = interpretValue(map_buffer->data[index]); From 7b4cee3456c8274f6b55d6ac06fe6cfe3aa43205 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Thu, 16 Jan 2025 23:15:18 +0300 Subject: [PATCH 07/18] Apply suggestions and minimize diffs Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/static_layer.hpp | 31 +----- nav2_costmap_2d/plugins/static_layer.cpp | 103 ++++++------------ 2 files changed, 34 insertions(+), 100 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp index 28ec4d5a6d4..f0735904a9d 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp @@ -154,31 +154,6 @@ class StaticLayer : public CostmapLayer */ unsigned char interpretValue(unsigned char value); - /** - * @brief Get the cells occupied by the footprint - * @param cells_occupied_by_footprint The cell coordinates that the footprint occupies - * @param footprint The footprint to perform the operation on - */ - void getCellsOccupiedByFootprint( - std::vector & cells_occupied_by_footprint, - const std::vector & footprint); - - /** - * @brief Reset the cells to a desired value - * @param resetting_cells The cell coordinates to reset to a desired value - * @param cost The value to set costs to - */ - void resetCells( - const std::vector & resetting_cells, unsigned char cost); - - /** - * @brief Restored the given cells using the latest map buffer - * @param restoring_cells The cell coordinates to restore by given map buffer - */ - void restoreCellsFromMap( - const std::vector & restoring_cells, - const nav_msgs::msg::OccupancyGrid::SharedPtr & map_buffer); - /** * @brief Callback executed when a parameter change is detected * @param event ParameterEvent message @@ -187,10 +162,7 @@ class StaticLayer : public CostmapLayer dynamicParametersCallback(std::vector parameters); std::vector transformed_footprint_; - std::vector cells_cleared_by_footprint_; bool footprint_clearing_enabled_; - bool restore_outdated_footprint_; - /** * @brief Clear costmap layer info below the robot's footprint */ @@ -222,7 +194,8 @@ class StaticLayer : public CostmapLayer unsigned char lethal_threshold_; unsigned char unknown_cost_value_; bool trinary_costmap_; - bool has_map_to_process_{false}; + bool map_received_{false}; + bool map_received_in_update_bounds_{false}; tf2::Duration transform_tolerance_; nav_msgs::msg::OccupancyGrid::SharedPtr map_buffer_; // Dynamic parameters handler diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 23bdcc35bff..635929d860c 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -138,7 +138,6 @@ StaticLayer::getParameters() declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0)); declareParameter("map_topic", rclcpp::ParameterValue("map")); declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false)); - declareParameter("restore_outdated_footprint", rclcpp::ParameterValue(false)); auto node = node_.lock(); if (!node) { @@ -148,7 +147,6 @@ StaticLayer::getParameters() node->get_parameter(name_ + "." + "enabled", enabled_); node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_); node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); - node->get_parameter(name_ + "." + "restore_outdated_footprint", restore_outdated_footprint_); node->get_parameter(name_ + "." + "map_topic", map_topic_); map_topic_ = joinWithParentNamespace(map_topic_); node->get_parameter( @@ -163,7 +161,8 @@ StaticLayer::getParameters() // Enforce bounds lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0); - has_map_to_process_ = false; + map_received_ = false; + map_received_in_update_bounds_ = false; transform_tolerance_ = tf2::durationFromSec(temp_tf_tol); @@ -221,8 +220,12 @@ StaticLayer::processMap(const nav_msgs::msg::OccupancyGrid & new_map) new_map.info.origin.position.x, new_map.info.origin.position.y); } - // initialize the costmap with static data unsigned int index = 0; + + // we have a new map, update full size of map + std::lock_guard guard(*getMutex()); + + // initialize the costmap with static data for (unsigned int i = 0; i < size_y; ++i) { for (unsigned int j = 0; j < size_x; ++j) { unsigned char value = new_map.data[index]; @@ -279,9 +282,13 @@ StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map) RCLCPP_ERROR(logger_, "Received map message is malformed. Rejecting."); return; } + if (!map_received_) { + processMap(*new_map); + map_received_ = true; + return; + } std::lock_guard guard(*getMutex()); map_buffer_ = new_map; - has_map_to_process_ = true; } void @@ -324,44 +331,6 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u has_updated_data_ = true; } -void -StaticLayer::getCellsOccupiedByFootprint( - std::vector & cells_occupied_by_footprint, - const std::vector & footprint) -{ - // we assume the polygon is given in the global_frame... - // we need to transform it to map coordinates - std::vector map_polygon; - for (const auto & point : footprint) { - MapLocation loc; - if (!this->worldToMap(point.x, point.y, loc.x, loc.y)) { - // ("Polygon lies outside map bounds, so we can't fill it"); - return; - } - map_polygon.push_back(loc); - } - - // get the cells that fill the polygon - this->convexFillCells(map_polygon, cells_occupied_by_footprint); -} - -void StaticLayer::resetCells( - const std::vector & resetting_cells, unsigned char cost) -{ - for (const auto & cell : resetting_cells) { - setCost(cell.x, cell.y, cost); - } -} - -void StaticLayer::restoreCellsFromMap( - const std::vector & restoring_cells, - const nav_msgs::msg::OccupancyGrid::SharedPtr & map_buffer) -{ - for (const auto & cell : restoring_cells) { - unsigned int index = getIndex(cell.x, cell.y); - costmap_[index] = interpretValue(map_buffer->data[index]); - } -} void StaticLayer::updateBounds( @@ -370,16 +339,18 @@ StaticLayer::updateBounds( double * max_x, double * max_y) { - std::lock_guard guard(*getMutex()); - - if (!map_buffer_) { + if (!map_received_) { + map_received_in_update_bounds_ = false; return; } + map_received_in_update_bounds_ = true; + + std::lock_guard guard(*getMutex()); // If there is a new available map, load it. - if (has_map_to_process_) { + if (map_buffer_) { processMap(*map_buffer_); - has_map_to_process_ = false; + map_buffer_ = nullptr; } updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y); @@ -403,6 +374,7 @@ StaticLayer::updateBounds( *max_y = std::max(wy, *max_y); has_updated_data_ = false; + } void @@ -414,18 +386,17 @@ StaticLayer::updateFootprint( { if (!footprint_clearing_enabled_) {return;} - if (restore_outdated_footprint_) { - // Increase the bounds to make the outdated footprint restored by layered costmap - for (const auto & point : transformed_footprint_) { - touch(point.x, point.y, min_x, min_y, max_x, max_y); - } - } + auto touchByFootprint = [&]( + const std::vector & footprint) { + for (const auto & point : footprint) { + touch(point.x, point.y, min_x, min_y, max_x, max_y); + } + }; + touchByFootprint(transformed_footprint_); transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_); + touchByFootprint(transformed_footprint_); - for (const auto & point : transformed_footprint_) { - touch(point.x, point.y, min_x, min_y, max_x, max_y); - } } void @@ -437,7 +408,7 @@ StaticLayer::updateCosts( if (!enabled_) { return; } - if (!map_buffer_) { + if (!map_received_in_update_bounds_) { static int count = 0; // throttle warning down to only 1/10 message rate if (++count == 10) { @@ -447,17 +418,6 @@ StaticLayer::updateCosts( return; } - if (footprint_clearing_enabled_) { - if (restore_outdated_footprint_) { - restoreCellsFromMap(cells_cleared_by_footprint_, map_buffer_); - } - - cells_cleared_by_footprint_.clear(); - getCellsOccupiedByFootprint(cells_cleared_by_footprint_, transformed_footprint_); - - resetCells(cells_cleared_by_footprint_, nav2_costmap_2d::FREE_SPACE); - } - if (!layered_costmap_->isRolling()) { // if not rolling, the layered costmap (master_grid) has same coordinates as this layer if (!use_maximum_) { @@ -502,6 +462,9 @@ StaticLayer::updateCosts( } } + if (footprint_clearing_enabled_) { + master_grid.setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE); + } current_ = true; } @@ -544,8 +507,6 @@ StaticLayer::dynamicParametersCallback( } else if (param_type == ParameterType::PARAMETER_BOOL) { if (param_name == name_ + "." + "footprint_clearing_enabled") { footprint_clearing_enabled_ = parameter.as_bool(); - } else if (param_name == name_ + "." + "restore_outdated_footprint") { - restore_outdated_footprint_ = parameter.as_bool(); } } } From 0e9dbeb6a1f83a41dae9bff93888e9d008fafa69 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Thu, 16 Jan 2025 23:38:26 +0300 Subject: [PATCH 08/18] Fix ament_cpp_lint Signed-off-by: CihatAltiparmak --- nav2_costmap_2d/plugins/static_layer.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 635929d860c..5ff2a76af9c 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -374,7 +374,6 @@ StaticLayer::updateBounds( *max_y = std::max(wy, *max_y); has_updated_data_ = false; - } void @@ -396,7 +395,6 @@ StaticLayer::updateFootprint( touchByFootprint(transformed_footprint_); transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_); touchByFootprint(transformed_footprint_); - } void From 2da4d29ab0c0a18294b87103b45f5a953f51a338 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Mon, 27 Jan 2025 22:49:38 +0300 Subject: [PATCH 09/18] Revert changes in the method updateFootprint Signed-off-by: CihatAltiparmak --- nav2_costmap_2d/plugins/static_layer.cpp | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 5ff2a76af9c..a49ee3cb235 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -385,16 +385,11 @@ StaticLayer::updateFootprint( { if (!footprint_clearing_enabled_) {return;} - auto touchByFootprint = [&]( - const std::vector & footprint) { - for (const auto & point : footprint) { - touch(point.x, point.y, min_x, min_y, max_x, max_y); - } - }; + for (const auto & point : transformed_footprint_) { + touch(point.x, point.y, min_x, min_y, max_x, max_y); + } - touchByFootprint(transformed_footprint_); transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_); - touchByFootprint(transformed_footprint_); } void From d78274b93ed34f43597d39ec38aa2b7c5a01550f Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Thu, 30 Jan 2025 00:37:06 +0300 Subject: [PATCH 10/18] Used cached data to restore map and broken up setConvexPolygonCost into two methods Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/costmap_2d.hpp | 19 +++++++++++ nav2_costmap_2d/plugins/static_layer.cpp | 26 ++++++++++---- nav2_costmap_2d/src/costmap_2d.cpp | 34 ++++++++++++++----- 3 files changed, 64 insertions(+), 15 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp index 927e5806122..5079beb119f 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp @@ -311,6 +311,25 @@ class Costmap2D const std::vector & polygon, unsigned char cost_value); + /** + * @brief Gets the cells occupied by polygon + * @param polygon The polygon to perform the operation on + * @param polygon_cells The cells that fills the polygon + * @return True if the polygon was filled... false if it could not be filled + */ + bool getCellsOccupiedByPolygon( + const std::vector & polygon, + std::vector & polygon_cells); + + /** + * @brief Sets the given cells to desired value + * @param given_cells The cells to perform the operation on + * @param cost_value The value to set costs to + */ + void setCostForCells( + std::vector given_cells, + unsigned char cost_value); + /** * @brief Get the map cells that make up the outline of a polygon * @param polygon The polygon in map coordinates to rasterize diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index a49ee3cb235..a5d1f2c2a99 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -353,8 +353,6 @@ StaticLayer::updateBounds( map_buffer_ = nullptr; } - updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y); - if (!layered_costmap_->isRolling() ) { if (!(has_updated_data_ || has_extra_bounds_)) { return; @@ -374,6 +372,8 @@ StaticLayer::updateBounds( *max_y = std::max(wy, *max_y); has_updated_data_ = false; + + updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y); } void @@ -385,11 +385,11 @@ StaticLayer::updateFootprint( { if (!footprint_clearing_enabled_) {return;} + transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_); + for (const auto & point : transformed_footprint_) { touch(point.x, point.y, min_x, min_y, max_x, max_y); } - - transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_); } void @@ -411,6 +411,19 @@ StaticLayer::updateCosts( return; } + std::vector> map_region_to_restore; + if (footprint_clearing_enabled_) { + std::vector polygon_cells; + getCellsOccupiedByPolygon(transformed_footprint_, polygon_cells); + + // save the map region occupied by the polygon to restore + for (auto cell : polygon_cells) { + map_region_to_restore.push_back({cell, getCost(cell.x, cell.y)}); + } + + setCostForCells(polygon_cells, nav2_costmap_2d::FREE_SPACE); + } + if (!layered_costmap_->isRolling()) { // if not rolling, the layered costmap (master_grid) has same coordinates as this layer if (!use_maximum_) { @@ -455,8 +468,9 @@ StaticLayer::updateCosts( } } - if (footprint_clearing_enabled_) { - master_grid.setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE); + // restore the map region occupied by the polygon using cached data + for (auto [cell, cost_value] : map_region_to_restore) { + setCost(cell.x, cell.y, cost_value); } current_ = true; } diff --git a/nav2_costmap_2d/src/costmap_2d.cpp b/nav2_costmap_2d/src/costmap_2d.cpp index 0302801297b..48238cbfcb6 100644 --- a/nav2_costmap_2d/src/costmap_2d.cpp +++ b/nav2_costmap_2d/src/costmap_2d.cpp @@ -399,29 +399,45 @@ void Costmap2D::updateOrigin(double new_origin_x, double new_origin_y) bool Costmap2D::setConvexPolygonCost( const std::vector & polygon, unsigned char cost_value) +{ + std::vector polygon_cells; + if (!getCellsOccupiedByPolygon(polygon, polygon_cells)) { + return false; + } + + // set the cost of those cells + setCostForCells(polygon_cells, cost_value); + return true; +} + +void Costmap2D::setCostForCells( + std::vector given_cells, + unsigned char cost_value) +{ + for (const auto & cell : given_cells) { + setCost(cell.x, cell.y, cost_value); + } +} + +bool Costmap2D::getCellsOccupiedByPolygon( + const std::vector & polygon, + std::vector & polygon_cells) { // we assume the polygon is given in the global_frame... // we need to transform it to map coordinates std::vector map_polygon; - for (unsigned int i = 0; i < polygon.size(); ++i) { + for (const auto & cell : polygon) { MapLocation loc; - if (!worldToMap(polygon[i].x, polygon[i].y, loc.x, loc.y)) { + if (!worldToMap(cell.x, cell.y, loc.x, loc.y)) { // ("Polygon lies outside map bounds, so we can't fill it"); return false; } map_polygon.push_back(loc); } - std::vector polygon_cells; - // get the cells that fill the polygon convexFillCells(map_polygon, polygon_cells); - // set the cost of those cells - for (unsigned int i = 0; i < polygon_cells.size(); ++i) { - unsigned int index = getIndex(polygon_cells[i].x, polygon_cells[i].y); - costmap_[index] = cost_value; - } return true; } From a0657d28426924b90f10d5436b6a000b8ba547ea Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Sat, 1 Feb 2025 15:07:18 +0300 Subject: [PATCH 11/18] Rename newly added methods Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/costmap_2d.hpp | 29 +++++++++------- nav2_costmap_2d/plugins/static_layer.cpp | 19 +++-------- nav2_costmap_2d/src/costmap_2d.cpp | 33 ++++++++++++++----- 3 files changed, 47 insertions(+), 34 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp index 5079beb119f..681f729a863 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp @@ -312,23 +312,30 @@ class Costmap2D unsigned char cost_value); /** - * @brief Gets the cells occupied by polygon + * @brief Gets the map region occupied by polygon * @param polygon The polygon to perform the operation on - * @param polygon_cells The cells that fills the polygon - * @return True if the polygon was filled... false if it could not be filled + * @param polygon_map_region The map region occupied by the polygon + * @return True if the polygon_map_region was filled... false if it could not be filled */ - bool getCellsOccupiedByPolygon( + bool getMapRegionOccupiedByPolygon( const std::vector & polygon, - std::vector & polygon_cells); + std::vector> & polygon_map_region); /** - * @brief Sets the given cells to desired value - * @param given_cells The cells to perform the operation on - * @param cost_value The value to set costs to + * @brief Sets the given map region to desired value + * @param polygon_map_region The map region to perform the operation on + * @param new_cost_value The value to set costs to */ - void setCostForCells( - std::vector given_cells, - unsigned char cost_value); + void setMapRegionOccupiedByPolygon( + const std::vector> & polygon_map_region, + unsigned char new_cost_value); + + /** + * @brief Restores the corresponding map region using given map region + * @param polygon_map_region The map region to perform the operation on + */ + void restoreMapRegionOccupiedByPolygon( + const std::vector> & polygon_map_region); /** * @brief Get the map cells that make up the outline of a polygon diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index a5d1f2c2a99..7f37ee4d4a7 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -387,8 +387,8 @@ StaticLayer::updateFootprint( transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_); - for (const auto & point : transformed_footprint_) { - touch(point.x, point.y, min_x, min_y, max_x, max_y); + for (unsigned int i = 0; i < transformed_footprint_.size(); i++) { + touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y); } } @@ -413,15 +413,8 @@ StaticLayer::updateCosts( std::vector> map_region_to_restore; if (footprint_clearing_enabled_) { - std::vector polygon_cells; - getCellsOccupiedByPolygon(transformed_footprint_, polygon_cells); - - // save the map region occupied by the polygon to restore - for (auto cell : polygon_cells) { - map_region_to_restore.push_back({cell, getCost(cell.x, cell.y)}); - } - - setCostForCells(polygon_cells, nav2_costmap_2d::FREE_SPACE); + getMapRegionOccupiedByPolygon(transformed_footprint_, map_region_to_restore); + setMapRegionOccupiedByPolygon(map_region_to_restore, nav2_costmap_2d::FREE_SPACE); } if (!layered_costmap_->isRolling()) { @@ -469,9 +462,7 @@ StaticLayer::updateCosts( } // restore the map region occupied by the polygon using cached data - for (auto [cell, cost_value] : map_region_to_restore) { - setCost(cell.x, cell.y, cost_value); - } + restoreMapRegionOccupiedByPolygon(map_region_to_restore); current_ = true; } diff --git a/nav2_costmap_2d/src/costmap_2d.cpp b/nav2_costmap_2d/src/costmap_2d.cpp index 48238cbfcb6..09d73f1d848 100644 --- a/nav2_costmap_2d/src/costmap_2d.cpp +++ b/nav2_costmap_2d/src/costmap_2d.cpp @@ -400,28 +400,37 @@ bool Costmap2D::setConvexPolygonCost( const std::vector & polygon, unsigned char cost_value) { - std::vector polygon_cells; - if (!getCellsOccupiedByPolygon(polygon, polygon_cells)) { + + std::vector> polygon_map_region; + if (getMapRegionOccupiedByPolygon(polygon, polygon_map_region)) { return false; } // set the cost of those cells - setCostForCells(polygon_cells, cost_value); + setMapRegionOccupiedByPolygon(polygon_map_region, cost_value); return true; } -void Costmap2D::setCostForCells( - std::vector given_cells, - unsigned char cost_value) +void Costmap2D::setMapRegionOccupiedByPolygon( + const std::vector> & polygon_map_region, + unsigned char new_cost_value) { - for (const auto & cell : given_cells) { + for (const auto & [cell, _] : polygon_map_region) { + setCost(cell.x, cell.y, new_cost_value); + } +} + +void Costmap2D::restoreMapRegionOccupiedByPolygon( + const std::vector> & polygon_map_region) +{ + for (const auto & [cell, cost_value] : polygon_map_region) { setCost(cell.x, cell.y, cost_value); } } -bool Costmap2D::getCellsOccupiedByPolygon( +bool Costmap2D::getMapRegionOccupiedByPolygon( const std::vector & polygon, - std::vector & polygon_cells) + std::vector> & polygon_map_region) { // we assume the polygon is given in the global_frame... // we need to transform it to map coordinates @@ -436,8 +445,14 @@ bool Costmap2D::getCellsOccupiedByPolygon( } // get the cells that fill the polygon + std::vector polygon_cells; convexFillCells(map_polygon, polygon_cells); + // store the cost informations of the cells + for (const auto & cell : polygon_cells) { + polygon_map_region.push_back({cell, getCost(cell.x, cell.y)}); + } + return true; } From 833b98364fa5757456bcb26c5787762bc91439df Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Sat, 1 Feb 2025 15:23:24 +0300 Subject: [PATCH 12/18] Added restore_outdated_map parameter Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/static_layer.hpp | 1 + nav2_costmap_2d/plugins/static_layer.cpp | 10 ++++++++-- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp index f0735904a9d..ec64b046d1a 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp @@ -163,6 +163,7 @@ class StaticLayer : public CostmapLayer std::vector transformed_footprint_; bool footprint_clearing_enabled_; + bool restore_outdated_map_; /** * @brief Clear costmap layer info below the robot's footprint */ diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index afae34000e8..5aeff472685 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -138,6 +138,7 @@ StaticLayer::getParameters() declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0)); declareParameter("map_topic", rclcpp::ParameterValue("map")); declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false)); + declareParameter("restore_outdated_map", rclcpp::ParameterValue(false)); auto node = node_.lock(); if (!node) { @@ -147,6 +148,7 @@ StaticLayer::getParameters() node->get_parameter(name_ + "." + "enabled", enabled_); node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_); node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); + node->get_parameter(name_ + "." + "restore_outdated_map", restore_outdated_map_); node->get_parameter(name_ + "." + "map_topic", map_topic_); map_topic_ = joinWithParentNamespace(map_topic_); node->get_parameter( @@ -461,8 +463,10 @@ StaticLayer::updateCosts( } } - // restore the map region occupied by the polygon using cached data - restoreMapRegionOccupiedByPolygon(map_region_to_restore); + if (restore_outdated_map_) { + // restore the map region occupied by the polygon using cached data + restoreMapRegionOccupiedByPolygon(map_region_to_restore); + } current_ = true; } @@ -503,6 +507,8 @@ StaticLayer::dynamicParametersCallback( current_ = false; } else if (param_name == name_ + "." + "footprint_clearing_enabled") { footprint_clearing_enabled_ = parameter.as_bool(); + } else if (param_name == name_ + "." + "restore_outdated_map") { + restore_outdated_map_ = parameter.as_bool(); } } } From 2322d9846c26d289d8307a73324a278050b6fab2 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Sat, 1 Feb 2025 15:38:14 +0300 Subject: [PATCH 13/18] Make CI happy Signed-off-by: CihatAltiparmak --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp | 1 + nav2_costmap_2d/src/costmap_2d.cpp | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp index 681f729a863..38171616c7e 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp @@ -47,6 +47,7 @@ #include #include #include +#include #include "geometry_msgs/msg/point.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" diff --git a/nav2_costmap_2d/src/costmap_2d.cpp b/nav2_costmap_2d/src/costmap_2d.cpp index 09d73f1d848..cf8f8f607e7 100644 --- a/nav2_costmap_2d/src/costmap_2d.cpp +++ b/nav2_costmap_2d/src/costmap_2d.cpp @@ -400,7 +400,6 @@ bool Costmap2D::setConvexPolygonCost( const std::vector & polygon, unsigned char cost_value) { - std::vector> polygon_map_region; if (getMapRegionOccupiedByPolygon(polygon, polygon_map_region)) { return false; From fe4aec0eaa71defa8948e9a0102b39d78bebf333 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Tue, 4 Feb 2025 02:37:34 +0300 Subject: [PATCH 14/18] Changed the name of the newly added parameter - changed the name of the new param - fixed bug in the setConvexPolygonCost - Used reserve method of the vector instances - Added checks in dynamic parameter update. Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/static_layer.hpp | 2 +- nav2_costmap_2d/plugins/static_layer.cpp | 20 ++++++++++++++----- nav2_costmap_2d/src/costmap_2d.cpp | 3 ++- 3 files changed, 18 insertions(+), 7 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp index ec64b046d1a..c938f30f55e 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp @@ -163,7 +163,7 @@ class StaticLayer : public CostmapLayer std::vector transformed_footprint_; bool footprint_clearing_enabled_; - bool restore_outdated_map_; + bool restore_cleared_footprint_; /** * @brief Clear costmap layer info below the robot's footprint */ diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 5aeff472685..fc782fb00b0 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -138,7 +138,7 @@ StaticLayer::getParameters() declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0)); declareParameter("map_topic", rclcpp::ParameterValue("map")); declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false)); - declareParameter("restore_outdated_map", rclcpp::ParameterValue(false)); + declareParameter("restore_cleared_footprint", rclcpp::ParameterValue(true)); auto node = node_.lock(); if (!node) { @@ -148,7 +148,7 @@ StaticLayer::getParameters() node->get_parameter(name_ + "." + "enabled", enabled_); node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_); node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_); - node->get_parameter(name_ + "." + "restore_outdated_map", restore_outdated_map_); + node->get_parameter(name_ + "." + "restore_cleared_footprint", restore_cleared_footprint_); node->get_parameter(name_ + "." + "map_topic", map_topic_); map_topic_ = joinWithParentNamespace(map_topic_); node->get_parameter( @@ -414,6 +414,7 @@ StaticLayer::updateCosts( } std::vector> map_region_to_restore; + map_region_to_restore.reserve(100); if (footprint_clearing_enabled_) { getMapRegionOccupiedByPolygon(transformed_footprint_, map_region_to_restore); setMapRegionOccupiedByPolygon(map_region_to_restore, nav2_costmap_2d::FREE_SPACE); @@ -463,7 +464,7 @@ StaticLayer::updateCosts( } } - if (restore_outdated_map_) { + if (footprint_clearing_enabled_ && restore_cleared_footprint_) { // restore the map region occupied by the polygon using cached data restoreMapRegionOccupiedByPolygon(map_region_to_restore); } @@ -507,8 +508,17 @@ StaticLayer::dynamicParametersCallback( current_ = false; } else if (param_name == name_ + "." + "footprint_clearing_enabled") { footprint_clearing_enabled_ = parameter.as_bool(); - } else if (param_name == name_ + "." + "restore_outdated_map") { - restore_outdated_map_ = parameter.as_bool(); + if (!footprint_clearing_enabled_) { + RCLCPP_INFO(logger_, "The parameter restore_cleared_footprint will be ignored " + "because footprint_clearing_enabled is False"); + } + } else if (param_name == name_ + "." + "restore_cleared_footprint") { + if (footprint_clearing_enabled_) { + restore_cleared_footprint_ = parameter.as_bool(); + } else { + RCLCPP_WARN(logger_, "restore_cleared_footprint cannot be used " + "when footprint_clearing_enabled is False. Rejecting parameter update."); + } } } } diff --git a/nav2_costmap_2d/src/costmap_2d.cpp b/nav2_costmap_2d/src/costmap_2d.cpp index cf8f8f607e7..06ab7ed9d37 100644 --- a/nav2_costmap_2d/src/costmap_2d.cpp +++ b/nav2_costmap_2d/src/costmap_2d.cpp @@ -401,7 +401,7 @@ bool Costmap2D::setConvexPolygonCost( unsigned char cost_value) { std::vector> polygon_map_region; - if (getMapRegionOccupiedByPolygon(polygon, polygon_map_region)) { + if (!getMapRegionOccupiedByPolygon(polygon, polygon_map_region)) { return false; } @@ -445,6 +445,7 @@ bool Costmap2D::getMapRegionOccupiedByPolygon( // get the cells that fill the polygon std::vector polygon_cells; + polygon_cells.reserve(100); convexFillCells(map_polygon, polygon_cells); // store the cost informations of the cells From 04d3c38d876c4e7cf55c1781c704e30328dd001b Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Tue, 4 Feb 2025 03:35:19 +0300 Subject: [PATCH 15/18] Remove unnecessary log Signed-off-by: CihatAltiparmak --- nav2_costmap_2d/plugins/static_layer.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index fc782fb00b0..24492327ebc 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -508,10 +508,6 @@ StaticLayer::dynamicParametersCallback( current_ = false; } else if (param_name == name_ + "." + "footprint_clearing_enabled") { footprint_clearing_enabled_ = parameter.as_bool(); - if (!footprint_clearing_enabled_) { - RCLCPP_INFO(logger_, "The parameter restore_cleared_footprint will be ignored " - "because footprint_clearing_enabled is False"); - } } else if (param_name == name_ + "." + "restore_cleared_footprint") { if (footprint_clearing_enabled_) { restore_cleared_footprint_ = parameter.as_bool(); From 981cdd3e5360cd925ce0f2421ce6ef51473c3515 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Tue, 4 Feb 2025 13:52:13 +0300 Subject: [PATCH 16/18] Add new member to MapLocation Signed-off-by: CihatAltiparmak --- .../include/nav2_costmap_2d/costmap_2d.hpp | 8 +++--- nav2_costmap_2d/plugins/static_layer.cpp | 4 +-- nav2_costmap_2d/src/costmap_2d.cpp | 25 ++++++++----------- 3 files changed, 17 insertions(+), 20 deletions(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp index 38171616c7e..414c503ce38 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp @@ -59,6 +59,7 @@ struct MapLocation { unsigned int x; unsigned int y; + unsigned char cost; }; /** @@ -320,7 +321,7 @@ class Costmap2D */ bool getMapRegionOccupiedByPolygon( const std::vector & polygon, - std::vector> & polygon_map_region); + std::vector & polygon_map_region); /** * @brief Sets the given map region to desired value @@ -328,7 +329,7 @@ class Costmap2D * @param new_cost_value The value to set costs to */ void setMapRegionOccupiedByPolygon( - const std::vector> & polygon_map_region, + const std::vector & polygon_map_region, unsigned char new_cost_value); /** @@ -336,7 +337,7 @@ class Costmap2D * @param polygon_map_region The map region to perform the operation on */ void restoreMapRegionOccupiedByPolygon( - const std::vector> & polygon_map_region); + const std::vector & polygon_map_region); /** * @brief Get the map cells that make up the outline of a polygon @@ -595,6 +596,7 @@ class Costmap2D { MapLocation loc; costmap_.indexToCells(offset, loc.x, loc.y); + loc.cost = costmap_.getCost(loc.x, loc.y); cells_.push_back(loc); } diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 24492327ebc..9f0a69f80ed 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -413,9 +413,9 @@ StaticLayer::updateCosts( return; } - std::vector> map_region_to_restore; - map_region_to_restore.reserve(100); + std::vector map_region_to_restore; if (footprint_clearing_enabled_) { + map_region_to_restore.reserve(100); getMapRegionOccupiedByPolygon(transformed_footprint_, map_region_to_restore); setMapRegionOccupiedByPolygon(map_region_to_restore, nav2_costmap_2d::FREE_SPACE); } diff --git a/nav2_costmap_2d/src/costmap_2d.cpp b/nav2_costmap_2d/src/costmap_2d.cpp index 06ab7ed9d37..1d9997de8da 100644 --- a/nav2_costmap_2d/src/costmap_2d.cpp +++ b/nav2_costmap_2d/src/costmap_2d.cpp @@ -400,7 +400,8 @@ bool Costmap2D::setConvexPolygonCost( const std::vector & polygon, unsigned char cost_value) { - std::vector> polygon_map_region; + std::vector polygon_map_region; + polygon_map_region.reserve(100); if (!getMapRegionOccupiedByPolygon(polygon, polygon_map_region)) { return false; } @@ -411,25 +412,25 @@ bool Costmap2D::setConvexPolygonCost( } void Costmap2D::setMapRegionOccupiedByPolygon( - const std::vector> & polygon_map_region, + const std::vector & polygon_map_region, unsigned char new_cost_value) { - for (const auto & [cell, _] : polygon_map_region) { + for (const auto & cell : polygon_map_region) { setCost(cell.x, cell.y, new_cost_value); } } void Costmap2D::restoreMapRegionOccupiedByPolygon( - const std::vector> & polygon_map_region) + const std::vector & polygon_map_region) { - for (const auto & [cell, cost_value] : polygon_map_region) { - setCost(cell.x, cell.y, cost_value); + for (const auto & cell : polygon_map_region) { + setCost(cell.x, cell.y, cell.cost); } } bool Costmap2D::getMapRegionOccupiedByPolygon( const std::vector & polygon, - std::vector> & polygon_map_region) + std::vector & polygon_map_region) { // we assume the polygon is given in the global_frame... // we need to transform it to map coordinates @@ -444,14 +445,7 @@ bool Costmap2D::getMapRegionOccupiedByPolygon( } // get the cells that fill the polygon - std::vector polygon_cells; - polygon_cells.reserve(100); - convexFillCells(map_polygon, polygon_cells); - - // store the cost informations of the cells - for (const auto & cell : polygon_cells) { - polygon_map_region.push_back({cell, getCost(cell.x, cell.y)}); - } + convexFillCells(map_polygon, polygon_map_region); return true; } @@ -537,6 +531,7 @@ void Costmap2D::convexFillCells( for (unsigned int y = min_pt.y; y <= max_pt.y; ++y) { pt.x = x; pt.y = y; + pt.cost = getCost(x, y); polygon_cells.push_back(pt); } } From 49916bed808b6614b63a9a37975880c668e75548 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Tue, 4 Feb 2025 14:46:29 +0300 Subject: [PATCH 17/18] Remove unnecessary header Signed-off-by: CihatAltiparmak --- nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp index 414c503ce38..b30179977d5 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp @@ -47,7 +47,6 @@ #include #include #include -#include #include "geometry_msgs/msg/point.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" From 1afd7b4997ffc11fe0e603c8c05f755a5d423e88 Mon Sep 17 00:00:00 2001 From: CihatAltiparmak Date: Tue, 4 Feb 2025 21:29:53 +0300 Subject: [PATCH 18/18] Set the parameters footprint_clearing_enabled and restore_cleared_footprint enable in nav2_system_tests Signed-off-by: CihatAltiparmak --- nav2_system_tests/src/system/nav2_system_params.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/nav2_system_tests/src/system/nav2_system_params.yaml b/nav2_system_tests/src/system/nav2_system_params.yaml index 5ee29e6536e..756f0958f9f 100644 --- a/nav2_system_tests/src/system/nav2_system_params.yaml +++ b/nav2_system_tests/src/system/nav2_system_params.yaml @@ -196,6 +196,8 @@ global_costmap: static_layer: plugin: "nav2_costmap_2d::StaticLayer" map_subscribe_transient_local: True + footprint_clearing_enabled: True + restore_cleared_footprint: True inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 3.0