From a3e95fc159b1e2fd66b413b5f5c7ff3691ce7819 Mon Sep 17 00:00:00 2001 From: ymd-stella Date: Thu, 13 Aug 2020 15:35:24 +0900 Subject: [PATCH 1/6] Add nav2_bt_waypoint_follower Signed-off-by: ymd-stella --- doc/parameters/param_list.md | 6 +- .../bringup/launch/navigation_launch.py | 19 +- nav2_bringup/bringup/params/nav2_params.yaml | 28 ++ nav2_bt_waypoint_follower/CMakeLists.txt | 106 +++++++ nav2_bt_waypoint_follower/README.md | 71 +++++ .../behavior_trees/follow_waypoints.xml | 18 ++ .../follow_waypoints_with_skip.xml | 20 ++ .../follow_waypoints_with_wait.xml | 21 ++ .../doc/follow_waypoints.png | Bin 0 -> 47971 bytes .../doc/follow_waypoints_with_skip.png | Bin 0 -> 47444 bytes .../doc/follow_waypoints_with_wait.png | Bin 0 -> 60033 bytes nav2_bt_waypoint_follower/doc/legend.png | Bin 0 -> 7911 bytes .../bt_waypoint_follower.hpp | 135 +++++++++ .../plugins/action/get_next_goal_action.hpp | 50 +++ .../all_goals_achieved_condition.hpp | 44 +++ nav2_bt_waypoint_follower/package.xml | 31 ++ .../plugins/action/get_next_goal_action.cpp | 64 ++++ .../all_goals_achieved_condition.cpp | 54 ++++ .../src/bt_waypoint_follower.cpp | 286 ++++++++++++++++++ nav2_bt_waypoint_follower/src/main.cpp | 28 ++ nav2_bt_waypoint_follower/test/CMakeLists.txt | 4 + .../integration_test_follow_waypoints.xml | 18 ++ .../unit_test_follow_waypoints.xml | 11 + .../unit_test_follow_waypoints_failure.xml | 11 + .../unit_test_follow_waypoints_running.xml | 13 + .../test/integration/CMakeLists.txt | 7 + ...t_follow_waypoints_action_with_bt_node.cpp | 84 +++++ .../test/plugins/action/CMakeLists.txt | 9 + .../action/test_get_next_goal_action.cpp | 171 +++++++++++ .../test/plugins/condition/CMakeLists.txt | 9 + .../test_all_goals_achieved_condition.cpp | 155 ++++++++++ .../test/unit/CMakeLists.txt | 4 + .../unit/test_follow_waypoints_action.cpp | 243 +++++++++++++++ .../src/waypoint_follower/tester.py | 6 +- navigation2/package.xml | 2 +- 35 files changed, 1716 insertions(+), 12 deletions(-) create mode 100644 nav2_bt_waypoint_follower/CMakeLists.txt create mode 100644 nav2_bt_waypoint_follower/README.md create mode 100644 nav2_bt_waypoint_follower/behavior_trees/follow_waypoints.xml create mode 100644 nav2_bt_waypoint_follower/behavior_trees/follow_waypoints_with_skip.xml create mode 100644 nav2_bt_waypoint_follower/behavior_trees/follow_waypoints_with_wait.xml create mode 100644 nav2_bt_waypoint_follower/doc/follow_waypoints.png create mode 100644 nav2_bt_waypoint_follower/doc/follow_waypoints_with_skip.png create mode 100644 nav2_bt_waypoint_follower/doc/follow_waypoints_with_wait.png create mode 100644 nav2_bt_waypoint_follower/doc/legend.png create mode 100644 nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/bt_waypoint_follower.hpp create mode 100644 nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp create mode 100644 nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp create mode 100644 nav2_bt_waypoint_follower/package.xml create mode 100644 nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.cpp create mode 100644 nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.cpp create mode 100644 nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp create mode 100644 nav2_bt_waypoint_follower/src/main.cpp create mode 100644 nav2_bt_waypoint_follower/test/CMakeLists.txt create mode 100644 nav2_bt_waypoint_follower/test/behavior_trees/integration_test_follow_waypoints.xml create mode 100644 nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints.xml create mode 100644 nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints_failure.xml create mode 100644 nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints_running.xml create mode 100644 nav2_bt_waypoint_follower/test/integration/CMakeLists.txt create mode 100644 nav2_bt_waypoint_follower/test/integration/test_follow_waypoints_action_with_bt_node.cpp create mode 100644 nav2_bt_waypoint_follower/test/plugins/action/CMakeLists.txt create mode 100644 nav2_bt_waypoint_follower/test/plugins/action/test_get_next_goal_action.cpp create mode 100644 nav2_bt_waypoint_follower/test/plugins/condition/CMakeLists.txt create mode 100644 nav2_bt_waypoint_follower/test/plugins/condition/test_all_goals_achieved_condition.cpp create mode 100644 nav2_bt_waypoint_follower/test/unit/CMakeLists.txt create mode 100644 nav2_bt_waypoint_follower/test/unit/test_follow_waypoints_action.cpp diff --git a/doc/parameters/param_list.md b/doc/parameters/param_list.md index f4a7089790c..1597d36d48c 100644 --- a/doc/parameters/param_list.md +++ b/doc/parameters/param_list.md @@ -474,12 +474,12 @@ When `planner_plugins` parameter is not overridden, the following default plugin | ``.use_astar | false | Whether to use A*, if false, uses Dijstra's expansion | | ``.allow_unknown | true | Whether to allow planning in unknown space | -# waypoint_follower +# bt_waypoint_follower | Parameter | Default | Description | | ----------| --------| ------------| -| stop_on_failure | true | Whether to fail action task if a single waypoint fails. If false, will continue to next waypoint. | -| loop_rate | 20 | Rate to check for results from current navigation task | +| bt_xml_filename | N/A | path to the behavior tree XML description | +| plugin_lib_names | [ "nav2_compute_path_to_pose_action_bt_node", "nav2_follow_path_action_bt_node", "nav2_back_up_action_bt_node", "nav2_spin_action_bt_node", "nav2_wait_action_bt_node", "nav2_clear_costmap_service_bt_node", "nav2_is_stuck_condition_bt_node", "nav2_goal_reached_condition_bt_node", "nav2_initial_pose_received_condition_bt_node", "nav2_goal_updated_condition_bt_node", "nav2_reinitialize_global_localization_service_bt_node", "nav2_rate_controller_bt_node", "nav2_distance_controller_bt_node", "nav2_recovery_node_bt_node", "nav2_pipeline_sequence_bt_node", "nav2_round_robin_node_bt_node", "nav2_transform_available_condition_bt_node", "nav2_time_expired_condition_bt_node", "nav2_distance_traveled_condition_bt_node", "nav2_navigate_to_pose_action_bt_node", "nav2_all_goals_achieved_condition_bt_node", "nav2_get_next_goal_action_bt_node"] | list of behavior tree node shared libraries | # recoveries diff --git a/nav2_bringup/bringup/launch/navigation_launch.py b/nav2_bringup/bringup/launch/navigation_launch.py index c421d709731..27c40ce996c 100644 --- a/nav2_bringup/bringup/launch/navigation_launch.py +++ b/nav2_bringup/bringup/launch/navigation_launch.py @@ -32,13 +32,14 @@ def generate_launch_description(): autostart = LaunchConfiguration('autostart') params_file = LaunchConfiguration('params_file') default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename') + waypoint_follower_bt_xml_filename = LaunchConfiguration('waypoint_follower_bt_xml_filename') map_subscribe_transient_local = LaunchConfiguration('map_subscribe_transient_local') lifecycle_nodes = ['controller_server', 'planner_server', 'recoveries_server', 'bt_navigator', - 'waypoint_follower'] + 'bt_waypoint_follower'] # Map fully qualified names to relative ones so the node's namespace can be prepended. # In case of the transforms (tf), currently, there doesn't seem to be a better alternative @@ -53,6 +54,7 @@ def generate_launch_description(): param_substitutions = { 'use_sim_time': use_sim_time, 'default_bt_xml_filename': default_bt_xml_filename, + 'bt_xml_filename': waypoint_follower_bt_xml_filename, 'autostart': autostart, 'map_subscribe_transient_local': map_subscribe_transient_local} @@ -88,7 +90,14 @@ def generate_launch_description(): default_value=os.path.join( get_package_share_directory('nav2_bt_navigator'), 'behavior_trees', 'navigate_w_replanning_and_recovery.xml'), - description='Full path to the behavior tree xml file to use'), + description='Full path to the behavior tree xml file to use for bt_navigator'), + + DeclareLaunchArgument( + 'waypoint_follower_bt_xml_filename', + default_value=os.path.join( + get_package_share_directory('nav2_bt_waypoint_follower'), + 'behavior_trees', 'follow_waypoints.xml'), + description='Full path to the behavior tree xml file to use for bt_waypoint_follower'), DeclareLaunchArgument( 'map_subscribe_transient_local', default_value='false', @@ -126,9 +135,9 @@ def generate_launch_description(): remappings=remappings), Node( - package='nav2_waypoint_follower', - executable='waypoint_follower', - name='waypoint_follower', + package='nav2_bt_waypoint_follower', + executable='bt_waypoint_follower', + name='bt_waypoint_follower', output='screen', parameters=[configured_params], remappings=remappings), diff --git a/nav2_bringup/bringup/params/nav2_params.yaml b/nav2_bringup/bringup/params/nav2_params.yaml index 784eea19b38..5c673100d24 100644 --- a/nav2_bringup/bringup/params/nav2_params.yaml +++ b/nav2_bringup/bringup/params/nav2_params.yaml @@ -280,3 +280,31 @@ recoveries_server: robot_state_publisher: ros__parameters: use_sim_time: True + +bt_waypoint_follower: + ros__parameters: + use_sim_time: True + bt_xml_filename: "follow_waypoints.xml" + plugin_lib_names: + - nav2_compute_path_to_pose_action_bt_node + - nav2_follow_path_action_bt_node + - nav2_back_up_action_bt_node + - nav2_spin_action_bt_node + - nav2_wait_action_bt_node + - nav2_clear_costmap_service_bt_node + - nav2_is_stuck_condition_bt_node + - nav2_goal_reached_condition_bt_node + - nav2_initial_pose_received_condition_bt_node + - nav2_goal_updated_condition_bt_node + - nav2_reinitialize_global_localization_service_bt_node + - nav2_rate_controller_bt_node + - nav2_distance_controller_bt_node + - nav2_recovery_node_bt_node + - nav2_pipeline_sequence_bt_node + - nav2_round_robin_node_bt_node + - nav2_transform_available_condition_bt_node + - nav2_time_expired_condition_bt_node + - nav2_distance_traveled_condition_bt_node + - nav2_navigate_to_pose_action_bt_node + - nav2_all_goals_achieved_condition_bt_node + - nav2_get_next_goal_action_bt_node diff --git a/nav2_bt_waypoint_follower/CMakeLists.txt b/nav2_bt_waypoint_follower/CMakeLists.txt new file mode 100644 index 00000000000..bc4914bc9d8 --- /dev/null +++ b/nav2_bt_waypoint_follower/CMakeLists.txt @@ -0,0 +1,106 @@ +cmake_minimum_required(VERSION 3.5) +project(nav2_bt_waypoint_follower) + +find_package(ament_cmake REQUIRED) +find_package(nav2_common REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) +find_package(std_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(nav2_behavior_tree REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(nav2_msgs REQUIRED) +find_package(behaviortree_cpp_v3 REQUIRED) +find_package(std_srvs REQUIRED) +find_package(nav2_util REQUIRED) +find_package(tf2_ros REQUIRED) + +nav2_package() + +include_directories( + include +) + +set(executable_name bt_waypoint_follower) + +add_executable(${executable_name} + src/main.cpp +) + +set(library_name ${executable_name}_core) + +add_library(${library_name} SHARED + src/bt_waypoint_follower.cpp +) + +set(dependencies + rclcpp + rclcpp_action + rclcpp_lifecycle + std_msgs + geometry_msgs + nav2_behavior_tree + nav_msgs + nav2_msgs + behaviortree_cpp_v3 + std_srvs + nav2_util + tf2_ros +) + +add_library(nav2_all_goals_achieved_condition_bt_node SHARED plugins/condition/all_goals_achieved_condition.cpp) +list(APPEND plugin_libs nav2_all_goals_achieved_condition_bt_node) + +add_library(nav2_get_next_goal_action_bt_node SHARED plugins/action/get_next_goal_action.cpp) +list(APPEND plugin_libs nav2_get_next_goal_action_bt_node) + +foreach(bt_plugin ${plugin_libs}) + ament_target_dependencies(${bt_plugin} ${dependencies}) + target_compile_definitions(${bt_plugin} PRIVATE BT_PLUGIN_EXPORT) +endforeach() + +ament_target_dependencies(${executable_name} + ${dependencies} +) + +target_link_libraries(${executable_name} ${library_name}) + +ament_target_dependencies(${library_name} + ${dependencies} +) + +install(TARGETS ${library_name} + ${plugin_libs} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install(TARGETS ${executable_name} + RUNTIME DESTINATION lib/${PROJECT_NAME} +) + +install(DIRECTORY include/ + DESTINATION include/ +) + +install(DIRECTORY behavior_trees DESTINATION share/${PROJECT_NAME}) +install(DIRECTORY test/behavior_trees DESTINATION share/${PROJECT_NAME}/test) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + + find_package(ament_cmake_pytest REQUIRED) + find_package(ament_cmake_gtest REQUIRED) + add_subdirectory(test) +endif() + +ament_export_include_directories(include) + +ament_export_libraries( + ${plugin_libs} +) + +ament_package() diff --git a/nav2_bt_waypoint_follower/README.md b/nav2_bt_waypoint_follower/README.md new file mode 100644 index 00000000000..34505eeaaa8 --- /dev/null +++ b/nav2_bt_waypoint_follower/README.md @@ -0,0 +1,71 @@ +# Nav2 BT Waypoint Follower + +The Nav2 BT(Behavior Tree) Waypoint Follower module implements the [FollowWaypoints action](../nav2_msgs/action/FollowWaypoints.action). It is a [Behavior Tree](https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/docs/BT_basics.md)-based implementation of waypoint following that is intended to allow for flexibility in the navigation task and provide a way to easily specify complex robot behaviors. + +## Overview + +The BT Waypoint Follower receives goal poses and navigates the robot to the specified destination. To do so, the module reads an XML description of the Behavior Tree from a file, as specified by a Node parameter, and passes that to a generic [BehaviorTreeEngine class](../nav2_behavior_tree/include/nav2_behavior_tree/behavior_tree_engine.hpp) which uses the [Behavior-Tree.CPP library](https://github.com/BehaviorTree/BehaviorTree.CPP) to dynamically create and execute the BT. + +## Specifying an input XML file + +The BT Waypoint Follower node has a parameter, *bt_xml_filename*, that can be specified using a ROS2 parameters YAML file, like this: + +``` +bt_waypoint_follower: + ros__parameters: + bt_xml_filename: +``` + +Using the XML filename as a parameter makes it easy to change or extend the logic used for navigation. Once can simply update the XML description for the BT and the BT Waypoint follower task server will use the new description. + +## Behavior Tree nodes + +A Behavior Tree consists of control flow nodes, such as fallback, sequence, parallel, and decorator, as well as two execution nodes: condition and action nodes. Execution nodes are the leaf nodes of the tree. When a leaf node is ticked, the node does some work and it returns either SUCCESS, FAILURE or RUNNING. The current Navigation2 software implements a few custom nodes, including Conditions and Actions. The user can also define and register additional node types that can then be used in BTs and the corresponding XML descriptions. + +## FollowWaypoints Behavior Trees + +The BT Waypoint Follower package has three sample XML-based descriptions of BTs. +These trees are [follow_waypoints.xml](behavior_trees/follow_waypoints.xml), [follow_waypoints_with_skip.xml](behavior_trees/follow_waypoints_with_skip.xml) and [follow_waypoints_with_wait.xml](behavior_trees/follow_waypoints_with_wait.xml). +The user may use any of these sample trees or develop a more complex tree which could better suit the user's needs. + +### FollowWaypoints + +This BT fails if NavigateToPose fails. + +![Navigation with time based replanning](./doc/follow_waypoints.png) + +### FollowWaypoints with skipping + +It will go to the next waypoint if NavigateToPose fails. + +![Navigation with distance based replanning](./doc/follow_waypoints_with_skip.png) + +### FollowWaypoints with simple recovery action + +With the recovery node, simple recoverable navigation with replanning can be implemented by utilizing the [follow_waypoints_with_wait.xml](behavior_trees/follow_waypoints_with_wait.xml) and a recovery action `wait`. A graphical version of this simple recoverable Behavior Tree is depicted in the figure below. + +

+ +

+
+ +#### FollowWaypoints is composed of the following custom condition, control and action nodes: + +#### Control Nodes +* Recovery: This is a control flow type node with two children. It returns success if and only if the first child returns success. The second child will be executed only if the first child returns failure. The second child is responsible for recovery actions such as re-initializing system or other recovery behaviors. If the recovery behaviors are succeeded, then the first child will be executed again. The user can specify how many times the recovery actions should be taken before returning failure. The figure below depicts a simple recovery node. + +

+ +

+
+ +#### Condition Nodes +* AllGoalsAchieved: If the last goal has been achieved, it return SUCCESS. + +#### Action Nodes +* GetNextGoal: If the current goal has been achieved, set the next goal. + +## Legend +Legend for the behavior tree diagrams: + +![Legend](./doc/legend.png) diff --git a/nav2_bt_waypoint_follower/behavior_trees/follow_waypoints.xml b/nav2_bt_waypoint_follower/behavior_trees/follow_waypoints.xml new file mode 100644 index 00000000000..41463bec22e --- /dev/null +++ b/nav2_bt_waypoint_follower/behavior_trees/follow_waypoints.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + diff --git a/nav2_bt_waypoint_follower/behavior_trees/follow_waypoints_with_skip.xml b/nav2_bt_waypoint_follower/behavior_trees/follow_waypoints_with_skip.xml new file mode 100644 index 00000000000..99206a62a0e --- /dev/null +++ b/nav2_bt_waypoint_follower/behavior_trees/follow_waypoints_with_skip.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + diff --git a/nav2_bt_waypoint_follower/behavior_trees/follow_waypoints_with_wait.xml b/nav2_bt_waypoint_follower/behavior_trees/follow_waypoints_with_wait.xml new file mode 100644 index 00000000000..0bd4b40f5fa --- /dev/null +++ b/nav2_bt_waypoint_follower/behavior_trees/follow_waypoints_with_wait.xml @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + diff --git a/nav2_bt_waypoint_follower/doc/follow_waypoints.png b/nav2_bt_waypoint_follower/doc/follow_waypoints.png new file mode 100644 index 0000000000000000000000000000000000000000..12269b095c15c8d2f5954e08966c9a4cc0c18806 GIT binary patch literal 47971 zcmd43WmJ~!w>|m*0@4lADJ|WS5+WheNGgaRAR!XcC>;VK0*WFC(y4Sx3n(GoAt8-) zpLM%`d;iaubH1E0&e*)~J6;AnJkNb!_qyhqYp%Jj@H@9}65!I{qEIM;TdGPrC=>=c z3WauY84G^$GxgmO{13}g{iYJ?0{Q1-T~<5_#e}-0q@d@SvNq{qq-S`Hy|szLV9_VW zY?)FR_^4FEQo>e##a=JH#bRK&jZ{}duuZhOFDW{&rtQ_BC_7D`QZ##C%M>2BQ8CJZ z_)))i^3j<~N?SKd_;s3(T#qnO^Ly7#-%V=EpWa$kq*bPT*d)kT97(qZJ?h`LgQgms zVaQj9?f-m3`I#^vOwIlL^qJDloA0FXb5Zl{G2(8Qm6VhyZa3W;RT>5=>Q z%hRPdVPSTxgwI%V(b`_p<5ijdG$ioF#KwMitOakJ-7k>F#DaW%68!)7n_O!lVPWPt zRT1;0o>YFf1|r!*d8<_Gt~dG$U&pH5*K;ZSZ}IE4-h%r=C&NuQZW|h+d{RZ1mX_A} z*urO9Is8Q0dmo=x%mIbc_#jOUzlx;1CUiKFoSbYsUVbfvh|zJYe#L!rilEB0(C0^r zBpJ$iYepe@os3w0sox!(8WYiGvi&z5J$dxwkfoQTQE z^$K@JM@MI;>bw`ERE&&_lDjr0s=k;m!8)h^wIagQzIFgFOurS+KGNVXS7^~txOX&G zW-s`3`Oa6z$+1g)@NwFj?Lp78-+U=8ZNg^sK~?p9H@?ny&YyiO+O(b#-&}Kipzw*GNL$ym?dN z`gN7??DsBol5M@R21vAS7z!XWkZa#6#%6#T&X zWdAV)sa0DPwNddsG)g|xY+iA@0nUzvC$+~bc{C?f)3W~OKHaHuj9MS06`Y*~UeaF= z2`A&A@qOGHBj>uP(fvV&wy&?R(s>rW`^OJ7lvb*2a8VJz`}$b0Q^OhM_wU~&T;?vl zijSXNTFNRReZy=W9u~GD#ZIo|7Eo3uO37=4O4bPRKb>bp1+1+(?=HSy*ycD?7=w>F?XyM;`4g&41~UZC*9S2Zyia3kwU(*RE+U9Sth0s5G^< zW_DZ4NK1E8UxT3d(awOIF7@DNilno%b0a*#-b{6>r<+rC1HLLzR|5I#57B>RY28#( zy7WMZ`u7t_gCcVRd1>$TYKZLTpFXkj^77ufbLZo>v-I9@02&59w>oTjfV&lPY;0^^ zz)nI!LTfKlcWrHwpC4rK3=Ivt-(RQVMx0@_@rv51|8M2mE{)uAM@$215sz+$m+a9GW^MH^K=<*GkFwufDP#T2kL z`)53vcA1#_n$gini500xLkXyM6%g1?v#1IX`y@X~i^H3op(# z{iUqBIy&yW>2ve(z4$8Qy{}P!?;HBFJcEMYIyrh9b8{?=(w@bqTeHmz+$L`U73u^L z)Ot!@AMdLHA48S2{Pm;n%^4K*blZv|$E9q6- zVk5nTjco-0_n9ylxycsE|7G{~ziq9l*L0~?PfK=DIZ zwwfm7XVUPD79mPX%FDR8xo-oI>}v|yS3BW}hev2?Dr0x|?!}I-o?cLiRlC7`J>gvcJK76=5T*UZRrZJEvPl`*GjkI=u%$_|g0)8F!E$Dfe28)0Iu~4#x)w|$eO!H?86cUn> z$(-B}JwoJUxGX~9+MiUu_4n&onE>dZV_;~K!$*=(zrevHNe+sRCQx}vhm)h1JMqxk zI{1EbNV35H`P1a@@f@E%enbU$3he_P+_$o_n#)Emix@7e zKN}g~qLNaGAJr)UxzA)WiB_;N&ai||B7%#7B(&PNkjhcR`XDI=0nEo~t zxo^6EPxNgheE)ATqW|ZcJZTdB;@_MzohoOk?@Z7L8RXv?qCyw-sSGuBjb$i@FI*e@ z%Xgn7Hel*7gdJ#lqtTlSJ9_Kq5(*NNko;+eg!o*t3=OLQz3CjAZ3_LA5>@Uv_vN_* z(>aZ^H<9zg^^ZL_8vB2K-KLq_rkr)4`z6%VR06gM zRN-TcHR-5n^MqVQd|23H=MFOMtG8m%x_MFW+HxQF9|wdo-W$He*+~{XyYjoueP#=r zWxMYxD`jyu#|K(%{eCNyaLz*+yO!OSEfx1;vh82>w~opUGgpW)An5qk(wK5D9Z}1h zOU?A+$1bamyFJb$guk)3i91}L6Ro$K*B-KRJ#!nXZSbVN5w|v4{l@8k?o>zfov4zi ziC5I&qpW$y(tK1$1l4BVFS>{(Q>GK@dlu0l1Dq?`!)8bJ(-=frS3D-7t~CDCynajY z>HoY%6Qo+Tj}DhtZByFKu_FGWCB6(Oi(ji6)=D;uRwUu8e3%L(${BqH5Lsz zdQcyNP&nd&YfAEbRM8t^Mav(?WA}~d#1~}mBoP=%Mug95o`n5fiT9f?LJKVlKZvdk zxI+{3 z@0S3T_XOipm3YKd+?G92RCSnqALLIA(Q?XieU$yhk1cD?F^K)m_G%P$XIiVq+Btxq zIKYPB4lLZ>fb~2jV44$eEV()(s^FT6-5!vw7;uwlrd85%MEg{9W{6+@Hg2z|s{a1U z!)<{|!cS<|4VkXvR8r%co)IqZ#4RdqhH?aC%LTB@piPg;%V0AJ6IO1=CvB}=cnJPE zn8jiG>+x}XJV4j}$4G5kWZOxre-6!o<7B`wL7@5t+C+`LxfZKa7s+_$wGLIy(X*)qSba~-s{Z1U-%xvDcQq7%Cjcl3}C8{eIdt{-`Of+6`` ze#b9h6>rQ)^m)eh=`W1I= z*+L?#E*b0x)L!n;#PagZHXiL5BCr)iRc?Q>JrvtWmva2Q8Ssv%*X8R<<-TU%L*JGq z8bNiGx5wo0>$FeW_S59W#ptg#AHBKOO~!NA%}+5wV0 zvMU#C(4Reet9S?ZiPHS`cjcKs`hpIslXZ$HHu+Tr+kH?$s&v>+Ql+t$xq(iMU_W))tgyjiLB=N66Qo#Zk%fL6&H1Hwsqgg zcXxYMcSUH}s(u-V86aB}5(R~ZB(q6@;I%TWv1rs>b3kRDrL?aM_V!)J+$-@!D4T|U zf73{>IU94StwWJmPZN!ZNaZ^EywugC*1NuZ`XHPu{&EsPw%$aB&~2 zK>0?T50UL0+eS*35}FKEcIOqZ=!hM(>LsnOKDYMj^Y_wXx0QBj$hCCT#vF$)6@Tq} z$;wX zmmbJs(tPbd@6L%nOeV#wbjNf&!}okie4djCLa(*FZXBt>B5<=?@-RqAR;@IsqTTu%3-GJLkNM7d|P z7^CAhu^dH@L>M0CZGI{qaijzgLY3~CN_5{3S_BxD+~r@qd20=q8eGao4j0-c z7%5j-_wpoAcVdJSK(2N=%!9hJrnzyN-9Nkce*r_q)t?#had>AH@8(v@#PEAh#7^`6|*9kL(Lk0Es}>DS$!m9Z{}ac>T!y)JU_c#bDT zD4~3^`$ji*)k&UbNQf!Bmyq#cB(p^TH~#VGkW@U>T7; zDjS8TWbm}2n}VL(mE{8B+g(REZw6kd^gkLA*9TCEeE0wQ&0&;&x=^Pk#%+FK2gd2q z0IRP4F0Pi~@FmLZ)l;nAO4skH`kCDlGpBNH{zEPzGqYL8XG4xN->+`hyE64wMy`Cx zyTJS~sed+=&)@6!ptT(-F%y8wXj2cmqOc139Y;L;X>EIrzvSl=OB|QXE;+Aro43mj z`sF^om8yT$#88`PxE`C-G2$^PPVXl085RB8eAuK;d45`#hc!5TrqFd5!&;gyHphCB zvTyws+7^#{Y9ig7zC$Z|;sxvv|J%g^Nu0K6tsYLWDId+RjY<8~EICS|Ze7)CjE=|_ z#T9Z=r|_%?!@F%BZMuWaxMWV@*q6ivKH8`y&dFH%ZH7O136!~dmJag&y@$*jbF@Me zIiFqraC)(mlQxUWX=qFikx- zBr|;+z;2u+3P_jMy{U7QAr_$MI=I=x(sGACxW)Nnl^m)pgH_?$pN`w4MImKOX|YKd zW}i{~XBf*;1&arj@U*C(UyQTnJ_xRAod0FXsp0-A>4K?%Xhf7mG03#WV7+QrGj~G( z*LKVV-$JSmzeAlWKI7dUMQUEpq_Z8~(|61vGMTdE;}L%Ye{+7kkIi(Qq(coQ?G+I| z{6{cdWA2&@gFG7@;g8nZ$aHk34el)wy_WZ>Xi4gUUIZ;wZx5(kjdV8962)!X3&VtE zuqrD*|CU;jzzVCo^q?i&w7reOc1+#1(%|kYseliQZw-mOO1^3%ZYhx9#xlHKuj1ud zR6y8tz)cR(16?1RH}3Kmt#iJ9Sk4!mv2NdXG9#0Ar)=ojEiP`dsqoWPv__P4aJ|L&R3nis#IxEeI1X- zOlq}W-gz8Tm#)T%{sv>oAiT{to~l)hN(&f?K7M$G(v3J`KANdLI%R6eHSbtxez|X? zM_E?tc1!k!Im(eb`)hZXg~@Wv{fr_b*fHOX{Jx2HL5!oNP(D(zcTYcRpFut~CcxDK z!&jCvdN2PHNk!8y9{I!^OBS~g111@o%S2eEbAjc}_(kf99Q|@qm`@2v!v~}3EjPY5 zld;6vi=Q4H2%4Je-g4#q{bai$F#(lig3e#d6*5Axh^ECCru6wR*96%sfl$bG=A4XM z*0+4rw@fy2t8foj;X;Y5;7gQY@vfjZ5%b2QtA$yV7%eWVqA26TymC1yoCjAU z4ib*)M4xH1$x`kq^#nbiJMQGZev6GPV0qzDuko&m(O8%Sy~z~@+W%CK`mbuAGA#tI z93215Js`!ox1Mn2;EFVZjPi@aCcBwKmYJUyc(&AD>g1F9GBy~a_2aya( z6MBsYPHXR>s>_A4H5*;BoLq)t(Lmlj1kk@N^{+=6T4)5bN}JH4saQ0cciCW=C4VH= z6JM&2d&GnLS!tG)w|%b63~8QBw0bjbtYPr3x0-ocQ^Wo~!y$HMu+1p9Sf-pgzaKXs zvU}-Nj%v?#sqn<>+Pa9h5yN}Z<_t^za4i2@dG^V7bEn=>S;WQEF}5h}N?eD5!}Yp8gos>c6Z<$Zu(B;?M3az*9$+>3K; z(-@9trq8zFg1Df;k;`VVZ)qNIAPPZa1f_BO|3RFbz*m3M(k|ywUfuZ1E0PPMI!nVM$Ch|K~89zpSp z)pzot!+Iy2i$;K@`s~Phb-1S3okJB=vi9gc-_}-=?J4>kpX(!!L7r99{^Pejfwm(G zqCuYzx7aHzyK-}NHva#S`_4;bu#EM;b z!5I?w9aq^&CwJ^LW=;n1PbooxC9!KElZrJr`S#Rg@B%iwUPsB3Um}UyytmJi307YB z2w(O;mwtin5^6sG46A4Jbk)ldjfp0f!S7gZRkmx(m5Xf(tEoKf!0dAvhb&Ku8Q07C zUOLZh`m$vUp5uiNttsTcj&oi$m4PQTE)wW9TzF^3tlMx3D`aozH<*&Yv*Ysl=Y!%8X{` zz33*tS0Dr3;CZ+Gb30CBV-ezKDAgDW#WLP?)G$?mdvi}TV2&=BX)jjHLi}lnGLu&YLU5!Qei#r~RjFx_Z9`_Q0fVAkXLYFR` zrgZ{$>%Ccd>H5tGDrCIoQXvunBUwJ(h1n6&Tv#GV_9?zUx$UjWs{FP1C>z?Fkad(VRzs}#C zs`7v;mV{>o*p7=Ik9Tv7Nqj1oukTFt(-l0CNce%9sf4?J*i@ zxI}qm)(9UDsVni@JxmtDu$@s+lGLly7%5|~&nGDs(Ap_;=3H#CY9+8cZlV1=RV=G( zMGX=c-6jicaqi=>e27(fj9L%DcxZRg`9=?W#h?F!RUo@e=lMal?7-ToTx*XPK|p;f zO0p-Q1{<`abjOr2)HQ4r;SYif!tk)Lr-Bxx55AM?Vk_v~Wst#Z{}YzlWjd8c-J34A zHFG8Q9j<5X<*$raX`JKy!`hPEFto*1h*6R=G9zv zCie-QkJU+pnO-FqUkdC>JSgf1j(azaFl%i#{QT{?t=*kY{%{Le(IG<7xEuymNCJH}naMOO||L zL9Lx>r+atDra$qO-iTZNiccI)%2X)F_w~0cAOiJs9LzX|az~(L!hNXj9^Pk+k9?V~ zYqysS7)-{E**WQo{NDM}(la6AlJdDuG-ke6<5c4%DNeBZO~LPDR~FyAjW5M>4fv9$ zx74FXPGIN;r276DZ|NG2^4*xhVhkohsydDz#}RBzb+oZhO%m?>wh8kc3^kRkAd5b? zAxWp=l)N!$GCN_8FU-S@`unTZ@1f45%gXV_+g;QKBPCgbj90{Cm;3S+)MF>(-nQpc z9}}*WzCOQHta!BgE2-h8FkWLl7x6RV0HxEqq+80HxKIHrgI$-mm#x0+u(iNB51`Q9>lWVx5L(Gd}18YW3O%MWL~|@#idUFI^%1@O<$kS7(_2o z9{!k)8>p1Ah*{H!->;$Utc9YHTEU!+oz!F$V{)3(6_f3urQ}f5$X`YaJ66B)Evk6; zJ+7YEtkM*VGf5&`%u!2QZEL!`xWp^dsfkz*IKta%S~Nt?<2S;lBFmdaW0(cW>O{ZC zrAO(S4BFg&+_HpJpSfa1SI#Fz*D+0xV^nW|Zp~2lwQIRrwsq5BpTZMX2(WWMp}~B-h?8^CeOeRMvkymRYD@RxUmu zzNM@@m}M@-{%6T1o54M+lCr0yF_}W%7$2HSEV);F2r=VG@@d0n1xgHC-rL_ztHk^8 zG;8i>pW~(2zw*4;#<5q;Nw8ZUY^a!1crf^my(H%0SEeWR==(w%I4&1?{WwJSesz9( z?h>ch)w!ZPb|#EDFS6!VVsWvnyKax+0WFPU_nkfqc1blh z(couuHfvW)yb>%A^_7RR_#$>5Tn%eTh*wwckEP}?z~D$vF2l>!kQQoyEzf8^j`GI@;v3|T?sDD*vy0ZZJmw3Tkss3h zB1KYp(891ztMuiU#9L}(THdiZ*7cSC|-q@Y^dybcr2Hc3z$YZN`}cV4e=y-gZ8 zKg5q^V11=+BEH>CkR?{VTEgZ#9^Gog>Oou23hcp7gEQMeSR{?9|0--+!l1$<-iV;4 zrEBX8w)V9DN9g+Fd=cg;rs|km*=*tS-4Li6sRY-%Fx8lj=~mrb6C$h?(cbN9YPB&QBg*-j-79u40E# zA$&RsVv`ET;Jm!NoMu>t+@~pu3VO{B0Vwz#;s@zqsz=f!Sn zB^8x)u)-XIT}Oi+d|29hUkmT; zy@QydnnQ`&YoG1JCMMdf6ayRQCII1a5Jkmj+6WgK`~H3OX2S)8VhFyVo2nib*rA~B zEj%+j8%TfMy>Wbee1I7iTwemRvc8qFva(U>1DxaCKQDg1zs@Qxo$_6YK*(`IA}A!J z>DxCn8L!<&Fc4|blfp#?BQ7t|y~Ay*OITPeY-~Y1*n`e1WaT%(5`#EGz;Y$#W&{-g z1tdFd(cLcohI{bN&aSS_T5@MW@B#0n*m6ZmRHC3vJ-n z7*xG|n{e^RyHIGFTY{$xEK2uZ2Qqgw?+WCcEQQ zZ8*5BSort|--$c5b;Pl1(v#|^KOQfib@D%<9jkDPf!qIRR^$E|A%Y#8z>$Rn!GI=e zKlIW2V8hwPMFHF|@!?YUI$v{D`khIESFEqh-thJaJ5)cQtH$A6Wn;V75=P>Aadxl` z2A5fIrP%gogu~ZH$n z@jY?h-I#<25r;!B=SQdeStC%1&sdAgGXn+KS+ zMZZ2C7eh>EA3l5-srS7;R{q%j-)HPv!sDbEEq_c~?XgJ+o;t8v1%JQvN7TBL+_c_@ z8e(I4sDM`N@z{g^ydGlod;hOrg3tawxP*y$f9&fcFemYDO6cZDJzWmKqvE^w?Kx(W zs68dPGQ0j=*frST+E=SRw^`UV-v;I9^U6{uN4f7VYiqohqF7v9Je&<>>@Bj8(+!0H z$Y?=Y!FRwhk-%e^?lfHw!B5cC)Rd$V+h^|e=PKNPn*DI$6@hywBm$m4NBu#N zT)A=MMlZw%Ttb;%`%8M4*(OY6mBFOdbhteq_v)1;vOBY1&c$-1Kfxs;YHtZA+lIa4 zFi}YYCM5yboS}4*PcG?Z-452{ZY7dC4FK2WTPZex5UUYIg$Hc^iB13)*ja5q-iaq` z+)1F7aAtxvnOR?t4hTT`?DpMEDb`d{(vN^eP*K&;Xn~t_UhZY~IsTJ%xb~&zo};7V zN^v$J7(Wj;YBsmvzozkV+VKjfo2x?wnh5#~q9L217rcH*z)w`VU?8qBfGSw{?_fBB zK*C^VX72d$BRD38$nSLf=D&4!L&2&DaRU;X>o%LUsc1fT>lqzo6DSqUkKw#|HdK|)E11#ZE^lM}1&udZ@(a|=uY_I39)fqx&T4j-rU$+KK3 zRo1sRSDyzWb~eG#To8UqftV+$_|01ea&$=`<8bMIW)c?ug&>4BK|6Sydz5e9oCnKK zV=x}o) z=PYJRd;2_?IgKivnd5PC2Sf0wpBEQ{d9xP{?rJIMF?5z`Of>XX>y8%RRr;Qk|Ll3< z>MH0oC5@Pg5M<@EsE-0mnt@A@(&xTP7c1nR506)iN-SG(k=z4L%+G|8P}E&vC)dk+ zJXuXK?SCNyCcMzvTIuK>$I0qo1{trJlg);91o8oXzqPfsDaDZ{hXBIC19m?8YYo=K zG>H0*?t%QMBTO;9nM2cnuGq-bF`jP)#Tq zA56^6nd*sP$wbLdgr5QC5Yy2`y}%}#1Gj3cO{y;zpdZ;yb-lW^$r>ue*$MtvNI--D z0Gx6r^*)l6*NiU-3k!qm6$^?>_9!SJaxq{Dczll*5{&=%l$mh+qM!M{+=b> z73c7S4T z?gYdEW>W4T=#l|eGc^Zo?SfZ{iJ_1cSI%l-x7hql`L;5cmnXoT{`Px!H$J29F5*6o zjEcf(WoICDt5Rn`U4cTf2XB$&^%-lm^j4rL_xO0O%oVvNecGF#=%U&cVkQmz5R# z?g+ChTwb>IeD;i4SXg({-$W;e9NBvSL13THmAHX?_&%&c?Ax~yjg9hkJ1lIZIN+*9 zp?9iyB^9_#G)*WykArE5l!)8i$9eit6@hun6hGAaIkpHPUIUmwvual71$H68xI; zHFWf@u`vsT8)Qy>5(XemWWbHv#;aVjp0Jd|yC^82A-*=BL+2-;E zn+*1C=xidi+noU-g0Uj~8kdRO>@QT{qe)X+`gPU+^M~&5XZOzRX`}_N!314(7u*V~;2%C_u z5!{N-JBykN0*cB`AAxgDd2h<(8P!O zJw#xz|4bOF22hPdMU|)~>27IhnMs$ZMoCK>iNtG<+(k={ZWeIOtd!Sv;LVm*ewRz& z?d|nJ-p%a_xE=-NxlR#KR;POkC2_Eo_XM|U}hdEwZ?OBaL}Nq(atD&cT4z&)c5NIp&G8C! z!BHq+xE7z+4GT>Xltsb@;TbRr@chdc;S3!v8d19-X2pNVI%;<#%AeBYE7=*gEOQeOU5O`6^)CFlknJ}L$D7O79Or(ZvNqCDWDqA6=fJq zQJZ97WQ=Kzq-q`=rB3zvi<6;~^V7r7jR#4}Av^chK690jlDfejKReqTD%GU|l@ct9v6j_P znJ=JnM`!1aJ9mfyNDM9UA@Jpk%tS!Ma2}wzzgE1R?6q2J&>%1rc-;5P?=H?NG5^;WZl2|PxC`bYU6jWAL zW^hzm?Rz4I3~0bb!ps1{%a<>g`#xb$d97Xpmn~P>?Ci5FJeHa!<61E`(|8&Av zyFpx(^ToMu!QbPM`QWnPLW8f4e>iWp3N(&zX4MU&c8cItcA4S%yZ{kG%!F(ADoy-Rey2r zy*5!rW>)?58?dni97fnt+L~=a=>JAZV5I2jpMK@40=QjN%Y*4T{Nz}(v6gXoLXFeY z7DqH9w#2x2cxb3Bt<*N4R#4>y987r=F)%O`my~F~iH5O(Kfkij!fK9PTwIJwEHS0r z*Dmw$@E}hFss9`u`Jh5ji*~y>KZE_!lz;b2FK{{4OdU@zuer=b^ZwB-(Tpkb;lKUr z{P&?`+uGU+0OEoaaZtE^MD|o(jwCKFJ~A?L4+e_1{{C$m{bIAdHY&W}x3@Zc)7Cb-%>^cKN?-sDArg@Muow@Z z61q%C*ano2f4sGGuaVSP160e0F|_)0A+P=jra2ia3niSv5xe zV2FVCRb+{SN=9|nC!)>A(vk(GEj~3h6&4fI4vUenAm%WF^7r?TR%u{vpR97_K;46s zXl%VYTtpN=Rtkbc_F~?SD<`}xV0ZVaMv{QS(h@Z_wW_MB{3n&@*W)a#tfDmMS05W{ zG`&$}yV~Zm^phTytK#D0Bh4V|a~TGN-n&wfM;j>5OL1}G$X%QYBNHMmElLlptslMS z_ro_U!NS67>gywcEY2=-8rSpY?mNdfFLOA=#W1A znSz6dhgW-XezLW@t0(qm+V{Y0qTbhpHLVx4YnE?eB&-6KEtenI*dWAX_$XP<+ChLl*Sxs}Rpyw~J}2`~iSDyIERHgyVN z$Wp<ojV+8=;pvcL| zxgzdJ2k>3&wrYTkf#Ol}1{4()m6`&nf`#q9bmEM*E;;;OTtqH>YiH-z$obZ+V!_`C zmD=MVw_u?EP;Afs5T9-VK`UV#SPdR6EvK3!*-%;M zePBlrSr8@xvyf|a5m0r~BlsdOA21~pktVuw!P+Nk-jK0QKqJx!Aq&(c5E&8d&s0Yk z0}%BOvc3_Dp@g&VJ*E^?RWDaR{ga;Z3xUN;mo71Zc7zBb#>Osr$^M8eBhf9o%K(a-_(0WMMON;VCVT&CSo^m83UWJ z1=wVNaO22w}@CXsIuprY} zc}{T2dQ;bmqG5t)tCOdQ(@@85qEhhrix;Auz&a2KB@h;9+XyZJB&e7n9bm_Vtw^+# zToV(c{Pyiz<&ylDs}Lv#Wu*-i1_A5N*LLqUP{*M-=;_0EN`#UV6Akr4^sQd&`L6&Vcgl2g@bKW3 zl$5CaNR5b!QhF!$_$eP6;j-W7AL+`Gue%Hl$$edjwI>a1IIPJ?&~mYoLqoCO@R>!x zSTeB1`ho35ai^&kD43n++Xx;!c+mL$JC5(keyfR79Ri&%x^lHVefI_p`=CleHYH4r z7k~Y#1Qm|}FxHXL(LYfZhE@lVWf5sMH8u6gNJM)3jcs#5jt6@ygNG0$XtspoAnRv7 z8L@co{Ey*cXEPGc-}LhAAkU-o%6lr|C!1gTdj2& z8~8S@LR$ca;a@_op8-v^4Uy!5B5}zLQ#5$J5R#OnhE`B3q;fnbC#UE%X*i0Z5%@&e z{mUS){y$UJra07RZz@I?>Z-a}P~@^UtA^mq0KuM>M84kp?-oS|tTh=>9Hr z^%aF2p+?=ct2k|!e_wV1hToxa8K1jHr1B`ou zoVxw<`X*-u5xo@o&6jivmX_&5+pbTZ5W_tG!yj+|m|@WpyXD)f#-$DCWFO2CE%6pG z?E3OYjDW}iQ|;N?ANyltiIGzg%FD}cW)}=%D5BF`#>4w%wA|b) z5q0MM7Z}lD&DqKH1z}_HMO#?5*F7RklEJ%NTwJPZYB!)sQUYCGIQ;-o0^wMLftnuB zWk9BcGchvulIJ9aBSM*IbSR0V6+uN_5TI~_;eJ#AZ1RFbNc!2e^S(2UX!wk>bTN!_ zZ2&Nt2^yR~=QlPA_e|+pk4(z!GRx?RyYh2&Thfj8t7;eauC<%Jnde-@Ma}?ey?ggA zT7ZG#IkFwUKe)Po`=2b1NCgG!ZKhd;Ui^O2W_zFwBy>gaWM7=+a*##%k`p`wx=bhG zET6Yjkez)QwfnP+)1I#FT&4~VspxI(y>JZc*aclw$?eT?kOAa2UgNKq0ltx(+gI=F zU62_7%swGLMcsHErvKYMmf}W)H&nkN)6~!iQex>d%26?F?t#i1l+APh{f+C=5l
vuL063na3&^3d(@8}N=d=S!inBQr7XQ%f=Q@K5v4{JNc?u7*BeJP zK}1z`Gh@@wAHU|omq#^hqpwdq%*>gEH|ux0*O)eicPLY2eQ6LWZ*BC;f^0nW;DUlK zRdMuZ#%wMxbJ_EHgW^ufDwO4Uq8Zo@RUAhaUf zrhSmnTiV)&jGtMr#EDG+hH4K1E_KTAqe^8D`#I*UDagqYk4KV}TW(Vl4csDdMAQR< zO+cReaB@Ovau#=PQSLSw#dhAjx=2gg)6=u#Rd`d=4d~i^8y&s7G4VQDaquLk zmhVBpUw@~tY#3`(P||$!G@_^9w@I0W1kr~<_?Q7P2I-M8n_c{ZmL+JeH$bI^XCDen ziO^Soi>>YLK*;`Zf=}VoyEE4F0+4Eel*bm_MXEF;hXH2{Y5FzwcP?=Sq{ZFc-7P56 zKosvRS2sL;^OG$B(iYVHWEGB+=y$dyLQ2P3K@y~lq@YO>)i+P}T3cW517!(0n+BW# z9pAqzz!oTX7<~?qh2m`Jn}l){&i9xBxoxD(o(l9e_+!L_0ixCHrx@8AHSX&I4kH4= zJ>1?O`n@^f><~aec(&MJA7Qoc=JBQv=xp%k`g0hD`~|2y&}6*4DX;#weRJ6EWwkqyJD5_RW_YnsL=XnONd&LE`*oQM+&b=s$lj7!j2Y=!LI2dPSJ zesiKq7+Pe%%a4wakv=Kv-s8v7z$N8*Dd*c6{gps420?9hZ7m8Ol@%mHgya5`_KqBa?PmASzdks#fAnY;q~_kCp*Q2^AZ8-` zR6#*ORbBl>X699(3Lqw9BUYmT0Z$(w?`rL6GYK0Us6*IK6c6on7B@BBTrwTf$6)vw zc_3<>E1y7A{RH|w$aOEO6(5PHsi_Hg?b=pWS9f0PRna7Zrv6wfpH|s#(7`>I-g|Jb zy;IjD+r;D6dh$dF+#ft<1x<5BC1XtjL(?C6t0C=uhERz7-OLo!fgwxHig1z^(F7zl?EkZ4=E@w_+) zw&Skh$HKo707Q%ybX#qskCAo;);!F*gU}{*`O|+D5p0s6yoN82HFbaHwSwNt;|JxI{M{r3Jey5(%!`>?cTu6Zk z-6-S-33y6_lv7l>IcxQZRE{W%h$UfDKlfwWw6|9OMezv?3Gquv;3Ys7 z`px6J>h_*KErk8gHE?2rC^lHI{#6)#uG%c8vb3+@*EVC;N@GV*R9yT%db_A-C4^o- zK=`R0KfVRC?-d5*sdf#;uG&Y5SH|lG@Bkd8Vf2-J4>rX z86*ikNcBsAT=Kv$5||h@Yc<7d=Dl#f)>rbeh&gf_|HSC?_ZK_ar}IPQh3{2^-&C~g zc1K4=od7ko`_d0SG7*t0RX)SoJl48BG#Bf3N2!Mtd5j|?BSfA=|7*?a)$bZk0-q(Q z9Qqw9dm0u~T)No>A~LK(7fImALYfv!Fm^PADe845IwgIze|-SzWz)VPSzo`I0mMoTrdS znFZ%5{zA|iFBbK?3KxX*_4N^Ha}A`5213!2_h5y`g|7uL%pqsLarW0Q7wiFbPh#Rz zbMx?^+A(yxFMPSdI}jEiHF3PXc~uU@@M>h^vq#X0G1cpno~E~oq+8Ys*mA~$jEijR-CwzCTaVqkiSft8gNKUij;5&a3z?fVgmxA$MyGyCj& zN?v^bC=fvlB2S*2q$t<>}PN!RxU@KoP(+je1fK5Lx=vyKwtMHzgw@qd6Zx(>nWd zhJ$|8?T(O;kZYITTqliR`52|vGP4z6J4~61oRDL^L0JR3!9Q+4o%L+3iOG4}>FE8y z=qBf~O8m9Q`!G5PF!EFtBqD|2JlInY;FC!?CCmEVxHwXQ+j1VIOr?IG%GD@2b{2{u zG64MlzLZ)W+Fwo{1VH4c82OY}XlYw_#SvRnn`-WZL&!&?VouPGHT^w@9T62J|Jk!m zV}LoYBOWgJ)~!734YAU{0=)2^Cmrb3Vb* z$W{+(3?fFuG&0KK9ep9S$P*?1^f$I~kca9-PhUZARF?LS;7m#R(Rn5jdqPIwF9{Zx zd)eEJj!)fc4&zk`u2^1JM^e3}KRe{Ao12%;L}DDI2n|J-D&M<%msC64^2jb;PEN78 zQY>I(4tW=+;fKQG;%)&J2aHNZpm2!X(9k3&^ZS_{Ir2wW#`KZZSudd85sT+^b?IrC zc%L-V8pV)zn3&kW!jkgz{I~jhxV-1z=cuS@)C>%m7U!mFunBJh8JaehIieIHnP751 z%Q684i$Li_s|L#SP)6+BzF)2Fiz&}B4686X!LsQKkDfumm5gPe#nc_auCo9ZNjhUfyYi|L>r3w zPw;)PHvAYHfD9x+B4=}sO3p%*B(Qt;KbRPm8#$7B*waTvMZJ?-|LfN;+wJVQx8w9T zd>$JabWUxRmCZM06K-j5-*07QRlIoVxUqqEh1AT&9D0FxV5<+TVE-D~WS;T)q*}RTRQ{b1PlcH|-8Na=Ojz z_57fNtwsb zZ=#VkE94#ZINZj`oI8N5$Ss5f222%OnmFg5#NWpb)z@ASpI0H%5X(Jd+uhT%so_z& zc7+tuDOa0{^AA5$}zJn zk`R@-j&wsNf|dz{z1gN0!w2>aqAjQ)D$(GOjuL%-do_PX0t%HJx+51rc^lc;>n6T> zH$4qP+1bAzf;D3&MGG<$nyoI!2vaVBV~jxLCDvN*>FH^rN&&hRaBs&M4ZX)&>(zf5 zqeUes$ceTrlXvy?)u2XB83oUj+jaDM{XBpMIT>xhU1{sP|6Wp3!d-;F;J>!2e{TyVuPiYN;J^R>hkrLg!X0^knyFc6DFl?1%&ixJ*OLXL z(6Kec5WGazQ2$ti$_ z4!3=bJ{obk zRo2%(X_mzxzKh^F9w_KrXNfT*g$Ck}bzp9y#%GLUii;JLRaC|$MNqvFzP4e5oE=dX zKqphY=;r1o?LKB~XK(+>#aL7Gz}mHdw+(LyMQD?y4w6aNx#QRx!8(xfH3MI3efht) zKd_ahvaarNx03L^`b8Q_BMf(&y|wMZfq5K?$Ev- zl492`B8S0Ldn}6ao__7T2pDxkvcI<|6b5=F#HxvO)PL9cPXPf?gpyp^f)2Ko8{@s@ z)xUSMBjPTyf2NQgwz5+F115vqRWHC`nxO#@Za`z`IXhB$ii~)>OeKmy%G-hCeHV7| zyKk?j(G=ioSrDtZ?RlazuxDgS(W=Lq*-+vu7rFkOZXr}V*pv1NyYJV~Y<2s0Kef_& zMAT}ud*IxaBSZ%-Smx;=kJY$is495I0s@CO|6lvVy_gbe^qqVXtBQ*A2L9eJQQKku z>as{;VZw+h&E6BS+?_34IJ zUshIm6i~fqy4J2r6>^MjF*t!bsPffAZ#4F5eQ$ij@;twqXnkM9H^b3r%huSP_xpD2 zX6o+G^c;n&EPAOzvZ=Ivp9sHt_*bn;BB{sjRgT9*4Q|oKr*#-JDtCUZZfsn|VE(c@ z-I3B!zMi9t*5GrCKr8$4%aecU9{e%Z_NtBKVX_;gDiM0II6qF2;hY&L#1!vpdZcSbMqKsJCE&Z=5dayyVV-x|XY6 zJ#X&t(hZ)WtpDp@{Y2dRLcbzsVOHr~%#Bjdg^#$VmdIb4f6ktJSY%+adQgboC&%EV zNbt{V!lGoZLgpZ$0@`bVcGg7#`5FEuU-KF!FtkatC$warT0HrL>meEKaNDJl=2F zuV}S(l$ZJYitCk|bH1iMQA+#qrOs3_CO?k!R#oeJzBHa)E4Lb}Q*!@uUGidi7tDI~yb`zb?8fCKyF}>|+>~?5lsVb+&RMK_oetw8beaj5 zI&E|I3BQ`Kd{cPL#QRZ}1(Sfl0d%~_-PfvXwsI_89j!B4@T$L@oZR>AxKs_-#?#c( z^4Fg3t%?ge7)f;?J~lB(k+Hjv?ye%$gfPXChFUQ|ty)#>pg`lyi&)#-l~u|Ht3H>l zD`H^h4E%WA|83p@ruhIHH)iJ*gQQ~CFMHVRl#K0m*I3dF00qFYJ*(buKLgP)Tt5{*B-S~#wXQs*GR3s%T>U9+Pd~2rT5RkP#mXi zgJIvscLwa7i}&)Xe1AmU)G(8^WbMCTD{AD^!Otgt$nL4fUE1AcblMc~LR;BjJwH?Emvez8 zrq=sWt<~+Um;H+C!`LPsuTTlthyMvcZAl0(PcE8ywsdjt_Af6+eJ`6+QewLzC#g5= zzZPRjDU^{a?3&%!YqwSPQfGKf6lMOb+SEr1k6`ix!|ll%E>AJ_2f5#BkQ!%HWq3X& zraTlQn@9b9k$!Q=hK)+-(@>((MTPU0`rj!MmV6S2%g?!7`!QSIVyu>$xumd4LwrK` zWq0C?cA(67(2uvTa^`Mb>l7FoH+Z?O`oSg^{&o-D=wFnC9-5gQ{+h`>b4 zH~ejp)?QG|+UWVCZpL)Nzffh3!i>Awu#(AwC+mi5D7=Pchwf5uJVkHt_)0x{!KNX) z&{vPl{4)=JupCrnz0BaNed)SIOicNYXM9F>OF=uSKIU$$)6w-yOe=k>$;*0Gk@2wj z`F8WGC2dcHeXq^eeU0AcxSK21e)p}Nep=4DwBfP8XWo1NvF?BGGpbb}JACBWg&KCt zOIy{xu_6*HS)JR%@Y3EBlUZJWo7AhO4pMKbv$q#b5I!{h>%C{n?%fuh7ox4Y@>}}Y z%C)!7>RLvQU44{gbzZ>!^MC4GK2>KLXX@t#-#S{p>99usHtWSTW!06t9GC#jvXXeb$=3R%lYfgOD(iUkJ zpyJwLeKCEOHmO}$s!rre*boby&ar27Reu8f;;Q&uFKiqC_>uYT-jTTX9)fo~6BcaJ zA0H0dYuhe79@O|oPjRHRuGfZ zXtt-HE!@qF;}pZo2Or*5F^NIx`kfB*!f34RH}NI?+sq4tsyroW`v27ebZ=)kD5=u+Saz6}_WbT( z*G+2`^v;%X2nu)$rs)42z3rbkWEs2U#wV|Hsr2x%-?zq38lMjS+^uPSE@WTnVRwL?=F*_DmUfas&pZ?sgPM-9OaHU|`DQpZM|mai_>#>-Fe2)v*sz4V%(i zrcu7UH|b~eZ&6Ere0%3TX7+VGr?H4cXqWd^ali45+(LO&!OXHzjpGX=MN8s%wFlSk zim@U6{R%-*Y`e1y5`kRt@L*5)7A zpF7*C;gYyd$+{q^{>c2J4-%!c1`S^&=|kV#S!J!2%vC|l=oZJTaWs^j`a$HDRhLJ7 zi!|@jjr1mJv_Hyc?23u^7oKc7<45CWm>|9UrINRw@#f?$C$r}2bKKXJ42Oe)A9KGyW&!&R{d zg<}8n-Ga8VjH=RUYR-x+|0>HE)3CKzV!MYkTFg>N3Prk|Kl z93SEv&Cj|L=G(YNWLh$uQ!+}To@VC@|2N<3yQqG9TOBlftozqrLCwxr`uARoRUCz@ zxt0AjCHjTF%%?5c_p{_lJD3bu_A5yjY{)U_-pBu*;^)3g@uk_{BQrbv3f0nd+Vgi8 z9@b7x)j#K(uq8IDl(R2Ww*8@EOlU{wa*lhEvEqizHE7FHI8$^r)EWEIru_Yqr&!$g zA6`LQXU|DCRe{?3w)s~bxieGZjs|iQY3>4zqj;o3wuzqqqOifxsPgPd{8W_jVakJ} z%dRIps|~H6UR+r*I&Yz=IrfUQ;@Ud*OI{`EviS%K*z5j#Px2mb$^ZI)@rR6{NNwNL zD{9AzN(9e-W^tnGG-%^lvms(e6O3cZBp>>t8_$xjwDMd(Oh2>E<(v=m?{i8ae!@X_ zcROr7?IUa0V_lZ7a5CmZLsig7Z)s%7-ppM=n%51|a}f%_)O6*9{L+=)-MdQ_vXq{f zed;Zd7Y}hHyUwow+5#V7r6)JSk zZiI-6h~p6K5%$)QsjelF{y_CIm39iG(3AOYKj_p~&ImhUQBe^QDMFRC2~ZHZyd&o3 zkCl|gZtlzjTd*7CLjXkOJM#EaJYf;uU?}Jg8z^AXRS5)23k01=R7 z-I%0K?8P__Aq-6RQ5zSWDB*rnOLHqyqXRQGh>DB*A;lk(?m+0w`C(mzqBp86tr6MX z9)YQ=&e{+?IF!+NB}BsHmH*ZQnRg8h0Z1JusPfTgr;|a_6?sf0e3w`w=LPtb0Q#X^ z^3ISVz$Ew(UzbD1W;M|7HXhy$a@J%Bb3${NPzh5M0ifY|>xIS^M)j(`zAZe8ZihTB z8Lz7qVuOlh9}puMa3vtGGL)1B?5~qWR89@h9$^HCgw^^r4W0m>kPvap!GB?d7q3kX zBJx2OTmkOLL!j&&s#ldkS^v8N{(o1%e3m_(m>!_HIa1~+2Qvlq`s<90jNEVTw?AZM z(?2=cPz@rBgioY+9u#L2gyjwR+8xH{>uG7#?CeC~)dU3gXp%XT7szM$Ha5_jRd^7m zg7zIba<}BQV2V}&fZ^CY^D1BB z(-X%?ynBS%FdKm_*cn)7fx72`tE!KaXCkM5;4#DX(aOUscc{5~p#SwvLd^b;0E1ZL1Oznxy$2~6 z+8^L>rz1nMq+|fZ`JazI%Ys~Xj!sTFlRq*d!iCttb5#+$2hi-Qo}T!iHAvheD2zQH zk6jN?P_p?YN@3z~fQFFF5NPXq_zw%3?8<|DGFUthmuc*ANwbymZ_(R}!zc3h4U=Ga zJb?!g=m0SF#Ws1ToLn1^fZT?(nj`0+`h@4`8sy=u>jVySlINlr9v!^~Qw7!-Yq&Z_ zddrl^?j0WnFQ9f$zaeXSb~c$^7{PFZ9B0A`XTom|vjM)@=9oAcTXx2m#3z`p;<~7EZ*uR-Xqr)CQ4!(D?x9k=I3h*eoiP;h^ z1UxFk7tsgA4<;y!>WQNwWKI4+Cq_oaEXd5@A5c70!k!0AbFZi8e~*j7bpQ)D@8M_3 zeDboIoWP+k9;i)Fm55+K_k`32XG#nM&aSRikmH^@FA5;2Wbf828AV0K{AwGVYq8sP zFc1&u_H8pfpj0g~TcV=w-lfGBZ1?WnUv5d2zXHJkJmVS;(RlUx^$3 zv)v-LXWSvnU5&7l^dQ;c8s-F)4w!F-Wrr2>{)|3Kd9Qwz3)9DoyTYYfRrXG@WcTS zIG%HKBvv2daDt>Hyey4RU`U%4Zf4pi$6n}4<`ES#zPa%YyvQ)}H%4Wr+BhDUHMoU9 zXtXh30s20|Gv`#Mrluwp4r2o@pen2bM1!4G3N`fO83qC5N*mR>R*&$UXuMgUtAfFNG4uftz~b z#EGOy<{-|p{Gd0$#QMK{@g-35=;$b6nvF@h;4G`E(tsKMA^05*1=p<yZajAE zn0;7y#;CQ8dg~?hGbvi|4Xs0wCMt&09}_}>zmp@Lh)f*IVluuftuKa;cph;>!M`Z3 zCk_ca84D)Vm}&NI7#T2TuY(K$>RxWp-Rh@KZC(2Nm#E0d_ZgCwm8}B1O3vc}b7~D; z&eOueGx&VUzt0y0=>ZOdoU;R*pLkX}I*tIJuLMa z=fBHri5od%iRfI&%N7<=z?8n&xNSpQ`b_T;;D0orBeBf?d#>;_3S^lP;sC>kPf9Ac z+0`bG1GgD7XDw(5qSt{N;0snD=r*qx6kO!lr?2_qJ>EIyh}ZAVGcZq_v{5(yNG{y- zD;fy$e4xIXhI1_1TnLgG+(|Ntp=@b{Xd2Xy$?q7Att@RWt(wN{sX_Z-4cYT|)~L8z z0R91dJ-M?2L7D=F9?Y7W5Ia`lLJTb|7=kocpg&m@*xRbJ-ye2$A?;GuemuFkqZbXdaVMxicX<*5LYhn zLJ34U5!eDu4t!%n(Rc`7OxZ|lCM%KaV~Kv<(ZNAP)3DGmfz^@Qf8f_9*5LGQu)Lyi zvb9nFSAVp#FHUv`A;tjm&ZOCuFsusJr%wmK+=C^`roYM`@T{1dyL%glgxqR_k1h2)gY#7cm**B7k}GEY+I@5RND zB7>nwGJ4AAzj6K7u?L0-9faXS(mS^f#2&v2!CIk)fZ_d^79`{yI(V_zoJ>wc)0xUZ*v^IRM>oK6$R8O@iHiT{dpQDAeizNnsJSoBP9Id zxHoRVy8nRaW39oPw*QzPPBgoxuMG*u7ve$~$_UKJ%ZEaMFs(d1q2w?#6nT3pGU8Y< zmtmK!f`GTKCpS5n3RQVzY^*jtc#U7)M&b*B1jo`}S2Hv`EiKK$W*V}NT9#W7G>NGa z%LLK7si$f(8r(=662+k|J^X=V3TUp0-2;I*u3d}_48%4IS~wXqEMGP5-n~kQieR52 z#s>WZ2gbd){gE+%;EM6tyT&_q*Rh)H2QPT_PybqY18I=MLIej`MU&Aw9oi)*NDSuE zu=K;b0V!2>Kw!|A6e_>*I6AWFFO}4H@87S&C*XzBa&rD)nM?LQW@ZfzKo2Y`NDOLl z1%U#jh6ojMjzj!;#OR%6@|ce$=nJY9meZ=*THR1X);6hsi$kSfO23VUdRB%=9y~U_ z@$o#E!R4i!f5OiWeg9?KR zjyS?GqdC2vnRzyJ%OVJ362Nk*q5@`4A_RXdzLo-~EjlW*(3(_ncdLqKVp>CB(<%xv zdfZlBE;7B{&f&ta?=_*^`4tt9Idx&tC5Ms0>#6Hh3eA7ju9RS+vuS9^sXe6*3Wvz= z@k6!o{J|NbP%O%VQzsjk=PzCm{XYr30hOn1U{C`&N*?AOY(`0N#F2B}>?Oj8+zz7{ z#M4{ofv>^*9cAtW2M9T;2(92zhdhyo z+p@&!6ciN&#Kf}J6B32ACq!icMT1zK{n@jXFwKxAAt%R)M{~b%1=s*6n$X~)?;~v^ zY$l|%!uOkuRuM}S!)DplsN@t1J3D*y?VsS3$y-1hy(tF9z#HfY(0)Bd?bod<(-p7H z5SuJ1xmpXEH#G&-=+pb@z*cKCSSB&>P*h@B7~|u#7l-Z>&DYwzBMdw|@${uCI-A(p z1tA}tDw|8Fy0k7O9ZNBx>9?Cc@dY6U>&CJE&lK#1eDm_Ax61|Y-MiP?(UFmrHPUrX zSXfwa#|~CpBN1G{K@1b&F{k?C;$n>8&|2KI{G#!h1yPb-f?@6K=Jq7=>xRr5=w7k8 z5R)*%p@$GM@A^tBN+oWY0nH;$V6EM@NrZ-$UyUEqe;-3-);J z#z9bIM}qbCee^omJkbq;-ZKt+RFV~3nv;{54_Y29H^YGg9~6~@A{5cflBYg&@c^!5 zq$5wTuT_rkS$lhI=8-GZ_sgixysF*&lylWA)uHgXfG1HLryjlKQ`$z;nVI)aH%!yi zbz{OA<=4dVvR#Y%yuKB+@$~5%8T>QLu^UR1>Iy6F9@^5I1LI@e?2T*F?*P>VxZ6=A1f=3K$+J1C=(8ZFT%hero44uK=p}T>cccAjJ zhU;Kx5=V(;v9sKMqiOE^#gg-94`D}m7g5sM`Xs>(H%2&g6-nR@82|(CAhsHd_qb>xP>g$ zJ7N0t^mGzDMmd35<(eCgQM;*Ry@@azdV>Ekey*m7n-?%3<)pE_y@psfGL3|}_jn!o zt(BTpbo|%C1kCK1@BR@H8&K76kl-9BhO5BV%HXWa!QtV$T1ix3jM*FL=*cCa$o6AP zL6#MWA~xj+9`g7q7ufo~w-@>v?92}>31=4-aUcf^G;r(2AWcr`oiEh&hI{peGIXpp znyO9YoafN-`eQ-*UIDvM9nFJy2y98V8>FJs2rnRM2GTos64NT_H7($hgL25V27na~ zOLa_}j&fR!%r`cKCIyCuzJX(Kur@mEXy*~653IvYAU6>Qni5UZdhXr6xY@69UHs|6 z16SL|3thfykzhaUG5nBUz`)38YYXeZbu=5)%$)l$3|^y166dp}r6rCxTGSde(r(0#aV0)TN@pHhe86 zrqRd=b`vZ&5RjHs4Tpq;P-rc)Qd6np(iUrPZNqTN>CeICT-i&~%#?kWxe;9ksdofd zc=kDQ%nXvfhWkBDRtq2_fC6H;oXz6NGo%tJR0??h80!@aCAmurTZpQKP0fY7Y-@C! z)pp6rL7;8cA;c2Y(GwJyvEG?sAFD8rrbS!SB`hBltBc7x`ub54LUQh7t@NtG-k%fy zW5j?ZGN~#b3_T3|(V?Z`V|{?GJSIbsFhdd$plx-f&W{e=XOH;14*23pWDs#>_ZPJV zEt=#WhX4m@9l3|B?k_>IMqy@&1y(bFP6=B!EnpiK^ZCR{Ubjt3Gc+C;4MYhWHg4S7 zuHuTm%s%AbJ#}~(bOF0jjK&S@>}F?+^DXUC8GEhDJgs4ZGvO7+Vh?{qE&L7cP500| zqR+|0tR^1N9P_CBJZ;>3x`u`ZZTKy**?NkW%U}4f$(z4f?H|#lBtJPK{ucdra$4FN zCMG7VmIzVg!bXY=Zpe&m-!~DN_(+prv7Z2XA8f-=ppMJst~UHibP}D_bP!_X|2h%a zDk`P4=61tMa7XF>i1^>D_pMQoKIat5c97TklH>00-D}nL_D^5?^f;JF<+h-MmPyfZ z^N$>C7vme<|JXdYUvzDb+^bp^dS*i`6=m{#z2+2MU)!Z~S=^5$zh+6CDfpm1$e3KC zF`n~K+WDKQ+wTybUXU?3&jdVT9 z3xhrt1tt}W?|)4aN24k8n-gkXU0g{1AW71Ii1YonjkRxAQ7}sPBBzn$X+n63Wu6}5 zU&B9MCN7UX|E6x2j^)v3q@Y5*d-smO5@cV1qR5X81gx?FH*ek)zelWDXt^H5#}Cmw zbX{64XF|NP-?JZR3S`cPZZovh4lW6+DF1%#Pvg%Kg>Mco=h`InkMdkEXZ6u^t(SQ4 zS((S$>|$$eUbf|;^`{c!4iB$&lpmA%KkvSf-1KZY_PS1=vgX>43fi<4fj*x?_gk6X z`F`QN)NViZXFk-FBOM+&(H+JLrj~C_%xRXcu=ZN<>2K*f^f4K!Z})ct??QOeDwKym zFzmWae3pZK9vV@!cy#{)Ob|Z^56wdq#r!?<=tVh@*#YE^=$A>5la!P}fz9*(7(OJG z!ZZb__}uv6rKyAvRQhy1hkt;x?K74S2`c8F-ekC)L{TDJFCZL5{0y{~1h8Ps@B{lw zG$4kPcTL`8kNt9h1DJ$WK|s5N)d1UCP2lE49FE~he8?BR)l>a&^{PhO{sR#l8_@^j z(U7BKF_kn1_$+C|cPJYgoji9ggh=asrI)k5Z*0bR(e zk*B!u;Y3T0s@0Y`oHXqJ*FkK{*ZSONdA2zU^sbw>9Mnmx?!6XMzI#BhjPwAC5PlG9pd%F z8i#hK=)2Aeuu(&j^L8W`dxKSI8cYIPy1Ti_Nyu23OoE5dRue((sl>}j+an2%$nH9P zaS5lbo`4vOJn!wHWbsF+Avr1;){K)_P8!?Vknp-4J)oHUX>$B3aoE6Dg8qvh!YQIt zLJ1+g!1D6q`3EXj*oeKq+qevx$+y76Nds>(Gr=k+i5c(~L66e*tr_&fzI<8h=&aep zvu(Nw7 zKVN-^C2Hdk6@?-0#htEL7A}SZ5|%s9w;den$kMxaGOe0suTiPfK$b+aUsZQbnVb4I_xLL9{S*W3-djo~}sx7*&R!Faox7=%jORE@*?Sze zvJBb^3r_ZnT6C5&d@wH__;9pqFf1|h_v(2CQRgv%K3i$2?R3_$9(;;_m}Mgc_&3D9 zs#=zF^EtEm*z?IuXI`Bqd6$(|&#jsk8kIj8IOGbi`M-9sn^G`0Eq{43{<9*rVd1J% z73PW;-@G$0cvo96smK!1J~z-idOSRWc@?9CWrqj%_4b;-YfET8Y!BlXX7qgf?Wy~g z)wey$eaqk1=@@2RaT;F!Lu(!DFC(>ULb=J>SN{6#MgCv!RW@!Ktg3xaJteM4LkWCY z%*1r?yxLgHVqJlB%F0Ft284EdXF_qOvEYGlHI799I$vWJuPBEvpxUS0{m!r zRFmv*A~>UqYIns+D%WNknT|yRN)=_ORQS`E&)1}6x`ip(77H<4dvza3fBVwCWlKMP zzb|mGvrBf&oohVVx}x6R_@w?!s`t`RjVQOdDwRM4&4T_PDSgN8i0CDbGk=E%Mn31= z{m~{-99=n;aOB1~)%K>Gshuy&zDP41$d2G$p;hlHbMbn8O8>89O4Uhs&kMZyMmCKu zU)I`vl`-Yd@e9;zlrO0MqOjc9+_eAQ8XpVQB9{41(Mt}!$LVE?e%}i&WakdJ7PKuv zSvmAs#m9X%gSH`7t_OFOn!10S2o-hc@AcWW{t2&dNVT)_6|YUy%Vl&W0jGD5ukg;m2Fw&2h;Njoi1-PuAr9`pO>>Xl>o@T;pr(2kdr(oLEUo@ZYwe zu?O0I^6AS=Io>asFJ4|dz{|Z~_nb7!pv&UOoL!#}o7I-ZEnnU!YBg2fbou*5_xb1^ z8gJoczQ=E0%o+Px_6FT8t@)w6V*||xKYwE*RL=<7Zx?yCGpH->vHpBprm=D3o$o2v zEw=g{e|2=FIFL!@X7ZMa8$oGCnIA>gd$GlCJ85R&U!M1L&z*ZOloXi~Znso4 zXlVS|_k2=O_ablmdM~RlUX5HohcGv-<`s zZD~GhlgFz5?vpPM57SUGrC7KY*YEu@-Qe1JaWpO=!Yg}cPb20RsPic9} zhO6##w|+WWQ0G%M;0Rv`j2$rLu3e4vd7Em&Bt6r@>O3m9Azb?hpWTiGzXuV~rJMgS z^06e3|9C_1KEkn+nlgC0x~>4F?{#(62CQGTDo$1x>0NiQoH&i5BScX%Z)g6^6Yy&2 z*ZX$|L*JAcjSuY+KA@qm$LRH`vGr~1idHRW_hB2TN7YiNT^S$6UDFUOsWV@<$;Q>^ zq)@8;MYMsu%5Od3VM8H3PK}bU* zCXP3EwpiyYg;FTLoP9{1(ybyI5_{PZyRyaSze1=eY@z4WcD<4Zse&{igRR%oPMRH2 zyy&kfp!KJ%2V3S<-F|tiN9p(}z7^$9E-l>-E2pC*NlURF&1`ZtXsFW-Dq~C{@>Pmb3q_yaT zot=IEla-qyqM{mOkykK!nBp$}t&?y-LGaXKqhEC0F@OOVkiIL;=IQ>QY{9phbt7eO ze9Mkfl+TRnP->L3Tff8MO%R=HOQL|nw*u#7Q^$?Jhg08Fc629K9WCbk$2~IE1Bv?4 z;~{nC+-0CDKb9AR4JK-1sC}_Fe+4n{r<3RGU{IE^u3DY8=NY(i|IwuFuCOB^z-@q4 zj{+>k7uXJoCkGJxo-H>uU>wCJA~7;pKK+TPM@2z`bXs0sF|}`Os72}em8x*2i>60? z?7LOe&_(Kan2htJR=*r^GR{)4lh@YR7r!Bp_iXK|rJjbUUw;Mh^ZcxbGfl00tqx#gx^la>p! zA_bU;@ulVB&C~C+8E&>Xgr3I;Ao^s+2J{IC74S`Ucv4c* zF#{p;&m_8V4*sGNXB8G+-Y}SBfm&(*?n5XNBL&%_H@ea36z+uwtl*HXI|2N#&m2ME z0)>Aw9a1TQm^?+eEs16#E*V5c*?*nQ2tz-o?zGV2I=4yrqgreB4e4ElH$%s{D3pin zp?w3_yIt$1j*Nwc-&)Rh+#F<0p%^*HQ`81SEAoEcIvB29?J7eVl3EoT!5sXEU%jze z#`nVQ>9jo$cWW!orl=;I5gK^GzvcBO$D}8fmWPdfqdHF9?Yiivy>+KBW1Km)Z+C6i zVHuCx1BC|PBjO_XJj81x1(VXU*Y1e>ZKwLf`;?H1)(;oe;*Yv@Y!yf3A3j&Axw=|Y zz>Ra(Fj_`gv4WAT-BYUT7KBW7GpT)Oc zW4vToUQ37&`y{l8#4(4!&~v>ni<@2DU$}Z|YOcn1-`dH^O1OsFmqhIX7=gPgtHgN? zG1%uA?t9#TEzCox2l7q6MlyV zWsT34TB;e467HRycn?*#W*a9h4`Z+Vxb^iM#sW5bI{H& z3f?!mJE)Gb93IQ|e?D$hU*;1Y&$-UUg}?dhmj3#JPLbM=F%EoO_c~MD3!5+w_v7Xc z4yUGkxlB`)^S!!Qb&m!nM&*xvW`d)6;(BH3qr1FhLh8RWFMa%|;qg?~B~9hB@4L9g zLs5x0o9)BBXFr%f-&eP*EIfhv`r?^gDX43h6-DlU%r&jp*}gl5U>%S=w_npZXQBM5 zB?t>RwSBQ&II+AmPqJmFSLSj1e+vlzrE{B&t86Xd z`TQ$BU{_CX^!B*e_>joBm*LzOxE9{VI8UgovApR`6R7!TT#pIE+LS?e>-B;#st^h8 zrYy%T&*vTp#`TEKELc70oRl!@#!7YRWG&}L_Mxw*zsLuc@c6!ba*AW;`8C^b=GgT% zuaRfUrJ-=_bO^$B_tItF{T2HML%rYW_^h(rYji}xegCkJH^cTCr%P-ubT_Zwnfl#w z_J>zdg$!$HjM>txm60C%l%&edx+}2)GBfmB2UzZQxobVD+)|m`a_Ei2Q85|`9&c=w zwXil1y^S}X>+U@|YfzkbVBuTxxlh@#eFx}smR_vRV>+m2ahSFxCWlPHX=`?77e^+_ ztDL_l80MYL{D+VAMHfEh0Tq_w+B)Yq05Z6v$VCtw@iejz_<&Qv76a*$m)SM!r~9!p zef=qWC^xmMaR`}p6NP;Na3U>Ftt{tijaxw$Ml#Atu=xA;nPW`G{Q!&pEdBf_<2tA< ze&nf|({ZSP0PzrKDMI}0&bIaOhk<0ezbhx|fM%;U4z{T6)gr7OG3$fT0dg6*$9v&j zE#xkuFJHh~{~8W?m*u6)@T01Wv%N+d05)-2;43JUm8G9d%Rg5pdM+EAv<0Kzy}2bC$r{LoZJtvz#P8fI>lb-eU6r%;H4y zf+$>0WDNmZw>s8s+qP{5$r?78^w^?C&ALrj>oV7hbsYj^eFhm5lqL8u5u2#*X|eAl zHKH2o!NCx`9P%F$M=z|Znz&{i8!{59e6f$;vuE4SmeS&4*kZ##?HqD_U5V0kZHLoQh1gAfU zjiyiI9dy?oh;`Ke-dh%jV;z{`s)TBTxb+F`M~4dnAC~dl3po-x7;S(lY;EUP#Gr|} z1;_}D5E440LsE z06jmqYr2l7bm4o444}Dv25b6=FPfYh@L_+@1rrMCuacLVlX{( z9n#g%(0KYZ{ZodFm!6n?TdTh^CGFVqiB>yogFagXOTux&OL;H=Q{;yJG|Xr8uto)i z_wH#~BSKz%<#(>#1acH}%gE%#sf79b`3#)}-LE_0%?0{2sRV>-uZ~X8*_QP86Wdkx zY}=MrwK-Gw=ixoK)B0C!I#_A`dDCc94+ZLwY`p_mMc85_wgdhq*^#Ft|H#P5kSIeUB~4G)LLop* zbHQv%Ty*psXrZ7Z#I0Qe?MS*oqGZd>VgZcpuXs?yDAqtFn~+5#WRPHSp1KFLZ5DTH zd(@0ng!a3-$iz5v=KGH!xIvb|;KEBLP%uhLN_foG5GCd1=cfRJmVKs_mY(kV!Tyg6m4&KWC8;>T9NdVBESYd^+?JdN=BpC0p5EK+F&cA*q z&eiu*wyoLE?6J`OmQ{&h)(}g8dGr(YS};PJkcptRlAy4awbq!Z{m-4uSKq+NSqpZ7 z1kOOiHh?9j`JN&8{*Q>Rr9fR~Ge0w=e}5+(g6EK@@@J+_>K^7j-euq3z0?pcCJhF~ zYYLDg3Zy!ciC|hh(gZ0AIZFU#34%e=(~~zu2;aCwA~Yqrn#+jBup5YspwlSJvP*Io z#RCL!N`$AVrFV+29XN2n7K|Pljwp^$M{F+(S{jTrfI!*PpOKy%>GK8i4MZG?G#pG% zLMD|cEX%Uz_f7Rl9etIB9@ur%>(38<9UUDI_ic*a@K+9i`P+2SL#%B2qMKWFS669O zewMB+b-v!~Y!L$_=HRpm5>SuGi@~ZJV_X~M7>{G@LjSr0UTnm%DS(ng?d`|uSf{}$ zLTvJ>_}^;LB3^Uodq*CTl@Q*$pkNoWLrClAS~LIW56MIWqS@5e_NKl*1mDMbZqgDV z5vzUCKcI(407z0!P8ec$(cnSnWz4yP8HJ^D7^kj~&=Uy>2{QhFK9>;_)BSwBAgcmV z8m1ikL7zhnd|=m#ZRX?0k%@`N&tAIT*c}z$pQ#LK0$R|^h}whcKeqUqit8XPvT})> z35vMU4-5E&B4{l9sl)N^O|7j_<G?#SO8nqOShYccPd z?LicWnqnG|GZ8Sh4~vS9c}sjc~WPSgq4|Mv~y==e;P?QL14gU z70>70;sz$}$yttnu%gRS12*1C7PHIvO;!#F)RGR`^3z^V3OwDO1i?62OTfn0o|E#4 zFwoKA$6qIVY|VB)fBIC-$S4wQry1wXu(0*uI5qf&jHwn)B5Q(E*SRIwy!J= zs~Q>^QJ?bZN|Ud_*(Cj7c~Kh>5d8|B`ax&{{pCxMB#-A2 zEjWK(6dJJ6WfCdk*!33FGg&c~*P8V_(Zw?G=HtiP(CX(yTZ?#$%jg-fx@KCwU9Les zg)f#%ga=9%R)~JXpi~y0 zgh~vKZx-my!Z(Mjz!ZU_f9RN)&LHF+dQ=-EW&vq|zHSN4G|;Gb{+$o^GaW%eo!`T+Jxri-fkCxsq*cm`K|~4EpbBkEpMdE%DG*tZGO|QBsbBgf zvVHpnq%Zs5Ua3)C=9kwC&&m=5p%)QHMf(N0p1C`pfNGV+mX?05v!jEVm)C04gCv8n zRo=L>IgThIF<5MQkG1afMobV+|Hx}D+Qvdhvew)jZ;nAFZhS8`zaO%L8$jQTuYAYE z-xyrFtG^IR(n-$aCU@ojH97a~E;7<%ctST=3|Bz??`E^^G$0}}m{4&(Dw2|6IO+)> zRSaDYN*zvII(Rzi3+h~!J`ufR-eN%TP#|ChYDG>YEW(ltYOh(+KrZdc6a7aAE?n3^ZA+z7x35Yo$$`KRsHI?F5y72)?XVE-b-va|r{x1y zoq$*$J2NP^_M@LdDmO$d?|I}Ql)^?oG&eWb?RzCQH+wNmHbeQ014NMEgp3#s8yf+G z1Z939p#ZD|_ATKkG}t=5tE&@~mygAguUEs?x)wtKl|ih#y>;gJp+kHVOp>%3E#%-F z%!Joi*GQ>HoExOo$j5xGx;#xx9bAe**ZF9rT3=VBOq-ul|Ms_IjLE6$eh(MDFNzv6 zD_^74nEv_m_2H;Kekq4y?55W-^;8jt=P|1gx$aBC?x<4JBFA8lwm zvdQc^^S6Ps|B9>8-pYa?%%eCpf|`cGZe)<|`h!w=0ovXlk|$#lwfc&jPI8VbCEPu3 z>LQwYD%eAw$w&X(+KQ*Ma%&im^0o_jDSSOHoAWdDeP2`Y@uBfjWhu#k;g6ROe!aWA z=Xc1Kh*DLWq!qv1yvq--mZJCY`@BM29M#K0Wj@nb}V$13d<&S8j47KW*;nn-PgNqq`$+ zJg$yYvFn(5$}W2;vyz^(pHJVBTzg@-q9Pe5 zq3)Z?o8|p`{@8Ql>6J$+sa-u429I5i=~~|Ecstbh$tXPj`n9uW z+%;b6jqOgd)9P*RG>7iSy-hpb9_cnMa{1m|qoYI6->2K$Ms}rsI{R3s$hPHC`dPKO zu-|U(^WnRACTzpDU;Q1GL9JIbU$bXx*8L8KyIQwB*p_p}#ilq-j=LKl-Oci%;!NZA z?8vGI#tcfITRa|k#MeF*(EX^#zTPec9e)wx7xxP9W%e@*0k!GYHn1R+W3FLz8ZDFM z&Z&KW9vOIshE;g~T3z9kaJ{E%%XG<4Zu+0iK^+P=Yv%8TSh0j@9(Y_Ov(CTx?Du2m zwv{#AtgYE~YR}6zl_p_!TyC$X%i1{18NWDv7p?NBugaR*x)5q^G&<+NV&JaZVyJlf zOJ_@s-@?I~>Q9@y~?g9y+Nxxe#cmSJim_jHUHu5se6Ey_WW#U#wOh2_K$4G6-D1 z6q2e}bN9F7`>L{iw|{mh^o5vCl%7yMxB0Cpb#2w4GI2K%(C&U-)xXlXG4IOz@ zq)zwID}6q?KK$`R!M^pj--A`vbTU6XA3A*Jab)-NuIkm^mGKVAFL?LLj5|tr9?f`n z&LPG!0np8A^-FS^YrTT4N*iW5r=?n-Gc-Cly!X}VyAyxs)eEDpF}a*}&yb|Oh5XvB z&qwX#qc9_#zs?#A+VdYpxL=EwY$=Fx57e%X8+?yAr3qB=6-AUwa_J`62Zl z3DMX6b%)x{`3K}|pcY!b$;M(*{Nq@h`=h<`@>}hXb(Aac1Z4>^4Xk9yGPZq+a9t<9 z5R&^eOq~0z?s!Itvs(E<2K`cNm82Q>oA!D;MgH9xyE`+oQxU(U!!E}BJypPU*KJ=) z`iHWPK+n)z_nVWliJ^+W(*7LXaQ1!dm|VixMwR!&ejhIxx4NGyX~OLh95;M9J9;Uz z*-0^N2;X#Lf~rr$@nP!Jn(9QR>ROkS*=L>OIYmB+rW1*A!&DUBVcYOuA_)cY3-79X zK0moxKU~s!FDsq*=xvBU67P#~Ih|by5nrt37Bp--HO4t#Wd1_xXTd=oI=Spm8^5I* zbH=8)pBmbI@6kSgS$DS`o?BwPg+#ay+PWVu?=tnaQ|9@$M*XCC5*vlW*{!3gZj49I zY@Z}un7XAnE1;lCSBf`#P#tQq|KOma#mx1BYn-a(Qk3(0>d1CO!}e_V`!mnB ztV+rfHD@2H({EC&d%2~q`1RwS$IlA2oo zbNEd(Z>}BBXn{;kM&v_%p0gv*_dSjds_Hj36%PKEEu?vaH04-TbPm)}d~4=6yDp+G zG|7CYjp`nx+Niqy4ut;onJ!+pf9|kV9ggl^vLE4Wb5L#@o&4tSzT(6D{I{dP#Rluy zX4+#}8G3aOZ!bKll|Hw&fp5e?UUsU+b%(wDF58j=>N>HH!Vg4d9k>+~y2B}9 zZDXV8X8pgr4GJV{+d~E1O_!bop5)ScnA{bXoXD-!-pIXeh)wg)p~G|ZSA2D*<%ukV#tPt-(c2v+? z^?$;rqlzq2<|gx85U8P7Cz+H=y?j6QPo6tHzy%$L^xey(ID zB355n^iz$}`drVc9FIZgwob)%RT+)5Hsl^%nk8CqF;#l{9-HuAN(2dg85*px1jHgY*|? zvV01u-I`vEn7>7RK`n z$AS-SwK%)r6dy6~boCQ;fzK&%N6k;B2gXKTBs{dsOsT|s7hg~b3F`^?B=VqkZ0oO! ze?6L58H3r+VPj8((Z6_|utp&JiGV1`xEqanO70G%@BbU}oGTxUqPu>GecFe$?k3EV3xv1A}6t^xn4a-uwc7wl1nsb+|x#b@YjTgAp zHrL-Q6sbROa_%tK;qxmh@#AH25nC-4wG6E#gJQ#2uAFB7M7_-Kz1Q&gw1{r5#n6I&KCG&HC;f$%KVOG^3@w(T*7x*A%$HBZwG?0VREk-N z^UligTyLrWIexpv?qx;{Se?=f{#=hd-tm}O#-H7MHzmF8zWJHI?=f|rrPOqnUA;5t zP|+sp9URa#++%X8_x8|IztrUiu?L+zWgji=scv?;{yfgyQsmfv7Lx<@SHcDtMknr; zO^V5jSVTD2w(BhPthmnquePo`9_x1h-=#E=CZQ=UJDY}(B(sFuXBFq{7$d_N!@aP@9+1zuFrdRq_J{6V`_@Eh(`+z zk&DB3awcQ@nUL&kA&Br$$>|>!*4g-a!-}{K>pS@4O2Ui3_>J|t_ujvMp&`3t&0O~u zg9=r~`41`f{EIAnnzj)yy+6M=@fW{mREz6yOGSq1g3mCi8knNHkxL)81tnsE<3r5|9Q%e&4O zB)yLR_He_RK0%+G0;`O>D_2tU=M}M2_YE1$&fZrB^YpaOfq;7-1 zL+bKW)#9qgt3TO|J(qls)>`{YJ>NV}t6ipUv)g|ME^MwvDtSLCDPt40x~xB!#*dd* zR=l9z;9U5k>2{Ry&cyVigAXUR=cKE|aMD;zr2~?`*540YQi=il*FNL^b%}CEdgm?! z9!|UO)wjNesTh7dikH=>s=U{ICH7N#tTK1CQTX5k4{=%DFMjR*n*FaQeoAV&4;987 z-1tB_iZ^#?rf*i_p8m2j9OuY#RLPUK_Wrch;>H#9^x4p#LjRrh;>9c2kb(A5P`=rT zHZ02j0&KGx)e=45Ag=3HXNMJ!Z%sThtre5jfOwE^=Vp(24- zkO3YL4h60|lH3iS!M+0r?m!g!+-~Si=+rr-)Bx{G?0STauoxKIzg9M(vD2d`7b}EU z<2C+mOFp%wS9S>u@^^5)JXPr3cDqy9 z=~mSf{FEeI9VR{HC|x1P9Dte7s1Cq=A@pxBQ%N@zvju2P3PSDxWfJq}#7vO8F4%-} zPN`4+Sg{$$b09(gQ~VRO&d>>*G4+9%AsN-2pB$zR5-!O&+VnI zaes))_sl@{`k>&H23EM?ha>0XdmU7#WP*jq!)#7k9HO>obgUKDPe&LEZs{wQBmlJGak-$+c z+R{u5GCx~)$sc{=+1|#d!zZ*~!9ynE^Ji;7PR>Bgfr-E)5&o=;|`dL+T!-Byt6z!5)xque}0ZRr@-+mfArKESw4}F{+D?-)?fx5 z5-p_n1}uvO7qqRsxhq;I>MlX$PcWNnGB;#GAQ49xEY#G)fC~|+f+iS=y1Kf=>Lbo) z7s`2Z$Hij*1;u;-jAb{^p|to$3V*R`SlCtoA3S$*J%FNX zz)wIcsR}8D=DoGG)hbv`X8mG2d7^gXiQ2U~Gnxgmb^WeJ-xL^O-7xZ5&1?s_0dpk? z-3wp^04WQ*{$))v4Q?)@Lx$#Z5~L5cI1tz>G%iTO!4CS4$oOH=(S2bd0}d)5ZSJIr z6)3DNnE(##IwRvjxfGP1h<&a3Ks&od_5ajQ9apz(FLi?p2&QuF?t<*fXf?f0JP>(p?T z=nLlzRw7b_HELP*kp~Q%b=KdCu*BeokmfglQk`c$Z9oDj;Xe`8f?jQq+e&i#)poa40X6`fqqWs?+~f{9O58Sn_d?I2d393V>!w;har8X8w)>8HKQrZ;i{~bm;%dc* z1QYPwvEX;lRb2f{NAe%<1n2G<`kqkn@H3GQGEo0I+(t)fv@$zQr5+(bSFmlVt&zX& z61`^>^9Ngxu-I%Pa-rL7{SJgZvzS_AebXlWG&GI0TN$1zEKnDQI6xPCp_UNX#xs+@HDF>B`G zhTQ^#>n`^6HZ=+lL^0FJD5h$eojLP!!qMb(Puab`1TEva0tWGfzb1AqGE04b+#PGl zV(6aJ*B&40?N|3QdGeGJ8H`rMktyW-3|oU|h1hiB1t#v%y$pM*`7p!NGppQt%i9_L@P^QE!7kl`J>->c%sPY!+gNl(p; z-esy$nVuJFW;}QgBdhm-=$9jpI$R#CD7z7R_$A%DeAhkkea*b9{WdbKCD6k92wtA* z*ZNYE+i~H`T*^c!HYdMUIMkPLmp(~LRcKGhld6shb$<9%VX|{wkioJN6$Mwym&%hD zdS{vH3>`DR2S@7VX1?p>lyCWuZ~9K`<5mYdE-@?dcDm%r1GH`IQdgR+zJ0H|5dPgn z($Ptjc}Yr1#)kW6CYAaR#SW=zqcFYZQ+X`3TAa%A7cjDpZBsDQO>4Db$@WpsnXtmo z3q6T;W;QCK0A{M81rSJ~?4I5A&Y zFK3_v=e8JSOXz412uhS5D%m+P^w{2UVa4_Nrrgn~bKMdtzH`bsyAGu3Jd>LgdK)Pj z7~?UQDl-75pa|x)wcC5pBZgJJ*CJY$NIn4DyD+16A_x{kRL>})LiZ1mea9nNb2ZzX z3CWJIY?7}9>5=>EgPT^w?N&S|dg!ZUz}OS2$zKILd|YYG?z;5JDVDh(+jTrKuTMSw zbjUF?hHJL_YMW1bPx7YG?u>koQH5W)ir|CCO;a7A$4rh5%jj%8<4lBt~`P7BzG_fufhIT)4nKw>Q&1pR1OYhzI6iaMeX6D1FD1*Ros*(D= z|2HPl_U4QpW{Z}tPRq2W#*>LCs*rh$!*&myF|Vc4?Wgjb!v1PkP3$lB%e=j8gU60$ z&1^E_V8Tf1clfX2>B=$+?eOq5x54ui;K=XA9HkXQ|L7_#;*s`jit&ov?Blc}$g;OJ zDB6F^%d7Rf?7k~}UaE`kC}7^tGbAuF#{u-ds-xoO{*^jHvsY?F7~X2+6ep}@WHiOO z4H_;JOG{q}lwjbcAV%rAWy?Ma^6W|CjxY3QDk}FOqZ7oQ%*c4!kjvc6jJPb}frc~y znbV|tr=`?$Nh(RL=~`{F8g>b6)({K9oO{2{7LHmIBo`2yA}AQRvFjlh5#YP~rl1Tt zC|R((B4`E~XanHtFF>*YwoKTxrk`PXa7Y*SZW4xWkCFnXU>Z)IZ`u@*p)V%(i#Jd; zI}e^co||LiK#|4VFtqi%5&c4+#J##ay{snwYLbB;#ktFnG}b^GqOPH_hnM#r7~sKy0Zu+)2w33v2ah*|oQyUfjc(~u>nK9PVo)T} zKB38TvFBbJ9~~%i60K)|hUlc|7df&T8#=trmI3>?4krbY>Vg0R`_Wck#lR1j43QxP zUUywyVId@bcf-TkP!IMVyyiA3`_&YXT_8Q7zL7C7*pBE1NIr0UOVME8vZezB7mjK| zAWb0JCGkTzC8wmM)OdG**`53T^`VasQOd{~7(}6QL_6FEm#GC_cp@p{djf830x|(R z9N)mp+B!H4K_@Asc1uoH_L{A&e_x(9>$;i_Us#60?1d_6fRzP6*0#u}pZC1{2-H6D zadBs8$7~Hn-c85z;+C_lQ2m7rvSxOP9zgntqN-~0W$mu~ClJ^0PNM@3RfVSHES~cY zf;|Xl$meUh4ZJ=kpbn#Wp4C(lcO;u*;Z9G-$I12G0O!?_QYdhc*nmr)(45Cz>uDJp zF1^GX&Ss2WdBkgl!E!!Av?J9RgJ{>d(*vj8U8g`#p@e%m*E30YSui(fD3Gq;EZ1H- zw{cj$<(R-5c+XiO!+~B5Z|vMq7Ea8dM-6f~7gLQ0PcZc zthC62`V*oj>3uZ!?FfD13ZKdTexb`J=!+gHHa%WbA!Rm@Uvnffo5$*8)lT@`HTyQx57) zW!;E?Byk;A=C*I!X4-cajc!C&0u57Vk+U$gKtk1br)3Y_|5kM1KPN3%byKA@{=S@w zIb&0a2?>xQ9>gf(-?f8-gJ-&{v2i^#g_cHN&f;(mOa%7z2Jp8;$cYIOlDD8>CBNy{ zfupRoseYWakmRoe@?Enjcn$u&f8m<+gP7AWih&jP=`8^hzaIX9g(DV?yD$f>W@JR= zn-BD*tpvaPfQ7=YKlMuJels&O)T7=4LyXZUkU=|=)z9+ju)GcsjcVME82X#Se%-#I zv0cS+6p{>qcpynEF!$I+{ZP53)miEWg(%7Bf=~uYTMAlQEdOU*!;^>HL^7_C+QH7w zFlZP^l99jvnT(c8rlyJNc}XKs8FD~?mlPX&6PXk2;^I`75q=Rc@1QtI5m%yy58BD^ z!rc41cUxL|`rwBT=w5sDLf?vAbyf;PM-ziiq%t08FE6jP-+jp^uuz1+pW{#@*3WKU z5qHr#s>ew?pLIo?@#%)gKYsdwYS%BkkugVCD~X~p?CA(WpaXG?RV7^VdUCJZJpMDH z2*ErW_lrVLsB@u1PGK3A7l`NJd?frikvgG0ks>ZGj@(UtriRK&Z}duOKQ0+9XIj0Q zL`evZv_Lq9j}Z4Vo+(7fn4o<_$hH9|5-feEscak^m;}#{xX@AXm^U{7Q6tT8h_pm%>P2g2Aw{9~;V+(fD&oo?@kN;9A!*a0+C=p-N|vW10xJ}uBw7;d^Ek1a zxd7RM5yHvUwd3HnrdV3B;HB=|tg4E+|uLVx(EJ|OQ)gaZdzI%K4!*?BrS{ZLZ8-I#Z0I^K4}Z&LA4 zybSbd>dXH1ZfXy0{`EML1&;amSIL~x{+r6dd%mT6dCKH(=8dd05(7-$zb+wOm%ESs y-!G4_P$%z-{8qor_YXRzsMWuQ4Ki;eFRdDVm|J{>;yg>iFGYFP6VGHXc>NQ)6X{d{ literal 0 HcmV?d00001 diff --git a/nav2_bt_waypoint_follower/doc/follow_waypoints_with_skip.png b/nav2_bt_waypoint_follower/doc/follow_waypoints_with_skip.png new file mode 100644 index 0000000000000000000000000000000000000000..1f5698841a76b3ff871c2b624b09ed86a8cf9409 GIT binary patch literal 47444 zcmcfpWmJ`I*ES3n{-_ID|_w)VnK3vxroQmsUj~UzC<~ENg4Rr-P910u+0)eNbD654)pkpBrXqH%L z@HYY~QP< zY3qC6m}Hp-{vJ&aW_S!=EQqG(dJKsv`+MC86^1)D^q8A|vbMyZWYeRAMOv9DXgf&&K8BuXJL|>g2ky#5&X@ z(krl)Z0*d}tIV0RA`?@2dEwD?g#X`s%WvVJr7$gO+Y+S=jL$UAp9+DuzK?Mo*KiHL-pW)K$VCkHs;Rv$xdWb)@E zCNA&oi9g-{t{h%xJ51e;J6`+{({;5MY11eAt4+IfDl)RfftNSm?_+OoiDrSkLfjo} z92~aOpIejVrY0tAb8n^d5(d`Xo7>pX80hjTq#n*)yQPasMU_1)apnId=Jr4;r>N`q z;4KAKR@Uw5s;kR?znCB9n3M{B9UP>7@KmEzMp|0BzpC0}V@O#*QC3zrT1;NYyzSp! zD;}lb16Wvvaih+_bfqag<-_BznfB~FaBafrXW(xE_e~*rd&r+}P zrmn88rsnp8r>;dJsXBAmxVV&Jes!_2vHOCwwAX@FnX<&5dH?tldwhJnyR)+x_|LgM zt^|ku7E;p?Rv~uJdA1G%k78$`_3vW)GwD78iSzFp8ym~Znze_c1qwYew|{JG_<+%r zl$6+yzx|pm>T`L1+Ex7N1)eqwu}k}LYHf!@p8`$5?@R>DHsH*x!X6|okV`Jm!DC#)%&h5vS3d8qI zoSYS1MD2eUpNWf$Gchp*{QE=2Z#Po!I2|^W)1N631fQ#_sc}o=GR48cadLL_NzH#RmN*6+6&tEvvF$j&u;*w(*-U$D8k zSyGAo4qt0)UKeM_o11oOY;X(0Cpr|9+;88$MIB*RIBw_V**2WX)j-Xo}ON~ZB2ExM#t3jH0Hkh!{e;<^pcLRU%#rUsp&eJv(nLZ4GmSE z;|vWAaU(I1nin6b>C1e;_G~OIYaaE)H8{_CZ%vfGbC7v)(-30CM5*?tPoKaCr1K2g z{R9x<(wea!Ngr8QSlHW_78j@G=2o%fJ_ai|m>%YwpKj#hl8AWkGzDD+PRe|Vr>Xk$;9TE4 zplIswjZ|o|E$Saks%PfpaQW*THv84v5fKq>3}w&N*=v{TIM~`wSDAPI=!w@alQ#6; zo$U@HiY&=VVyP3d4B6C;p%B3NkR$f2j!JQ%=GosppGDt@E2dkT0bla?Q85-tME`&F zTVf964L{$}(a~0)UsK-1UOh!BX?0X+{{{Vgqn*RGfnRM$aSa7`>GE4-AluYYp=(kx zCo00u1pI#6Ib%x8%94D)^M7~M|JP4RHc!J&6eGXo@#jdSex-?K$JgFo9)A9b@o}O> z<)SfMGOqi=!uG5pbaZS)J1UOUq?2?Q#hQI=ZpzMD+R7R$XD( zjH0ogo}PZkTa(q6G8JKv`AMv-WPcmQP>Z!#TQMXmGO4D&NqHI>sYs+66KRI)=(ybx z@Q*E5mPnD|)$*qZM|OBz*)7!L81LSd*5epBqtQFp|@dMcF)YuojepQ{DC zERiK05H%>UW1E}KM??X}=xMQ7Sj3T+{}>>kn)c?X*BV}@7mL^%^(L0pF?VH&-8_D! zI8q|Sk!2@}4+o1toy1T*v+@o;7_tBuR{nIHAsmDA$Ip@Qr3k>|zi-83idnDd+yWl4 zuC-uPyS|u181R?C9?EL08)04sQQhLOyE$trD-tMR4tGpin%`AK2-r|je?<}*Om;+yQ$1O_rE0T$$ zMzYszYczbBQeQ#U94g*&-|!tKAuOD=E~aWOcG< z9?2S|rp3+k8#GC4Jy1#0c{Y|qibqeW7&|%8F0X&l{JH#zPQQ)dR;+wG`xB{NCN(NH zeXX^!Wnx*`$tW@TLL2*0goR$)fK*QW;C;lTP*2HSOv5Ois!Ceg<+4c;qbHXkJ;egf zv|<#G}eyz0zi^bxtC+HKlH;Tl&lin)^Muu>Z8+3Ku<`T2`)?`QMHm`Q4 z6C3fTV$_>X+J}Cf0x`p{5K;OxkjlrKw4OLL28%tkY3j(%0>T&9*VVU{i^#5ag?ygpTzf@Ltjp5d z-5y}aCpGwz?WV4;2$k3gCs90F0{M$)|MF~g4(i|Bi%QHU%RGx_R6F0_!6E#Vkc1{P zz}8|P+{{Pp{y-#Z71K@>`$g*3--O5#QV1-w$!X8$C-N=R&YfiMe0k6QG!R|zYjl~| zeH_J+!Ooc)KY2t#77n_HqUUmJ;Y{&MX-ON5zo7+)kwTXm5w3;rV`~1{q&X?_EAcb#H935Y6^a{qSp_^{UB9sgD*j{gLA&H~jRu@;47oZDRKI z2*D!%WKz6R-k5hUmEUF3E{ngSev>Egisr5`q3Om;8hb*v{&b6pRlEba(`h=zAPnsu zD_`AG#>aShE?PSr&85MzI}^U$Sxm2`^P@+y6UgYqF!~a!y}94tLuyuh_#9bRYW?z! zEkcz0LFe-mV=EU0bsWTu-4+^^x zFSYatw20|`2*1lDWv}x_4_;NgU-xODeg6(#Hd#xyP?H*}a;&L=doL~upBp-`>pEmjwS|Bl*0 z#r~X0y8b)$K*1rd?)U77TLCwk?d?`Dvq)D6+S(BI!xrldaXVO?t2V@rQlu}FaN*Js zh6jkx-A}DT-JS>&;~;t?L)#<+Sg*Z*F~TQ1hW_9_PS$$0gVt}&@Vr!y$q<~X8%1JU z=6X>NIt_jhpkKqLIE4!(QXhRI;91Dy73TQRn(_NVsTSAE|6_P&R*!EY=2Ax{6}HCn z)o~;KKsYMF?H!P`u5C}VsjHMc!#StiI!UyeB4DrN?mi^(hfVKp*N=I zhj#Cj7CEAj_mwDs)NSmDVhe(^7Xf+*>#2zm1oG-Qg(W%A!qNYxBp3u960glm8ndxS%f9S07c?qA|Xes`64VB|OF*=mFUcoJ5 z|H!<_v!{8@X0cL#;{9oFxXfQ2Lk~b2fQ2YZ4?jmL$^fz`5dkve|2K#K|7Z07{ga%- z&*Ofj?q(Yj{i7W00Va}(D7=rmyK*jbs*<6CMPz!-F$N}QjedDObFP1o=1U8qw))rJ zs7a3MRS5;kTBV=N)-xO3tT_Adzr@1yzzEtUdvpCL`1xfg?DS8T8n!5OZ@(Y?blfr z8QPxRUBxC$N1wV3jrUgcbYonX(TatvqTIZ^S}X~!1nSwJ59^A1RmjYl=Ogl~?fCS+ zna=Q6xn(GvdAMDuelsnUCz+d+B`RwV7SD||F1>}E#Cr`{|7`*0RSHRb!Q^#sYB|c( zKI!QGA2Qukf(T-3`cunMg<6dnUp;+)3OxzF|L( zG}6m=@AESWJeQ+C@UptUdSk`WkcHwDjobb037N3A9$GD-h4B#~eH7QM`e({3=~h;O zN}=dT#nzK}x=G?2!l;nf+N&&SNnQAb#}TVoU5+wV*D{omS-bHLM%tbRi|doy?&Bj? zEGEy;STftKcjMy5EjGfFdk`Aw5rv8~4YH{>GY(w$UVi3r8#nxBT6YHnQLACVAJT!1 zbA)_`J{+2u65QswscdO?!_kL-3r_}@K|*rmh1Ewa+lSF#QUr?3GkdT;o5=ZbFa$@T zo3xO`ZtFf}7RdOt=#Mq_D1kigoP#|5QyypLF~oI5*VX4FJ~@H#xe}Kbi_wU?+*AbU ziNtX`#FE$O+0#Wnc985C^P)AZ6-LA!2<-PC~;W*y;^ob$0$-MrFqLWt67+y|G6Y>tQEkKkP=yke6VE;o7z=I7lxf!KJ)Bhn398 zuC{?d=u#(~;^BM58$*eMiS?n)17WU8>3D8H$%9W#OjvWyPQB`~uZQ2EHBKN6A2IEX z3H^6Bmdhkbc<13z{(^PgofmVWU}o_TW%4ACJ|af^c}$+AiuWkyNseGxf05Cr*isi9(kmX6&daiv(EEuxe+^H2Em8;I4S==aTDMXo=Yru_Y=!%w-*%!9MZZVpaX zRl3oT8+;hSi4Ev}#cZ3vI=!d^06CimDLy3D@N_F^kp4bv@_1 zlN&LwQ}a0R?MYWr*8Q2}+;H2pYj5t7@lJoAZBNG4F-sneCc_DzSyE)Yx5=Emf0%Dv@I5xjXxe)-#&T%S z2zSgUZZ5_|^dwTF8$Ub=#Jfu2@z9DlTzXf6x!q?7cIH7MKUE}ARb0T`F{0bt(iX$k zn#3(cqd1JH=#g5wiKw*(|Mu}-nRho?3VywsW)G0<49cNhJ|1>I&S8DuijMZ^+Fn|2K;kK@=bVxQHilbYpzErpM%es`oCdhgTr=9f8_{}DQ zulWo?d?^B91$XQ(E-H=U;qYS>ljieHfJI3RVOsp|MQXmE2XC$GnW(~%ip%H zP6Sl#`96KI}og^&A%7w z{VRXXwI-A2FJzJRM^>@|AsZ}iA?owa5U-^0sdHte1Q9chZ0~=pPEsaQkX7(m&uQJk z(4rFc(DA)#ru2=ku$;iLG2fjELVwU`X2guSm9;iM5zE;wGTSd9B+g>1(9SiBzF@xGd%uLD!wI&4Cqd7sSnqk)wfp(#mt1u^cHnslVJ7 z*19^CXH6YFSPxoX#%u&%e~b5h3{QPAb5RM;I^#E$_hVeN%4042(ZBE}*eNdHZZj82epV&k zF5bN#8EMAMwXb-ruFf{Z$$m6WDziNM{&zgxW!DdF#K^MPOr1v1zb*Bk*mI5puk8a@ zJ50oFx28IriZ35(3Qk7*sx;Cu5!5c9z7^vPmD7f!X-IxjD^8+w4IuIte_r}&I~H*A ze~p$N6dpph;JP(_Z)}@UKnA7wy!j`2--~T_#cX%C{OE#tZ%5V%>+GDU1;fhHiX6cZ zM#2dB4_SAu;!D>^e!qGJb~)3&saAz816^4l?7K|L$yib|vJg{_F>0BoPFCxBa)3a1 zGfQvf-aGK09E*6QZbk`iQxF32U{PNFPL6p*rTFXC{L)SXS_z_fb)XX5wJojUA75B( z=*~Wuf_h*)&~+;k6;RRrUf6BLzsQarVr-3w=t)50ipk70hWxv`d0X!zV-o?fIm3(P zkGzFFlKOzPm&LI#)+y>Www_N5(XvXv8}YfpAo7$razkjunHnKW-CZDwu$!Xc5>HS} zAjc4W2#A@E55H0jK=4mq$m9qm0*hU}^{*U*-F-J!nmJ5HeMxJR+%C?3zB;5P-=MuugE&JHIRNB|E#?1utMcAKgQHc_)v$onR8ytbp_n_(pgIE@UPXd{*u>6xiS~x^!gu0>@)P>9cpR8Pc=ld>cKLi z;HsM{u7@w;s1Nx7uEbGUIN?fOI2&S$_((l|z#y`DA;3V0h&&}gtY0Nd+0xS@I3WXcU;}Z^k}t8&F2~^ zN;nRe8^uGB9WhLSJk=$?>(h=+%M;1&ieadozj47qe8r>}YzoOzk}V{GhS*ky$V+Yp zk%Y{<+y%cKv>sXay`(u=!DcG8uW6L-f0c%f5H9U~^|9#Ls3vJ8B7qp&QE0~ZgZYnd zBQ0lgNmaPDZk9zefp2eeExatt5SALg6@?^WkYA&*nWtE(U z|HiIl=&dkyj-=K7*8vH{T;5dQ>OLIZC0?iJ#=}@2Ni54X-F+;$6B5ybq(s}OMBJhb zi5q`8DdfZD=R8TQNtW>E=405AhS;6eF{$S@=N8?1h2dy3X12uBS<}#>)xks))#z;1b;KxUWiqMd`;eBhNH7|7rcO z%2kf-K6FnGdXs~Ew?6LS|9`XqnRJ(ORuk_eAU?R>ydfM(5T30tN=q91#x^pHhu;o8 zTv|2V$@u#>63F=KwKMuUmtQA@q(TKFn{hTO6$8-tnB9nLH~n>!f`$1Q;9=HTeh0P;EM{Lm3o#rRTBQ7s~b z-45@m^>&e&Xhb zSv)1AViSR*PtC|I9w8OO3wlxPC+Pew8C(ml$DO?~pWZvV?qLX&x#3jd4Vquh3eXBj zAJIZlQ~L0hFHmA5&SsN!s0L2(=s)owt?{WQb-CZ~l}d|ioEcv^=- zlF;{&26q{In+BH%>lDoO@kbg7=#+nJ<41QSMY-oCf~!NT?eP(B@p)>coUm$>EN9;s zXbW=Q3c`#>8+C6o$hW0@4An3ixRpca4PD%>gJ@!ad|FZXtC=#Va3D zjIO#}%-k|DL`OhTtsd6QuFeUtaV&rT90ShUi?8s(=TDLkTG7JqV5}>?{QT)h0tKyI z!02QccwdWj&5)AD-U_&lj5ye#_^meT5OX$|?hdeZ zLK@PaW+b>*Q2C7KBLtIowX58qF7U5McMbTZx82~#KAShSQz3GeB)#dh3SPF?yO^#& zS8o2P7=$0cyz-8fiq$IQySRqQkfhQumK!aPM~HTDzBCnUj;Y)uiF6UkeC_qGo(HT( z0&^ek@Jj7d;6?Rc1&1+W7~z9S{{2I@%ymaJ@AOuUx?$QauWQp&QA?VK=$ncI|0+$N zNiJPK&446aysA!#$LVa;x);Iz>AZ6ZytS1iO7djYb?vl-P3 z0|f2RO)7EE=eo-*7jRGS@dK{PceNJ_Wm3>TBEw(!pH|a%4GK-uqy6jDxj=d4Q(zPLbp$zU z3=FBe1k7m8)lA6Zgs*fu#&2&a$p?&e4|TV#px1pJFFhP!K_c5Zz!9_Bp2#=^qF!8!Xg=VCjY!@^#p76YJ;|8c+j2oN`mpTF(oxZJn|NdqdmhNzUh&R8*VtcA0Tf}Q@ ze7rUALgYQ2+UC!noMvq&=ch*?L~@>MxY(}htfPXSS}YLF4viBN6CgTJ&v|f4b9K^l zdbF`HKVL_s={yF)jPKtqf`YC-hGGt9@G%Ps>CeFv>~BYmm5{djpB^^3{iv<24Ln^- zyS(`4DEivSX*fr0{H>aYxA$VrBL!GTJrzDOajLo}(xIrUtE)Sj?C<7ifm)VeUS8hd zOS4fB{Dg#tLQfM!4z-WJQaDG*$QBCh@aE5M{2VX7cI_HSRes3m>Z%CSKkH4PmAE`9 z0NG3f0PV6Ta80SF7k`(E)w8!YH&5nVI_vGn<>7dwKtF=u=2!ry+ak`S1-A~Qm-yc?Saej`0f9JmK(CfCg2dF-&P5|`c>OX;; z=1UwEB_-v*@rM$4R3bX?D{ze)pIm$oB`~V9L+Lfvzh*g#-l5Ci`T#nPpTs!bnF5X? zURxlKAR{E~dRH>5`uhICRE6=`*%@f4e#AJ@l`%uujU}a_k+AMfcqno4`)F7~BJlhv zw0Y~PG%v;qm6G1u4hR1EW(yJb%KUwZ=n^= z-ftIFB1FvU$%+iHIFJ%edfx{ug!?R}gsFdc*u3qj+tua8v)`LY)RGjp&wl^(`1fZQ zKK$?W)JVBhfYv^O-qt6oBXR83P;6D&)=%52TMx;~SKer{mE5l-UClP9zI5s{l~s6Oap zI4hLgtm+CJ|A2;u`hS#6v-OU} zyOEo^zE7W;bol$O4`%Q^9wZm@^K^Hw{qF*A-%&2uBBh`JJ=HC74yaxBTSDm zZU$i}nv8o7b9=H`D9BrK__ z)InBGPA#2h8I(I$=Nl3mU$cq}KE2Lj+yA>11hM~HZ|^4Lh25!&ER@m$4R)N#&Kx1` z`dt!?^2f>w7kEg}rT=5O!YGKc5n$I&-)cdehq`fr>p>qBwSRT|+iQRJcLE30Dky`4 zeLP3U#JF+8P1K+)8Ki@E#QmR6mgz19{;TNh4D$4>gYD#>#Q}+84KCPuemDSu*xkb; zB^;i+J61FR630UbsLl&5lb=7!MkBR2850%Z(L}_=$q5M~py-0Am}qCnkbOcnQ#D>jN#Q^Rd#%}Iv0T3j{*N9TRe}88-nx|;O}2YNsF9xhU-OJ@;~|-aszkOy?I}cE|Hv^ zeCFG?3rMu{bI;8pK*;8^6!7veTWgVK$exp-tmgO88Txkpjf zi&Fj|tqE4~0QssY6RxYh)?cKYMyneeWYpBuBqWUIw8_dv z5N5K3T&BE(Wp!*1B4YcKv$90N?O&~(o}O+D=bE?sc^yZ{9*4oYH*$jlm%GA2CG(*sN7JgVyLINiMv1aTB2FBUHe`!}epB5G_zQj_3j&YKdWReELpqZK3?c28* zuWo^4idxL?ItGR^17XEyd08)Vh$O@ysD&Lc7T;20AQTf5LqH&bY_w2q8T$PBb3wF1 zk;>|7SMX+GVd0{;>#!%tou?3Dj4z%eHM4uD>DjvB#sjY|eAez}>adYCIPU-XLk+eF zF$T_|WD-#t2ja_(lY<}EP}<4*%7TuLKv&o5;$qw57qE&uMD$vX9vkYGL-jgrUx$Yq ztEvqk`6^>Wt^KgQBqqFR)GQ;Qs2?xp$is(;&TjX~IQ- zk1r0v1D?D$-%KB~k7Jtd=jWH}f7sW!6j;7X9#yi(l1koZT?=YG2VRP?7SII$+}{3o za&rIveLK-qqrUO+@u8tT63WCrYh6Os1<+u5KpyD?nexuJ_sz}CU8~z5J#`h{@#~tO ze|<#p(+l`Tos=>LUR26Wxvm|twzjs==6eKkY_OR$MFudbb?Pt2QYq&bbZogObsJq7 ze?UNh3+f9j##SQWOou56i2ZyvlxWI9NMB#yIYLs_3v>E^bmNot)CI863iHlOP~+la zVQFyYf-o3_(1@Fqf;$EA;%xP@rPbB@04d;3n?ZL8AsjGUMMXt~f6Lfmg+a{<_$LBjPo2YLS$|HQ2&ZWaKM&6>$z1V(4v6U}5GH#poxR1Ytfcg< z#fv={lYqJ;pbn&Xj4G)JyTvwNL&gxeSO|)~fFIiZj%TYaKS9bl2H+KYn~#Z~-?JMO zs`{1h%IpSkB#G8c>`&K+b2~xji}Ud8->*)BJNNg8vPDzy-r;Zp#sEF`)6#$NTYtN6 z=~(^lyt)|f>%+Dw#9dxqMgVlvRPQ_9p57SD7zel&ODP0yGB-1$Sfusr**}Oe+-7a$ zx)=1O_Yim~K}A)8W4*m72^}S6R==QGz1i92Ex`7#Taw7-WMxeNUV+{nkzY{Y;o&jK z78V|^R5S+OmZnQcM%HLIN(Uc#u0-^SjtN%?%9F!Q7^jsMTO`;IbJR8TO*L z;PKpBy{p?0Lmu1O5>W7CNdka(nQubgzFjJEorsJq?bWL>u#cc>%yP$jpZ!xBdcG zThDSyo)mOhoCh!iKjAW}Q)D?k9N_+UysfW}Tb9-UWfvIZ=JvMF&oP_XI(v}cg87Z@ zZ^Hz4lLAzijD*lR*RP--gMR#Ktb`7 z@95gvghili+bKYk3}cLAA!jMIo1i9A?KGsnpl_xsHv zAt3?!J}`bjWQ*@@;~N|Q<_2B*f+*N#hSAm*P9^{rlA4+dMcKa}@e&aB>fkToq_1r* zbzXtI8_@=WP(Y-l((v1+AumqDX#s%4GSn32#F_$#Z{0`8&0S?4cxnUcYRJjipx95) za5(e=N6?LGNg&^ysR5mO0sN?I4#4HLNU)U(?d8Gk+VxYwd*A-vfMPNv1Py^wXE(VO z^NCj(dk6S#fkgu-3f+Ehr|p9Fa;0$@Zk-(H{|)R;JVn@tn9%c=!at% zO6M(*3dPVW1luNZ)9sN+05 zj=)yXA#Z325+ad#6f=;6Ef%`2*^5<5^(Qet9avK#mI z_Zxv_Kq-9;l6L!Lkg7u{^gH@01n^QuK|ulT9dL4HW@hSHEGj;T*NgMMjE zzGOz}mN!%JT5u#`Vb>9O6#N>FLH)_BaO{^*%7&+go1f(do?(9gNTTbA6KZ#GaDad$ z1t6!eWhJrtcGH$8T|I(>lk?g;2)KWC=cL!5bSg1RW70Qruz>3EAB?}GFq0@J=i+1= zG&D4nJ(nu#*(}Zte5J?$KCb7i-D?!qt`0RD90(N|+28Y1kL7WgggH4oWAn(wF^0on z4nFwNQ?AD&D2QQeMugNnE<5&!5pJl)rMS4br>AFbZVuN4aB;G|S}9{! zn4{(Uy;plno$+MN(k3SJAh@Txb7$i56;|hg^ozuVglfQ+fYS!7YX=8aZKx(?CeVQP zsIIGf0J8uvox+f!Eb6(*^LQ{F5R6?QSUW^QE-o&ch06VXSBR=Mn1p7Y_es^*E`%~Bw0BO?V0@nvEPf&l!|)6>DHaiTPV4sdsOhe(`4qMTZ1H@dRgmjqy` zC`Zw2Mny3=nKcb$+UBj^YETc)&56>|T0$+2LIr_mFpN>0Am)F5&;u2WHj_LfdV(SY z3~}7PXRQcy1b|bhicw=Y7Z82G6#7z9DbmXT0Ymg*QCPVSm9w|EcmGfYILV}lbQa`U z6j&W_AVn1e*REq?Lb(TlbnE@FILN`LtHS{dq~0`UN)ih=OXjPJ0)6x3%4bEcv?|lq zKVVVZr=IOuSup3KYHe)|c{}ghSR72Y%z?kd9iyY6g=tdj!o}!LHNJoUDH_RA1RM)J zBcshkiRRSQ6ogzQRaJ=Ol>mG9?ZF|QK5c@G!(-oKjX=f!psS93hBQF;P?Awg1h#>r z{{HRxwW@C71D8otHB>4P48G0I;_y}JZg8%xu09Ajo9O9LFg!dtcmzA_$bYTL1+x3x z2fl}`zdA&p?px%2URYRws$-Mo@XsH;-OaM<8??+SFgR0D4f_3X>5tg*BrP!E1C_9@ zO5nw@zOC&>NeRm&R|^zWL4)bMMo|hD*47g+vsS8I4ELfZLq56w;W_%%-=M2v|MKEu zADBK{W3$tKtEw62+1k|PG}ln!Fl^>-oL9ToSq6-ozJqyz{(M_x$y8~#M+`oVxRaC9 z&c=rRA-$!A;_1UzvxOO2DiF5;@h9ixT*7@q6)6Cff`r5s+_6GD^~L@t0=R;y24`bS zaSfPbIX^$o&(CjgS;~Rf0L}mj%WHe;^z2MMOAwEniO{s|DX*ZQAUptSD3vrW7+%x4 z$k4}y1hfLCjp7~p`uh6&TU?jB01{0Cy|%0``-z%EefG0BS3Or8rq*tL=1QK*kp3TDtmjmgb6tt&1gqzdu*tAH5ZsPS%~|E?q#TMQj{*k z1Ow(x^1Bc2PQf@3xD2aA|JScnJQl$wT-?WS@tEG5BT~n#2k>7gMywZSy!`>#26S}vA3uKJ-Mk4PkrxO$@qjayN4GAOl$DhUQ;`l6 zC8IEVc=N;5)PF8^TN1(@&^3^^tR6jr@+158YuNS?I4=6gzH<0g8JY&hW1xS3{uBm^ zkANV)spZiQ13K^PzbYGnVEw2W3UQZ z#`krA($B%P00Zm%Nh)2eJTz8RSHFbGDUY@O6tFQsoCK7D91IMrz*>x05LdlD`2Cx> zWzVb|pc|WR5KLX!+uOs8CGyqb;NT!IXFyU09Z%|a6<#{LC5^WLpav8#E-43$ez+V* z)PXTUg%4;%?{w@fKt{Msh?O<_J|@PH3etg>)~ArSi-XO)1}v53(g7uPZrZtL z-z!G7On%nmzEJlV8VR#J4PY}1x-!A?aj~(5{eG9+!zA46gg9OO!61djm(&?F>yvLt z35t-&m+^s@Fw+-J%9$zZvj-`-{uN1H9nu(qD$_niLG&|<+B#-E_Dkvd^od;*EhQu4 zHW5+5^7YnNb2!)sB~%?2AJHr|W73Y?v&fK>TJ=v41(3_#1bOe@AH8B!fhjsbQRY(& zuW)>9Sc^m4G4_mI+9v^J!J)$VCDe^R+f&ZqL}mZJrDU=IbH>li3>Kh3o{jX2e{+xB zAI6N}WHEK*8&g`xJ+~(8VRLK0EDDsU*0_W+?=WgS(WXyPhDk?J80rKFr%&E_Io)~5 zsJg~#tG^Bx4$zZTVr;do{~rpHYZt3u+XS!&i&I`GFJ5hswpqA>WNT^HabEF~Us%Pa zvlT{<;g-ej-Mc3$3QXyC1Wn+`YCK&cDbS=P-b8`vD0qLc(tQJ$G&zMtw~1Zllq8wY z6^f^HfD3?z0c-idGNGa)>YrTEyySsd(%q%bpoJDMC^+@-1)XQAQ5m#sQvCAdk>y@= zt!%SstSXcCo&^d@Y57!-7OEE+$sag7c>h{lfP{^TZd_?V?V1XIG;A`XqN19t|CkI! zCWPtarAVd?hyfL@wt7`&oP+74Ph3i$9VcfdVTZHpz1!DC($H}0um_dXsSRnB{@Q~! z15l}EF#ZT81@nKLIwkwCJMaH?hl`5~S=PtX6BxB+sK2i+eg&o7ktOoBLH>D(R0d|v z6HN^4?vJ>B1M3Rsy&HfWz1wlTvLGRNwvGk09wZ_#HdIWVU5_KAbO3b7r;fC|ocQ zrpd!`cJ8EKJ4I<|Xx4JWP_xV<-{Yc;|5?;N^r-+Y;h!~l3+Z@RQ-v{2|H-sIBf&Pg9D$LT# z+e~%bJ2LM$qzXYfFynRMFzd~ z|7ZcA?gCN<{DH09#@ZU_R+Dckc}|^xGNcdlI5g)z${W;{ui^`4P9VLTM^{T~8%m?1 zqTJlwwX!uxsHpJXSbloJ_$v$eB5ds2P;tx(q|!K-`n-Jy32a=mlqd!bkQP~{ldjIP zA^+7LIHHa=qg`9~twe92Y0A2FHiA5NXT6~91BmMsxWr6;d-wxUo_cs|Etbk@N~g6B zz*5LRkhgSj0dxb=1p&HhCyYgSyL)D)2}~D7VMDV6>>#`gsETmuyqH@bAcrKqdIjyZ zeAq^|yv8NIAjMSaK8vNOb-l9#&|s*oZ*P|yu@sW^wNw2LDH+pMJ*q+`Wh_6 zj6I{u)W+_{w8^|pOe5AP$H_nSnTB$=o}7Q)3dG~68OrEVu`E=5MMIPO`t@rF27ouQ z!fkf@?^%70l(;(APQrP55M8ck3&9C)!pm@1E0=_f+Kw=%h7e040kCHOD+q)6Pvwgm zMDfgaERMFk*dCNk{O9zsgxS1ZugUYsWOX5pzE#UY4ONOPsU+C}P{5H?6ovi}fG*Al z*Yyu)YMIDWIEYa*!Ei;e{l9#PmxQCH4ig4$x!t^KXJ3n%ZA>`5~_5+XYE913*BdRNgiGQcW$S}z+yb4~$Ko1oLL{ED8m|L}^ zYL#d<^Fbd~z?2;N1_FH0@EXZs0-@4h4LC#Rwe8?wgk?yy1+cP^6^YFxU?dpckvshOz2R30J(*WjR76-^_Bx`|Nxv#Ocn z19Ui4Z;iFJ6wq1&h7M}WDsK`XOE~}(&R*!x4Uv*K>(;@mG}MOB-e@gR1p|~cJvQWn zBVohU?|AC~?d=jadz-2{2Ofyv5U!nOs-@9<2t)MlRpV{A<()&$1g&$ zCxC1@g;j#2U zwkON=%i9j%IB;WW#QmElaNL_s>gRUqMf^{yZ^iJK9xy^A?ffB?^f3pOwu=x=ZFyNm^* zzY@4#cyQ;%A7g>f8cA|;a!`u|0uV&#RTv$|2c65zA$22ygM+W3W4tqb{}|vW&<7pB zb-@b|;I{L3n_!;Dm8!sKy)TIw-gw}klBY2V{RcNUH~Yml;fNy>6O%Bd@#B~6?H9mw z*Hhg<+V`k1$pgW=1TS2Ges*i?KTPNreZ-_e0LuFh?Lq0_41Gb!B`;pQfOm@c!kZt$ ziwU8&0SMs+)k%ix`qq|+O+WD@rVzhoAa4JWk%7U}r%z+3M1d`mIkktIg%&KBstY}R z0j0dJr zGmm?vz)I#$@ADKWMT0g`i2+; z)NR11JrqBcoyoEX4ywxq1zo`xmOvwb0`5RD#lC!*2~41#9%(QX#w4VqPiCr@LEQ1^ zON=2<$Tn9BX6m?IzM{aQL*WJN^!D~PAikcm9uzW_)`56-1(D5Vu`O!sg%_0A`@jGK zHS7ia9yIK6u(1uHN?XI)EONeUF~FAs(?*olicVC1TO0A z%O$1@8a9YeV%u_DWa$!h=5&~W5vDa`;)QpeMRI@g;dF)ZH1rBl z+$yjZlanZFJ^+FyI4;5;$V?Ea(-)b-`d7pMpM?%e~6)+;RrKqv$M8qAE&WC3V1s5sy)Gw%utP%n!B z0+;O>NK{4FfBoVvWVN9x@@}19SctfJJKwJb0?=tHn2@i-G9+?xO3HGQLrSEBUY}4t zBqWByc(}759T8q-6_x0hFSQn~D>&Dmpx6Vvl==C2ph>_l%xYPIB7~Qz^kZl^z-8## zF2W05O2tl#=7%)s5)F)un3$Q$br~pmz#2V|aWVwb(2y@i3mvw^gU- z72@RNGj>Gz6kpIRi zfP`^WmgwuFsHk{WikQA6i|7T}B!dD?eu^6$C6QPmZ#+vwJX7&;TYp8o=TgCxBi-)^ zJpGWvXS*)`Ua3i#&z4Ex7{Ub9#ogWAgLmZ=mdYJUUp$_3mQ`0*Kk-m0U{DnUDirmS zkWIJ8?6B9+z>6~=J-i?SqBK9iq>YZ+UzELFn6&da{PT!30z@leKpJhjoyjkb3Ei{o z3QJB-h7^mq4*_fL8D_#QX~n;z%bz2^iB=aD%089-ZA(Hzf+#8~%1?uT3EjKNsi{ii zMs?sdhKGj%lSoT^G^$|e8CnjnF9l7}t_!RgIuLQKgA$D^deOi z->DxIz0gi!R)5XH$*HES?7;744SWDV3ScxJGkKhY<^!6b5bA!77sr>CZ9!mx3c=CA z0i0M`Mn-hv$+o~dljeJzoV#EKjEs!XAA$~T`hB+*#~9-Z_z4@^7H}S`uJ`ZY+d}LB z{pMZGy#S(Sh*{r1hU$w3{M6$l{!c2km* zUqBYt(&}}TIqA#Ebx%%C&dnJc8Hup4Y=Y8_ zRIkIT8xDja^9Pu1+&10PH?~(e*nG9Kgw@yz8=25r*I(imoAv?K17DnE$Fkdsh-cLRbyn~ z_nEkZ^z95a4EHrOP$FPr3>Paw=b*473D5Kxp44KHZ@@yGKXK4&VOXl!WU z^ZZ9SKUkHLX`g#(#S{UJ4IEb_-uQrbZ)4idO=b}j2Gp&4dytzB{`LoDiLP!!Lk^9< zbK34-cs93rVE?Y`($4n1YZtmv!t8jKwDaZ}_1k+E0ySCLA0bV23#(gJH@b$0Z6K zKDuw!k(@FvApsDTEcj@BX*z#rQZi+F`0d}fZSUVpL9EO91sMvkA_OXm{!tt<>M*vs zC`4hkkPFD?SVO3VK)rk`1b^K8zmM%Di^#8>`3)igF3z1h(jJ2UeVm29kr7~H*b=?n z-Jt0S;ii&SoX&h853?ye0Gs%h!UPl$V`imWp_B?Cp!Mf_0ZBn^Z7t%v?a6XaSPvyG zZEo181{wUu9`<0sJQ0A;g-1mE_Z!wx(zd+p8#A87BCkAGD0S2u#{#?kfzB zz9Jm{yl0giW7v6ZHWO>7k0L7%?z-LecfR3aDvL=w6szmo#OO@XO^HF9i>-KpeCc2WBRm95`y0rY!L-NJK)(O~ z)eE$iaeeT|QSaWT{U^!W$7r5uia1o#;NCq*Y*JPu<&lXxy&ErASR5G6q8*WChllf0 zv8soXf;P7r*(U3hCgFKEx&xAf^yl9VnYL~q>Td{Z28%`R%aAmpj4PYs@?3Jnlt1?o z)K+^~`sfiE-3Lh};)IFJT#S9qn2_(-Uq1L8tCHaE)dXVF{gePjwd<1(Jv*Dna0d~0L{72dpqY-ExxGd*rJI$V8J7M{ z`yQ&*+E`r6{dreO-}@v4uh`5LqL~xUuuZUKlWC4Be0=WL^GUJUZ~5+PR@$7K zcAkmq{<+~xwrb2K{t$RK#zVMPIcu z^Pa}2Z>L7*yQHRDTB_{iOxwTA8IFRadn$}^utcP!3AL&!5^vujj%)26z$_$@GAZ8K zwHs-zF{_CW3duKazP6*wy~u{(66N|lokZ+!<5jS)z&YppK(r1*iv9?xah)SlM2dkg z{kcr^F{ZmZ8Z%luu1)|+8`XFyBC`-XwlesNQf?&c7gHhapIgotpV!_=;d~9`A`6)( ziRRMR`1X>*#JUT^@M~aHjMQ_-ckgFyy3>QYq$?Qa?y(>$o(U?v7L_1kOk(QqK17h< z1|2(h8rK`B58uiC5xDS7U(Hje1B;V7Clu8@+Ci!FT?m!?*wTmDJ6sc3Mfn@s985WO zLGxDHAE)%jl~3!6)iF1Bkdd{fH2?M#MInjl7aPQqF5RD7CjN9HH^>r>dt%B_*b*BB z8+4U%5kKo98U#>2Fg)oEnYu(ii&t#k8XZDXu6%`X$+P-j#OH9BA@i84q0c6 zPZ9IMFAW2xH|Vi%&>rF*yUV9!-TIU)IdyZ%FE(WG;){oWxaVlq`#_!MEu~g8M1C30 zEk$Mi;JTR$mVR5Vo@Ox=-ZYw~U`aJn#21z@?QzG`x^`%A&wmY8<2pQ_;&iN|U|W=V z#9$)d@s`j`2a#DsVlIq$y?0?@6BUEzvqhMTLC;AvMKP&6m7z0QRxb63@|NMyBqFnp zFg{@8*XUb++cWeDpUJ@}>Y&eN8^t+Hq;g8HO<0Ad(ly9mNcG^eICZSki%{G{8?{mp z)9GRA_eu4*R3ysDMmUl^YghJ5ZY_^dW!k{Ze^bxJ8fb0s5Vc z06|>Lbm>|H^|3>X-NGWw)y7c*B|qhAMBB3&Re5(@8|5tPAMbrqcKpXxzZ7Aja~SO{ zobX9~Y4$OhegNY?qc>i2fzmO+)Tyv0_{vz#k7r(a{tTT{8ij`U?i3@JOF&>e4eRn$ z_6l0uQHSZ&w8rCanSm_@nCCa9C=i8T&=5W1i2Va@-+C;Q-z)=JPY;bt;v6-yO3=gr?K~ zqO$p_0lSE-=s6l$!YDNur(zIMr?=zfmZq|PGiF~)+UfW`y?#fbnI1NovXtOw6jGw_ z#sj^snkMIlWEA?8F6YwpxMQQS<)K}_5h_bH-^+Sh;_C{1fbjS3mA@z=NLzh>2V92iG) zml35fBkae2Pqm4?@4mD1KfAxj@=9F>)4ebJ`u&tE?a~6S_R6%k_I6k&^*8UgjyHtW zp&S(|y`ZmNP@JTh0!(mQ1E!PrZBCad3!)q`S8|W;+I)rf-;-goqCb0x_`>w!=p&+| zSVkF9MV$k$b}uCBGGo&YzsWxtN4F&;L>i^(zkr|E2x~B?dFz*^U>{A!d8D;l)KcX8 z1>cbIY(u6tVHIz5HV0Sx2^$)gp4W5MXnpJ9HfkuG!6N#M3TWIBFdiG7ex zD?-8Xbc%CfXr1;%)G^(sFCa#Ia6Z}r&%F|nDS~<8G-p*1wywE;$kV##zl>??cU~VB0S4su?h3WM+;nNXS9nVf+>Wsgzc#evNTN;r0>>dW z+@74ur28n4$p|4BnV~j4vL^cbulKMUi}nXbYneJGt#MWvnPB_fL2C7;(4%MJXXOnq z==}Nq%ln+slt>%+>s{$+bB(gH`2IgRO*j+BqbWAi@6t4pny`<*$|*CPcfdawe)i|= ztwWzACV}7FAIok^>DI~IK?&R|O6S$K59w>~+uI&%>EgS|-e9$`Gpu~Iu=Epm`4)`; z%VxFtqVj+ur{UR^wz{Bzk@A!18t|btY>0Qd??!ov}jkDJ>7)Hy(3 z=H)hx?RgP}xtt$atE;PX_kvdkgeZ?dI|zr0p%g(*5aA=U;6M1|&0~-o%ZdUe09fB1 z)T5*U1OU8SfByUd8g)b0KvNJ2Gj4A~X5W5UwgL+<>$ja6w?#vkPcSdAYcRz~TU2gtW9D;K&NZqxJ%KhXaP3BBv}Q!ntAl zXK%f|y+Paq?f^iB01Xc5kJ4vLXpq_FE-5V?Nfo|BMpl%WxwN&lwYy72KtQ{jiMgqR z+$UOGM5#s=7rh~|N5Z?~;{dav#1e*xl%)eS!AwK51Se%cx`1#xIXY4WRfn5~{}CZF zXfM!leDnmq$H-_7gmr*Ifsf`3d=xO8%O8pbL5JoEcsp22z?lID4DcF&1FoC$F0B|9 zr0r4l*-cI7faijwWMN?e&N%KTzmwYAuR(>s zQ(FMU14oyUzW(2{v#H6+U=a>!4-({AJB_i#c6u_!o>K9F$J2?^=XOA(C!K%QPUE5K3!Ot68WA^Odm@W~Ij zxg9_e4w%*QhcLb_5bppB3}QiOCTI#=-P|HWLy_~q`RRY70K%)!AgCG};|AasCO#l> zF!7&N&%nEDI%j6i;IIqi6%!K^iO}oJf`WD6)p}qa{2)Ni1J~!@iog-30p(*sVUUxZ zZRJ-@)dvnWQPF>(y8x!PuCfx=lKa^~UV|T9uIGOXCJ^`*V3M%}g|P9E3YbisVGkyv zu+^VGkzE5iii?X2P~U+%JG$#9ad@VaVYlInQEpk;?*E7e zz+6K#0Elr98jZv#;H^~1w<4l(h7&lSiUSJ=#0#Z_*F4m?h419ZE-&|nu>=JsOrjBx z;LgklGchT`Skj@x8xP7@nVDxQUtm;s&cH`L*3$YwEdh2tj@^b}5`FM!Nq7OeJ`U3W zz>3}7U6A)9rxAx7JnCKN?bo5KG~ z3$U}Yva-3E6ct5-j3;!+@8?ifSGN=p0>XU}m=KsS;5)PSce1OZ1lSHc>A^m z%4$bOjsVq$34OAWlTe)1d)6Iy&&suK?=XfvN9(b!I6kDGB@y z#1h~UkaNf$Ifq(UO-)S`afbh0UIO_AvXyo)$hy0`JM_sliNI_G9U07gm=s{`j5fGa zRa2u4&vl>+@n3O|n3NRI-_50^eK6MmsLa5?04$z7fG_aX>9U4~$p&{EK@$Z?x8*ng zlCm;n{Bh=i*|a&7SX%^gx~Rm&H$YD!5h#$$gYp3RMrBP+_$tTE@jO__wN+Kw{Ip7( zGSJPfk0m8Lf(hvT$y3F={v`?s(WlAD$aDc-59BqJNe00hV2q-kCnd<)?u2Y(`DfeL z0%l+E-Q3)W!tRlfD3Yf}*LRPO?nA5utQ{ai5Hpa9zx@kC_g|-kLR9d;qKb4o`E3CB zDsu8}Y={Dz0Gkv*@31b996>?}h85_Y=-5~%pdw*ahlk&VRoxWTI0?#Hicf|$STs&P9lil_8X_y1610O|1 zMEZJq(uAFWxsr#TaRY1D9E6caX%Fv_l3Krb0s27@?XV-K5Hg@{Mg!vn4&%Y0A<#>S zLP>n^@_@W@9`JYM+bP3(4)*tv9S%Z5aQxXqA$TC^mzPapxD`Dipef>k0kR$FG2k`9 zNCNI|US?)6wyHmUid|w* z@1X%o>guP5hfv5q5*f4I4-O8%LZYamVg$(opu~VX;!%kL$i}+cfN6~b6EgTINKm%X zpbLQ~1L5s7$m?M%8AG?sEzr=?GX3VCD&c(vd)Cg*4sb#P>xVrMaE5YVGvEg89jIlH z>|V7cXg0puzINRlXN335JaWPE@jp~D@-Oy**}(Xr}?bV1upG6|%-1Go2D7QxP$vInsL z^}vgRMi2Z&Fb?1;gCPtSVLEsOT^d#9dVTc{Ub3}i^IW$Z#8{4QZtYNq9N5|Jd*rmn z>Ohxubk|&fyUhTx@W7p`;W7!@b9ZoReCry4t|5F|ppzFft-1AxVUom(YPp zz-giO1u_OuC76P=V=y@ix(ZfTixcElx!W}{_qd@;z;M85 z00UBX+s$@j=>>G;chC)XZ|PRiA)as`ZI<9RG$tjX{Sg5mFK{5xMEFO&Qp44yrO~zI zs2Wp-O*Z6Yy$4~L^&FQBK@`RabQ}DnK4+(;&C1K;f7XF?mxgg_!R7}vB*;Nz6%^)X zW`-b`LuLl6%eIaoV+3|jMK!gZS%lJF_g093tBDD?Vn(_t(P(#$LC+7n6K^#mWRsA+ zfn*uN2QYK+A0T>5NYI5DIyp7P$k4Q5f6vIs2(GOtvo2NuTpd);kTBkLquFbM>gZ6% z0L+z5jg8=Yc>()Zw&nHtb~zaEK(Y%ro=C!5pGd_lyiW+HU)fo9Y=m18VAq)jtrPr= zj%K=qU~V#j%M^Bf_<>Kufz1}kbdbeVgTPKhPp|%Y7djSJ2pA?{q=6CwDlJUJWZVy# zoZAzp45foXzqq&z|V`Hy%29)k0 z2*Y_LAU8Pm!xOjKWb*-O1^Bo&)RJFD)_b%|gICx>;5424MK3st#+h9Rr5Eau9_54t z0ngCBU$BR$>*=|{j%Q49Z*z0QJ%P|*M(58VjV zg)Hia2|`sdGPa+Knpq>Qzg z{F^s_A<=-VMZnRx1esk{R;NWZuon+h6DuHwBH*!h%6EX=bOp7IYf3Mei6EVZlM8HO z79*~OS<@eKo%ZV0264?{MW*RL*bIT#Jt&KS>qBbybK>Lgwf>n@`@Ptn(H{z_0Z?y- zhN!kc8N=qeIXkL2A|IkT5)~T@k3@un69K2l)FBJOhp=gu=jKjk$KN31Rz$ls4is6DOyomyvUV1^wpHg`GNyt-u^S=$&l_u`w8G|CiB%bhNbG zpeKQk=D-c%dkKm+AWgx$a1NskHwZ2L{Q2D8o|B%wE7iPu2BgPqM8J0rWk_7Zk!d+1 z;fRK>uh0@iE#APwLPwdIo2RfZ?d>gI&3+visIIC4?NM^NvZ5jv7gt4neFiA@;0y+% z2`3nTOW2y#R8?VUL`b}X=r`vt>>^?70E3aCS@0knMImzr0)Hrd$JgCOZ2I6`z_Qi1 zyIcXoHyJ5~A_I9dp6VX?#-K*!wleFn)q=&CkydWH)a_)ARCH zp+W&{-2orr?xMS3T5T5|4`XI!RZn|(4B&wp@#p8?w(hEE=eFvz$+@7ypLg5m*QqZX zbr>6!bj*=5;t?5`ypmQ{Op$#M=rZ=19k$_^8wrX(eH|U7L#AXKP3= zK;oxhD1R~m4*;$J#=%gUnDfF&sk(p3u=T9Kd2Ok$E&~0v9f}Yh8Y8`}zh9WH<;GG1~CB@ylH4t&OC16o3lo!S5>F3!zagZ; z9{Kr}0UJ^Ekj6xv|5+!TV!%HLIUH>KY@)2UbHs4K)uk*Y^&C10Bru>+flyixmJ~3R zSUIWD!-G-50e))A1*CxBY=i^8>U$7oL46(s#0B^mWZ8L<}8Z>XfJS$h>1f`B_-Yz<@1=o?B( z*hEA;LGGxA4X_C0F~MbHJWzB+L7@*&Fi6i*APy&*OXc6!)UKcxpKNSR0 z#9$G-e%K+D_TW2L8%2e4D2y_Q&iFiaok@a~FjLdgAV)GPV&~?L9$ByF`|!$p-e9By1HQL9(4px^^?HiGjdOuWFFIp)JcIh=s3P^cn_iHPnqGQy@2 zmyxme>ldhVj%O@0V7KKVodaJdI8#|w!{OivdN%n8vZ?ckD7RaOhHbAk5(id2+}%S2 z84m8Vs2slVi_Dj3G&D@?FXecwF*U*M!m}&UGx|+U`8*)qoLwtjQvN0&!ca|eqED>C7>=Q%qi6%$5ponBn; zElsLlj-^T4gu*5usitNJ+Z?QIWbp_XW+)@n_~aFoqk`uZKi|lysNe$ou!UDR3_CbB zwY4W9O2U{z%9nJU0}tizNye4Z0sXqVzK+y@BE9Hp1j+AsU!EPT4(=y#d0MH2Tw=Oi1LkD zQn>GIZshQ$VfeEF7Nvnt8%B|&Ykw#aYB^UsGe#o{xlm?4zzyud=R zCA5SNXMRdCyE_S+2pXrUY*^M~C*S`u!Jc?|+;+4n;2OFa`4 zs>nV#MnPUc#`UZN)&NV>-Qz$UatML2aN&S14tpgWY`}%k(A0Db8x*AXX=pm&`Xm?x z`(B*IjJ}%WWXc zqvL_xTAWSL^0rVtC^A z^%c*E>tNN-^y9-fT6CAFc_0mf1@)P&$<(e#A_PNZwNvi7dW6~U&QA}! zxXcSb4G0s7@~AoBr_FT|9k_M2J$Btq*<++VUT{-#@pxW~5r^XUOWI4gs*Bhboh2`qH{%%_ zv1q;X<&D=??jO3lB+Fl7sLz#5xD{GyH-7rb{r;jVc2`gDE^E=&OS02?CxhWQYwhPt z(Rs`S#7P;os_2idM{x2b7vE3Bb`8s6Txz9KKA>fMF=_vqD{{|lMJL5NyF^1*sjK7L zko7FFIeS+up}2}d%Q~2Ctcco2d!SYG}e8Zs2M3kQN#uI#>%@hj6{jq zKt@EcVADvbvHw2m!uI$2@3sFC9r-Qe;YS9FP>e#SPS;|j|(`Qr{%q3&B^4@ z3Qsb6Eb(J~woRBVp*vVuWa`LHwwiu~zR>Xm>%mvUq!Hg&8T#?D6g*B7lxy!=zxh$LKC9nJT=l;Az&@<> z_Dt0I_cdjlrbhd_w|S{mL_VX~*AckiUr2nj{5>wib5JzW#rb4zy?_0X52tx7wICna zuTew>s)5qK^5m5wKbuCFH1yeYXZuG<@TQxLs7HQPkMwwZjM2=!&}HF`0ZKcY$@mJD z#YCKRe#eE#K{?$n;`{!os-BLezOnS>*{Exk_+fd^zn5EM56WirT&u)JnV~M}ezbhB z(E9GJj_$uSCF%^lZ#?gGN;*ZYOepJ1Xx^P9Xb3Z^A+|i~KI|6zeei(SZi~D|zcba< z-p)h4ENr@qH^^w%i~76wJXhZ2l{RgL9`V_p`b>!1kA&;|!dEne`V5F)UUx85ukf6@ z9X>yBIQ?MRiylwhs-ZDqnat&sEasTLG*-UZu}P|K&mbz4M7C)!-d#OJgL2nQ7KN)S zV~KA^WexK%m5p)P)VYHSd%bbEx}LYMRDnb3wphfj*df`GE{Nx9q^rr*3>nMS3-+Qk z54}%jPn^%aU+F&_LCv^6`j$1=kTN*)`g-SCCHkWo8jp~gmRmjt%WP{eAT(9wht#Ah z=OnYL91et4PaWGOm0%)_7h5wHFtab@7 zd2w|f>(Gg6MG-J2OX$2d>Akt5?(NZC;@F z-nS_SY@VFzWxwOnK0cOA>kXRXLS~PO79ni51mEPV;``y+E^K7Ph!q`|x!VUic(Px= z6c=sJ2o&aS$eGN(V8nTG&yIKOmw5oGGFh+M;_q!;gwGskbR;x&NW_7 zh9jw|MlEUQ;-16f?e&V>ZBOX1Qs@DSPjWhr&x(R~+P}~5N7k`YBxCR04Xgh3wEIU) zOoAZw@>!9-UM(+_&D9naPOc6ao~D+z5iOr33NlA&Mfvtc1_6?q{1i!FG^)1O@0 zm1?>>)Ky5wqUUKlb{{zIX(DVIggGknu}&?J{VxJMk!=r#TWZ~^o@4^?1xQlzs3K+-`rTfyg8uT z)tx-fU=`l?kWpZ}Zeke)FYg{{D1knw4PTho+{^Bhgay;#w7o=W2#6B&`)a5(sXqv{C zv}a>yRoSYfX#92)ogaQlj0un)@oZkLW^5_sP|WMieK2v|8nB@1QdI75xjsvaa>`g| zkXSn0;=4^rIWHmLnmD=C`;?!Sk-flr#Y)UE;iu?gIUpQX=P z!Nv2X*_SW}SHIG<2iVL-`5`#gfs+PcifsTxhlY%v)Gp(=FkN+YbO0I6C?IgM(ogjC zIU{melN$CF8Uf`5r$Hy@-}0Q?0NIg{k->Q#aQILWB2eq(h8-PrZy-H~kJ4D!*lH>& z^lPEMoK7(U$WJI-$%z093)rrbQ&ZUhKR_1x6#pwJBZGNXT)G6#U58?7v#;HL!+LOOCwyuC$R8JE^3tH9f zABBU#7}z^-rwagv2d7Gq%pkymk_Kf!eV`62NC7+niabAe6iS6Gy4fB;X7H!B${9?&mNu+Z$+njIzm;vb%nrQAA5S@6>qgcRjDNB zb7Xg}egryfZjRh1H1w-w#=A8j_yNv_RwJ(k|7;4hIg*$J=nL$Vy%KDY{<#)$=>V(^`^qphv1)PQhkj2?_V@RUCuc+mnF2f$3iEB`25O~IgxN3v8h z3%s|Du;qTBTVluVAH^kB)BQh6#EC6!{iDjpUf#)xiHU*10xsuPBp@nS-osFw*BR-6 zlaitp6`da#DAv>g0|}hC)KZ`x6&#kKJ|liu51D{%VtDvq0Jg7MWDpLyDFx-ZgMLm{)A3zl|xr_F(U$sZDuNbB9?GA%gVnUX|)8VMxs61qCV{?9XMhdjMq9T<3 zg4@^y=0c&;A0Vk`BJ(*`PPAfU$T-`i4yfK`#BE-?+o73h zXPF|pqBZylo|vSD)`&1YLa8U@Q68-eI+IoWiaGq%8Xh8*9a)^X8u`&;$ z!!(p8HcTvX5Fat>=38p{uKydod#uoaQ?$pO0Hs1^G$RzlI?x8A?YO2f`qz9CyH8Y6%60tqXFm-ly6E$zhPit9Pp^c2M5>AzzYm@hLCtjfjYI0&J>{S1^M~kCMTh^ zV?bbF-J~px6cCXBG67u<3X&uPk#d5f)YK=iU&0M9Ay#Tg77J@eEmz} z_*(lOb~cEgU^#bxKIonGYjoey zU8uDCyZsUuHKReW==}x(M$G3IG^IYY)LrJR=S{SiRM~O~oH~Mj3(xk?6!Ch0?BQ<( zt!y)myu`mAovKK@5xn9mu$Oa9h`_n8SWDHP(ru6)7Ss$X@(JbeOQH{9QN&>lhdU2d zf*V#u@x&?@T7*Q}cCvp+mcKK-iF76bRsrEn)M44bw)PmjoOj8{SU?q#N(s@RynGMl z2vnzH2Lkl>?|*>1a2>t@<<9BO+$lJf;e}Am-5E53fEWRfmL%jrcPMZH^BY745DR~A zZ+ik11H%A|=@_ad0Dg4jpt2X-zWMNme@k5q)NSZIHmbOJO_xJMRY^?47&K49U?P=) zQjx?cl=sW$pT3!x^eaARj9a(~7B_tI;Tnz|g53&ypC!j1?)|a-CCv>|fQ$O}bX5Z?mmA^O?TFkAh2z#nv ze2U8DFhzF#>5f5}UZ2v5GQp4tyk1BtRI=q{ammO1~Ns^7f+gXKfu z|L%Y1KS`1%B#T!NIEz&NM(kOe(e1X2TI#PZ2+}$z`2m%T=hLLYil0mR3m>5 zQ~H2Fn)~hZ@%yjxq9QO*88FT(1;cyK4_6wDT+r(nj3 z(6bLnFq1Zsd0o06yz%>Y9lg7sP}1t{^z`?CtU4)N2RVDsFiq*dx2>9(97uMq}F@!wJxGvRWEWiLC6HN8e`Wh)lIHx<>0x?0Oy1K8(DZr zO%3J~vOqc9oes77Kom;)zulQ2mk3aK7AELL75Oneor;=zq~w9pmz0;TzR{aPh(Z>5 z1KgEKvXQ_~YY3kbWk2QbjuF$6gip$F(Mm05&4+I^oWA3=%u62nXQ09D|CM6@>#CQBXEdzzPtiskBw3?XX9ow}0W=tXDou#^goI=-XXb|NWnhppT|&6g^rk?$Dzjsw(Q%c1nrkq5XNL zB;9o|75y;IT&A|){@jAo-dPvvW~d`ETE6#sfP66BLa`s=liIZO!Wt|LQ3>(unfZ5< z%h%RwAH)cT++iaT>gph^o%#|cwXEa6*HeJYaQfgQ|0nL$ZQg%X^FWU` z16@(EYAEQ^U#F zH1#c2eqd%6mC$VUmeqV=UF|Voc}V1!|B4S1b$Jz>S`)ttV*@lCyI85qd5LcVqzs}1 z#l<+n&D=jbnd`!RhrTeP-oM6Rzg^R6GR@x_%3jPcYpj!ZW_aH((EZ$XBY}K#D7GA; zbZbisq_rMU_Z%e5P<%CgM!AGMCNAy?Gk>S*?JbrA-TiV99E zn|80`sFG@Qs6cQd*o>MPkt{uBp~;_?JOT4RN=fF{IpR{)$fO z*1W4rQH%s#W2@6qiTucgzdP+2Sd4JscJYmL&3W0fgJv`sv_3~mu6Wg_C@mlQY-$%qlLn9HtdWtpkN&Dq} z;YHwGxM1jJV~eLxM_`7Wp6|}&MqYa)z1i#S46wC6Gxt2WJB2fpCYpF#Ua8Bf&AuhM zto9TN4ZCR{82=JyGrWXO?Kf`}6ERYuil7 zDR5(dO#ZbykD0Q&{@8tjrt?GIxFGw*u(NTs-un^aoig{ijE5uVCqDy9DVtX1J)Dr* zWL;%Y9;5Z#e`$gmr6WhJpuIxNh&k`5{gLLF2#j`pC~L9XVYP9F+#h-Ei<|~JOJ!l9 zi=oaLL}|V+VL87oIp$2`9`~TLfqS%srm$4LqaIaj_ z&CI{eEXAaJLsr+qMkGcsxcUeU{8~{yO=Oe0^n1)zRN%d1>9xz)xi39puQ^pqCc1-d zAcq4d^k@@__?0}-W~Y@}Rz6Cuq3_QLjdc6F9YUw}(Hz_&0kv^6?U05OF*ybinTTo) zWox+b!Tx9ODd$oQwI2-hzD1Owa!bsd-;`FL z4YA36O=XfdHZC!J@`mf9?30Wm_k9Rp;e5Z$ zqQ!4OL>@X9luqJ%c!edG9cP}3f7I0YsJF@MxNyxd!;?L2Lv}3an)oF_2U-=!p0m$$ zCRMFg^WB9oW=&?DZ|kAc1HAlg!=@rlH*1oI`jJoOvy5KlihN)tkoHLO6w&yzRle#I z@l5IS@mw#q>fDfD3z3Pa?1777RhBIR%$W{%Q%hOo_XRpf)E^-_HaN*ulPx$#Zp)3g zKO2ylB0)`%TAeb}Xcmr|mNn#BzU)j0Fr`jx5_t3C<$e%YislOx+k=v|6su^PH?(YO=5g0sw*fmwHhkRz)KpV0P;b%z<- zZH2mRTQ?1p)SiB&D#~irH?m!s)JD3@tXHl%Pyg){SU*Duz8t^?|e5=G(l{J^I3 z4jcUimK|=P4v=|8PbRE<_SbP;a>9LC9teK=wFed9J;+PcE!MRmnCp|rZ%-+k?EJ!_Khf}UHoNFdC8Ti({HIozLN@P3D_ z^r5A>&d;{$v&TD)PoxPgemxgx>lwJ`l2tgjyeiFx^?f*S=l3~1nQp{D4Q2m!FLN<^ zal&GN)g^R;jxIt{zO8dSsp{62j(I@2aY2pky9Jhy}_=Yr%^67IDk0DiT8_{{L_7wT{HA6N24$GIv#CTw@4`iI6)Ab4&aQ!;v_ zl)AleaQ#PrZ6`cJt(&mQ+ocNV;X~(Y_Nh_Z=7c2uM9#M8kw}!N$UX;!xLc>^-!K0$6MZ;j=CL)Xx#pl$9U;UMi^{?%e z$HtoN2{JD3vqcmSU!3d1=4wuTOpss@3P^t|odqynZTX*6W?p+6|1H zii9fL@CS9wvn~tg%f|^viQeVc<8O-XX;I0iL#Wf@^}eBK7@I6=W~Y5q7ChK$xc;5a zT%Ikm`q=wkX&W0>|J(!JduH7=*N==oWzD!gl}RzS6dv3j-YZTjtELcdA1Y4#K)6$u zTtwJ{lKf&41=0v-IDt*Mfw%I|dHGZIOPdyxt!{d-RzNVwr z%qk&PBm7!7&E>9se>y-HBU; z9#j^UEJdmboNfB*^;Z%4PGn#G)Q!)RH-^h4nvcK84c^I_E-rN`YSMi)Q4eAJNN%1T zA!GUOkcXLJ>wHAV91Z^9U7h>(74y3mdK+}O9*uu*?qdt&Gq{;e34D!46zS#P*~qDT zJ!nZ|4sPD}#OAaFS!_tYve?`g7k!*c`LwUpi@=ljmw{x^tX*qh)}FU-}vyf5-3IQ>vKEJPTF0vJX1yYrf^WySv8LIj3{6v`5|^oW9%;L_$d! zlbCJP0^%qn6@Tyxy#qw$P&nukq;+Abj^}y6^@EoB0Log0h;h*x_cVg26ZCYWqpw6> zcHl#qx~#mZ#eO>u;_khNVb*0Pp1i6=uQF0buN}p2?~SGSdA}-HOUL_kxo&SDEZ6G5 zVLyCL9G{ObO*P+`>dsU6sY&%^N&JrI)70~?A^*xNzXZh!*cXhS zYC1a>q*YI6Rgw3b3vzHJRRs!Q+bzy9)3YuHjmrjl98O;vDE$j0#}2AJ|7FbS)i>hE zCm-o;Kevi;_R(=9Xfkdw?y=c+qHv4wo|F0U`W+5IC#nZtXWzz+1vjHSR!`y+$=iS1 zS(l8H@%Fs>`LRISVpyNb;-Q_~X?JbT7Qx`cINZL zn=WP1Lv(#p(Z*AAI#>hOvE^T=q^4QRMF&UE#kPg7A9TgEr=+~uTncjjDR3wrhO_2o zYx=T{d%;?aKazmfEUvP3?tvu~gIH|p>q%N~bIBl1RBpY_ad9HLc6H(2d3@Tks97lx zlhclS(9Oimyos#ATU!f)eh^K;k3T*X<^nmgv?Azcz$yerhT_c3XK)b^h|O%WX>fy} z)X^Wn4~vRe-o3lzfBEhE+~M@quBB;>_w^P0I}~2F?jfb17+iHcg&V_ymY#D-ncn2X zdLX|n%_v`fz+&ND;5}06{ar^r+2qsNy2ZFR#SaOwVmrRl>%8~)S>0A#f_YGP2P{({ zqJD7yK3L1ZSm%Skytk)rP7d{v0sRKWEf`Qh(#y%o2@Z>wuU_5v*9a>D1S?(G$pT6> zL1iUSL*3KUPMbE1H%qF(ls0;+c$c;4w!bgv~wWP0SPqf*dBqp?2NuO{rt5{1k)%1I#?ZLq%soAR{)Ti!n?*QQ*BOZ^R z0CzTeUiHj~Wv`B|m-wH%K>$V;78Tt}|7=nHX$R0G(B?w0E-EiCAWJ`&@Ez>$55YIJ zw^whyh}KO7;S}@>jIe(cIFH_wlVTwDn@D_TI`CUo(#dN=q5}ibX>+rFp0TO>W_$|J zBqx8Gcu<^`C8eNHP+H0kmp49s%==#rT_{Hz=e|bu}pWWDOq-rC&q9tYmv5 zRyDN-tR5ipg|cd(RQee~03#43l|oWEV+#l_9QnqL0CC<`fc#>j@fYwb40%x85!B^%nT?A6~!Nc2(t{tq7gVA`zQ!R zFjt~NUa3iIQ$xdFP&~mMiy*86l_J4>Gq{joDkE>UXnorTH-tcWde1j+tX{qZ-$6lc zEO=pj!?P|uD@JfCZwSF_po=yy$v~4iNp|UrjLol8k~gP7d^3ky~*=maJ=7I z(&0^nIxb&891AjQg?IVi?oUij<((p*if-MS4^;ZidPn}tphVtL7lr<%BX40KS_c8? zelI4%gdV0E=^VRQ04x=`I;9NbyZV@li%;7w_2 zY640G^j}zgz(jxn4Eq+`RCT-ChzEh_$mC93BoP)7aS}=eS_o`z8ft1oU%%SGfxoJ1 zyu}OyBM4+^yR)@nT|eOlInA6^#ybUose#-Uq}t0p`dugphSFo^Qw;AbMFJbN;@;#7 zhYYp+x;O9i4s$=PopX8)l%=hIlh7u&wq0#=8SI`(8#p^$sWbYBi!WW6Ul!BC`)Q0C zUz$Qsj^xt5@!Lhc*VXnvJr}&aFU&9R) zHsw{G&)2^StGiYr371fRMenbg-WtNp`qcH8bZ=$kx}6%iz}IkRLn5_8ywTYF+TC#bC;s7KrAz5FrGHtae=O+&5r4VE8e=Fl+w1SM$Y^y?OQSjDOT}$sKutu)-&uu=^cF z!+-9srk{&kUTmtgZ`!fz#fno4d>#BM7K~3S-gjdn&J|U3>;wCytrfT{y#D?U^(#30{^!!p^=-VthHAXNu?_w08l0V5 zJl=dMZB11S3L#=za()sw>aR4VhG&fLotD+{>BN4(mHzVj2UaWlwbEl8+Le>ljk%9G zX!U|qVjJH3RgPkm<06^QJ0xXHk7gTyDFUhrt{8%JHp&8Dg5<#FbweW~*k|DX!Ov!{jze(hcEj+Z|pm=DcXp{6-ozyrC?JX3y48*!b68DDk)|C zAJv_CIF|dm$DhXannGIAut*tp2&-8UNlHqEQVNxjCaqRUqO5vLp`wW>q7qS3S|UOr zC6b|mYH38PxoCy7KTqrIbN1Q$+Shfae~y2Omv?xc-*Dge@BV(ip4w`X3GF+MB_>*1 zSwRWDT3kG3KzAX1!8QGUQ{R<*eHGr}=hWwb>G_!+7h*Suc;2e{qjgfZSEr_HJayB{ z`?AbQJ87q}qhrmDywz_9XYO*CIX|lTa^BZp!NnN zX)(3bJ|7_sZw*P{=jPoHI{lWXv)|alIb5wE=r8*E2qdD|2-oQD>U%$GY9dE(J9gN3 zdnaeOcWUgmH@VbiQt-9vhEvW%&%Qt1Z+gk#v(tmK3%`~oKCQiX%X8Ox#g!A==RZx#x->KD^}A?CaLqC5>~&tgO!jNM&VlX(d%WKqvzHc`n$4@3=H6LBSaZBs-v_4DF*0hAeAT%I3u}IR~K__ad~W6T+f}^H$*MN+_Tc!J+ZNd z?+und8`0`pbLS31ei)I>9UIN>)Yj?^)xNBv+@`WHea?KtOs92SEV46pCi<%XkT}Bg zY}<(jEA=;L-j9tRa)AAEG0kn+h&ePqSL zAV>MQB9=k)1sxW+DrC$8NW?{f!YF*gs*N}F$;_hF}$A{EUp zZ>`kA?yQcU%_?5C!0ww9&*H@y_+Fw&MPBYv>Z%r|q^>>=wFkjAtqMf_6d254Y7BHI;PK@ z8TMebR1nn4Y^=sRzT-$`U<#IISk=BnKa`YG_oqGK{>aFyi-*Efq#N8aZz8jrI!Juw zzSHGBvt7ttP!TJq8V(y)mA;I~O;t86IT?+O&5}W}lC{U?#7ZzEj+mm+NjUPg`-(-? zFgjda$1S}4!P^-9U(-!KDF%>xb*3d`LLufj4fwjRVMv*0WMt$gUA644CtYoAZT%xz zC@V^g{3D#YZ^7}`6&+Gme)&6xY3B5n^wwO=AwBGNM1seCu^PHnQ**xU+?d}C3x3tI zEa6gBUBr@jiUwf{W@QNIMAz(so^P!R+pLx#R%Q5$v582DF(aN+?!H1}&{APoOj%-P z#g~y1&Hg=tl@d<2UiRO(d}K^57QB5`RDPxfqqWulWJE&dlatwc;}_>z67V+NbUD9g z#xn%O+S<9sf1FE5*sPS0k}{SC4MJWb9_aZZVFhNv%Z}9YOxw3Vr;Ro-QMSavh$E4% znNN1eSE&57cI}YCgJtC9wWO$j74NHA2tn}+Ds-#~ai!se;r^lZUJM7z$?on)>j%?k zfbN0tk=x82W?B%MP1PBurFD$?+AwRK!{!qIwjez(lu%$>1}a7Y0){HUg*5`PjUU6M zj|MNEOCAo4@5o{HAkT6sa(8#1kT;yDj?qHiWlK7fmSz+vAG_TzPBH|5F1m6YD*+Q5 zsHVjA?kpG=D%2(pXE5SG1?tA%cKrBGU*_@})2Hu#acw+pB7YyiBbTqdbH{7wL20@2k(LY7lNQM%$dX$qYsGao`!K#tU{bn5Ws=9vuf6$ANAc6jsQh zAPN|nrF?ir?^G|-RC0}}IwGvOyxdS%chZ@zrpoWeDgP}O*r|X}JE)^yh7THF1hpNH zLyb6t8Ut-SBt$lT*C2E~@;!P`4nYJB3Rv{kC0j5vHRaZENRB20B+lA3Yk+9SLZCf$ z>cIzp^7o5_e>piyN5}J4!bFtZ*Z?)dqG+vHd7elabr1NCLw)r(G96o5d|P`vF&(0{ z4`wIC9@6%^i2S9^#Op{x!Xk*>71pK^zxWO0Nn~ZsTrSHjs1L}SIiXfl*j}*Aq#_fr zF*-{lbGpq>*cBBQ->#|QX3>=;Vx(8yKFCL+{VM6gg*og6<>k9#N6?Tn7Fq~$5h_CT z5;0J)Y0;4aJpUbaQFRuV855Lmj(eW6cz{BI&t5>IvHwPq_awS3T(0*odX7|sZyk=&mq}Xip z_u%}Pbcp4{Z(x@%R#7u6Bef=UWKF{6K zQhoBuRg#|aVrB}7My`3V>So=6stkAoRei>}lb7a?FEoisCzKs|92uqyqs|(w@{(bV|KZp_i&Myb-39fYhmZXb~CkpOgExC8^;FU+qA7nS< zr_Dtn^<)GVRl4kXR9|mQ`Pb#5?@yx-Aw69xZ^BcM>!c(laaHgto>QAH2=YBABn_VS zlJIWg$`h*jov&R{X)+mpyjdx_QrOnF{igqKj~ZHLZPD#42w#RrwW;yK!bjPjgZM`n zCq~zT5Rm4fF^J)SAE5Un@$oGR55N81TTMcLL8zZVzW~WrFtIb4q2dk_X+hBV&(ASA zO#I;=;s1aBkTT{EmAg6#^|R8!1+}*av@Tn}K8v2ogoJ_3khfcacrz01LwX3^52a>w z5d^=jVepZL4z*uZ3elqRCj5nx5TX01;m11(rkSW@Py43NNu^Y6Ypg1ScNTw~vj9sR z#&yrnndxWFRNTEg=e=g9pu&2J5&3ctVXZS#<9Et;cgMC}d@eKbmKe?XbvbaBixt*= z`W%D;WTUMvglm0!1VH@3F>Ceqe!d)cwWXznGwdn)T0*#*_~7N)r{`Z=VBDC->Qqp$ z5cd*$c^N^g3->F?7+?=J#sv!il-q~A6M_l{aBr0oPo|T6ZoG^9@}3CR}$aEK%!st zW06V;K*e6aHhi^8u&_KcyRWeQExJ)Q74J!!9>h~<+<_0xH;gQOHf3yo?>&)`Ugxk? z>}=7KArvHG4WXgvfNwARksv)FmodTa%Q8rDlVXq#kXbUNi=ec#XwiBIQW0i#P z{^IMqIAbDcwnRhN*7@7Fi_+&*_8`fZ{kKu;s@x?=4F>;0nop`5z#*r) zU~|O!*8T0!>}@l>jn^C*tRNI7o;fqa!2#SsGo1L|SwIr3!fL+n-5UTJ?QiqLJbGIC zzP{ho*myU^`w(TCu12Sh90^hyc;R?bQb|R{8Qr-Mu6PbRyOr!IQY8YSQ>R|Nd2@5| zP|+2Wmde;k-GsoP#NmPxFnqlp!ROY!aWyy3qqqn#>|k_sg-rC9 z;>smxdzn$W(KlC7pxNxky}TB>BLYv2&`{gyAtxz@oj#4uulJ1v+Afna+lZFUcFPK_ zf=`%WVJa&phvuF<;LY>rw{P82R#!K?kV%<~_gDSGJ#DCAWZT|M5Q?D*X9wY|aoV+2Qa*m7UM$%Qsx>lOE~sQk8>4b?0xF2-Yf z-?-5XR?LJ6fDBYid6l}lHlQ2z@BF0U=_t@>gB%!}%;gu^}q8*dlR?}ol^iC%?SsnngL^{x6?4YmC&WLrBSqlTy z*Sr|E{I2m*lU8sZ8JxCl*y{fXuN&8_)z7dzwwpS&U9{GUiNS;w$?zlzVdU|LBZ0!{ z<2#+7AEfmD_B*=EoY&g7*#&76tC807_z)^@6uI}vj3GFySbHeFBnxP>L z*42$QGYb?i%N<+Ey^HJ8z&U6>t@FvlA(pQb=Mpqf+v2Kj@8pCJfoPLP13Qv((NAvO zB}GCcVpYxuraqV3w1BvhJcy8i2vlS@>>k(3X+hb|n{UXFEHfi68LICVHL!jAMjtrf z$wi^DF((57{#i_?u9uX&1ldTxJa>YmRP@?zdcR?#rZ7Q;T~A4|;8KmKOTBd~ixUyT z?Z(`X{f-j(FgAmwQoLE{7)3&FfK3iBhwbRm9>ya^%(Ax!tZ`J%XXVNc(blp{m!|be zh?BQl{5*>SG%gK9bhK8&NjjdIDqiImO-(ZDA1eKmNB5E6##v|mah8Dq?0krwICF4( z#1cx&SsP90*icAcZz*va$A&_dirx!$#%{G;Gb9_J+7kh<(SzbugBhg=0)i zD4Cv4OB`35K}R z@RE|rRKg32N5{86;cQA8PVy_Ks&8a8T@ruP-#ho|CbKk_;I4|HJ9aEIRwLk4y+8Q} zhgq|z>7*j@iHv`+sQb7;oUDV|DI3>I1dfKREnabq9iRj{Cpg4Tw;A<)~uputD79U zwiQeTX2pVOWaPse7u{pIeXBb=FI=b@Q^rKok%GHUn`q;e$}!LgX$JS`(*|~8`>!_Ja1@_gZmW@eF8`lwFG|z^qU8miTF=JYCT$jF$oH4fVeqVe6wo0WR-_Dja=Oj*1lHGmviHDaL9nrOS?@D5A zv+ctC?R#t~h(hB6_l1RFQ`@UdHmB+1K0g(GE~~13e2 z8J(KaD~}}VDjFKoyY2~#t=<5}%d(`OPtJIW&9rGyL7u+za~wFZdSW)N%DB?4QPk^O zqpCAJ^5}sBs^@LrmWV{tJ9j8Bx~+0_{`92X&Dky>!1Teq`4krquY0(jMa$3B)!lv2 zXE*DbD_r)o-!A)_5h=}lrlccBEV^!dnH=^ADvKXjQKAzYn`^z@0t%k3-g>r^&R%kw zxp+rJM5M2LFeZM{*62eB-2o5H;H-&Ik0_JHm@I>%jfb~wrzPA4#^K@;$iXXmd*g#Q zlm}VoU|Nl`efrd?sTc`+dtWOn`vM1M#q#BJ;%6&{4PE_oGPe}v2n!=9OBUley07Wf zzjbS7Ve|Fx`Zs$@cfvj2tI zeRp4tA#dmUB#RY1x+{8(c}^tE87YfSVz#BY@S*^Li^z)0(HU@4nwd>t;xtsL^z3;F z#3Vk)b_(Okwv+1j?BsnF85|$eY&b)aszx-0bkY+hzW2Cu!TJw)^%-P)e zjXc0Il!W+}=hDR59EDOU!zb8BCilLw(Y$G*b2z-@(+Z9Rzd z^OuR3PPc$}Tk8+-{znWSZZPMJg|j9Ph=FHL3kOaj#D`CX-e5K>%+;&G!NKBvp#8bB zhl1cbOzpIykd{j@O}x#~xJZC3T14u-0-6nzrE-^?;A$>TqJcTD1H&wGDz5(d+N53o zvqUXFMO#nrI+RGDu>c1H_2bz>DYk&O;Z}2Y`B-7M&d_pXMA;WFe%GxVo+dqJeJLY_Gb7MCmbbr-(u;T@`~f_#l-Ls3#%RiEFg2~Q`hrQ}LQXN!0rj+GLx>zQ&-Y2Og1-;Pur&Vzz>#Q@NZ?h(^c_P(7k-)S z{7qK?h#0zL?~96R1jLmULhylc^y$uL($i%W6u!S-SzV2&MeFluZw3@u(S!bikY+%l zQ?ZVWiI|Y8#fi))g6}v`wbGWpe=Bwx0;Ns@jrcFy1Du>_RXF$SuXf)KP}y^2LyKP6 zJQd!CSdje(PEwdce)dt7Qb+5s|Mh|YqHj0aZo-5uN|hBA7Cy@DsT|!%yq7QUWqSPo z_Tu71-5vua^DI9T|o#yH?e|`Xif(kVU=nM+UYcRl1 z=!Zg+mFzn1KdO5f=g(7dq`F7O76;)Q(Cz;H+NZ-Q=VG&UOwEhZ9R27Q48Ie!WZb88 zvXC;ASr0$Gt^emj+)83LV!!H#|5T0BX#B5L<8l=?{(GIQGGy53(SVL#-#d3AGa?U) zP=gO!X`PO^9Xfp2q<=XO7$QtqL?qSceP208=&zm}wq?r|059ua)fPQkMbSR# z*84p>s(>%!Tvl1R8hYZNPs95dU>O%vxnPE+LtptH!~pi6>sh>(MOU^85;jT;X|e?# q&nfDxK~p3Cu0vn``NwM4S4ExKPF-bwe`YQ|Xfx5y>a^v8&3^^`8P==- literal 0 HcmV?d00001 diff --git a/nav2_bt_waypoint_follower/doc/follow_waypoints_with_wait.png b/nav2_bt_waypoint_follower/doc/follow_waypoints_with_wait.png new file mode 100644 index 0000000000000000000000000000000000000000..ca3fe74550085925c283dc0899b7510d9f155c8c GIT binary patch literal 60033 zcmc$`byQYi_cr(tfnDFB`MtoDIg-HbV#>!O9|2v3P_3|jdagG zzP~Tl#9H6XnpuN?DDrU5eeQe5wXc2c6RP@94)-e6RTK(^s~|6}jzVEjqfqE3m$Be~ zI0%X+;4dswMLB8I1@b4YF((FvVn8WK-_!6&TKnm#ud#TJy)}TsU@BnX458kbC3_IY z^;WUgqBt>YgjcYh!;);8|JJt;mW!jswa@lGW{19eucd2Wv-$iQPXJelUHRtM-p#14 z9|@GkZ%j}Uo8z{Iy-A+^A~QQU^E=5;M2Kqjd9VqQFSXIDg11~TrI9ZUA-*3BOvqQJ zarwP}|0Qc;vVsc9waZaSm9?`g%xg>IylL_o^HH!Qe7uM`iQ%C}MFhPBUGwSRaO8(A z64lbuyRYXkoiZkjr)r$ud|mVz8J3fm56Sa?6%rDn^t>DE-+d`B#o+$C75`OM>VLN~ zCsDc$p9l&0!k%D9fP5%g?dJbsJ+0<1{(b26|LqIqo0V5oFhi-!3QHKI7X3?zto<`UAiHZ9>@z?L()vsOO8Ia(0N$rZFH~U%V ziVEnCVUyyCH*0-<2`lx^ojcS|C#yO_2(RNzYa3WuvHxvndSzsSX_sH&0;C*v-4m=V{nalGeH8_T7g@wmcL#aFymA1_e}D^Y2Gqzg7D zV`AX*2pU23c0yvJ$@%F~f`|)i+>OW2f7ZL(#ww_&bWK#+ZubezFx;38>!lYaHUqq zij)axVZTQ$-~?8LxwyD|wpy{_=yd9y<#l@h`0?X#f6`%lNRIx`&*qvM3Pwgoin|^+ z-wRly+uGVb+nAy(&?*|H;HmUJu#X6xJUTiOt)8iO$0ufc_%bu|dQx&SpJ{tY&I&Gv z@2Ot3y~*d7R~+5kwCoiX6wpx2Y;0!xYd@@hl(XF6=AN6Me-2x>yr#^Tbpw|4r_=n! zGUZL*<7Wc)Qxsrj*X*Zi(x;j%`=}02PBP89BE1fNHv3B$`tE7Me=KxHP=`cBbnO25 z#^=7FkBN=V^)-S{jLNx|hPU~&yz@M}dLZ!@w#)C{*0x}LLL#E)@R!+emO^Y()o@oT zpBdJ)=MrsuXXkux;;oxPLfELgUb~mY#l^punPE4bY~0EE_>t+x4V=8Zysf>xQJu1{ zZ_43Zv*=@RGoA!gRto;^PrjC@6y$%lYJ>`yn$j=SuO*`QKXs}-IXOC-OT9Q{qY|(R z2*RZ{9V>k7v0gb|YBS1dZfQwH@>S2F@sg2|(f9A)jR({2QHc8p_oqsftoeHAwzjrz z?d(XM9q$cQJW(MbC(kr#3p!kqxClKt*j)JF(9~LL(q?RHdySWu*KVeX7M`}kvQM3^ z?SEQa`<=}O3^0+?)185k(9qW7z15)tZQf^phO>LmWM5MRUYCosdb&AL$rTnBMnFkv ztx5xrO;ti#VBFEwMg5G%H^u+lGkMZ|a~k*7ty@JFo*&@&;fDGR9)wO#PFV3QU}|SI zRHQ?hoMh;*7+^#N=?jdZyxuhXSynbQp{1%C@cK1Q@{%?=EiEoNdHmIQS9f>+9;?uhkd@nD z(PC1TeeW+}V`JM*R^b}dyU9e+iS_(^^6N|VAv`1B(+L4-8JT;mG55ex7kgq+?Tvyq zqF~#?qN1Nae@2&)k)aa8((uQj5gtrK4pHMa1fl@~xL|Mc9dcL@X`PgZg2I)DDR)Cz zmERkKkvcj#1xhoap?)ncQr?;36twK6fYVs`)g7a|$!*j`)AvD0&dI5))dJQiFM(Vx z;ng*ACNVMEM(+cj>cZMuk<-)DH*ekqkaB4;u&`Y6^z;;V{&jh*NKYGgNGqAQ=@7k0 zueuYCG}QNGpAohTEKR4`PmGM$@O4Sk@l`T1vVS|B!T%*RSC(4HKFJ57EY`Z2nb~#h zG#?yV(NDd9S1d@Q9GcIxc;dewU(H4RpH_?s}G=g4gIyN}L~>B`?v6`_#zlU!2TbJnM{$jm^H1xq5hf{z=U5R7V^f zt2Q_|Sf4Yt$3S2ImsAi=G`+CnY+g?s8#A-CgA(ke>vz0ReZy;5`ov;wol*4osLQyx zf=-x$Ufo)g!GV;lLyn@ zaZ3=z$V6Y$Yo`3Uz??}T%@~P6v7ULP2@Iy6Vs38LurXFdO$_KF zLpQQ5HzZeAIpr=TQD{~#KX}h&9Gt?G00d=N0m@LTbaruhQBuO&+q-*l#KFPQTH~~k z&<D=f?v7)mS(5KXYwtq_(uQT%Ku`fc&Z3rv`aRO%ou3^r$_gGOrliQ0eF6M*fZO zuOm-phG3`B{_gH8FR*Zjb$lP(V~U=Q)i&h2hnTv?DBLz$0TUBbk~PNKuA;QGMUl4= zlZ}mySVjhZt{DmdDY1QdDAUB+Ii6+w*+pC*?3cjZ^em3zZ^n=X5Md!r=P)Cdi| z*9D2?5aa#NZC__+vw+c}P>zm{Eot{&DAB;95^A!nyRwC@ym?nBEZv#P?@FP8RpMvg z;va~{D;D+0-7Qg+hVwS#04-n_jz^bJwEytdxrfC^& z#8#rki%mDGciN&MwOP3dzCkv3laq;`BNWq$59MfQu_6yonwyUx(HPrl6=qsw)2b05 z7-NkOp>%tDgoCDjxwnQYi zbZiDTwFYD-TQ3NuJmw_LMJL{YOcKKr8lfX6!3)N+eHEOlQw^}jEcGE9tGT2?jT5{WrFULRU$Q$bib2-`;-?0#3RDcIze8=!`9}1y(RWd8#Sh&}Q#Nr%SZ% z2LiK0GP4tIeLL*GHQ9fYvp@49bzHaqE*PgBmFOf{As#d?=O?O~fFZDA`hCCCAn>Il zp|@McvW4R|=0r1&e39m2!Ewb9`D848U^`d-I9^}C(i2*6Df!o*Am1Rnq>d zBR6KvuGpY^)91c!Bqjv-@ZyA=V=SNFo*mJ> zb-UzBhKc|FOny+at$UiE)a;Z$s+#Wo__y3!vu9)kd)R|qm)|5%`$eqmQPfJ^eeh_c zgmEvOH;}`@dxDnlO5>_V%M?+_9gOxhjH?wLl~k+nYME{k8 z-YB6_)MCDR^%Koy{WArDFlu*ATA^e7mQm_uVOdxG6HCdRrg`6p1eSot4;!{U!$Y%` z4p=%mXnECwU&+WrNUQ4_iXRBz)XMH9^xi;Su;eeGS{C$LA`AjvRhsOjH$0?Bv8(Yw zqkEw_sdt2dKMr0ls}N;_+OXcqT+mAuc2$a4q*ou-guJFZp)KF8@Z;g<2t zFge<~v9h@s{KS5z8a&Jrg%dH)zy6~WbHV2UNMnd6I>7g4kE*=}fA==T#dOGd55x>7Biwp9_i-85vk z&0)9m6P%rEbfxrca6eIBVU|T*iElqV^TL~NJblK8jY2*2%e$x{+iM?qt~A@~#Bda3 z^_qOiHm<@t%TwQ$t)(-2Eg^hIICP+|1lst!j0wIw?(!WFuCxnA7QYT_Lx96Ye z;tXa{JD!oZxI8~(HEexjtI??;Tb^z#@5?^V-b?24U?jHMKs!@>HC>)3NjIGFQRlH8 z37>E^cAYY*i)8<)9?qj3U!#f?Sf33QPlmikM~@9N7gfcTc+E)?-2S)s*Z<0Rwv-KY zY;mDN?r>4n6rIW}JQ_-fB@H)u=w_dvE*Q2zW@$?=Btj(IFxxG(gK~~(SLqO=A^IG+ zpxE)?LBJuIp;n=Q>!;Fchc^0_3;PkXWo~2iz~GvwUChQFrnS=_BeXK zc9RC3fsnWoH=^UsfGnZZLcb|RY*B%{hRdS>Z@Jx38~_1*El|&gS^S|q!AIfV35k8p zPiN&<|MQm!pQrGCmQ_F;2`X>M)TasV^Jgcc@J9@zc=ve6igNi|wgU2}q*87p)W7#= z0$B|LlbDCtxqAq4PY$n{TCfe21&qd|>xX4!2&)JrY`zLr=n3m|dW`EID!uDLVjjZc zFp2k#$Lx!sRu&y8P9DDGuIzGM(?9X0@B~pXty=@hDQ2IRKaIxRh9j^2h!zxqQk`isV1&*b3_`Ud^3 zg2a*AXnI9wX}@kYCu2OffR5$2sZ9Q`R1l{w{kkklyV`nVazqX%iqoM!@l}Gq^Qw?j z6hW=hZosEq;|})HYG8;> z<<4=^xbiL;m2|Fq;7!|w+GxrjAD0RYUTWXrL6cl4&OhKeBlqx8+^h4HNIT2TkBWy| zD+PluUK({lVU-Np?;dziTMg<~6c$nl@2a#73}t=rpgGq$v7fYP)K0eh5aLzSKq+6x zTBX1&d7*-)NUbSSOC#Tu?v+fEmuTnFd?{;&R3Uig$;826uJSMb?K{!VQd60kUso$n zyx?B>S1;}`XFPD)R%fAhuC=nN-&1W&J(8Tdp~|?(%D_t~wERfEiD!e(aFY7><0uUw z8>J>5`^fJt0d(934-T@9ns|xC5L)V`3*?rT-upf$4qpiJCpxn;mxom4BS(BBIEZdO zQoIqi({4~U$|8r(lhPSpR`*>Hjmj0PH!H)C=6#|lK;(?~fk*&)(0q;N5XH`M)0MfC ztrCq!H`h=ilBlhV$TZ;22+(xqW_EHpQFgNis11){q-{dYR20T~dGpYBK z*ls%3C(NmmJosbEu6Zm52%A7Y0*%TIq6K(iOJjTjW(p-+53>>Z5}Gvs{NVlG9d-_M zA|AA;&oWc59tYHt=w6?CBZp0KXpb~H(LTMHAuwGdEI&{LclX%=|sBB}NK%L}{r zs6H=SJhTEU1N0!36$c@rFJa`}kJWgLE${{YT>V7HUG3 zFyYda2xgWnn&%(XuK-t!mN8tb5rw-6hXjPt9NW!|897-6+XZhvpzG`7|H{E2(~=w) zLY;hUK|pDmfdn5?ImoSJO3-LIU`psM5#?3onzN!=d^lukyWPoGWyp$L)zDH;&o0Gq(hHZwyP3S`8;0ftZ4n*qs?f& zii)U1JuE^C_mV6iM_scm6Z=C&;QjZ{!p&d$M7LT-^(q}sFI6rrX%1A-q5p_#-+7HK zY54xPdj0K)fMZSqr5oz8V~EvL>dmFSFcarZwhV^;M!f|8hSCyce&J=V3X7` zk2UjyqKwMR&o78Go=6`ZX9*X_Hg0&?h^W$38)Bqor`nvHWlBCQ_pt9BDEhO*#8IBh z<|RNvGOn#w%fU2+lHOE(F_uBzHZ0rz=lk&1cf=o&g6=xU7tG;}e8X{fEwOlclr7un z>dTN7iTLBv^fkGRu5@9eUE%Kn>Ww+_((}Bih&$o3<)V96rY}*>>s`D)$zOM~&j^-c z6j5hp*`vzsUzk=Dh#M%xjJ$!u^I`wpL}H%1&()(Q21rQoZZ5mFPYiyD!`{LGM&HSD zan7)-S<${ekM`aQ#g5A(mHyr$je*gUN~Xd!&9>sd!_p4@MPeCCtP-?aN7&wi5GQv5 zFl#b)X=MbrOf{;770_u~zKE#eo0rDPHUg&1vnzw|qMCGY0sVXB^HUwUaNx@a@&3Od1#IUNml z@l$fCUp&RcZDUAS1&9+Jt@FdWDULMOtEkF3rioFaQ#{^lQ}%vM&1AJ6el(4IDh@ek zFS`8((GGgjgiY#XSvJLf)|(F*jY&`cykuSo%vZ7x`~9}&sUZ=UL2OP3ie0;|M}=Hr z=tWF^E!**zk>8r{-sQ6?POh9y^)PWXU#4Se!dfI`>5} zXcyU!tX?5%$urpVv$s&AH@y^+LXD~^C9ByksQEJ!h~Kd^)*{s_^JgDxaE^3TJWK>B zu|Iw`fAJ;cZdbu?E@neg#cHx8j03#zAU=ksWS-4Q53^)NU85awa@;$)L5uI`_!o6; ztaV&h#K?cg1w5keJLv1}Nd6qV^e6WiYkK0b%ZBt6C7&JF#wVM%RpQ*I8Ux|i+JCJM zx1~I&cbD#s`l2$fZ&DyGz_l5}~WiV~;h zAT}|qx{a@>kk0J-lJf(vUV&5ntKC8YA>%Exk8k=w=T9zaF%ay09os7dblS;U8)6W6#)-#zfV z=4fBy{h{oo?^Tk;d_(sX9DzTqDNoqYbDGgb8?V;5X~&A3@~Nt`r?}H#)SOW9Hub#u ziuMJ~lVx8y0*l8UDdoHWT_igG}!zQ8J8o1P}0$1cCNg6pUEhUK^(tciU zQCcstd+eHaeljnDXEjkV-yF5lHvZ6`+i%PkwR>{;i#N{H#5KUMt_verR)PeMRwjo} zpb976U7)%E5_CZo`uhG_yBo-HBGtKEAHe&uHtk$ukUoXnhw|rVLxYP zg6$Xbl66Xi7Mt`KKoLk^dfPLu=$vKsrrPUXWsxwx@cF9{N`lab?W`@8*n@kneDw2k zA`BY>v%jxX4atZ|u5kcSk~^cimSd~u+2y=>Zr&?^6e9v3|2HjwqaDk1xELeVA^t%8*^k7> zAwfQ;m((@~&QiY{+29JS;@)lIn15!^R?M>hPM$&c7>!mIqpBGANlBC2gQaF2D^T8! zZia`m8E+bH&&VxRnO?||cO*qbngx)l{GI|3sq-V$)=ETjWT{B(eX6farQ?2kz&P@YLJ>N&E$o@ zL4zsUkg=ld^-PVKKRc$e(?Fw{H$oK6egMPii8R02;@0loCO5z->kjBDRbH`bv;^nn}SB=p)b6>gc3Wq+MV9- z4c(2Da@oEmD9cREL)-Ckv*%{@ND_l#5_Xb)x~Tuda;uU23K!ytjjkb5mD`+Ng+a8a z(As5JYhb!5?0*Knqs}+ays5ZWApZJmZL<7jI=Rs4%n^1?-e4DRzGp>Qm)UzsP7)Pd zyYf~mY$u3oTqKq5yKk~ou}GtS=GbmJY!)BY1qM@K#U2rqwtX9aV&O;McLN2q-L5!_ zX#2#Jm9&u`BGM?-U(s~Geqe~r!aJW+0>2(I1 zg4~+IHaoXO(Q|SWfY!z>_xpAfS8d~C#z0B#?dR*3~k}99{yP$3GrVgqU@v5_ijXp0QndUb$cS zE=4Z0X8O6(P@8(RD7&I(bJVei3dRNws_(dhxF{ENA{yF#oFW?}zqNU#bTP%f~@Sc_3q8c=%AMPUyEM5LYNLmDsl*IGf7shm3l0 zRo{?m_ie9=ge+Kg+BCZ#Q}fkUD~#t*%W7^M8AwM3)D?ORwardx9r&qu-yr8LJ06Ba z>p{X0^x^TH@Hs_KYg0N!>;CnQ9(8y8&?C~TWMlKxr|&*w9DJ!Nqv$vP@?>f7exc>w zY}PVunL~cPzU+;`Um~NcVEhNI(+12mnwqIze{^o9-BfhVl<27Rh{Sk!1A~A5A3)gN z7KgPO|CGcj3vFg^+KwX)cNlnNuk}-8A_D4>Fc#%-=l1J1B?&syUkX~4@@BBL4Bm0j-qqQok#UfnCml7nlGJx_&Y~d84mb5Stg~6Hvc*uA{)`MV+t^X`kwrqQbAY$2Mx zVLKfSNj0}jd4gYf|L8*S^HtC+83w8~OILmy(z{doY_t7pyh;eF*j}^IZ4YY#2P2YK z?P-M@)^R_1Bc7UfV6O+CMz#s|P>50kQ%@y5OH;bGM4TS}wsOV&%znuo@%iGht8n1N zZ|LR3YI)nFwz(T0QS%k%mkVWo9T;pNlk}O~yrbfN)KwiY=^whN-j{7ksomkrII_8( zRwK@Zz5X-^kaPzf=uIfDj0qx5-7k{qG_o?%S#8NL=BL??{$xB!+byqzh@c_< zkbsS8`1&!v)4|4=RDc)mvxbt}@79L>1%o4yE+8V;O1_H~D)$(Q8+?G1!x8^8c{Ymn z>hb)&kI^w2t_M1da9)bSuftXZ$m=ba$L*8y+HU6OUW+QV-MjS6V;YyYdGhDT++CMn z&LZa($EaRzW{L|xl^THxUjH23o^M50?JwU4gh|5VtEiz!N!`%{di6%=G6i^ z5prHbX-Ua|JSip=w2yT@SrI-=5)NEmwtBWcLF#{gl#|y6o59Zko?j^~D~knEk(Vtk zlBY8lXY|M?Z$F(#5WT^ftzBYx86UrEw)F*wp)O-yx|E)l)-qxOJDZ5P1o|xWC;dsS zwk3^0pc+EfDiw?;=qj&)mY$xTAnq$V_48-h)5+T)w)!!`h-4+UepqPtg9i^vt%jI( z*C)vh>Ym**H)ke}&^13j+=hDvzj%S+wZ9gsS)i3D$_)7529ciyd2P+2Vd2q)EPjn& zSS@MpEHxIX_7N`}tZf&(i3_}$HtT)ijV|XSXfw0KsA&g5pZ%}^1OFn8M|U@b zw#lT5`zp~AB@Tjl-L&W-k!L2d`%!+$&(H589$4kFHSkwzu3Vg)pEG2_Z$4XAMGg*5 zQ%T@5+_rtRKzk@hg&u@#E`NogAh-erLB4FY{m;)?3NZx4#4ivD5QtEOz%VeL!i6^* zcJS_siIusoYJGY-IrbmR!19J()Ymv}J!AtCK73f1?+8~CkS~E{BCf*D!Ex_k<7b&k z8`h&>#Pd0jPT`GPw}@ldRAh~f8K!-9l#}jyzMau{R4e*yIpEfle&da)T10&a>Y=Xg z1^As+M+(wt!elXTvXaJqDraZstu}m#*$#3e0a)5KTG3~hALTrJ1$rmH(`~uk&6%11 zEDaOsg-d~`DvsAE((mjzUHJo|`83YB7rX!Y8ZR6bI_N9gS^_Z$Nl0F1WH9|_s}TXC zX4&`eI*7MV)w=u-Z#P{j&5cx5qC5Ee_cN%dhCV7&|9hw`d}I@b!L|qCut8(E0OBSv zLeq?Unl@kw!v5!XuU@-0x4z!@?|Cv2w@3dkLrvf_yXkZ2h!`rY<`x*Loa@?mLc~Eq zMfW1{))Q0EeaI^+!jE7Bb-@spIb>vIO+iTL0p2xMViXlh%=TWC*(-?Vt_K0K6&jo! zQ4;4N@XY^wk?9g%CR6^6TK!1y&UEjC4G=_jg0Ux9sa8@8SP?)-8LV}A0+wI~!q23; z52d9A5t+gR`G*fXbJa3$I!xc~O_iX>#;1E(Utgcsmht3Wc=$EYsJ#%h9h;qWXqIXA zJ99kQfBJ6++kxCs4aTFr54PmEx1vcS;*1Fe)$`igTI5%gq?uY_f1J)wJ%24NwM|Y^ zOPuY-Ab~C82@Tx!Dkl$5Ct|VYUkG+Lep1iP%`Hz>m%s;xXaD>O1p@&ID#4?VO06%i z5Wh)Dv0o_#W2fu@7bbN)*f40=pRld*IpS|RoWBN<4|X8K`Rwdq2E;foV`EAEj{mU1 z?Yj^g8LD_i+#cFfVeyp=w27BM$b$SLF>bzK5Dw+@kdVs|Us?wS@L~1$6%<1Mv&PGi zoW%HV-6A9)2!PnzaP<3wuuG;mrpY`OnV}-5pMt-57%AE(b(7zCs zLI~FXOxS&crlGOXX|@IJbi0dQr_zQL;)F6SnOb(P3f(|o->d3sp{l2omj8J$X#2@W z%uiE7_<0o^j17miHLS>+D0(A=yyJNECOP>j@@u(x3!sW- zGc_~YK3*+Z0DFS))-}~ zGYYcU*@cA{AWa3)H4VhNd=4oV{@RDhq8w~dD(?jpHh*oueM^KaL^19L-@SLRIg`ld zDDWrZoShtW)w(RHYG`0e`n))SM`B`T#sm>`TNl0mYZdV$%-_F%vqr|{TK=fCCI6`W zAqY|7PF6kL+TYh|s($uI{f15{3Upq=PV<mhlhvDG>>>2~b<}BpQR6aipl{`?CV^v8vpocXu#XhmPPzQERAX7xi2Rz20zuX}c- z3MB54uXFdqA|hVJ$CHEbe(!wp?SpKH8ocm%%us3dK0;*uohBL@LZAb_&cGnKc^3!v z_S&^;D9N4QeTaU$P_G(KOG|5%l2xrpU0wb86=GHf35n)j=BC`-%W_e49scJ#sWz`8 zK{0@_56E|GrJ!UUlz5{Q;w-Tb)YR3{QCr*Ftz0Dy&+om!Lc;9Ft1-D+Kbm~+u&Sis zNaDnEZp!+_#l<0LDJSQN>q`*B3DRq4W=uGM<@6}bsppYE2twp=An(6vGr|rETN2O) zvqrwnb$g(!+>tI7>(*wW33Zdpr9 zR>ZqV38L>25fg9!{mOfti|bmEZY5;D29$(^1O&ZTLaPNPfcH!s92{0|E^~k_ybKOD z+njFvUhBdJDeWUoUGB2XCy)-FY&J((e2q)w*8s##`6(vi*DrJZX1|{rXoQr2nK0qe zK&LJf!>WwP?pnWnBj(}Zkri=sb}mit2)++lDQh1BE*~JG<&bf|*8dp-rBL zfF7Hd1*P@5;kz?4B1 zaPZ$}JqCjCV8lSD-i>?OYn2;vzEz`y_r9Het@9<+O|M-m2%R~->nq?_j=#PT(ujGH z2sunkdwGejj1~lgS7&(c{6-wlYj5Qh7A_UV_Ej#jg7lt(>M-3V9}$R1*eK9fVmBSH z6y!t}eLMoWxYP0=BdP^($M&C`)c3*=(U~&xyHX<5hrfL*gIt7aS)Z(SjeFeaB?wY% z9F!HPrfVljk>CXh2T`CS@dtqM76b)TfT|vQquPX&l%asK&7gGA^nFa)6x5S1->9kK z=y>zC-FIVEI|NI^a)WHgi^WE33%(+Hd4L0Gx$lqJU;+7|33l)PLYi#r>%*1&5%D`W zmmMVucFFbW3?Ln#nfriGOa0EgaOmz*KwNqAAlqsrmoNyAHVo)ewA`l7oF*Nv%#1xP zwV+NiVqy%?f(qZcBe7Ropr|<}0k~65x!qh!`Pnl8h_SCOT_Z!Gz&ce`RnscgK!?r{ z`(UWt;;VBt8!M~n+~-#aMv&z> z%b=joqoaFy{d&nHfKeI{D6Y$ zll3>*Ri4qhsuFN}5fKqU2ht$y?Rjkiroa5N{@{_3qRetVmK3GB1F7rk829(d$?^PO zt*QWOo`3j2y|%WdM0*vUDq79)`5|#IKE14=AzctYJsxUnYpW$&F&-dvreH4%A0OeL zKYt)uO4d%s#Kbu5F01M2>Dk7XdN z1TS<&UB7*s43f_JL}eQ+dob@&&Q*gpFaabXBFPJ6`w%n&Kv@j(_YxNlMX8md-AZ!{ zi`I^gO8}2s0As%6BZJ`q03yr7+1Gds8$#&)4$;)q)ZiFl+@sBVvoS~M%?Mk}$>E_@ zpL?y_I+fen_rL<}5+(>44<9~U9xtIs90b3w$z0XnItFT@pR4i2hLHThCQSXlm1!S+!lH4?@!0G=BaKn#VsimUr}D2M_rkb?Pa z$8IDfhH`FiZJ|(rx#bEPni$3Fs!{>-!;>f9aSw`(jcqME1MfNPk~l}x)6+u^*L#1h zweWF;g1?_15t4a8JbE`PqrbQnEWF z$w;Vx76v3P+QGh^j(4qLd`6w?w$!S!6Ste2n+|xN-^H2x4gDH|p`oF}<;k5E`o?sFiG;z3RqN0Y;f(JAt>4MIkW#WJ z=^git_O~pGC=|r%4)+;fY?Q}#2RR`b*~f+;Sk=N;-ew5B*ihu%RhsZn{0+ zu?6J@z@IYT6E}ngfamKmN9xbqV$*UoV*nM)-^;Goxvl3&BcpZqg zkmFfe%JD&579bHS0F22DCVRFH4!R(kFDSZ1gwev?(87`YhMWaeedBzJj?#1P^iwNIAcFUl;>^OdfqQv#<=&fCXU?D z1I=Zr|5bhcox;Mx!E`C?*R*%Yo=$uk3M+#DPY`wGgb6K3Hc{ff$0!0Z;gyWc%*x_L zxclMx$>!YVW)$EmaA?xow{Ih3NevARj(>kC+=W??S|eCGRPe=4Aj;zi@TK$`c zH8AvZ`O1}6kei3V#*!Bo7nfF6c0lO@gGvRYw~)mf?DVox1DO2|fDG23S7tC|HMWP_ z$QaZ1NF8P-BdCSOJkNz@e29?=qP=mW*d2yKo*Pi@1E$I-}5aurT-vksq0vvugkNz4+nKoo}Tk zQbo3C0^YZ8!*wB-K{zkk;h;K(!5NhFPh_|aR_L+299=#I;T<`z~v|KO62SS6S zi^$BDq^3J+3o4LRv8afMh`&cJ17g8|_Lv}Q!6Cs@NP2kG@GJ1|*1*DRJa;}$+dfoM zdRb7wwYI*#M;DBkd6oCam^X} zUf|#jIm-#+0nF9KQ7Zm1Q4TY|FV?O0rrR7T!*ATUfuR0(??`$R_%MKDLjnVk8nL*4 z4yL{F;kXCoZ|`<+M$6xH{w4pK28LH_YY~tRNi;yj<+m|_#U9y;^gXSy%6D3T5@86^ z7N<|W#&wlUUteFq%ONa0yt0R@e;nrBZs=7NPPw2n{Xhk5Z8;(ngRps@gX#S)D=L0{ zKzjhV2KCIy1@@fou18Dv9Kw$*iB)t5DY3Qzy4Z#}$W?>LDulL(ijq@O!U2qNsb%ZK z5iTV^re2j@Yaj+T0Rcf8jm@Kpz14BSeRn4(G*nUOPt+FFj~_pVeAX$<-v3eh-_FYDg!pJ3*Ej0ggl2D!}i~N3o-<| z5xo2RgM$qY?$fbCO5lXLY{Fdt5h8>fim%}r*fOf;;#6_6(l&lfbuvHXMM&r$;->6O{$dcrt*LlgjW;ab&7X6$-8-5?_BzVRCFHU}ieJvX=8fTgz)+6_2m z(UR!=RNyFJvhm$P)sGsd>+rAHjSW0W0nR5dCaJBhjU;D?qk^nMsNF7lGO{3K5Ezb9 z*26=1+W*2gx!X_qFA&0}-%CwufH1F2cG+DX>KT~q?ZrW;2_y-+E{uZd&%u1+y-e8% z0x~ko5osxHG33(W5bSQnQ{&JW?lKY6_>;KyUiD3^z!XnkKPC_Mh^ z?bqeP1_SN>*101GlGb%*X6a0&d-u=`z5cL#F)!zj5(JjQ!`s`I+g%j?h0w25lk*D; z$iOb#he=WDcp2csY6_3opn z#!Vd@@Ksb)kkKlb1(Y^5%@{kym$3torCGd%8FKM!+Iv&1sQb_K^mI??Z>Sg#p^QN4 zLI{MdFb#_ocweHg@3B6Bo9R?o;%XJ@qz_4H9N)@YcKS9vyanel4|F;^C+B^jQ~03B zfygsUS!ccf-?RXm%@LM{YLg-f@X^i()Mn}DF4S1`a{{%*`>C}swy%`=k(Juo+8Uvu2FuLk3JvPX z0w`<_kCsx+wq{#_E*qo>()qR=X7m$cWyA*|hp|KRHVwo{($W|j4(G!YB>bDEoxuWR zq44R^r^#SK%6K4AVg8=-(+oDf4@~x52DdZ1p04V1o|2N%45yQ-y0i|uyxlV z-a~Q6?e22|z_HY<3s1k%ixfh!qqFmU;AgkS^c-3zCMIUfS7IC>-&=Tico+|)h`|W^ zD_|154mKhX(AwYs@X2W%)n~}Ga(;f|Ku*OUJSB);z`(0FTB&caIMaRUvfO5*_9iM>s-oOD^GBUM{O7p)s*J790+>m^2h|$vd@0QKqk_(;uV=h3u=KZ(lQuUG>--Jb#SwxtaCB)?(q`}r z34*p{G_enqm@y0;S9|FFP-CPYb zYAj29|2_Eac#bBLP{?0bS^EddLS=0WRmY z5ZR)6-@RHiXbx%JHdLH3*VyjchniPl9=enwaXbcL8$au9e`*MDa$Y40m3A;I-+e

ps97$1#wV%C5L(O`kD>@UAZ^2lo6uL8EZPzNCIlCO8-?NAv5z34kBdaa3V6xn^l^cny8wqQ+@X-QElfDz`%B;;4*nx zW@l$J0$GjB-9sq|)k!!Y!$PBG!%cCZ175-?x3O{Bn0MI8GP^y>TK=)508L+CU#yhT zh={N-3IzmF<^1ONvdq69{sLtWFS;N^c&_vF6Ne&c7_NeRQgm|8-oH6FmtILrpxBZB zs69ic?%4Y4s-AiSQ2$%tdsqQ3~OLE;x zse(H9z=nmiH3pr9*Av0~p>6Zp%0<3_3breP6X{l$~brnU^>@!J72igI2RgZILW zdD*K%)+q$p>4+ovGP>S>mp3I6c<)0KA@cqgb1So3W^g-&;*EQmWdtPNT@PYEGAP&W zE}oc8#af^}Hhl!7-wBU;U;2&o{a7 z4MC_h|Me9O_eWO7#sNT70}#MuQ%PwDL}xA@lbRX@ML{ClkJtlXLU|iSN*bmhTy1>R z=Z}9l`r+`n$^q=4u_`7m4yHjaKU*F|14QfG6`PcVqo}A@>lF_MjgEq%_m}u}MzV0H zo!`nzNy2LO$xL03Cp}B*8uOPRFV=OwM9*#V9)+C4edYoke1zgbPzD5V=y&ixg|Agw zIo}dCcyB^2Gp6d=CIz7&KD3Q;NAoAJe?qwp=n+_>J6ntKMxR?-(SRQw-hZ2u=bA__ z!%wMeu%xb_s3--1&1-j=v6=@`F=T8YU~+oD{ds@dh^GSH5vlj z%a@qYBMp|f$T(zWF6 zmoHyh0IjB_rw8IooDytoYz$NHAsUH;&6#+G+awX0P2-OMnHEH7M>m^EkK8S#CMB%Y z9mS;I2@O@ZwN@MKcVMBROc zhLfc^ZwX&8XVNLi+y7QlRqgzwku3bOpGS!^~eu0h7$CRMDJ@UPkO60$||oi zBS{Z}F~a^poEVnQgb91t56H-GMQ+P1LZZ``_kL*HMI73U3U&(q=e3>cw zGUUww=vP7mXcW=#HoRcHHWT3GZQ;4+5o29{w(=#()0JMiNsadDbPh4l-UVu~(5c0=M zjIdQ*eoBunf=v*FcQ^~B;*J_dufyw!G5}m4<^dJf8}OD-p9GNV2C&;D)iYdA02m0R z2Hj^QK}vyTx0~|){rlGu+PpV(KV3%Jb3jA>5-(VGdQhBxdg^0tZaxdWfDSmUY@y?@ z6zsJ9O{4qjQAlGLDOMp=hJ=T=fwlrT;;rEsIVl4bqOkKu#*B|qw?c^3GOZrm3TXyt zHGFjNp`fdNb_DZz)gt^nTuI_kkb zJT@~!56|2M#3&&JMF_;;w1x&6ptphZxeCG+9otg~EpiZ)d&{9024pij3VJNtP`cc| zL592z=N`O+37P}5zka=hSD(y64S?W#l<`Qe8X{r<%y^?htlQ@bw92F{Ek8c1h0eKF zk#4r?31aFQ^L~aV5?E-6f;1?Kp7D&vKcVQUC^}cd;BK{$diE3&?|_L zL4-oP{AvwAu(~iFiq};Ptp&;h9-;hqO#TilVQ>_Ay@r5zN7&!1mk*IBC)`9sm})4s zG-)4%s~H+bLMN>Sg0rQwsEsdlV&LO$nd)zW4n~00T1`$qcHXh|C`>)R3p*`XjxL{w~V?JOBbD>qH!wnxdy2rhNGg z0_u5Ch{>D9lWYjSgoF2i#z?|V6Lh5Uk&uvpHCe^vVKAcdbi4zo$?XZ-5~K_59229~ zmj5)!%Bu_-14zvcK}X8Ti4SSVJQ<*a^h^iod~0`C!!<-&x=5=+@iv0w0VTz*d4o7Z z7%Hgb3AfcTTp%PX$uIiU;&Z#JZP4Tghk@Yx9W0JCyK-2C-7z^ z+#3H2ad<`1=$Gh9JmA0(vKNpw8VY%J5xjFKdp`GlDtHuird$-FmjU4b^0qIe?+JZ- z4ur{E*$N5K73{CL$IAk!gq4+b^nc^-J>$84-~ay?3Xv_FtRyKUvdKzhWtGgNLiU!K zy|WU^COecpGs}#O%n;d;nf*V`zTfw?-~WH@cjf=SeJ*@%rI+XHe4gVtj>r9YoDl-5 z-ARdwbkCkWo0^$vvNBWz5P~gQ={lLQjYBI}?pEFsP(|FvsKCCR>%fDJK8g45jG+`S4bMmTMF7M7Np0Q!JqEIyg=OAaq+22owS z9@JO$8eyuDQB&i2czB?SHHvECOUOquU9r3<`~(!wSF{fd?M&`|bK>gF`pH?J7_5@o@&2y0OV0-~)fcE&`N8luD1*m=pUpCaxg{ z6=A^vPLY02o}FB)=FPBNXXRB{R`r-XegGiTe`VZ^4u@(%BRIjp!Q|`XgC*j$5>zqi zrc^Wm0*f*DwSmP=^XJd_Aea9Ifa=de9~M*kSf^(Zy``jr&0hI^%t&V2m%akhMZX(yqNQ+h*A|>{7Mol_;dv7HPTIT7uFQ@MrP{%DUEh)xGAk9>+)}b^iDJc|Q7w95d zk6j1v-~RUPTU2bU9~_#Wxt;CoUL+?ofrhR9Q{pTU5&XqgY1&Y={%vt&l9Gj` z5~}ZxC=EYT2xz%}{d(+ugQ`d&=B;o%wbiplF#7#)V*NpcAyh$q0g^P^4UcD>TaX(o zyi&getES`dIK7A?dKLVyFnGiaFCU~NCK6zZfqsDf3h9brP@aKc%{L)|7St)7`PG4~ zx0**srV5X38HH?^0a?9Lkv#05dO?pGz6=l=41jxJVIX7E8p$z%r-NFAL#eU3If0Z* zwEq3UAK_tP7z`8(?Z%)4iHZar9UaB6et`310|pCfv1%F`&4~gQq>POEYc$KH6QeU0 z_|dDX3D-`;>dh}(MFI!}s;m+cOi;GD*cL{c@zsfazJAGBO+RW4xRqi+7OC4HUt!sF zLJ>J6WPbq>DzW`350g?YTl{@!wOQVM+g)HqNSY#~doTHUD5Ny>K9*MuEjKuA~^qBP%Nsc6Y@bapXo~?fNZpoRPo<2V|cmx)RI)nkMA_mls-v-`?HZ@7Z zH?Q5YMeUKxYXU{-Ew7F&GfmqH%ZZcpk$xw5CRw?MMiTR~yuNW<&Cps~NvIZ=?%fHE2U80Emh!lXW$t+qG9u zb?;T*1CoP)fM6X0%er;Igybq8yz$HBCiEO^K0?vf&kVD z*EkTC11SseW9Df3?9zJmQ%|td#8y^T21)u?Ryj2P1!;myR#eA|K#&6-D;H#l4#{88@A7Di6G5k>Rx(7ebYEKp(!>x_)rDr)fal zJqFd+wD<2Lp~zygG5aNt80l|`ELn~j=64JX49bc~h=?p>g>uZM9s53_Y%G_cMx89T zYm(}ZOTvwCO-2K1*hOUX2AKtr&8jl6OuV2QXfeW+PxCPc`c~8I^GlXIVxL4(aC3wq zP8vQ;I2Fh)4?$x#SwwIIT(>7$lEx zKo-v`D*E7YLS!Tfu&HDB(qOX0M*=lKHroEM350!~i+#KgpY(}yKAkaEKRFlq({ z#Ny)OfXT_g9;uZ^PF5!Wd?XxRL1H1)t}z%m%d$@5;^Q+43hwOJR9A~ky8I;Kpp%v5 z0#X(I6r`w)0|Ot21R;ZSSuU)gyM#iqFl2%v@PLkv4$0|vZsg^4b#+b6%?-NTgcnJP zIzG&YAYOa{Nt*dERPK#OKbooO=vdF@K)vPP>+K%*#=-&F)-u-?XkFywl-WywYkuoK@C!}1K66waf%um6i{$|N$dlMaCqduM|loZs&9UN zepe|hI1pRz%b_Xt?>p!Qfr|0PAHE{Rv zr$vNYruhX|Z-rB{_Y7us`%ZE1PKL7-#c0Bs$tC@PxV6wUQ_SmX%xZP62stq8|5!G{ zZ(s1f_UoXI-&1G}q*G;wSLLz6dp(052mbrNI?12rh+yDRl3Ostf`hdN`t-b|xNqcf zDD8E2d!QPB$JMHI`jzWcHHklq&nf#rlVv^!eEZVS3(jo#SIWa_{9a zj4!cwr%+=fxzy>G2c(r=7=~l z?Gv}|cYHf+X(qpC^=)Htq+e!^i0c>c0OC~3oWpx9rj3P$e)dBa#6~lmD-UF-c^z>@ z!l_4TbuUYTedtUQ5xmh1b`s8>(_zoB)CD46j!+~nBOMP1Yx+<@@bNb}*@6982})18dtcsD#ABb%ZAwYH+bw^eZ2kI& z#o9}p9aNq}Td%Uhg?S%dNo{k3-zNX*2E0mTKlYKF-)-W1Txtf`_bRcfvrCstfBN|G zOF1#9>Eb`7$Cvx6@}9tdj{JgaW5#8vQN}4V5jAxz8r?H;^MiwTXW0qHy4^6b;^zno z!V9pHZb~2IFZ&b-rCFK_*|6&UwI3^zayFd$&BVMHQry)gw=fiIM^w3)wBpIWeaWoC zXFYYkv!?cp!$RSAzNN%7k{U$>6Yrkk;Z$=BrmXG1k-@mQQz)FJs1D3E!`Cl+(~eDD zPt|h?v-OvHeTw~M68qtAF{5LDvWvdRhI1~0ITzWmsV1K~ zBoX9Th@afi!?$@tZ8U>%NIvVpaOUYE7M~Z^Uar&uQ}39;2u4g9N92gYhW7Hfm;^Dk z)tkcoj!D_JKx}6x>^5TWgJti{r_EmvlaGSdiT1e%(T7MrP8CEW+}~L8~z`r1XH{WIT#!3$n{t4uH0XrUrl|2b#M2% zrzb;zxGMRTaX?9|wwsneToi8y@piK2teRr&K+B3tCi5lS?pm~vmg z?Q49Y7@5wc$V=}ND+B@ry#oZ-*|p0p@0Y9(G>l!B$}IZJhb_(h_M)U=imhP~-)`D^ z_NT{)xlM&S8-GXH-aLso@p*itorQ9 zu|tE2TA!`rBGR9JVjE#&!g&|3R=cAjpOe~C`?nRv^E-bRd8O;?x-laxCidsCExVG} z-gA9XF1wkPWFD1h{}jR zPIL2!(6X~4%B$7tP$KhGtWF!;7PWl2sVu7r@lsIn^u_;J0ND0YvuA9GEYqw#I~QPdsQhUi!8<)$yHnP|E{#uvS%{;YGlgZqEK}xZq(H_f58J0_N4)OWR&UsJ4 zbJX!unssncqW7qLy7`#a-#wwjy=z~>OzqO;G-bJ82w_^rP%sXvbIyWj9G9_+pKs6+MKj{1aJJ+8Ji zgX%;7BGJcJrEl7qhA^-(GbpJ?xIegkFfi6cPo?pswSuS0mgmY#>m(cbzxTImVp>@D z3S|3F@9l&zSt!q!*HUsS#4BT#_uq2S;Q*G1PH%JUjbx(xc|TM<-@0Bj*35V#JMwN| z^*Mp+cudck8_{#EO`mV++`zxFrtRThZr&SG_-ze3V7)8#Xi64#RMJGX29qXtCj2jM z|M4QcF`VTuUDrGz-jqbP`b58q{kGiww3l5ifds8>(Jfi!rxe-AlRK#A@msrkOlHS8 z?ZTq%U(;S_(SJjz8RUNhKexjBvLt~uPPNK&PYKGAdV>dPJ?xTN3lZAdobJ?o?S3BG z&Tpcl-uJH&ZhFSf60(V#iYH;!+x1nZx9fhZ>VD47;OtSaA!owOnn$QE=Rcc5$ja(Q zd-7LzYert{%>zQQ?w9(HXYjXNb(}^DQ~Z-2OXU#JeAHB+n^8HVUl3A?rOY^e#W(KV z%6jI^UE}Zl12)sRcgGZROukwWwlGnTKBdQg@4jE)Ax!E_u2A*oS&gM1i`i-*L36HR z?ChD%hqLThqx;^bhH1q@^DH*5Z=W4zt4OW6mUfc&;5UEXNj$1Gs>!QnVq;$ry{&HE91zfQ+&%<-?v zIpOn;CF9R;1XK#nP;ST$46K-<5J+k%=9${2^RWd>0?o%egHhMTLFm)1t6PDtX<1Fx zxeL;(ijMlNkn;S?r?y|ka}N}0>YP%Qm1Wp}1&NUHTx;Wx6bYW_NMSC@2$DU?!8V99 z2L5G5cVAWu@}|EEUW1=&w9@>)9~A!ktq>3YzvN=-m$mmPgG5iqQss$|V|&*=VxFT@ zW6^eGmz5=wkr~7yB`c%staHv6@e@%BQEHn!ISMZJeUh4+jJbWW*TIYLu*RL0z9w*Ox3<7LkO|QJuM@wuCC_KioHo1g$5- zAbFbcC6Q;9;mJNVq7lGc8(LPFFJ8PgI1ODtXCRGAr}_nLHt_p> zp(h4unCzsPyBWW??&^=YjCkc`})}(BTyTni{HFftvFj+N`0e0+{DO zX!p)XLqiLz0m=`z#RK4C4|jKWBrrlD{q{27_3J{Vu1Zggj8N$w6-z+jZHMaM^z7^@ z=xYMJl*F0)+4H);Cpz>qEJU8Jf^=aBWn4hZGDA&qLERx~KwCw@`O! z23;NMm(AdI4#P!OX7}%Nd_VyG1aAYnn$S!E8ilK{9TYMRN0)(90IA@@haegQ_47m3 zI1TDps2}Riov^%Swsh@~e{swOs!%dueNf#T^o2_2H71x|0iZhp9^4Fdzd@F}6q#9B z=yDFI$(=`_A+TN309V4FKuaH*Gv=l!2Nd9g%Ivjmn(XXsq-`$qDX>5)kA5TMgigQ5 zg8}Vno|s@n(kN8(|9uhie_tdBv~DyYpadZKTt1x6AF07GAZ+qsYVd9D08BLsBMRO(;A8p&(Uppu4iKLAXq zV1@eD;iWc%MveZ&eXkUa2o)NUC<28gJ}9I5K|jD0)SXcM8>S_M|BY^E@6z4wx1H-a z#{gOZR0L3^P(Feo7|M44hQavXFr?SkiXlDT%E}7K5FmI$qZo@v4al0gOQgByX!#zV z0$|+_YI?CyweUJQMl>u`DYIZD=lG+_!T>%r{K2op!1X%Z_e)Pft*a7xMwj_=Zlj-- zmX-$k6c==U1TKQnzO;=^ah?oY`eWqm8bywJR3XVnEeB9dEOzjFR>7k7S7bY}VnQT~fFeW0J(1m>-cvvVL+eK1oXS-q^E zFcQZVxFPPg)d=lHHh`r#fKUnT(>I|_1@+GYXQLH(OST(>_Kx^1uwXC~4@gNlzrV8@ z3L5Pc==1R6wP7*yC`TJXhe`(Qqe$A;)7LM7R^8aRxLhT{7!uYwt&|4vEfv+I>*!sza_fAeS`S|z*g@iPLR9o_F0sYMehZJ5_+(k5@?_ZW3d2SRzm@gsRfO_2LM0l>WU!yj{`!Sx=Uo<5 zh#7>Q1`Yt|06D-zW+K4B#txYP-46RxI!7*GfoLCwBJMwg9CgwI+k-mGLH|K-FNa^WAp|1|L$D;x4Mrcam!R@RL9HHuuW5KXWH$ljel12;^$(9=lSR8S^of9A`3c~vOc_~8 zXum;Y%Z64Q(#hEi_P&YfU_Be3I1lkgWh3~_^ ziz5HWwp;{o1*RuD0Z}^zNQ%>NQlZvDRAgghQV-1nIs^7^*l!RmjCf84Mn*ocAAp;Y z(94Y?hto1$J1sq3S~n8iPXs`QBH{hvg8Mii0c!;+445x0E+WPr!SVmwA=v~I29_tF zOj_u*dc!3W_|s7g08h5F zv-5Y&>x2;Yb2D)y-JzX%P#P+f@Q{cGK>cD6Yv2LZ7yy(#sHa76Bwdv0b|lfGPy zi>MFvWUto?mKyXd=MhH+QKn{R2cV{K&6n;f$wu0y?aI!sKi~qaz!i0 z!_BQ4CIAThz)N?zolU2Lq~a6&CZzTNSq6L%BG}K;UB`#sTJ&`0s4TC!1RFd8vemS; zcbdupZtiyrJ2{+}bOAz?3??r$2{bl0XON{|VAY~W+qPaMl43x1GWxqdjkaRg0ks(E z$h3T6cfC2$79Ic}#7IjiX~LkTJpNb|dJjLZ%O8WsYp}cVv}Y;gS*5 zO9sK!r+{JeaI}FF_6{uCBr$)gT!h zwhu6na>4uUZdg5sZdByuo6-IYlUmqx}hW?E#;qNyA4ba1n5( zb~p$~nV5j-cQg9cmC&D=akb1?cAywdung4Bk*)HUpyVER%u`HLkS5|3KxK@2{W=H@ zDrjt6A+bS;H6Zt~!fpbmh%{X8#tR*smDSY`VSV2b38F&|PUe&lFtq}e1>3#4iKIDv zH8IzXQ*Lf<;S7vqWtsr|p|uaxIJy!HwBRQAqA)Vhmv9%R>lG&WjJws~FoJ|E9_}IF zu3BNUihBEYLLrJw-C}xb${W}N)NO#?B|PIa5D5?1%)g3kaPYVsqhDfNOxt^!?W0AWGx^kLY~fKZOUL9yq>n{3vn(>-3Pv z*YJT4c&EjPO*W`*W_AgXFn_Q%`OG~$FyL2TF9BjO9C)~(d(zO-e)|5M2DlzxfNDU@ zgTMM(@9{h*_tLIw5bXTWy&qRiV(t#=O^x$f8<;a_G7<=|LEjOyvYbbvA*>eOk19eLQNLrvk4(1z17 zD`WWzAS%nl?{#cvWtAylW&rfUb@uF8lrKQ^TyU=h8(~a|1EItTx`K)M8h&oB9ih@8cKHAl?AUw}^k0JMjEe;`?x0{Yg$!2$VjK#+jG zFkrjz{)p<=Bu@@0p!XtcYZrbu1vo185RPFr0-Onc9Ai^_mlWgX-H*sppXz|3^;;y>7kMpD} zUUhZ#Yq&s)O-_Em!S;HdHt(!qCH>nwuMpT0>zI%rBpS9*-b6Sy1e$7%E4mJa>2-1_l>F?hgGo3~d)xVVL_`f5%(STZr~JPP3$)95yM%zT$l3V1vaF^&7Gb3ZGy1XAzTPR zC1h>~89mz7;E0ShqlQ2LY6%G^370$nXWVjNRROVbQ(wQXZ|C;F0GuT=A9^KZ;G(c` zkthW}*#0+G4GC=ovQH&N%;)pIDDsxm$$5Z@@W8Y`Q6k*zk2;xU*+>zSy}83S`-Fp) zhyP3!tu5zg75OjU7;1&*t~?VtrX&`x)1r}#+OSNp=Bfz$B7YfJ!U%W=GCDfcaMfS# zupml?Q12ixB*4h{0;-Bj!W0H58~PFNXP-8pr6j!J#^y&3rp9?v2{Q||_MLwswSKPE~>I**N@2N(sy-o@UA%N7v zi7Rc$U&sBj&0_zBpw@?|-ycF#0xwU9kdfU0?8qhH!2ujFKANhi_Y^wXl*Uj;5gffZ z7^!C&0WM{5lcQhLB zp=Er7cdai~J6Ol#@_IV!4630)4&Hx)vVHhzj1(9JqCE5JTp$kycR@W1u{i6Oz|T6~)752#EE+m9UYY3#KbA9r4mvE@K#`3JT&u|f zycq(Q0APbpyGX5}Y}>H1H}=tt0`bDo?%W88AA~FY5w*7 zK0w#d9{|PG4!Hl7iXYW2N2T-c0ceGSNt^}G?Xa%yZY=!U-OyNI^Jhj5$dioJRHsGcWeXD^%7JD*QaU=WZ;bXcEx}x1Hy`8@-%kJ`Cvx6`MOapzKYHbs9sdd> z1Q0XU+DJlv0o;X)F*Ki4AE7x63#1uBUu1=tP^1mdhRPSP$DylFq4%4u+-ibrH(*K* z%>n?W3-umA-VKnQ6ogN}l>8t1RazF|C~k-9nrU=68)W#WkC z)e)6QvY!{(o_2{D*moyW$Fvpn=-<@+o7d_V8LYN+Uy zThU5$_A}u*e>SO1xs^-(a52Tq64YQ#0b&2Sr>6}}`ivk&f^3KlTp!`Y@`vkO zulJ#}2qOPCZ{9o#F}(l&Ci_~-$>F;#WkXm>h1NHNH7{NHO|WxZ!xPQc{MCA9-o<{- zv9^u_+c(?Ycgt^CsLT{M{pxXEtjB|D;G$b{ENGPslbGfdSk z-ExXs!iU>G*(rZz-Aw5J<4fL;|R@P|%^1-M^3c_@#6C#gJ#7pZG=^<;&ECI~_UdWA38kh>mW6R&) zzdzxlI3&<;&Mtbgf5`haKM!jK2O;wuDsMQQWAw%rZo|FBQBDu?+}R4Ba--Hr@Qy&y zYmh7}!1NTTi{j*XR}!v)?pWEBvmM?&gzSVEsC=2bcgazO7s3tHMFZ^t&46hmH$X5? z!FDnDKljiu$7?EZ+?-X=lc7Lu%oZ7kz}gX}+6M zPnT$`ELTn-P~^<(0AZIc&Zf9M+Q5q;P*VfI-55$)u+4mFH3OvqPLqOYq z1d0VM+(PZLR<~;&Uc=J!17(D!rv88f8v)4=X+QwjlE7I`kw6y(Ezc~l29RH_pd}r+ zil96mZ6y#9Kr|w%k|GffQTVOLmD9*I1k6TIo@BAN6RaDFS_9yqgrqaqHkE)?OEFj^ z^hLp~1rc|w0fD(djT^kq-U`Z$+1hWH>ms*W=y`c70?U(cmn}n3_2>FL->ArzPh#Rq zVQOVM!(5g>1|yz9d~Nv}d2?D(8qrVUw@Zu<^e>gZ4{Nc>u@F?z>tMYt*!8SBS13B* zV%|%!A+rn%;EDm1l*HtW!IayycG826K{MJzs01 zB4%#+j|Cvr*^Bx__hRV@sWna1yqEmWH)X4n^|_vo|ElRo zML)&dT-NKuHH$prxhze7-@gX+|M)f;Wt`$A!q+8lf)hD$_~A;~t=1o@Sti~+GCzEL z5)Om>wX!5C!^Ylu%9^jpQA&3E6d6DG?tDH};-|Kh#)F*Ad_C@?sr{Q`m7b&+qaQy7 z%=B^8ayuisKU@_(caF15=~jQ8MrEb7aF}T2!@n!5*A9BUHb~|6Xl)iQjft1=-XKz^ z_LOt~Ydo9Tnl7zJY(K`dz;7iyD!daT8u9V3MWwyD_}zy+8Gp?Lx55jJtcG#k*8Nf# z)2Vo`G4`1C_dd(w8r4o6?{Nl2e|bb*8{1BY#5nPY_ev~&j@i@Z@@38~ub+}%txWXn z&+e(Fni%0)?2@h1RA5&J^x`?@E|4KQwc@o)Q&10Nbu1YJ%gU?>kK~bAd*rXv@)^G0xcH*5tTpIZGlc`!6-y`-j0>n=|@B8sLa7SO& z(fH>5VLoYLdDH9b5P#tY?QLbBXZkHA+c7NUxyDno?~NYLMT~FZ2{C@e+-mS*jL|U& zEb{UHxLQcDY%}+j%Yp7XuQ$I66gPgZy7~2Mzg)`*v)-P`xsZ)(>q|{_c6^n@ZvuuVC0_^zP`SA9 zoO=82V$6TOL8r4y!oNL5u!4Q zjKf!K_FKuH7UT|$pH8bS@^8p}pV_zzsn^VQ@70^bQm^?t2KpH%Ze5lCtok8}+=Dox z&OH-cw5J-T2b{@q>-WkW=&78<`&<{qT7HP>t=4n3%vJ6US11Hagp%1G<9TQ-bG5U6 zEL+~^a*NngsIEQ8*(J5Tichi@n996Nwsof1 zeODhtDI$pZ?EY%&yA$o{NZS;}c%@0wR((mov5Q`4eyqD65iahl_&#Rd@BjUzeQYD7 z87l%|5V8Xcu*h1ca(_%04m$I}0_Co0-_jBi+mQ{^q zQ;CbW)$VYeGtSSocsQz4(w}5|rlj&LhWYMuiT8tLM$@=8^Z81%5AD26soJWDE+#|ywt7hJZlf9pnLt8%yG~0OY2L7Gj_@FlY^_7LiqOLx<9igiI-M&wzqz*(~ zQTtPnoc6XT7FqgNGLWqKODXG93|YyX6A_eJP}!O76aTo(X-Gs851o;f4{|^Msoh+`meB!fy@cBLFy%)|^6Q7GEz(7mgPBu5Oj3^NEvo|{~ zxOjW!erisl>o@k*Ew3+&L?? zO)+KqPIg9Jmh<|@(Z<}hOvRKap6?N2)PC=Ta~JrQ#P8J*#Y~39$5XMf@i9Ce(q|z* zQ<31-_6ozy&sHVdRG9Ji2VOZ;dZI?+JyflqK3!@Y$m16wd5#BnRFHa#sr~v8U2fX@ z>vZnQuM%ra6#j%fx0~_V-RANPPDvby7i5Nu3#Hp}G50T#L0lT(udiBViR0b#L3$${ zuD)_~mZ`u$^N>IJmD> zDTlP4_KSkqgTK!Y7-FgBzKn}4C+Rkq?4E)%i0#mYIb?%h{qQ=yI<@n37f&efLZNlq zZoxtHBSWgV$=WTZWfBh!dcTwHw_jTe6!lb@CgoPjjySJ$+_I8q==r^mvAyBjH(#b| z^v%`p&RJoz68w{8QOda|GiE&|<05#cwqqw!SZkrTMa>JjP229-4+8f4k4@D)@jVeZ6I0-vQ(CIqVe7soS_-P_MraqzTqSB zXJzu_mlf}iZ!!#~bK(ir&@J$vudK$($-(SjdF9oq7JK@QKF-+(6YDa6CPz+Z>H(^Y zomfp&vl{>D_L2GSY@dD$916Fhp1|5A^{-k~8}9ds@@FfU2+Y`oVU=mc_O2{Ab>ldt z?jWKwZ{@tuvGE#<4B2UQn<*7pwQ=#xsq{*qw zN7#Cs(@Nu}n$47y)GOxA-S(&lR`+iZjEAiqY|m`Fq}Wdk?-|UGHyF-8?-4lu8?wOm zKtZWGAT9XZHp7Fyyo3Bow=lKKNl|pYhMk5i5<90jsCGWC?2y03ttAu@d3O9cW_Bz- z1UDGtLnu~? zWe*YM{>Y>lBEBM2ZX$un)+P?yTS*CA#ovFiu#V}EE;4?k9l5V8`fWO)B6n@(Q+H1D z;c=OpPWn#0#?uLVG5Q}od$|qC^<-?nRxUbpGFZu-D0>=QEmvWDx^`fg_|dC;p^BT* zw?6HRQxD_QL63q_A!_9@!AJY&TiXPGeX!3P`NU+9BzjoqDyVb37gIaVy(IiG(~(DV zhLwceQFhUOaiA^Ulj6p!??Z{Hm2yYyBc##;_saxED(#t64l`?8ZFCx_S$OEBf8DgA za!4WKkUOqn?jS!Q(HlQA@wjoX&}P*-XL!YUI2*g7w=t`s@!)Mp#yC&qR~@grz>$-O950iKWW~0%-%E@&NZ4;tGX|_ zT`VeMc}qryq}$|Zo;pZ0?{KXAw2*UP=W`YTl|^}N2IYvicB|7>j;nY#RJm3|Pw-a8 z#12(Dwr6UD;~Z58YFx>S7}OpP38=M&TtAQ5ok{cL>*S1`rz2pI)q43T1Do5h{>}Ds zoaquZ_dTijs~1#Nb)uk09WDs47IOc~3vx941jCJr(s!}>PgVPmL7oSVPaayfz!?Kq zP;le5R?x+`4WmP|Y5Iu*%}PgHRxiBe?61FEx7YM0anx&4OXB;tI~pmi-oCJZz`}M$ zB*NpKAjhe6Cuuh8^*8u!+Ap0bdY*a5T#oZuFrTZ9wF~(5lJv~UGr!EvDRHeTpBrVq zY@we@KDg;^kKMc|88nVHY3&nXu=miCpWux<^9sE}L*aN(1w9V#W5u%pzrGf0(6%2l z*8cExd8QUkG=}%VfG$zy+q>x*;yKH}x1y8|k*ZZYHmROb_BtKHmtNn$zTq4+f!8CR zIuWYqoSXD+sZR@YQ6D+I#4;D~ZBuzJpr)L?U_ z#EhSggy+Ho>r3opo=wQQKJ=2DGad;QjV)pN%@!+ra~Q+@HueS{Rro-sfQ#C@+_!h1 z`0jK#6z=}!v?h_-E2@vWrlf5wygTjg9etg0d?o&(w)X(ud{d9UtG&^)!tt&OFIrt9 z9jou#XO)C@w4aJAiuYkIBwQ9-7^@O}{hjMf_crhLvYHSJXRmOTqwekN45BifEF`05 z*x_~OBl=uE{@!>)&El8C75!|$2*}5Qe4R+J2uOWz$ZvQTn%QS&XJx@D5a`1`Cn4zp zm-}WmlC%YH2$Wq9O6|&F-o$h>TOwS{9=-tUw+m5GQTB+2xhuOA{OSnuF z1D)q?Ojz91N$aZVI9XcYvVL$ahMDb;aTN>#{hy{AgLA>>nCjsJ_4K46|EBbk3tm|2JogIW>#K=Gi%9_kLu1guc46Ky0eM z(5>a#8%ipz8JFl9n3o1JJ9yYCJbcIs;@J~0JOk^SGZ-)w1}u^Qxr*$8m=F{Z(FW2r zw0fc*L1?DNf_~J;pgDo-gf~Elpw`mfuwsC!OBR#l)vFOu^+^U<8X#0<(9e)N^5thz z=D;%L-j-K3Zvaz+#YMS!GHU5q)lUz?n^Y%>?xeOFRXUPeF?p@~{ZJflwu1$z}^QP-bibosV;eiwsDCwI*{SN~cvS&f$1%UE1SS6vq0h0F; zUjT^BDNv{_cH1@w5gb8RP+2tv_4M433gg?ECpEcdtHXVLX#sb_IAqJT`=@L?*i6?q z!hhNve7r`CVUoCAVITOeEzV$ff@aPuyikcpN9~F2+{Pv|i?nNo8t-qc*jD_Tw|N;v znyRiSQfD`5w7r6baj2(IlU6HmNxAN^T;!^R^rFFbPVDjpp3LEg_g6l#+uZrwz>hSYYjD&`6HH`4{0|39QChH327nOcjyq9yaKT0zRMe1y z1O>MbANWDwn1>SKAvgzPKq^WA_fr!yGw?<}1L_J0>cEGp&HMouGnir7;06GTip1XD z9$hAM=MIxf5EC7pBKWv>9wzab$d|Ok?K#cRk=ji_y|s_} z6kIowX$l?Alv-kKGu@^}?LY_jOjpkxV?N3q}mzIy2Z-sQlg8=Td>MR6M+CH6u# zu8)7$-LrR5OnA7x#A2FSn(T9z<6({6w~2*Mr|jE?Iw%g3-o+M4!)55zis@ukjJlHV z3i60ZI`tS| zmYv<@;Yd(P`R#w*!GL2%nPAN;Qh~m--nfx4f0eZ?l*;9&np> z=xB%riKmXgp`-Dw^1UWBl9sV=J6f9>##Tv%tM0}56Sp9#QR8PE{m!jUeaZB*i9`Hq zR{LWS+ExLf8ogS#1;xkn>1xxFz}E{-wyNyBZpy1IP*(hPr%Rx%(2HSgC#wya=lH4CsJ(ChrB9hBPd4Z`7HLRlP48fvy7!#Ft|)%%}&$`+Ic+qrb^#UytaCTzbV%P%RrMyTVuu)t-aOZSn-^T)RoGXtFu zUgso#YP$9Wr&X1fw`I_|a(%g7;%MPQy-9A!@r$@wu;({ta1%U=SW4|sPQkiJ+?C#nTtj{*Y^ zKE#UNy4BwPTRtm4KNJ)KAlw0xrXDfW7&U}@PTFnk?VG=S`>;a6>_>WzlTDrW#854ESbw;oL?>Y00+O07 z+zvB3ng|ph>|`=v0SCL^1@3~CJ||!=AH!gRdgqG_CY?%Opwf@dGTkQqE zz3=yanNmt?h99L!ZD?KS6ROj`f3f*<-pbk;7FoF}$4g;lYt^>9^0FiT7R9=Ik8!5p z6z32Shy#Zs#C++NnYY5bJ3~k)qq;V2R}AnJnh|hwLNpKt#?PLG0kCRa`zOFWtQo++ z`(PDh4fk(=;Rcul_Q4%v@L0ECV_y8x&|oeyjJ)~*g9S6KPWWlC;v$4adEv&5crd== z^Ey6cRo%`y3W?7Cb51%aBsMO)AlqYB)Ks4^e)8*AnKAX?rQiGh9;ZBRyqN#Rl$rc9 zCcLg-;U~k~c6P;@SNcwDVVN$}O--Ort=(gR9EX|+c)W;7)s;gYqWAE{Q;*V;o95x<-s zu|Q8L`!(wC8@6*3_5ihSrXX z%R6Z?KRoVMP*enKeGpX{$~*+J zj-WvVP->vwZo=PvWQ-t{#)n8$s%)pb4O)4W!FV4291)^mVhyw}4VY~1@0Vqa0A&6U zv^BIf0z34Sz9Z zt)w$ZoUx_M>sVT+7gKSSZSmS6+tyZi@?W70N#Xmyol+!=qh;vNU#0u@WIPhm@Traw zNum0m_R%v}jh;Td8AI&5PA5U);4qlnHthVz=yTXaCWoH!H$2tc@&k_)wcqy$-i%ee z_~zxI1nG9U%Ido3Z?9(u=?$ZQQnxH{Unab2%$01ouro{Czt(0vm@3TV`?xRj=tCsq z1J|W13@IfESGM)Vp3WZ_F4g4hws&=Qvp8&Wvz|-_`9#tFo@n0~@TMi{k^3@H$hAZl zry1${P%!b;z4TXNGs zOorUCbNo}%!l0dI)&L_@Tq{XU==~RUlsY}fpHeyv(wq6M`^wjn9%WxFwcbt|Z*Y#E z{vgfEE6C#%Ci_?yTeA0Anj&`UYzd{awf>{d_Q`wS1wS49NSXPbE;`J%Ls7cqsO!Ke zQ=v|%cZAM9p1s+!(>_5It;!>U8m7_%_Nd@NH?277_Q$&vjH9P1YH7 zcNtXO`UQwju7xJ4r% z>rVf1T-hbIJgC2Er9x%wbDsRU`9+fkZ7R{8`jnof+@9~(&3)Tbg@wu&dRmK>8II@l zaqH{C1G+s1I?kyGcGSx6xju7mz#&R<=CKR+JaJ=Y`*A|=;LuTk$M}|YnElE$!L5p; zNQ?Ow=bv}AMN(KYO?<2xa>^iwH6c4eMYWDKMD(EF_49L@q_Kw+slpTO?#haXrah~M z>S^uf`vasg$?L_a>k_`U}AsACoN{QDBZj1ZiH6{6_ zysJS!^j6*yn%K|iD}Lr4f75LLz25ae?&0ukqU*^4f9=T;t^8v_8k&UZU&7Jyzdin5 zoNd1-Vx2fZPqpr2M~v6|>2nvZ#$~+fhV^r9xNZUL+QL7y<=nnD> zQMOthK4xt6?53V<>(1+9i}ZTU8ea>Y4Z9DwE8X&>BQ;*F6g)pHnRPv@%sp8BEAvM< z+n&?MrCc|k7e$h%=QFZ;m7qn*e(|1n-kq%yDP5O_)cuw5^7EcQF2?Q+du=?%{C;;a z%3U-Ox5&V}z1-eYadk6BkDra-BHH>^oU3O?z70$h;p=O8+HH-W!{Vta#mkj5q^)}# z9e4#R*!TtNTTIN{!r^ljRGhL$1wzh_DcHa7qZ`)f7jXS}`JP;k#M@nev;_+V7sE!#|s=uGseo1M8hrh&Z;1%p%wxYjYFa0W+ za(^>6-&^HzELR`@%7GDMVlSE~A>bGE)$!w!#H+FR<`Tn0+`n}z{_wDtywk!h zykO}@^QXZFt8@vvf{o+ZC2iZW4$9XpAGj)%!aI@HOsnCuvAf`+a_R%_XhinTHNlG0 zQ^$3gtOwV=QIvdi#)_qv@~$0!Hh8?!HDGss?YORHDdk%ny@|%n0-B;7^fmuU+)x$339(^e_H&}zt>IXhgE4r8JkTLqZ zU|RP-7NE}IPD06br!}RMFG+l5nw|^0-v;5!4$H?_yoyii?pX^kF&}*Cv-YgLqn=iz z+HK{5Xs}=Ylg_YQ_QZh)y6)%F#D;U^hWS=bTtk-V$`*DWRxMqsq>40%Dd>uw36UgQ zl-I(7y8~2EyZ~)+;EvdIJse|}=@)jCWmCYZ$6I1dMT2|{Z;pGZZxOVTX1dZ5Z8N^R zEj&pmXKd@ej7PSH4qW{?q)WYXb}}Oz7Y-=wWwz59pQ#zTd}nU=JG+Ui*fGBGQM(H6 zZku(tKV&N3A~cR#Pl+u^IPM(kGKMz@M&55~Byy`VwB&cjHr{q;3ArHNTJOoAd&;bsRAg`2EU^Ha%`T7r)tP0a}Tu##Jbj|k+WPJ zntQ#sF#3KD3%g$N+xlh0GwE#B{AtXO3?xO3M>nG$+phgoc-b+}!6T^~e3z-1&AVm&*KABYSMQ3@EM`{( z(?6M~{sR=So#M3`@L&uO_KuETgc>9Jn_8?p4Dkrz;evwpnq3#oVgdpPM@me;zQkb1 zbTx0C3Ae(LstS0dxVS7UBzuhi3S>{6AU%zu(4;(HrgYsbVcbL^ENlyP$A^5;tA+Po zhfhydJ%6@cFyOwbpt13E1e@TlGzQOrbSc|YM)6X?Oo96PbXrqk$`{P%Rj&KZ*&~K1a_WRM!u~f_>6&;ee=@H9aU33>w#FmA+f*W zoDABE)k%z54LRxuJ?(fX43Nruip6qTo( zuEF@PoQ_Z)T^Pj{b!+9Sf|~^eOMDg$QIRT7gsEq@(o&?ea&eL4+QhN{`L}i}&g8G3 z1-a^jEUarhoQ&k5bTMpm1q**E9h4ZE$`^R$HcK2ux)X5P{uSlK#zE4bkt!~zs)8#LbmAyHK z@EVAkLrvatlj4XIB(PIzk@?SCecO3*Jo~Cd`0C|`2f+oXI>3bNTj=3^ljiMk8Yh}PH5lZ&P={lCFiO1VYo zBtFvAb0%CFL17QuX~GQw+!xS^#}vj}vz`*r3WK7fYcaE;dc=}8mR&8^ULcL>!LCyF zbqD56rnw>XTH@zT#`e^>hPqLA{H)s4-=mvwKYvT7$ex52_Kxg{jcM-ps0%#@ zM{*wxYzg(C4Tx(x!y0hy_z}@93?h<+VO3`ZcTiIm(_iTenYq!TkknIorFd;~&gs{| zF$05zZ}Jq(TRuloz1J*O>bv{%d-CtQyUbUuP1H<|zW5%nRY5bsYusjm=Xd`De|o<0 zEgFhdXFVc>@)d+j#RtUP8JjGl{7HX=Mui*yS@&GIu+){uQ$Zo-jUB&zrL=qZ-CLp* zR$WzV4-)4`8b#=dzJ+#{7o1-)z54;&Uraz5&((tKN3tqEfBt+prV+p)#-MsQ#(V4_ z4vHz9PZ${`BdkY(@d4@e1Cf+)<3XT++t;P|-17;ZpY2H3mN86}c*HrGs_A(!<*eJ8 z+Mi}8S_PgkP2RuA+%GFS9F&>fPxa@;tF^9e?JYjx{<>gx&}6Y-tB0g}JxpDg#St85eN$bJybESb;}a#cBX+jLW( zS64#ku>~jPeCihI6=$K0%@z^o>lQxP?R`^m{_mB_{B%8!QICg{pECFP%hf60z8%_> zHn4>W+^ruWee*9=?-o-qGEJzO8y>3IER?-%b~cpLKz#6l_a268X>GzZQu~fOxP2Wi zEnyKK78#sBt!dAnyq)?~mXPOnlsK(U0&{qSqM`#jqNG| z$zQIozY_FO74&LP>U3>3pLd$m!pxY_xnZ__g@6!3j&1&sPhReMf|pfTjA!PxKYgRe znK+}>oS&^S@_G^TTUj`~I$!%q*o-HHaG$w9@bKqv<);TzUG>#9cd>GB?tj}U??(66 zK({lky8U{Y0sfeOE>ImVbj*6G<#oO=c_5^-HX5UV#%y;m}f_)a=<8d_NS8h+Ee!z4!AH6rpsLCs4$+yWk#gwYEoVbgMoVf$+q z)7RJMdwOtS;4$=tF*Rja{h~L);r+jObo`fw|3IA?J>aYZj0CeWelRQC-=?qIu6Y&X zD?4ChjQ=C#VXq%v4?OR6{6_bmU#0eULg~kjANpXfmnfQk-?_o^G3DFBIt8vJ-DJ55 z!4ZDdg2VAT*>2c*g}j> z^QP@$d%S7!=Z4v<&y{Srx7TlSajfURyseD(oug)Vnir{0cyfENTFY4KhmUN^3|-Prn-?Hwedi2?;9}PeJSqp9Je&7V3&IH*k!k6_AS1UEK##Qwlg_k9D|F@1U`pp zTQWeU=9crPj+ku`KR;I|a#yTDC+X2B$5513XHIXxjqBPggUct;d0bgWt8-E%(BT{V zq|lGC*2{Re1h2upS%6$gzwM37!eEr zyXi27T`Gl#UA=i8mz8T2sO&gGO29kE_zt?G<n#7rQZ08|0_V&X^RO(*0v@}VRRraLKv3bU51{&f5X zus9SF61r|_S%YR3+Fr0d^ToW`-UA0Ts#Q3i{}-rhHU5nNbzA>tw4d}mA))GG{OV73 zS=GL^StsL&&MKSH-Q_W=-8P+PldEN$S})4;NjiUzzM~bsO+Zw4(YG^gw`98hri+|> z%qf@3=(9&}T&uHIXS=At*HX_3rO2 zO`2@`sHD6`NE+$y2|J9;8)e&qf`Uw%Nc%CYeiOC`0LLHR-@;sy41pE}UQqc{xILwW;MhM_TYgHuPP(FK@p}1Ge~&lquTR!hpKLXhs`i+_;NhmoIsGxi zu3?EmG+8-JyOdFAS<>nCjyo0+9M-3IHa|64e!#;&8nwN?>9l*4zh@=+=ye@(w|&Nv zb~E>@RF~yCw$=|C#=m^K_vqmz%KmZx=uNHpVI{SX2c_RxY2S^CC|B1m+^Mr&t(kpO zKf^V_)A`+UhN&&PMM{&}GA3SX9{71N|Lw6O1A9Ks9je(z3LD5PwRPXcn{`hwkb5Fu zAnm=1)0d=?tmj|mb}esTvihg4M*M=foTKFvmVYj+ZQ0aWN2ljgt0xRwZ*~Yu{`1h$E51Bi-Evi8g75Tg z4hz_7yWXvvJ!#HzQ^m0<$x2OXyUL3@aoa2g}1V(qoxckpV9+lkTAp+AATOZSs z)%db`w_-?AS?ni)-T~n&_GM$MlXZV!;TK6ms=znSM{}>ac*UgaTi_@ypNmbhe6^H` zLeL%poN81!U8MiJk-5ia_$payLEzTIJQggg-JMrQ7W}GHE))!O|%!T z=*wi3_>z;|rUpr}ZOdTJD!c0=^GMl1L3h<3FCNv09HYlx$>NCFsl|}~U2Wm7wD-T* zSmb|WZrs@x_wsAXKFbqzyX$g7XTcp$zbw%|uN?D{Ju17dRP(Xk7s{=Rv0Gm89aFwo zuvT7i!n@>GU#eSt%?p|FV_#(%ZDF^H+qn!49bf#*DWh)kT;cQ-FuwJ{oB8!;s&@_z z4tz54IuB>A{YsjuI_eWUVA^26d)XuUQx`oo9!;D~F0J}9pwPC(E}KiKbUc5e#;>*s zo|n@MbTdEx%x2CaX>Md_h%|EIX;e7y%T^t&I#Tf@O~LNvcjX1_arEl9*?Ddr;bZ+O zyOq$JN6J8c9gZJ&AbwF5z_eein$%vEvODbM<4&HZ%c#JMQ zYK)AEf_j{588`&K)xGMWza6KX6qa=%OF)j+I7}fbKsR}pagv8BRl7~RcH2yX9!H+V}8+Ye1)kX zz%`FaZ6xaI1Zz*MZjbj>L6fxh=&&gDo5f!aR4FbNhjg@_ZGG;v`cnH4uen?bJ>T)O z^G?qu$z7X+16I3VhgbZm7?D+fDik6o^W~K1TeEQydUaD=91zHt<)~nSLe#l)=jcK$ zdrHKi7LhKXoDSQIO5BJXMcn{P;P6hkHzVn4R*2m+UFf6}zsgCFZXkRF7lm8s-KjH# zCz?Q>iSW53$RtfX4P@|%xPf^tOluRm9_FG9QwMkZRhu-Mo*1M|E6=x-nBDECwp?u) z1xUHC_nCg43(JGfv1J{J(y-*gHTL&<$xCT3uD0HGUsnbabaYXJ=GhII_4S|@yBHf@ z_7K&=(j&Zz;bseysgv+VJs&*3g{e^Yt;QZQsBM&?nU-*?gd+R!&HW@p>Q-wt%yBZ|Fq@Bb=i8uzrz zTP(KH6ZOGSqb7RNTowY=>UfI`8Fj^humfw9Z70NM*oZqZj62t zeh#he>|BR}gM+n7-No_X55q$Q`Xca^g1A}TzRwA!#gFxJy^L*PAU%LG--@^ff z2jzFu{L`mTuZ(i@@^aWJPIMRh!pt6eY0j~BS6@P*@JjIRMcu}go<|#WwBdfCvf|W8wD$5% z79pV*a0ul#sXq+WFJb^uV&zrJys-Uz4E({;ha2wFG~MmhR4EMD;P1mKmy4Lf1bOc)04K}>lY=sXQd@nn`s2s@APS-%4QV9n z@HrYk@)NF#807y1k(#SH7Fy3R%y(ZEA*OH1i0l*(1;qu<*MszQE{JzRYeP)MFQTy!)3;C;AsXSR_8=0< zZP}h>KzC!V#Y*f_r3Y zR&{A^8W_YXEJ@cq3lIMa*HXB28{+Rk-ON<K5L_)~D~+LKYK zDk$uP7FE2i=$vpSw2qSIh0mUi#<2ExC=Fzf6Ut=a;kO}7wKwnv3>%x0H90tk3`S0S zr9%wP%ow;6Bp9zfn-nl_zBFeIsgab_RCxsj_Nl9^*`=@OYp43EF45GTT|R|@{^LSI zSJiKVbvQfPqTF{^p@1zA-bipk=YT$h@!J0Ct7?aFy`a{CO_U}<(A0zoTO_m( zbUTiKW|OTB%G!hc1)?U;kyvW0s@i$4QEhIk<<2S*5fRv>lmR`2tf(Qb06weEgOGw5 zsEersYRD`qt2lD{bcxU9%j>(iiY^a$oWhj47GxA9VfGHKMxzh+o~ZViUQzy-?=ee9 zBUmX2n<=bE*rC#dgoO4E|Nl+HYO4A+DaG3~=csb^@?|O0Ny(&LIqAOVf?fAg_a_xhVn;3_Ek^J$kKlXyXMs_GQfvWTz)AmK9x?f>0#7qh2pwtc|w zLBmCvfNGId5aLXq=WoS;{)R2{xu+*aB~BK4d)45z%A=P9X^az4Si$LhkFyWq3IHv? zk)wfg3C*%Uty986LMCd~=Uid&c^#sknBo8PnO48P)MI_;@B_Zvz0yP`3jV9QG6P(* zZb2Kk$%+BYRze*VLP)AnVbjesL;U$}%MS6Usu3xqWMySDmVZ0G4j)-7By=hO33zv$ zWY+|x3}Ux$L9Qif^_cC$aVFgS3LM6(5W|IWJwCJYjqSbT!29NXq<>Bsl~hQulKY-; z30uO*Y^|0+Pcdo_T2ZWevIfD#g_k3Zmhw;NM-rqjoNRENrXUY`O&R-U7sOLNfgBm! zxN#qnG9a{)UMww4)K?CT#4*^&N|CKoEaTOe&$xK}^Xv z1&H7H^be$8lG+D`hAQ!=)JIQ}fpm0kZV`TB#NQ?U28R2eJRv7;T_`G=O+}w|i-123 zob4oN4ymP@if?Uslfus#T@Hjn*ybl8>&5O+y244rzv##f$0$e+5Q7<2VlnX^yZQAT`A(V}WXD@DV$PQJbRQ`8Y9FH`&&zyp~$O%F~GRs8e zS-7k8IAqM~z+?1b4AEggiXa9B*s>2F2(MuY74aYowP+m08Tgk?Ar|0oP+C4w9meEC z4P0&hA~{`zDrEAw4dQq~s}4tn1sQ_$L;Q-}^1LO+NWA_1`(Yto2L7~wWxI)}n2PuR zRk{;5$Mdi-^bU4omefpj$!EkE=H+eup;0qCZl9|dyqIS%q zSBEDWF!2@GgOz{&Oi-|~u(--J?H^KStHJ>s^9j9>O8ieQSXSb6VPf0EU{8VnLK*EKx`TWPN-hvG?(|gM)tEP(gKkCi(vamIB~X9Bq;O`4)P+$LYhu2F-U_=4i|8h zTiPentE-RTI!szVFC|4fMxjz%IT?HRnNgeploxkFO;S6@LLMOs1T_bWpuM2`Hl$t? zgqV-eogpe*ob43ys1xN;f=YLxhWZSS+?SS?Fl2l-zbmPcw`DN~HG>WJb9neGZ=F~f z#6dTnrHSe|<9n<_>F@u}aV3nLO`LY9}8hkJLM`(i&W!M_AF<4L8>3W!C@>-aQ2 zCGoWJA|{|~=9DEJSer}tm}y zP>4A#_J=tS$A^Iyg#W@S?B~B(O}zdHE8rI>*Vbc`5VA)wfz3Hja^T_NAvAxX*~S1{ zR1|a@fmc0gU^f*l&Sy z4iazdl6Jl=D{glpA%iO)c#w_k1kDw0;zj_YiCgilBK^k0*{}4)0xYT%%~0tZ>d55+ z3;kwykuy$$MpbR?0NAwycs{roprVwzk;5JRN_HD-B%=%KI(#(Zjo>GYsq9z_ASH}k zHOs0i0@ARtxY0L$A+~bk7e=rcHfuVkQobL5PpEugblV2(5x1q2keA+=%zsVM`0sldGvIH3RXqTr(iJ< zq9u@MH#rE|LvpQ13c^@8HWett;BsgxdhCd&lL607kjMTZ!)Tj9{i|~XhKVc4RP?3D zNl{UHP<{bJ66YW3-^RI(_T1RQn+OwFRPSbiLjilqvhGh-1(%JqpDc zLL(c)5_qed#O4}RSFkv)m^Fev^ErajT5cHZ_#V6N38IrfOqan~egYLtZ1_h-v)?Z= zh&uRT=^Bch?cmLqvhfT$jfivGsAArnas!(hqM!jNN%3l429Sg1!MrJv-8wl5;i}sB zz*XmoeIcz&Lq}Hyg`^k!=FgAOHNAjcDR3V-ef=1is67o0jo)~6o!>RYt8)ulb$6I@_~K7_OrWoR)I`lUE-*n_egoZPqn{sJow)oyx$-I$EQjd9Fdb`QiN$&t(v zDAzY|1l|w}BxM*xycI?sqo>XLdqEID`Gxv`)km$STUqo zj@ur+QvswSh9B;2!g&&VjO&xQB|%+>?QPhhawLUO|BiHi1ZZ>U%ylw|kp7Nx?8Yng z?l{KE+5ow{k(Ts2Xc$7$zj5Qp@7>s-*}6tX$B=r85uVo4aR(AL)0uz)4WhcV6@Nt4 z6kUYC;H79D~3-&!Is$EaK8&S2?FCjQRvG0sYp0!cW_LC6qGmtSG@>rZXsQro|!?h+m8)vh(Mz4r(|*s zIW1T5>|RvYundnvPlF6_MYxzV4F1w}=5Rys1=r$8JZLlW||>~YUTbK=hNqC18$1d!wsyQB{gV^nwpaj-yu54PD6 zk=KeiSw%}D$plP=1AZV<4KpxL02`4gmA0$g0pjSw4;60z?^ z+O2*ty#6gPJ)&cdv5#xLA(dq4;}ABm_!i62mG1>;adzt7!iF0m^alfJ(uhsS6c3GDK|zvAS#4 z#qsTIBhN7tM74MCCrra+WM!RlNZk+9NQ9QSM?;7X&xngvL_B8Hf@XC-NWdKMFdJ$COv9Jc)af44j#9)^vi zZY_XBwG5a7fg7WI)DBQmyM{kf~_guJX;|xqd#CeJkEa7UP3@Nf5O#!3V9|AVLfMMMOkZ_IYOm zeXTXI(61Rou@9%rOJwgbEz@gEME({1DSmdzY|r@moW3Qw`f=wxy55oNY2#-+6Yp$% zRDQ?RC3}!&17O0DbDlc;egH*Hv0Pv0#G%*#D|9drGnI%gP2vE+wWM(>>C;9=Hwle` zEXK!FvClW67?B@%DQrX>f&dyL2jD=L!w(z6vuRHlEihsb!&L{GOu4i!iL_0bbA6 zS4i{CIy51>{rdG0PEJm`mL9|$e0!)lmHyQ+cD(vnS78`@ihlqPgWhkrsH2rJpR(Hd zdCsUm%V#&KCT}AvS~5=2j@@MQ>w^NpTz~fb^6zDq0j5`qlPyC$W9L^&lgQ7(nncXGTy&u5fzPO_E^biv^}k@Ro0Z?O)g6`7x1bSyz)^*Y>o3XoTLj^o0=%?>GhbagU1Piac9Ju3znkcKe^^ z&bGbWQL>QG@+ZdV+v@Ba+Z@U5D!TF;kKZ>i@VKyWI4;fSD6^>;7^+d2n_^5=J0HvW zEIL}xSTz@ub?+4dRIeh~p=JSwch-Rs+kh+cG>YgG5f+4q@aX8ZH?CTs3gp=hQa}S< zX77I7Jv*D7Yiesb9lK%&czAL*q5Vs}OO&>0zOvpPDjH>}L#6VHc~VLm+m;@)kydZb zpNf~s4Lfs&v*#|gxc*XF>-dzW()AmI51wfiPYWXUoF;DYazkG~zc)zMvMf8EqXr9# ziKzoN>=WYa<@Mq7=dIx7otD;G1Qg)y>&p>jr0)4Zkbb|qqrA0(r1LfWbReis{&ZhS z-|fA<^BG^Q-DKh7dcx~*`gI?#wV{#5Q$I1+!e^n+q|{p3+BNED^R*70eADUuu{+=J zQ6oY!6Oo7YWwtzH|+!8bKfN6tJz@y%F z8qaP)X?dE=V`YkbeZgZrVZIo$xZW5w%Yc8?*}p%xG|fX=&<1cb%1yFAv$IA(V9a{D zz}Eqc#|Bk=gfo#lLm$vOs`Xf#VTPI|+267Eb=csMvQwL&Tl)wzj9cCTJe!|T-&PNj zKrkZdRrLvESu4}uxQG^6W1|{z=`_TV15HOu<#G`A8;rPtughmF*Wp3{^7#olC?@;A zKrR`Z6B50%xA{X#m>a6LZIIC-om zfK7snR&+4n4iitzjJgrJ6Z2tI(Z~>3y{G zq|LT_U9)$<X)SC!r60~EYNAju$j>3^VkjPjG!Xh9Al6o?6 z0pVf1N#Lk3cX4t`ysH4Cb)v>UwLQJ za8$%$tP*t^JW1j)9g0cZNZ6FIU3&3Kz`1~ZY7;RH4H%E?okbf@(?1hFj|j{255On6 z1qE-RbR@za;3?wGpyHdaAB}weToy?eTu+8Z%+~CS0XwoONBf~uM*x^W3c;ofMGKF| zvYij|7Zt@7q^~OxvXX)h7J%PrwyKafp5R z9`7c5Msq>iE5hF6U{j1Zy|M92(dj+9Vj;<4Nk0BM#&xptDrYqx2sR`w7?Dw=x(8kx zoS%tUxbk>)aOaj=%(01wBR_;r2E|0Bh}8ASrKqKvG`)HB-fa0^;ATjNd2IQ~@5W`Q z8PDUOPNJcc5+i@pih8)?VQ@(gvV3fE7{st1J}fz&=Oa$f%8J7C7-8jv6Lb%$EtZ}@ zzM-a$TP8uI8J;qT9uRhJtc?l_tAJK0a*F5?O{dEgTiHGI^9djcnG7CWI0*e{YM|h3 zDE06F5XBeJ!d5c9g8YEMj=u2kq@WlmU0>xwEQIW(6Q9$dt{m{>TULK7LPAtzl*N{QK?e8FsWhKqh_q?AdFFhpCrOyf|}XGtoRC&=|L+*(10BiFwtp zzd*tr>nYWbtC{Y8>a#D5p3g)QHOlrKJC309Yi@2%hGf|{GBWbZpOh-AddIQWO&=g& z&R?4Z)1X(+p9oBa#{7W$x1nK;d?svD&|!LlO3!4BL*lHkaQ^qu_e}iy1Y|=N%E_X0 zwg~97yrs+MufI^VH#q6rcVI2auYV0NsNH^{ZYodh!EjA(eYkK_z2&RxZ|e5=3!u~^t8Y+WFL_hGre)D8Y;GZF z`Q7KSe|5C1f|Qqtln(&PY@I@fJy5#!=blGLro62!oY1?$u>wOQfm>LNmGu!Os|hDM z$bww5vP#pYrwo|#08~h<1~j>`8rX(%($bzIkMm*y85o+GDa;I1vGNDwUWMZtHXKRM z&xhz<`}^-fVcg`y1uP7jD=^lIZ*ahsgPfBLN#_+qkNhX%l9M+$R6=t*0BZP~Z>^$t zxCbtEqNRtL^4H)j34`+O(CFR)ED&^SY#pM1011DiuFIZHzVPe-KSd8jT|)X8Y14mTx-wb#Hc zVJD=7pl=-rh#b%BO~J<%0NZ)Mjp9FVlSBrB^W+MI6^Xs3p?xwOfR0Gv?i{B{YV~Fb#zi3 z&hFaPe|Ht7EnUU((h{jR)yfs4N@M^W>F&Ye59r`YxIcBJXbPyH!ygIOP;!lBQle|6 zsxjpRS~*u3XI`Pi4tn-<`j#K z6TOB=pOnjW`O1rjsjAl5tNnHYxIiC1vUjOY4UKtiemplQEc^m(;GtFr8_oT63qHH# zy~P9LEsx*1GvT5Cy)WH1{mo@VjMBtrQsulGCi~$3E~a&@t`_z*&5}7%UZp`Bo5;Cy z-$!I%Pe9su~-Cg@fmox<~ zC4z5pXQa^^rWjag86_nONX`Q=y#MaqyW;`rD@UB5mVqcoh@NyzuKp zB3QDvWG=b5YZZtBeB@rksR`5ZV3WdZ@eEQ3V~l~4gz4MAgkcZ~;A1|b+`qaK#K;UT zQ?mZxJVH>xxZ|z5$cQXi4VSWA04*+RJLd%!qfmT>+dpk)F;`Z-RJ0g2V ze^UyU3ovuoM!}HC?O{~zMGd~}HOolYEuk|;5@J?sng@wsYG#H7GYn`)&?2=7r}cxRP-n0i=w-`!%hj;vBY_c z-S>ieH-B32_?YTd{QDNGp^25^kLS7&Lksw`rRtaM-%XEQb5p)mc^laePW6V`Fakmuh<{5V8); zM0zCFf+`ifA{vAixM~H#Qx1d~R4F$b6IJfuiR7H80X;MNTIOsjUQPfP1z>4{zKBPN zi=sW(x(?5380nmSI#zEFn6UuyaBk;j?euOR;V z@igU#YAV0Gk;#g4B&O2QqGV}UW^_^DQqFIMKW~rkQ8%aj7MJX43`jCk#anWXlsQrkEKIFg1`n;m`##hw;Caz#x5(P3L>xI*U z-emrPqcryC?4D>I8ny%K?BHs7j3TYuBI1TB%ebbd;=szWF}*S0iYFcBSk&l~#EOkX zffGZ}q8uF3#xFA|z%mDc8%c&7&dWwaQ%cR3SkKh)?&3&9ou|n3f#?HF%^V3^fK1)H zn>BP~ASw}@al$AH|6m{L4~XBu)O3d=8pjea&OlQRowgsKEOvXWyMb0WN9SLfm-qKs z@ge(@5|5~L7@_Xp!#B8ArB*A zG6}ctEo6OP9Ck0x>Vz5;yBe_2x@(;~=de>FRmZ8xC8K?<$8nV_EFg8u^*;}K-n|?C zkm}|3kL6!-GOM_jpMQLEwJp+}xsHghu?vk?Fb=FM_GbWb={4HM| zEM(uWt82_nZ^!-A&vVo$zH{@>{`F` za_E+WN36r81xKfBhl6BfJ9_1% GO&el(xyJ*d0@YO!sa=&5W!K|H;4jzU>gS5^y zE;~LL+PPe13hm!bOKmdSYIh#v*M`!sSqcG)#5K+Y!`2P6>1_pkaN3DW(!>EP(etxq?FC>rbj2vc~-)dL$oE<3J zlDJ=7%{eB);r-wxUwy-o`Q96PWBk*VH=gKyyIR z%7DbCGiP$%RJ=1DTMMKQ^XT%j>lr2)MrI93eXEVGa#~y4^xB2?nN6Q#N(Z~kenT$C zfy#&*f#M04X6C;o}Zv32gvp)ak^ zP^eHB%ydmJlz`QQtih4vlU260onlt}B%4VL%rXRvN<`%1Drtv7pp zjHH%oa3;gz<2$ak%f(i$l_7eD&6%q)QNk`ZCz*mBOd_9C%{?HpM|KYV2Tef2EDO=K zY9Fnxz9iYk@#ipL%ceDCgb>241oHvBtIK<6ZEb9vMl!ab3g7YvREXre$Jj}}i_TCL z8*M&4P@@_k(*sone_iG&BRT<|xcsu@@|O~ozQt^NU8c@(ZaFKPd;h`vO};0q>W&Ub z9X>7MOzIA%_V7o140f8?y(oP0&)}`{?>RqI1G%^^ww-@#ZS*=vx2HZfvn)HdrC!po z<41MsVL7dXY6p_cvEx9mGjZR> zR?!Js?LOf`#(wutHXu);CrD?Bd;p%7=jG*hAYjEJ)g#nvQMDqsMRmlDr3mzkD=14O z2F}rOBK&jFP-;3jpr$#Ud;-pzaFzvi5@K1tvlflFPm3-b|DE6w6iKbDF|ByYQuK9l zvRrFPomb(?E^gY*&c^k}$wIn027XqZI~bwWH`m}^4Oz1W%Mad`!SeovvyFzle3siz zxCp^GyYjn`hMb({e#89U%{6t)Wn$x&DL%YY()e{ir2hPxKzyiRLpU1n5O zQ=4rSB8mFp`V2#hw7%HI5gZl1`IgWX_MMcJ6|kg1A(h&F+)NH(Kxlk{yL3J49&LN! zrt3F;Yzk&e%{w%|ugx^$>eXEG!=kK@i>jqX@|8aoX-%OXSP`oKW>n=k|)0??~ zkLYz?U*$#Ex%McDygxHL{rjpTa$Y}^-5$FO3&$OP_gqSuWj zM9XlfyST93?gYWK$1I1ppC9f8Pc)^Tfx_YQ4V(>dtCQLZnHqG^oF4dvmaNWS0|yR0 zwOdhj))@0a@i~pr9kJWpb&=8H*~|Rb=*=kysoc*O>LuFVqCEBMdxpK=)w{ac|5)Jz zP`J*p>G94dX-IFr5a4|n;XCOzt%-?AfNq80iE70`4bRLEQ$D1J<{qc0je+! z)N~|8hfQ6t&E+DecE8STn!7HUeuD*-{kBzR6gGL(6X^#6aS#4nnlEiF`MJhG{evxa zYE7a>uZD!{=$F|aw%9u6!@MVVc5T}kk>e0=zMju#xtiHLp1)D(^qGA=TFzU(QRrlh z9H6I!51|1;Cetq|Qj!QQ>?FDjAcSBvDDC@Hc6bl^`~$B9tWMKaTAKElC@kenDU;MDMP%*o79E1||yr{(MMT|HDOKO<@=eK7uR; zZh|m=41ked_Dc)gkB*bw2kGevsxxeQ7s8@6QRO&A7#$3ynrr<*C(9~r`Sga`2ucjs z-|m*0`g{2=K34I*`)RW6@1ZM1K@@oGGfFAWjfC@ml~R>}VMn+*IFixE_7X`_v|Aih zX*{*)=e;DwMiAyUN~;HA=u>Qbt-?!`X&YZRZa+z|0g12qd)GJZ%4Ezga^ou^!#{Z$ LCFwM&>ks}9r|F`& literal 0 HcmV?d00001 diff --git a/nav2_bt_waypoint_follower/doc/legend.png b/nav2_bt_waypoint_follower/doc/legend.png new file mode 100644 index 0000000000000000000000000000000000000000..e7c53ef13653a1ab615bd4e89c2b63f0cbb45e81 GIT binary patch literal 7911 zcmb_hbx>T-lV6-ba1HJRTO5MB2iF7*1PQRX%K{-lun;^zut0#|wzv}@cp$h-7FpbN z;oi6I{<^xl`klO2_4?J+NY7{b(>*;Ct)r!aheL$}0)g< z00>NL4HZSu<3Dd+dvP)dME6xqQO>~c>%p?WiGl4M*71?^2wyK#Yv?}sqejfPjYtOh zA3tu?)81uuEPOMvyG_fiO3|1f7uByCD(e%_&>w!O>29f`NHQ8>E{8rJ>1`7EENYb= zD=Nc1=*u&sy$7>nwLh}4q6|R4? zxk^Xgeb-Z6#NIop-;Ey~9ypBM(<(j?sH2;#`I1T?-bqOQANBt=!GDAd_B8yKU7=f8#2OTvt>_tL4-F% zezX^Ba1zX1K9+j|Z$knIbJClU*9J@7Hy0%%3JBMo8{S?Rd|veyv%tv2M0p#!vqTW$ zqCC%o8|ct6b4zYZCx5AS{x!~Jlfe_i5}V8Pg}2Hv_Y16sd$)nKwVtB1qZ!g5Mn%0P zHCd?M9qI4V*R1r05x>MSTfxUP&P_1`Q6X=g;^tkh<l9OYg1^@L>(@7TP`8QWo3~PZ0Nq=oDDSBlr?2y7;mbg>qiT- zB{bSEyS*Vhon~`(y3o%~5z)G@hW@fmtm#ZqzCYh>kvyeitI) zMI=D*jRmdL5kz@m`SESJJI|U7CVc*LF{3TP`y!K5YcazJRhiJqms6|Z5DKrr9#wX4 z!zO=9CDFX{P#sh(nd^kGil~UxI+(h23K@tYNqD)ok~o^$T{|L=^2K$2CGl>^+Bh%K zIjUAoo`DF4kzi7^F zmCfaYa=e9hZ#RLkt?CU%G&SEb+1#Cpo|q{Y9o(O-UQH%6llc4#C_RTzoxxi!_Z{IP z6I^u45CJ=}3R@679DW-4H1X2=)tSt44PG=_XW07%qZB#Z5hhbd1_(UJLO22>pKQxw|EzXbSltDEt{v#9od;Im zS^`uat5DJ71X^3tFJ@q*X_YH@FR5AeJvhC8AW5qWS&+i9-_Aon%Y7-mBTaXOIG#0f zFt8)w)W!f6AI9VT^!eOE>C>~h>uqg|OD$@!BnN4Rr^>u6`)WyZuj`H#)2eAU z`=0lMPI=?f5N7E5c>M2{6Mk(FsOa%cbJx(R`zTzB2L9?-=lc}P3oS!U{8C+o3Uo{C zZZy35bR{!(&?jC&0WWWUmdjDj2f2!*1h9hJ-BX;0_pVKeu-&^vZ(;=s`7NA$bj0hD z)PTSWEfkQosb{1R{H+hY<($VR6$xqhkmO$rkmcL{JTtE;^(B3T(uXX4Q6KC0K=n9_ zWo3%c3W1MP7!Ni&?pVzfPmK-9*0oT@uOddsKxTnxvhE%>Xz^66yKAxM_;s4ZAM=`L zk6%34EU7ts3)YBtYNO=8?Er<5d5mR>mgqBpNQ*^8bPV%fhj4DrP+w4`*zWR-h=2OS zrCasR1y0~tL3pduBT6&ang|6=EB#&yucc{@zCOd9YhvDcu)OxB#&uFDJXF#Zm{K>O zSVtu27%{mqm5J=VFNa9_k zlyG)U=RVaIH6Q3%crqKJ?2a=9(=puCLUo~2zB;M!P+ZTrxZ$JUkLTYza^>=HlX!Tz z^OXN3Uf?O?^#sH6_nfj}e3lA82^gI4qty}Gs;=8U4hV2NOLKFRu0k!+D{jf*n@c1} zOU%$xCYB>bC9t9%V3$rM>kXj(^69`KO5;FnC0{eNqBgYjdt98#o%Y8b$`pO`59esl z2Sc~$oW+@~p4Ms?u+V}eu^68h<&zv}k|v@zvfd|~hN&Fez}^U|`Zdx~AsFm;TVm!b(}%1~6Lx0j;g2UdmpQD`+EJr&+c z2>rx_n@|5(_OGFyn==y_4jGwA6CoO=Y=z6bIJIU@ToUnzh+UrY(w?p`zpacSQPFl= z&lh6(h3F~?s9n=#eplwqPMaHRJ0FvXX(a3h36-xDV(a+m%Z%P^DhHiDF)EjBbRmpg z-*~TEQ0+v)#BACipFB0IP!OhE&{(ZOA$jsajmI>>2o?!MUS#;8^a=naOL*b7h0_4VV+NRx6=^4am_)_9FVy{B}} zg`DAOJbHx_RRt<<>;XR{MVpfYI)k#gMq z`3jmLbxphx)-f(D+?^fplS~&9>ezkfa*OyKhq(nN22hr0?=N3{oQe_Yth$S&C+q%erv!uir=-6V31VqWMf`o+Th_+*4|ZllHeH%_=@4*_&0;q+Jq`qdiZ1HITI*4qs8b@7 zCVTSw-4SD|$jH-|yuB$%KB(lB<5!ugMmJ=@`L4}6Ed+PF7?)yWRJ6tl1t6;(8v@~W z1%_UuXiG<1v{%1TP^i0F1sJdrOc8}Imk(618&{S?nJMSrM6YpvMniLa*!sd9)zDB? zv+t`|2pl8Ij!(i=(Iq4l z6|Kf|`f(-AT|48Gh}&6pb@6z3&AOW0t6`9)(xr~}li;Y`KQ-QED@OeMc&4muOhTl3 z9FkHsK0NB`bPKggF;hr^>zc#aan-DJ%bC^=+kdoLTX<`?0h?Xh!%f5<8^b0TsOro- zkrHm|n7(`T^!Aqdvugj?`|6cu;^59vUG%&EZIJnocIVK?6hbtw`~QzP^G~!Iy%lx; zj-zP@EkiQvPZHBOU!!F6Jc32J=re8*yqlz&jm!u3vZ02u_9PD(-3q^NBC2(yv2o$y z|Dw>STUl+C^tfWogROr_1ihKH!W<8 zN}PK!y1W_Q~v7z6u@93br$Rz(!t%jO!!tMD|td8|;w-mp9d@kpmlr^22@m+r6!|gV|-`UN2rraA6s$bIKAWV$+bQ7wT{J?d6Dpj z0$?;mGh{hRa&Lcme4@@+(^hv3#tab)(Ab?6{I*KsTINWm(iyOuqdva^udi&#%H=Fm zceRvy;V|g|T2?4#-G80rbBLAOk+9dup(fr0zN?Zc9Xc(CeBEDe@uoeme+(^7(uR6J z%)&u9E;)|~Z+4Jmht*bO&psCxzH3f5( z$szN9XO9qew67Y#)H1uYVu!_S6v{{sKI~a}`*) z4}C6hYrIcUehafi@)E+$B+T?*l|yv&b(^*eevQPoD%co}UOx|>4EfaROAmG2TS^f$ zy;U5`hN*$;lUi;Fa$suGPRT)Ak@6tvgm|F%@XytgyXm-uKkQ&}?)uu5 z$N9pkI#WCmwYdw6qmRZ#6)kipr?bBL+V1HDMQbP5>%347&*PU;t-_l*QcK@p0vJDRU}+yj=5kGkIu(ds(Y=822)W)cvtlp}rZ-9r-l+6?|FZHA@Z57Y{q+UES2!!P5BSk00EVka?TAr^cOx`KeQad?RJP z2D(0a74j|{&xxsvCj>j!aTV>MW;#ZnUF4ooTtan>^`%+tVD@Xz6HT^uh)6|jY`p!$ zEZ75W$XLY`9xn2YtN58}M!Kc=HsDn{33W2OBEF3#Me(P)NrCNcJ4LRY>@ba%C@r+l zK9wh&Yo^aso1g8GG@M|n%-?T#_;4@1~in)`OYF33DU*@0U1Kw_~KbH^ts7!FDpxH=@M zFt>(mBi2?5t}jzdYa5zWCY8?;>OB_?U@<(d-uxyO0ixfZ?XF@l^V8n@a>nUy6QEuh&T(&^)_dlJiE8(wrSbp)s~c?tm@ ziB6#y?N?hpV5BW+rGT$ zzq`7c8fu%;mrpFz(D^W-nW?~%ru1+pk)L|r|D$S@Gh8Cs!~U68g}g{E6Hkgw1N%@Z&?|gichG{X#SR%#6Z_12zq7M~bNKF^T5oDg zcc4e=>7vBSQB|-bWDj5~sjZ>fB>m&S^5f^Z7cIWDg8gH~)bnEB$ihy6FVe^}Jx6jLeSh@W#~wv3ncHiItGkZ9`!$ zb?I+`-~dTQYSEu81%QT1Cx@eEY|X`V3^Scx|L4qcvV2vBH6-x=Z+ieaw?v7FiOF4J&rTkj8p(je;US$tzmGybU#k3jaz3fMRlFtcxivERU88wmvC;MMbeNZf zgaiXsPDkhW{mq$_q-30n_x165DwnZiF4&~n3J9}BUV6H^HQswO*VorQJ@V0t#H6I> z`*q`&N2~N*Nvs+ho14vc?SWS-P43L08tGsjpxJb(p+XcsMz#B<@&UR-UkurBIE&q&olGPFJ#^z|^qbyDl)36Ry(t{}K1VC$9W;*1Jen~jas%T%J|ICxm1Z|vS+1xiEnXZH z_#k(8chDyqu^y>x3E#sgdMG6gO%O0_bu}L@rz>xQqqJ8%y-bI3l?8G1+pbU)g~+FB zYHA$3ydl*Y^7$rhel^MkH`kj95C}x`=0pGH+vgU{=eA<{#pBlgVy*au$j-%ROibEFRG7i*!El$109Q2t6}<|%0l_AU=H zF*QZ|{V?)O=Q*iB#(p=v1y_lQ2o#8Ma;Ng90X?d^^E13t$6 z>C>mBKa2{Iz`XkU`chL7Eo4315K$K}+{m6W^4I zwX#b~N`5;C0U82uzv_e{_o_Nwybx9`W7!e|{rzdFsXV3)FTd+$G)?c%*DWtEi#pG_ z9WFH^5Qwi|zY<7a%YxI#vqTdlhTQ<#gZ392wF65irGuIbIF}n;SHJMvWWMqb+%-As zbeo)<^f_Gezd#rs7PkRQ+8%I`DPXG(Py_~XS!z02aH@KjI|j4>C|;l(KM8&&@K)8p zAmxy36M!ZB{d=#*)8pe`!^1YdwRWRaATlzt)sV;Fpr9aK-9!`at-}y>EG%jR>EK(h zRCQSJoey2Y0MDyByV34&tVZYgjlDgm0Qgd#Gvw?+LuCYuAERAHWr6-*&U*gK{78cu z`M}|?IC1iyb07j-Z=bm++L7 z6t!fw`Nc(z?~`)jmC1svjG| zx@7^EZwxG6Rn-x*s0`8+z8OJb0jh>9iX0@h`X0sfZJ?lGx@k9uFxEQFf+696|NUW5 zdIxc;O}@Rmxkg^C!ZeCrW}xPklO5%{`@gFGvnmqVkM4_kB>j(Tps@d=m0ivamYn9)YR6Z<^e83D-QoJ0+E@P zW;YS*BpQ+%^s#S4D_fj{G$u2X3OHNbs|EH)<>dy?Nn2K%fvMDq^M5BUKzk?i@`~tG zv>8f-6T!j30W6$^Mp7jAjw$hR-S06T9v+wyfA#gTa&jVoAl`y3EGp8<6dD{G)8b6U zrxic{JD3cx^dEl;q0Ig&;j88Qn^hxiYVYy=77(eQVs3zguMQSP1I`^PM@KRQ7p>D_ z=(k9HbWF^dsj0X2_Km)bv=gguAKrYszYhY`Ue=x&8yXrK8HxM&(P5xeyf(y08kCZj zHkKjC&dy%k(jv~!?~a)I;p5{ooW|pH)FNI2)DZVQ4Ep;k5%BDZ%qrq9UcCImmv7qW z5*-~4OyI!$HI~vDLC@*9IF!&+_rE{m7=A=cQe%2ON@m;y++2gyl(ZBp<*nZT8wPxc A3;+NC literal 0 HcmV?d00001 diff --git a/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/bt_waypoint_follower.hpp b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/bt_waypoint_follower.hpp new file mode 100644 index 00000000000..a179f4b4e17 --- /dev/null +++ b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/bt_waypoint_follower.hpp @@ -0,0 +1,135 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NAV2_BT_WAYPOINT_FOLLOWER__BT_WAYPOINT_FOLLOWER_HPP_ +#define NAV2_BT_WAYPOINT_FOLLOWER__BT_WAYPOINT_FOLLOWER_HPP_ + +#include +#include +#include + +#include "geometry_msgs/msg/pose_stamped.hpp" +#include "nav2_behavior_tree/behavior_tree_engine.hpp" +#include "nav2_util/lifecycle_node.hpp" +#include "nav2_msgs/action/follow_waypoints.hpp" +#include "nav_msgs/msg/path.hpp" +#include "nav2_util/simple_action_server.hpp" +#include "rclcpp_action/rclcpp_action.hpp" +#include "tf2_ros/transform_listener.h" +#include "tf2_ros/create_timer_ros.h" + +namespace nav2_bt_waypoint_follower +{ + +/** + * @class nav2_bt_waypoint_follower::BtWaypointFollower + * @brief WIP + */ +class BtWaypointFollower : public nav2_util::LifecycleNode +{ +public: + /** + * @brief A constructor for nav2_bt_waypoint_follower::BtWaypointFollower class + */ + explicit BtWaypointFollower(bool use_bond = true); + /** + * @brief A destructor for nav2_bt_waypoint_follower::BtWaypointFollower class + */ + ~BtWaypointFollower(); + +protected: + /** + * @brief Configures member variables + * + * Initializes action server for "NavigationToPose"; subscription to + * "goal_sub"; and builds behavior tree from xml file. + * @param state Reference to LifeCycle node state + * @return SUCCESS or FAILURE + */ + nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + /** + * @brief Activates action server + * @param state Reference to LifeCycle node state + * @return SUCCESS or FAILURE + */ + nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + /** + * @brief Deactivates action server + * @param state Reference to LifeCycle node state + * @return SUCCESS or FAILURE + */ + nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + /** + * @brief Resets member variables + * @param state Reference to LifeCycle node state + * @return SUCCESS or FAILURE + */ + nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + /** + * @brief Called when in shutdown state + * @param state Reference to LifeCycle node state + * @return SUCCESS or FAILURE + */ + nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + + using Action = nav2_msgs::action::FollowWaypoints; + + using ActionServer = nav2_util::SimpleActionServer; + + // Our action server implements the FollowWaypoints action + std::unique_ptr action_server_; + + /** + * @brief Action server callbacks + */ + void followWaypoints(); + + /** + * @brief Initialize blackboard + */ + void initializeBlackboard(std::shared_ptr goal); + + /** + * @brief Replace current BT with another one + * @param bt_xml_filename The file containing the new BT + * @return true if the resulting BT correspond to the one in bt_xml_filename. false + * if something went wrong, and previous BT is mantained + */ + bool loadBehaviorTree(const std::string & bt_id); + + BT::Tree tree_; + + // The blackboard shared by all of the nodes in the tree + BT::Blackboard::Ptr blackboard_; + + // The XML string that defines the Behavior Tree to create + std::string xml_string_; + + // The wrapper class for the BT functionality + std::unique_ptr bt_; + + // Libraries to pull plugins (BT Nodes) from + std::vector plugin_lib_names_; + + // A regular, non-spinning ROS node that we can use for calls to the action client + rclcpp::Node::SharedPtr client_node_; + + // The parameters for test + // Whether or not to use bond + bool use_bond_; +}; + +} // namespace nav2_bt_waypoint_follower + +#endif // NAV2_BT_WAYPOINT_FOLLOWER__BT_WAYPOINT_FOLLOWER_HPP_ diff --git a/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp new file mode 100644 index 00000000000..ac850e39d6e --- /dev/null +++ b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp @@ -0,0 +1,50 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NAV2_BT_WAYPOINT_FOLLOWER__PLUGINS__ACTION__GET_NEXT_GOAL_ACTION_HPP_ +#define NAV2_BT_WAYPOINT_FOLLOWER__PLUGINS__ACTION__GET_NEXT_GOAL_ACTION_HPP_ + +#include +#include + +#include "behaviortree_cpp_v3/action_node.h" +#include "geometry_msgs/msg/pose_stamped.hpp" + +namespace nav2_bt_waypoint_follower +{ + +class GetNextGoalAction : public BT::SyncActionNode +{ +public: + GetNextGoalAction( + const std::string & action_name, + const BT::NodeConfiguration & conf); + + GetNextGoalAction() = delete; + + BT::NodeStatus tick() override; + + static BT::PortsList providedPorts() + { + return {BT::InputPort>( + "goals", + "Destinations to plan to"), + BT::BidirectionalPort("goal_achieved", "Has the goal been achieved?"), + BT::OutputPort("goal", "Destination to plan to")}; + } +}; + +} // namespace nav2_bt_waypoint_follower + +#endif // NAV2_BT_WAYPOINT_FOLLOWER__PLUGINS__ACTION__GET_NEXT_GOAL_ACTION_HPP_ diff --git a/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp new file mode 100644 index 00000000000..bc4f443c01d --- /dev/null +++ b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp @@ -0,0 +1,44 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef NAV2_BT_WAYPOINT_FOLLOWER__PLUGINS__CONDITION__ALL_GOALS_ACHIEVED_CONDITION_HPP_ +#define NAV2_BT_WAYPOINT_FOLLOWER__PLUGINS__CONDITION__ALL_GOALS_ACHIEVED_CONDITION_HPP_ + +#include + +#include "behaviortree_cpp_v3/condition_node.h" + +namespace nav2_bt_waypoint_follower +{ + +class AllGoalsAchievedCondition : public BT::ConditionNode +{ +public: + AllGoalsAchievedCondition( + const std::string & condition_name, + const BT::NodeConfiguration & conf); + + AllGoalsAchievedCondition() = delete; + + BT::NodeStatus tick() override; + + static BT::PortsList providedPorts() + { + return {BT::InputPort("goal_achieved", "Has the goal been achieved?"), }; + } +}; + +} // namespace nav2_bt_waypoint_follower + +#endif // NAV2_BT_WAYPOINT_FOLLOWER__PLUGINS__CONDITION__ALL_GOALS_ACHIEVED_CONDITION_HPP_ diff --git a/nav2_bt_waypoint_follower/package.xml b/nav2_bt_waypoint_follower/package.xml new file mode 100644 index 00000000000..0f1b81661d1 --- /dev/null +++ b/nav2_bt_waypoint_follower/package.xml @@ -0,0 +1,31 @@ + + + + nav2_bt_waypoint_follower + 0.3.4 + A BT-based waypoint follower navigation server + Steve Macenski + Apache-2.0 + + ament_cmake + nav2_common + rclcpp + rclcpp_action + rclcpp_lifecycle + std_msgs + std_srvs + geometry_msgs + tf2_ros + behaviortree_cpp_v3 + nav_msgs + nav2_msgs + nav2_util + nav2_behavior_tree + + ament_lint_common + ament_lint_auto + + + ament_cmake + + diff --git a/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.cpp b/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.cpp new file mode 100644 index 00000000000..eec6cd709a7 --- /dev/null +++ b/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.cpp @@ -0,0 +1,64 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#include "nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp" + +namespace nav2_bt_waypoint_follower +{ + +GetNextGoalAction::GetNextGoalAction( + const std::string & action_name, + const BT::NodeConfiguration & conf) +: BT::SyncActionNode(action_name, conf) +{ +} + +BT::NodeStatus GetNextGoalAction::tick() +{ + std::vector goals; + if (!getInput("goals", goals)) { + return BT::NodeStatus::FAILURE; + } + int64_t current_waypoint_idx = config().blackboard->get("current_waypoint_idx"); + int64_t num_waypoints = config().blackboard->get("num_waypoints"); + + bool goal_achieved; + if (!getInput("goal_achieved", goal_achieved)) { + goal_achieved = false; + } + + if (!goal_achieved) { + return BT::NodeStatus::SUCCESS; + } + + if (current_waypoint_idx >= num_waypoints - 1) { + return BT::NodeStatus::FAILURE; + } + + setOutput("goal_achieved", false); + setOutput("goal", goals[current_waypoint_idx + 1]); + config().blackboard->set("current_waypoint_idx", current_waypoint_idx + 1); + return BT::NodeStatus::SUCCESS; +} + +} // namespace nav2_bt_waypoint_follower + +#include "behaviortree_cpp_v3/bt_factory.h" +BT_REGISTER_NODES(factory) +{ + factory.registerNodeType("GetNextGoal"); +} diff --git a/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.cpp b/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.cpp new file mode 100644 index 00000000000..da77cf153d4 --- /dev/null +++ b/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.cpp @@ -0,0 +1,54 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include "nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp" + +namespace nav2_bt_waypoint_follower +{ + +AllGoalsAchievedCondition::AllGoalsAchievedCondition( + const std::string & condition_name, + const BT::NodeConfiguration & conf) +: BT::ConditionNode(condition_name, conf) +{ +} + +BT::NodeStatus AllGoalsAchievedCondition::tick() +{ + int64_t current_waypoint_idx = config().blackboard->get("current_waypoint_idx"); + int64_t num_waypoints = config().blackboard->get("num_waypoints"); + + if (current_waypoint_idx >= num_waypoints - 1) { + bool goal_achieved; + if (!getInput("goal_achieved", goal_achieved)) { + goal_achieved = false; + } + if (goal_achieved) { + return BT::NodeStatus::SUCCESS; + } + } + + return BT::NodeStatus::FAILURE; +} + +} // namespace nav2_bt_waypoint_follower + +#include "behaviortree_cpp_v3/bt_factory.h" +BT_REGISTER_NODES(factory) +{ + factory.registerNodeType( + "AllGoalsAchieved"); +} diff --git a/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp b/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp new file mode 100644 index 00000000000..f319ac54d08 --- /dev/null +++ b/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp @@ -0,0 +1,286 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "nav2_bt_waypoint_follower/bt_waypoint_follower.hpp" + +#include +#include +#include +#include +#include +#include +#include + +#include "nav2_util/geometry_utils.hpp" +#include "nav2_util/robot_utils.hpp" +#include "nav2_behavior_tree/bt_conversions.hpp" + +namespace nav2_bt_waypoint_follower +{ + +BtWaypointFollower::BtWaypointFollower(bool use_bond) +: nav2_util::LifecycleNode("bt_waypoint_follower", "", false), + use_bond_(use_bond) +{ + RCLCPP_INFO(get_logger(), "Creating"); + + const std::vector plugin_libs = { + "nav2_compute_path_to_pose_action_bt_node", + "nav2_follow_path_action_bt_node", + "nav2_back_up_action_bt_node", + "nav2_spin_action_bt_node", + "nav2_wait_action_bt_node", + "nav2_clear_costmap_service_bt_node", + "nav2_is_stuck_condition_bt_node", + "nav2_goal_reached_condition_bt_node", + "nav2_initial_pose_received_condition_bt_node", + "nav2_goal_updated_condition_bt_node", + "nav2_reinitialize_global_localization_service_bt_node", + "nav2_rate_controller_bt_node", + "nav2_distance_controller_bt_node", + "nav2_recovery_node_bt_node", + "nav2_pipeline_sequence_bt_node", + "nav2_round_robin_node_bt_node", + "nav2_transform_available_condition_bt_node", + "nav2_time_expired_condition_bt_node", + "nav2_distance_traveled_condition_bt_node", + "nav2_navigate_to_pose_action_bt_node", + "nav2_all_goals_achieved_condition_bt_node", + "nav2_get_next_goal_action_bt_node", + }; + + // Declare this node's parameters + declare_parameter("bt_xml_filename"); + declare_parameter("plugin_lib_names", plugin_libs); +} + +BtWaypointFollower::~BtWaypointFollower() +{ + RCLCPP_INFO(get_logger(), "Destroying"); +} + +nav2_util::CallbackReturn +BtWaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/) +{ + RCLCPP_INFO(get_logger(), "Configuring"); + + // use suffix '_rclcpp_node' to keep parameter file consistency #1773 + auto options = rclcpp::NodeOptions().arguments( + {"--ros-args", + "-r", std::string("__node:=") + get_name() + "_rclcpp_node", + "--"}); + // Support for handling the topic-based goal pose from rviz + client_node_ = std::make_shared("_", options); + + action_server_ = std::make_unique( + get_node_base_interface(), + get_node_clock_interface(), + get_node_logging_interface(), + get_node_waitables_interface(), + "follow_waypoints", std::bind(&BtWaypointFollower::followWaypoints, this)); + + // Get the libraries to pull plugins from + plugin_lib_names_ = get_parameter("plugin_lib_names").as_string_array(); + + // Create the class that registers our custom nodes and executes the BT + bt_ = std::make_unique(plugin_lib_names_); + + // Create the blackboard that will be shared by all of the nodes in the tree + blackboard_ = BT::Blackboard::create(); + + // Put items on the blackboard + blackboard_->set("node", client_node_); // NOLINT + blackboard_->set("server_timeout", std::chrono::milliseconds(10)); // NOLINT + blackboard_->set("path_updated", false); // NOLINT + blackboard_->set("initial_pose_received", false); // NOLINT + blackboard_->set("number_recoveries", 0); // NOLINT + + // Get the BT filename to use from the node parameter + std::string bt_xml_filename; + get_parameter("bt_xml_filename", bt_xml_filename); + + if (!loadBehaviorTree(bt_xml_filename)) { + RCLCPP_ERROR(get_logger(), "Error loading XML file: %s", bt_xml_filename.c_str()); + return nav2_util::CallbackReturn::FAILURE; + } + + return nav2_util::CallbackReturn::SUCCESS; +} + +bool +BtWaypointFollower::loadBehaviorTree(const std::string & bt_xml_filename) +{ + // Read the input BT XML from the specified file into a string + std::ifstream xml_file(bt_xml_filename); + + if (!xml_file.good()) { + RCLCPP_ERROR(get_logger(), "Couldn't open input XML file: %s", bt_xml_filename.c_str()); + return false; + } + + auto xml_string = std::string( + std::istreambuf_iterator(xml_file), + std::istreambuf_iterator()); + + RCLCPP_DEBUG(get_logger(), "Behavior Tree file: '%s'", bt_xml_filename.c_str()); + RCLCPP_DEBUG(get_logger(), "Behavior Tree XML: %s", xml_string.c_str()); + + // Create the Behavior Tree from the XML input + tree_ = bt_->buildTreeFromText(xml_string, blackboard_); + + return true; +} + +nav2_util::CallbackReturn +BtWaypointFollower::on_activate(const rclcpp_lifecycle::State & /*state*/) +{ + RCLCPP_INFO(get_logger(), "Activating"); + + action_server_->activate(); + + if (use_bond_) { + // create bond connection + createBond(); + } + + return nav2_util::CallbackReturn::SUCCESS; +} + +nav2_util::CallbackReturn +BtWaypointFollower::on_deactivate(const rclcpp_lifecycle::State & /*state*/) +{ + RCLCPP_INFO(get_logger(), "Deactivating"); + + action_server_->deactivate(); + + if (use_bond_) { + // destroy bond connection + destroyBond(); + } + + return nav2_util::CallbackReturn::SUCCESS; +} + +nav2_util::CallbackReturn +BtWaypointFollower::on_cleanup(const rclcpp_lifecycle::State & /*state*/) +{ + RCLCPP_INFO(get_logger(), "Cleaning up"); + + // TODO(orduno) Fix the race condition between the worker thread ticking the tree + // and the main thread resetting the resources, see #1344 + client_node_.reset(); + + action_server_.reset(); + plugin_lib_names_.clear(); + xml_string_.clear(); + blackboard_.reset(); + bt_->haltAllActions(tree_.rootNode()); + bt_.reset(); + + RCLCPP_INFO(get_logger(), "Completed Cleaning up"); + return nav2_util::CallbackReturn::SUCCESS; +} + +nav2_util::CallbackReturn +BtWaypointFollower::on_shutdown(const rclcpp_lifecycle::State & /*state*/) +{ + RCLCPP_INFO(get_logger(), "Shutting down"); + return nav2_util::CallbackReturn::SUCCESS; +} + +void +BtWaypointFollower::followWaypoints() +{ + auto goal = action_server_->get_current_goal(); + if (goal->poses.size() == 0) { + RCLCPP_ERROR(get_logger(), "Goal has no pose. Terminating current goal."); + action_server_->terminate_current(); + return; + } + initializeBlackboard(goal); + + auto is_canceling = [this]() { + if (action_server_ == nullptr) { + RCLCPP_DEBUG(get_logger(), "Action server unavailable. Canceling."); + return true; + } + + if (!action_server_->is_server_active()) { + RCLCPP_DEBUG(get_logger(), "Action server is inactive. Canceling."); + return true; + } + + return action_server_->is_cancel_requested(); + }; + + std::shared_ptr feedback_msg = std::make_shared(); + + auto on_loop = [&]() { + if (action_server_->is_preempt_requested()) { + RCLCPP_INFO(get_logger(), "Received goal preemption request"); + action_server_->accept_pending_goal(); + auto goal = action_server_->get_current_goal(); + if (goal->poses.size() == 0) { + RCLCPP_ERROR(get_logger(), "Goal has no pose. Terminating current goal."); + action_server_->terminate_current(); + } else { + initializeBlackboard(goal); + } + } + + int current_waypoint_idx = 0; + blackboard_->get("current_waypoint_idx", current_waypoint_idx); + feedback_msg->current_waypoint = current_waypoint_idx; + action_server_->publish_feedback(feedback_msg); + }; + + // Execute the BT that was previously created in the configure step + nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling); + // Make sure that the Bt is not in a running state from a previous execution + // note: if all the ControlNodes are implemented correctly, this is not needed. + bt_->haltAllActions(tree_.rootNode()); + + switch (rc) { + case nav2_behavior_tree::BtStatus::SUCCEEDED: + RCLCPP_INFO(get_logger(), "Navigation succeeded"); + action_server_->succeeded_current(); + break; + + case nav2_behavior_tree::BtStatus::FAILED: + RCLCPP_ERROR(get_logger(), "Navigation failed"); + action_server_->terminate_current(); + break; + + case nav2_behavior_tree::BtStatus::CANCELED: + RCLCPP_INFO(get_logger(), "Navigation canceled"); + action_server_->terminate_all(); + break; + + default: + throw std::logic_error("Invalid status return from BT"); + } +} + +void +BtWaypointFollower::initializeBlackboard(std::shared_ptr goal) +{ + // Update the goals on the blackboard + blackboard_->set("goals", goal->poses); + blackboard_->set("current_waypoint_idx", 0); + blackboard_->set("num_waypoints", goal->poses.size()); + blackboard_->set("goal", goal->poses[0]); + blackboard_->set("goal_achieved", false); +} + +} // namespace nav2_bt_waypoint_follower diff --git a/nav2_bt_waypoint_follower/src/main.cpp b/nav2_bt_waypoint_follower/src/main.cpp new file mode 100644 index 00000000000..01c9fd16851 --- /dev/null +++ b/nav2_bt_waypoint_follower/src/main.cpp @@ -0,0 +1,28 @@ +// Copyright (c) 2018 Intel Corporation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include "nav2_bt_waypoint_follower/bt_waypoint_follower.hpp" +#include "rclcpp/rclcpp.hpp" + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::spin(node->get_node_base_interface()); + rclcpp::shutdown(); + + return 0; +} diff --git a/nav2_bt_waypoint_follower/test/CMakeLists.txt b/nav2_bt_waypoint_follower/test/CMakeLists.txt new file mode 100644 index 00000000000..b4d9db019ea --- /dev/null +++ b/nav2_bt_waypoint_follower/test/CMakeLists.txt @@ -0,0 +1,4 @@ +add_subdirectory(unit) +add_subdirectory(integration) +add_subdirectory(plugins/action) +add_subdirectory(plugins/condition) \ No newline at end of file diff --git a/nav2_bt_waypoint_follower/test/behavior_trees/integration_test_follow_waypoints.xml b/nav2_bt_waypoint_follower/test/behavior_trees/integration_test_follow_waypoints.xml new file mode 100644 index 00000000000..55c1015dc6f --- /dev/null +++ b/nav2_bt_waypoint_follower/test/behavior_trees/integration_test_follow_waypoints.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + diff --git a/nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints.xml b/nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints.xml new file mode 100644 index 00000000000..efd44e7cf2f --- /dev/null +++ b/nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints.xml @@ -0,0 +1,11 @@ + + + + + + + + + diff --git a/nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints_failure.xml b/nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints_failure.xml new file mode 100644 index 00000000000..201b076aa5f --- /dev/null +++ b/nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints_failure.xml @@ -0,0 +1,11 @@ + + + + + + + + + diff --git a/nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints_running.xml b/nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints_running.xml new file mode 100644 index 00000000000..907bb3e269a --- /dev/null +++ b/nav2_bt_waypoint_follower/test/behavior_trees/unit_test_follow_waypoints_running.xml @@ -0,0 +1,13 @@ + + + + + + + + + + + diff --git a/nav2_bt_waypoint_follower/test/integration/CMakeLists.txt b/nav2_bt_waypoint_follower/test/integration/CMakeLists.txt new file mode 100644 index 00000000000..0941fef25ab --- /dev/null +++ b/nav2_bt_waypoint_follower/test/integration/CMakeLists.txt @@ -0,0 +1,7 @@ + +ament_add_gtest(test_follow_waypoints_action_with_bt_node + test_follow_waypoints_action_with_bt_node.cpp +) +target_link_libraries(test_follow_waypoints_action_with_bt_node + bt_waypoint_follower_core +) diff --git a/nav2_bt_waypoint_follower/test/integration/test_follow_waypoints_action_with_bt_node.cpp b/nav2_bt_waypoint_follower/test/integration/test_follow_waypoints_action_with_bt_node.cpp new file mode 100644 index 00000000000..0355d001749 --- /dev/null +++ b/nav2_bt_waypoint_follower/test/integration/test_follow_waypoints_action_with_bt_node.cpp @@ -0,0 +1,84 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +#include "gtest/gtest.h" +#include "nav2_bt_waypoint_follower/bt_waypoint_follower.hpp" +#include "rclcpp/rclcpp.hpp" +#include "rclcpp_action/rclcpp_action.hpp" +#include "ament_index_cpp/get_package_share_directory.hpp" + +using namespace std::chrono_literals; +using Action = nav2_msgs::action::FollowWaypoints; + +std::vector feedback_waypoint_ids; + +void feedback_callback( + std::shared_ptr> goal_handle, + const std::shared_ptr feedback) +{ + (void)goal_handle; + feedback_waypoint_ids.push_back(feedback->current_waypoint); +} + +TEST(xml_loading, valid_action) +{ + auto node = std::make_shared(false); + std::string package_share_directory = ament_index_cpp::get_package_share_directory( + "nav2_bt_waypoint_follower"); + node->set_parameter( + rclcpp::Parameter( + "bt_xml_filename", + package_share_directory + "/test/behavior_trees/integration_test_follow_waypoints.xml")); + nav2_util::CallbackReturn ret; + node->configure(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + node->activate(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + + auto client = rclcpp_action::create_client( + node, + "follow_waypoints"); + while (!client->wait_for_action_server(1s)) {} + + Action::Goal goal; + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = "map"; + pose.pose.position.x = 1.0; + pose.pose.orientation.w = 1.0; + goal.poses.push_back(pose); + goal.poses.push_back(pose); + goal.poses.push_back(pose); + auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + send_goal_options.feedback_callback = feedback_callback; + auto goal_handle_future = client->async_send_goal(goal, send_goal_options); + rclcpp::spin_until_future_complete(node, goal_handle_future); + auto goal_handle = goal_handle_future.get(); + + auto result_future = client->async_get_result(goal_handle); + rclcpp::spin_until_future_complete(node, result_future); + + auto result = result_future.get(); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/nav2_bt_waypoint_follower/test/plugins/action/CMakeLists.txt b/nav2_bt_waypoint_follower/test/plugins/action/CMakeLists.txt new file mode 100644 index 00000000000..5f2c95a816a --- /dev/null +++ b/nav2_bt_waypoint_follower/test/plugins/action/CMakeLists.txt @@ -0,0 +1,9 @@ +ament_add_gtest(test_action_get_next_goal_action + test_get_next_goal_action.cpp +) +target_link_libraries(test_action_get_next_goal_action + nav2_get_next_goal_action_bt_node +) +ament_target_dependencies( + test_action_get_next_goal_action ${dependencies} +) diff --git a/nav2_bt_waypoint_follower/test/plugins/action/test_get_next_goal_action.cpp b/nav2_bt_waypoint_follower/test/plugins/action/test_get_next_goal_action.cpp new file mode 100644 index 00000000000..b585365d6a0 --- /dev/null +++ b/nav2_bt_waypoint_follower/test/plugins/action/test_get_next_goal_action.cpp @@ -0,0 +1,171 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "nav2_msgs/action/follow_waypoints.hpp" +#include "behaviortree_cpp_v3/bt_factory.h" +#include "nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp" + +class GetNextGoalActionTestFixture : public ::testing::Test +{ +public: + static void SetUpTestCase() + { + node_ = std::make_shared("get_next_goal_action_test_fixture"); + factory_ = std::make_shared(); + config_ = new BT::NodeConfiguration(); + + // Create the blackboard that will be shared by all of the nodes in the tree + config_->blackboard = BT::Blackboard::create(); + // Put items on the blackboard + config_->blackboard->set( + "node", + node_); + config_->blackboard->set( + "server_timeout", + std::chrono::milliseconds(10)); + config_->blackboard->set("path_updated", false); + config_->blackboard->set("initial_pose_received", false); + config_->blackboard->set("number_recoveries", 0); + + BT::NodeBuilder builder = + [](const std::string & name, const BT::NodeConfiguration & config) + { + return std::make_unique( + name, config); + }; + + factory_->registerBuilder("GetNextGoal", builder); + } + + static void TearDownTestCase() + { + delete config_; + config_ = nullptr; + node_.reset(); + factory_.reset(); + } + + void SetUp() override + { + nav2_msgs::action::FollowWaypoints::Goal goal; + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = "map"; + pose.pose.position.x = 1.0; + pose.pose.orientation.w = 1.0; + goal.poses.push_back(pose); + pose.pose.position.x = 2.0; + goal.poses.push_back(pose); + pose.pose.position.x = 3.0; + goal.poses.push_back(pose); + config_->blackboard->set("goals", goal.poses); + config_->blackboard->set("current_waypoint_idx", 0); + config_->blackboard->set("num_waypoints", goal.poses.size()); + config_->blackboard->set("goal", goal.poses[0]); + config_->blackboard->set("goal_achieved", false); + } + + void TearDown() override + { + tree_.reset(); + } + +protected: + static rclcpp::Node::SharedPtr node_; + static BT::NodeConfiguration * config_; + static std::shared_ptr factory_; + static std::shared_ptr tree_; +}; + +rclcpp::Node::SharedPtr GetNextGoalActionTestFixture::node_ = nullptr; +BT::NodeConfiguration * GetNextGoalActionTestFixture::config_ = nullptr; +std::shared_ptr GetNextGoalActionTestFixture::factory_ = nullptr; +std::shared_ptr GetNextGoalActionTestFixture::tree_ = nullptr; + +TEST_F(GetNextGoalActionTestFixture, test_ports) +{ + std::string xml_txt = + R"( + + + + + )"; + + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + std::vector goals; + tree_->rootNode()->getInput("goals", goals); + EXPECT_EQ(goals.size(), 3u); + EXPECT_EQ(tree_->rootNode()->getInput("goal_achieved"), false); +} + +TEST_F(GetNextGoalActionTestFixture, test_tick_not_update) +{ + std::string xml_txt = + R"( + + + + + )"; + + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + EXPECT_EQ(config_->blackboard->get("current_waypoint_idx"), 0); + EXPECT_EQ(config_->blackboard->get("goal").pose.position.x, 1.0); + EXPECT_EQ(tree_->rootNode()->executeTick(), BT::NodeStatus::SUCCESS); + EXPECT_EQ(config_->blackboard->get("goal_achieved"), false); + EXPECT_EQ(config_->blackboard->get("current_waypoint_idx"), 0); + EXPECT_EQ(config_->blackboard->get("goal").pose.position.x, 1.0); +} + +TEST_F(GetNextGoalActionTestFixture, test_tick_update) +{ + std::string xml_txt = + R"( + + + + + )"; + + config_->blackboard->set("goal_achieved", true); + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + EXPECT_EQ(config_->blackboard->get("current_waypoint_idx"), 0); + EXPECT_EQ(config_->blackboard->get("goal").pose.position.x, 1.0); + EXPECT_EQ(tree_->rootNode()->executeTick(), BT::NodeStatus::SUCCESS); + EXPECT_EQ(config_->blackboard->get("goal_achieved"), false); + EXPECT_EQ(config_->blackboard->get("current_waypoint_idx"), 1); + EXPECT_EQ(config_->blackboard->get("goal").pose.position.x, 2.0); +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + + // initialize ROS + rclcpp::init(argc, argv); + + int all_successful = RUN_ALL_TESTS(); + + // shutdown ROS + rclcpp::shutdown(); + + return all_successful; +} diff --git a/nav2_bt_waypoint_follower/test/plugins/condition/CMakeLists.txt b/nav2_bt_waypoint_follower/test/plugins/condition/CMakeLists.txt new file mode 100644 index 00000000000..5682f2f339c --- /dev/null +++ b/nav2_bt_waypoint_follower/test/plugins/condition/CMakeLists.txt @@ -0,0 +1,9 @@ +ament_add_gtest(test_condition_all_goals_achieved_condition + test_all_goals_achieved_condition.cpp +) +target_link_libraries(test_condition_all_goals_achieved_condition + nav2_all_goals_achieved_condition_bt_node +) +ament_target_dependencies(test_condition_all_goals_achieved_condition + ${dependencies} +) \ No newline at end of file diff --git a/nav2_bt_waypoint_follower/test/plugins/condition/test_all_goals_achieved_condition.cpp b/nav2_bt_waypoint_follower/test/plugins/condition/test_all_goals_achieved_condition.cpp new file mode 100644 index 00000000000..93b01075421 --- /dev/null +++ b/nav2_bt_waypoint_follower/test/plugins/condition/test_all_goals_achieved_condition.cpp @@ -0,0 +1,155 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "behaviortree_cpp_v3/bt_factory.h" +#include "nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp" + +class AllGoalsAchievedConditionTestFixture : public ::testing::Test +{ +public: + static void SetUpTestCase() + { + node_ = std::make_shared("get_next_goal_action_test_fixture"); + factory_ = std::make_shared(); + config_ = new BT::NodeConfiguration(); + + // Create the blackboard that will be shared by all of the nodes in the tree + config_->blackboard = BT::Blackboard::create(); + // Put items on the blackboard + config_->blackboard->set( + "node", + node_); + config_->blackboard->set( + "server_timeout", + std::chrono::milliseconds(10)); + config_->blackboard->set("path_updated", false); + config_->blackboard->set("initial_pose_received", false); + config_->blackboard->set("number_recoveries", 0); + + BT::NodeBuilder builder = + [](const std::string & name, const BT::NodeConfiguration & config) + { + return std::make_unique( + name, config); + }; + + factory_->registerBuilder( + "AllGoalAchieved", builder); + } + + static void TearDownTestCase() + { + delete config_; + config_ = nullptr; + node_.reset(); + factory_.reset(); + } + + void SetUp() override + { + config_->blackboard->set("current_waypoint_idx", 0); + config_->blackboard->set("num_waypoints", 3); + config_->blackboard->set("goal_achieved", false); + } + + void TearDown() override + { + tree_.reset(); + } + +protected: + static rclcpp::Node::SharedPtr node_; + static BT::NodeConfiguration * config_; + static std::shared_ptr factory_; + static std::shared_ptr tree_; +}; + +rclcpp::Node::SharedPtr AllGoalsAchievedConditionTestFixture::node_ = nullptr; +BT::NodeConfiguration * AllGoalsAchievedConditionTestFixture::config_ = nullptr; +std::shared_ptr AllGoalsAchievedConditionTestFixture::factory_ = nullptr; +std::shared_ptr AllGoalsAchievedConditionTestFixture::tree_ = nullptr; + +TEST_F(AllGoalsAchievedConditionTestFixture, test_ports) +{ + std::string xml_txt = + R"( + + + + + )"; + + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + EXPECT_EQ(tree_->rootNode()->getInput("goal_achieved"), false); +} + +TEST_F(AllGoalsAchievedConditionTestFixture, test_tick_not_achieved) +{ + std::string xml_txt = + R"( + + + + + )"; + + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + EXPECT_EQ(config_->blackboard->get("current_waypoint_idx"), 0); + EXPECT_EQ(tree_->rootNode()->executeTick(), BT::NodeStatus::FAILURE); + + config_->blackboard->set("goal_achieved", true); + EXPECT_EQ(tree_->rootNode()->executeTick(), BT::NodeStatus::FAILURE); + + config_->blackboard->set("goal_achieved", false); + config_->blackboard->set("current_waypoint_idx", 2); + EXPECT_EQ(tree_->rootNode()->executeTick(), BT::NodeStatus::FAILURE); +} + +TEST_F(AllGoalsAchievedConditionTestFixture, test_tick_achieved) +{ + std::string xml_txt = + R"( + + + + + )"; + + config_->blackboard->set("goal_achieved", true); + config_->blackboard->set("current_waypoint_idx", 2); + tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); + EXPECT_EQ(config_->blackboard->get("current_waypoint_idx"), 2); + EXPECT_EQ(tree_->rootNode()->executeTick(), BT::NodeStatus::SUCCESS); +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + + // initialize ROS + rclcpp::init(argc, argv); + + int all_successful = RUN_ALL_TESTS(); + + // shutdown ROS + rclcpp::shutdown(); + + return all_successful; +} diff --git a/nav2_bt_waypoint_follower/test/unit/CMakeLists.txt b/nav2_bt_waypoint_follower/test/unit/CMakeLists.txt new file mode 100644 index 00000000000..a3ef6a79b88 --- /dev/null +++ b/nav2_bt_waypoint_follower/test/unit/CMakeLists.txt @@ -0,0 +1,4 @@ +ament_add_gtest(test_follow_waypoints_action test_follow_waypoints_action.cpp) +target_link_libraries(test_follow_waypoints_action + bt_waypoint_follower_core +) \ No newline at end of file diff --git a/nav2_bt_waypoint_follower/test/unit/test_follow_waypoints_action.cpp b/nav2_bt_waypoint_follower/test/unit/test_follow_waypoints_action.cpp new file mode 100644 index 00000000000..369778f0b80 --- /dev/null +++ b/nav2_bt_waypoint_follower/test/unit/test_follow_waypoints_action.cpp @@ -0,0 +1,243 @@ +// Copyright (c) 2020 ymd-stella +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +#include "gtest/gtest.h" +#include "nav2_bt_waypoint_follower/bt_waypoint_follower.hpp" +#include "rclcpp/rclcpp.hpp" +#include "rclcpp_action/rclcpp_action.hpp" +#include "ament_index_cpp/get_package_share_directory.hpp" + +using namespace std::chrono_literals; + +TEST(follow_waypoints_action, valid_action) +{ + auto node = std::make_shared(false); + std::string package_share_directory = ament_index_cpp::get_package_share_directory( + "nav2_bt_waypoint_follower"); + node->set_parameter( + rclcpp::Parameter( + "bt_xml_filename", + package_share_directory + "/test/behavior_trees/unit_test_follow_waypoints.xml")); + nav2_util::CallbackReturn ret; + node->configure(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + node->activate(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + + auto client = rclcpp_action::create_client( + node, + "follow_waypoints"); + while (!client->wait_for_action_server(1s)) {} + + nav2_msgs::action::FollowWaypoints::Goal goal; + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = "map"; + pose.pose.position.x = 1.0; + pose.pose.orientation.w = 1.0; + goal.poses.push_back(pose); + goal.poses.push_back(pose); + goal.poses.push_back(pose); + auto goal_handle_future = client->async_send_goal(goal); + rclcpp::spin_until_future_complete(node, goal_handle_future); + auto goal_handle = goal_handle_future.get(); + + auto result_future = client->async_get_result(goal_handle); + rclcpp::spin_until_future_complete(node, result_future); + + auto result = result_future.get(); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::SUCCEEDED); +} + +TEST(follow_waypoints_action, invalid_xml) +{ + auto node = std::make_shared(false); + std::string package_share_directory = ament_index_cpp::get_package_share_directory( + "nav2_bt_waypoint_follower"); + node->set_parameter(rclcpp::Parameter("bt_xml_filename", "not_found.xml")); + nav2_util::CallbackReturn ret; + node->configure(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::FAILURE); +} + +TEST(follow_waypoints_action, no_pose) +{ + auto node = std::make_shared(); + std::string package_share_directory = ament_index_cpp::get_package_share_directory( + "nav2_bt_waypoint_follower"); + node->set_parameter( + rclcpp::Parameter( + "bt_xml_filename", + package_share_directory + "/test/behavior_trees/unit_test_follow_waypoints.xml")); + nav2_util::CallbackReturn ret; + node->configure(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + node->activate(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + + auto client = rclcpp_action::create_client( + node, + "follow_waypoints"); + while (!client->wait_for_action_server(1s)) {} + + nav2_msgs::action::FollowWaypoints::Goal goal; + auto goal_handle_future = client->async_send_goal(goal); + rclcpp::spin_until_future_complete(node, goal_handle_future); + auto goal_handle = goal_handle_future.get(); + + auto result_future = client->async_get_result(goal_handle); + rclcpp::spin_until_future_complete(node, result_future); + + auto result = result_future.get(); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::ABORTED); +} + +TEST(follow_waypoints_action, cancel) +{ + auto node = std::make_shared(false); + std::string package_share_directory = ament_index_cpp::get_package_share_directory( + "nav2_bt_waypoint_follower"); + node->set_parameter( + rclcpp::Parameter( + "bt_xml_filename", + package_share_directory + "/test/behavior_trees/unit_test_follow_waypoints_running.xml")); + nav2_util::CallbackReturn ret; + node->configure(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + node->activate(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + + auto client = rclcpp_action::create_client( + node, + "follow_waypoints"); + while (!client->wait_for_action_server(1s)) {} + + nav2_msgs::action::FollowWaypoints::Goal goal; + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = "map"; + pose.pose.position.x = 1.0; + pose.pose.orientation.w = 1.0; + goal.poses.push_back(pose); + goal.poses.push_back(pose); + goal.poses.push_back(pose); + auto goal_handle_future = client->async_send_goal(goal); + rclcpp::spin_until_future_complete(node, goal_handle_future); + auto goal_handle = goal_handle_future.get(); + auto result_future = client->async_get_result(goal_handle); + + auto cancel_future = client->async_cancel_goal(goal_handle); + rclcpp::spin_until_future_complete(node, cancel_future); + auto cancel_response = cancel_future.get(); + + rclcpp::spin_until_future_complete(node, result_future); + + auto result = result_future.get(); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::CANCELED); +} + +TEST(follow_waypoints_action, preempt) +{ + auto node = std::make_shared(false); + std::string package_share_directory = ament_index_cpp::get_package_share_directory( + "nav2_bt_waypoint_follower"); + node->set_parameter( + rclcpp::Parameter( + "bt_xml_filename", + package_share_directory + "/test/behavior_trees/unit_test_follow_waypoints_running.xml")); + nav2_util::CallbackReturn ret; + node->configure(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + node->activate(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + + auto client = rclcpp_action::create_client( + node, + "follow_waypoints"); + while (!client->wait_for_action_server(1s)) {} + + nav2_msgs::action::FollowWaypoints::Goal goal; + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = "map"; + pose.pose.position.x = 1.0; + pose.pose.orientation.w = 1.0; + goal.poses.push_back(pose); + goal.poses.push_back(pose); + goal.poses.push_back(pose); + auto goal_handle_future = client->async_send_goal(goal); + rclcpp::spin_until_future_complete(node, goal_handle_future); + auto goal_handle = goal_handle_future.get(); + + auto goal_handle_future2 = client->async_send_goal(goal); + rclcpp::spin_until_future_complete(node, goal_handle_future2); + auto goal_handle2 = goal_handle_future2.get(); + auto result_future = client->async_get_result(goal_handle2); + + auto cancel_future = client->async_cancel_goal(goal_handle2); + rclcpp::spin_until_future_complete(node, cancel_future); + auto cancel_response = cancel_future.get(); + + rclcpp::spin_until_future_complete(node, result_future); + + auto result = result_future.get(); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::CANCELED); +} + +TEST(follow_waypoints_action, failure) +{ + auto node = std::make_shared(false); + std::string package_share_directory = ament_index_cpp::get_package_share_directory( + "nav2_bt_waypoint_follower"); + node->set_parameter( + rclcpp::Parameter( + "bt_xml_filename", + package_share_directory + "/test/behavior_trees/unit_test_follow_waypoints_failure.xml")); + nav2_util::CallbackReturn ret; + node->configure(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + node->activate(ret); + EXPECT_EQ(ret, nav2_util::CallbackReturn::SUCCESS); + + auto client = rclcpp_action::create_client( + node, + "follow_waypoints"); + while (!client->wait_for_action_server(1s)) {} + + nav2_msgs::action::FollowWaypoints::Goal goal; + geometry_msgs::msg::PoseStamped pose; + pose.header.frame_id = "map"; + pose.pose.position.x = 1.0; + pose.pose.orientation.w = 1.0; + goal.poses.push_back(pose); + goal.poses.push_back(pose); + goal.poses.push_back(pose); + auto goal_handle_future = client->async_send_goal(goal); + rclcpp::spin_until_future_complete(node, goal_handle_future); + auto goal_handle = goal_handle_future.get(); + + auto result_future = client->async_get_result(goal_handle); + rclcpp::spin_until_future_complete(node, result_future); + + auto result = result_future.get(); + EXPECT_EQ(result.code, rclcpp_action::ResultCode::ABORTED); +} + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/nav2_system_tests/src/waypoint_follower/tester.py b/nav2_system_tests/src/waypoint_follower/tester.py index 7f5db902fba..81d19805839 100755 --- a/nav2_system_tests/src/waypoint_follower/tester.py +++ b/nav2_system_tests/src/waypoint_follower/tester.py @@ -33,7 +33,7 @@ class WaypointFollowerTest(Node): def __init__(self): super().__init__(node_name='nav2_waypoint_tester', namespace='') self.waypoints = None - self.action_client = ActionClient(self, FollowWaypoints, 'FollowWaypoints') + self.action_client = ActionClient(self, FollowWaypoints, 'follow_waypoints') self.initial_pose_pub = self.create_publisher(PoseWithCovarianceStamped, 'initialpose', 10) self.initial_pose_received = False @@ -78,7 +78,7 @@ def run(self, block): return False while not self.action_client.wait_for_server(timeout_sec=1.0): - self.info_msg("'FollowWaypoints' action server not available, waiting...") + self.info_msg("'follow_waypoints' action server not available, waiting...") action_request = FollowWaypoints.Goal() action_request.poses = self.waypoints @@ -101,7 +101,7 @@ def run(self, block): get_result_future = self.goal_handle.get_result_async() - self.info_msg("Waiting for 'FollowWaypoints' action to complete") + self.info_msg("Waiting for 'follow_waypoints' action to complete") try: rclpy.spin_until_future_complete(self, get_result_future) status = get_result_future.result().status diff --git a/navigation2/package.xml b/navigation2/package.xml index 29065f56d8b..9122de17168 100644 --- a/navigation2/package.xml +++ b/navigation2/package.xml @@ -15,6 +15,7 @@ nav2_amcl nav2_bt_navigator + nav2_bt_waypoint_follower nav2_costmap_2d nav2_core nav2_dwb_controller @@ -29,7 +30,6 @@ nav2_util nav2_voxel_grid nav2_controller - nav2_waypoint_follower ament_cmake From 35557b431b4c6623c95cc3db14574ce4a47eaf02 Mon Sep 17 00:00:00 2001 From: ymd-stella Date: Fri, 14 Aug 2020 07:20:48 +0900 Subject: [PATCH 2/6] Remove launch argument waypoint_follower_bt_xml_filename --- nav2_bringup/bringup/launch/navigation_launch.py | 9 --------- 1 file changed, 9 deletions(-) diff --git a/nav2_bringup/bringup/launch/navigation_launch.py b/nav2_bringup/bringup/launch/navigation_launch.py index 27c40ce996c..ef736e0921e 100644 --- a/nav2_bringup/bringup/launch/navigation_launch.py +++ b/nav2_bringup/bringup/launch/navigation_launch.py @@ -32,7 +32,6 @@ def generate_launch_description(): autostart = LaunchConfiguration('autostart') params_file = LaunchConfiguration('params_file') default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename') - waypoint_follower_bt_xml_filename = LaunchConfiguration('waypoint_follower_bt_xml_filename') map_subscribe_transient_local = LaunchConfiguration('map_subscribe_transient_local') lifecycle_nodes = ['controller_server', @@ -54,7 +53,6 @@ def generate_launch_description(): param_substitutions = { 'use_sim_time': use_sim_time, 'default_bt_xml_filename': default_bt_xml_filename, - 'bt_xml_filename': waypoint_follower_bt_xml_filename, 'autostart': autostart, 'map_subscribe_transient_local': map_subscribe_transient_local} @@ -92,13 +90,6 @@ def generate_launch_description(): 'behavior_trees', 'navigate_w_replanning_and_recovery.xml'), description='Full path to the behavior tree xml file to use for bt_navigator'), - DeclareLaunchArgument( - 'waypoint_follower_bt_xml_filename', - default_value=os.path.join( - get_package_share_directory('nav2_bt_waypoint_follower'), - 'behavior_trees', 'follow_waypoints.xml'), - description='Full path to the behavior tree xml file to use for bt_waypoint_follower'), - DeclareLaunchArgument( 'map_subscribe_transient_local', default_value='false', description='Whether to set the map subscriber QoS to transient local'), From a5d2f772d488ac3ba81b39a5afbf1c323521fb55 Mon Sep 17 00:00:00 2001 From: ymd-stella Date: Fri, 14 Aug 2020 07:29:53 +0900 Subject: [PATCH 3/6] Update bt_waypoint_follower/plugin_lib_names --- doc/parameters/param_list.md | 2 +- nav2_bringup/bringup/params/nav2_params.yaml | 17 ----------------- .../src/bt_waypoint_follower.cpp | 17 ----------------- 3 files changed, 1 insertion(+), 35 deletions(-) diff --git a/doc/parameters/param_list.md b/doc/parameters/param_list.md index 1597d36d48c..4c907a04527 100644 --- a/doc/parameters/param_list.md +++ b/doc/parameters/param_list.md @@ -479,7 +479,7 @@ When `planner_plugins` parameter is not overridden, the following default plugin | Parameter | Default | Description | | ----------| --------| ------------| | bt_xml_filename | N/A | path to the behavior tree XML description | -| plugin_lib_names | [ "nav2_compute_path_to_pose_action_bt_node", "nav2_follow_path_action_bt_node", "nav2_back_up_action_bt_node", "nav2_spin_action_bt_node", "nav2_wait_action_bt_node", "nav2_clear_costmap_service_bt_node", "nav2_is_stuck_condition_bt_node", "nav2_goal_reached_condition_bt_node", "nav2_initial_pose_received_condition_bt_node", "nav2_goal_updated_condition_bt_node", "nav2_reinitialize_global_localization_service_bt_node", "nav2_rate_controller_bt_node", "nav2_distance_controller_bt_node", "nav2_recovery_node_bt_node", "nav2_pipeline_sequence_bt_node", "nav2_round_robin_node_bt_node", "nav2_transform_available_condition_bt_node", "nav2_time_expired_condition_bt_node", "nav2_distance_traveled_condition_bt_node", "nav2_navigate_to_pose_action_bt_node", "nav2_all_goals_achieved_condition_bt_node", "nav2_get_next_goal_action_bt_node"] | list of behavior tree node shared libraries | +| plugin_lib_names | [ "nav2_wait_action_bt_node", "nav2_recovery_node_bt_node", "nav2_navigate_to_pose_action_bt_node", "nav2_all_goals_achieved_condition_bt_node", "nav2_get_next_goal_action_bt_node"] | list of behavior tree node shared libraries | # recoveries diff --git a/nav2_bringup/bringup/params/nav2_params.yaml b/nav2_bringup/bringup/params/nav2_params.yaml index 5c673100d24..17e87052d4e 100644 --- a/nav2_bringup/bringup/params/nav2_params.yaml +++ b/nav2_bringup/bringup/params/nav2_params.yaml @@ -286,25 +286,8 @@ bt_waypoint_follower: use_sim_time: True bt_xml_filename: "follow_waypoints.xml" plugin_lib_names: - - nav2_compute_path_to_pose_action_bt_node - - nav2_follow_path_action_bt_node - - nav2_back_up_action_bt_node - - nav2_spin_action_bt_node - nav2_wait_action_bt_node - - nav2_clear_costmap_service_bt_node - - nav2_is_stuck_condition_bt_node - - nav2_goal_reached_condition_bt_node - - nav2_initial_pose_received_condition_bt_node - - nav2_goal_updated_condition_bt_node - - nav2_reinitialize_global_localization_service_bt_node - - nav2_rate_controller_bt_node - - nav2_distance_controller_bt_node - nav2_recovery_node_bt_node - - nav2_pipeline_sequence_bt_node - - nav2_round_robin_node_bt_node - - nav2_transform_available_condition_bt_node - - nav2_time_expired_condition_bt_node - - nav2_distance_traveled_condition_bt_node - nav2_navigate_to_pose_action_bt_node - nav2_all_goals_achieved_condition_bt_node - nav2_get_next_goal_action_bt_node diff --git a/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp b/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp index f319ac54d08..cede551345c 100644 --- a/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp +++ b/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp @@ -36,25 +36,8 @@ BtWaypointFollower::BtWaypointFollower(bool use_bond) RCLCPP_INFO(get_logger(), "Creating"); const std::vector plugin_libs = { - "nav2_compute_path_to_pose_action_bt_node", - "nav2_follow_path_action_bt_node", - "nav2_back_up_action_bt_node", - "nav2_spin_action_bt_node", "nav2_wait_action_bt_node", - "nav2_clear_costmap_service_bt_node", - "nav2_is_stuck_condition_bt_node", - "nav2_goal_reached_condition_bt_node", - "nav2_initial_pose_received_condition_bt_node", - "nav2_goal_updated_condition_bt_node", - "nav2_reinitialize_global_localization_service_bt_node", - "nav2_rate_controller_bt_node", - "nav2_distance_controller_bt_node", "nav2_recovery_node_bt_node", - "nav2_pipeline_sequence_bt_node", - "nav2_round_robin_node_bt_node", - "nav2_transform_available_condition_bt_node", - "nav2_time_expired_condition_bt_node", - "nav2_distance_traveled_condition_bt_node", "nav2_navigate_to_pose_action_bt_node", "nav2_all_goals_achieved_condition_bt_node", "nav2_get_next_goal_action_bt_node", From 6e1251b7ef0ae6bd16388b79c10f8d0e0c82797a Mon Sep 17 00:00:00 2001 From: ymd-stella Date: Fri, 14 Aug 2020 07:31:41 +0900 Subject: [PATCH 4/6] Fix copyright of nav2_bt_waypoint_follower --- .../include/nav2_bt_waypoint_follower/bt_waypoint_follower.hpp | 1 + .../plugins/action/get_next_goal_action.hpp | 1 + .../plugins/condition/all_goals_achieved_condition.hpp | 1 + .../plugins/action/get_next_goal_action.cpp | 1 + .../plugins/condition/all_goals_achieved_condition.cpp | 1 + nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp | 1 + 6 files changed, 6 insertions(+) diff --git a/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/bt_waypoint_follower.hpp b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/bt_waypoint_follower.hpp index a179f4b4e17..80c28a5df9a 100644 --- a/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/bt_waypoint_follower.hpp +++ b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/bt_waypoint_follower.hpp @@ -1,3 +1,4 @@ +// Copyright (c) 2020 Samsung Research America // Copyright (c) 2020 ymd-stella // // Licensed under the Apache License, Version 2.0 (the "License"); diff --git a/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp index ac850e39d6e..e391483ba6f 100644 --- a/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp +++ b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.hpp @@ -1,3 +1,4 @@ +// Copyright (c) 2020 Samsung Research America // Copyright (c) 2020 ymd-stella // // Licensed under the Apache License, Version 2.0 (the "License"); diff --git a/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp index bc4f443c01d..1df05ed67cc 100644 --- a/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp +++ b/nav2_bt_waypoint_follower/include/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.hpp @@ -1,3 +1,4 @@ +// Copyright (c) 2020 Samsung Research America // Copyright (c) 2020 ymd-stella // // Licensed under the Apache License, Version 2.0 (the "License"); diff --git a/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.cpp b/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.cpp index eec6cd709a7..19b7f9e331b 100644 --- a/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.cpp +++ b/nav2_bt_waypoint_follower/plugins/action/get_next_goal_action.cpp @@ -1,3 +1,4 @@ +// Copyright (c) 2020 Samsung Research America // Copyright (c) 2020 ymd-stella // // Licensed under the Apache License, Version 2.0 (the "License"); diff --git a/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.cpp b/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.cpp index da77cf153d4..d65fb9edea9 100644 --- a/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.cpp +++ b/nav2_bt_waypoint_follower/plugins/condition/all_goals_achieved_condition.cpp @@ -1,3 +1,4 @@ +// Copyright (c) 2020 Samsung Research America // Copyright (c) 2020 ymd-stella // // Licensed under the Apache License, Version 2.0 (the "License"); diff --git a/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp b/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp index cede551345c..0b3160a022b 100644 --- a/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp +++ b/nav2_bt_waypoint_follower/src/bt_waypoint_follower.cpp @@ -1,3 +1,4 @@ +// Copyright (c) 2020 Samsung Research America // Copyright (c) 2020 ymd-stella // // Licensed under the Apache License, Version 2.0 (the "License"); From ef7736093a0e8f61650d1153e2f50e241ea40a76 Mon Sep 17 00:00:00 2001 From: ymd-stella Date: Sat, 22 Aug 2020 08:03:14 +0900 Subject: [PATCH 5/6] Restore description of waypoint_follower in param_list.md Signed-off-by: ymd-stella --- doc/parameters/param_list.md | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/doc/parameters/param_list.md b/doc/parameters/param_list.md index 4c907a04527..1e1da33bf3e 100644 --- a/doc/parameters/param_list.md +++ b/doc/parameters/param_list.md @@ -474,6 +474,13 @@ When `planner_plugins` parameter is not overridden, the following default plugin | ``.use_astar | false | Whether to use A*, if false, uses Dijstra's expansion | | ``.allow_unknown | true | Whether to allow planning in unknown space | +# waypoint_follower + +| Parameter | Default | Description | +| ----------| --------| ------------| +| stop_on_failure | true | Whether to fail action task if a single waypoint fails. If false, will continue to next waypoint. | +| loop_rate | 20 | Rate to check for results from current navigation task | + # bt_waypoint_follower | Parameter | Default | Description | From ad017ca7a482753c37a5fddf8a39fc25ad8f3ee8 Mon Sep 17 00:00:00 2001 From: ymd-stella Date: Tue, 1 Sep 2020 08:44:14 +0900 Subject: [PATCH 6/6] Revert navigation2/package.xml --- navigation2/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/navigation2/package.xml b/navigation2/package.xml index 9122de17168..86c635882f1 100644 --- a/navigation2/package.xml +++ b/navigation2/package.xml @@ -30,6 +30,7 @@ nav2_util nav2_voxel_grid nav2_controller + nav2_waypoint_follower ament_cmake