From e68bbedb336c19b48e79752a2057b0c86cde9e01 Mon Sep 17 00:00:00 2001 From: "Marco A. Gutierrez" Date: Thu, 18 Apr 2024 22:57:42 +0000 Subject: [PATCH] Imported upstream version '2.3.0' of 'upstream' --- .editorconfig | 17 + .github/workflows/main.yml | 20 + .ros2_build.sh | 15 + .travis.yml | 15 + LICENSE | 24 + README.md | 11 + docs/Gemfile | 3 + docs/_config.yml | 60 + docs/_layouts/plugin.md | 27 + docs/_plugins/attitude_indicator.md | 6 + docs/_plugins/coordinate_picker.md | 8 + docs/_plugins/disparity.md | 20 + docs/_plugins/draw_polygon.md | 6 + docs/_plugins/float.md | 22 + docs/_plugins/gps.md | 20 + docs/_plugins/grid.md | 22 + docs/_plugins/image.md | 20 + docs/_plugins/laserscan.md | 20 + docs/_plugins/marker.md | 10 + docs/_plugins/measuring.md | 6 + docs/_plugins/move_base.md | 6 + docs/_plugins/multires_image.md | 8 + docs/_plugins/navsat.md | 16 + docs/_plugins/occupancy_grid.md | 6 + docs/_plugins/odometry.md | 18 + docs/_plugins/path.md | 8 + docs/_plugins/plan_route.md | 6 + docs/_plugins/point_click_publisher.md | 10 + docs/_plugins/point_drawing.md | 6 + docs/_plugins/pointcloud2.md | 6 + docs/_plugins/pose.md | 6 + docs/_plugins/robot_image.md | 14 + docs/_plugins/route.md | 6 + docs/_plugins/string.md | 20 + docs/_plugins/textured_marker.md | 10 + docs/_plugins/tf_frame.md | 16 + docs/_plugins/tile_map.md | 14 + docs/assets/images/disparity.png | Bin 0 -> 68355 bytes docs/assets/images/mapviz.png | Bin 0 -> 411094 bytes docs/assets/images/mapviz_features.png | Bin 0 -> 274323 bytes docs/assets/images/multires.png | Bin 0 -> 530325 bytes docs/assets/images/multires2.png | Bin 0 -> 559179 bytes docs/assets/images/roads.png | Bin 0 -> 289186 bytes docs/assets/images/satellite.png | Bin 0 -> 292903 bytes .../images/screenshot_coordinate_picker.png | Bin 0 -> 23990 bytes docs/assets/images/terrain.png | Bin 0 -> 268716 bytes docs/assets/images/toner.png | Bin 0 -> 130031 bytes docs/assets/images/watercolor.png | Bin 0 -> 276254 bytes docs/assets/js/search-data.json | 12 + docs/index.md | 63 + docs/plugins.md | 27 + mapviz/CHANGELOG.rst | 306 ++++ mapviz/CMakeLists.txt | 210 +++ mapviz/include/mapviz/color_button.h | 73 + mapviz/include/mapviz/config_item.h | 90 + mapviz/include/mapviz/map_canvas.h | 254 +++ mapviz/include/mapviz/mapviz.hpp | 219 +++ mapviz/include/mapviz/mapviz_application.h | 59 + mapviz/include/mapviz/mapviz_plugin.h | 392 +++++ mapviz/include/mapviz/rqt_mapviz.h | 68 + mapviz/include/mapviz/select_frame_dialog.h | 127 ++ mapviz/include/mapviz/select_service_dialog.h | 174 ++ mapviz/include/mapviz/select_topic_dialog.h | 197 +++ mapviz/include/mapviz/stopwatch.h | 119 ++ mapviz/include/mapviz/video_writer.h | 70 + mapviz/include/mapviz/widgets.h | 171 ++ mapviz/launch/mapviz.launch.py | 41 + mapviz/launch/mapviz.launch.xml | 27 + mapviz/mainpage.dox | 19 + mapviz/package.xml | 50 + mapviz/plugin.xml | 17 + mapviz/src/color_button.cpp | 75 + mapviz/src/config_item.cpp | 122 ++ mapviz/src/configitem.ui | 797 +++++++++ mapviz/src/map_canvas.cpp | 640 +++++++ mapviz/src/mapviz.cpp | 1494 +++++++++++++++++ mapviz/src/mapviz.ui | 814 +++++++++ mapviz/src/mapviz_application.cpp | 64 + mapviz/src/mapviz_main.cpp | 54 + mapviz/src/pluginselect.ui | 90 + mapviz/src/resources/LICENSE | 9 + mapviz/src/resources/arrow_in.png | Bin 0 -> 600 bytes mapviz/src/resources/green-arrow.png | Bin 0 -> 941 bytes mapviz/src/resources/icons.qrc | 11 + mapviz/src/resources/image-x-generic.png | Bin 0 -> 558 bytes mapviz/src/resources/media-playback-pause.png | Bin 0 -> 464 bytes mapviz/src/resources/media-playback-stop.png | Bin 0 -> 429 bytes mapviz/src/resources/media-record.png | Bin 0 -> 653 bytes mapviz/src/resources/remove-icon-th.png | Bin 0 -> 1035 bytes mapviz/src/rqt_mapviz.cpp | 66 + mapviz/src/select_frame_dialog.cpp | 257 +++ mapviz/src/select_service_dialog.cpp | 292 ++++ mapviz/src/select_topic_dialog.cpp | 335 ++++ mapviz/src/video_writer.cpp | 128 ++ mapviz_interfaces/CHANGELOG.rst | 97 ++ mapviz_interfaces/CMakeLists.txt | 25 + mapviz_interfaces/package.xml | 24 + mapviz_interfaces/srv/AddMapvizDisplay.srv | 21 + mapviz_plugins/CHANGELOG.rst | 374 +++++ mapviz_plugins/CMakeLists.txt | 242 +++ .../attitude_indicator_plugin.h | 116 ++ .../mapviz_plugins/canvas_click_filter.h | 73 + .../mapviz_plugins/coordinate_picker_plugin.h | 94 ++ .../include/mapviz_plugins/disparity_plugin.h | 150 ++ .../mapviz_plugins/draw_polygon_plugin.h | 115 ++ .../include/mapviz_plugins/float_plugin.h | 160 ++ .../include/mapviz_plugins/gps_plugin.h | 91 + .../include/mapviz_plugins/grid_plugin.h | 123 ++ .../include/mapviz_plugins/image_plugin.h | 157 ++ .../include/mapviz_plugins/laserscan_plugin.h | 153 ++ .../include/mapviz_plugins/marker_plugin.h | 179 ++ .../include/mapviz_plugins/measuring_plugin.h | 123 ++ .../include/mapviz_plugins/move_base_plugin.h | 118 ++ .../include/mapviz_plugins/navsat_plugin.h | 88 + .../mapviz_plugins/occupancy_grid_plugin.h | 126 ++ .../include/mapviz_plugins/odometry_plugin.h | 100 ++ .../include/mapviz_plugins/path_plugin.h | 97 ++ .../mapviz_plugins/placeable_window_proxy.h | 122 ++ .../mapviz_plugins/plan_route_plugin.h | 133 ++ .../point_click_publisher_plugin.h | 101 ++ .../mapviz_plugins/point_drawing_plugin.h | 143 ++ .../mapviz_plugins/pointcloud2_plugin.h | 165 ++ .../include/mapviz_plugins/pose_plugin.h | 101 ++ .../mapviz_plugins/robot_image_plugin.h | 126 ++ .../include/mapviz_plugins/route_plugin.h | 120 ++ .../include/mapviz_plugins/string_plugin.h | 152 ++ .../mapviz_plugins/textured_marker_plugin.h | 145 ++ .../include/mapviz_plugins/tf_frame_plugin.h | 94 ++ mapviz_plugins/mainpage.dox | 23 + mapviz_plugins/mapviz_plugins.xml | 84 + mapviz_plugins/package.xml | 57 + .../src/attitude_indicator_plugin.cpp | 392 +++++ mapviz_plugins/src/canvas_click_filter.cpp | 83 + .../src/coordinate_picker_plugin.cpp | 306 ++++ mapviz_plugins/src/disparity_plugin.cpp | 781 +++++++++ mapviz_plugins/src/draw_polygon_plugin.cpp | 424 +++++ mapviz_plugins/src/float_plugin.cpp | 501 ++++++ mapviz_plugins/src/gps_plugin.cpp | 292 ++++ mapviz_plugins/src/grid_plugin.cpp | 376 +++++ mapviz_plugins/src/image_plugin.cpp | 611 +++++++ mapviz_plugins/src/laserscan_plugin.cpp | 687 ++++++++ mapviz_plugins/src/marker_plugin.cpp | 725 ++++++++ mapviz_plugins/src/measuring_plugin.cpp | 476 ++++++ mapviz_plugins/src/move_base_plugin.cpp | 380 +++++ mapviz_plugins/src/navsat_plugin.cpp | 246 +++ mapviz_plugins/src/occupancy_grid_plugin.cpp | 565 +++++++ mapviz_plugins/src/odometry_plugin.cpp | 407 +++++ mapviz_plugins/src/path_plugin.cpp | 211 +++ mapviz_plugins/src/placeable_window_proxy.cpp | 365 ++++ mapviz_plugins/src/plan_route_plugin.cpp | 497 ++++++ .../src/point_click_publisher_plugin.cpp | 254 +++ mapviz_plugins/src/point_drawing_plugin.cpp | 621 +++++++ mapviz_plugins/src/pointcloud2_plugin.cpp | 888 ++++++++++ mapviz_plugins/src/pose_plugin.cpp | 299 ++++ mapviz_plugins/src/robot_image_plugin.cpp | 452 +++++ mapviz_plugins/src/route_plugin.cpp | 423 +++++ mapviz_plugins/src/string_plugin.cpp | 435 +++++ mapviz_plugins/src/textured_marker_plugin.cpp | 522 ++++++ mapviz_plugins/src/tf_frame_plugin.cpp | 255 +++ .../ui/attitude_indicator_config.ui | 107 ++ mapviz_plugins/ui/coordinate_picker_config.ui | 119 ++ mapviz_plugins/ui/disparity_config.ui | 313 ++++ mapviz_plugins/ui/draw_polygon_config.ui | 152 ++ mapviz_plugins/ui/float_config.ui | 358 ++++ mapviz_plugins/ui/gps_config.ui | 330 ++++ mapviz_plugins/ui/grid_config.ui | 328 ++++ mapviz_plugins/ui/image_config.ui | 367 ++++ mapviz_plugins/ui/laserscan_config.ui | 376 +++++ mapviz_plugins/ui/marker_config.ui | 133 ++ mapviz_plugins/ui/measuring_config.ui | 269 +++ mapviz_plugins/ui/move_base_config.ui | 202 +++ mapviz_plugins/ui/navsat_config.ui | 282 ++++ mapviz_plugins/ui/occupancy_grid_config.ui | 181 ++ mapviz_plugins/ui/odometry_config.ui | 409 +++++ mapviz_plugins/ui/path_config.ui | 159 ++ mapviz_plugins/ui/plan_route_config.ui | 178 ++ .../ui/point_click_publisher_config.ui | 132 ++ mapviz_plugins/ui/pointcloud2_config.ui | 476 ++++++ mapviz_plugins/ui/pose_config.ui | 330 ++++ mapviz_plugins/ui/robot_image_config.ui | 315 ++++ mapviz_plugins/ui/route_config.ui | 296 ++++ mapviz_plugins/ui/string_config.ui | 339 ++++ mapviz_plugins/ui/textured_marker_config.ui | 162 ++ mapviz_plugins/ui/tf_frame_config.ui | 312 ++++ mapviz_plugins/ui/topic_select.ui | 74 + multires_image/CHANGELOG.rst | 129 ++ multires_image/CMakeLists.txt | 169 ++ .../include/multires_image/QGLMap.h | 110 ++ .../multires_image/multires_image_plugin.h | 113 ++ .../include/multires_image/multires_view.h | 68 + .../multires_image/multires_view_node.h | 84 + multires_image/include/multires_image/tile.h | 109 ++ .../include/multires_image/tile_cache.h | 128 ++ .../include/multires_image/tile_set.h | 78 + .../include/multires_image/tile_set_layer.h | 87 + .../include/multires_image/tile_view.h | 67 + .../launch/mapviz_tile_loader.launch | 31 + multires_image/launch/multires.launch | 7 + multires_image/mainpage.dox | 33 + multires_image/mapviz_plugins.xml | 6 + multires_image/nodes/mapviz_tile_loader | 204 +++ multires_image/package.xml | 41 + multires_image/src/QGLMap.cpp | 301 ++++ multires_image/src/QGLMap.ui | 32 + multires_image/src/multires_config.ui | 165 ++ multires_image/src/multires_image_plugin.cpp | 363 ++++ multires_image/src/multires_view.cpp | 199 +++ .../src/nodes/multires_view_node.cpp | 128 ++ multires_image/src/tile.cpp | 223 +++ multires_image/src/tile_cache.cpp | 396 +++++ multires_image/src/tile_set.cpp | 124 ++ multires_image/src/tile_set_layer.cpp | 197 +++ multires_image/src/tile_view.cpp | 175 ++ multires_image/test.geo | 13 + tile_map/CHANGELOG.rst | 154 ++ tile_map/CMakeLists.txt | 141 ++ tile_map/include/tile_map/bing_source.h | 141 ++ tile_map/include/tile_map/image_cache.h | 171 ++ tile_map/include/tile_map/texture_cache.h | 78 + tile_map/include/tile_map/tile_map_plugin.h | 126 ++ tile_map/include/tile_map/tile_map_view.h | 115 ++ tile_map/include/tile_map/tile_source.h | 122 ++ tile_map/include/tile_map/wmts_source.h | 86 + tile_map/mapviz_plugins.xml | 6 + tile_map/package.xml | 42 + tile_map/src/bing_source.cpp | 187 +++ tile_map/src/image_cache.cpp | 337 ++++ tile_map/src/texture_cache.cpp | 178 ++ tile_map/src/tile_map_config.ui | 198 +++ tile_map/src/tile_map_plugin.cpp | 469 ++++++ tile_map/src/tile_map_view.cpp | 325 ++++ tile_map/src/tile_source.cpp | 84 + tile_map/src/wmts_source.cpp | 71 + 233 files changed, 38957 insertions(+) create mode 100644 .editorconfig create mode 100755 .github/workflows/main.yml create mode 100755 .ros2_build.sh create mode 100644 .travis.yml create mode 100644 LICENSE create mode 100644 README.md create mode 100644 docs/Gemfile create mode 100644 docs/_config.yml create mode 100644 docs/_layouts/plugin.md create mode 100644 docs/_plugins/attitude_indicator.md create mode 100644 docs/_plugins/coordinate_picker.md create mode 100644 docs/_plugins/disparity.md create mode 100644 docs/_plugins/draw_polygon.md create mode 100644 docs/_plugins/float.md create mode 100644 docs/_plugins/gps.md create mode 100644 docs/_plugins/grid.md create mode 100644 docs/_plugins/image.md create mode 100644 docs/_plugins/laserscan.md create mode 100644 docs/_plugins/marker.md create mode 100644 docs/_plugins/measuring.md create mode 100644 docs/_plugins/move_base.md create mode 100644 docs/_plugins/multires_image.md create mode 100644 docs/_plugins/navsat.md create mode 100644 docs/_plugins/occupancy_grid.md create mode 100644 docs/_plugins/odometry.md create mode 100644 docs/_plugins/path.md create mode 100644 docs/_plugins/plan_route.md create mode 100644 docs/_plugins/point_click_publisher.md create mode 100644 docs/_plugins/point_drawing.md create mode 100644 docs/_plugins/pointcloud2.md create mode 100644 docs/_plugins/pose.md create mode 100644 docs/_plugins/robot_image.md create mode 100644 docs/_plugins/route.md create mode 100644 docs/_plugins/string.md create mode 100644 docs/_plugins/textured_marker.md create mode 100644 docs/_plugins/tf_frame.md create mode 100644 docs/_plugins/tile_map.md create mode 100644 docs/assets/images/disparity.png create mode 100644 docs/assets/images/mapviz.png create mode 100644 docs/assets/images/mapviz_features.png create mode 100644 docs/assets/images/multires.png create mode 100644 docs/assets/images/multires2.png create mode 100644 docs/assets/images/roads.png create mode 100644 docs/assets/images/satellite.png create mode 100644 docs/assets/images/screenshot_coordinate_picker.png create mode 100644 docs/assets/images/terrain.png create mode 100644 docs/assets/images/toner.png create mode 100644 docs/assets/images/watercolor.png create mode 100644 docs/assets/js/search-data.json create mode 100644 docs/index.md create mode 100644 docs/plugins.md create mode 100644 mapviz/CHANGELOG.rst create mode 100644 mapviz/CMakeLists.txt create mode 100644 mapviz/include/mapviz/color_button.h create mode 100644 mapviz/include/mapviz/config_item.h create mode 100644 mapviz/include/mapviz/map_canvas.h create mode 100644 mapviz/include/mapviz/mapviz.hpp create mode 100644 mapviz/include/mapviz/mapviz_application.h create mode 100644 mapviz/include/mapviz/mapviz_plugin.h create mode 100644 mapviz/include/mapviz/rqt_mapviz.h create mode 100644 mapviz/include/mapviz/select_frame_dialog.h create mode 100644 mapviz/include/mapviz/select_service_dialog.h create mode 100644 mapviz/include/mapviz/select_topic_dialog.h create mode 100644 mapviz/include/mapviz/stopwatch.h create mode 100644 mapviz/include/mapviz/video_writer.h create mode 100644 mapviz/include/mapviz/widgets.h create mode 100644 mapviz/launch/mapviz.launch.py create mode 100644 mapviz/launch/mapviz.launch.xml create mode 100644 mapviz/mainpage.dox create mode 100644 mapviz/package.xml create mode 100644 mapviz/plugin.xml create mode 100644 mapviz/src/color_button.cpp create mode 100644 mapviz/src/config_item.cpp create mode 100644 mapviz/src/configitem.ui create mode 100644 mapviz/src/map_canvas.cpp create mode 100644 mapviz/src/mapviz.cpp create mode 100644 mapviz/src/mapviz.ui create mode 100644 mapviz/src/mapviz_application.cpp create mode 100644 mapviz/src/mapviz_main.cpp create mode 100644 mapviz/src/pluginselect.ui create mode 100644 mapviz/src/resources/LICENSE create mode 100644 mapviz/src/resources/arrow_in.png create mode 100644 mapviz/src/resources/green-arrow.png create mode 100644 mapviz/src/resources/icons.qrc create mode 100644 mapviz/src/resources/image-x-generic.png create mode 100644 mapviz/src/resources/media-playback-pause.png create mode 100644 mapviz/src/resources/media-playback-stop.png create mode 100644 mapviz/src/resources/media-record.png create mode 100644 mapviz/src/resources/remove-icon-th.png create mode 100644 mapviz/src/rqt_mapviz.cpp create mode 100644 mapviz/src/select_frame_dialog.cpp create mode 100644 mapviz/src/select_service_dialog.cpp create mode 100644 mapviz/src/select_topic_dialog.cpp create mode 100644 mapviz/src/video_writer.cpp create mode 100644 mapviz_interfaces/CHANGELOG.rst create mode 100644 mapviz_interfaces/CMakeLists.txt create mode 100644 mapviz_interfaces/package.xml create mode 100644 mapviz_interfaces/srv/AddMapvizDisplay.srv create mode 100644 mapviz_plugins/CHANGELOG.rst create mode 100644 mapviz_plugins/CMakeLists.txt create mode 100644 mapviz_plugins/include/mapviz_plugins/attitude_indicator_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/canvas_click_filter.h create mode 100644 mapviz_plugins/include/mapviz_plugins/coordinate_picker_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/disparity_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/draw_polygon_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/float_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/gps_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/grid_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/image_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/laserscan_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/marker_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/measuring_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/move_base_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/navsat_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/occupancy_grid_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/odometry_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/path_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/placeable_window_proxy.h create mode 100644 mapviz_plugins/include/mapviz_plugins/plan_route_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/point_click_publisher_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/point_drawing_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/pointcloud2_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/pose_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/robot_image_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/route_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/string_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/textured_marker_plugin.h create mode 100644 mapviz_plugins/include/mapviz_plugins/tf_frame_plugin.h create mode 100644 mapviz_plugins/mainpage.dox create mode 100644 mapviz_plugins/mapviz_plugins.xml create mode 100644 mapviz_plugins/package.xml create mode 100644 mapviz_plugins/src/attitude_indicator_plugin.cpp create mode 100644 mapviz_plugins/src/canvas_click_filter.cpp create mode 100644 mapviz_plugins/src/coordinate_picker_plugin.cpp create mode 100644 mapviz_plugins/src/disparity_plugin.cpp create mode 100644 mapviz_plugins/src/draw_polygon_plugin.cpp create mode 100644 mapviz_plugins/src/float_plugin.cpp create mode 100644 mapviz_plugins/src/gps_plugin.cpp create mode 100644 mapviz_plugins/src/grid_plugin.cpp create mode 100644 mapviz_plugins/src/image_plugin.cpp create mode 100644 mapviz_plugins/src/laserscan_plugin.cpp create mode 100644 mapviz_plugins/src/marker_plugin.cpp create mode 100644 mapviz_plugins/src/measuring_plugin.cpp create mode 100644 mapviz_plugins/src/move_base_plugin.cpp create mode 100644 mapviz_plugins/src/navsat_plugin.cpp create mode 100644 mapviz_plugins/src/occupancy_grid_plugin.cpp create mode 100644 mapviz_plugins/src/odometry_plugin.cpp create mode 100644 mapviz_plugins/src/path_plugin.cpp create mode 100644 mapviz_plugins/src/placeable_window_proxy.cpp create mode 100644 mapviz_plugins/src/plan_route_plugin.cpp create mode 100644 mapviz_plugins/src/point_click_publisher_plugin.cpp create mode 100644 mapviz_plugins/src/point_drawing_plugin.cpp create mode 100644 mapviz_plugins/src/pointcloud2_plugin.cpp create mode 100644 mapviz_plugins/src/pose_plugin.cpp create mode 100644 mapviz_plugins/src/robot_image_plugin.cpp create mode 100644 mapviz_plugins/src/route_plugin.cpp create mode 100644 mapviz_plugins/src/string_plugin.cpp create mode 100755 mapviz_plugins/src/textured_marker_plugin.cpp create mode 100644 mapviz_plugins/src/tf_frame_plugin.cpp create mode 100644 mapviz_plugins/ui/attitude_indicator_config.ui create mode 100644 mapviz_plugins/ui/coordinate_picker_config.ui create mode 100644 mapviz_plugins/ui/disparity_config.ui create mode 100644 mapviz_plugins/ui/draw_polygon_config.ui create mode 100644 mapviz_plugins/ui/float_config.ui create mode 100644 mapviz_plugins/ui/gps_config.ui create mode 100644 mapviz_plugins/ui/grid_config.ui create mode 100644 mapviz_plugins/ui/image_config.ui create mode 100644 mapviz_plugins/ui/laserscan_config.ui create mode 100644 mapviz_plugins/ui/marker_config.ui create mode 100644 mapviz_plugins/ui/measuring_config.ui create mode 100644 mapviz_plugins/ui/move_base_config.ui create mode 100644 mapviz_plugins/ui/navsat_config.ui create mode 100644 mapviz_plugins/ui/occupancy_grid_config.ui create mode 100644 mapviz_plugins/ui/odometry_config.ui create mode 100644 mapviz_plugins/ui/path_config.ui create mode 100644 mapviz_plugins/ui/plan_route_config.ui create mode 100644 mapviz_plugins/ui/point_click_publisher_config.ui create mode 100644 mapviz_plugins/ui/pointcloud2_config.ui create mode 100644 mapviz_plugins/ui/pose_config.ui create mode 100644 mapviz_plugins/ui/robot_image_config.ui create mode 100644 mapviz_plugins/ui/route_config.ui create mode 100644 mapviz_plugins/ui/string_config.ui create mode 100644 mapviz_plugins/ui/textured_marker_config.ui create mode 100644 mapviz_plugins/ui/tf_frame_config.ui create mode 100644 mapviz_plugins/ui/topic_select.ui create mode 100644 multires_image/CHANGELOG.rst create mode 100644 multires_image/CMakeLists.txt create mode 100644 multires_image/include/multires_image/QGLMap.h create mode 100644 multires_image/include/multires_image/multires_image_plugin.h create mode 100644 multires_image/include/multires_image/multires_view.h create mode 100644 multires_image/include/multires_image/multires_view_node.h create mode 100644 multires_image/include/multires_image/tile.h create mode 100644 multires_image/include/multires_image/tile_cache.h create mode 100644 multires_image/include/multires_image/tile_set.h create mode 100644 multires_image/include/multires_image/tile_set_layer.h create mode 100644 multires_image/include/multires_image/tile_view.h create mode 100644 multires_image/launch/mapviz_tile_loader.launch create mode 100644 multires_image/launch/multires.launch create mode 100644 multires_image/mainpage.dox create mode 100644 multires_image/mapviz_plugins.xml create mode 100755 multires_image/nodes/mapviz_tile_loader create mode 100644 multires_image/package.xml create mode 100644 multires_image/src/QGLMap.cpp create mode 100644 multires_image/src/QGLMap.ui create mode 100644 multires_image/src/multires_config.ui create mode 100644 multires_image/src/multires_image_plugin.cpp create mode 100644 multires_image/src/multires_view.cpp create mode 100644 multires_image/src/nodes/multires_view_node.cpp create mode 100644 multires_image/src/tile.cpp create mode 100644 multires_image/src/tile_cache.cpp create mode 100644 multires_image/src/tile_set.cpp create mode 100644 multires_image/src/tile_set_layer.cpp create mode 100644 multires_image/src/tile_view.cpp create mode 100644 multires_image/test.geo create mode 100644 tile_map/CHANGELOG.rst create mode 100644 tile_map/CMakeLists.txt create mode 100644 tile_map/include/tile_map/bing_source.h create mode 100644 tile_map/include/tile_map/image_cache.h create mode 100644 tile_map/include/tile_map/texture_cache.h create mode 100644 tile_map/include/tile_map/tile_map_plugin.h create mode 100644 tile_map/include/tile_map/tile_map_view.h create mode 100644 tile_map/include/tile_map/tile_source.h create mode 100644 tile_map/include/tile_map/wmts_source.h create mode 100644 tile_map/mapviz_plugins.xml create mode 100644 tile_map/package.xml create mode 100644 tile_map/src/bing_source.cpp create mode 100644 tile_map/src/image_cache.cpp create mode 100644 tile_map/src/texture_cache.cpp create mode 100644 tile_map/src/tile_map_config.ui create mode 100644 tile_map/src/tile_map_plugin.cpp create mode 100644 tile_map/src/tile_map_view.cpp create mode 100644 tile_map/src/tile_source.cpp create mode 100644 tile_map/src/wmts_source.cpp diff --git a/.editorconfig b/.editorconfig new file mode 100644 index 000000000..c98ee52bb --- /dev/null +++ b/.editorconfig @@ -0,0 +1,17 @@ +# http://editorconfig.org +root = true + +[*] +indent_style = space +indent_size = 2 +charset = utf-8 +trim_trailing_whitespace = true +insert_final_newline = true +max_line_length = 100 + +# Use 4 spaces for the Python files +[*.py] +indent_size = 4 + +[*.md] +trim_trailing_whitespace = false diff --git a/.github/workflows/main.yml b/.github/workflows/main.yml new file mode 100755 index 000000000..e25864c0b --- /dev/null +++ b/.github/workflows/main.yml @@ -0,0 +1,20 @@ +name: CI + +on: [push, pull_request] + +jobs: + industrial_ci: + strategy: + matrix: + env: + - {ROS_DISTRO: humble, ROS_REPO: testing} + - {ROS_DISTRO: humble, ROS_REPO: main} + - {ROS_DISTRO: iron, ROS_REPO: testing} + - {ROS_DISTRO: iron, ROS_REPO: main} + - {ROS_DISTRO: rolling, ROS_REPO: testing} + - {ROS_DISTRO: rolling, ROS_REPO: main} + runs-on: ubuntu-latest + steps: + - uses: actions/checkout@v1 + - uses: 'ros-industrial/industrial_ci@master' + env: ${{matrix.env}} diff --git a/.ros2_build.sh b/.ros2_build.sh new file mode 100755 index 000000000..3ba41d07b --- /dev/null +++ b/.ros2_build.sh @@ -0,0 +1,15 @@ +#!/usr/bin/env bash + +# Enable the ros2-testing repository +sed 's#ros2#ros2-testing#' /etc/apt/sources.list.d/ros2-latest.list | tee >> /etc/apt/sources.list.d/ros2-latest.list + +# Install colcon, we need it and it's not installed by default +apt-get update +rosdep update +apt-get install -y build-essential python3-colcon-ros + +cd /ws + +# Use rosdep to install the rest of the package's dependencies, then build it +rosdep install src --from-paths -i -y +colcon build diff --git a/.travis.yml b/.travis.yml new file mode 100644 index 000000000..3131dcd3f --- /dev/null +++ b/.travis.yml @@ -0,0 +1,15 @@ +language: generic + +services: + - docker + +jobs: + include: + - stage: compile + name: 'ROS Dashing' + script: + - exec docker run -a STDOUT -a STDERR --rm -v $(pwd):/ws/src/mapviz ros:dashing /ws/src/mapviz/.ros2_build.sh + - stage: compile + name: 'ROS Eloquent' + script: + - exec docker run -a STDOUT -a STDERR --rm -v $(pwd):/ws/src/mapviz ros:eloquent /ws/src/mapviz/.ros2_build.sh diff --git a/LICENSE b/LICENSE new file mode 100644 index 000000000..602b49878 --- /dev/null +++ b/LICENSE @@ -0,0 +1,24 @@ +Copyright (c) 2014, Southwest Research Institute® (SwRI®) +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of Southwest Research Institute® (SwRI®) nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/README.md b/README.md new file mode 100644 index 000000000..ca297968f --- /dev/null +++ b/README.md @@ -0,0 +1,11 @@ +Mapviz [![Build Status](https://travis-ci.org/swri-robotics/mapviz.svg?branch=master)](https://travis-ci.org/swri-robotics/mapviz) +====== + +Mapviz is a [ROS](http://www.ros.org/) based visualization tool with a plug-in system similar to [RVIZ](http://wiki.ros.org/rviz) focused on visualizing 2D data. + +![](https://github.com/swri-robotics/mapviz/wiki/mapviz.png) + +Usage +----- + +[View the documentation](https://swri-robotics.github.io/mapviz/) for usage information. diff --git a/docs/Gemfile b/docs/Gemfile new file mode 100644 index 000000000..709bb019b --- /dev/null +++ b/docs/Gemfile @@ -0,0 +1,3 @@ +source 'https://rubygems.org' +gem 'github-pages', group: :jekyll_plugins +gem 'just-the-docs' diff --git a/docs/_config.yml b/docs/_config.yml new file mode 100644 index 000000000..a20d390a7 --- /dev/null +++ b/docs/_config.yml @@ -0,0 +1,60 @@ +title: "Mapviz" +description: Modular ROS visualization tool for 2D data +baseurl: "/mapviz" # the subpath of your site, e.g. /blog +url: "https://swri-robotics.github.io" # the base hostname & protocol for your site, e.g. http://example.com +remote_theme: pmarsceill/just-the-docs + +permalink: /:title/ +exclude: ["node_modules/", "*.gemspec", "*.gem", "Gemfile", "Gemfile.lock", "package.json", "package-lock.json", "script/", "LICENSE.txt", "lib/", "bin/", "README.md", "Rakefile"] + +# Set a path/url to a logo that will be displayed instead of the title +#logo: "/assets/images/just-the-docs.png" + +# Enable or disable the site search +search_enabled: true + +# Set the search token separator for hyphenated-word search: +search_tokenizer_separator: /[\s/]+/ + +# Enable or disable heading anchors +heading_anchors: true + +# Aux links for the upper right navigation +aux_links: + "Mapviz on GitHub": + - "//github.com/swri-robotics/mapviz" + +# Footer content appears at the bottom of every page's main content +footer_content: "Copyright © 2020 Southwest Research Institute. Distributed under the BSD 3-Clause license." + +# Color scheme currently only supports "dark" or nil (default) +color_scheme: nil + +# Google Analytics Tracking (optional) +# e.g, UA-1234567-89 +# ga_tracking: + +plugins: + - jekyll-seo-tag + +collections: + plugins: + output: true + +defaults: + - scope: + path: '' + type: 'plugins' + values: + layout: 'plugin' + parent: 'Plugins' + +compress_html: + clippings: all + comments: all + endings: all + startings: [] + blanklines: false + profile: false + +theme: jekyll-theme-cayman \ No newline at end of file diff --git a/docs/_layouts/plugin.md b/docs/_layouts/plugin.md new file mode 100644 index 000000000..8ab648287 --- /dev/null +++ b/docs/_layouts/plugin.md @@ -0,0 +1,27 @@ +--- +layout: default +--- + +{% capture content %} + +# {{ page.title }} + +{{ page.description }} + +{% if page.image and page.image != "" %} +![]({{ site.baseurl | append: '/assets/images/' }}{{ page.image }}) +{% endif %} + +## Parameters + +{% if page.parameters %} + {% for param in page.parameters %} +| {{ param.name }} | {{ param.description | replace: "|","/"}} | + {%- endfor -%} +{% else %} + No parameters. +{% endif %} + +{% endcapture %} + +{{ content | markdownify }} diff --git a/docs/_plugins/attitude_indicator.md b/docs/_plugins/attitude_indicator.md new file mode 100644 index 000000000..f692780fa --- /dev/null +++ b/docs/_plugins/attitude_indicator.md @@ -0,0 +1,6 @@ +--- +title: "Attitude Indicator" +description: "" +image: "" +parameters: +--- diff --git a/docs/_plugins/coordinate_picker.md b/docs/_plugins/coordinate_picker.md new file mode 100644 index 000000000..62972fa2c --- /dev/null +++ b/docs/_plugins/coordinate_picker.md @@ -0,0 +1,8 @@ +--- +title: "Coordinate Picker" +description: "Transforms coordinates of clicked points on the map to a specified frame. The most recent coordinate is placed on the clipboard, and a list of coordinates is displayed in the GUI." +image: "screenshot_coordinate_picker.png" +parameters: + - name: frame + description: "Coordinate frame into which to transform the clicked point" +--- diff --git a/docs/_plugins/disparity.md b/docs/_plugins/disparity.md new file mode 100644 index 000000000..bdbfda3bc --- /dev/null +++ b/docs/_plugins/disparity.md @@ -0,0 +1,20 @@ +--- +title: "Disparity" +description: "Overlays a [sensor_msgs::DisparityImage](http://docs.ros.org/api/stereo_msgs/html/msg/DisparityImage.html) onto the display using the ''jet'' color map." +image: "disparity.png" +parameters: + - name: Topic + description: The disparity topic name + - name: Anchor + description: (top left | top center | top right | center left | center | center right | bottom left | bottom center | bottom right) + - name: Offset X + description: Display offset from the left + - name: Offset Y + description: Display offset from the top + - name: Width + description: Display width + - name: Height + description: Display height + - name: Units + description: (pixels | percent of window) +--- diff --git a/docs/_plugins/draw_polygon.md b/docs/_plugins/draw_polygon.md new file mode 100644 index 000000000..e5e9ba18c --- /dev/null +++ b/docs/_plugins/draw_polygon.md @@ -0,0 +1,6 @@ +--- +title: "Draw Polygon" +description: "Draw a polygon on the canvas and publish to a topic." +image: "" +parameters: +--- diff --git a/docs/_plugins/float.md b/docs/_plugins/float.md new file mode 100644 index 000000000..29e0b483d --- /dev/null +++ b/docs/_plugins/float.md @@ -0,0 +1,22 @@ +--- +title: "Float" +description: "Displays the most recent value from a `std_msgs::Float32/64, marti_common_msgs/Float32/64Stamped` or a `marti_sensor_msgs/Velocity` message at a fixed location on the scene." +image: "" +parameters: + - name: "Topic" + description: "The float topic" + - name: "Font" + description: "The font for rendering the float" + - name: "Color" + description: "The color for drawing the float" + - name: "Anchor" + description: "(top left | top center | top right | center left | center | center right | bottom left | bottom center | bottom right)" + - name: "Offset X" + description: "Horizontal offset from the anchor" + - name: "Offset Y" + description: "Vertical offset from the anchor" + - name: "Units" + description: "(pixels | percent of window)" + - name: "Postfix" + description: "Text to append to the displayed value (ex. to show units)" +--- diff --git a/docs/_plugins/gps.md b/docs/_plugins/gps.md new file mode 100644 index 000000000..108557352 --- /dev/null +++ b/docs/_plugins/gps.md @@ -0,0 +1,20 @@ +--- +title: "GPS" +description: "Projects [gps_common::GPSFix](http://docs.ros.org/kinetic/api/gps_common/html/msg/GPSFix.html) message data into the scene." +image: "" +parameters: + - name: Topic + description: The GPS topic + - name: Color + description: The color of the GPS data + - name: Draw Style + description: (lines | points | arrows) + - name: Static Arrow Sizes + description: If checked, draw arrows the same size regardless of zoom level; slider adjusts size + - name: Position Tolerance + description: Distance threshold for adding new GPS points to visualization + - name: Buffer Size + description: Size of circular buffer of GPS points + - name: Show Laps + description: If checked, multiple loops of GPS coordinates will have different colors +--- diff --git a/docs/_plugins/grid.md b/docs/_plugins/grid.md new file mode 100644 index 000000000..c77a0f042 --- /dev/null +++ b/docs/_plugins/grid.md @@ -0,0 +1,22 @@ +--- +title: "Grid" +description: "Projects a 2D grid into the scene." +image: "" +parameters: + - name: Frame + description: Coordinate frame of the grid + - name: Color + description: Color of the grid + - name: Alpha + description: Alpha transparency of the grid + - name: X + description: X offset of the grid from the specified coordinate frame origin + - name: Y + description: Y offset of the grid from the specified coordinate frame origin + - name: Size + description: Size of each grid cell + - name: Rows + description: Number of grid rows + - name: Columns + description: Number of grid columns +--- diff --git a/docs/_plugins/image.md b/docs/_plugins/image.md new file mode 100644 index 000000000..9d13b841b --- /dev/null +++ b/docs/_plugins/image.md @@ -0,0 +1,20 @@ +--- +title: "Image" +description: "Overlays a [sensor_msgs::Image](http://docs.ros.org/api/sensor_msgs/html/msg/Image.html) onto the display." +image: "" +parameters: + - name: Topic + description: The image topic name + - name: Anchor + description: (top left | top center | top right | center left | center | center right | bottom left | bottom center | bottom right) + - name: Offset X + description: Display offset from the left + - name: Offset Y + description: Display offset from the top + - name: Width + description: Display width + - name: Height + description: Display height + - name: Units + description: (pixels | percent of window) +--- diff --git a/docs/_plugins/laserscan.md b/docs/_plugins/laserscan.md new file mode 100644 index 000000000..ce6f448c1 --- /dev/null +++ b/docs/_plugins/laserscan.md @@ -0,0 +1,20 @@ +--- +title: "LaserScan" +description: "Projects a [sensor_msgs::LaserScan](http://docs.ros.org/api/sensor_msgs/html/msg/LaserScan.html) message into the scene." +image: "" +parameters: + - name: "Topic" + description: "The laser scan topic name" + - name: "Min Color" + description: "The color associated with minimum return intensity" + - name: "Max Color" + description: "The color associated with maximum return intensity" + - name: "Min Intesity" + description: "Minimum intensity value" + - name: "Max Intensity" + description: "Maximum intensity value" + - name: "Point Size" + description: "Display size of laser scan points in pixels" + - name: "Buffer Size" + description: "Size of circular buffer of laser scan messages points" +--- diff --git a/docs/_plugins/marker.md b/docs/_plugins/marker.md new file mode 100644 index 000000000..d680b3530 --- /dev/null +++ b/docs/_plugins/marker.md @@ -0,0 +1,10 @@ +--- +title: "Marker" +description: "Projects a [visualization_msgs::Marker](http://docs.ros.org/api/visualization_msgs/html/msg/Marker.html) or [visualization_msgs::MarkerArray](http://docs.ros.org/api/visualization_msgs/html/msg/MarkerArray.html) into the scene. + +[Markers](http://wiki.ros.org/rviz/DisplayTypes/Marker) are the most flexible display type and more or less mirror the [OpenGL primitives](https://www.opengl.org/wiki/Primitive)." +image: "" +parameters: + - name: "Topic" + description: "The marker topic" +--- diff --git a/docs/_plugins/measuring.md b/docs/_plugins/measuring.md new file mode 100644 index 000000000..56714f464 --- /dev/null +++ b/docs/_plugins/measuring.md @@ -0,0 +1,6 @@ +--- +title: "Measuring" +description: "Measure distance on the canvas with the mouse." +image: "" +parameters: +--- diff --git a/docs/_plugins/move_base.md b/docs/_plugins/move_base.md new file mode 100644 index 000000000..1ee62a8ec --- /dev/null +++ b/docs/_plugins/move_base.md @@ -0,0 +1,6 @@ +--- +title: "Move Base" +description: "Allows the user to send goals to [move_base](wiki.ros.org/move_base)." +image: "" +parameters: +--- diff --git a/docs/_plugins/multires_image.md b/docs/_plugins/multires_image.md new file mode 100644 index 000000000..daba699fe --- /dev/null +++ b/docs/_plugins/multires_image.md @@ -0,0 +1,8 @@ +--- +title: "Multi-Res Image" +description: "Projects a geo-referenced multi-resolution image tile map into the scene. The concept is the same as the Google Maps style pan/zoom satellite imagery." +image: "multires2.png" +parameters: + - name: "Geo File" + description: "Path to the geo-referenced map tiles." +--- diff --git a/docs/_plugins/navsat.md b/docs/_plugins/navsat.md new file mode 100644 index 000000000..0d5eb3f99 --- /dev/null +++ b/docs/_plugins/navsat.md @@ -0,0 +1,16 @@ +--- +title: "NavSat" +description: "Projects [sensor_msgs::NavSatFix](https://docs.ros.org/jade/api/sensor_msgs/html/msg/NavSatFix.html) message data into the scene." +image: "" +parameters: + - name: "Topic" + description: "The GPS topic" + - name: "Color" + description: "The color of the GPS data" + - name: "Draw Style" + description: "(lines | points)" + - name: "Position Tolerance" + description: "Distance threshold for adding new GPS points to visualization" + - name: "Buffer Size" + description: "Size of circular buffer of GPS points" +--- diff --git a/docs/_plugins/occupancy_grid.md b/docs/_plugins/occupancy_grid.md new file mode 100644 index 000000000..9a2b0b3ba --- /dev/null +++ b/docs/_plugins/occupancy_grid.md @@ -0,0 +1,6 @@ +--- +title: "Occupancy Grid" +description: "" +image: "" +parameters: +--- diff --git a/docs/_plugins/odometry.md b/docs/_plugins/odometry.md new file mode 100644 index 000000000..fd2937e75 --- /dev/null +++ b/docs/_plugins/odometry.md @@ -0,0 +1,18 @@ +--- +title: "Odometry" +description: "Projects [nav_msgs::Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) message data into the scene." +image: "" +parameters: + - name: "Topic" + description: "The odometry topic" + - name: "Color" + description: "The color of the odometry data" + - name: "Draw Style" + description: "(lines | points | arrows)" + - name: "Show Covariance" + description: "Draw covariance ellipse around latest data" + - name: "Position Tolerance" + description: "Distance threshold for adding new odometry points to visualization" + - name: "Buffer Size" + description: "Size of circular buffer of odometry points" +--- diff --git a/docs/_plugins/path.md b/docs/_plugins/path.md new file mode 100644 index 000000000..2667def29 --- /dev/null +++ b/docs/_plugins/path.md @@ -0,0 +1,8 @@ +--- +title: "Path" +description: "Projects [nav_msgs::Path](http://docs.ros.org/api/nav_msgs/html/msg/Path.html) message data into the scene." +image: "" +parameters: + - name: "Topic" + description: "The path topic" +--- diff --git a/docs/_plugins/plan_route.md b/docs/_plugins/plan_route.md new file mode 100644 index 000000000..58b929d45 --- /dev/null +++ b/docs/_plugins/plan_route.md @@ -0,0 +1,6 @@ +--- +title: "Plan Route" +description: "" +image: "" +parameters: +--- diff --git a/docs/_plugins/point_click_publisher.md b/docs/_plugins/point_click_publisher.md new file mode 100644 index 000000000..9398787d1 --- /dev/null +++ b/docs/_plugins/point_click_publisher.md @@ -0,0 +1,10 @@ +--- +title: "Point Click Publisher" +description: "Publishes a [geometry_msgs::PointStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PointStamped.html) message every time a user clicks on the map frame that corresponds to the clicked location." +image: "" +parameters: + - name: "Topic" + description: "The topic to publish the point to" + - name: "Frame" + description: "The target frame to transform the point to before publishing it" +--- diff --git a/docs/_plugins/point_drawing.md b/docs/_plugins/point_drawing.md new file mode 100644 index 000000000..9d49410ce --- /dev/null +++ b/docs/_plugins/point_drawing.md @@ -0,0 +1,6 @@ +--- +title: "Point Drawing" +description: "" +image: "" +parameters: +--- diff --git a/docs/_plugins/pointcloud2.md b/docs/_plugins/pointcloud2.md new file mode 100644 index 000000000..1e3e431db --- /dev/null +++ b/docs/_plugins/pointcloud2.md @@ -0,0 +1,6 @@ +--- +title: "Pointcloud2" +description: "" +image: "" +parameters: +--- diff --git a/docs/_plugins/pose.md b/docs/_plugins/pose.md new file mode 100644 index 000000000..fe51cc22d --- /dev/null +++ b/docs/_plugins/pose.md @@ -0,0 +1,6 @@ +--- +title: "Pose" +description: "" +image: "" +parameters: +--- diff --git a/docs/_plugins/robot_image.md b/docs/_plugins/robot_image.md new file mode 100644 index 000000000..705ca6172 --- /dev/null +++ b/docs/_plugins/robot_image.md @@ -0,0 +1,14 @@ +--- +title: "Robot Image" +description: "Projects an image loaded from file into the scene to represent the robot platform." +image: "" +parameters: + - name: "Image File" + description: " Path to the image file" + - name: "Frame" + description: "Frame to tie the image to" + - name: "Width" + description: "The physical width represented by the image" + - name: "Height" + description: "The physical height represented by the image" +--- diff --git a/docs/_plugins/route.md b/docs/_plugins/route.md new file mode 100644 index 000000000..d90101a7b --- /dev/null +++ b/docs/_plugins/route.md @@ -0,0 +1,6 @@ +--- +title: "Route" +description: "" +image: "" +parameters: +--- diff --git a/docs/_plugins/string.md b/docs/_plugins/string.md new file mode 100644 index 000000000..da91b5298 --- /dev/null +++ b/docs/_plugins/string.md @@ -0,0 +1,20 @@ +--- +title: "String" +description: "Displays the most recent string from a `std_msgs::String` message at a fixed location on the scene." +image: "" +parameters: + - name: "Topic" + description: "The string topic" + - name: "Font" + description: "The font for rendering the string" + - name: "Color" + description: "The color for drawing the string" + - name: "Anchor" + description: "(top left | top center | top right | center left | center | center right | bottom left | bottom center | bottom right)" + - name: "Offset X" + description: "Horizontal offset from the anchor" + - name: "Offset Y" + description: "Vertical offset from the anchor" + - name: "Units" + description: "(pixels | percent of window)" +--- diff --git a/docs/_plugins/textured_marker.md b/docs/_plugins/textured_marker.md new file mode 100644 index 000000000..d25a76caf --- /dev/null +++ b/docs/_plugins/textured_marker.md @@ -0,0 +1,10 @@ +--- +title: "Textured Marker" +description: "Projects `marti_visualization_msgs::TexturedMarker` and `marti_visualization_msgs::TexturedMarkerArray` message data into the scene. + +Textured markers follow the same general approach as traditional markers, but can be used to texture dense image data onto a quad which is projected into the scene." +image: "" +parameters: + - name: "Topic" + description: "The textured marker topic" +--- diff --git a/docs/_plugins/tf_frame.md b/docs/_plugins/tf_frame.md new file mode 100644 index 000000000..6a6c989aa --- /dev/null +++ b/docs/_plugins/tf_frame.md @@ -0,0 +1,16 @@ +--- +title: "TF Frame" +description: "Projects [Tf](http://wiki.ros.org/tf) data into the scene similar to the Odometry plug-in." +image: "" +parameters: + - name: "Frame" + description: "The Tf frame" + - name: "Color" + description: "The color of the Tf data" + - name: "Draw Style" + description: "(lines | points | arrows)" + - name: "Position Tolerance" + description: "Distance threshold for adding new Tf points to visualization" + - name: "Buffer Size" + description: "Size of circular buffer of Tf points" +--- diff --git a/docs/_plugins/tile_map.md b/docs/_plugins/tile_map.md new file mode 100644 index 000000000..ff2394848 --- /dev/null +++ b/docs/_plugins/tile_map.md @@ -0,0 +1,14 @@ +--- +title: "Tile Map" +description: "Projects a geo-referenced multi-resolution image tile map into the scene. Map tiles can be obtained from [Bing Maps](https://www.bing.com/mapspreview) or any [WMTS Tile Service](http://www.opengeospatial.org/standards/wmts). Pre-defined services that access [Stamen Design](http://maps.stamen.com/) (terrain, watercolor, and toner) are provided. Custom or local WMTS map servers can also be specified. Map data is cached to disk which enables some limited use completely offline." +image: "satellite.png" +parameters: + - name: "Source" + description: "The name of source of the tile data." + - name: "Base URL" + description: "A template URL used to obtain map tiles. When obtaining map tiles, parameters labeled `{level}`, `{x}`, and `{y}` in the URL will be replaced with appropriate values. For example, `http://tile.stamen.com/terrain/{level}/{x}/{y}.png` is appropriate for retrieving terrain tiles from Stamen Design." + - name: "API Key" + description: "When the `Bing Maps (terrain)` source is selected, you must enter a Bing Maps access key here and click the `Save` button in order for tiles to be available. You can get a Bing Maps Key from the [Microsoft Developer Network](https://msdn.microsoft.com/en-us/library/ff428642.aspx)." + - name: "Max Zoom" + description: "The maximum zoom level that will be used when requesting tiles." +--- diff --git a/docs/assets/images/disparity.png b/docs/assets/images/disparity.png new file mode 100644 index 0000000000000000000000000000000000000000..c526b89fc3e4c5c8446e5064ad8cf12af542852c GIT binary patch literal 68355 zcma%iRZv__xb2?72Pb$S5ZqmYPaqK7Wsu+!oZ!wt0{pnU2Y2`27TjGE+}-Ww)UES& zAMQhU@7`VgRqd|cU#(ufR*16VXG{nw1ONa`8R<`|004sidp<)2|Eph=n1uf|AScz& z;y}e1+5W!{nuD~q69AyU`JVy;Qqzh5y+m=AQIJGgLnp;0$12WSlmP%rK<3j&b@!#C zHZKR=c@Opn-ADi1FyMVOL6gd@Io2Z7n+ z6nS&U@ncJ+oe^herMSbibQ zZk$%d_<(>KQxU4=kYRgaQWEf-zSrrs?)u@aPnh@XKB~Ii&Ulb;3KVJ)RA%NyMLsk zMDK|Yh}UX{z@hJP2tVg7B#U>=+@V1W^mB`~g9>tmvMifc7soK?e|#o0lb)yt<{Ge# z9YaKvR+v1wzgg4SWsq56huchvssI@(sFB1+zrnI3JwN^htA7j)hqb&L=e_z(A$pge z|((mwi@&BO?+z4!HUkwF8hi zUM)>MicXwkz z0#cps2X~WquozSdUo>KYQzNU3i6yct$jX<`_kLQdy??`RMOt#*h7(X)*I)N4u66y+3I_Gk$!s&wX9l_} z@*Qk*{kjf*gPTszCU(X)7X42a(bmN$B;eeYH+Y@vB;IGt_L|r=#T0#cQxkGK!8{7m zsHPCr8VUfMkQkv44uMubz<|Xn!}ER6r_Ye`=ed+P`7hYj_j?iMa$V|-9uQ@)?0i2X zxbTbaBa!|2O=V=mSY(5ypEy7(JXUT8#gIkjn7rc1R(81mVB)|4;2AA%?X%jwa=}Rr zsBkMnQ2I&s%^^3c)3yq@sM_b;KRVcpPZWK;xP=zB{tiZk4z_LD7_ z_R+*!L4Yb7V9D;xf_+sAekA%l=d%&@N%6&zi0eN|8=Ui56h)uBc}I^}K=Ag<$%>mc zzPro@C_HmW&$M{?VsQ7VMHWu>#7kj;t911_>;mCr0Y^x?XDUmJm9 z&G!z!n?8=%HWqapZ1xODNWTCNAYA^y-#CfYF71f&>HT&9_I*Y(T%Fp{%Fnt)o`3B1~MRklo^~6LkB2|EE`*% z0x^$Muzg=!UBryhL^M{44~X#rT!%!>y3TWh^=o>i@u%LbFB=-$Z&1$MH-GgG!Dk51 zpQXSsoV(4}B`=pH2@g05DviI-Rb!A?Od%uWN$h!}amLX>j?C~ z4)2}r+alaA_#8e+DUnlp*gawmMwCHP>HhP#m(IglawO|J~Zx|`SUK! zA%^w=2~O){6yu8n{yC0fzoHj_TMu5WUi==T)Qc zeTeXIOk8VtqH%+buI36uZoYeNRvpnBG$c6VjC6D?l3!1O?Cp zNP*4n2HF#!@As$MBYSF(gS!F3@9&h?m6-i}Is&nL#5iNo&o!Ft!calxA9H_7WY z_jg~t@rs#`V#7J&iG!DtDr!Lw=Yqx$B?@z!V#*UEp! zSrM%cx)QlD0ftEawM%QjkasWSF0r{*cYL1q%S&K?D=*vf`ugj)h4JaN;uPec@UNLf z=*oN77yXHnfY?(SyYp%0%Lm@7*_cg_KqTC-mQb|S=g#K-hTr5EMU9;IMafbB0cvAP z-}3TmU}Y7wtOB1PXj0OLjo#JD(~h_``AABt%F`T8+p$H(#{> zp_jqJk%otrwMyg~naljfhF~^+DGUB1&y5uXC9F`YMlvU|r(89)Q`?^!AIrp-woWrE zmbII>4DI*E_?^*#D?XcrK}2MHg+F1IeB?VfPe#N)R&P3I<|MSHji_i$2|Wl&;w235 zk-tld|=PIoU4PKCq)0?1e!COkDNMqGYoWl5Ze-;HazSyc(v7;1Dg zmlQAzqYJ?Zl3efS5xs7Fzh_YxcS~S&n&z7BF*G*6I!Y8i%o%vafdVCi#8Ge{`u-og zks<9BtPLN=W^Ka^Uh^d;!H6!)su3cC*nUCvtdo7UIxCUNRkyyIJDkU`NjvTx+yDa@ z>ddSONmb&hnw;v;o`T+eUaX8o;}~|m5-6mJR~ypm|00z-vG$My@O_6bi>0Zj?{ z*Xv<|DDa*B=FWSV0vkRM%r7J|sB=2x*z0mOY{649HkVD;&F9G3l0E<@|}i(V*e_KBDI z&W?XM{3}e)`Jo%jX@S$$EZdSJdreA`H;<61@mgQ|tZ&Mkj!psM%=Ej|_09h@kYp ztWzryhX*K6yxzoBx*d0*ZuH9Cl7Dy_BM(o+k^#8he>CA;OvM0f6l_N6%um91Xt{FP zIapED;g&1*8{sxoKoI>+L7Fn`0?kC!XaX#m0Cihz?e9mp%rHo;^j=)&y`1g1YwdWx zp~#lE{d&bdQi*AxQ9*<~-``XJQc%@sjakf0@>fgTQ>P{dp!AF!%T#@g{N$b+3&CX^ zmt?>2SHmKp11Ca1gWxhjqxfYV>^3FZ+=iTk;Hd(H5L4;XuPtZ;xz}(SA{^m9>#Jn- z|9l=>>u-HU{(No8VG>p5=ZjuI$E^a`5aq9NK-6_#Dj12pjL)gx-_uHXLMjUO>Eb`= z>dzB6d`?dqjtAX$2ClUV#YGLGAXj-f<<(vuL`G_B7`eJ3>owSHScy0TUj$r!8{vZD4j~i~(6n7Ws((1p0cEzu}XgIYds? z` z*S}6gY|q9d6z%%R&y4X;0kXC6W=sCJupL8dt1SQIWL0eu1;np+tf?5$`IlU|1-GIZ zqqJlxKf=Tf3RLlOMeLWOd4;sT{LOkc5G|o1nA=XAa94VvvyMSAGOU{Z1jnI#id4k? z`fS&y=Ov*^KhA(R+yzIpmlQEXg29nO;Q_CX+mbgYDP`Q>t*AOH5StRHU-^LfSgL=g7L8~ma!ZKjZ(&-K`OgPU{& zc!7}tIUG3urS@S#W3pxCxhTu!zka2J#~LV~h&kT-`IJXOm2;-M)nho7+{-*3bL5sO ze&un80xQRX`DkHG#ph@@glqVTS{(%?c&PFFAbCt!y03N*^zo1NYI;vSE&9FnL*aXH z3*;k~u*S(6Q}@<40%eUobz%*M`j?r6&0kE6w$BthrS>|`cSI~u%uX`j-PaY6U*jBFRTj1BUi;;N>36h)`4K27=JTmrSc3_HuYP>DEG#Hwq~aB?(QYFZ zy+?h&#*Fbg?zRqJFII!mC<(6!BvQfpue09JynLk2uYn}^Kj7;V?+Xh)LK6b`oHW_~ z!T+NRL=X&eCRK2agETQyTSrzj*zdCKuL0L5T@mG5Se4F9zhQkXRQyF{f3Pe3rBTQ2i~M2tu9f+iyDDz&YMPsSoD=ofYSb4b4xg4WLp7F@ zpQXIhk9YalB&N6i=&jg#|HuUEHfG?Rh@{sEPTJO_}00VNYRwvx)(6N4S z(V=l6in`9wTCrzZO;^^X^S7IVw{}BfZM*Kzp>C7pe?bKM1+)X7{R@-|vO8LxTD%78 z8bz^?qk$Z&-y@mR$Q5>Rk#%ik0&qGkxQt@kVX6`VW`v+n0G-Xk zyxt+rp=M|CE}>^UBsc1-OparJ9X3U#*0!E{+m0co3=v$v*RLT&hUZrH&3hNSSILfE zmF|Lw_P3bpM`BlEw=Xx`^bh)T2*QSNt`)wkeUQW8fD`@eky50K9a=2-E*7C+eu9M>oThu{-wdBMluc-TL_)GYkeOnRq zUGX?ib~^vrrP7GufG^Ct+FHQJ`#tdAFPp} z7nJ3lY?o@)^1IO)w>1uoIkv!@c%OLH^mjzozO-@I2i9SM$yLIsZ|_UMrox_v$S)_-PPM34o`>k3 zO__J19}tm!Pr<+3K5SG_mk;NXtaUHzT)*_NsgY-;6RLqgo!!b~2h*UMwQuyOu6K)> z)P$Uc1qFQ}L?$BZB|^7tw2Y;RrGXzvZiHRAaCjYK2x@MdY`x&ng4F6zD->4 zj#wQ&6<+U#g7Fo;YafOJV=oRuf&Kw~C=d*L%SxMwDGhOAQg0LgBqESpf`S6$@43&C z8TnUn2Jd)_pn_%Ksm#J3?$Anct;KV68Cr)aampnjYYk$MBy(a#>f3LRCQIu9g{+9O z!!OpGO2t*81UvPvNTHvAnoDM5rffQdnSKHumzpN`bplXkX-=t-J3fzZ3%p?k$5JE znc%C<)QMfIz^sjgSO2k+BE|=1bY*GosFz#r*DDG!6o*?epMHdy=#yKc?9$5s7d4kUF>Eiec(WrSWoogZO%` zd`L41Vt;r_KVItX45W<ye-9pNdQOg+ z0Ec_@iiR|IO!_M?XkA!RIRr`B;ivDo1bX8rJI=I~v9M&xySM(m+0qVi4nadjRP;Fd z9AJpD(|*)$t>2xeuNd_+Kf#g2DTS%JIe91l4iQXNnFqwUo5u4|Sngpi1& z-v-w&MQf-s3}xX&46t2u@}69CZtc`~Kt6-x0o(jLy*5z&ZSFv$5ZV1-%FIjrOGmKo zKUvHTxnddtR1D22t$if_@j1Oy2Md#8X&8=^-vCN}SliMr|AUqy`(=L`gIYp#Z0lg+ zD*~Wb$G^@7C-}(fhAPplM2x_I=s3!E7_2>3a23M-G(oxVvYmaG_!R5Y&!yZ`r})$= zedtGF+uUSp7p6buCmR5xC|=M}Xh+~ZQGA0W*A=szlOwwr`;+)}8SmBij|~$6!;;Q* zgXVK2z4dc2`I^s;$Y(1#f6m|dWcGg;uGYrFhYeO9XGt=Ut}{|jDubj2_(-vJ@M;s& z^nIR^1>9u^pkOEzWOmuL{YhDg(nU;@Ni1DNyD8`9H<#dWedy0*-i4L@gTF74^tNf( z)@3ruBJyk{c%27~FyWdts_}H5ub>0H@cVmyOfyZ*Oz5Ptc#f8lilLg}Zgn@cc}=hI zi^o5*0b7}v0a>oPK*LHzdBO98nPaJ&CT`ueLziEbgPirEa!DLxA4nU~S~xdyZnNU1|?kMi&m8q_qD4Ri`(xGbX`faC=89<^`&E&14 zYsch~Q4x)%O^J`v7oORDi!r_hkzzN4m4{|(BE9mI=9tu-HFv?EX~Notj20SZ<1ba4 zJsC!dN}!f~Wpl?WsW3Ex*z`e_-?aaDJj~_CO18-V`e<0`ildc}%jX|@>?!I6_(S?= zOdQJWU_?r%P0pU5k=hV{(~fEyC@y=l31`tOw>@Hr7+7FN%JU5=VxGm|B13&+!10VE zmp`C+8~;#$^6&~l1a}VUNVj7)$@U61IsxTq2FMm%(>ao9uJ*=eK#Nua)1)aQeXsng ziM-mT0x?Ug{3`@U&zYBhH;L?TdBcUx!l^vck2`70W}2#7rWY7eY}g=urf2a*y;`f{ z*v#lzwvIfNL9H}AHE_IL%$jwWWJ!s}4dTO4WTdJ!!M@uuUq5VgaA$F=x+Aw??!4gu5$i@xP(? zLhOA~eFfuRmM@qtG8ISgilO)^qkSK0bwO1e+xbj!a`7xsIR!TI#wF{YfB4b2zoN&b zsO9c5TKu(Mp4I!LAg=;u+Gb$nt;|D={}>4cobiQ`wCt>87@UnG3n$(v$Lm-zAadD9 zi`WhW@{0Mcwa(YO7f;K^SHjFYALbKVwPCkG9u}G0a0Gelup8o$loezdo8fq_7EU31 zLObIy?X+;KkH3Sb5v}lArxref+GG}m4RUPq3@3)PP=M$P7&`ftpLd2L7X$mE1^ zs$PoWqfmWjvv8Sm>81L?vaM6rhG(&B5;dQd#tMIX4M$v=OC!8E$pQ1W$u`f9U;3ni z)xlr`@4ptu+jKRjSzoXJLXglo5E=Tni<6Rm_Gp8BkD8X=v+8U%Gyf6R z5cVJtmuviYBNG@em7PaTE2=K|^UYMMT!^tABz@!H7N_*K!l>zUDjCNKE7H%|k`QKi zz<<8=IVnf-d1gmUC;()a^-yMrp1bm#22b!d)P2W#N&m7mk zp*U=eB)xuKKLr+RkQC*D+Q7iKu@VV3>xjyxtHadE z%;OHx*G_hQRsxS%{)p&k9lJNffb&b8rp2)CbAx&|-~h-VnZp0wVa7&(6*in)JPWfA zyZ@lI?z5T;7v7|*GkCSyQqX4U8Y%-5vv|7U! z`c;619`8SvDY!U%Rf&*J|CUyQE`Tbq_<&0GPVacUeHCC(&HQYXf;1cM3KsB;toA%z z3d15kG-BD*WJ8G=I_VR5?2n#YRsSz=<)Q98G1dX`=gy@?_0F%ziv1J6U#I!@ud4>i zIB{PQ|5M@M=}q;!*@(gjzqlJ8?>M_x(3qrEy~x#uN}c9E--eSnwK6}c`SPjS27eni z8Cwa!pu~l3%C-qD1lHUqN9s<0vwqC9)CvwfKb_Fz_Sf^F5oc2VRNO~aDp05D&w_{Bamcw6VHNZFnY-}59Vlgn%Q?d{{7cnDUQvFp81 z`7;nKEOeV&U6gR}k~?Y)@d3REJ2@2YzK(ex0|`^79^|a7wFw~efr4^!g~ai(;}|sH zK>v6Q=|!aK5~a_omKwysNum$6mXQP9HxipVDEl?`BQp<|LVos(jr67X zp>MGn^LUtTw_3Gr&#wL|MJkGQ4EdSQ(@mg8@?U|8t@%(6><3>P?yZ-yPV7F+q(j-^ z$gkq#IZi-$z`4*kg^RgfMffxWaYO(J&b|3GB}Rdp%1$>LR4*XZ;`t*wwD(bL3ccS2 zSZ}DiSq9-{!4Rq%BX29%cz{mtY{kT;W~kaM2~z%cX@#Rtiens;ZS_R&r$23{+wRn> z-ff26f0J!3yTJ_8-{-dB3QP_I?Y@=juv|n%A6rq;M07HP6wyqf`}&2e^Q#M(kw;m! z>`Z-e)$znkqQqo7^`(xLRwBzJ+VW0MnI@@r%)*av-$vL7+#ynFZ~cd;cJ0PNXAR>T ze956))%ChCQ&?u=vUcTtoGji)m1R-XJf^mxc-_vV20jf{O*$IF;+C6*E^3KwXHtnS z`>#q~f%s8u+tO6B`hb3qmW1Dp|a{w;~c%W8FuVHKy~Bj$3`CA zZkL3k4L6vPkq<2|cBA-qme^WDeG&5rM%AKFpEqwrwVK&Uz4r9#OxTb*r4d;>c#W=C zuj@yjbpeOV_ttzrm!3=S8&j&y)iaELwr$@-pS`o!zVp|kDg>fSYRSC*f>0xU{wvaj7Hjoo&%{yjCQ<=P5xbm16>VlQYA(;-{aBfkZ1w%lBge1u_#?EAXG6e;k$ z01IW)2=A{P6kxe7o1?}c#qGWTtpDmM8tnZ{@4J~X@yPKU(d4Y@JjTq%C~>%eH8|D5hG-lbAhfn{zfU+Jh7%OIKG){g*!v z&lkoG9Q;H(XDMXcJFqr{;*X;$jlO-7uv1?Yob_93O(k8mgSgr`G#mR{M%WBl6Qy#> z$kGc(%tnzbw+qR%>vS$|hr=voq`BcbilU`Jx&oSo+E3U-U`Ycj&|XnDJq$j&88|Nalr%;l+d_na1S%Tq zcaTy@s?nkSV&*onoZUDn4--05*mU9GE_8m8s7bT}FX*ihl9aAr=3i1=4?nvuQ!Iqu z^H{gsAP%WE;YE#LW>_76sQu=(WO=cj*l~4J-oVDQ%p-`YeoaRvx*Ld4;LvJBYsM^{ z@b@fwnGja;+Hi_p7wkKBa;jeO(7WyO=0PjLA$x6}Fvpsl7MX+6h%r16IWDJbYsv3Z zGk-z@3@tbzm9OTIq_wLLPuU;~M7j7MIGdQAHu&(d&NjeN`bf-i+uuIJt&tX#{xlYO zFz8Hfx#p6W|ESCA)iL|^=0JG0z&O@+uhx|M;3-9TXg3OU=2DpEiHB%x+M67C_6PT| zJNfy@i51{dF&S5@##|0%$l{jHzVp<)?}_WNwQdvt&{k?wj(yfb3<;WaGEU6bFzeCb zLW8PhE!>trty$z{S|D1y4QErXs<)k*YC3tbSbJXKwm){?Gv+eRZGzyhDL5bEGe7VUPBt`Fqjg&vwpdwsn-|IUkeVkZ+nPp{NrtlZt3>&dA((< zlCEv7$t5Ap40aCQYiiNkDdoKDQAYYbq>0XI2S+ND=?INr6j$*B@tL09&Gi+NnN+-{X zdoLab#nt8Y#`4W+j$Q0t+H?TcwrX+J#(k$rD@+zMv*{q-E5VEigO+T7;`gV!dAPRTw0O(<)8GEDm+7d2FNFZ~DS_iG_wYt2m#g$s+%L*n$i{rkvhPQ)+ zZe0gs9t|wPQU{Geat@kR3;M~+o%BZHYUW=MUWbgoZ2{glF*zthD7aQjcd8p7 z-!mpXi`47c{J0P>|0kL{dK?d$`(9O_*f2HBj*dUFhh2+UV&5U~W+ZgbSP+Jq6&|D{ zHQben$7dd#j-H#?r}7TkvhweyWBd13m^JCpyo=NSoW;23Z&MkYGL*`Z6(g_~_i#{6 zF;&)1yiI3fl@8)Qnj8JV`He`0FnIFjZHwf0liA;Ar`om|2D=7LyD_sr4-H;Cehozw z9cku;>((0wOj}b4DFNp@_Fd)BznTh6!w=Os2~F!U8qzPqchj6dsV@H_VIxXi6I{a->hBkNu>4q zr0j(9n7PqGo-W}6GrcZ@s<0;TlQ*7gp<>jM75RXvu{wv>s>mwfSj?tFFnJs?Ywzl3_|j50+C$+y-}Dv7`2bBUU7SF@QP0 zLSbKtz8bzEnnZC)5nchx_2ME;u(zQR1=o z{8$@(6Ub`}$u=Ifto9AtX-hrotS&!fkn>ETAmVkbI~tpQDBx0 zQZmlkzMMcltj#zdtz~vq*uo(WZ$#Ij7X0dzC|fS0DiOI<;HjN^Fc4zWHWdoA3$`>= z_@71|iMacocJXSCCRRR(S62Qf@Sk@1cpRx<%IvR?to(6UJN3EJ!x8G+HTtR;b`osq zr8Y0AlBr?UTzaH5Bkxip@WMWyc*X+#{Otwto6A;$FqTH=nbiF=!Qty-tcp1s=arI_ zp?Mk+T6c})bupxU;;i$0$Gf(5bAjq@6(_1}mWUxo&C-2V z@=I+|Hf2^N4N#M570=zwH%@XoMA^M~uySh@VYdq5{;^X12cgPocS=4TL47?YpmXkf z+-{U@z9Cg^#lub7a^s~%Uyu*KaMVs-yHjU15m}@>+3VU^aBZ0pX72aSpKC#d|J12L zB|09Oe90R@n1!ycAP7|O`(+0ACCE!{;sE4NYk*-_1@?d<Ha>NzP-$62@dU`MJML0d?BGW}iguOG?_W*(xf){fY?PCyBIyIk@Uu9Hdm`NnSMiNup#&&*0*N zTp#Kz#*^6Bdi6+E*xIE@Z&uIHSN~o$t!(KG-dzkwjbODkZNJQx@dE*$&FymyjNe-j zi?rnm#=vktv)ylV+at(+p*of+@ZxlG-PGKh5D@Zdm@E1+6(eUxLd`(t$cDyk8t+kh z2)z8aoiXoOfzhbFDEIF6EnQ>vcJ%#Xvp{Jv3LAm=eT=^q!WE8uZ`o zM8A4=75+rZio9;e!~`{%_6iIWeruu3BE*%)1RDi@n00X+pe!4VV!!92sgg#>jwXOf zH=maT=|_+!M5a1TVtV4M89nd58ei9O>PUwC5?m7GUh+J@!h&qsv=uLWviZvB*kH<$ zw((kr+((HUZTCXTA^|SYlc)#kF1b!i)0X5B;=!L;kB4UbBMkI-W5V zhx6`u->M90AK>`7JyddAdg;T+djPcWZD)~JW0;OXmBNJ5$ztIfgEA}02u)oWgUQ8ad zUsV$k(Zp7)tj-`VnE5ZJX#28PBy?Pyr((t-|DmTtiY&nO3Xnnf2U1u3eVtSr)$)fs6LTWt=a0>BPw!Ym<0c_30j>w%Pudbsy2Vr`Gn~PWhnG44mgg9t3 zTAQv~>-j?xWOmE3d?|w8^CzxSc8=G!WPiBaD2#vXa5is6;edGO%4M)uJpjdrN|9tK z!kKd^#!}0LpicYtGmj|0>IRR&Rs2U61P3WsD{n$LPpL0ZT95abPpWK(IkT!fbug=z_<_LmcM-bJV=vOgnI zBdADfK2XzZa(~c4luZzW;~B9Y5-j>YIC%$Sx%zL6sqW7bK$b z&>UKJ9qY^jz%crKbUHcfJ~Svm0qFu*b}n*k0C}anay7^$v;n!@os_K~%-eC{ zX+jk`Ur2a4hO=Gjk;(D@Nn32$4by!Y2`8-H^62F6U|c3#$P;*y&=E)-r{EO9#g!MX z>sSeJ>PYb*8OWy@O7pBJM{3`H6%-9JoyRdDnHg7AKToXGSDI8Q`?T~m42arHB3m6A zEO}+|x8XU=q#%NX3FT=`))>$mTk)=>MsuM5zFE|dao7wWDYwbIDDsX49{F3t&-?wv z*6a;k94z!lly;g}OZ~&3GUGbMf}H*pkwdtm8o2Fk#iUk}r@`1+ z^J}OG30Z(p0GzVTI70<0cIKeX#`x5_&O)n6ihZh#$aQ%kf7NDuA&Xo#);9d}Kh*SS z^blDD26Cj&a^(y>OSwTt&6{T{4KLD{7I-^4i(4$C(MJ0-zs-v<;02M3kG`)w@KOXh zrf@dD>g4Qg22$GmR_Ln!OC~kTFtsSCV8#gn*uV4H{=4pkd0WJ5E7*NG2xL#mro8v} zzAjAZGblLr&8SXvs#|V&%4y7BPf#MxH9@WoHcw(9os57AeTaQs&wN{~{#8Sci4t$4 z_O&k+qv+mDb#r%T?Jq&d>@vfne{TtQ7Wv+SbprYuzIFU{z_44N>F*)-`i<;mz2pad zOB-yz0>57Uw05*absb&l+ITva8?!VvqsdinlE*{VD7d7b^OhRYhFqa*30I-EO1%PS zEB$o{a5v!h@_6b0a2McYS#fh0MX};#$dbf|`84{y}VM45EYz{A~-87 zax214;#nUNMMgt5(3A+KAwF%P0VsArG-Tw9&3F~jOpztWq_=+kT{PkPAjchjVY>OT z+Nd%)Vjsf%i|GxV=eF$VWhi~p*N407&pfAKzv_72j`JX8k~YUkhka=HUYJaS@BD#M zKWVCx?LN!d!==JoYF7&>-XWxlt7sU!&;K`Z<(exIsM4>x%TEsDO<^=rbk)IU-Ly|w zQCXyoyZQbF|2!Mv`#;O?e^xhB^FLa0Lsgy*v#F_=h;X z%{ZxRz$214>5EPS`?+0JO)?PMc!W{&dwLG+RFHrZ8qX0+R_z=3QW}I$3`q4|-AKre zy*)J(H6QEnT6B)H^PPCU^iIrTP~{kk7edU_o5^lH(`fJ3cM=y?l8mBPH!U zvM1tYJl>bX%3M8rr);82L(s@3na;A|T=?>5?~n7y%S&-atJhywx4CH(^o;)qH@ipV zrd>N0|8A2$u#CByH~?WiNKln71Qu2lxB4|6*zrG5L%jUY#z)l)x471OPqw+DkV-TN zrD32oVIps4^WC*zIUoit zs|RQCwlpo-IzO5mZ6}2ivJag9BpxTx)ANb?BccCelsQ>1z;&$>haFiTQpFcmIG=!F zXi4*#vQ!yh6VpYsITam93`+-Xd@n@QRqYE#=y};58!c8Yd>{{1%tyx8?aiwT# zRhD1DxZ|)om6HMQpG7ywb#OXxhgKYW;N2?P%b_P^=eM2>sO#b%kYZ+ZFaM$YRr#w%{7U3<|WoJ9OhabIB~a@nDxNiq;J z5=4~Z4Ke=TO=RR>iwFei&5GwI&3yJx5x4r!8+X{_7~G;Ro%KXPLPDw#C;x})99CDY zhxQj-KupZle!hJ;0skB&pWkuYU?lCY`A&Uis&A~1sqvo3GF?Ya6Dz?|&_p3hCwJi& zw)LND$;HJ7(dk%Dr!Nym=SAX?_J`xPD}J{=oB!;Z?=8;m65UQa?&63}wfsdM*}+wU zj%ltVqIU`WCV!SDr-ft_WOTa;!`>5(0cFwnXvyl7rSQC6aaAlc(%cfp3P*5IzBMG7 zX;4dt?}H=|5`zXWg=ZPmn z6QZ(F-JSGpEsOFm+(CS(u-@TCxx#E!e){}=L*&c(GI!26rY(tw4?k!u>m-?MQQqHu z#%MzBQIzLm>GcHGlqk^l9bx9=$l1;HA-89e9@((Abz*|V{?tJ2_=`L@q9dOyU}hO! zZaFnu7wUG~;^%i&MR``!3qkVPruF$VYyl9n_GLV>b%;!q=ZD|CYpOC?H|rF<@5b-6 zwwx_jvim2WC=B?S=ril;qQh3h%&baiSXRDsti&6n#5S6h&YmldJaND7OOdVRE1U_z zXM{mir)4j?w81Iyj^drEQxuDf`}b#QQ`+jUT{ateB(#x%1>72tL~$Z=Gn;k|$hvWM zCh+QbRb{`dm*Mx(!Ye9(HsAKELXB47$7N^yg*rvU*e<@_@B>5_t4N$}vD z)z{<3b%z2WLJ-+#;$X04756sIL#og3v8tr8yIN!wKt|Oz7R(_$S(0 z{Y)(gI-U*PowIG(iA`OCvWKThqt+hcjhRGByZ%=TfNMc@VCZi=M`?<=6t*w$;o(mQ z)82KWIB6C5;&Vi9R4b`W>2-+G0hoSNOK~BQexB#<{{VJCiND*hP26-S-~ZkCz0W2T znOhn+-tw@BPe8qy(f!JE{gS{Fz}p(FZ(8c>e^&*(&1=XcjhiE%>3_GeEpq>t&H_kG z8&_v^WQ`{SGg98%Q9j;(DsN~MxW5CG5l-tT?C=Y5{% z{VxH4RgaFW<}%7hUx8uD`GvgRrdzrYui1*)yG#H$n~AfT1vq)QB$z0S)X>=d{O4rK zAAwMt_o)sgFG1Saz|768UjD`_xtY2-+s>2u&pe+Z9K&!_$5k0dU?9k?;NS+&XA!+HR0|D)Ar1cTxtiSOd}9SiOy94UD~~`QcOTO_H4Cih<-Z2vEhO`@^+l4F+EIcLvKyhX&vOcYpcUoZ)WkY{ug}bI^2lzYEZx z-QV;{2h@Ykz*A?pJTw@(@p?ldWChs7ti{bE85W& z-4a>^AXcPnFDw9h33@;;@?145-a41hgs4j2r5ejs0F*U=Lf8BJ&TOa*z|m_@jw@S! zgRj0HIrrI|`w)C}i2zow+1A~vvsqC|5fHH=64lS2f&rxEv*WHKJ)BJ`p2M$>5r$B{ z9C>}LeQ>v}rvm_C;Owsc&R;Ar20egV=c_kg6Daf&tjQTYP~QT4J>kfdPg5)F0#6Xu zplc3T(=U|83cd1Iio2b}vw6|5;V>Hrdj&e6k>Qf%>Tk^!c^e?x*< zQfxhSNB)cVBad{gw`Y2+gdtl`+`|j@%IgC}VhA8fOk~RE?Fj=oTYk90auLo602Q3w zvH$qY_*7d*&+?){xHrfmRO;rp15aFjlbQ zxANmZI(^dZO?Cv9H?Ug){L5#5xq0``9|I6MpHQz70hopJTf0Q5ZD`J3m~2zUy1>HL!aDJ62eN1FkJ-;4|SQfwsQf6BM-yC+JK z1c0gU{G4vAjOgUIe%L(FZ4G$x!Ik)kTyLWoie|1i$^o32n8{AemLe-AZ)@9ApWkxK zthX}Pex#5tRwlUCUS6$M7_#oLOImt~%}c9!*6bqrh?rIel40R|$>tSv5h_-sTtp%; z0SuH;kEAwqK*$zKkusxrnCMlC6)5PH(<=}CvCHiKt(KY1Zv@cjzndC9c&T$O)L1L= z}165^yU+T*T#Am@8-f)${XK1zn4>A(`3CbDPqY0 zMcDubpm`%}EsLLAKs{(8$CaOLO+^};10tck&Io%)v1O;yLt1>lF*@01a)1z+o2mee zwtM{M1{>4Rq2qI+bC+RdoJi#gLA4Ocr*CGW7Zdr2SV;?wTTN$wb|e;Y&RyS9%A52? zzEak&M4SLzp0zt3e#VmNsZ8v>BwvtQxHTtt9R))G2E01JK?1;lXHa2KEiA0H9&9#y zEC4ELe)?}#O0hBlPe56ei;<+WuRc&@<(-UBD0h6p-PmOVz}d{4%^V%Nu5qPO+<6GZ zQY4YN9x6rR@@Ap8Tg5VO-QH^3=><>>hF8zNEo2MjNGx~lCTlgj`dh^cC}qoOowb!Z zx|H*nB(TXv7hl%P%iUoQ@~iRX%kAB5N>1MAl@E*qx8g-ci7qOIwEDIJmOtk|D6}zPTe`x-Ti>o?D4a zJ+`vm1~35ElBxI-<$pc_93E||6wQT{ZTn;KMjv*as1si~lVoqtkN(Y$&^zvj1{d!e z`CweVdP^%~Yp+xjYkVpv6*3HXfZ?p{$~(#IY_^gtn_W78+xYH|GdsGkEvI)r`Y+y_ zo9x`S`;N4jND+dOXudR~I7b8guJ!3X<_6BR0&$*Ly91;mb7T>j4TP1l?q0^TzHI!~$-73F9 zo8@dKBo$&3U!bb?h^e93avW-SBegjeU{G=ds-2ILwaFBz%LzqwnxWh=1_fa_UCZ8& zbEoszA}f_MJk2OIQ|-X7j`shwA^3*bkSzxn z4>(@%bw$7UmAi3bEFP0ks+v6}`Jn4LEVDioh9HBII&ehMzKaz>t(q9dz=h8)uU*fS zla<!5eGk=3e&>@`|4NsnaKQ_DwU~Mdivg+H1g3R2Y*7W+BtW!! zl+Q-M=Yr|kpDnFN0iXh10t4ASQz%64L4hblKSa+zGG@Q@;+DjWJVlKrW{hvYxJ`mt z9`7W-y{%STaexKb2ajp3?k_5fP((xT`IGdG&Uqq%iwg^=wb6qVMAt zFBB>Cr8LtRu=PIMln>v--ORDix%*V_?o)gEzWs3jw|53kIv)A9M_s8JiwCue=Cfrv zS2y^Ky{Ec&JhL@1p70)R@*K9w6Lc$Cx#z?#UkDY#3Jt($D>EoCC>iX!@R^$ctbP}* zd)dl)SQZQ`^O>NKG>{&fEr!>1M07Tb&SnG1%>VOui3^w4hA%6drc05uUw&Efg-(QB znrM?Rk*tW&4#_4GIC;uUP3_eCtjWDkW?wS|ltqp}-lQZ|6vb)$2^25hmVI~QV=Z3D zT|OO)4rg-V(#@BHcfT)l7g|Pt*r_(6d36ozpioMya@_Q(rnv#f3Yvj-q&h81mq4nk z%f>xhH+`3#eRHU}V*?EE%ITB$zaTH{X;T~f(kC5I4;sXZ2VJuBOFZaw1+@JeWf=ju zHQE*)_YxiB+Lrm;*WSPP?_gpL4pV+P4sfchTq!*2Y(3y1VyD;jus*}ggs!}+)DJoGA3O2tizW--eir`{k6D@)Yw5!#PO)MX)*1Y_GKz^wcD{?&7% zfLKZ9G(SZNgvh9|!DH__o^EPe(@emw1da>y=j0Qtu-VYS`n=!BaJ4a@2S`%@+m1I( zeP7;{sM-=&1~SPXn?lzZFn1hxHFe){96>gi3BNug^7h%EWf+d3d?j)Hrtk6Q#(+K- zOcMwVf##KS<88-#tbtYl6R&Rr%4A)-ClrK1#SvJG1v?a^T|FEH9j$@#a?sjVA_ic+ zBZ+v&jb3bv`+ln(NM#OR15 z2$YuqDIKhC8T6&66SnD`$iuOFW2(B`s(l^rJuS{eKrQ^miWTLYGyi?4=yuc3B>rhOAXyVYxh=Xx9IE^;?p_? z70OEhSWeV&qQJ8Np7<*P0B45COTi(Qf?+s`^8EUem=Xw$0mJ_1%>d?x#HIjs?6ycS z*Z9e5T+~DzEI{ntHplL}S(#ryeH{RcG9Zb(kw9N9v7s|74Du`|P`*qst>^NExnG4! z-|-*kBwojYhhjx0DaO43gGyWXN;2F6U1jS3FkClup0n)>(3NwZeTvC@Bb0R~sSSJF zExrP~7gm>>7pJ`<&q~0NllMljroBy_@!VXiedxdzpa7IV-Vv(*e}Y)^?`^;SW^W;7 zlVGIaC^!*jq9Yx<6?SO!x-&fPi_NrL`5)ckvDRYBL?AK{n|%2O_Z_7UrG#+vr>S(X zsye*r)RG4~zTz}FxoVcQJ<{Mk(r9#=QvL#AUF z7m6zd&!Zg;{*7)J@#~m-5c5 zDu`E3{hYHPbtOn3GHQdmvK(vv?0x{n1e2WQSmfQkX!7#_?5(N!E876<9~=YF6ku2* z%U6v;Sr_=CUT>AkYeW(xqGWFo5GyIk?BcBLy5JC>4$^8C*|4O#y(^|%0PF5=GBg`1 zIpTcS-a242G~O{u%>C?EKAcxokber|3{%b0C@O5YG{YIBer2s(@Ll)gdn|0C*k zmC%t*iW1{4Z^GEMHRm5XFdLlk7cv$CeEIn|?zzZ|2L1m$5O{sS50rosPytGVV}*YX z8Cc!P8Gw-o{7FD8R2OHgg_~xFx2wxkB&cpXvg8V^SsZs0Dy4%Wtxp4yRGvuidn|$tE+tH5Ozh!igQd+m? zj{qPOEKzU-yy~S~&r~YrBvR-W&&ApfJ1O!MI=N_XJ+>n~K3fd06v9b>A<#oHvSL(2 z*>##es#NTxHkU}2^-(Z|aBBYLw@n@g1p`!9FHAzAD9fpdDTQO1@f(f%cE-jji!6(r zj@9QPOoNv_|I*`FPk?Up(Y?>qh^vOkFhBJ(K{XpuyfQy{IlVe*BcK%Q;;?8BxH%vj z%&Xc-rZHf2_S)8_OD%n-_QN*4?QT?@~qUK zxxFW@`45;^#&t{Ma!Qv7ge`}2%>kh$Se+W`$b@y~K00iB2n=ju5hC^_=bv5~j+&bP z^R}l^1dMW<9_k3V*wA|wF5c=nlpoE+_XOfAP4Eq~_I9>7!; z=*VcQV0DyFuAlg(nmH&%qi&K6+kA1XqiBgRLI@xcVwq-X|ST&z9VX?I&H^Q z!n#>4weXhDoKh*eraEa+wTP94fgA;A^tPsgBp+1{&(p7z+xm68pD|e-xqR|&NTK&I zH}$iUY<#V;j1*&IRVdeoq=I13z=AR;D#moday6SQ#d!*DX}IJbXfnCDtxs(3SAiOXkw`xVD7*~wc1B=jT~M=f20xMMTv=+ndL zc;kI8@w0m$e&XsCKo3}CK*5ot07k7{{rQsCCg0Y-d^fz;Flny*k05&m^ry^_tOF79)U@UI75EE37Sb3|e zb#6&6xTfIGm$FUU5FHv{8=F_{S8MGee*IN~y4Dn7J*nHr%dd~yeB0$Ro>4^+%5gL~ zeBJZZ=VZ`Wezo=iE*-PC_+$BG!@V#TmO`g)F7@eznmvwE=p|SPs%ndil;V87Wz90# z@EsY^CYRCVGHOf$i0Y@wx(~H>4tn(VjnGkIMo~l=#i>WWSr09%tFrUS3V?5hUQg>R zc41xN`sDIxw#j^{X{TaOsBVTMt{wLrwqkePTM`$u*ykK=Z|pxX>FGqd!ChX6**QQr zFim1Qd)#3A2qRtoX$3H;Pq0O^Q=Po^VA)%;QUiCrgFhW>q*-b(yO?$LsK z_*C1~7oxd{pmqW!f~t_OH2T+ppR&KX(N6dM2@AM3KgL9oX0Jmm6anNSQcEw5O$ZDG z0zMys0gE?&$m%U9#Y(Kz#OEanmOxi2Fq*@vycvnAy&DM16h=TuPc9cGSJD$9^~6Zl zqeNPQF{{Bp=Z?ZMciB zM{ZMlNiHHE2N*SsnOcdYPGHqZFfuR$C3*K$YX_EsRP(gC`yQ>zwjwdR4$=f(AyCarBH0HrW06pp+u zJrTa|yTEGyp~?faVXSS5$i=5lg3ft#|CVQ;eCWIX#&z`J?WcaGCnQ5Tk_{74l^Ur568UHJ+B`BKP??7MiG^ z1B9A&7r-NAaQ~JoJLGWZ^+pH;go3S3_?)|h9FpL!HJHru)~>j88Gd~0B- zlwywj+p+AjF)?Q?tue)f0aT=583u$p$#=%uL5u-&xMDh`C$Ug09%yRZ(UhA_kb2P8NX4QCd{#O!8f;9d zT}hqi2mscAyP7I6;MEB)@C^2~pByl@HM0iJ*0Y7^SoQj#6c;nW3aD6$3xyT5b*(ga zGy9*oV!N~1;;&Dovhx*6Ws8q01D-JOe8vRAl#)aR+d&v=Z6n)H=u^{`a!RVC#7wZF z7zuIatzXoe9Gm9}D$(#S647@GYC&Fy4^lTPTYkp@z_~*RzRAjt2?Qbo-W5plwLC+ssDCy+{7>4Ew9V-r3gnI_x0Vf>kg@X^h*xy|Uaa-lNPFc$Q%|-;B1TRx?&h z#%^I*L1HREQSMo#Y`|1I7;G1!j%rRK3<3RkBkO^kfh7V+U;uqA=w?t^nrL2~Hm5>H zK-zX}b>@64fZZqOoq_Dl^PSE>IvX`7Lrqk1sG+j&RBGXl#`aqV9e^WpA)O9ZWaaIL zeayW)0fUuRbW~!&ag-NQ(HfXz&=+584;z?~1)QlEmml6A$iHvLk7sD}%7gG#9oT&~5lt;g5Uv!&(eo;x-+ z2ldXL#>MlQbg=3>Zdsf}c*@szXMJ2cSf#vTvLlR9)0iE@74rfJR4mYN~i>7s**+tffRU3IpYup-6#3^^M-Pk zep=EnREpzq6AnZWt^; zKY!{T=K9{FcJI-T_#yXy_t@gl!otv!1as?vbLnCRkQkIn-Jwos3@BTJ&2LDKhb5lM zss>fQ%c_IIWxkXm50IxWl;h=mDB}?J%z~XPcOY|zm zt)FXrR+$*MTJmQvHkR{7;~i9Td|pt|GKqqC4mFU4-!%Ih0lTYL=jvrHeMc?_h}lIW zmq5VV{HEkowUSjnXC*7eC#tUAJC;H^tIp&$=3@-Nn%qVT9bbT}*O-|rs3TngVC%8! z)??Lk|K9FDBFzrzJcrEjOGK_mWX-1bai(>k0xsfk1oA7vrq+nr3BXz{b15;;8Tlqw zDWUbs*(J}I@~qJ+-lH0C4=e*H<&F0g6+ZjRvFE;auy)r1bTL@zaF^0W&JeLVf~{>A zn)ZOjm&Y&VIir;?e_Apy1*prvQb`Gww8Ws$b!_?8c{y33yh5A3RboX$>$# zKbaqYWlJ$_kp=X2??-|2BIgsXzD9%n-nCY2EGNN4pau*9@Q- z6U=TMu+hk3EvVaagm3GUW`-EEo0VXs(AfiAY^=E6Bn%T)KUkz~mhM6%Z!pQ&cK;to z%<~mtH+l1PPaQYV0Xkf4*fp*9ek1k|cK&XRi(J}5f$@vG9=WeM1VupJS;XK@7B_Iw zv`a=U?YTnV>g@S#dw83?Bo; zdIBliZKNwtZ`$s?QAipS!N!_xe0)a8S3J!%CV6| zCRkFNqKt~r5(-^Im$UmBg^4-*-1`<6I!|mdIt(VaNoSCvAR7X>*1y#v&+2S3NpoPn zOMmXeJ?wY(Rg@oQx4!L=Ei_b+pqKqOw|(>X5+ifTkvXv9b%K##m zBnHHD$m}2d5Ly&xuSN5wn=i=bfMB%Ka+XB zMH~uG4JO8R#TMS!(*J2Hp=H!`@@x--5 z6<1dVz`Nfm`;Y5qUd@%W%-T$K=@ReW#{o1I6n8&kl2zj)r`gB8D*-4*OOr3o>TN6q zTTWK4y%@20&4ox&rY@Sj)&u`x9o;H9kyDj7M1$_iq6N8wg2FO?^W|XkuBQ1{7b;mv zHR~W6J2(bFY&2Jl-jtdBW{<6N(2<@>6{7_}N{@%sISeAzj9k*#(AEqewY?&8*Zv#; zl%olw$Eo>m9FUBjj}Ea~J)8uNf^F;91F&{^v$LzW*8qy|(=tyfTTX<;`mN z-x`(uP%d&!fQVt&L$*rkaQcHy-#QU(mbrdYqg{i~{Nv~=2MNUOhl6%c>ds-M<`tII zHCh~o+aGf4)91YVA~t7tI`Sz(p<7mG9YkRrG5`xgI(JWIrqimwA=-avQTLPahRO4$xt~CAM!=k_m z6+)qxfnPpbRR@JqJ}Z>t)oM=6h0D2c`Gfx!%`KEAflwIKbjlKlL7cQcG2!Pz|YIZhh>vET3IZLOag<6|s*JgF<^m8gz=<0YS9~Bc<){@r?uD#Ze z6LdAe*1?3%39@{xup%yx6n#fG-}((AZxH#Wj?|>0D`GSKT=pPauX1>$w_P!EL2K*d zv2}Cy#xLyo#Sgy_3%iET3>Zz-rP+24u$rpZ&h{r3TC=N7frFd#tA-BvRFsVPVwFtZ zr3fm_s93piZy>8PLqb<3+LelaS^~Ijb=IL7FpJ!(Iq>;xYAi@lC4enp>Hl{+axd%c z*cEZxARBuxOX?jOC14~0QmG)8cm}1?QZ_l6mjsrABMOovhoa)TOh5oqSgNc|=H)+P zNuUDNOukjz>Qt`@CVQ*W`Gn)f->eo^6uJWHoC>0PWymUjrpA||(50sf(F;q-t7)Ul z)cwEi5Hi{P?6TTts;LEu`kFd*;}A93mDPNg$od;C_rra>j|%1dba?H(naXM=edT6$ z`~xb8k{~56jI})enU8$qI5TNzXXWSxF!Nt8QVE1*SATtz<%l)l24MG7NzxIB<&->W zk@X)p?D$uf(rP90>uf$;n*Q57A(B1t@#JKNL+4R_Dkypmu$f>*EC~x2ME~P=Z2PmE zxHP@R(p=1^nzIMkY(J^vhJt#xIUJ2&@6N1CiMOUY<|h2{C5IsBmT$E}VoU&$m@N;_ zKla?4frB%5>MBipn^O%|d3pTdd)FIFe6X=CATFn@4GKet0T_J!>JUqR+pf|BDxn!p zl4o!+pn$}3;_ktjw%yrT@C+CUd?IL@8DhInmhS#Keb4IviRCEes}zEaY)LSvK)2GQ zm%z#1P81A*#Gs_c0Mr3Ll7_~pRHG8~1d?hNOJr-PS`hvI}-4{7TrBWH7nd$s{&)sBDR2j~q<|K^T$ZRMh!sWrgQmt1^?=V?_K(Gefo|B(h zJ@>xE3(G^73Ciji6vCGbQ_glqfr&pJTrX*ejkeyxuNaV~_ zv(I7c_AnfFoD_cfoTOF<;?_YE!x4r<;AFG!c=N};oOC7vuuTDy36M-s6ia;KdbPQm zt8Fyvs-cmkXGpJlSunLLDNjXE-$I^~QdOgr5#UrupHZ?Ag<>_W zU?LAp(v-?Fzq(qp@{zwwzym_!?P~y}Vm^2M20@7^*F^qtT8?hw-FNZj$6~?z8r72+ zjR1(Ao6ZFjR5>Y#^802cBby$}^UERt-*M+B5xr_@K(Bs3n+Ym6{p$B~x6W-YTw9pz zgw`EHz&g%u72tsqb|*HH?G2_XG-o8J1Eucy2rOq*w{UK>t34n@VF1j4Q9W!C^u^~s z7PbEa%D^`+?1o~wgeq@s_SH`Rx}AUI1<3R{bROO${l0hR;PmiA&7QS%wE2;zhkK4p z0_grSmktu|VU9Cp0A1u_UM)u@m7~k3R+0v~@x)lOdgA3?B2|=nL^J(LtQos$*Ckby ztJ3_bPd-RHdvzWjb>a*5BD8UoH-a8*&_fd!bA3p1_9_i#2N z0E3NGvQ%$lTlc}{`^49k$u8E+NeBcA&S2Xl{RYRkUcIoV1`6xq;Nsv_BajOz02pq0XmIiU zPfY+*5DI2%|IF6@*#?cg!}mm6OP>uuOW!7Y+tsuCXNDhQfONDOz&o!T4qxviz@Fpd ztQ$bI>*+=SrR795nJXrB5-b2zTQ)rf)6`{X-|w3LSzOf*0D!&ALcnKcGGtxw=+uKK zSzleDMyQ}l0Yq*qwNNW`wY9FyKcULINUXBk*P@ryGP9;Umeev!rjAp!$wX?L%57gC z48FK-kXJRC1z-ty8B`0|j5*M$cQn}h_s+lgcNC~5)0_6?=SI7>58MP`y>ntoj@~jl z4Ea#P+24^1CTv}fYBE(#mZ8)gI;p|~MgZGSvXeg&oIPy!(}oAIqI6c)=wQpq`t4{x zyoqrSU*T+y91E0^4FFt!58Hc~d{x=2pT0GGj~16FIWxYsc23PC8yfE~2|IGdWP?Gy z(v?6m5p3FCTRV-D ze(}8%AG}p(9oc<+qn~3@WKfcccoduj0|mG9D`w6lsMWGEJbuqNx3?TA$YXVw3m zQA2LMK~?dQjqr%6|dGD!qoWG@CrdSl{o`h7bWtk zoTi`vfVGhiqObjC?b5aKN?HO}2uAcSS2dNFe|&A^gG~e2Xe$y{8hd>p6SLpx7F6PC zDheGZcDFydr~8{nyTAEZ_o*igfxT+sKn*TsA+`^&-a~9;gglrPwe3k`+kip6ZWJI( zmo`z1cMshB(y5>C9GI@%S3?BuQd)ClQSni_$wjz!si)pf1b+Sc!1$$|i927e+GAik zthjza0Qg`_6Z8^{MOZU#aoLaQKmFjfkA)Wfz|=^TKn#s-U5hyH{=C=!)9=lV?0EMl zhoF(kYdeqfKQb##b0a&}BF?pl^VWGWI;JD2GAOFcn)Myw2qew|XP?{RZBY4%0)RrK zSWV}Fs;pjWJ>=9R(hZvqQA=@FQW%|7bC#A=bpfLdT~hA}$3nZ?kj2Z}!^P zXZX7JGL+-x9qJfRfJR?`=XS%i)$?Q3bg`N)%Ad9vNn|I3>LL|3eXW&Xo5fz3AKNBN z3jt&z8)1l+Bi+?>skyIi52m+UR)T@sP#yr-euAaO(E?giW7|?Odvc}ezH*ity#Nn$ z2F4{g7SKLh*gijYpz=S;mO3Nc$=P`3JE}%Z- zR!mN$7^U4RQP5kjg$UTqFkachhPzE?Pc;?tIvuZ;(V=?5*HUW*Kqa0RvRPUwsIMif z9jNN^vQ7gmp9S27HkjRODp(&O5FYk9)l z=q<0$z_|v$?Y1A}sA2$$*_TG!j%^j-vioT<&iIerV+Bl~-*WY}9sYr(-+nQz#M|6Y zwfaj7lP@I*bbS79O-T7R>^gdF^1_~_i+<~$@%XREb4Kl<^;`JE@8WOnv~fzn!DCmC zKK1VX7M;osk`(I&LV+qE<&7Lr?Fr|tLitmZffyxmY^~4G%R9Fhb2Nxb*4F__O znxa6W67>&SeMijz4*o^Iz1yY&9%5!Tlb+23Ixrl-f{~4m4VubU)C@f$>+dBCFpUAz zW|vN@$k)qEgN8tJW4BX}FpC@kFIFmiwkTG_^#F7Y^irA|s**t>kT#e<*KltYtj2n^ z1FQN-b1GuYuXjpN9-i${0^Azk3ZQoJ6SHQKClXKOA(8+hZ(L_h>&}+*XRGSqQWjuR z#R_SW9wejc)c=DIXK zzJ5R%*x9-I)VKeBb~wOtqRY3cWJ8HrnfAt}y#V$ODu`TbSCj%xo$0lZU4zrEyN;ZJ z=M20%uuLGe1Y!V9;9Y@WYE;O_I`R?K8MwLQwCPN@n=)Ff< zm(E8$N4<;Z)AE%1^%#{RZBvaVrCJE3g952n$fBm?u6@XAQ;$6pEIN7&w2-Y%mnjVD z4noykMx^U91fvOK#UGD?&Ce`pqPKQ1W(dmb%YH_q_@}DNoCJ-<*SY}iif-u%FHQL< zAgNRI7@hdWH?{-f_G78;!31kyOkSt&sdXYJp+o^zf~7_>bsgCiJkKU(SXYlo?y&w7 z3(ku_I7%ydf-=CyrkkeDc0M$C>wXr`*;fy}dtuMh&;D|I&msW5f&ay;hgPG_yu@T~ zu3dlq8bO7?!k{eiQhK^De^wtDT=y#zm2vU@>jU+uk}zZNyh;vTVD~7wjKNv<;X!fi zPWg27?EcGV_t)0P$*&J>=~?H{Fza!A@5BLrEFE$;XzmUJVA|^hj6l}F=Q#0WQw2Yu z08WG)Z@u{0CU3gQn|kX9U)XRa0U&E)V!^hVOFIF?LvE&yzSgfqXK$#pH`MG+Hm@Ib zA zej(l7@sfX5{v?(_M?Sc`=}jqTH(sS?KOdW7048#Nr7|6C@UrodWZQ8e8!SjL#U?0# z=!nQ!8GE23HL*m&Fu>Z#4DfKrA;D;;YeBX-u!$M6%fH&-%48z)@Q2OCRkuHic_V;# zFYE#Ew=X^3=1uqlD{bDyyBGGfdJ_QFLa@ZkP@G<5pU?`Q7Yi{qHAnSUrlpqva0ixm z9J;YQ*R~qk$PB;Gy$AERwG`CH7ysbGuU~tloHy3Oc=w?j!3lpUZv?OsYS|FL6Mi?q zhTIOIs`(uWfRNh`=&j}4$@kJ9XKni+55TENqt3wh9GkS*3z`G12*6+|PoCc!3%1UT z>`;#!q!zstFxv~ej$Q3LIkIiwX7g=>Y8t$HgWYiPhsUp9IuXwwE2cN$gzP!hqhi8( z2?i03>7bMe76H~^X8@{FBSb(n+8Kjgr(rk?GHUJWHMn}s+MX>@B3w|V{BrF|i;+w* zl9nfiYEIx(+ge-y6{@Y${aVNz8Ecf$7lWM>@}=T*9q3_wX5c- z;h*yd9$3tqMlbFP-t;!w z3o8*P0T9^Ld19;HZfx{(HowK@w>0{7;fqq_k`Q@^S~NtJLtp*%m;d}{o4khwXa^jC z70|&>*NF;u4cy$`t5n?$_5uM02H)>JaveacKi1VZx8cPiPTOtWU;wZeO8!{#*wyJ% zKcDg@_>VED9vFxv5|jvpM6l7@Js%lwlZVYxbrZ?N?BhcRzVP*-*1+
  • lEzgQ%@* z$WWLF=3I;|#9XP!=XMQFy8@{OSG{Xzb{n@m=>w1sme!`q67-tK|)fb|bc!foY0u;uFPjvvKl$2IRGJLj_p32MYh1jJy1;eQ37z|2)$UvfC zTL+u~6B|jYtSL!TbrYf-Zl%qtGc7zO)w<9GQu9E!XK+6N*_%$&B4(NfcBMxq)Z&@Z zkT(_HrO{<;9@ug74TFG|Uw?1kqu;DE^@AhZ7bdoC$l7Bsw-@4yJfroH%L2#ZP!Wm6$eZk}O#pV|Bv+|j$(>`emn zgCYO?h_}IY4{7(cksZmHeJy6MC9*G^9GMv1e*DD9m6076h7Krau0t++ccal!w+)y( ztK0U3aFa-aJ&fp?zjL-gxcOPWig)SZPa7_}q_OrHI_YGG-7j}{bQFeslDm55VF`vWfAq>>I+y+`V) z>ETn}TSM{X;kE5gyQ0HcqeBP4=wL0aO?sR2%74xjqLQjEtW6tTH@GM@m9Ci^6U8@8 z)EuDbhQ7;f_DGxP3bRuY_pv?Nq^*)q*zD9I087BhMFGmKn(gqvl?-s5`MTpHTEZ&;X|32&x_X zmYso2H0Y%3n?uE{8MjaJsx{ezZ6;gk=(E4v@b%f@t&YyMW?$MBSnEC(GTN#)E z`hWZ>0Tr_4Dz@1I2TWck0F&1le&u}t6qJCc3~tpn70zLN=tTV8@B6fcdhKEJ=~H2G10Ei|uw00icRsrfz?P%J>UAa;zQ;76 zLef;u8UXU{%X>fb%+*ER9+J}+m+x7iHaud8f=XP+oTPI zCS~tjH(vQS-#@TA*H$fYy9Ym5nQmPTwq7~I0Yrj@LJv?^AZ~ShIR72zZj*Dj34mkw zMhUCV#O^t@>z!|m96UWR^;b8u!7PC&LA&u&76o}(SC+FiqjOr93TpvpmfUUZmGY}w z1FiYsidd?yjm~cS+7}ylD{Kl|z#&1G53c5MFn^A2RR>>M1MYlqrS*7kEw?AGR{)|j zF`fOZ^TTd}YGkybr8}!fSb`B~s4dX{cIuA=LD$P*Is@MKxo?Q z4J#cGEi3eTD1t-gi zBG0u1Rwb}HPJB#rSwFTCf@AzA+jS=0mXjUXV0Lln7NcW@(mECgK^f3Xyrinz<${W( zs*I6nAgDXXumqrOa6bUqzmh^<2(Q%wc>Ad@1DGEwq=wcp0d}1F-F$FG9>Xa=whmg; zK~dz%&%bdHkXV!fF)_^&2s*40)OoBeopC^lT{p>}Gd-PM3oa5(Q>v-k)VO|1sGOx! z({)J3?h{f$2t~SjodM9ajdHgs?VW*4O(VH+kW{D_z#9Z z|Mg)i>B85xc0L>m4BXsxY~mC8E#z5BhGv5;U~77)sd=X@F(x}IFa#1&tf57XFEpun z7!Zi+ycMc(oP?&)O;m>f3Q(ycR8}*5rUbB!yE|N;?b0`zYn@n00B2<)Z}R{f7&HRl zOQf15`sN0fLv$4RCBf9pFdV{f@pJF?lrjeOQ^^TaVo~t+SJ#$g2X=HFyxG<~o|rWg zfP&4X+!O{qmTKG3_J18PHm}2tEp6P&+c5&EHsNvd#}q&+h~+VHc?_X*tj)(*+>|d7 z)#erE=E~Gir+j5rgPvwz#%Qas+}#RqUtq;*E6q%H0_Z(>v#~jU{N%{tV-xn~k3O*E zLdzaOr>kFn0ncCET<9AMx2&z&DUeAuOpk51JF`Y}_3yrSLSC7>4&JPk3^%WAYjkFP zU5dSi$Pxm6RbfmsQ$AZ`L0oV*wI_3*)(oulR9RgqYi@95_8cGo#S2erOXy_SwH9&S z8V}$$F~NpNrVeQY3YNkMNCfh% zU_$C}l&HE0NXjx%Jub=m8kIsPGq(t2e<_*|=LsllsPllf=(*Uw>&Vh3&>QP_NB zE$U82IY1J4WAET)`Dya=t#?&^<&zCoNA9;v$d>GMnSiAV`%*DdHaM)6WKp~AP%s40 zI~uFWbd44w|CRa-!?Xn$gRV^6&#E+@t1(aO?rg@ERwO5BMR zI`$&T#Q`8Z%mRb~PoY~L6<5Fma0H6UpjAG5D|K(g-v8{9_JmSM+AI#X##kkwhrS-X z`J#=*HASm;Pk8kc>2_tbiDCb zKl@yZH}UzW-tFuOYYi)3J!ElZctn6Ju6KZgHw( zaoXz+EcYHCpTE4#?oQvlv@@&GXKkQ0Z0nzyeYbo4cL~5qnvr%C3<1f-8&`v^qpv+8 z0mYP+0*^dBY;R57sdaqz^p_4kJq*Ct8>)S=7~=sl^`lg+XS?$c9JfztNlz>;pPS+w zO$-F86wh+gg$Ed$zcramLs28t2X{i@9OPl0Pj3^0jgF}Rtuzq zf_XaM*rRD+j#TG|ibRPqNrndVQKlG|OLU3Wr<}5dI03k(fRM{8E_t`CcZ;u05z9i0M}mIqAAMs z67&@8%%z^KeRHFic1DA3zxxLl9PV@?W_PZ?ao0w6xZLUECr51dk7H!E1XKW49T&_3 zdYsucV37FUm5}y{KRx{=t>NgkOFQ=*x?y)^?5@n=6C=r(y|X6_ph+W={pRaw0MlOX zg(poiRqo8d_K$1;{7)i){VHdrTHz=#d2#pT#ocXzWp|)dDj4Zz*uDH1Ju^^9Td+=8 zz(_ExulM9$B`*E=^QoAe7 zF{_qG;!wf>03ZNKL_t)}FRxwCP_X;|d@q3TMS+5oHw86L*vmiAX(n`1jZ+r@nhNTv zwW>}cAh^S&-r6_Y(8_B&TfaWtMWJ`#msYR25Xk|^2D7%nx>me){AYugm0*+y6gGGX zfP>GM_15~mjYXWfAb0b;SN<3h4C?uUFQ?50OWEa4FHC#SpBYH5G&x#RPp`jms}ZLJ zd_2($0F*#$zZ^+TPFVdBs}nq+QUwnFM_(({prN=Ms%B3we#+(FX(sdW> z?!LKF{*F$4!PeFq121j)q~@DFU^yYq|KN)NWO8X}!hdVRPj0I%wDEjv!oQiRxo*?v zXJU4;KCy%+{PB?6wO+Is54mN=wQ{7qw3EwUDNaxCd)^VB*q{(VH7~7PO2sZ!0b+6) zRxZqnMX}b%RR_#VHMam2wGsffA<*RigM-D;vRDyU&tEB_+O)4Tc5x11EPhwxF5lYq zbSYNh^E`m|W8S6nOQ?I|5w$3&QgD&;s}j>t%`5U_4M$B;EP1^m_H8})%!n*h8mJKJ(%a>SrIGy{yt}Yd_ofZ1()u&12uoNiZ{v07+P{(UU2YOd%9o9-06o z0+uL-a*QTxF%+We%L9PqgURKyCYKJ-|Vt5-;V$ z+1rdVLBUYQ{LpiOOh^n4<%n`(gN8^f?-$H%A`U4|D#dk#i=|Z<4v!9<1-8+ zQHcQ%o%TNd_57jdBbQ$AY4jBmwFOv1-m&lA?(o}=t~Giq$)GtIYFL?K9RWR+GK8VO z8S0A!+d|V`0?bcs;ZS84Yz(RtY)e;SHPmt7%Ofi@3Xc8RC$4w{D?fR0kV;H3YbNXI zv;fK_y(BRV^P#&k)6{#ey6@|TAqEnFvyS~|oA-lNM~$l9WXFT!-3i61@4d781)i-D z=oG0MbH75O*>;yI31)UJtn8a#{v^Wc0kx6%3RldUC*SVb@bwe_`_Bt$OD^81ja7PE z5N?RKLaJdk*mgT!t+|6Q8${rvy>iVShp+yV%AV|g?kVtq%=sd;wG zWBSazNHkCyfykmnATd&rPi3Ll(^Il>N0!tVRJhOtqS@D+dVdB~B%l(wt$+M^M$aYQ zi&T|8qX=3*sT-t3UXShl!QvqCX0Rnl@(O46Kl<-fVj01~3NF%-JM;}T)m zT->Ia%?*WdDPiB2rjko-0QUcj_gl8ESe*Q=;U=NNsh3e|-IcMmZFIVbO|^@cgWYD~;p%l{vD?;hR8ecy?G=7qtVcn}0Zf=`eXNxevml;r4X zS(Ys;P8>HcH`zApHk+H?+;n^0-m|A?_hhp@yXUsq+}q~5$<3xWZMt!sv~FTYVQkB? zY=xF3OOz<;K~f|^iX;dS1VFr>gPFO1%=~}>NjYwlrd4owa3Bbn8T{t=eSN;4@AsRa z0VW^UtxXvXcJZe#9$ydJscPWKL}gwC-8ZFc^jNA)cqMVY%PwSS}dcvQBQD7KRhvyfOw7hL^n`$ML>V*>ViiKTjC zK>*=Jx2+fB)m_|4fqgD-z(_7y8#D zbxYG;n>#^M5KF4%Km6&pQjxmV*=A}h|5@HDXrs0&MUzq6#zr%Ah~)*EmYuE9(Z4-5 zf4Mtft)WvR=O*`P{MH)4B<5KehU9#KG=f(Jm_~s?o=bd5+0Nb=X z*}6Anb_twGTAFPJ(6f6Xn>B17o((L!@?bysxpOY>)+~;#+oTQ;a>894aZwMRcW zdh3ndpk=co!|KZKXYajMc;Nem!-|caml|10?4g79ayDSD4;$@O?MGpEbYUPeZx#ye zi8TPWhQvR7^Q4ji7J);LT|4-w%Ke&}=x{auoT|V`oq4v|p$PD)vBiHT$@&$Q6Ye^4 zYxu7lhj z>>vKzt0%rR1+@&2mB33di7<+&6Jb)wUNj0Me@l@Lb=vbV_s}ZJDY!Ch0_w|fO0Y=a zGl2qWC|$|f2;{d)6>_x%PJ&K`PSY2x>dH}?-T+FA=E^cu+UO+%%&i|7j7}*qW|ub_ zGdO+Ow*6|qXr(;!!t+NJyzqffE$eN{@dXOP`hq^bP{rY|e7iXr(33EMmBI2h$l!Pz z`@pAyN1wgZbv$kFC^hcLw(d{Xc?-#y8acbY(a${lqYr)Rt>66It8Ko}pMUx3<%O+1 zbH%H#Tx(@Q*LNvmYGDiwqbodlx<1L;uBkgNqw>V9cr$(6&Z zWxz5xfK`y5+Rs;7$!n*;$ZEt(qG%axejV8eADXZfvPR9gE#-@BF0ONQW_hy3x-sBSO?fJI->$^X; zH2Y>NXF|`h72Yhk`;r|8qPA8Q-MRASu4K#tAh~X}yOM5i%+;9q(RUxBfUEEHZAr-( zI50)iayo7{n2LKJzR}da_SnbY_Vookthc_P;y74I%RpX zj9y~tZSu;jv1!)UTpg0bAgk98M(4dL)i1C)(}g_WKR8db;=ukpeFJKG>B1Yk-+p8F zm3R7heW|nOp2Ll1o7}U_^#BD3OAWSTHyWs-mYK$*y&?&lhswiFQTrF?mYA9y8ELZC*m|Tojd_oAO8gxJn^1I)yUq0Nb)Ry8V>8 zr>#xJL~!fTo4Y?SwK&rRAQ7`9Vl}M=+V0I{K5+8tz=0_Mp_!(xp*aBSK}S63Sh(3P z{^K*MU$Bn6ARHcLw<{e`USap_k>-NDQ`N~#b;)Cf>J{3Y>4%@ZWVYtC=jmGvr~cly;k7k?gD7&&wv7`vQ|o4l%_Ws3-sMN4&B0kJ@8PtZSBO zR_`8*xXCi%>`+GpQ|hp9u;_^g6$DF7bn_~?C9vfB#(#h6?KgK7@_caFRUtK8z0^DU z=B`lCnNAzpYO|GZ4D_zqbfhd?XDCS>;rM-@2j22g%JGXg+ctFJklz!vf@ZG4X7Q%( zje%{13SZtYm6;tM9tUKaW!C&on=b{(DL-TPl^s5$myFsm+)#Ouj7)k*YOl0X^eaK9 z%z}`iSNvgF&EL`*BTR4lA|bqv+&O%oAv z=!{~_Z*=-{E?+3@_sGD77Y@_F*>61l(6g^HoRkitai{7$NBpk0zJ5p<;Fbv4=SF>G zz!hHpk0*q@P6pe3Xd@%CYv*EnZ{W(gT>y%CzL@84#w?XWpgT9)np-1V-kOUq@0SIJ z0%k7v^dFjZG_61J#nTKYULF~;{Np*W{yGnGWWUR}X>6;hC82@$oQ&D%S&zpoiXWl9 z<;t7!n5Ct4ZNpb`I-Le0VVl;|zqS_GTA%6~p1u0&o(*2Ew>RMM#E<@)x8}#X6<|Z& zD!#3ibLn0No7(F0km%5~cXhVeSeKs}J0QUx@^@w9b_1qL@j}vH%16sGbPTc@+=!{n z@1@j`SOjQ^#H$i?is_SJkkvT0N;4*ru);>-D*ahyFm=5SeZ4*(l_cnix6IHSFEa*F z(i1>yLoBbIx~9{NiD8vXg63N!??sc=v+Se)W!mTv0A%9k&}_BedUDOS^N||>+7DJ) z4JJqK`pdg1N|q%?mYCIP*Ugc>$urv~P7jpJCK)=Dqd0f5M{g-u-8GFZXhv@DU6~x~ z7RgPl4w91S2R<;Z{qW+=wl}}~(DcRL-hFr01NBmwWjS&B-E9y5_Bm^P3c$tFdwqio zEGHK8ymIjOv&Z%oX8e>VN?BDG#}4QKy=KNU4V2Ln5B98Y5!Ol)eeTsg0NQ<_MBLK1 zb1|DXboZ?ce_*=1H?XqkdidnE4b@Q}n4Uj1cIV6k+a#I+*t%T77mEGj^F;qO3NV1N zSN8-o$s_>0p?K^w=XM{TFgr5d?Mrvw?$_qi<=O-TnZTk9859BRfBNl~or{56ZSTPn zsl1O1ec0*PX|wOFPuyAqXiDw0ta!6J zfRSJ%^9pqUr}WJumQzo}Od+vwnrXnaW;PPd8hJ_J3Q0!ciYiBLJ85(7FhnP5%^7K` znopuDAdFn&jVo4K=>o|SV65W9D|j_)Z_QcU1puMhrr>O|*4epnW^iS)HMU&evQtfg zTzcW)`jTVE$;t3+BWHlVt~BuE%^fGF9W6#V`HRpPw z(3zAmlQIG@TXVDHK7oiL1sJTk4}I~pg8&2dt&!Hj`T6nA%@9-t`EBrpT;A0+zq`Q~ zZtz9ghx`C8zHoT+=Qj*$q11t+qTQQx`+`HCxCY?dq2H#bq9Ln@bbWn{XP zl1OcUYV>57WbhOO3PlQ{tX4{~04G=5H7mkg>Fvx=Ri9ibjbu_wkU#+j87v?wQddkd zjwTi;%hiZiseh`v-#f3pXD-^BlC~ywFFIP|E?*SD>tB1UkkSF-%xKTtX#4OduJ#<6&5*>q!C zU=9i}S#znBaodiK3DQsh$#-YRy1Iwv&V1|9o9A{85t#bw`5nE3^Z)R*CzLB3eR;nO zTs=E*^rIJy@2{~=s~l;iBGaOGT;I8|BPbNG3FCHOn6*DM`+5zFVZ1ZAWZ70wRy#4HAY9-I%1`z*h39pt|z0UjIeKR+@|0bls?_aZ?D$RLV+C$IMIzf(ub zI|6>sg;yTnBznu52gM%~fn>sb>e)-${|)&)O2wF`C%8J(RDpCY&a`ju%$ncR;0w_Z zZ@jXbf@F54PyO*v09<`xTfHx?cZLF^f($+#kh`C(Quen$yMOJ{TGqc(jHLnE+I8GD(nvNTEQXBtu6gs#b~(c+xMHBA%o=y+y9NwLCGu3;?~85sJF-O_q#hqUB1` zLnWdp2Aq=#)J#6cRQz`Gn$k48q9n*Nn5e%F2%r`$)M5t>zK}%9ANPIYf~t9AmUPUL zpD}nyLO~Jc$DaM^*{?mEiCGm?Z}Mzk!9cw^GNc?c5vkL9SpW9fm&Pw`8{VpfyL)I3 zK>N}%GhhDR``>juEkFhYfYbCHWYlbL zQ0E9b9iH;~$%U)c0N5Kldh+V^%RTEciwyMiFTe519sm!Yy!sv|8tw0LrP5;RSwnNZ?}Y3g;4IBmx(jR4)oru8 z_P077Xm)*|U1zhdzMED?nJ9s%q&BQ%6$hAvvMkhbClxVMkS&$~U5fk7lZ-Jf!y>{= z@y1-txIV{eon-Pwh9ru0nm1W;%*ti367*27fzian62P?Y3%h!f0O}f&x8B%|O&ESQ zZkfH*TP||t5(i4{zb}-yt3TO0bE!AIZZSJDdP3;uO+|yXv^d_OkkWdO`PXyCsq3AE zoW79LSK!7+p1N4)$PDbi)45H}PF=X!*XrKb>)Yv#SsRi%y#U}Z|I?=_AfMAqz^(&R z8eSjlE$Ecl0CJ#S59EqmzAsR`zb)|C z`5m!Uds$!P(;iuji{ox0ie4(3{wke+(9T{%%g+BVZR{=D2gg^QFKmPWY zpJssRiH-um01e)#;&1Ofa!V$RF69yQdq%$b7)45BzyIZ@E0J><82R=idQ$=wO)|I#pScx}`C9hhbAFss#Jh4KA;LnV0LY}tBP)R= z1%^e!<1qtGK8hIwwRtu~C2w?g0B7;QsVfhh8vDC1KmG9Uyv~~o`K#uIA9hTt}Nb;%(R{!zNNZC~L0A zWXt5Tdbc;a9=5gi24rA;)$VY=uW<){$)nB;ECC6C0gR|FtqfJ~i7*QrHA0;&YqeFy z^$)-FLc@EW)EkTU2K1Mg-xj#u6YuB^6mtCC*=7JA`OF*R7yIfP z6Rx(%$oGz{tvbR%=e5!8&c?*jw0C@TduXBY?B5@}b*Wb_$#te&Y)x zu^cZ@xHIG3xyQe};I6Z00azRvXVd!JwJznB=d*ff7@9(f&1d!btbTc}>DpU68Cv%4 z4(g4C>p$vqv}eMz%>d8v)Q#7McRu!WIOx_kJ~2}$CIkhzlEKI-8M98Y$pvhaV3MGh z!OPGqPO=O=vAP_w-YlRa(}P*^CZo+H0Xi9al3r4X%~jNie1#)cT1V_NUr7sBB$-kN zvQVL=HkmarR4Jb|&0X$6tqgC-$uXSx?hikZTDQzx?pa%KmrE=FPfxI^CwS&tkD47B zvpox7+o360q5*o~!#C!qTB8ZG7Itp*Mu(5wx_!;JYwzsYcL&BMyO*P`lE6N7^die_ zO`N@Sc3^(0r6R+vJ;BHS&0E{|%?v(t(`3yJJan_ME%HA1UQ#l>BlK0L=+J;glSz`Q z+M+ET>C9~GQ#n7|@y-nlN{W^q{^*70zxD*j z3!+5-^u+@*@Yi2^VqvD~=*g=JJ1@9umpM`KYdyZu^0ZgpWV6H~S1NMnUOaH%)D<(I z2IRF_hw}eo5t|3NZ1JF(<|lS=Qt;+;e$r`x6Je6Um*JADed@|k>+D4e5^=LDJ*62y zl%Xf_ZABVE0^^GFOlt=?RGQS0=36YuNYOHQilZPhG(*WiS*SF@RMS@!$_+iq0@%PU z5Awo}Q&SDT&||;%%HKTu%$9s20LznVTTG=~N&6^f^)4bs25WBUqgP~!qG?Ry(dT%tF96Pee?8VUwCq4%R0eQk*#PJ5fCNXWX%EKc%kzAJ|CwGd%-|$ z5XJ*V&;?1NXw|9K{vvt{(KvSU+Fie=-4{A`^4ibG%+}Vw_QVmTG8~W>U3EaBf9aQ; z4gQw|v1q{8zvSr%`=`B zl|2A>UWf!8I!+8MxB*O!cNX)y&;8k7SMf&Te z9_H{2OZExc1{dD@`pZT3@BZLPXGhB0Kcn~YIzH{}*GDFq$RrC;5_A;7oGFz`tq`R9f`{o$)G4k$m()4#UjZ_fz&GI)+IU4Lc&^7J;EmcH}sGaDRf>E2`*<^8~9 zYyY81Nnk{Qp?S^R30f`{xdl?_tJu$@#M$oX4FGs$bPx2fnsQ!u)F1YI^~EQT4_xQD za(~CtW(^_(I$qH6LiByj*WUWk&n{0>UR9$A;922RXzYir57x|Yq`?b9e{u`zGEGar z`^D4maeT2TGrYQBJ;5+1mWs53u`&`3KtI`9*S~b1yU@x*Z!Bd}#=XaGCgWzku@nv4 zE1*>0?uCZtb+a{Rv1fTh$$z^|u5I=Hsb^o}bmfW5-DiIEU^-<4aOAOTpZ>j9n%mbP zQyo3Qk?$S3b+vo$cI)+vz3n|gg_#f!+qIjI=Y>O0UHrh~R~M(f^S9dk*Ep zDQwV71hs!k z?uFh1)7`_ftA0;%&35DLKsI5HEH?Dimg$~%^7X0k?S_0pp$LeTF@iM85_A*Ep*! z5CB#J*LomY?@Pb&l?NmkWEG&6WiS+22}T)AB)~A+OE$SzKFNSi9LH#^dmM`G2UShe>Zn9`dHN_QmR(45WvUKE96r>>MXIo@CT z{0m?C;Zp!?)@)JaY^Lmi9g`cNtaQS3_52QtE$jA1&y5W0&H29F3;*O@_s!B{CaRF3 z^q{euTJTEI>dz|^Gz$n=>tF8J|EZa`-v5yc33=uvAroe7K6r+ZFzLs-TPkJ}DrzX7 z8oT>z!o-S{>I~a*J&gf}D`hknXj<;vwqkc=qJjE4d$yr@-C$DDcB?HrbF*D*Up8(` z001BWNkl<$^^j@VUb`4I0fjE z)cK5j1ss-OmZ2}hF2X9oBEdueFde{&Fv}`b#;;B_`rm0K$tOnbst8U3FKb?q3=@kg zVUzCKeYU9r1^PeypT`PhVL47b{-Mj8x50tFDFCgmXuUPPp0?zQdL1u5 z|L##={i;b{1aQsYlP~DXS+3C=Elc$A4_?t5|LGvmX<_dgY>K^Y#`64!oAdSiFXkN0h#YH8HaL;y%1x;$qp3cn5l z{JoWU+D``%;^UX-v;o~fBV?fTRY=HM`e%#z)%oq6yl2}M|(E8 zYF)ZqFXVMlnOF*~Qr~eX9b2lGV31W8T5+&h89E6T8Jwj_%B34b)X6ZAq%kkTB*Cgk zy9f)(6`M)An3teevY8~?%n-zzC4qGH8K5K}n=%%P9K%WuZ*>31FVwk{;RW~nxUUkY z9Q?%Sj)!hKn$|n___GOfEa=b*aQ~s()7Lv~P3s@}-+toRwh~)*<+mlt|sNz1i)-{tw9(Z%g=FZ6}= z7Tn>(VLL_R$Ya-jkzJRQ_*to0LFH4Nk!Qbwa;1;H90-;{^7ZX zrgd9=%HdXH{Tud{hFp61*v;d=@lL?+$s|pMA_qVLw~9p$K!yxAymh5prx$kbo9XOZ zdFRX^G@UvaKosc@oV;eXXIgp#cgDI8J#}&7XWN$v2lzc6gNJXm^aKHLe3{dgV@nN0 zp(u1H*6GWoR}JY^Jp~Z?(J5fEt+k}DlWeW|@T^P8B$1p`&9m?D+S;sx^vYpnm^2&@ zR)&GFto0I%GFS-)S*@B-$XgZj%gQR$ys^)T@>e3O*ET%&v+o~j>RP?>lfBtwwRi91 z|LadH0B|&4QDiy4sj*KAyj|a~HrA1A5@-gg)RFo*Gf-oD)+0V>!{)98;wC zOl%Mmbs^X9+8s@YblZCt?e(cgK7L`z-Fgzvf~!c>)k ziF3PF<~`enX92jp(LIk$>^L~N`;iG5Sn+!vedg?szj-nivKRBbZ(w2H$*b;;aQE=+ z2LD-kEX+17%r+lBF+Ox~vcYrDAem!CBVX!n4n8t40l**dRGTExh=(m7eDLzY12=yW z=>=e>g|A9$uThr&4$|l8;K|yaGVb zO4wrYQqjF_v$l5M(wd``i(AYj1}*~SsFh2abiUQ}eJsHKf(I1R1;eAR_nHuSbGH4v z@rR;}wUv*Iyfi%W*08BQx5Kv>q0Ro)=Ju9QU43TX!Q1`A3nxDGZmN+z_`&gx)>Tko zC|S`3M^23eml{%Wi$tWfTxQEcxtFpJaP#@5K< z9k0QWDa9=tOdP;UFjJ6SzEnEy5@B)pO0#2w$!L9Gwl^@_A;DsB2${G`f?g3|#fpkB z$k2u?_MJAhBjsq?aP^3uShF%_azJ zSzwY;>*SU0rP=23H+Mby+vi$(S1gXqh0}YLgRl5K3?n%_iI(0#HM=G-N{L@tV9t#U zr{b1nzvsrg+ZO$v9S``m)qjONuiOrn69tj^+UY00fAO$?%~Rzk0}x@*6))WB=OFq# ztH01*r{s~uu!>ZXMs|{gR^_>ZH!0Y22|bA*Q<8n@kT0#CccgP@(%CA|%<|nR{rb&+U=&PJ`)X|JO-l5r<<_n834 zIEzs#0m#YxWU2K}I-bARC-Y_g#l-_}PVa&pVBpVtunow*)1WL z#om%Uy)v|(vAj9AYb?}#W`1yTy>(BcpJP;SZRhZ8*Y>4M(zL#2)AEWce>?Ww=^ygX z-D*?hgEthVG7HTRZslX?xP<}&eh+|j+)@U7I~S8{whBvuFb()r+#!Jz!KUIC8B`{2 zsqEQI+@jb?36uy{1XBhlkv|!n2)!mqW{COaG>i^~N2zvN+ng-j@Vr5E<*h(wNppnC zU%>B~8ta}M>kjxm0l!CYEVlP8yP9JFjMn^$zp-3qWx&-E+jVfVB8}OU@%ztxu%mBT zZ!G=n)jikW-BwvigRyw+VxOfhYql0xPMo;h^H+cN8<$7>=cc{e2N%LgTR3H3i8)cm ziQVH)YkDQ&RE+SaA3T3O(CIQIyBb$HR(wA@EidsLwZ$h#62mZP2EXb76V#f^iU1SR z{L$dek1xMnkzN4$vhbbWhsQkK^v^EVeeWNHctVP=h_FjAQV{cT3g85rA^4RClJzDC z@Giyfx*AbOX%vz|zoy5!y{(ayJDIsZ1USVQFIl(!Kg~~^S|1zFbe>+{7m(|l*mV!L zg8&9w79Sv`X5$bX)_o5Y$@#f84$(*SI>@B4m8jPviYi;VFDj-=j-3qtOC7XQq zRh|_9Sn6`IwK|2lDc5dy5pXspR>St?phE!m9l7=JCr5+xjhU3Ork(eu)*lieu~Ji4 zD79+WS~lLAQ-X8(9_7c{!(x-2lt`@-rBXN)^GhlAw!%i*Y=whLFf3z-o?45H-9<=;NYX<@u)SOHVh8T4RkDwTpC6h{$ z{>j@*ZIFNhuHWqhuoP}^n$m6V_r;q0)0K}7m=<`tiuVS@`te-n?Q$FR01X%jJ=u(n z7MKE9Jagyu1Cc59yY)H%ydc+=azWm?YPEOAR@!D~?8E&z|00J~9Ri%y9P4wfe6-`n zU+#=pTVSG5M3OOCseI8+0Y%aut8yCJoyhbAqraeJ{fhFyqt^Zr`>@hJH7GfPtOG2( zx~4FzLAZUgJC^FOtBv9jGF$fkM;K^r{Q=}Zhj3ZOje{rwMo7uT{_RW!D zT9Z?+j1PKubUTPJFGs8oHLZW>bFY5$KYdzjt2dDQmDiD=qbx94rNM(UosL-~fZ_#l zQ%|2tcP^>M<*t#F4V`1RY!xJJ`r?MRVN$K8kTwS&hO9v``U zz5DW1&)LfZC=lIkP}e0>(9Z;#T!!@c<(_t5NCq6vw0*1gI>j>gQgr`sxz7QJiI&Sk z&uMWl3Q!9=E3L42K!&rFj_EC+s(m}1QhF#l_uMI`Z?)`iG)%S{UCGj^vE<&F^r6`8 z@tvL7;A+Mn&iX?DM?um%b+do<^y^RVQid$~ZU_Ck7O;R_=1VDnhx%hA&At$SDU$W8 zB62Wlmi#OAPsMF!q=9t=%MKU25tay-ZL5@BRg=mWwY$;;Gys0UpxM;4rkNd0-jVTJ zyUta<=Wr#R?gR})!#1tC+b~PXKiT^7D-T}1-M#D4sdiK1{0|?LwjwiBJ8jN$xe%BOWcPA2Io0d6@TE(F?u=IvLT^i=2wyYOhRqD%| zUT^rMq>=o4)nF?x7G|11{Fyht_NCu!?g*#i<_&$4l}|<^bpX~Qbz2@J7O9hgu}j+w z=KQIrF7|gU(UNrec27q`I5umkt_};7ar)w308ja@ygo9l9AR*1uFjUZ>-V(zLLI)< z?S$j;Vdtf*>8`(x9DCGu?XCRI^U@CJYRxP|$_Zuck4}%6hpY1$DC`eS1DI?zO|~i@ zl_Par#L5C_%*WvrIuok^ZQb3KnwSP8bBFy#{~*8tC3hm_FZ#d$1{o+v3`RhJIuBVQ zFQ6IMd_TC*v&N=bV>4tVXmdfQ0|lgUHP@A(%{hS&l%H#n2mzAeeFsdGo4lrp9 zlOoc3AW14)6;&!}dLENcdd<;Cx@w4fJBQ}{(=F>!tFmkdPmC}6J^PQ`T3J+cLQUSN z#hT+Aaz&BJ3EW3M^0PCq4|{!~bj(6+GG!a;D};h>g8(T1^mMJRExR`R?G+bVB6n4y zP%N<pi`_-4pcgg^8V%KZ=X84S)&I!OKPaOUp-6w_bDXDRC^R zE&*s5`D|l;ZFIXGnj-3+V6i8di`JP&ceKtwxLtgF*mPpJw4T<@%oT!h_GrJGDFbqP z$z2k3r~_mQ98JJyp;jg80H!AxyKh|Rnmb7YdVE&@+F5Dfg3xy%+Xo8$#-%UlMgX|< z$&92|!x9PL$%~40WdS#k)W|I~EmAi2C+jaQ(^>Uec z@Yszw?L-e9Ka+6M7btq)xJ zz>N!iDjC=pYVxhF_#0PA!G>HbCs{J6a)VPq)mmV!#M1Y$rJjy(OK%_?sMi{Bsn+a^ zwO_xNi!N`H$ql*XD;N5xdpPQw6@*qJcss&NnpLg*YG2zb-XT|`g!?5@KSbfo>A|Rz;yd$(+>pON$#L9b?sXiX1a3RdKPD|!yVJ9T{-S$}-xy5H*YWkMaf@V6e@ zFW6g%$rg#(qyeOidO#@D8?PQ6xC)v-G}Qd^dH01IV~-Ahcw)kpT%U{^GIq0XG34*? zK&C)d_`BtQjuFAs*T4StUxDzB)DMj~hf%7!dS74sh6Gvw^9P3CRVKu7Ht~dXt)sZs zom)|U>F;O%ohqU!fRKE?*l-#teC^T`s@&>`Myqg68T`eO|H0As^iSrdy`4QlZRMII z(Ie-FUVCTo_`Zp=@9ggJ22UIw@97Nw`1QTMw$K}+0}WX$&NONLTY9TuE>x|AZ$^wL zjiDdxF6Qw=xJ)uGK6RAceZek+rTkwUy|Ko1B8m zA~3WhX*wUNT85S+iQa$$D(?%mZIW0{l!3M#E4Ne4Cx)+$oKZm&h*0N1mO)AA>I}{M zJ&G{0w8W5<6-`Tjsu@H1%F3Qup=mnrg&D9C)JjPL80T~DkGol*?g=6s>Pb4n$vcT(v zA~;BZ5h$wC(`yXC2%Z&+MNZYG0;+c!0E3qU`%g5DTiLDiY+ah9rScF&W;*0;Ymc0{ zGzbdQ3*PBDZ%0dbVc87~0-(I%G7U&I^23m3hMPfVW)qSmZIUI_ssn6g$K*|T6*P|M zBC$f0#_t8NIMXC;3ZW~aD{GnuZa~7Mtu%#Po3hfr5NqvTds`&5;1+9-@XQxRes*^E z%w#LAxgHr%q*vRoLz(62u_r$HsW<(Ljg_Cob3#$zKpI~2ge9iuh0lKORi&N!=($~z zMAv2_bzXgRy5J?n-z4bOp;DK5);>_AIA!@3U9K-Z{+muQdHm*$>E_l~_Be=}R|ZPF zAo)U;$yVdY@XlI1St2pI>EHYN)&I2Yb^ zF2Czj?zaxurryuhef9fK2BP(9M-@@smOEc zkw7*ijW@^Y{slL+2~-bkHu^y2LoP>hB~=d!lmrTJ zxl&WW!^f|m)U@(BbnM3FRIplwtyF57pwh+-r~q0W#qhMnYnBQb=%1Xqv?o0GfBf60 zzt#F6AOI!6=uWHxA`r7@@+l(&Yy)V8P^DQvh55nwJuX+O5Vi%)azXXJ)t{iiIYrHY z9{HCg$-hDi%xT<8wmL1Yf={SRK?5=ZZ2j|=qwZWn-P$G6*g(QWt|Pz1XNrcJSWqP2 zWnnX9!6G4=k~Ae}I6&NFR}V>eq@tt8C(J?y5Fi@$=NZ$%$C| zb-LDP2EdyN$&4Obh1}A6CXlxbca>8N4$U1naw{IQC@g4Y9TIVKGGS7Vso2kS+?*r` zwhZj=yR*OV&R4(oq<`K68iA#HN^|s|o!{|(w%eyV-U1L@bU4lFFphBKbNL0UeQW3gGc%>!pZn9Z3wk z*yN@3w*8hn04A4PLBSty1dUg2?{S*av8?6%ogGd#9nYJpdzK>|$mrT=j{=*=t%(kY zGu_#NC29Bp+(KiajF)|!ltRk@+L}&wgbin>+Vrnf zYcn_a$rV#v?@ETkHf%!X?v-|WkL;AzR?jWC|NJjL3=04LkA4VXa<;XD0hFXJ>DZ;-lkcO+ z@*lPRa6}$b(-}ITi2b=cy9*1u3kv{VG#%K#e#c!(xJwBD?nH9`on==tdU|i)vp>4% zOy>by=qpP!b-70bq@I-!Czb)aXC-#I$3s>~bS2Y~I#*>~CpuacScf141t3p==n4>F zxUU45CXk*$T#0+-CCeJmjI=<0R(uIOQnGP0)jt;QI<(`qKkji_)0|EWmK*?vn&uRx zHdgF9o7wHsr@*2}as9^SV8Zb?Z#^7XtA~yt88l)!3pm6CORQwEnsdJGA^)^THS!fY zj#v`~GFiw#EM|$5tdeqp>oE&}^_XRYh@!S74PBe0-4a!%Hkn!FomkAWxWKtxx75FS~m4({!MKocF5#UPlz`80%^Qq~r6~t)(hZ60|xd8{7WRb8qcj z3@FkI;Ls%Z;(=n!BLDH;SNK4&ULCT@Rw?qz<~`PRUuePaLG1|k%>giK zPqZa#5?hJfh7nQ|kl{KL{CfaSuc+gxrC6y$Tgp;9CX*`}}vViZZbBaqGF_ zE|)GjO?gqqF;6827(;Z2wZ5?s88%Anl!*|I8cJX>8+7ohhRc zfHzw07i-N?&%CbRu_(?oxe{ipCI~bfx_$fUpWOzK=eay@IJc{hTyCi~5^GzFa$@e> zu2xhhu#-3t1wa52zXZYh6%je?O|x~))oJInX6wgSYs?h(<`om?JRk8g%R>2E4lq;&zbxKr=RKR39dOZRl7QCYLa+5ZnMCHy8{l1DX%yUivC=2 znmJMSt*SQs)y_Rpla-@IUwGB;aXK>9{sjNm(chiw><>9DB;g?g+<*9ovnsqJO5MSz zL`!~;1t|MMp+9)}&9EJ32OJWe1#*OprQGu@kOY!F!CX(Ue4kigXk21tW-3Fv5J9t% z1rmHRKm~Z0fHH2P&4iXe{PA zu^=!EP~=20$4deukZr9%J2`^ZDD;&3C&bXqe^4;nMXkO>4j>?|$rC@=b{ z#;dxnCkq>;H?QLjrJ6w%37Embuk(DP!Gkyq$>I*jVy>)HUFb?sBobhpJkCrHp4xk5 zQ?mBjP;xC>!n&;K*r8Ax1 zJr~|Hx%$<;A6c@wRELWPDEK|~gv2WX3@8x{M*wPN4a&AmGS9PyV%3D67@rpyab&pD z?_pjz>>b_iB$%y&`Y6e#0-4K1Z*rLaHM`KZrdeBabw^YR6*%HHSF%B}rmjfFC$pn_ z%KiayVMuo~VluthdvtKM8npcB$&U^!E%4=P)fmG{w{>l>0XkUqxw?+LXkx}zyVEIy zsuyIUM<@(>=Jz!EQw1Z>3K_vr5Oqt5hN_RPm=T^hemc}Q2juL)001BWNkl z#6cFxCYHCbobsmNRs@{xR61>tl;-Y=Qot5IxlC=Hr`fVDU*0NbThWAN%~zZaDNob- z(o)0LzBC1yf=mMxWCk(=nXRV%jum7@uP31cEO9J-c+Nm#2Soyq2#_*Y`alt zSMI^}awq&cJW$p|Xp*H+SaDc~?=BC77wU4kor{64(3&-0jGHYV`^og{?x9y(hmr=9 zs);z_Bj|EOABrm4M1drSRa9-M!OE2j#!@L|WR<@c4>Zp(AX4+JjTL2_bGVV1LTE&ocfB>0RkEYVCbZQ`=94fHt2nHPzt+uzNB*+xx zN^c4sDQYj*3bzq54b)+V_Rv06xj+C4q!v#i*Q~XuGyxj8>hD#pF00YnOckK|LGTc) z2nvp%Is>+yT z)7W>enjip8?5arQnI_MAO)gYf3Qi-yl%~4CNZw({I@47b;DB+;#1zhmgR1TTx$F|a zp+g_;l>!%veag}HpSwHq;q3qql>Hv(pMQAQGp|o>-jA+i=0JYREhKnGSk>FZc3aiS z=RxX*MUC`sC?4|NA?nVC!i5z;e2o>G5fn3MJ zn~#3+&S|qy*pF$mdan?u=e$wD@3DNl`w;-&Jop&Q_|l6nm@j|%Kjgs~?B9ArI^2RO)z=mIbS1;{1>krXxPy{z#DX$_ytps|xo zmGq|43^@%vL2Ftj=*X_C$W@7eiGX(HPiOY75z zG6wwxz7G_T*I0X_Dj;KG*XN{HFO>Qq!N-QqKe|o1E51+)$oW>oLvve~?Ac1$p~&1& zWNxH;Xv90L1_BJgNLz7I%bTd*6&|mk@enH8LZ~HLN}By4YUum-ivTl3fH_rijxSvI zn>-5!xALQoE#L5^L;Z7a?&KCZv~M{cRWr%V zMg%6K*TV^vNa$4rj6?~FKpyHeUj@F>6DLSV)J=l$y(E&%D{Hnsr`e_)xiuMrrB^&a zO0z5Isy~^L_2A%7dSC&HsE+`!G{-;3SiK|hZiJw^}H;=!Ef-W zzgGqdIL6&Lhg}`|@B;7d;KCjGuul#}1|!EV-8koJ_j_H?tCfd-Pa`1sJ*~SJVjbZa zfOEV0kKL$R<8#}0`JEnLG<3FiKn)^TGFwhvAW=iLXEv2%VylXL0nlq~$c8!_5QAI+ z!`b^sfO)bBL?DkPZ^IKeFF)rx^@Xb=zGR52k_90!3?s?3EWNVFIo@dnm?9?w;$OV` zKYstC{|-i+8|Z)X%B5EZ_naKRMoSU^iK0bN<8__tR-LKvx*4n`B7f``u)@+Ukn6O9JIjT6rC zGvPsmHT6Bp4mXq4P?&;xa$aq&LDZCMDY{7ya9Gs2R246hm7$61=K%_wTm0zsg%9Hr zQcIU~T*l63OwWLspNT^+spHZLPN|k~tBssR;zH*&zqU-aV@XrkaKFUB9AE)x z36u!Pybh~Ii$CRl_S#Dw@tWS*{(8^14xDI8t{=ZMG3#~?&PT^PRhs*(w~n_8fY5(; zY0>4FZt?U7>N~<~02cMGuXH`7u9cz$3k0_>6XZ|Jk)%myGXO=hU3ef$j7g5zTUL#A ztGSRINt}qJN?AEwB^@ehd{HGDGLpEu;-*@OB{ynS6;=mC7!OSwANMi4lfHaC8-2lKroNR2JtZ(tf zL#de2TF8C=r{T$#2EV5XZjnd`!wZE|W4Df9zf;*-9cydPoqCikU%BG?`kU(fO&nQw zZRW1x>y|Zeloo(hjcWf=rhhr>_Za+*T#+jmIo6sh7rA1QD``+ckpO^|qv`J}5Q|ZN ziMdcZb!Gg>ty|}J^meRo?0oNwhMt(b9B|gZ^x!@)a_?Mxyt7WhD{i)l`|sR7Fg3mC zYBUzhevd2Yu(^^cbD`jplJEdoVoX4GXNeexqJ{ycSm^@UxEy)r0Vi2oUgIm4HO{17 zgJUU%Gy@okhNY`Oy4g_3FnaJnhUD!lp|T#;Y87Z)O_pS0%A^EZBKdz-lZq`9h$x4J zyjzVS1;Y4MVqFX1AlGIDVn9wKJd~!Fs*Y$_LE|mTfS%|baZ~lMT#IYa#48ju=6!=V z&T7DCR>RvVlisd6%><1~vm~AROI=9r4bEKX?DM-lzO~T#?i~S3{W)eAO4uL16KLWC z^>su+78GyZm5dmQc>ozbV=jmpJ^#|a;mvg-#MtUd3Y*cG&?0f$mH~DoUGh9mYjMspv7s(q!qlHC)>#izS{+KeEoPlYnSTGaT+g82+ELeYW7P&b2OqAXwnDJ&)@o-O`* zwOBv`r}pd~+_$tmHNFc*lN||tTHoSCc6lT@U&{Sx&)5^MRZi~NzBr*1G9eh4465-6 zCQ=aI23bXCr^_(|lhRJ(NifP7_NTXFC*U8|Xlc3$HHNqs+j1MULN z=t&;Bc=7%Is9G3pCM`lfWwE}xG*$q#V%=RHNf+y@UwQHM3)9nY%xqR1{%T>QS{Oku zF`%poMtC+Ub>!L|K4q1PIb>4wsPfndZt0LQ_$vw1kbz#J9L^1#8MZrn87IAOOknqgtw_;Ql37BMJI?V|5!ik ztdZ=tfH_{l>Vhh7*VuWaQB-dMd7uCkSb0Tp;8KIsH?rqyq0s+$QD;f4+cS(y21Wnt zADf*zHalLdcf|e3w>N+_pujMbdNAJH$ z3034YWVO&NR}zk02O1GEZ|}l*v0>an2J8WCAShSrzw-L|_hmA#trZ(J$DW?5tv&qC z+s(B9@cH)|=|sNWo!fp_zTF+)*m!aF(9h^gwJ4?Z$WW7U`i?>S!(+fzz{Io+@?%MI zl^zA*s$A(ZH3e5mxl_p}WH1t!)M+Y0D7h|U&U+v}9MMFqEDYAso=SW|0> zj@4cos{!HTbK9m@f~mDTi3{yUU6Bu;zw)>I(d?Bg9V_vBU;ldAbyK}w$1+nrFW>G0 zc;uWD{Y@j4rf3{7BCuh=2$9ebX#IFH!V6ktP5}$#LI$O11LfiViJ2nYNTZ*Coeq{d z;;ClCHAWLwq(&pksR6N`Oa)e%TLIP)_YFn0< zx8B?Ug7S^^a;4_jc_93=PfW9#kWY?cZd8# z;@-yv0L_D;!!Th1o?c$4I4Qedxl!k}4up96-S7U<&R>neY|4weECg-Q{!36Gnq;Q{ zsU;!=I)FwJ{2p@}k%Q%N8TTzFgM3CPK3_uFtssPxw+E_O9^MjL;lc6k{x|mUcw+8T z*|}$~KUGdw9#7333uhf^_unE#{)X3Gb-Zrv=tt=ZbX;ptXL1>07cwMCr;2w#41Z;u zA=S(^)?21ALlZ0rG8s8Ui@R&En8l!MT(Q>GvkP&XFuqTqMM%#N6pY>8WaR;}Txoy# z=+T#EcORSGLh)GtI4D7IM&Qc$i))%E~jX$;3^N62G`0LnMofcErvQ^#hz zj@_eFF+xxpiu!ZxBX8Y(J^h`-uX{QpR}U)wcSJM8RPxeh{|MHC$f1uLV@#J z^in-W1uoU=cP}jcqgPIvfw(ZW?V0cV`(`S;k;?dnZU$~BI?<6_zOk@gF#q*mK7Y^6 z#UI;uM;oQQQ7MJ>5z$(o%#9^CoUJx8z!)pW3f4oD1X6UMYd|!vIZtH$G-ZrwvT75^ zP+m6%i~?go7X1mKBF-qZ7%*!vu73*1pq#BZciHQ14&(HB@)Y`NKn73i-(62-*AuzB zwZ*;i+J#NiW$VTvTpl%>%|xo6%*8wI@$4ICc<< zmGxX5SO+>Q`R>h;YOaGH?^)iuoCcsvtz2ndn(~|JK$lvihda^^e))W-nf4sJv68O= zZmQSwjTX=Wy8Ew=|K^E3BW-bM>g>&t8!P#11ZGC{eRtQ==3Pr$?-T=0T-q#lEwy$n z^?uHm{Pq3%xozfO{Bm~7a#*UzC@*8JCV=vd8w-U^kH0y0@Y1DE&7IA6Iz1Co>puCD zw={ScrgK2+{FcIGvwn8Rc&aTvvNFGaZ6TBB{^YZZ z8Z0v4B+g9jTuYp0Z8;kXk5SmNQHYCT}A*=8ivCe0D@E#DPdVz2B#y7e^@7GS> z{F6_o{^o!SnA5A5>KVUSZ_QL&^CcCWcY)S=Ztcv@nq#jYn|<&6mio1c)}_rGKi#n~ zy;`5W(wr}ij&B6%o;)z$9%~x*y7|MsmkwQ=`0t*7U}4kEQayQKe!>XWezN=YPs=|A z8tb_=`gp29;_q6T-nBGyXN1tRSK24;$>lr0K-ONq5&YRF0Q44$#@6KkK)!t|bM3RQ z4?2V&e*2wrr82cvTbxKQjz{~*T_|dQ_K6+9%BZ~d+s97>I5Ke`j5bA0J(^_?7y{!G z(2y7Kl33RUB9#DARI%isu}@Kw+BpjTNw7*U7t2uMK|ve}RaG1XM@KPmo>)z73NkIC zXJ~+n1+%z-;$R9~hy_`U{{7XvzA%8_L1>&}3Mov;Bq!Mf5@9KA%2yqNd$nqP+VCk z-psdCMuHlpH}| zW*?TEy|VX?0kNjm+^MzB!*4fNa{`d#8}jdb$?07k%QFG2=94cR9@9f{_}xai(urNR zwibVvnq#M4JXE?km7?lOv_svcvEG}$VN-~iRoz-|%R1!!?4K|smF;KMPW0c`y zyuPuT%MG|ReaKD1@EFD@$;aNJWuj%KY!Dx@_GX$0=9D5lE{`3TerT=)#`jAGe0C?_`xz${6J*)kEMy*;X3|f3bR=-dd>tZln5R9tcmvd?CETvbK9#ca2 zK-6t45dysg3~dl=NDfD#;BM5?8M?9r04-qc@2a89kJG_CVzGv-8>`DqB?_MFbfde3 zROtjWs;Wc4s@^EH+CZQ~w(wq7-)iD6`rPV^qs%2U;)p4M+o~;3HEwfGs ziYjgm^xrjv0#b(rWeWZm!vrEN)ahFKtsPhFdPXXjo0{JFq#LW>ehi-Jar0HiFC z^2^G*FNjk?WH=6eWC#KtmSO{z@a4o_1G0Qgb>v ztC39)fNqN=+lhFZnqZ)j$-anS9lSh2H7Q3;NhBpq3Dbvgp}Ejn&;p1abQcL9hJXkm z0_Yla4SEP&!jLe$t|cJ?=z!)!3!(WWI^)tg=Tgk9x=*^)R??$dpGu6Cw{)qt)KO_L zUBOjcOUB%auH5M+y4{58@9nXzB3YUg)UvHwwgm*;L>p+=vTL>MN;lE!CK`m}`*Fe+ z04d-n5n7PZL%6#2oDR*tx$Vvfq328H`7Kdp6EEK@Zi$4|%69cf-<)vlD~iIuJkrQ^ zBbE^U_|xAS-$?%P%>Q*^+T43>{7WxA`hM?q-+c3xeR(?nqUg3uyH8{N_yKFovEp}w zw_;Obssp+X$btT1gac^-Qa~W!YW;diE2m|0p~+B`P1Tuo`cT203m@8nwp*I-lnnHKaR_lYmQx_*Jq*WL<;qZ zPAs?&WNL3px6@^Y+GA~EytkH5W%Yq3v-W^}jUFTa7>q>Vv3gQK1$~$0(m^}`_9!k; z*50Oz@WK@r9TqwP8qv31FI1b!<{jgKf3zp@>OLVtfA{s^OD}cx_fLWC^&}uKZC;I@ z!KvL>K0UWnYVvo!^yfDUi`R-*v)%1C3!NLIt52Mn4MnKQTidd}`h~GZIx*S`R&!u; zs60B|1FHFUDN+jJno~T#R8P*MCmIdOGoS^~I?w`W2GE1nfe2s%2^UET(S;sD1khY) z0T4oX&|DY^=v|l+i4Z2BH=()ECG_ZOE;JWXbym5K^)E|8PPcH44STALf5O=R%Tgi{~oo8gF zDIftMLoFeth4NZu-A=;P`*@O~NoFOIvb?f%(7E8)`A8*1ggvP#Q}LNOMd@X)xY1b6 zNnov9sjlZtpw7Ig&l(z(mG@sXw#noMAipsD0>?duY4b*`Rc4e1cQ2ns~^2g^! z9Q!&@2U@@e{k=LbB=f@|dFC+QsN}LJU18uF!$LFxZyZ6M6&wYyb!pd@rCoOlkwde* z#8+Ny&s6_zAo__jQz!qdVq$U2X_R?-qz|B^e|t@Ioku^8ZZHo z0f4jsBtik*2U?CT9a~Lj4jz4T;rM|v8H1qj;wjJR>CMQaIyQiJS&_<$!w`bC$aD26 zmNED5lF#&LbXNOSxR*8c*n$z7 z64Y`f9a{j)#d_^eKed%YIP3UP2e4d~Xq0rXUv3 zb);4Re||DLj8;_xQMT(hlNK}qgwXYDx6w>)kQ_mDmIcQT6oF>EJEu(vst<(oC7&W4 zu%fd|P#b4f1q>C`;vg2Nk&5?86P7)QSJf3blUeaPd?r%mDRO=z-CUelr+wwIv)gBt zw;=veLzXXqY2|q6>)VHste}TLhg8%U{Xc{E02!`1sZ12Wpe+$v0*?M8Hl1Bblz>OokM~g@Cs>AxpLQ zn#m&VgAnivt)Q04(vvnQ6iidH>yxup(mNL0K&lAB5naBsI1vEL5x2h3+8Ay2zVY!H>h6!4mH8v?v0d&F^{K}MB2*&U%5)c+ zN%6qt#AA%6D@mFSBLDy(07*naRP!Y{Q|+ADY1J}d z^F$PSoFF3!D1z4jS!j8q&F*|D@w1LR6~)xauoXPf1>ADQbZn1d>#A|pWvIFbv~pzYXv}53vRU#u!r3Q z+SP)je-DP*Rtt+jlW4vPU_%eH)YLE8rr)4Sr4rF;Q-LZ)dr?Vvq*?bc;^iit8Euzg z9v%=B>;CeH%D7s@u9ko(*1O9i7OPq5MEw=yH&%i1Xa4Hi_=bCND*xi4l4B=|_0IB0 zIo zt6Mbs#Rn8ie@F&==wfp@{~!Kd&%E&Yx$PIf_3*2=$OM1wH~!D^jbgd7)$;Oy{>_hF z2jl~nbAVVH^Owe4CPL%>togN39NVQ^;jiW*3^PkbRi8;AYRqhU>{rny9$`3{%7K{( zb$_4;$aq?Gem8;e;kVr<&IJGJAFKA|4yE4$z@dxc$iWUnYZEL{l(g-d^QB;X1C4aY zv3;P|Guwz{tOsC>pa4E(UAaA=Ly^3S5u$hRtmeG`<%#HCxt@Vpr}?=bH!n;ZjkJDj zb_{5fIFPrR>mI#702^sN#UtC00bM~{*}li7nS}AEr-y!Ros)9Zz3NhV!k{}Au+b_?8^r_yfu4pijSvh( zF)7ke(g|Q&A-K~*Xn4kd_=%HmXC65>yEIlmanE_c-?BWpP`m-i#fj?T#N}7^{bc{u zCsk>FTh)5>%}w8*edX<~7Y(3h99}4{)BWV#=pkvwaW4_=gBp+{!w5*#LKTiI#%R@J zO4Ea`T#tzfD4N$Y(Iyr8-4Ds~ZRFd6e7Il*4-E)jzSpCNr2)w;%cBcLp7`}CO3!`L z_|9Rh=CmlO`6%HD!(qHlF4}aWRU*NZI^S~<^HSUt*y~nP@yWF z#o?t!8jZ9nUI|8};7qB=JXV14k#jSQKkKr)Dp_?WWS!Q2{CP=M^6FB2#4WZL*V70o zs_L?$Q5YxL_(V5V9cnrd2>2R8K-UlmNC63SbU=p`aTqhfw7|K}7sok`JIjEdJhk>8 zd4+%Q>c>-VYWL*Xdp4bUtFrrlwOfzRJ$P*PhXCH%dI{JaWv88l`!}=4{`&9>9cUUf z5hw|q46v1r@m64oYU&qEL|>KTmAI>-6f3^sEjs9tNwne;-hzeS8d$8G`UvDpn?sO(rxRG>yqh zanB}L&nDj5>J!eVvlOF4aRHZN4cH;*vd^Gk+b*Cz^VD0vq38 z-DCom3hk6kY7MLjRb#>sh`Z%Gz<@uH^|`APiMACEuRnR}lP?@TvHxn~ z@?_>yb0YvApDX=~r@s~gA#^|ldW}@=LSUKHC8v4LsaLve>v+Un0y$(!MFBlt zJTTY`RT^wEUb4nYRv{qoUNpb*VxLmC|ElTOQHRY66W!9uSM;5{rx(q@_w;~B5sCN| zaj+eH3nmn>c3#2uuEE?!z`{kr;y(R0b#gaO816C%SEne0dq1%7MCG4h#}WWMJv0OH z#2Ia2lLz!JPqsQ%o$+DyxPGr>07t+eF3Aj=tI}~}Q4v9#Ww8CgJBhCHlM!EsWEZ50 zves>fjjSL-1^b6OAT4V2u;N2zl9Xco|IUEJO1b;ov#DSGqkGb|J*Z*Zd!3iQlyXxK zzkT1J+F*4s$akX{FUh2qH6YDgYsi!}l(>e@`coq%heW(|p&ZL7A*&(zRgcNxsF~$$ zMu{*OmL9e(w`1i}JsrSmu6Jy9o(_c;(^cv)8<4;o_F8hG80k>9sXHMQwh=-4^hcDh746wog&&dKlb+3 zP3v24jy?I4o%df}b0!=A<2QCb^VA}fGVvIN&Zi1omyKi$SvNnQMI_m0-~oJ>eSQ^> z2u{b-;yQe{!%oUj&A6tBvTc)TF6pe}BV+;x{~s~nM7ohoHySI`KhGcU$*tb3m4fYa z2H<_+tB=3*CB@71Yi0Kt`aiRyv*()Xx%x!P8 z&nbS^nBjmJED9x3P`n0&C+@incnifP$6i<(YXb?#UZE$YkPD>-++!e?&$P%SfP6dA zNH^o4aY#{y$9~>r6ZJ&$oLU(Mbb7i)kTb01^!!N9j zER!;MAb|iai5`%bn4%(Km+rq#Hry{)I`#rlrZa#yzA?UC|O(F&-JZOcbNT z@E*{Y5^U;`db=7E%ZStonm{E{#P6e=F5f1@<0&5wQBa8`tF+z=xKXAmlk@E*Ei*q%Y9X z5rzYSU72TENr>mDf(5{wIHobRf1Mepn$2i1yOnXTjyutSXSTd?=-`Vly!gy5KOftA z&Kg;MgCGhYJQQaPpNOzWjY|fDv1M@W7mN(IsrRu!}}zOpvCo^ z`%(S!NF#3E{bSL9r(?s1D-q}jlJwhX|3q3NMtp`Or@wK?1oYktTT|L98l&BU!3=z$ zy<+X%c_H)z2ac?)P51m*_P+V!-^lGa;{v-r`P}OKef3KD=DUagjtfmJb}}_EOy->( zueUR`MtpvN#%2!#sM>F2yH^dQfCdmsBmw~F2Tju}#psk=oT#e8Pc2i6H=rombAn7O zWS#FJnaVm7m30XXQd%C0uiLNg)G`2sV>hN(Mu93reM}P6>LaMrD;A(nuTGuX{Wb-( zs)}ooB_{|C)#J`zr{c3<@U>tDoMchDWKpyWRHMt*GVS9B-ldyre&_H{o5{XD^&{uD zJChrW6LkvUUGlMA$G!|~Frhil4;KvnHK;u6kq+P};Fl|rW~XrMRW{N}V|g_gw8pt# z5(ss4CAvwtCc*#%!9SHFnKYv=5%;l1e88JYAGfeFtplqQi#`EV2@2Z;JE8HzvpM3WFFMegUI+H2QCrk6=drn3Nrj~4u?m0QS=cIl3g*X1) zzj?olSfzP$=8YapPP#W|)(;#v*aSa~;Vt|`bd$9#YJ}Bxy1-1O^p4$_scuR2q+?$p z3yfBdj^KdZsK~LTfC4=o1Mtd~v|}%nD>=uOlo)gVv&xTrQc|wRPihVD^X&q`GrXZZ zwX<5fQF?o(GPN{uG5{WV^()y*i3dP`gKq3UXDZJYSfa)@{U^~Z8f{mW5hK@oOBIboPa-$-KXs) zi>q7;C6er0i`!ZYAmE$uvv5_-Pz{qwGm=e$!Asl&n=CLh*|fIFc0RD3ESqT=G6>|B z>_21$VS^R-^*alN)?(_E>f9 zaejs6`;VGhr~~=Umj*=mzznqDhnwaNv!~?Zbc%TzKra+hgkXoWNs6VBecZ4wjsUIV z@~Q{|7(l24!N7ke8JQM*+(x;Q1-g!1Emv&Et~+)Bz_FJ_XoVuAf@Cmg8yM^pmwFFO zhTM99Jip~Urx^+O7ThGXdhx1-aLIl*+8Hk${?3-`JMUhca_mb)Ur|ogV8u`O@wxkt z&7Pza#Gv9W9}}#TH;VvXt6Z6KY?m&msDeuQF~j~IG^r#2+@6Uz(jE}(*Q1=}7V@w1 z(mpE@_svR!l;|4h2}l7?gq=|I7?h~oyT&?v`jT`4z5y8m8H7p|JD_I}QdFZ4=0o4A z>IVu))ZuDT@h}5m%lSw-HgzXNWt?1Mj}~c$zRwGwN%*pFW*+UTKtrfQ0=QzoE};R!v1^nBNy|$;cJ{#| z2Y*1wuufq!=wJ!xajU@siMrX*jIZ-`}~&kK%l`l5G4DJEK&%mF#^Q(sf%}C z-M6_qQyE{}UfJo`?*ZD}_P3Z^U0(y>*z7AnOG5yJav)K!XrVd{R#cd1$FWx_7|hV- z93`grI#4WE?sDvFWD6eCxd+3Uxb%6*j_Am_c{)Ns81N-DKuSpJA&?lTYXy-Nb?tW_ zsqVO3S_e86qBgM|Vm0bT7Z@qcM~B(&2Va=~!Ecp6`JBeE zLdo)&=}-OX`X9x_x^mT-BuTYKH*VwXV*n1EeXO(RWV28O15Z>1(=E-90!?xsiMWH{ zSgjv}9HfMlfJCPQ7myKe&SFQhi_iyr2nivH*!<+FPdAetk~>A5xvkL=;L8}xvRkee z9=y2k!HfHj9z1#l9Uv5xr={8XE$ILVfsdVi3_!V32Jq;c4*~eEp8g%#->#AgO}J^a z3f;`k`H%c)&yQrE(PBn{hK?{qJ46T=VT^3w0Rj!tfFEdB)(}cSLIai@`vw3S;H`3X z$*^TE(&+=91|w30G7t(#6H=X_oZa>_Eh>tF{L%nbVBI8)u@)2wtRVy!c5L$HJ)U{f){=1D1G|9&4+H>)R`?)-iD z>whM9pTg?&9b>?gql>LddCYdA!>=^4nEm8)syl`sQOYacS}4w}r-3|^e{o3@?17iR zc=2<;-(wvHf>G%<107(IHJE@=q5}#dB?F^bhGQv{ra=NdgAkQ z`@TOy5UNQ!>Vg4H>X^T{<4ksAe93k;SIW`W9EZE}@_`@km{Z?RK;+QQL;lmhdS<*< zdTY-~x4-#Z#XXP+Lm+_cK^lMuO+W**5HgEEvJ{gE@(BPM8kA`C*x+^P)^g?{+g*vZ;^WxVhs@P%F8eZ0}An zVBuriCTD}O(bXHv_%x5(NdVE>wC6`|e0E1Sk|P;eZhY?dbEG;P0BfuKP5{|ZZvZXIP&JlRZwbsgpdskTpd-~y@LXW5UaXER zhk()7XdG~w5|Gh$`Plh~0Q~Ua5dcR&{*5e~8I+{LhC(dwdiU`B?o-hTa&7CmtEG7Z z_~A#NkBY5Zf&J@6^WFPT?>^-rG$Hdq9-#!rYb6$!4yG3|=MeVCeby%cu{=_>=zj7J zY$8&I^rWHy*ca$URACKBB2Xuehd?kMqef&Jg%TxLoXLmGgsf&G7`7DE$HwYK7clF^ z4zRT4e3Gsp7{6R&eSp!sOaK|C`4uwjO~j{7N&>5t2ENYdENSLod2(wIF(qKL&DA_} z8JIdSQK%*Xqfo`xbCbJHUw!R~t7o3LGYl9Sy80l?kIt}-wW+uN=C>zik42|%e#ew!QoLO{0Yy&o#z36V{fHj~_ z1$V?JY4sGrk8;i|kj$;>z-aW_wW-yyB}qH1GIep3j-m2F3j zFtI!pc1&Ppd@0JQ{M>4mNk>K;$imuGXKX1tGFo??&#I#H#A0anz@+9fz|uV@w%jO( zfL_@)Z#yO0vS7O{#d@Rkxaz3~q|M&`w;#STePP~qvP{=l2S(PW#@D9qs+2F;&g$4w zZEPvBWi#m%_gpKx4)tPOtOfP)zseU5b&X3>w@*wK| z|!S8f0<_CUOqdq(`v9I7NPl^V(E}*Jne{BqgF5 zB|n~7&jH%|yg~ueh ztRj#F?tkH#(@#AU?MtK^7JdEQ&TMPjTkYaPj?FXC(v8OUxe-9x&R!PFo%_U}Wp0#< zK%Ek~1aU7tb|9vJiB=&GbZtkCWK!Kgn>WTEJo^}c9o3ode&!EUyIhk^YiqLxx`0_x zq$)o`H?TwDsG^KySPzlTIv6CqL=9a{0!TMn+vgHM{gclLKxS%bCQv=|=A$e2<$7_! zW%2na>nc=1vPnplNd_4KZpq~>UU4DCWV6-y3WLS!f_*knIBjOu`^=b)@v*Tbld1Rn z1oZ1{jLZk%89y9h_XqYLIe6d*Oh^M8I_kig?>@b}cy|yC=qQ=#3%ft_hdma|C@x=z zJgOV#*Sh3&yG%aVWklP6Wv!fH=mDKdd4-z7!0@e*wKzoYl4Z|WUCj^7W!-C1;%!jS zr8D-3MuP1weFdGBM?=P4)ad|HgIuP8Ea3H0p4H(R6McUhnCVJ6t$WM1a}|SOqX9EW zPO^`D_y)Bvf#EKksCnSEC)RD}+Vlk#$oNcoRt6@3kNouU!0@h5I%~FLF?COa6axiy zkf^o4Qr@r~n$(SKrMzl8Io1!IAkLc3`f0&%AT^LQNuS4Hx+m9(3l;(si+AflZ~B79 znivxCRtzw&o+1*AqIBj1Gt@md-bk4xYfr>SFN1Y*ndF?6aJa_Ef*Na5jpC+vUVGw= zJ0^tIA(IHCsR=I#OwBg}H_fdV!1M!0EIOD&wyi@JaS2A=HOUDy;=@KHWxt?D(k4XF zAOck6XLP`|FrFiKm$Lp-5?P3kmRRa2)CO9E&FW>5EU zTZfG>Jb(JaG*Aa-D&sACe_K9?xjLNvpSKh8L5<` zT77!@LZ0MH0Kj%enVZe9AZW|n<5y>o^&^_ayEmpUBj*C|gz4hj!6PvCs-`u*gyye!c?Kq%Rpzs5M|6%%64qq`Ibfqw zu8l24iEe0hl8n%piR;;o_EKr9V=(4%g1&_gY+17#`DJN!daN)8njf5C(SC_K)|=E> z54vv_+n~{ZqeS4YHM{GZ3$_#XQeBGSbzph+m`a;FwiAUOP1{K^1)yt(Ul{xLzq)7c z@oR@)h#(?sW4xDJP4-fU{^qwgUETlhpZ;IC!MEea>W2kW0QuFf3XEBh+K2aDp~%Wy#763C1i>kywikWC8u& zmm@oDv$=U5uuk)R6%uRG8DTPWN&+?^G#T5OTAOND$|+#|o)h71eGh`nwbUA2w>l;u zDrMJpl=kEZunib3E>za0maR^-`MOkMQ5seOBlL`tUQQaQvyEZiHgh`@?Y81VB;IGV zM$cQFJbiebF<$yC2;0f2wyCK1qPTGBlh5t^-cuv(d^g=Nf&JB)^=84aI{wykZfkTC zeX1xLa*GQQ%4oIo-E>1^tZ}fyj81M-)n;UIAsOdO-C{_RrOH`gBpPGd8oj(WwP8DI zlc-TPeF{`@K{Bt)OT?;cH_6yOw`{hM@I{N|O=?q#5SlkoNstDlK)anc6AjI!t>ZG? z+dIa9yD+u)EqZOAJ+|YX6WxvR`g{BL-GB7xOaB9ao2QcoG%4j%{>LDq#TpO-#n*qOdjC;;@2R`qe)#&q zBPP(;aVA2cys@RFdrpiqmYGto9ee#(3hy3Xe&EQ)uG1O|f|7J7Yiv}o$+SgG!oy5D zpf%PXte`KkF`mnl6LXX{KmMnoiMi=06D^w15T-7V3L{@B>;b8Je6Bbu$)V0 zn1TX91)J{J@A8!pJ%Yl+K3b&-Xc~f!r6pNyGi23~JH~)}5dI)yD5R^k_F%T+>im7V z!!KOFaQNE0hYP9Z;g3FFt&}Gx9KAX-mRk+tD(P*YS}P?BRmtvbz-a7BJSxRBV3Z7k zQW=yi6qjtK*Qf|OWDk1WMdX3dc6t=0tB!|&rRW~>Ew^y)bk^OXQ8b$Z+)6oNI|_-_ zSrs%7q!}P2*%vf{7OC=a$R|ZQ(L94lvhG3Ua||*MCD&wE%2#biMHVWBivpHBumO}V z9vZp24?yXihh(b2=jgJgg|VRbbWntq)_FG6*{w0?>6a^DD3F~ zHLC1etb7+RKPdn`Q&a8j9!r}|VqYamoJM297D^Sm$6EC?(wlt*_)A8ti!y?76&Ki! zPA}mqb&5=qVECLmwiGI^CI^~;wlY07u^60t#N78vNbR-;1??WqKMdl#Q}w$>Fhqxq zrBHh}dJ1De`0LLmyO~~Phxvow%3j^)6|as>EM^Ffmh22t^SaZv6Yf40eeua;bDcpO zImQ>~fVmY%F5NiXWiSSE8pzs?#w4~k?Kq?FIJ36@2U@ZfzV(QHun&$#A8BJ{TANtZ zm=_hSZ_~)sz#fy%7$)j2MK|A+5FTLz0oyA+o4_I2_To+bE=@1KV+=UNflbHnnLLp; z8}L!cRj2n{IKA?jYJJ8YcS@u4Z~Wv*bvj;n=b?r7_RsD*cJINLr8(FKBAOs8v1{gy z4wFUk<07J}QL9s(NtNa!+O9|CC;^NES*F_HvN_l$W55YkF6M!jPUBS~tH?500FA|~ zQG0O_5WqERUQxZaSvJ$b9QyL55dZ)RHAzH4RHa@S70vK3u<@ue?~9yp#V&8w~& zt2!e?F#-g(V*vFlv&o6Y9lK8@fI6_sVAuo^j8rrpFxI}B;G1U%Dj2G#0#`lRM6ziW zs$s1(diJr&y(d&8e4{$kF3rohrc9p>@#vptD3q{CFd<9j8L%A3BWscI8cZ7)q35Nu zxFbubUYov7q!pIzWH0^X*W7D+b6d`*O7l9UCt_q7jPuiDd9q+RHW*B$Gh|Cs*2|@} zRN+yP2R!yeE`aM(7%AeA>3{x24pa0@(Nn3andm)q@3%u;z=uHiy)*x0cFRjBh^6|j zP>OaZf9kEz-n;*0%Yf{`44`X+uqK^=p$+6%0y_Iu7fh5Tn#HR=;Zj|SNHgifctgK&=B4w=fs+K^t#3KOR9&?JN}4h%`ukoSGv50DStc1UyM{3og3>DHnp z-F^0L)fiv)L87yZJY`h)%FE|-rXc%M9I$s6`BP>MA)Zi0hg$`*{J_ullQ~80cusJv z-?B@-0y`0xy=ETd*v1&`RjkwruyoFEXH^NhbABEu9zGo?rB8q(YEo6z7;X9pfKa2* zhiHsU{ZBmc74CYn4nE}5AkS@Oz()O?af z{6_GzSMy(baX$uwZqtu97yGvCUxv?)HMlaDDp!)w$|ZXi+T-WRE8?QLcQcB^X02FC z<;r4bW+}>-*F~qJlz%$-xlQ+N9j`{w4I?kTDn7|rlIcgFh!88k;WWYE=BH)F7(1r_ zFU?BbGcHsy7wSs!p2Y-Su%GsgARP7{ejPvXrR*@+ubDgWV_ny>Lqr30fxS2Db(n>K zMlQbvc3xJ9&iAB|h;a%rZG>_a@qvc{o*V=t0Yw4dH4OB&8L%=nI+9vHs^MuZ1DtB1 z#J+riS{SJ58h4t^8JTC$%o2}=^+5He2%6`*Y=Vt@~Y-Jd3M%Y z87d4RZ|ay>`8`%xZ{{~%)L_W)vfJv*AD9?1(E3QvCXWluiN0|~tLF1s(x4G#2_ z2m|yj6v;;$KcgKU0E$-MP4oiBYE%J`@x1UlFX-)+?OjsoD($tAN2y5|?V#&W9Y8sg zw2y751!SoPx8fLm_p<}yUu1H4HG9hxR6jWg-%h=_i-?)oQ|efdpV7kX zG%2NFRIl`5{B*WwK<>oCR`C?;S7+l$H)E~ENl;mSg`QG#*m{)LT7l`dP3zW7oQfCF z897=CkoL%q1;{|eoCsv7(QqD};jhu1N-b&~=K`J&{eCY^p)`0uwFgIsAMAqEq> zC(Gs5u*Z@2ZsBF@k(geMo0oqzO1S7oPK3niSPQgewHUE=TNW!-(ocQmnBWqM>QIZp zu5XeiJZ<7_N!j$~BHm8{XPqa4&)v_P928SUdfZ33EHkB+<52s{*RJ?PGdsoVw(9e; zlvKq|+xag9?Vb;9$a!!02ipzw^n>*k7L`E*#n7MX@{(-j!WJ{8I0NM&j|FATP&ww< zq|y$As@-p}PR)7T+W^`bA8^F!957%5^V5~BZE{lm1(VW!ltJ%cXttnJi=qx&0RB^% zMIpuy@B_p_w_8f}kLy%zLOcNizGrO%*xGpryIH@CDM%0jE``KvQ2aO`YCL`nGzH$J zJ1C`;{_MmW4FV)CgU3y;<}S|XxrKP;MdZ-Ti2J z+)Rx5cnkpCBC`cnY@3IMl0l?5NtHu0U$|Hx2Nm3%y0MNmSx$pYtou+@lY@#&jATkT zO;h01@3O8xJJ&$2Yr5%Cf5Mvs0sY!?<6Lxr^tI=tYIRw_h3SEPzQ>qmHQ%{XCnRZ~y5u!fK8^1u$4c}} zT|xzZx_WZzL~gF_>#rnf(n3Fv(Tbk>!IK1DLP9NMzK2Vs#?nstmSo=DB;*Rt9haH% zB)zucNH1CL$Xa^?_qqwI90VUCt8#CzCbtBSD#m@0QW@$NGKX6G$g-|?Nb|E_{ru5% zzsE6>5)KVA%CfJ17DOE>(~pf9HGq0b0l6jfB?C4Y29mZ2pf(4l6}^wD5K4^xPSv%N zVdG;H1eW7ydQd^b=WhVwA~`UOv3NcQ(ia@d+MZULa^AFBkK43^zP(-*Y?flhb~WXB?mbZSOM&9ANM4^LBkOsnrti4A|9q; z5YuR@Kz$kd35JiJg?W)vfms3|oZ!%0U}e^{`u0a$iKzR^r&kL1cy6t$i@>;BnOZp0 zn!+K(s)>(vDQF3`^k)d5zG|r@{8Abupq)37SrPK1famzdwhHk{sn<-+~fOa&A%dQGbiI`A^)KHf8-#>kEz?1 WvR4)u9uxpLDH8+B>-9*thkpY>Fd5$f literal 0 HcmV?d00001 diff --git a/docs/assets/images/mapviz.png b/docs/assets/images/mapviz.png new file mode 100644 index 0000000000000000000000000000000000000000..b2a1c897b22187dcbda93c58b2a6bfc81a6a4ff1 GIT binary patch literal 411094 zcma%ibx<5@^yT0L2$G<|-GV#8B?Q+%a0u=)z~CAr1P|^31_|yuxVyU~xV!82`)$3q z`_ESGt(u~znVGgL=bn4M?hTH?hyo-lC9dJV zcnI@oF_U&>YyE9~;?wJOJdL0zDG8b4UKzm{5fbNcufHxd+%ET z>uU5W(SK;x^qGTjNFkz--;am3cl~D@M19R`Pxd#u<|%?smk`*2{_{Hz_kT^OYxm0Y z$nD{GaaonOKGzkN&#q*-&yh_o!|%BRFc|zS_kVr%V)y33@NQ5mtb|MIaXeJyGIg$n zPBxAq{Bh>&^j~wwpV)ILgIzB|+8$PxeNU{KLjScsFiOsZ<>NZr^STi`YS*|SCf2_e zZ9!m6XusTWHkI{UGg_oo{Mk=c=s(N+fC|bsn%+H=Y8PPB6YM4Q2?)F7@lm~vc+mAD z5*8B5e5>AJbW;Cv{JU9@-KQhLLC7Rd^lw}BMJ90UtZX46b-&TbmDr@wXU9zow6-hY zWPc8T|1fk`fk3Eoonwk*WMr8|qV>s5p%(kV_L$8#X4a?Nwx+-!z2*Ay1d+4GfiV-{ zA7rB7{NsYf0#Mub!Qa1U+#ydfBG0AD&j-<7>>j;Cydx{l7j+)VU%W<#*bLU1pNQ95 zO|;T@G_$VGld>wShCxe9tq)f$SSNBWe=NeD+D{3;Qbc9mwlq2onzmC3+sEee-~L?-uez?aMLs= z9Nc!~)?B~hwnSu+u3DsVSf9q{;Jc2LBU13J9;u(Desg;2o{Am&Z2COwu>48%i~DAX zU)z3N%>n|*e>+#S;W{yQ&E@a8*udIT-KDhR4bP+BfN z35A7j`NN&whks@^$HxQp9|xr1!;3YNIlbWjb6R9MdaR;bZLp{7r4JdSi7dLT4S(RF z)4)bveEpj50}_GWDNXYI+Z1bu#;wGR4-kCc2J?~BDWwlbcOFaLbOT*o8&(((aKl1E zPn{6h%{eW^=N7AMG0KWd5OAg2T4u7_Tk_{F&4p!HIZIOHkMGs1X8}V8RRZ4 zqIZ0J!+iC2X~GtFocZ;gQLXF3ZLT`67wi2FeY8aJ9bhI8cQ(9{%IThJPuFQnA5NB5 z^daxP9$PcsWLNE7TE%lN2~*{K@$6Vy1YkOzs zNI8+su+`&YJ2*Ia=VJa!z!eKCx?o4zayzK#C+{~e2uVcZtdSS-JNir&;ff6-$1ezV zqmro%Qt?Nj7|!~MG~8y%<{8}Jmh}fIJeV_R_?a=+gLRy#0M=-=L3;x z4z|Zleh>?2!$~D>w%hvNPr3YKmv3QAnM>7RCDzr4+Tzw~EThBA`j)F;>Ue9+sqGyqpp0FRRO}n9@kH*yti2i$f zdt75eVBosH8_v`J_SM$Y69O`!L&M*Y4kHk#R_EwWVM_QPU%e%w#E6p$mUF@cse~g} zzBiT|u-(Kks@UnZv0t1BGMe!yZ~2p4c^kmycbteM=2*SNc?|vXhCS@z4aonyKLUfc z=-Kpl;&Q`zkC*GC$4XqI!_A+>a?srT2KSxUhL6{|ufllBJs+5{4u&DqV-vc|fD`Qy zE6b;4GlcJ=QzC*sF=lms%!{wCu2#j3Rnlj4{nH*m;r?d*f<9GUrdz3?8h9!njvFLV z&rA^lvqW!s4F7pF9ET_$GMIwH+}vi?QpVta=fTDi{7)Nx7`m^cEi5=e)@?ueIUWa; za?z((Vql7#w!?$k-oh*-+HF2QiH=n-^24ax>0!mJr={lN@uPf@iojh?t(gKXXmB!Q zM854QGRO)IG*v)u7)#B$KksqtrF)$R0u2PcJWrrtgSs!Rl3H9OgI>H_dVoal+j^GQ zf9cnNqt+%=Yj?a@TWnB1XI-n9#!I>GbF(scv zv3%(+Pu)cnRmL11x$&R{>CS_r86W0Kv?ZaLX}oretv(OGKNsT@5M(j@ef)zW>OMf5 zbh~tF+9ANU%=^$QA$6bH%HZAmRN58+lp9Z`KM7klnu@5OFh!b7SOdW`|dOE-LjA%qFH)i<1&TmvvTT>swpJ(W$7Ht3BPSHc13}1G{{gMPBai z`Ohs~_g4pSM!@q{{_7A#@ukXiV0c&|HNR`^IkaIr)utuuUYW-YcHaYdz+S-q(OR8r z+Y_(IY5y$30tBcAp5wmsUSO}fu>}V#)?o}~$$|A%(h*qhcA2St-)!SASlW@MK2mAb34=j?2+fX4={`x4i{TC?NTo(JjzkSe7 zQ)qy|+aXyp>2IJI(KN}3lb89W zXQLBc(W_^4dIheQ%Su0whYt=-n=el@Ka^qXEXC0nPd@+sp!+J9D+slK^~vz%WYB~P z1o~r)TTv@IB>A5Fq6)ol^`chSVyw;m6$>2Ahqi~KAR9x-=y`T8ThsiS)W261oh2zm zdxiei*cAJ+G;MivRAn z?`rbBU)W}>-(3*aYUB1%*6q4h+vypfvfqv0%Np^HFIpK{nRmw!)|$srq7NfT?BuV5 z?Ovwif|VvZxL-IiYPp53btf~3vHOGlf_~cmD)^=4+v;^1xuIuorR(-d>wmCyj6j`y z*!QjtwtYUt*7kTl2B52*mj<}h2;&l*(u;3G`jOB z=l48uojV}{xsW~HE1uU3DUq1GoRKlxj0$>h&xYze^_?t>_$(aovaVi#;#+k+xE?&~ zV|(>D@}C>IV{R0k&KRxJwmtY6vnKy)vAEW?ChYt{gKH zdJPhJS8g84&-vZ|b~y1qIxsJ5)K9-cA+|Yubr`Em0=eH5U9LGgyM{IF&GD7PZiebb zs=Ru91{UkfA|7G?9rV`2WM4spKIy&w??!t__s71(NM+b5EX#W*|9r|d-TVAfKKiA5 z&A@9%_2Hx}{pHz&S=ljqNO_S^@8;%pF#wOHqI6RYJwD-NQw(YLxNWGxk!9DiB{-W<9rbyCirM&f}Evs(h=ZX6WG^yo0 z$?t)!)!Xl&fLGVzYJ*Lu<2pfkc;+dYw%t)mu^5Z+(L4t-l$x*nhokM3tUT<~ zf1$e}fO*}4<$Jot=GWMU{SW^C-!?|7=XF%OY>4!)`va+jBC`f#Gftk>3GkCto6LaR z_lK86tIhvV>P9(8Aw8%)c-`PK^JZq7;Mi(E4t$nE?GPx~_;rL%dHIV$3Yr(M zHps0Ajh8FpRzwMc+Yt)SVaLd2$f>RXGAbM>06P$Uw6WRn#(jCiBEpHR0i_FRP76;= zj&aNXx!XH=s_hsbdxGrLi2c))#xDuPBAW36q`4%_0FLZPcBA2CHI2blOfe%+jW#Iz zK+;cw8tzKps2_xb%k(jghcD(MriuBE#C)1kZs2IYfw%pr+zX3|+V2jd7)&**7-Gsx zj?rBMbjsyQQ>-+w_)UsiUU@{LV!Jh=B3Mcn}j3RwpnU^ zkcObeZ>%K|%k6FOXoJYdodJm^hGAiKsl4LyT|s6a_LSka#tmNd>)XenM-x^F| zgneg^ot+&iDGQB_cfmb0vfr@9v5_U%dxL&-u}Zyu@L{CgX;CY390h<7VaS!IFh*Abvz8nqbAnvKRID0R7Yz}B zwE+lqzf$9m^aIo~*cZgulnMpSt!{!3spX{zj1%VA3z`pKuEy%E|iPy{Q14A+#2+joVA zZqPVwd}8ww+wvN`gy=DrX*gN{9DxL4Ao{O6=8fHDbt+`u5;Zv-#R8j88v)lNDcf}z z{^;U229%te82(%%CtM-u?Tt}CmWg90w84IR`Zj)<`9*4KDem8?u%$2p{Y7MnCqm)H zgj)G|v0uxKbRvM6aDNaUTRT*mkywWDi$z^A4B-c$dnO%JDsPCBze3Px7qA%o_*Q`l z34@_9dxHZ92ejf`woveQx`r(#n~)Q;|8>vDUI8vREF4S531nNfe3vS@fY!)VCw7-W z<5B*poA?EJ@v*wbiUl)cAVhaCu<@wox;P^`D{!TuY8p%vct#ODPHi*Rd<429=DMJiB|Rly?`&@ah#D???Sze$HQ!3kMTL=v zkI#b04Odzf*AAeS@`Zo1p@38{|CDrTr=o>B?A+6$;s+G^BrKalW z>20QS!3EJMVyyEk#eH+L-td#G;2vU;NuD!}Jp zo!WEu=+)_HKL`d5ITO=0567rd#L|keT=lonUEQgm;Uo)od&Qm`93QZwOQfF$rQn6> zjq;3bU&yXecttZwm9Z5)-NLi z&vMYBcsVHNXSIbP<^~|7`#@Eu94Ng3>xgK0{$;4Ni*RFqvr)ThdtfX05zuugq0LEnI`3YNz6lYqL%cFX&nOOmDMc;}BV( zVh}lwHY!SkNw2bB-SO{)Ge+Gf$AZ&D6rhN~sVs2p(6DX<_>BlkNwaxkc&6Y8u3ucP z{_j7dff6)~$gz9du}8QSRVn$1#Eok1^9V3(;bXWSbiM4&ant_N;0X^zfPckP87Nn> zY@|EKY&kb-FsZs#&)7qnR+I{s_S|q1u+tMK!?5>N!ZLMyxbJse*ayXa-7S`>Z)M3P zRb@Ia4m{kPtTjU%>X%-3IeL4ytetT6E*|lkL?pK9lxo&5*>S%M>HvXS&%(&qEtG0M zkS4^7rDFv#zxw&Sk4xTg))E9+Qyt{*f2qVr{^w_OAUc11{ z&XP}fLXtZJ{DC&$yOscXB?-5XmgyKOf=(g>4e7Fr*Ix%2B~o*P89qv{z<79Q5G$Fp6W9UDt1Iy&*@`F_ z+hpec_V%{B8xeYnM1YYT@9gAcY;SMxX71)xDSK9;7y#yL8$n8K4ExF|$cMx`Ju!#L zFv|fauv>#R4qqLIhSTszP`}I{jGT@@1@7dq2*!7vA0#w+52DK;{x)1}2=sOBbfuR% zO+S$=($SM}oXci#Ejf?U!DjhjN``|J4r2LyJNP(`kAVRSkug^ERfX+jlGjlacREP@ z{@~tZ=W{zGD$7-4{(D=T07?q=J;WBx((Fva&JOis>3Q7$5;I&1m zW@g-hVn__wUUb`h_oxzTwP;{%xx1AoUY8u2L=W6leurOXiPM$r# zdm|`Hip|iGb$5Z%JX%hsSn6QJD(ICsNh86yr%>uyzJjTwmO^O3aM?`uC&H^9}iD7a3ESdctkh?J@#IK zQVOE2^r&dkNE}e|E1D$}rFxU9y@*O`%~GNBe(If_ooM0f`A{-XOLoFb;H$ELU)a>@ zq~-$=G_|KvBb!spt=RVB{w3P;2$62+5K2!{XSY=6+~^GuaR%i{G_O|J)H+oV-yjC4 zF@@*&wvqQ$q6$O~10H|nnE^!Jkq*zC3Pr|XLWt8HPtF+Yutn zzdF_scwFk7%t?Fh#~jYPLf`X~YIaY}$Y^E_E!+M`2`{BOeQ+fQeX}DZ8^?|TlqTR5 z0kq~KSgOe!wZS#YPmR&lVN_xBGGC|vv!)zfDFZq$61AaLR8vvm=-%dc?sK!}@}LjN zXz_WdW%HaEol>r+w@C;OV?vd}O&CnDh8d6-&lM-g)#??+4>^%Q1W6ZNi)Z%xoF97C(&-7!=BEKwY>u@ffJ5Rc?1v^-~*Q|gnO)ZDE)fR7dU<1Fu%*AEN zGU=A*uV#D{WKGgj7(ajmQ*Y`+$d^BUU5!~(4!q^GabaI(KdH!R!>s6DbLQ+EqFPZW zVhW@_caj|~afA<2zdagc=wZ2WoqI{4?64nI5MVO6w_A?(f*CZg&`q$gaI05=*$MN4 z#A`LDbQCCe9d`BNM~E5CX!j!E=m%igJb(R@o3^d{u?caE1SM$`Y8s^~h8ndW%^H)o z0$D37*l70J;}GN_wnpmNJY{qu1q(;5uCDj6rPb38y@n zV8NK>cPVs;*LivIaZ)xl&T$F4*#;>_C7Q*+W0GrBE1e}I2y%&Gl14%nERSX=G!L5S zNMnYA8$H{ubJCblYr2JVqZ`EtEKgK%dEP}T6{s^Mtn=sZ$MQ$@_4a%do!OcTL<-m!kpbT;2>8Jd7!Syg|GWS1lO&@5gP(YKD-;7Z~;@IDeKWTmb)&vUq z;ziOIB>pwY-}Y0Y@QMy+qP+5^6r|mg!>SVRA;Dyh|Uu1ufXzj)?1HWfzK)=&~(+K3#K3Ywmg0g%9a zYu?~SJ%dK)ts8sN0)1OOSet4F0abExGB7Lz=wh8xH=>7PNXteQo8Mh>#s@f~rUmaV zg0|Z~v!!#7oot04B~d4=YY+2Sq$s4YQB@hWtZVnbz%*HtKGn{j+*pm|P3>`~mD0$j z-^8YDNwud3H@A>YzEW!+SaEC?>&6YtA%XYT5Co|+rlw<|fG8~&A_6TCO~VFB@rcw5 zY6K%1ApfwKLTf2agDzFS+XXUQIKfx&yyC@;1SWdyiEJ{iZ{;I6SQ|7GJ~Y86Sw!?B zY)J)*Nsy-fU~#;ZG%sMN4sF!>nKoGKpodsv<=V^{GXar8!g#$vioZXPP+g$RRVyt1 zAYCUTGs^L}53LU|3w0SzEWt8eRE{%^!A_~rU_=e%R!o?dPB$h*qa@sMfmD0fO;DIM zQrXJ^Y$|FF1#07;qPT6>2sQdBQ#vVe(-`@{IKqVxYt{=l?R8soqtIuNV$^wq z+*pgVesJkQiO3Y3ZX=9=BmT4PJ!)3+->C@jVh&3xs~&zmS^J=Gg8}zcHV@7?0UPm8 zxnI*miY;oTi9=h?MI<4VR^hl3ZCTw;3XOJBdDyC23SU1~k4X0OILv+5>$Qy(OKhK6 zhGn0KY)$_JvK;{d!Ct`Yu9z^=ofbXTn+Kms*tl7qbC-4P{Y)|zTQezQ zM=Foa@0tDAe9K~g4-OA)2}5M#uqU!oQ{nv=?udwwF_95|tC3>7Ay!tqJow$K7~o|; z$-IoH{^|E}^0Jabm$=AKVCQ1P44M9t?+NulUORv!Hq8Pcv>|KD?zSXJkoP z6wtSeQQ_vLqqtT-TicSUy%=^YH@7;?;-i)3dJQHZ_8J=-D=RBIj2w4hd&7bF+ZkTx z7*wpfb++c_`8uU)**yX$QIS5Ez;NWuBpPmCh2%_Mw%^TGT zkYKE4WW9MaETR9=TFf;4chz`56I4R~6%AhCxGZV6SeWf!csvQEX|th=TC^W$aB}}c zBv;9bYPnl5XwW$m%FS>7jPvZAc#Pg=?nhBW1CCYy6agTuWcdXhY%0=NGMzIxaanvmx9}-bX*DkFPaeCljdQ;2# z)4Z=8mRG$Lqrk<3lMtBYb(`TkF zwIV5++NHf39YszF;|OV0RHI9i{&Du>lIb4&rbX?p2nc~Rl8eMv=M~80hMT1*6Zv~TVJK55P>YY-+5gh zz6unRlXXR{C-HlP9n2YeK3&l-doq(=_h=dVY$g)xq$#g(2q-mW>y!$v5)wObThCbI zN?!^AbkxFvw)~VUO++D!VJACA7X|87o{Tm~WQiV?FQTmHDhT=shNqI*TEC1GM7Z_|4u#L}L?3?oHGz2rw_YAD zszqN`Pui|eL>-?AFQ)suHUz#&1cuT<(tbL&IT~{1%^;M5X=_7#E1gZgm{~=p++H>J z{Q4!ZE-e?QK(NbXMPh6gFukb9k1=QUD~0)jjaHCXOI)>3d)Uq5w`h>ceEb{Yo@sq; z7Cfq06_F`NtfDd*RyV9lHO*!I>`4@;o`jffkUf5iJhC`NVg74MRCq*{!cPVR!K^9J zq_SEr0AS%b;)GF1fl~4(D`amBHPjfbq@`T=h17j2#86GYVB>Nar3A%rT`x2L;U9P6 zO`m#)`7%t^(!3mmk%vj2ekQr#vlHYQhC9rcKqg^JE}6i)a=1*RCs4QNkI;fOyE3 zTyZTay(LR+krTEt?q{1B>r%}kO@QB6K7ll^XcjLV)u_rMQxqN&W*c4X<3p-T%D9W& zpk9I5&a|zCe3D7249>X|yKc?hzr0{%R)gOYV|RZXn>6Za%K6w8D;1WfVMZGY@DgGO zW??{LQ2>%QN1O#ov1Od&7j-kY;iXHdFG4D-n&n_G%-bcD!M_K0~f>krq>2duKCxQ zWIofeEA|j}!uTOGCQ7Jwp&qNcdlw;q`L~<}!l?v{WXKJj9a}%932x2XRaYMgdtKYk zSBNw6h>9xjQ-}94&_&SEJ9tl}k$t#XMi;qA={VwzhY%LWHgfQly_0pDes+$$q|w^9mbVLUXoz#qHtCLVb3(jDs0P8 z3l!ShQ24rGSv=iDoR>lgVl z_WM=q@J$cZ9%seGq;QlGRpEvB<6pj;Abn>6O8ALLK+to6fzgrL+n7GUQbICHz^P7| zDvRk7h#doWu2(i~?x*j2_$<$X46a2(WBJ9_qKNK%*FjN>kA3}hF*pzhnNzYK?71x` zYTCLz`c5ULoG1nV?H%gKQvWo5j;7o@1hi4EkCx1HgccF#Mna0T?AdYZ#T!~gHc4TH zPY=TqXxb${BkQF>*RU=9+z;9&^%!w<<%wj2MDdCr%&%V3EFE~CjC?i1 zK1ly7X!X@Ypn9uuZ%RNBUSsp>^{g2Y$(Zkr09C$(CVTu9CVU44O9SQ554s&p4vm2ildSXPX;OHOTQue=WEtCXI?C4S-Fc&e~iFLWNWrQ}UfiZXSS^ z$W+isVgB7ggvEi(%HT$+WbQBabTj(yc8-d%kamHcbZG(C-|DutI`rv|op$vr9}!n_ zmX46cRRF*{vwz%kStguX)OHiTib2qxt7|VIgY>tuc18Pe z$k1OIUqx`KwkHZ7Th#kp6;1BApM%MDJiKO7)>1BoZj^8s9;z=!G58`TTqQ_N+V0Vq zHdUn61U?Dz9Av}NiXr)L)#=@Udj7pcown$glHP-(qd7B?-D*;z|G--6EiFG8Iug(a zx9tUQeS05)0MX%b%A}n}4>y2B8W>u1tfVF1u_jyBk&KCLCUQASN)cHpO^TipslbSmqPeK-A?J34=YMCa*USAW>ep0*9Aopm-Kr1(eVgk$2kZg7iVg6oSa!18PF|i z=lcV63wb?5Iql+^!sxhoPNvZK zo|EgQZ#1&+t83q9l=0F&po14;OwsLFiiRdA*&vmJ3>LnQwUWbEEuzz9n2J-sVvrmK z(US)anU=>2PQZ7#HV)xoVa1xIacZL@Be5UDIO@Lkpf!yG&JDz?PU+-g##O~)C1mfp zk;(2b{U@fz;Op@0e)yMI8M30egP;z77fxeBR_&^99K52UV*=$f)^iyZXHmJ)-cyNb zQC{9`AO$|%w)4Akk*cE!azGEbf8|+(>neD}t+>H&0EorhPbpp*HLYYy^aS@uj9(eC zXXdrrQj5}mHH-Q{gpw;I^U=8ci4?EQ@!~74QWo{cfv6G;ykzXCuqYxF8mRxPl_Zv| zEI}IezS)eI(=jZE+j74LT{fLgIM869{-w>!1r;L5cID;{%kOeO4dU889g<{lcU*7a z;+}`;`=sCIbYxX7vYtt9|AC)?&Ev1b%d_s7?cu}z$;;@P@S>{Ubv`o{a`w8L!;_cj zL%>B}_RG90`BVFvk3&Ja&P$H`-0~CjuHNtdM!Cqn6Bzv-vb$ENTNq*uhFl}9=O|qN z1XE23QR9oP7;=KmQ^N=?^nQKqLN=8wx}?N{@3%6+oH*?Iwb@iCPcQqUoONeQecVm` zJ`ikA%n)0T|8@3n*T`-&M%N4yBh+@^%{0TtSape0N9zhsNjS$@5L4$MB9P|0Mzv;L zaibSu0`ouU*@~qDX^fR(OO9xVBv^JHetbxtiIZJS>yu(*uLP9}rSr!}5fi-SQx1EV zDWh47_R3eBO{?jZO}d$B)rm6f*388csw4^UnE92cj#2&yDRE;IP^BWB`D7~d8ynMn zcC9H}=a-Nu3n}4dak<7KCl^ax0(fkwnzo!l(luwU`dk8*|HqyT*XWVYbfyF{&A$%B zV}hshg(%Q{hb2&8mkFH3lE-neCYuqcVR3`u;`F%HA6TVSShWVX{^2Avin-GRDFEp+ z_~HV{f-Cm&oNkEQi)i}|<9R8OzU>LEmd52io=%%z(b|IvGRFvYfvHMX7CAXNz_w4j z7iuug99+Fs;s<(x=HsT~wG+N~kpKWM(x@Zb6|GRFpEj&(UA3;YB=sLOV7yYo8d_dn zo}R|td2A0rm{sLQm8g2XcjY;)KJ~>ohvyyBCzMFhkudLX&0*iPqnRyc-uDfq_+*!u zjaIOl?HWFiX0KEAj;Tg{e1w;g{*3IhRbHo>O%5MgRg$>x-L<3iYjt)MtMK_RD7sIM!J|$+FaiTw+BjmnoGiT+GcWwH0 zzaf1E&pTPLll@$g^N?H+#j0<$=Y!$%RfzRPVw?LzpQu;IK%48b*~yF1{U~JhD&Oz+ z=g4Ojl(y%xwH7iEg~#RE^Bg@S{iZMLX_xM-pJ44qv|Lf?OmCoTW5IMEgLF_Sq#P}P zvgL_yO+ChgpUO3{-1@7iu|C;H0YbIJo`l@_Qf<*zT=S=tAecq>V6)EYeN8x9CYQ zF&;ow%qW}2gjgJbWN-6}UTD7<38AP32-3@R4BD6vsFOt zcn!$fg*@I0Kf$p?%))_Ze=cvk;Haj~z#&Hr&vhV@(Rfcz6qqpeM@&SNvGVW$$_@(l z^&m9>>BJ8KVWP&A&;&E6p3$>qW#vr^;{M$DM)kL`IR*R>p)$q1wZ*)S4Pc?bBx6 znJf8GnRZUTIK%iYPQHAP55YQ~$R18Iw6Ev9T$VGa&}f3)V?kJw2sM&feQrE z`V&yoj+6?fj^r3~3#C4uNT4DQ_b=2`wpCKiEZ`)(O1TWDhY_g~l-j(GkU)|nh#E(G zL!g)a$9y7!&V(+7g`@y|*kik`i(;p9pwYi2a)&adX@9h5qWiX@u;rTr=+!pvn4;ju1sd%T1*uk$Q|?S9AW!y??u$10W239#T-de86?bSuRVX6s71bp zjS=P3Lp=I?bJLT_?BOnywog!C5y~qHCuQmuka=Nzg43L8CF>?$nISN>MR2*|3WHZ9 zG5^_h<$)v&dys`#6E|+blR{p<&3KPWJVECeZ`S-k9|O^H@gdA``H-tM(O(-F%OYS$ zPsbO>sOQEm>|!~w#^cV~pQzD_^0#70>Tfc7a9yJJ(t(Q65o-Mh z*d{v2v5{!V7|AZS40}%wd;Egk#QxvKRLH68%|KM|l4KoqmUO5gQDN=zbh~uAA~ixF zqJj8!V8+QHRmBWhR0S3qSzgt6|seB{~;W3BXLOo*Z? zjJD(5PlkrtGYW7OxhS40+H-jAE(^Ly&n*Vwy-ZT`{L4gYYroBYB9urho z-zBqMbGcQrWmP^`je~0D$B3*n<>Kv~Zmp2Ss*m>3MDho6oluaQ9dcWR#QVex%9+3F zzaYBDf<|Q}FzmIRgw6MJA2pI(-<2mk&ake<|uol>4wtsy30bHN~| zY~$S%Q7JTfa_WmK`kI#OFr^B)fe?#~`Cr))D%C~(2(u{d)ghgY1C%R;UioUbKlaGAj5J2wxR(2-XH(d z0UoYDMeHx{^v}I^UpwX*bO!?&v=lIh2#xyAOp$X{eF}w!v$}uy4*pDc?Ay)2fkAmq z4NsIs#%VZrj~0n&dMpIGhc{RqXr>nVx&pSGIj=(_yZU%5sL~-iPrsHZgWdGM2t&Hp1qOA)B$wN>+lLCp2I=O&t|_^=Qo*1g5eK})J5Q;- zxHrt|tcRAjs7DT0&4Z0?`DhZauj;>Q(wOZ1h*x90FxIEB#V;kTEU;m-q(-w5p{_Xy z*F`U+6^q}Jh@x3p4_{KRhOP6kZH9#xNxEQ51*17rcN+{#tOO5;g6SA8N=mTE7!YF^ zxFBPCL*52L-j5 z5-2cg8a@>@tVKUKrFRb){Rt0LNN(@AHQ_|8LaU)nR5~D*nf3++c?AC0N%t`?)m&=x z^GnUoBcT5acR&CSjE`T4%qThyngB6(!9PaA{-L&5xf-zSPrJ?-tw zCM+W&BULG_awozz+`n3N&sN z|GJcLGe>28S2EK1d^=fEPN-itf?b|%$Kuru-ychg0a7F)6F|r^V}14D6W36)WJlS( zzMi8?Dnf_>wAqr)m=11(Anf2E#bR<@z4!#V;NN9I6cm%ns~t*O-6yzEw8TxWKGui8_!_&z?rI7D-o!aBX$r zbUH@0h>f6&k~79b459W-O-3pv;LS3Om8~b+ctIj(*8p~sP+Wsk)(LXPEW+awZnb*{ zJK}-(WW0h=rkg1jxb+ndz0cZD6oj57@-a_X45ERm=A>O z=Ghnv!fy#iEJmx;Y0LHy)+?^+=VwN8XTDbL5HLyCI|>bTnNWU}TvRYDgx`og4JC*m z&7BnXbp2b7-?NSUofEHBa8EwmgYuil4Y*#Tn>!cjAY`*_Kd4B9uG8X?C}5B>N3BSM zb;^$l)g2p^@;)eU>e!`8e^42ig>UNQ?DwOPo?zE(h38+zCG5ffVL+2_dFo+n_=L*A z#RdM;4yRTM5+muG){{k51=vgzp@qg8ol;#0y%+xd&(9od2@b8h^P%Lol~>{p08Z)f z_ZBFO_yzQpRWqBLG(P!iKjPzN#a8q+@|-q3A3rG4b8-sn1*qqZOA^6dzkT4^Y;2y8 zqOPtV&ZuK49{b=DUE(-HN>oMhog*>Utr=CtF*I*g%s&ikx$Wu^eUvtufN=|m69CZz zAfXV3>*}iC>MbCx39Oa`GI$)X^W(%4Aj1IxITx)mUae+Uye=a0V-T7{Cp(~Il#NqR zR(|=@d&2oPUJbJq02tOYo-lmriQKlUIvGQ!vnH&^HQJkH6p*~m5wL);m5aD`O`l^X z8n}gkI1U)C;Go*Sg}a=lw^UmLLLsxZqkKaHu`o6Oi zcbI@loU%*s5aqBbumN%LX|9ZCDUhY!Q2Fmqx1ciI4_Z$t^x2ve#xIE?CiPg7qh`UQ z)Ll!AhzQhvYNrwbEoTcAhR&2_6)m$oj41tEJThb!0p3`|nt{1@b=}jx#(rk#8_QU` zqj}1`DvCFUzwbJ(nF@LtdeNyABTFL{pwrL1faC-@$d|K%fM@P{`LFiEC-X*Hh-1V( zw<1AHUZ|KxnFcWWFH-w1w-pc%K*1TSdYvQggj6ARKzUm9iq#}shmMkgzNt!2ol6*s zgi^*Fzw|eh!)@EDASycgEjoanok-NVG&~Iot;GIEkPEbFy#0@Z(H3wQyo7NLYDK|oKC zjYq9b&?s-{F%S}Y0L%jxCfNWMrV!k=M$f2`ny*pd1w^OR;RLOG=8LE-x>Q*eUiEejm$0^~&e=uXF$sU++^9c4f2o zUj6FBsDpu%M?LO@RZGJ{qw7K0-20l`LXB`aRgE`Pjx>@nMf%Pn2@3VtL+@~R`(y~( z`JXC~gTzxYOU)K*IPtV6~_w!x`7iR|S9?SBpXQ6F1f`RlhwYfZP zmtI=OFKd2}Ls~-vS8Oepon4Sx*g#WgU-jVhMMOoiJ)~NOU87t;PiH^BSB7o^Ju1|m z(u%S+{VK}I^0mwz7 zV+G1)EXhO)BbTPG-l!NhmI|vAi8nA6-#_6SM;~{26m*P-Am}!jvkU%8-}d=SfA?AY z>V1qOS`r|53ko41a!E}B4{}jU$d#LM4)T44xa{++R9ffa$k(QfWLkLxmGD7sGPYg5Xlc zSQXX3BH>cp3`nv^z*Fjp#|rzr)1giZs&cZ&(3J+VdM87K9Ml=e&$CQ3I*n>a^iN9l zOW(a<{F+T0f}FiU>~F*gzv1jk2y)}GVStGYk|KV0VjY!M+fW0=f5pCDhs6f0MC26S zVJW7zm;i3|zB}iSYJ0I1T9Sp!es`{w#VFq>L?SiJ!_a+8Rv#u{P{0Gmn7|!a7^T;1Xw(4U28pKrlGND$-TQrM}1LQ z$uXG?$X}Mo=QYYP7groFdi(Z5SM2!|r>tw6fR%?uMT~=_fd1>`CKwx7RbQAJ1rHjm zT5}%$kz)6+7U1CZ;zLrU8Y8eUpjM|;r&J|OI=FKL7|mJRuQVJN(>m=z{B9>#9(HeE zjQUoGbYOlWcefccI;^f=NBi?J719T#%-M&kISqb-;OEZQmf?H9v?HY1qjrH5)G_so zO`I>}81siDYhq+9rh<*?!eND;??$HKzTEZyD0|%aQTG1X`|um{^Ql8w|5F&7Pmheq z4cdkNQN)d*53*0=`i!5?RdJ}Oy2yRp%h`ANXB1%J)bY#3tOE=2+e{XqapX((q>JLY zlVLdRk6m72A^PV1wC=b+hu74AmJ%B&@qKdvMnDB;6D3lWs~A~Jfo#V2m(U$ zkHG#uI{%e=XUa{68i=b07r&z53OQ!=%U>IQ4UU13*OF*MYr&msvE;0l&Lx`NNBx#B zF$QI2=Dp?%D+vLeh5_pIpyMi-*GMfKL+(eP%NsN?XwmVS#cOa$!TP5kf^%vgb*Xd= zrF%i9sqj=<>1Xd_z~RV5GjO_d66QLmI@jcg0UBy~YW2Y~D%~%tvQQGJ1MlGS)oc3Y zt+2@=9&Uxi0HroK(AWL;{C-7rmqo4=-=F6`Uy$`Tf7q+SZO9?Q`y&}+e^hM*C`6kC z9YsWOQQ1iix&ex)f24@WR&jah7l5LJ9W5t}guA4YAz_^ZmKsw)((f!B82%Gshs40~ z*+Z^~KdO19Ozrp5QJ`x0R4SJCFZC1(*H!H%m%ST%_lP?1z&$6h$Xqx)XSWlbO;1nn z@hsZUyO+q~o3Z;*?Of~M*ABqil6M%$0Ow$+r&kjB+42$6T(_XA%ojN*zY#)Smfkq1 zvirYi`pT%Nzi4f`JBO5pL1GAzRvL!x?nXemQMw#bI;BAxX_W46kdT%x5djf>&;Q={ z&Zk)mSZn6TIcM+v)H%V?mru_|RBub6WtT?TN)f zROWLxQ%{$kkeIfBv)K*TjK&QXR%#j==3#k$W5jMIHNVEBLycbNZf`$EC8VTC3$C`g zkg&@N)W>zpCuHJ@U?PYVj7$aMNxdpfe2!GhGq9^3AMd6U4DZ_;?{@Pr_1I96g#CTC_b%4&(yW(*z7NFv=P;J^y!fug4VVc3$pzU`|IU2k^t~#oqhm#Yx>jPOL)-C1@TXOLwl8Y0nBfj|n6m*$XhWz8 z1OjZE!NweR`+|suko1K#XaOs-+s9`;O(XeFT4W-paz)5n+6!N0Fe7OuU$Ux}-h^RT zAR;YCoQ)}7qL0j`mW%$Hh%`!I3I^0IG6LFDp~Iv9O0$$&ms6amM+Bt=4y+c-@tt4V z3RrT_J&0gaQ1Y{toDhogSK}hwk27Zk5F7fRgFyl-4DWaX+fB~BL{FCMx`83QrXm(c zLdiBEW})}5`GxR`GBHwF)lL(6Zzw9}h@U20>1Yjxr!IO_BB=Tl2qN{(l;n@{)D*BZ zYvmDFf@$u&=U!qq$O($mWVk5hHh)G-26~0EM-bZb_EXUrs}`wwsWMBmvlSm0Ph{lz zC(^mH<&i6bQ)xYWa@B?lkD7#17oW}auAC4e$(BVDP1?O*pMjRKPLjy!xih(b`3DjG zIY~ng0B`Iti<{#`OhS4VZMq+BP5mh)XI|>X93A)RG{OfXR4^ih=Tskz!Iqjl7M{f^ zTWQm}oCjY2xp{U+YHk*O`qxm!Ry06hGgo z3;*Xj>2Dnxk&eNSIMiv$-W5DYR6H!)ET0tqT81`u4)F`YIDRtGo$m-v9G%fCux&?~ zPoulP%cq*AqH@lA>tWX14ULY<(xn6Z(@X zR7ics#x!T)$SyAZnracBp-4r0!Z&ClVRE%!cvL_iA(c&vMwVMFO@W0Jg3M%*4JV0y z3LX6!N~7Ch-2JpIiNj^@!@h(Fc~>fbYi983M*de=8r|S2G4XG5TsWA~G z#mc4&rte44G?|yAjfPbrCLxt z8J>zDLvPVMAYBA6R7`@I;0!JPp%-r^KGNtvxo^R2E%0+AKuY%wc>6ni?c3W`Y~yrQ z?aJiTvDHVfB+4>)qIVN-?d24>{vDC92w^vSIC?mG#%C-xC zOz?X*?1kO_nMA+1LIa$M2#Vc1g$-~2937-`=73&@ARyE3{Zx0!X(iHGm7Dvhf&L-d zY6acZh@seZB57Rpd&Vb)^S)*Sch8|{9Pjm>{$t})Y>IU|9FYr4QX0tOprh~|RTtU$ z$3ex`++=(L+&5ydJ;L3V0O;KdirSAf?fAIdT;aYaxSw3%h~z$*A~Z)KtEU|vydq6y zcHad>@#FaYCeRjgav-CDY~tDOpQGHSlB#HQX_5E)+eR$|( zh0J%x$_)<^Cc_COA#$^Odp5Mgpd(y6 z1ESl?%F4vI>L+G;LIafwI!Z$G7q?J1oG^+cClea< zoqjz^c}P94J(N__+jb~xv15jz``_P(=guoY%=N07T2A8^RbgAj{9w*SR?$Y@+p%h` zk3b9i__7o9>uUgLIW@0%^TmW`-rlGtotYXLjg4HV7+z@tSl0iP-&N@VY>(5*B9Q{p zgS>)*a^ok%eAd+_wQf_sg2!*Y{!;P2alWOw_-gb7uO&WlquzP-jvdM(M?@!dki}7Y zw_4PmhdrfvsZ-`^DBYzXd#0hOY{54B3o)vMHTJYGV3wMjAs2^-7cKQI|pU8LF-aVNG$kX)iiGcldO7E-@; z^@V2l+2_Ar?Hv?)$!h)F&1lGOjA95^69?O;GWeq_%NW(J37S-;2`2!7ou1*zJXOCK zbg!cvc3(dkM0|o_RStH{nU)g~i;$`~4A#`7@8%jeznl8TysD?p^QwfVwXIDt;RqKO z*DJPS+qT_A^6}^VykPKUFJ?GH{ria)34!Mqr?Wn0K`N28y1^`j~RgU zZ{IzV2sLXamg^FeL!=^e;un!@l`ZV0m^m+fEEqxtD7=M(F3hxtgk_s+fFDYy3 zV?ijLZfQ1iR*y4pP2n4*^EVI}>0dr}-(p|*L$VeWBbV=(K$*#dUzIlv4pz~kQ!*i; z<9uaxr01JSeCwvc{<1*!+Kbk;xQZa!VM_?eK4QSip0vv@d#YcH*Pn!TUJ}lmF}`ee z%gQ4xA_(lC5tce}K*_ZNOa*oE&xU?KzWMYux1gXPCnpD#_?#SL6BD5RvV^3=_Zdd2 zE4sWFh@aE9{NcWpyxZu{VE!QMq`=TD@Se{$Y~n@vp{_-l)DSr-S$@Zq1frdQrziJD zWhA|(@sgw9Rx?J0e2&9Lbw3Ma5?~@7pb%H6;~0EFMnVD*P3sA!?ble`4#AP;RiqHp zP9I=nvbN9jrdYhAbZ&QC@?0bqL4N%$%&qNp#ag_>N`w1w0-d(D_WSqm(WTncST)A{ zS-$WPX^iM^;L{{ga!o5xH_ZPCCPGt6p%wSjfQtwT$*W4>4CXD&?Q0x3i1iWFiL@!B zoga~z&?&HKo~d=tpa1MwHPJ#_xLN=Y0;$0=L@4_BK!gKrj!C)?Y|x#S(VdI*W0zBH<5u94)3ej@2zA9;sIj5^xGfTdp`Y7kO}$s-z%O33Lp}!b%col698pe=<`m>`@N8 z`NfVp8WH*z3|nDx*ni+yv-FC2q-+xt{m4sGN8!iryWtNrKh6>Pz{D9juFq4P1?*mt zk?69B-Mjq2bHjEI*7jxyY-S9il}31u#MzCUX3@9(d!u6#OGd$r2vXQh7$ zm-*s1a}*I({SWQVK;)He^F!u0P@}Hi$yz&C%fDi9r)^z33kMCXxSt!~nBTp7Cq*Q` zH*OGDkq}l^Wd{9oGOv~jm+r0;I4&bk4whC#x7Y8JTXVZ*QvpFbZ?{@trv!9Kpa|46@qEi~y7h`95aQDNb1!YIreGvIxuD(EV*))f}E!`meG|J z2y0Kp!4u*AZr8pQd`28%6g&_aR$W;%3lFaL&3Tn=XagHCt#}>-D0k=xSzg&YCQsRa zGJ-KdF_DcF+lW{O3qvs_J8i=-&v{1L(>fL6a+)gGP-Y5_i2K!!F4NA=&mT5Af1GkK z$bRbN@}WiH<(ANS*4*atJHV(!=f#^}cEXkypif7iVMdodYm=56%od-&64>gY!^RQ# z;{sERtrQ@Zm0nQ{;e6H4@LxMSfAr@cNQca&)A#27JT0Q@ebBX0abAg#1IgPub60kzrIBLc$QihiZvKNKb|J#2SKV*p_krYuwuBf*YSYH#m@>w(8OQcL z>XyTi?7X~wj+;N~m$Imr_~q+YrYe_OH5h;&N-HW3{x3ca*c;$B>fDIJ?c^KsmRP<) zx;p!)7)>or_X4k8?L#pGOVbOCfC7zZ63xz7IB))HSbC4E8qO_**A`yoAV$8D1ZScwSFFNBt0vo}rbHkYMJ&pVsMf z7ABw)bqM_0{{Hs^v7}o~NM94_B?1oeeDg&-ql&v@D-5_?H@hAeDz(8ccYq)nz;8;I z16yS4nyHyt7nr(%x$5@xYxwQwtuS1*0?FW?hnks$xt>!Z2L*2>GmjXs66nN)`1!Rs z$bvRs3sSSI=T975TU%Rer~|1l;$_+Y{0XgAVfg{?BZ&LO+a)3}@fNA5=3+Q!ipQj-298B-U-y zNul3=2}&2wX6EIYf*u(7z)lO%I|Y(v|JaOpr$!VmMJ1&b7q@Bf8@-wd-V)x8Q--l~ zmqr|mH71ctL!)<4`cp#XKQqnSfnZMmkR`lf%eRHhZ}FfaOq`;ts~UK9#g(s`(53Sl zdJbNHwAq{HDw<=BK+C=^y&chY2zruNGyQ{tq?H&3Y@H^42(@eOcedaHbk)s z&)HvQTbhp;w33?YXP9{*pMTJ+(yd$W+~66}*}M(idpY1#18kkCTBTY_@cU9!@6Ts) zC!W?iw~tQUn;BXyMm6%qK!X&ti5V2ZIQsLaSEWv0>c>>Ab`Ka<(37GJNtDEuYp21( zbp;~@fo}&#zfyb269k~7-&Z}liHV=_&RGQC)kf@bVha=r2d6XXPY5sKJkL~{=#JlD zBKkV@l54l&6?>!fAZHp}vcQ-2;O=U-+P`1U@9uK@*{das;A`=^4Oiahxq*aoI5*=y z1qA&>U$qS8Q?-)XJ~&ZRQT0Z~Z^oks|gwYxpH58-d#!mun<`z6@3j!Dej@6*zLjF>*0JG2@d zF55BP-_^TG6I0+&5zauKuB*xxJyV)pkKZF?6&}hQux6j_k`>ba-wmeM$|$yL^J`qT zA?C~{r+@+k1}r+|iFlTo@FXG-3r@}8=pP*&1=4n>W;=WPi;k08aB_jgJYTNeeLHTV@5R;XuZ$7?^PkcrJWk<>lsSH1_QaNW=2NResL!q8D;@TwWggG zLwIkou~;)QGHBw50J`vQkV$55;q(JtuF}B2u^s&y@8Vg8qW{8n-GqP=_2npR4_MF} zD3%EO0kY0qu3mtF^yO~n-IbS!_c2)$AJU}J3HW5+Jf|i63P6Pvzlv2yqmw+%9SMy2 zz@b~DE7UaO(!|4Q&tnh00mx20NE_+vu7yd zuQQcKZN1P=AbPVlTY0-2m8nT^#XdprIJQ1q!kPwzarne(UsfEpsd> z%T(sd<|(Y+V)dAZKV2`dP~H;Vbv=Rbvy?EJx7VI@+)MMAj{pNdYytJ{%-Ib=ceQfDF>E(Yp{^Z1XKsmMup2-fb^kIyGeK6SVB!1PTFR^R|b8FZ6mJ!H^AhC}$c1 z=JxsY7W1^wm6WKTkuVX)$<42JoEWj}U6QAWh}OC_MVWUrP$ca}#q7-X8(N^~azlH~ zRjCxE=kiJMeRepxOdL&@h=vT#V^g_A`|=6+CgAnoo|>clvh=3goP!LkvLE+B4F&@X zM;RBH30ODHH{A0sj2=Nkvmt#VeI9_W0_Q7{cJ}lEn5za(h*fUIr>{NyRYWK~?muUY zAHhIq2bL&^^x$ad*r+Ay8~5k;kr|HL7EXAACIz{(gk1((tDwyl-xWftm8HUJJANEz zJpQOlgYV}ZoCRGx{F^g?Nf11VkNBshl#HJ|h{^<`HB)AhO(jTHL)b;8G-uA>kneD6 znQ!Q|F5*vC{t(-|CwN}$*}mR>kRJ$EnpqvDP)5w^*)M=x+-+RE zq4bYyQ8I~o#P7eX?L3zbH^xE^nF@Vo@C4aMq>J7o8N@Xlg3|`VxL?R;;ov$IR$*uO zr>6BA*nS}9mFe>|c;E5)v$&+>n;&~hOrq{P1HciCBt@{&2_7WKN^svDf|u?*{5?J8 za;v#`usD$l-EF(?`cH|>tdM}km_5ms#J7b)B*5IAoSY0~Lk@x^sjz%7;Q8NeM}wG@ z?pMpTHz&)eC%&S2*24*tlaopy1ZxcR0Ih2qpX{eCV1Q8p9fH=_o9?%p!MBA($6lhf zC-kCTSe8dUf+~g3(y{%Nx<3BC3GcO-FH;5aJO?q6Px}KN zCnk_M1RJg3qhms2{9V7?>KQ8LWauzN@%oVFo)(rc6uyM_ULl-=6(Z)`bbE}}G!r~h zPujv#l8VW>f}8sjA!1QN8cIM}!A zkF%X;xNX>s&6wCUYf>5PkXuuO%wLg&S*R8GwU_sn5JjnMJ%E)F`XoY%D5{WvPYI_I z>CeR$x6B(Idtj^Hyp1jKh|tjziCZMoI6~>cB5gq6Y(BR|kU}&0>(R8cru~jp0bbP~ zg%6Z1L_7~&iFFv75vd+9$V+HwPtMn`U+Z4bei_ZbiQJfHetdTD(DinlyEWuDItz+e z2=OB5xN7vSyg@xEU#jc33e%(4gMG6kK--!y7$?+RA<2I-XeHs!N=YG=@`v-e?3{_O zT@=f`rPW@vlQxTZdtMS}VHk$l-n0q}Rm=K!Vpu1U*FJfMV@=MaUH2yDYY7Nm+#pi| zOZ8;o6O_L56ID!govV|;0@$uFfz6@8K?9+QM(+ydvdC05(N2q4S12CC$b6|*yGgA9 z7e!p8bi;@EBd?B0JJQ;0T8@*p+Fjv$>0Wm_88)oqWKJ0}C%Qu-Um)|RHfdP57@!jfM+t_}kgcLxR`Xb3-;BOzPoxuT0Sg!$U0`Q`B^Z$3`uX#z zznNq~_eIwOeb8lZJk9ffeBaBhUe{J*4zdJVk)qTv;uX+e`JAtdNJxBXYxDba=U%!1 z);>>0KdLi;6gOP2B`r3yC(Bfoqb=K-ng)V`zL<6ICWrweP5J!jz6ZNn?%m(pZo=G+ zlN*B%iL>7x&O0wakqYnK0t{u)pWP?CrQ*O$u;IJ8;UK6nv9+>V^#V@$S*b=3^>9xD z9MpsoKa+@ddNH4f->!RVqB?*3oMkH{NcLQL>Cg$li9$L19#qxht$o_RDaHlaEZ0j} ztQF&s1WIiBU`g_v;Fx2M@G4=+@>oB(#$x3&f1Q6IQdlf=)=sZaO~v|UmhD-?i1`4d zxcP(M)Ew5E5jfOfVf>>n$UrP4Dv77y%VD#g?7yU~zwt{?*j20)q*^FY(ye|^Ao>DW zD)j8vPh#IR{DkoM)0YcpBM6MWCSv0c3}>#o`5+ zNbxNOEv$&I|EC3jL=A#{!j*tPoE99>8O7Ks6$F^Iubu7Kn0hbjn*aTg!MF$n4<@VV zQf^138BvyP_4Tk8yJ~T*P)-ckmqciPreVFh0)OJGxl(nj;`}oO{ORgX_T@0_u>@~J zy`jpH0O;x>!CSwezp8zK?47Lqu|HM1N?a@>o(cDk%(v{semnVt>jUx+Tw8Od4{#$< zX8cRFdK&=;0p16Y9Y&JOPCmrR>hR!|EfWaUEyv4K4(mbDGvxg)UXE2XN7(_xVthh^ zQ_Xa)Ncee$mL`uDa#`WMv}Az-jv*0Ro@?F4@&6yHG;lLf7!E7YWzCrW%}S-To(&mbBJL!8!Z699#2of3%=QNm~Zh6pqJ; zgp{qj9n9tF`^|MSx~ZCXf0d&DuP;nRVzZ_U9VFY3!Em`N%;TPp$xRk)r4y(u3Q6&S z6SIF$BF~mN3eu?d@}b4cFPosaPKlms#=mgRRFnnX){x|j%N|sRjVMb4o(wSZ;6(QI zhGV{JUIlHRU&#c-^Kwf{yqnkuivV;DAo$@CxGoD}YptK`X8$trkHui0$r-}27m1XI zz~3Am9)gJE?oInqqCY;6ZP3zy)-4|lX<#4B^b@`i2SzqiTpGecOsj_v#VJ?81;an? zW+tbmK-#04s;X|)A}C6=hMzDJJ0`fG#OP9h7$QaMEmO^bbq@w7s@$dxqWiRl@@&3h#tz_^DKcJF`8bgnQcMVKsSVlh9!ZHc zKy&Qm_6#%_76%lu42t8iQ8yv@-N4(u}_mp%8u4PYan~#YH1W3n#-1}tz%{SfuK)3Nwdz`Mm_Pdk(r-R3hJB-3 z#*^jEr?k%usMShH8cSlVF|--7v(;kpAj3GhzV>__cu*jRp3k@HK<8+3iisn^H%*)!@PZEieD{tIYXfdDVq4HM$Y^{B8Iw zv>!@9reSXF*=n*_c+*v;_}BeAnF5WN}z_kRGef%k)FvypB4NE{+2KK}~VqaCL$-Nu9yhNR;2 z#SGH~oQQaWR3Eoh0Y1?6BdreL+@CY=on4toiRnwp#Hz2qjzUU3yQNIW^_NAE-j8<##wU6dda(O({k>Pmv&)l=I`OTJ) z$TdRN-lxz=ogP(-dlxmb{3B@x#)z4j%IGMBhIDe=RT3G?sS?t|`Aawx29oAEoXLe` zTDwMuk$G51h-Or1yBBbH%4DjZYqjirP91mMx30GB0kFf}(gDa#4VJ z8gO3Z%7shey&vX}UcRG63l*X!>NgOGVr#jv9;YYnvzTzZ4XUi`( zFf;qsU_A`Z0=ybr@rNW&z(~WoK3~|pZ6Hm1t1eQvaMVmEfF%43COjQh)89(tMTD@889;+N_p3(+da zb5%>oPjQ?jcG9B5q?7F)Jzz4@iC4@-f`3ljx+0B_84eT8A^4QVMch7`G)w)Zu7a>W zZb83w(Z!qQd~q(RC6kgYFlvr1#YGd1@DDP$M4*|HEyuU1ki2*l?}r6N1U7^R!#Qwx zdymdI74ZV8Pg<3L54($C3uPpqL9N3w6C~e)+5Ec{O}so?K}>gJu+G)Q77y|_(ypVH z`T?OGxsqStP`G0^XyfALy+qJ28S+Bf9Eo3R8)7f3z4T!fP0#LHV-S|Ve8yA}_;JzW|*r<*rY zn2bJjPU&@ETeh==jAi=6ooB6&$kd8VM}^0>J(533hb|Or;vsUg_fBO!ebO({bUJkJ zj%SR!LhyGc2o+j@T;ipDBmfxZRWWJEmxP`Z4|^ z4fl3IG=&NIAEr-kC{fRmIk_P85|~RPtP5hkFwhOt(b3iDDO52pYBit*`n|Xm+fbwV zi^xkznj7B_u@2Lq$-BI@tYCJa-yd$g`Vc!zCx=t~K~+jt+G);*iV6*xO^|jtD?1yY z!g%rpg&NO?QsJy^$Zw7;aK$de-pN;$=2nyS!E*ER2A{TLqRZj0M7Xx%s(<8OYuVX_ zg@ag1u{?s?O-PwC7Ib0~67ip=C3oS_>Fbd1 z?*^@aqtJj-+M)<-^QN`4zX0}rWWa;1s>vou+b2wa2=NjR{VolW%66Wf9}r8HJ7i1Y zk~_goPtcK-5j5pgdQZ&8_gAT^V~4=Z1BGiDYTQ6Zsk(&kTm)(R|I>ovMv?y6@LWAA z1L-zbRH!3%>9F}_zz_vqKL4X+)J98#pc`b3_wp0w(@yU1yR;hPcu#TA2G73=(e?i} zCE6RQ9x4b$IVOSM-~EF6K2v2+fxuZFF0O%Vf0j~O8XB1Z zp#&D<8qjA%rCc_OgSmTsowkduhl2q3Eu|~#+UDxH;)-kRFU@A|Z7NQ_1aW|zEo%Y- zDhX-Z954i6AZhn;YF%qK;wImwDwq7)to@^~!I~i<=!aFDgjt`4vYf2Q^sc0EEvwB; zSW$R*mlj->fG<|p%Eq=@6%v7Au1(|^=klb8nL$^FeQ-HeNv>L9q0LSPzce)!E)wVc zRQBoNovQN#5t^jFm9Tcbv)yk`*d!z?2o&1u-*4>OHWd|pG)neGr;Pq#2@?-yFb%&GcP4$JN{r4SB#OG>{TN|6b%kBP1X=G)=GT9HsCtjkLdfnIGVl-a7U2`s7x%tdw zCJwUvW1(Hvk%F5cnqB8l1FiN%h5c$GCuVVgVr*%@PbRmlI3 zzStgX@w`Q9WojRL5oum57P|3J6zp_<_~$Q}UdxprbzRS}kUe3`8rw#eQ8>dJ8=DdX zuD*TB4j+fQD=9=udmK`NEap;+H)`mCKm8B5{|gXhYiB?e61E+V>Q$(bnVTz{++$9P z8H&E+v!y1_Zv8HqUprseYh4Lx&-Qc*Q60>3wlg`U-1qiObc`Yt@09?8F99(jvr>h5 z$AE`I7o`;w62YLQg@W%U^Ky{p+wiqGItv$61hkQL|?M7FuT+n=vWGjwu?*^Z zJq%b6Xhx_LL4K(UmXwfaDVC-ddqI#DgOU#R8DSi0@Ifn(#ept0W8wsqLOz`vXFd#0 zgiyTjnJ0JBBUsn0Sn`*R401*t+{}S@cpDCblW|VXq5=YdN1yrRBuG6X-=hoS^+3K2 zbA)j4@1MX4^=F~mjY0JD^m^9tKCnD%$nDaJPlu~IwVPlJ$TlM$o|<#ji|5%pGnp$R z2S=!M@)%iB@;kzV(T|kZ<6;MYE6qy#$Z877q?0h>Jk5+K+%^#?vm})?SPhgp`fP7~ z+l(Zm9Y5UWE-Ndo_!H?;pG(h#9E47Jw2Slcg|>lVFV_bQl^^q>)#D2Q`crPwah;ml zIP1{Ei1Ug~l*WEKKk|udsg~3gq2>X&AC=h&A=yP8pzIu@(!T2=0p z0^K@Au_|~Lj{Pg9{COe&7>kgkJWWlnDCFN7ARuy#h_Z<{oExAb{3tn;1+?yUa&_~=gi)Zv}drD3&I>lJc0 zA#dBCBgDd$da0HpxIC$gXku(_8c8jrQI0p}G9)XYdoxLzfN>vm!LB4TKdZ6>3DYE!Is96cd?faL~bdBYU{YG|4#6 zgl8F^kpe%vMOj6zfHb^P#fCd08I_N0rZ54^dqD!kz!w!8Ysu63Cg;*Y({_bl9y2pD zr@`fDj&CtFC_zLo3@wA#bm5XF*)1<)%d=EsBu1^v5>o+ArVv#`4FE=-?mt@7 z*BYih;iX!YFEgZN+fG5X1>|6MHaL3|cK>t}wp?}YqTfe2QhpXbHg;?6x&VgNJB{tK z@q=rmcSD(4r3iSGGBqu?R70DsgM4bdw%)`G>hBBI7n1LP2j+6BAKiVdHjDgpYW>MS z=gRKyV%W(NmZQx>IXA*Jvj);qY<*VZZ(GHmr;kZeJfR`mr=t$(pDr=+a`9D1$8^}Wr%Ghb(9$$KG#G6)q z-Xf70x7A%T%fj26ngsdzQ8s@jCledAU#o$@ERY-|u2c3Uw(;v$OD7X0C)LXyp@e?N zj9)pI#4Vwn+|kX2{-SpR-iE6r{<&-~ld<-QdpeR>`ZN?UV)T$L#t;1oC8pm?A8MdB z_J^Z%RIm6=dHlkYA!QRAbrAmO5`$nU#t&@R_EU^meUDvlK&NKI!Y0V@X|`}lD#>s5 zvJ|}%k0wySGf|zLqy){MOo4(!;}0jcOT%wzjE%Y#624%C%Vj*6)VndMXt)v@Bek_o z5fl42rBa;+190B{H@fp+GlofpSry{Na{j77K~d&~X1AtlDY6n5S}5`=VHRkk7mILhuD}}!{;0s<39H| zXTTZN?;cLhfD;HIx|)1<5tBnKnJ>CJKVcCZN2K0=GEgv^?Gl3$MZ^LhEeZG5;L5iW z795TWh+;O|y^>pVm6+?mZ7jyK;vI&RMK|0Keyxfys9f4w6Yr?4|8a2bPdnP?f!k{X zF3v2GXZQlBFz%MtY3_{61of3*9Mj>_QdXAgn}ZIF8)&+o3BZxjjdUks7rnrP3%^v(KGVl zqyu(Yc~G7<*~gNJm}Kp zr$wOa&L<}7eDvKb1vvcA+*XVVG3h&YBaTQn(+oT)acrtvjQFyrNwl&s0Tv6BR>F3O zF=M0(I!iJUA0-_U8zAei)yF)uLm3Pa;wGC6gSyv66jS z&25*XOWF$}G0gnjL5ay4Qm|etsx`99mVU`?nMe2|2Z1cTDC$M~JY$@ZkfUJwm5auA zhWbyN;N}Qa`m}`9FQRkHoRt2csB^cQ;?Te%M*PD z!EIg9ULtE-q$pQ)Zl$D-yj8CfEz95tRhzW@Jp@#2s(p)x1?H*BxUWDidEYlD=<>TX@Uw z{2QQ$05Pruci)2h2y5t*7SH&c|NT_|_w%Fvm*ZjoXc!(~58phTwI(JcFdg4(GTy{2 zQfNA(3cw)rV*`ya^ATw>dc3e>RK{;$Q5W30=SNx@<%um+58HBK^^ApKTF}v;{Lp~f zr)n+Da&3Dt6H&bKaE8R2_R)kzfGdak`L;*JqXwxSC44bBxX10P6m)oVE3s8^fA{&x zew`51k`sPUu4VMWm;i!uesL2(d)eC=N{)S#w$!1++4~PD*_k{CS`uv>tdtWu2xyzD zG8p+nsJ?GNTfVeXc}e#D`7XQ)V@#l(v<^$cREZ=@Kz&dj)=UV&U`=1cfzs_KS?Av2 z3@E;|nWQkhph+rEj%Sz;@0A1wK?UZIwLBlQOI>;n%fVVHpqQf zndsAruOyoEWL3eLJ59Ft;f-X$i**{q5>2K#&fAjssRS1>z*I91yRY!oYj6Mq|EWJu zhBiD6&MIsDE8vTCC04^T*<*|OaE1YqX70>6mZ$j39gcQ+)oOVS?4pR+A-MKBXANQ@ zi%6a3a1A2qUuuiYqngW-mRx?_kSHlYvAN=NJV23n0-GMmGz zq>{2`v+g&+kf_bz4<@hW95JTbyV^fj!>n=MLfnw+O@}=so;@o~?Hj|E$!EZV4Jk*V z`L~@}*$)Uy4?o%m<1m_$Oc1FnRyxBc21` zDD|`HKM(%eHzS>AXyyXzo z{ir~^pP7UdaHUkSS=%SwWPMQ_#}yhA2e<&5n)f~LI@~Sjco-W`JpH=8gX4gf=xGkRXL)X9d z-B}NvnY{5KV`;?sN<(;zYuCNqvNuqixm{QgkYKtvIpM704SPyWdydQkg!`~=;8sMp#DZcA{WcIs0DS)ANAlr!n zd6k49S@h$ZC*$Z&9xD#NyWVciJceP33m7$`}`6 zedx|S7I#F?BpxrzLlA2bKb+Rcpe}6QDlv+1R3ELgt$vcjam}G%=X;bTF+;`)Kh+;O zVtULv);$RysnsG%7=D%FBl{;t)nFjhsEW4oes~eH(BQICAF6ctBv?Rxja!I>C0@`- zrpVs-)b{k3UT&S0K|!zm-BSh>{8BR8m-Mn#T)UQ30c<$YM?O8ThAJoGuXr2taII0` zIhw2A=z89rZedhRqUusX6{D&L308ETN4zw-z6_zH4+Zm|yL*FKoy^o!3gfAPWWhnQ zur(fw%!=;w|AeRvr-gal{b5w6^>pTG*n*RPvKpsvbWoRlz8(ZjP*|>U`p}HAs1mwJ z&q*gGM6;z4$t!MSEj21bvqD%HSV)o{)Dwu*fj3_Z3)*Ix4EH~|QO+h;vkYOPYnzp;9utw4_ZtJf%q%X&Aq)( z>AXSAf8hUic%PFECPfCU2qK_Nb}6211NsHG2PDe#jZS?y5bsgP%Qu+xks#0F?s~tt zMD8!TC|yYM5%*SKd77^{ePeWu?R-Uy8Z5T7G<0{AE%J#3#}XQAWf{M5+(1d&cXtW* zy<+B?WfGwq{gENAkc2txXre-eCe@>Tn#ln)X1JKR_8p|MO+wv4qy7S2bxXCTYtBNw znGB6_lzfd7{-7g@aj>)ujdt_A7vJLnJiW$9XYJE8{-GwZGk`xhKcktHuiE(d{21_^ z3x&J#m%2)ke+?i}Yzv}VA6QG|Jv@rN3`dI%Dc5#i-L0?pvk+xto^xUyZ!^Uy zWpOs;)3TEt{68%~BNO*78@$vUTeiMbjJ+h1ujBl4_2C}4d4EE=;cQPEIIg3&e|Y=7aldP~AHRcmc^EO$5L-nKs<6K#+(V05g@VW= zY2ozCIL5YV*)$4#)v|Pox5i4Yv<*AGJf$7{iyCim%R0ys?2;zfx;z=o-sW zAWH0L*E6GIcZ&5V?;gXp=bn<5kURP^N+o)q!Qsp)LW<6IiqHm9!&OwcExRqRko7wq zt?-to8_d7f*f!r;UGY>=Tct0!$wbAVQ9(3X zeD~7pTEzEF;Zb|r%8C&S_bS7mcd@e~%i;stsY0SpJQ|*6jBmIuL&7b#fUt&M%mJP%BXn%{@k0XN+E!%%0qUD;dGn$Yy3d z>B?;vFg9HF8$SkP+!X0pOQAesZU=AIO53KVK9Nt3ns%bX6shXVvF@92ZQ``mOQ3AC zOl%(Hoo1?G;Nok!fGpE{M+>eHI5Y-|C>-bQboTL~xR-VCwK${0!vI?b6nJ4NDI%n| z`kZNrbO`YU-c3KWM8@1?2CN-t&Hs1|?l5U=L0L!?CgJ9jD8^(>t+3gij|9szS`8c} zhdyE(t{|3%n}>UHdYYGqn`b$_ALeC(DS-?n&owD}U|j%OHHPe{xM1s|thfBQ7-< z`*btAIv(|39w(lG04KU>RvGD(xbG{{iYEFd7cL~C#kUsTm6Kg-yE#HR`Fz64eNb!O zORY*l$^Twvl{!Gc3cw%9g6Vya^%u58s8z^+1w5;0-;dVWpeH=`yla<)I50J?aYuTNG?w z&sL%2{$cE*#rA)Sse%T-(o$RE&u}W6EUEwka&7 zPi`5D5rOfL8LFf#X0i<=#5Y*3?p87c=ecalrxY_p_Lqiy|dMYp8o?Gu`C?6UF+& z&@&)isS~g>npOVyv0R=a<9;jXb_e(0_aDQ&yu8ujQbE23kC^<@DXDy$xVtX=r*sbQ z!>-(*;fsn+mUyP!w@!g!w37vZte^z~#sE&VpJD%M7oF~d{^Ba=Dv-s*NdH4WXxi=v zS}nK8T}WRUhNhLQPNj}hbM~$bbf^jGHtN-w#-j92J6>pPc~ zX)EUrmXvKhv%T3TlZ#+0q7;)RyGWxCY?h$q?$s2BSiE&jF?3o~!#lyBm7_GndZt{d zV`N}pQDvgBrL3%c`3VID!~O5pnWZshOhrk@S^-ceW)&2GD^fr|P z-53+cFa8kLJ?y{u{lndJHmCbjY)S`RzW-`gLm;z_zXy!@tn9fmRYng%~lI zB(ab{Ji*i>uRc}9>?xxyasXGDxS~LdzqExU!j;>-jsfyNMc+=3MUmro@}Omsh5)Aj<-1qnmAjwhXMI z&CK?Wmuhi#qdyLle2%BS-nL%&?Wl{bnlo>eGH!LQz?+N{_J5y&*>zxK2Jt$TTJaqqf9F_b*wS2$(z)9_U{KCTLZb&W7JODRW2oI-w*)^ zr^L`OST;(@5#F^PO6j5>F~s+VsGH@-Iqz;ms%NUWWx|J!#I(@<_7u*c9XNB3D39Ro z8GTjj`pGMDZW+kwmLB1KM%GY{_?}k4=+MUnj&_$f&?ta{>Ci%r9C6xl`2d#rb%fCy znP{t4sME5yQ}C$tuGP-mlD1(Kw>QKw`3H zhb`T%GV-5$Z{KF6VH`+$y1s$AF5o1dxK(QgL*8*sw)_m@+-+@L^a8E}amVs;HH*7I)f$tk5X)IXTA`FNAv2tOg0R)l*)`UYTfy4=QV$cUxGybkngpN}f8 zU-&MLhZu4T3a^ti5H+ue(Mf;YJLcS0bephifoY+ zxUuk61VwVd1r`+*0TV>6vpN2FDCaT?Oz6-sHdv@M+f7`B1KfgM(NRl$DM?e;f+*EC zFJ(k<@z73mTETtSGOdQgXQT)z_(KYW;sDH;v)!>-Si$1w!>m83^G+9Qfqt3uq^tuL ziSd%fW7b4SiPv#{&ncBJ8@11O7v?WZZ&%xCwkv;M3%f_BUGsrlk;*OL5+;tiP^j=s*0MUd-OlSb(^C+QG)uxVQ!5?nzI2TNhLqOnCC> z+ofaq@7JPHX{6t|&1YN2H1{J#uN!QQB*cTlex5yn!x8urgPtAz{9b{B%An_1SuK@n zg$z}ymz^Xr6!Ro+GDA3w_u~e5a$Cw!JV>xFF1*=hwGrl%9llSSfbHPxLIKX4W}S5) zPYS`-YXX`ZFz_Paarz6yNT2tUW0U&wql;OzLkmP`FyXsSxv7-aHlLPVnh5vB=)bZW z@F6IVOW zl!-#S!DO`Nf+BiQtN{B7k~ly!GLu337sXpjn1u5N8&(uY%PI4hxN;*rV$_dfL!VdOTPjq#@;a?eZvWtP_f{P64A z+{LhrG7YQmkKmgLxS!?xDhYYv^kn$~O*+u5 zK`g^qzULz1pg(=nLJEE?Yy}~6{2xW{@qUE&y!Sh8-tWPXgR8Eq18I!Fn{@Ti#@ZKB z^`FkWLx}-1D#S-H4$X1$>f=XXTf(-k_bOKh5qpL>2Q1gVoj@ag3I1OE_W3j-6H!*GJ{ zi2K-(zY*###k~HKw5X25uT4mfKD4y@J)Nz4AxZd#IO*QxLX*`Jn+RmSCnvmkQ%(P* z$v>UpF}+8Oqn5x) zKX*wO#K))9cr2TY1PPWG%eb29sXrD2-V|_wc8yUbH^5!n^*cy7&L@v?fQ-CIit9J@ zQQNmvoCNP2;1aTdJk()=&E+mUjfsv1YA>sDkS#JZqXLGkK-nt+xjyr5w`<|~6>$z# z&E>59ZXL`o!AG$MCJ_MVH#av2J{+L&$A#Or4ExBUn0+bwaYoU54{M`(@o1}`pTxRR z=^MYtyEK0^dGnFj(xSig^aDR;~6*ip8LrP>fC!7~3&r>3iJ>pj6np z->0DH`t}nFT^)yFwtKZN9w9vjeLJ%TYVRG2Qkp1<0b-o`Pw%LWtk1YFW&%s9C3O2l z(g{}@4OZX7{A<@kfrV}SQZj2uy)gcrD@}%y4D19q$~7)%Tb&Rl@^XoFqtd-dpY#$a zu5T}o@cF7YZL8g`=^Rtc9SqNbd}7Jw{oRfjfq)n0vbZtgpfXmJczG{(!rTQvSDN#c zCv)1BQ!~Lp6n;6#Lio*vU+#u6uL~fL!f;Iec(G8bw7UkISH76?RZ^v7*;*s+^O=1} z(b?Gjr7f$sQknGO|TxxZc+E zeXoyDm>xppHQN6+zO7tM(0_p6dwsFrczk6hJWg)Vy?P#n5$b_eKKth0zCHOuE#&tw z;ceCvwSL}EB6Plf=VSPGvD}5b;yF9IaXxZXB9MREvGJA?XZO~8b@sMjNo1pT+jj5Y zw)Jn8`01*%bJxTD`9tU99+%)-R$yLL!yCK*P4}eVlbUvn{`r_j`<5wi?uEkuM)L4V z*`&wCylUK~N1@9

    #uZ@T1tT=@#s{U4G+)&1g~U0MW)YB#-tMeZ z?szCjjgMKf%8A8~3=K(@s-cU3OO)+eiz`kruiNn-AfN)YM#Whta}0Jj0+|uaSb^;& z3l71jrAYuvXrA<5zXC3>e6R=f+2`Bf@i;dCzU&`Ju~?h$>5{nVYJePnxF*@K8zuM* zw;7=Vf{3Du9@o1OmkK#BF^hXU@jCcb~_i9H6fgM48x%Zx{`7JYdT zi`wv$Mf`BaGlX~EQUh$!k7^JKk9qVy;H$};IW;MuXhly;NHK;R3|5dA`Tc`OLubO4 zuvR6w?{vIFso-WGlr*;6dF1ooTdKuAh8JD4=j6*~GGj0jQERR!D@1q1DIMpaZcbAc zDWJrVKIByS3Yjct=^`P-ygD36qm8~nZq0L(Ii#Tu#vZ{wa&1#paz64|FcP@zQ zn?7q^Ph8R8)+ZeW79G(z5syzk(E5TsB(Shou35Uatm$>e6;k{hJ+IN30NRbIznhO5 zbShRn3dsW`NjlWF&Z6lY*tpKhWj?k3W|cohq}Zm`#AV!tsb>2>EvHXe{1E*C5;GkG z!;n9bWh9U6IcY{x(GE!oXV%p*mE?|zm9`%8bY96m`5jFP-S)W)KHawp@;ko}KgSJz z3AXfqtK7I=EXlpui|epW^S&%Q^P0_l9&bQ-S;*PbSbsfjZFrv8=-e5(JY;Tvx$9VZ znPv-mey}Izy%RX|Jduc#+aKC?t@OM*JIz$PYV<#kIrH0JWcC(H)mBgohIu$=JvO} z&JA`nqQ`6d_5-es`(Qr7%WFrn{0T_?gN_G;jmPh-DIo$A3u(TOSKX?)ZYyX0PZ(Tk z|EoQBuLxEtPa8LhZ*HUV#E%PumH2#5MO^Lo^OYNpSCYA-R}kG7imwCqFDnyws}D;h zF+>l2Wqy0PD}3t0=l&21zToTTT63B8y<3C5G9cr1Ihe{3@D4S6G~StuDk4)#JA2Y9 zt5|r^Qw)QXQiQ->QO^*=4Dvm(3jjNFnh#v-~HvmEbzbaK%hm9)HgXj-@ZuEIj zOgpjH!4DLlO-N?Hizu-2uxq;*00!Ju@b3dFvCX3M37bTD$3O8%<{Av`$2Aa7N;H@Y z<=T>Bp#Amp%L)6(4L7{*PqoJ0pBO{3w78KeesEs;9A&U31 zFgS35E=N`l3ta-AT=i;DhDQvr0D=uAS7w`M|26xM^SizWunv5g|u7Guq zCY&N6@$&;_38hSVefWpFeFDMPnJ1K`#%JuDyX&w!J)r6=LhT^Fehjj!T(oQKMWx0* ztYVw^9QT*$(36{-AwB1SLn#1)HS=DGBE0YM=15=?$V37C23VZ{l5W)ycsD>GdG4fp ztFGE1s`V$x{R4w&s1Jn4baNz$p#A5q1{!v9Z2s^o)4{<(Qd|3aEgKE^=-7p?CKEXN zk-t&UlJQs@C4|*YC{=dDDgCDCAG46RJQ6&-v^C$*{&=~Nt88;>IpVoWRgy<5NU~Gv zWhTq~V^xMOtKZ=+C@A3mW#M=}$GjXT0vDaMu!pz7{Q&hm>x!N8Ef$3C!r* zVJ}PlA5#S=h38(o_wCZSUJkFAa9qP1)~=%zUyg~_ed=1b`ZVI?IuG2Lb6ucqeJ`2U zuQR-f9#Mo2vi)1a=7zACms_VX#3&;7bvn63*fiP>mQ*X>ZX;gV7d}P|Ww#t++x^i} ztGoHvekA01g~Z(EEZLl{MP*mA3hL1?rBM%|7=mvck;5f zgnCq?{l!`1rO+@nvuQhIvX9ukebaT)|BT*_XW9F)NmA_LO8>QHbZ|~)q+W6vVCQ?y zKiYfT*{`u=lP_OJZ}^SF<~$#seaiKAeWpooznMj`@jiLVt?5pxJKBGJn(Vl1@CL;| z5l!WdwCou{|GvlGX9xdip`sgak^$~?lv@*!~*Kee?AW` z{QK<@P7<-y?#+b;?AwIg4giMd_ou8cl_Sr7)Qp@{bN@5yarD^}@!LJn%m-rs{#t9c zKamZ_J77!A=kynjh|afO9#23mHIua=%3_!6dWyWk-=@OWKUT*E>GGgQJI zq*9>P)5_qURw*-t4K3bO5k-s2(<9p<>eq}R4x`fT2(6OTeU>F&Q@@I{wbKQYShQd_qPqT`##c0J~ENPkq+gaw>Kbrl-Y6wE~1_t3-95ehC9@7~V00)4A7UUE;VR# zlN>6!#TbWrR69$wp7BfY6&@FjygW~ly)dSE>+uL^Unc${pqIw)%ZP!RoW9WS=%#z; z?Vg;Wl-offGYm9%niwnw0SVuYs^NC97hPFx@HRFniqupB0sj?sW zF4ZP4bIYjGh6IBV6ZxDfbc4zwG^B;B5@DIq)4X*oEp@KkZUe;r9(#y_T7{=sPruwd z4n@@@ilhb^6()9hP#;C{SbJ2X>5DuWSAJRKN9fmteWR#<(d=5iDnmlc*KfJ$7Q|tv=OpICGl$*5!5>_J;26;yp&6lP_w4l=38! z0mFtnBO{kj*LgL%Y&C12kD${b!Jq{26tZ)2_H>Bi^%{PBYp-HUvvJ19RWoNU?JaDQ zAKTGyv{_PNO5@9(046s;zc|k59K*DsN|>8yl3u&GKw*V@s*dwL{#917TxHk`LT6@k zZtH*t&>H~GvK3%kgR>U5$ZT=E%pS4sgZ4c^m>mE}e0~Pm)(wx81>cASRU5V`|BY$A zz^>%?HAqxX7MJG^|Fj5Q!PDud)KHLPG7`bGL(DjAFSLr30o0rwZr}yDYFoWLUbxz;Wx2bJNkJm} z>)&M`eT>xE=mF>N(7w=N$&t_$0e#)s)7`4KMzVbw;90ON)1{53BmiUN1okE1 zCQaMS;m4SjEm=~JP%7bjC_Dr~oOU0qlc9?Z!6=J}Em=xm5NA9i2HiyeLcL2$PT-0| z{dqUbOj1xkwJcT&vrMC5NY`b74lhxmu$;3YRcaKcu?sc?$hD-&Y#jB><%1Qf*m~fK z=tMD7+E{*PyMC2`vfg^Qj9@N!(de%8I#4!P#2^=)#;J2_e)iVSc*}qAY@_VoxxlW5 zDQ0Nhf%Q5_EGAGhAk@=b`O*)2)_EMaekZvf$NM;Du79`8=ikRx!1jevXiG!revh7R zn;NE;=rH#YrQ_|BzvI8%+~yPFJGJcBcKha2%G$%PiIN(mF}7Ol^@pNwuh?l=C&XL@ zbdoW0alwtuE}yZ91;1eG{7b_^bZP|7ii5c2l)Myf6?HPQE=) zR^D$94wTxjHdX5|iJmUmHBPV2X@SH^^>Wb#pC9e0DB5Jpb50U4-`Qop8=_=jc1k3QP{ zvI)Q5;nV9l*M`sdr$s1XC6LPQqh`H+6i-5Yy;4ju$S-+ z0@Pj$)1DFQeg7X`cGAqPaW!<`aoF~8Eo^B)Yq zk}_Sc&n5+&o{R2?>&_Asb-lV7)ATgy(&$6}BNTl9Cbd&z$pPr0&QrwPu{)j>J54G- zO|(+P_|r>*N!(B(TtA}8r6rK?63vTwQbtJGY_y@>G5{&a%E{%;2S3bl4kqmX`4rCi z&&XlP#+0VA@fSFse7`010mFLr|HlMy=kVLKdtU7sReL;MAL>;$I?hTAIvSjZ(W<;t znnKM`QR)lzOGOn*L`Pyjz_rQZLBJ*b3RA3Y7bm7ph^h-C8ffX=j;{QgTm_9oKZjI0 z_$^xYeYYz9f(+J;tlJ5Hr6vQ=vIbFplOjYf&?^7$vQ;`YJ*_+j1MI5)XA^X2U$XaF zo}Da3UDP0s0HUj_InT1RJ~XRXr8FQtH!JI}<_Au~J14#WAhH0u&67Ln>fNr;xOnIW z6fW)R)*S!J%`ng=G~I$xdEsK<@rCZT z;#PTIF0DDSg9Z*EQ5Y12F1A1HvnnRPqS_RC-}w3U#*ULCLti!eUOQ96YCPk>HdXC| z7sl^`xZ~;2|LXCGYv0Q`tfRKGc7H(Dcwgp|>&fJ)*HM^|@8;J^J|T_Hqk>%Cg^eos zK>tYY8{*hGYAUM#gp-y2FGpP9s2v&_ie&a1%knB!1MwdxZul@QEaJ*CjFWdK?nK2E zxVVyJx<#7$-M@sj;ee(DwXE9pXyHFhbO1IE(F*56V|fjGB=(B^-vn-5tzo>Z89@qs zF1z3AWj9_g*N3xJ{?)>a>?63}pg!}@PG;CS?Nus$U3D5|Ow)B+`X5j(GdXY2b|igp&G?;Z?%%zHM-} zP_JYCzWms5Aqeba?H`EB#R7GrS>S{!xt{}w3s$&p^Bhd z8W%47P*H%n5*`oSAw_i}$3SDdBVa2>he}N>6u64&^f(Jzu|o1&vA559JjY54O>ydu zV)(Q-Gqxl_R;DjbF*7YUZ`=Rb$W z)|mow!xulGPt$Fjw>nvG|L^i~{z)VrcWNDQ3YgN$)XO%$ry)gNV@+<%K{@DXY4u=n z;~)Z-LC_CpIBJK+1}(;oyQ7;&fOiX4@s&-tYg{&&BM9$AxfrtH7piv3tf}65BELzP znc}}O=hW+a-hwAtQQG^vEG|xARU;Zz<88r67@=B>qgQa8p{ZGq2@j15MzcVOv^A$j zhZX+CVGK=mSr5m@{DF+@7c7Y2^3T&G0O~bUcdZ1EUWio zUim!qwEhwqH*srXINl(e^YHJA*?B?W#a-Wd+t&Yjp9IOTLUBn!j~_harCczVYk@Zu96bElK&>0pg9tr*tx=%fJQ}}unl^}a~jK4Jt&btIfIXN3}Y%9^AqEVC>gy1Gn zFMU&289UF~C0}w!{C;e=OpkyG&}@(WTJ+>dj+M7AOn zeSi)Vm_R`1FD0V8Ul$<+L5cSZ8U4dNTKq!wBrX)S z!CwcxB2)=D8rh*s)yAmdgYCI#qEOy38cdThoo#kpUDMC$3qM$)ZoL0?VT4s9sQD-~yZj-jGi6Su#`wR6Qa9@C8mZ`9v<6nopPRjY{7l@=!cLX3w( zMv{aKIED%^NbYFE{2qb4?~3N;Zi!DP4{V1Xb>Rw@2hBi183UeW9V%Y@Hm)e<__GGOEJq&Pa_38T zR=?hSo5jW0W%BqzH7Sm~yVI2w7DPn^^(hdTTSCo<jT-?+)nm_~o0M zRiAdsDtTjnl8^y37aVGcH^}lly7BVB>vAblFAFiepH^HvU#7P%`2{Np2KZmKwBE}N z*5XxlXq6i&f-1!&Boz1IC-d`*x$Q6J55gjmbosGX^H${}1ND}Pb=oIxW%KKH-{f-@ zs3Ki3#XC?S)o6b|@Jm4{%50$UZ@6b#%2@vh8HAPO;nK<=xG3E3HjrLkLjNujT0mvX zP)!_4Ctu=4$FWttGr^COt?Q;|^NNPj;-zBAr8usW^*4HlZ&qw#_kzCjl78cPe4`CE zJ*SV80Qo;)hPHh>7TI*Wt-Uw;N|@mF5A2Tf5W8Qy3M-;00xtbn8pqd_js*V4#>C#> z{Hktme@XH8Qp!M|w&4DEgLDSs*a6u0@$vC#<7un1ZaBr=zy%u}8AU~gkk`cmAXE^5 zg&Jmpe2{YBgz=mKo1%Qz&MEbS5W??TyFwe|ZO`?s-Z1;--PDtl6R?xopOz$cO$kh% zWMyQS+?+$OyWk^rZ9@s)XF;s&e0`*eG#CQkDmXsuT2C6lmYrk<1fnxCFmyF+8eHE5x?K8JkKFnfU6mn2ImJLn2wrEjkKflFRC0dX9zGOUrfj&V`6-;}*0kFrQv5 zt$kTr%kh1QIEJEyEXcBJ>ZWK*X4Q0$8IadC^x&WclyXcfd(oeKd|&HYS!+!*?hw+= zY`)GVlXN{&NK?%YyRez=qaw`u4iB7US>@L+$iUMID0kv*XzyQudYEr@I1J3DoYJ8!LQ-e#`k4or$g{N`nBR{>7Y@4&+gw{&!)U4FZ_ z2gCrUw~sp)6mUHHX`J zFXHfzf~5s1m=6A-MosIfu%_A>mvQ{A(xk8=8#!9N&{<)f{cL=UZFM?b*YTJw*>>mR zztj%iZ1A7v=m5oLq+R~eY-8(@ZRvXbCZe);<+ba|4tt!Hf(h{L0Od{@6F_F&S_wl* z>kd8s==nYDR*k=ubw0>;Wxy4norQvc}= ze)GKls{g!=?SCk%57;nrC9_N5x#;T)fz6RPwk{NmqqQ|c`pV14dz~sBO@xwJOM*e} zhCi$XEnvfVK~q`JOu|KoI_f%N)J;&rtcbEyUR_!n6|X6^G!TKn#eWl%^5?AdQ<2KV+x zF7lzu&n9m+L&Xr(&4HF-fH|EbL>KYi!{PbRg_qzutoPMmDp#STY26^&SgDLmLpn=U z@xzW2Q&AN}jrfg}XDA1sHSXVSa%Be7T0YYOwVy-%7CcIc@<-4*@5`;o(uR-FDVOV$ z9l3plwXFYaZhk`z-2w`r+9gbpECFvfexlxcez^Csinsh{XRqsON{i#UIsyx;>+2H3 z!0z+-=mkP+)aU>dW{M43SgBkc(7cGekE^xH_l)Jf#-slAWQ*+Kjs;PQy>^B;!rwq4 zSUI`9y#)msq{#e1+F)nNu>agKQ#gv2-o{!EO`9!~fM4o_^d&@fKs)brDFfOvJfe?- zm&M04wV6WtOJ<>THMEdif?yXOu$#+iETFi`$z+MWf3n&2vF{iQOA9dzO&IP0sxnq|S;`g@#=FpOd{QEJ8 zKYJP*i^4hXrf9q;Yt$;Ii3H$wH}EH?i3bCgKkMr`a#Vmz4Pr`cq9!9$Z)E_YHq6Z^p``jT#|BF{-N30XgiSohWIr(oB+FZg-0Kmg+bHI9m7*Np*CCVs`9;P+%rTOMf8_ezQ3lwdhkA%Y3^62Yj6D>!$b*PHC3pa)=W|t&pQgxifj-^OB7sK{8qubhhX3iMwJeX zryA$!^uP+25Qbu8+C-Hm4UtUMUnFoZ{Pcm>vEQ`mym5xT^qRv&r-RxL8j%T}Hc0b=oN zgzI0-97&lE+IA+Pcf01;B)KXr4vdFi@yBtr8$~_}L-(fk)JAR0`I1-@sl?ZC7}|P? z@XDvC^VevyG)@MzJS1fVnP7W5q3=#Lf|Onm?+Fk*B5*qSELz{*F(dX~-MOFIWyr3#3v7%HR1CW4!`LFb}M)uP^W=$WtZp3B6fPUa>quB7qq&T<(}uB`%I+&Zz()^6qa`5s(#|0 ze8CV8-Ji4m+o30=w3!Xw5UlAqWC#!O0WmyfaNOfvse<66d8^@tcOr9a#ltYl#!Hen ztYe(&+X(j!Grh1Ux|D!4x?vhB%^F~w`uL-VhDh~i$ZC-~Oy6vSCKEtbz=;NnOc1_< zL*ZLCFG9WSI^e*XYW-z&YVebs3ylO_mkV|&w%!q5WG=VkdyEWhCLM=q&#(4f`l-$n zo{l2$=qzGC{%pEKGIjq8*=pEwz!|)_*crT7#X*EQ7lhpFQX*W&15Xl&Yu#5JVHr-+ zpCyhKu-@)Fgoxt6hZa!VOsFh@9>QJd)2jcs+XY#F0`myFu-eq()Jrhc4>^R_(Z$H^ zxqAI8U-a+U{G~o^ZVGiXk9~DaJLsXb;33#>8QLNim`^j17YvjXRSG_dfo8h#`%lY% z*fRZR)TIh$)QV)9jGJPDrkD?dr0o(`K9lPb9sP}DXo zx8J|uz>VXP7AsXz`JV6&mW}O7!Jw&thS&R+0Uf_(jj6&`XF%uke@re%#4p#aMXAZ~WXO@^i;8JsiUZEHrR4{j&e=nc9InNm3RH*>p_Xj&Nl+L?n?`F8 zIHZO1FV+}5mVq&BvP$kEX0RpLx{(I8L~BL^?MlTsHB~B$zZ6?SS5)9gx2%3C^AtO5 zG^VQ{Bzn2&k9IUp%>Vf<3*yOvKeJavMW&8dLtVX!qt9{GuCaarWQJU!5OpJT+HIZf zqYPSRUg98fu;7Tu&$@v3ddVg~?Y*ess_BPoT^Y|D#6Xr z?i{xb{$dKcaMjJtz~A70VVc`qB;6DEF?H~vUd!SG3tdJ6c8$=(l3KYsbLaD=SGyk= z$uj$FAD=f%X;>kt+wJDAQDAT+;QB6q`(sB`i>VCWpXSdN_TaQmS&dQP zV{D#J$!N_g!k)U%HzjJfrg!(KFx;87C||039pRk*etUPOKZ5PTjOg`J6!@GuYu&gDicm;L`GH{YH?CoJ>W^g7>iKwpc zF;|kPSkH6U?NqrFwH?Iey4{3W^-JAjU6#nrquu)ztp8m6hXb1>SKOo}QQ*iX|NABe zfFG&gs0Ae+{ZK;^g45}~$k3D0j`G#6`ITdZ5jakV@YSi8={7kSvfz*yzWbv~8uY#p(kg(G?b5F2e_TE2@hl+|(Iz)}l~1$H_FJ#aq8!Zu za(uvqKSzO@GioF=Nt+;BBhSM9=UnjnT_lWAmiBYZKo?m!n4{hI^*D(J1x1k0NKsZ+1_aUSWuLyw*AZVJNGBH3-S{%Y#p_^7 z7($Jc+?qH$BapxT7X+=6Qan4%5m^9QnslO&AJqrLLV6y;(;~QWM1~M`)X>An95qq& zqoJ1>BPLXg$HUXfau}G$BXyL%v{0w+$h_yj-w>P?#g+|aStR9h_OBQRstdKOg;jPE zOlBio6%9iMVhU2>-m5ln89TevO~bmA_i)`e zuQ+vDBAKA+uT++wga|BFR`g-s-tqyce`K>z;YETnoS6LMG zKEp@Hfb^#SrI@H|XiU2+%+>)UPBxP4=70T1LxUS2>qBe+uEK$K(~ti+ruFsE1o~2j z-z|mor&@fLn2=H!?BJO;cSk4|M;cWfpKbmwM{`^l}e%;S&O*mJI^sPhmLm-V_+qU*Zf9Ys(c`;mfwGEGHl zvP_LGW*`d-B5X4b^hPlQob}GzPv6eMI*6qvC4c<-Bwbn#skHedSRs+jdb$(%CnGV^ zbOmWq$d{YI$j^lZr>fbUVDKkJg1IN)M;Fb_%*=qkM=_-2nhq^NrUHH<8yuWzAjS>c z^UBo`tX!d()#y@4;K1_(yK`W@?V0;mAG!aKG;G2v&%mUnB2}?Iwk91o#%k6K)tbcD z{L4;zc>3qh=b_+kZxLBiDGODEW37%E26MWZ%*gfF*zCd>R;+%HIh`Ek^+0Vtq>^Lt zdz2ABldmN7R{TUDCROuTmKKGOH#ip7?X1Ax{SWHD(YtYdHBrfgvls4I!;CnL7@sn; z+6;;h3?yg%n?y=jBwRm?BX(pk`;~DXa)bzwK`#x=0`*!!ukXk)>AsMx(K}K`k||~) zr>pmuaO^B|^mY$?noc507&22V8gs;bz@t^&HO(-}l%gI^mXe)xurlLZ;%!8y5|WZAwk(G-s29s?%w%rh*`4`>pR+j*P7|05?OSx=?wWS5KC%BiP30Al z`B50JLPJ@kR#U ztaF@5SJDiufNd2o#k%IxF!{!v+P^XmN=4b~f@^(i#zKd*=X|KI2c7(G!}>(6fXdf# zL>WRcnKZ9e56V1#j8-|CxH77kh*DxSL^kY8w+BB`;M5(Y5M0qU&Pi8{GW?-5d#jC| zcB^FO2vil#>Zl_Dtnj4RGhdf2T#Z{4-1*we zfpxxx8zXTX3RTS)>K3qg5nT?#cQ0^abBjZh^)Ls(g;>2zqpY3;PO{*_fF(d&vvC&O zl3&)}HP?C=3@Bq}{;Lw7%kmlj%ODrWmPUfo02R8SPp2FWp$~M)C}?Y z@$}QqeXzSR0Z^7RIVR>r(hW!Ex#;T6VG$q6w(z~_&GE*Fs{c<5Fr?w^xc88wuEURt z=MKt$=@M$Y+w=W}fC#AiPTB;6`VrzgX+=P%b3lo*g3)^{DT3Zn;9gh{R2L@ zjx%C@4^*x9UDqJ4;Ls(&cTIR8BX3nV4Cha?^fCJy4nn@kA}^uGhn7EpQg8GjK}FB! zqF=M@5Aw_>QHH!Xwi#1HMA*#4l*6EYF&jSow~MPEK+)|b;8RCGE@_7*wjbR_iVot* z2AmFv9B@cQd3rCZ*>O)Z4t$DbO5Sz2v$;BckvVBfm(o8~Bp|;Ey zK@k20sDgzJVaQYmT9&3ok|Oa7Jy^s$^Y@EtrSIV(N6k9C1s6uDS%+!$btThq-J#;k zFlVM)aL7LxFPZ(V6G40UrjR0|I+JO_IxI!o@5uy5kRmhelN%f!j9D1%8Jm|SK&kC=Cu5%cLtRPK6H%tDoY7 z<5@-6DaOx53*Fk=quMw-4-g4pQu_$dS4d>R_hEXjNpe10SJ<4q*--7p!zNBA^^3sX z0|v;j#s|M+I-V~_i;{uf_SCIa5}6pe0M+bds=bRZVN7{WBq25Ao0%On=2@n0TQq!5 zl}TW=8QiS-uTHo8d0JvB=J2dM8A^@>%);Ot0a}jM)QNhdteVG+$)=qC$n-A(q~wV* zq+Z|JQpEY-v-+d|>sHsZ# z7$%{G&SA-km+_*)!>#fEk+RSc-_#buP^{vaBZ)~<6Wl*pXp+9Yhn=T{(<*Y1Wr&$2<0gp z6yf>#FBD!ic;?&$f*`^nU?N2ETR5}|#%Eg`as!IGC7XpK*WWZ>J5bQH6L*?XhA9)V z9Z`#CX;;XN2H!1!^{oRpn0J4^{ppXx@mb@YGYr>UfdPl|y?Fn|B4+dFr*_na1oDBG8yqu{0cw8Q|A@S<=I~J?|x^fV%79n{W zOw?pLGqpAES4{f-j)E`0uY4slx^v@Ixc81~Nc!lmKe#XJ=)|C-BT?eQ{(GhZ1rE|rN`xBTnFve?*?0O@kZ1r7)A-_~q6i;}_4TRIVBw(&~uQ;mvYMhsV% z*wcJL=ta#rN*ab5;0w5!J;dBW{SN}yq4YD?cRTsS;^9WCod>kSTwoPOAnr(zls9a$ zYF7_74hwr!n5w;7Qr3inXmwU3b8A5iwo8?A$kpt6u{%Mz2$aDj*;dBnis@t;%j78{ z7s97nMx;c8R5-18R)}H$jZVjh8P6p03wn z5w^aMBc}NAL7?0D_I7^qWh~z*ja;kI;JK?(@EFi&PELx#BKqTul&yT*L&Jub{)`i9 zV}|JG$W74WozThs+sT8U15q^ZV`J4fSI8>9D#7tYyH?b~JmwOWzrVblmWpHOiCx4$ z+qPg!;HF^<2HIMUQGfJ$3k=50Om>-*=Ydvur5;)S>MX1Efjia2E;`_l);n^4+#h~W zIB9^Q{<_BTOWSHO+Si}38r>92Jd@! zB$a$B|D&hsCYCgBMxiLF9pHY)^!IIFdU}oV< z+w+$}s+|i=I%YA}t{b>bKW>7G%1ZFC3X;XS4u9=XZyqL49a?Y%mLtI@9y?@`tOVW_ zHCW{?QAwE;jX_i4U;m;etj+&AlCf44%0d5A>W{Mc@a(AB-{dCEPxZf4C6$I#vzc+S zjXgh18vbWy`Dnw+dhx-JumsXq2ywp9@-afPqIWd6-bazlk|{Dhrz;3^rw0U1but$b zAcuL_fk7znVr)YYg&OKal+DWkuQUf9c%{K1gQaXU0K$}~2T z6LplfU8UwXu3r^}zh8c(7f&tiu8yBsX!>~c1nz6UK3S@WS!Q~bmiU&dr2OQl_f#+b zQcQ{ClV$CcO>Fxk0K<|ZyoILNh)Pgim9`#f$f%Y&C!VFcxM5GpJL_@1q4C5Pw|lrO zdZ7==dZ>5_GfQUrJ9sxG`}inRs|{~J5~`Ay^3B_lWJf4f;k71l5fYLW{peH_y=Y*-Oz%r3cRvN1v>`uy zJr!5NqK=S=%p?>6JgLeLaic8NH3ewmEt}BzG6Xn-y3iu+|3}kVhDG_sTU!BX3F-LL z4Fb}QbazUlQX<{mDc#*6(jeX4-QC^Y!`YtqJ$&$smzTrLp8fpdUTX=>jv1tn1u7TK zbbipDdUyApr&Hjw%`&1!)+aLdo z8q@_`D)Q10Nevu&Fxw57L2et;>c&i+o4N8$_hcPw+OXL;BUYKJ{XaPbg?c>EYfEEE`DwsUycB{vZsnf4&it zv0pi+Zf>blc1oepO+kkD?I$ha2T*#RBUinxf-?%~-Arg1@lv*02`fdyNinICmpU`MJB^lKbKMPzbi zrF3hoU!Z3nBB@QQYfDMx)Aq8hH`(KqwW6uSc%(4+XH#eCk^R@X29ZH*# zDp6i}97;v@!LmSvciq>jsYv&4C)dk)`Kp7a?`px#OkS$`CoXRC?o&)~tKdaD4Y?r0 zq!K3B(wCH!05p;l|2EQtM}gg51g|dHR`!WAy}N_qKvd{sp9afG{-*?-Vr(_|FdCD7m~K&!AFN20i>B zh*EgNgWvS|gwGlA$QbrfQ5EWvj2uBRwXFmVDipmN3!u}pf4y1yP(=DuDF(nl+pNJO z#Ia3zW|$B^%~PQx zdvPs9Wg7PeI%`|I%6*(k2KMT^+x-RstYsgxZDR$x4_`hR6KX?cdW6G-9M~@&-8O}GYguBeD@@RW>Wz{ z(e&Ydc){Yv$^%TpqvIZo5%vk*0Wy6rSO=M0f+@7aoNirf>!^6;_+QyVmHKHA1gVhG zOj!PMOMeD>P-o?AI4*!xYiKC>k@{kyKKx>Ag!dHUIy)B>?li>=0BytSZ?LObyHZU7 z9qNGd@`-)jaBVsTf>~*d>I0&@+&bFd&g;Ml6C<@2tnrY^3k~TGLW#lSZPyHYIPDKc ztE4rf66aPX;q^64RAl>x{jnKxm>gGoj6Ec5QVKBz%dslPgglk960v6O8#+G>zZ<6z z#`f~ddw>e#mSbpV9?dA4PM6u)r>s%0{NIj|fnj)LM6FoOUJ0p})*uDMH~bsXi9$he zg*Hj%opacvVn9yk1_RNNshvnq$9%LAMf0C{-Qg9=glIe&34b&VkTEwnh$!1fD&TTG zA%PC(7xM;7tZ=GhlqUbr%%L3Tihqcv#%xYaU=tow<2gFCDKw(QS%w+iaW(rvEa<4; ze{Huha3TZmhhK+x%`uo@1zWwv7K&{g*JG;iW@Qb#&wcon<^M*16xRJ6!jtTX>|5

    F*GW zsxPzc@f=w0&axOOjE07y8n?rlQEal^%?b&*+m8js2s~+**2HhMsMHgeK6xJPaM8Le zxl$RJf`B~&sj~I9i%rn*tV#H4U3Njiwg9fW+MrsGO^nR?$HU?co7xA*yA`KQhuJR#FEy%k z9v~Z{3DktMb8`xil_o#(L{ zPznnQ8du8HA`+x2xpF%y>p?(N>GQj?J(tvma28QrcV22)2%lT1Jx3fetB}Z9;W0mpsRQ^Df|&P8N)0kQv65?YM;UX zoPX`gJ4mL4#!u5500U%P8{0``twsC*UR*IzZIDeA0HjTpoYL6MTy6N?JI63=Exd*X@g&)8{eX0A0MSm0qm0YW_1srn+qxz;h(Vy!X# zx@scud~oW*w50Ml;qyiCc{{h%;+M*r0q<5AD~F4wz`*7ATDG={k|zQ3;c;NfV31s< zUc9f=84q-fwxiiN5(f%Y2u6;MwaP{9=@sA)nsuP}*-Lj?1=<=A(vSggjr38Ax)lyy zUbj`3J&zM}eUQhn)Xw(Qy7m)j=2^}$JVRdm&i{v|vkZ&!i?=o+($X=6bgQ&<2vS2c zAl(hp-ICHE-Q7w`gLF!FBMs8s_3r;U@8R;RUX1fRd;emsbw~NMeH|6NUb63dBX!Xq zVXWb6etHciW=lqulS>~J58jRj72$J?vtyCOr{ST9?S%Et-9IV#1 zLoT{0)acWYw#q<8ac%BGtAw0`oo>OEH!8!ZVWb;L4vnPWXd77G=C0|_f%>&rGRz9; zrQ-CINXZO2L$~@z%Tr$zo2eOva>@%@LOmW~;gv%dfc#1wrn{42;J5d=YZd0_U)*)7 zWM9?t;&xY0+Ml~EI@Bh|z`dX?6=$5<%aHGzDX;w15d>0E2?%!#X8gwOxLqQ{=zf$* ze*d-_$EJQOLFHvTwaK_iGgsO9BiW%Uo@6U;>-4evT?OZj&}Sosg`V%UPAP(XuQE@+ z>5`!%_J@fIkdkfO3#C{gjcvB?1H^e&<0lzAa-sX^q;xA?RHex=rX z%0Of>P#KCBP#{y-UVDum6=|J+&xhGnQt+ntC<3%>#WnA}?Ffwc>9gVguH8BKyn82z2 zmwh2H$hT(KZqq=k`GJlJoTvSRj``q=oM;ky5M9sCG~HXe4{9+@*e$+E-VJMlU^rvkyr+;qfQ{)iyjn>5HLx6k*fK`d zq-fp@Rg}pT8cl;3zYcKRb0N7lBG

    b*ZRzw~yRJ&p+UjArQzGEW?QrcG}L1y&)n&c@(#TP~Mof>+wJT z5Xm8EH#bc}>qrmf^L?$p-tap^kluS`a*{ZL*5fJ_u)BUPgB5*-yrgu`n>~Vdk(4RI zw24$Q_?{&LLAAffy6~(@pQXWSJ)&=sUo@#+4|Ap_SQ}y*U%n z^Jn7{6a=yDV3yasd}PiUmiuq4KF!soCipHW>2jxpwnEZAg%QyFO>+x4Z`8mGW;=6iXT0%p)ncxbxg`&r(zxs-Y}sMayP!s`KJcBI zsjGd=+MXiMcfb73_`*rGJwZl_Ud zibwj@@#z12<*r@{Vi)?}xKczwlZ7mLx4JYd=2qH88^E*vjAlW1M0AySOhtM9O$XT$ zjhdHZsx~r25}q8RJcG1H=-8#X0ESZhHjF9_UW+-&Z~44IfLd^6sWON(t6R=c42}Fd z_K-20heV$3Thg@lq@bddMUlS^I!3yE&qyz|Qz-(13`MzE`+34lj~qMol^nA+_;dx$ zq^S#J*LgzYc;vP18`J!mcnCB5GUgbe9-5yyX6|HVDh$=~Y*XBf9+`QQ7R)rR`*?HF z8yMNg>B;-p7=vg|Yw80IsCx0)MtC0#@y6Xq>-jTWiY6^Z?#LIZzV!!a7$DOcIHG2h5+|QCI-LYC{x+cP z!TV&N8AYKSBb?CO+az7~j3xglNo@2=WXy^SxH;>tdS|Ylsf$J+S~@!7%*)r|Q-UyA zs7c}D!6AZ&SUYk9+rd&}HOLI%buczHHTCg%$_;1sn5oXZjEVNz^jx_oV@Qz{+*8V4 z44X}5gRviRYuJ&hyF(< ztdNi4{#wBP)C>eXz}53Ellda!71t}>ny@7KB3$v9{U1kR+B!~|Nu`@#a(*)obZ?UH zeB99|%5mzGbdJP3c`0BAgtopIR?%g|^m+L6A*(AP+N0=9TeRCjS;EgIIuc{}@ESPF zM|KY=ADPaVBK}C|ZdF*&({702#C$wYmJ`s`q5!G+aRyVOfBNMvD_Zoe9&s<;_!4WHJ_e;6jBTP29ya7eK+#xZt^R|n<` zq&oQb_|cP;uiwOrZZa|obOid6xv~;tAm!QAuN+?0Bz;YnDj9MkGmDV1(0tMq(tkiL zAoz{7ky<&VSyId+Keh*CNXZnkv76Y@ZrwY=&+huQ01AQN2V)AOir)gSanf`0t1O;E zBxqJsUZXlokNxk4hMVaMA7>8_V%tC$f-A^BIAl*Sy*=qm9O%@eZCFNHH7;2H-NMC|5 zf{X7BzR>QyU|Lu3?Q;^B`Ph1y?TG&FEQp3oS#lr;))8T=3kOhq97V8dx%47MM{F-n zuVzIaP*N!oOOPf~CQ`3K3J|GZ+^^w3RBZZl=G5 zoUI7Yv71fP-cUtn30{9UAQd=z^rh;<_M6@iSA)~x4UamdYRqZ@fF-GEuPn4hJ^>iJsEvksE77!u zni@RuaX{vXky0yB0Zj+U#w9XK2iubWx)0z(7D1XgzRpSMNCx^jK#u?A68Z1@$nY>Y zq&E7ZK^m0-gOKgR&Yp+zhiVIJaKBw%I=g;YLe7{(WJ`C)mXcVB9dCY_q4nCSFt?JR z2N*$AU9+dl09fF9c&Kdq11pLB&e6s)cD?AzzoE_ILw$9e5J4x!F*K zh#DNMbo=skb-TA-vl<1Ptm-z#p$@;iLSpPRdq-eHv0{5Utc-oo*zN_&@!F}%9sKGe z^GZK@Dsh5l8Ag#Lk+*{(G70A4sD*MQAG17lo5*=KHXVK*c@bH(pbR*eV7iYBJtliT4;z5Fqo&@jyk!i zSVpjrdv4+DzW@W%P;-FkV8;)cdQn1|A{A>4@{4}&_C=4Z7HmtOpBT|d~;&>P9(*G>RGYfh#U8v!?esy zACM$bIeAcnnYe%Ird^_vtpf@Tb>}vx{gfL>wD8u-{vy?d1h}1#@6GMAqr=pE0TCuw zvn-eE{%*Ey2*NhvHHzjXd=U`KMT;6hu^N%*%uD=wF+;xkzZ3n?g2ZL8E$Q=!iJ&8Ka@Fj0HvFG@n0hd!rguD4_&ma zzAP@ZR=f|(1@*@zk}!U~?TRjQQW@jGpD(8Iu{PDSPsWl@*8ae=2WoCrY3~h^l^dXn zaRI%fA$G7k6}v`$JXpzd`(E1dEY(>r9vr+gDqXe#4>Dx}@xPV70sI*lxt#tKz%THz zTvdAf&;=71mklB=O+~17hlXTJR779C(U6iy5UdwE@=dFwU^I?L`)c>XW}9(rR6+g^9TF0n)K#b zccLk^QMk?XX4BwK%Kh&zwMr=84F_i6GU?+lAWE@Pgn5uziN_}G6^_Pj|JTzdFRlW6 zKVl2a=wspbZP3Wa@^C5T^F78p_PKS8pY)5dk7Oj{m#vs~hw{V-HGH4qu(louJPDCv zG{~UWuoN+{MCl7hOg!S6hso^3gy-WyVKg#ID&;EDO1u$NE7wFjW4}PQq;3ToKOPLh z&Npl!zb2MTbezB~N_~L`F_-k$4~%OBIv9xP;vr2OG*K@KHUO1KC#zU(=(Yc~ON*{# z#MZALD>eC&_*sq3CW1r-@s$L;=R+JF-77AO)*zfqCN^KUqR)N_kO3RF2u2B&N&@R3 zZccEQvfat81P5zek$w@wF`nzT4k%;BKaMuFgWsbpci5OLIpm{F(^oJK$Ply7nwmaL z-5U6p1Sw&1h|+Of{%m73KXYjwhJf&3j=W@Kz?kbxl@$XUVaV;J+H^;U{O^t)HFn=K zkVhebG~-A!_9Dq>?Ue>bT_*NM0}jMpG|&Jmkn(|u$f!z|B3@5R3*a0j8y3ON9wr8p z<3hk;1he1x?dpUP=8@Zpv(R}stzZ9)Mtv{v3rv${-1{_JSD!g^d{4DU?9&`q29rl+ zo#8wm!Hu{Ty|K(ik-Lb?miqI{*>a zBVU#s=2#cNc8%W=lgFz{8gGAc%iZ!myTD`@@m>LR4}c>(8PAgxJ`Gj)h#ESIZd426 zlg&AKb{e#@@xyBi$IX|#&WC;LutFA@S>3h(tw32paJq0^1mz`~qZLqvGM>fc)8Zfj+)@nBE-!N z>U|KDxSZzN`@K&*EGYF1{h%;?Dw9i!X4sRZ36eoqB&zYFc>7ArDmQDsxN1LjZ0(Z+ zWk?M9T{kazUoWkKvayBTJC_nrNKp=8krHQ(?abxyAuzFtvnxT8s`h(z) zX9C8IX0mqDG;B->xv)k+HP3b6MgOF?VKlQ_+YJ0YvqTt3inn&XA#Sl!X~7}a6TFfZ zq=J%i@c7Lnt_m2XO435RDAAuhus=Hf7YFJAn7hsuvp`VastVj7M!r{tnq?y+Bi{^e zau)Ma6w5H@UsdO|a5z|7PwhIDA`YDk+{A%&-$9l((hw|r{bDy6rR8&P+5!%7;^sKa za)F2%g~pt&1Qqr)Cd*Q7E&=gnxgV!PP)1}t(7ISJyjIS=srE1z zAk09>XILgqdwfsN*hx$ zn}*QtHyYA^LO5bWWiQ?@iOfqAhnOC9Mj4@y#w3stD5LAAIp*Xo^Wt{yeQSK#&%;(u z^uZyn-TEe5Xe`tb7Nf%1q3WqPREYD6Y9wWK2r-ql7fz7}0D!2Jg{>pUd9E99X8@+rw+E#2%$@(X4YwbrE%7%N^aQb&mdA?5CS5SCY5}99OaML1QZ^cHA0&27 z?Pan&v?sC0ghm({Wm~-S7!sQ4mx>gVVOASRkY)_?ZwF_#mX=P}%#l;m{{%!tZUDO73TEdRCcGPc>PV2NADYDj#H69&G?`Z$+ji244MB0zwa2`$-mCZ_w5C?}cV!#0 zd~t$|vWMBFtjj+Rtai7)X}$eJG)oNeTpU0y2T$;SqmwymXWByw)xY_qy1))hk=yw? ztiC~;Z&H}kA{p)@rYo|P6DTYG3nY5|L=W10@V=r89t|+Ne{1IH_vHU6DF!;n)Qk)u zKtMjCl`b)@4i#Rji^n#a>q&}8+L8!t@~o(>&e8v|>XA5}V9J9-7{3$5kTPZqnHCv} zqY1^|Hm!8d@t}$3(jNQn-gIBEWPv~``MdVZAG0FyvawgLM-lsm+h1%3SZvgdAeZp7 z^49709oD$%Y!WEYULvSkWqHO-8L|dWRgHlSdJ+-adV0Ky=74lMo472|*bx00)@1K1 zv$$nTSU-0w)P*+?-y1?- zlm>cnGTi3h%BIlpZ9+;bFB4}L7$q5xn0eg!9bF+)hh)Y>BZq3G5UBv9xnjN`}Ev={J^a1 zxNC4PDf^wRC8*XM@{K|o7;yCam48mJlHvB9&bB>$j`-q{E~!)k%I+Tt4&u+sWz&IJ zhb~3SN1R$^wcup>Uy;z^DG$bw>9mP-jBNbGI$+vg7i>o zfuMRVeF>La6=z*MjE<{9b~IgG&BYT+ALzA-Vl zqq)sJ%aE{1R865FvRB#uu_U^uwK#LN(VWuzgaE6*4SJ98S(eFHhr#v|=Lqv?U!9L2 z%tb6QlgHlB*%{mqn#%B%Q~DLy-tgMU2*-cdK&&;$;Jdisl;UB~YhGqHLf3I-EI70` zXzA)s8%(mw_q3nhA;{1YtzvC9qxP1`f$#pDZZwC7S@*JpXeo>6;@#$t@Q+Y}C9`DP zh&Oq}ey+`N86~b!o@4JflF5gbk+aRh!XEk(doTR3tNReB)3nbw7RX}WG83t>+h_gx zYzd!}ydEJ#7ss>K9mFz3nyIKM%Iueq&$h}+VJY*Iq~QC6$kq&7cVvUT?0UWm`#6W? zoQ%Ih;QOtf?-9t>p%-wx7Qwi1QEVfE9fE7OKC558lZl&K=J5G?G|z%S@0a46?wMGb zSpLbl>~O-)BSbqkH}Q!g91e~?bju&+aLb#hkp1P095?&1wLAaii&OyDwDdYp6j)k< zbrUv_9x0Gz9rZ+nm_FP<(SBw`MN_~oRuqrzNBA?M;vEbOa%T5|?H>Hk!b(5{A7X&t zvghNe+p5@``8`eP5(l#na&(ubVtR@2MWo7U1_a3)!x;e!OS;DHZ`6)HTz1m$bqQ&vUVJn3kLqUVi{1q)5vFLIMw-<&*OX?JlIc9% z>1Z_N(5{uDWqs>x8~rBh{MFh(=)-5(Hn;@}I;n)_ZpGMc*qLY^nP;wOuX7?%ed)B8wAn3_zhh?qD0Amq|kV$5~Z)GV+&&=%A*8HYY=i*S~*GAd>UU85@ ze>&H3c8})k%KIVdd@35HketJspK@pezTZS$Q{@6_N!X5#w#k&)9URq$*U7$o+4HC4 zS-SHrX17g^X~mOZG?_5I+@<-z?vjS0&&F$CfR~i&ngqAs-Y{T%m3>+kf=A1=*3D~A zDIizLR?aYfnl9fScB$>ET*a_aMXlUAf3m~JEiRov!S=!6>6dOqy& z6|%Z8OTS!WZn^@iY5_r^Ql zIgwIA8B-V%qy(!iQ%(KRAU}vdgkSlL^9dTJeEf3mk9&>0d^^tdLEfeiOH6t@`Q~}- zzg;#MLOkJ8JOAOWe(70gP#l7Xu;QM}&0;b7{EPK{|8@Y?DG~&`pC@mj=79)!N?gJh zft#Ekd^~{lYuW+yDIoE$Koo>Zc&#r?FRpaWw>SA>BEI|?GVI2_$>y<^PI4F#Nh&xSbivuoVyGRb}NLk787ec#$_~vp#)zSKE)EV zWuasu5MO{o&P`oLqfGSW$EO6CJyq{2q>FSEY1`=>pDlKQSu^do)Q0qnM*&e!2w~@W z&<-237v_UWpbTKDf%B7Q!Hzkef{G480skGzzW*dhU-mww*M8_CNj?BG!x3t4NcRHP z@x5yCkc`&>0cxCnZd#4(x7cKsw76W( z+Jn_)j_*^Ns%o71h0i&T@ zJ9+jmU7b91FKb@>;P14))9#Wr9tV->#Ef z1hx@65RBRFH)4Eyn~-Mog0O^Q2T%toP>YFYyBTc$gedWQGsDfn}a%2of$UH1@-+=QTEjEn|I^r6@r=qImU zqpRhHrC|J$(n)<5Eq=`glSO70P;hJAxy8mqUaae}NB_*H?lK3DqxAgG zVy6zC%46$gt=5Q+b?FCvN`Li9pSBgtTHoWtxoeOiRsegk%ukBZNMGs5S|ixbMcNA$ zU?b=x+A`(j#ypuw&HU4s|E)-MG2Udp>ZN;c_;T&QABV@0YP6*AA*4)Wgt7Hin<-9? zqDJ`v&d|>hPzln%NvgzP%?7A0U}subRP=M2i7#?>HYal44X z2ojka1r$g2!jRYie08R#z1NTP^YawQz6)|I3HBr2D`;I5$ljyZ!~G=`ana*ewZy}S znrtn)EHUiJ@CwM*8VmqTh%7?WcruZrKeoee{YHwaBXr;CmGtDtH~BUijx~HsAN)Qw z(<2zkMoAn+4h@yEZ$-2!_Tt9$_om2gbF%g}bR*Qu#>X$+c5POv*3oUI@0My8_4YfR z9PqfUp;QM=)z_6B_IW7BLgn9i;wmLy421KX58V~MS%inHk8yO*By+*tJ(ZcmgFEV4 zC5jpxYyWs`lj3k4M}g!iKo;QjYfJ$8$xg-KCFRC=;tC~mU~LlxVd;)|aL_$Rn;Gi0 zW6r*#&s98~pceaN?xr!<8kZ41ma0qztiiGjfN{!mgl3NtWaq2jEG%a$2GbB|n+p z=sWC*VCEBffbHP(pmL@gAoGei`a{P6+vLzCj{&GKJg*MGi3O0&DojvDz(W@FFteDW zq}olIk#8$rJj}K0w5!ZO^Y4^n45H87`T)+(<7-?Zv=Kpt_G;lU>1oRX7^9>TO`us{ zM~WRRp*rN>)f>uKsBW3i z1ohjbH zQ15tc_~X_2&@KHoJP+bjRo5|O?rMG2`ay`}?x54m5T`H1 zXo83DJLLkAkrad2s^T_Q7cy^*SSb6M>$=za$7Vg$wG4Rx$C8wguFt_ch*Q^`mWu7h zF^uTPuqT#+n^*9NEUAgk@9^%V;@4#628OM=V z*LduiQqU3sOk(E_$m}wEnMGQ|Z`A1RYM&>fN1ta<9TvbW0J|Ne-@qe%0lf$Un{37G z+oVAyJcII!elx;RCFlNj?3`0noRf-()k6B9AOcubO( zgRHL$XnJE89J@rdSPRnaBMW#&C#O?j92X+#|t+>@Ec&TCA4p3$U4 zg>UO${VAWM>mibL^pgY@!rU|%h4yD$3V=tHatrV5`qb^=`uT(nQ=_MwXJ@Neb^CtkbSxFC)6Buk%RIqCy-jr=afx-?T>m32dB9QG17=Ybpd{aj*E^xnpE& zBm$WzsOgCwN)zM!>(|DQ63^{G9glK*)RJVfpF5(+%mvc1>U34Ih6VX)fAx>~>y8}u zzuw>7vhJcd7h}yJ(zosTtVq3~MAon4a)<1Y+T6@&xPx*L3^$#mG91(B%HxfjaEp0l zfFue6!;_?G^IrjRoAw*8B~(IE^D*wu zyc)mq1^;6K#9^;%+0>HH45pdQN(LJPVQ2XAg+CYr+ph97iTJkO5&q$6n$t0s+vli= z>k~|aqMea_jUzixISRa*HACMG#62UJ_>`pjHTQx-qsgo$GPer#GmLEnVHEk12>b3} zeqA~)Tb8YG)Oth*vlX68CdQC-Ob;B{kJB0z^@ZVY@ajgPROsFI>K7IetZ{u-g#__a8}<%TP2`?>!KKa`DJY zyI;+lDagqIfVQE#y9QflCHvC%_Q9yWDnZ*w?*g$<4F5!u`Zx8n@qc9d6<6c<4GiJC zv0vkkch{^VR&0x2p)het7F44PIcm8FG zce%dz?vGPdRgI+qo&@<=<3&Ne*GO-uq<`DFU;D)VQem3M#>Qd*4Rs=d$nEC6kao3v zI?q~cAJ8+%?K}^Em8&pKSVp%ci$TdCG1|P=Y5W0^cdOcF?HdmF(Llp>F>ylYm7t> zql<{aQnyX9tErQ4X>LyL;r>$s#t?18Y*NO;eZnK*S#VZL22RgI) zZ{Tbtj$9SVDktljl`B8jhq znofSJ_C@a0xJ^wst418jhihgl@<27z#jT8qZnJrW^deaeW9_{s>jEM1Yu!#BuPc+B zZ8+2injGh<)F=gTN>;e$p`2X1TZR(cp?GFqzt#J#x^U&W+QJ#Dzo z6P7vzaqX4g_4w^FD-Jfb?lHVIqL7Xdeu$N!U;}5KU9G>?;K9KG2sML`MhtkdBM?TF z+-1dowp^tmWY*_;^i%aGRt%^nK#Ns>3B(}zit|$jHOmx^&%NAj-@rnkg@FlB3%`k! z;3a~iU%UVYF2nDiX3aTM%fPCO97EDRU41zuG0M&~vZrQ79Gh?`CcyDa=qMzg9^Qn0 zCleO?r#o3__bGKITz2kl%45U^a{}U=CW37;;o=Jp6+Fq0R+j3e;ikO|p+=85(gbiG zgTEE%oab<@s8}olgrX;TQz**F_+VhLv7&Q-@MNuECof^MkSMFPuyT7fv2!)7-SWRR zr0{9)@Ei`^J}oIC4`3G!;;)(Dd8+6qR8lq!#SOTN3P#5s_Nz$XR5vwQlIssI2#y9A z*XdSp6Gw{1NIWTTDVh4H&rBC=w%yQ)1H-QNFL!FE=Fm22%GVpIOr{b>9A20%n!PAR z--||%vt&5}xmfdtkc3UX)#`Wj63LL}$EAkiGD6-;nM{?^4fo?kEKE+~QL?tX1YwCg z&<$Hya-UKe*LGC3@1x1jB&x*3cDs8lo4;t06AsFErusM4?i9-oT^H+}Q1O-bk1j+& z$=u2zzsan?;f;0R>Gs`%b77E9hhY}4&~frbxR))*n%09I$B%5M&a>2VAb=7 zxqEorfs}gSZ>}S$Zf*VBWOScdSn>5dGFUE)EG{I%ZyGnC)Wwa#T#2(W)wl1c`-jqguU{0L`ZuXZj0ib;+{S-q#`7A z0)RviIvB72c0=t)@^hb_`aDD_UZIRjsgD5xo4h8RH|M8Sc<`6KQP13jPXJ0Gxm--DC#wlkxS}S zlj;2Ar#-54In=C+=S3$BM>D_opBLSTn-0>Z`$9ogw$R2&s=>HY{NUfIAWF( zsVv7LFgRwmxr}Zgbr_OmrzpV+*!Hs$+MDpU5wa$^cF1--q|r~*ECzygS}LcP>=h~W ztf(*PxNxo-o=(%cE*`#`atfp|v~gd5bPC#LmT)zxxH<)0O?VrA-cG?u8al$xdp%Tq z_S;smzn_;y_I6X^TCsKej2+Doln`)5B(O%2N0r6iLESu@4vHZrQMHi?Dai;@MEn8x zrBSq6W~rm2Ff%j5?$u;NZ=(y89A42b^|%)3zN;jKH0hw2=eb3I$;+w0u^&oSSV(cO zypGD*AozwNJo~jZTt-7W47%D#M8{Bt*Y8ED(my%+?8RsBUmeVIeE8tJ+WtaYdE*oa z%5qH6oTRSs*0!C;`xJ4A#b`4p@$SgT$bj|VES<5f zVk6ub7y;VjXz`L-zNBzYFS_Y#f$J#Adw1=fWzQ_|24>2FQ2*PN!|YHAAXb6Gt==D(FF z96VKSeO3br`G%tR?0-q1f|n{^t_-IGGIzi#5iH!+luFAlJs#2Y9^OeS_evojx$8D+ z11n-JG1X5L(SN!X^}l{OJanJp(noa#2uJnJL9eJd2m{$08!P4NM{-j6)#$2_Us6!~ z#g+&pQl_%-QgaSXyMC?AlqWVYv+s{4K7h}i>H+@~E8Tdt@JBkoKHayOZDTp~S8HaT z@#kGA?yXC6qlI*J5I(a5q(KIgh!_Y5ohkUDCLmAbR?j6}S0y{6Z8wK#fz zqD8K3mL}}r*4Lc%Oz`Zw^4wYNe~dO->b-5ka&w{Z_2f`Zu356>wny!$bMdHO&|~GN z(A{d*Ce3~>h#9&qx;YoRiB`~F)v9#(a-U-hlcqAzJl75`dSz z#ZQOig)YsY+*<>#mc<7?sZVb-GRe^XV0-rPVrXL_h(HiT;9fer6<;@bfMvKnDF-u; z8VzGkAc>^RP;{Y_5n`)sSVayaY@sw(@W22Q=tZ9IDxOhmUw$WL<{aUT(9@^+Wj2~Q zKd&)*eguO2bYv8m=_5i^;Ts>Qxxs9Ke#0$d+F(B zC9lUY+%V4jnJ*OI%rEgcj*arw=V)?vHjH_w(0gUWcW*>ZNupvl@eOf{XpOp;Ir?N{ zE$iMWB|^q#>7zF)5@yRx-s)!DQB(3Sk~^ji!w^b8nZ(F!|J|g0rj|-wY4+o*@9n^Y72)1vIwkr1hAX@mU)e7Q~t5T zSz%V?TzZ`q8jDr%Rsz=(D+EdKj+ircDR;*?MT~tD|B=ANK3Wu({7i1vD)!zW&P?@zUGTs zM%JdE(vp$ZiQ^akTPjyl$MV2cM(_S)*$^pBhgYq?%U@9{Fn;WSfbaOx=PPx5<2W9j zTxz&kA`_vvsWcj8H&~1s|4MgM@9`r-_0OKS+TIU~{O&>7rrX~<30+hcGAGITp5mi8 zcD%5l{(OTzcqD|_`r4-B6K~4>c0)SX)yh!v#AdCa3a5e9B?{3eN;yXy#%-s-VY%fJ zSVU|v$BSUxl8^HI>sc3Ee;~?C%aq$u4Cv>Fu?7RO_8Lij-KV7p0&x*McN6HvFQk?$ zy%@WGgxF{5e}5lZ5PQQpz^2jZ%H60&w$r&+89>oqNpVI8d@K5_|3E582iANs4Ze}K z(op=Ww0mb9-AGJxd&gdBjZqUXX)g<=Fv$4m$=oR`FGm#d4gEOc4k%);UR5it+77)l zBtI2QiQ>5VJK+!tw8Cug7^mnbfWkyfK>-h}7fLO<*8;WzWHK-%tT}0%qAvq{ z3gzTpq9)n(tmuua(%9jBF2%hgL^8C?mzHPg3TUar73+};0a1BEjou}peyG8)X``y% z-C)Q9g$B8eRtb}M+?|I+#E9_y0kH4Ssd;690=M|Zi)I7;=ycQcrttmXQ{JfIqtILc zn9Awo1#1^K0bOzM}<|TU*^G(^`14$h{ajazyQY6+1ccOej4Yk zuI^eo0Im31R3)W=75(M@dNj_0mx;}dxgF{&0zOkdWk#HI$B@s8N`o{?(w5KU1u}Tj zW>~*c1>y8Ew5(z$YuGa;+OZ1oxFupjBxFb(C~GGsbl%km6j^YKDj37_T=Q#{ z6tKyT%q9slz!V_o68`?<>N~M;c}66W!T#{uk;Z3=AM>mp?E2LZ+5g4(EY8G1U9(!uFweOg&{7VADf@f%8u`fv@p3O{tnGYKToSY z+*}+MrdxCU>e%gZnxjnX`7YY_=B7<>48M9u=rX9{#x`2>!u+DW z?f11c`CX@_p z5;~pLJ6{qO+$tL7v)ecvT>D({bubRY`{eL>f6z7KAKmy!u->`WtkC&y;<&-*heehL z5RccqUsv(B`8QYc*CiRB>sd0PLC53!y+^&9jFsDFBb~cty;l3ZShdGLZ{?dGsb^PC zuItkw-xir4c30ePS#-Ge$5*dhg`TZ9=(T_OOx8!y-B)DSTP4CtT^T0Gzc<8gFcHmDe=YM7n8>A2c1cT zfI_!@XUN+R<0f1m{))wXb6h+ZC`oo!=kT_Ci<(;_M;WKWXWO1dRpPB#W7_%820zXs z4Amwk6vjvL%902s&BT6*-!a}(dDjU)#)_WD5H>5IVoJE@N_#4q!(^v@QiUZA`-y&Kue{qm`r|n=>fEQ0Ec{Vb8ujFQey3A{3TQS zeRTK3GL#){Z+U@-s#Pe;h_x0rP*TF!UJvFVcPnAPe1+JcmhCB3<;EjJ1qS-wag7`I zPv!!|(UL^YB2>6vLZfyKuDw`yrUJBg(>}TUq;e%veS~R~M8rDt`*}u=0C@qPaPY9<;x++&`46?E*!dPcC0NrdPLM(8v_#&u{HIR?rV@AP&F_a;UO4}DU z0HVIB7OISp*5$#j1)Njwc)VAhr;46Y^pL6Zw~Fz;i4@=@41#kD@MzM80d~mh!z{^{ zGMAr|hc%03Yj&VC_-_J>V4yGWkb}p@oS?E@{BIY>(AZ26?V4i*$xK(dDjg=a zce(vB^lX9?hou}=h5{KdS28yi`*n6`zxL|Uqm4i3xD1sm^nwOj+W5Nkz0Nb$ePu*e z#r{%-6x-HKsN7!(a#WaFDC}=Y2#~5@^fX zbXKQ#yT1Q?|Myju*T(CL)~7dFg4bmVjW;G0wwtNWZx#dDe@%azUJ z$^PH7ZH4rwnIeVdyADjB>)hF|n|I#$^Fj{#1!PB0jkCX3fBsiNwta;?{_5c3aoCt} z{Ci1Xk$jEUGx+5`^Y(5>yRw<@_x?uPbF=O3nEUbbu;V8xVz1*bXX3WcagGCJ6>XQ| z$B+Mvn7vN_^4zx;OlI9*36r**Tq9L@J~T>Mvpg>f3ZIs{wiv5@+_-;Evhvyw@0xAfs(3>3-iY?uAFl8^6d%1gbp2|j zu;bYFyvXf!u@|oArFuWe?Pa_hYWujK#aqT{L)uiK{5N*`0b&bQxyU6wp6N27Gi|W$ zfh`A#$8}#aIU{rKZ>-&qWK7Tjjc<9?n0$S}@fzLrMsvkb&XA!dIVD0?>=bx)YBbBh zWB-70Zvb2(*ajI&g+k^hV*#i$3KLwJVX~8q^hhgSR#QSe$DtTlyZ;1h90*SjvN?2e z(0<9BWtrvStkZlxOA`}?F^_S!Rh04=P!%Ug*~uf8e3=y)LGgacPnJ!YRE;^`%@Fi$ z9>y+Fj9wty5cNV$iczgQ@{+yh6ryMuo9x2|bJ zdtN&)aoBo6*6jc=AcNEq>!w;1e;0Uoj+N^#wW;y!=$~Z$%Y7Ud#RaoMOpSat{qMDg zO+o4K2eIB&>-QSBoq}0}h$1i@&7{5lO^mJK&Uc37V0d)#GpG3U^0zgzzn-0+xk6IE z><%=9cO{v9hMAsGe-UDotsy$YCm8o_dk?W7&H77lKGD{JNoi)791Ua2nr1|{x-q!7 zDPzKN%~>JY_LPA@McAAs89J{1qo7e4TlE8RWG(}+1_WQDp-%yWynf4TTAUw@9Irsd zmr37AQLMrQ4m7a-(kw%zy!($fwtMM$_#a-HJ2leuC!4(CNaNUx=6`)2nMIFJP_`Z# z#>ntc$CB0QTy-WL#xVr>TmwcEQBzTW9SM+1ehEm&!Be~}vv!gws z?U>r(0>&+la*uaDOHUzRGV2Z(zVdT=4Xle<;E~_YDv&Onr_buzOLsFg{YzHP1^Ad0nS}dMfOBD?sP-yJxWcTlnY7>ypu?o8!M< z7p1+97{%~1Z!e0{bqvIm@5vr3|LU!*BzopO+`}v%=w<=F($huz{MTCr6y8IxA;+&z zwt6?aX|tIRdV6BI;5Q>{e#`2~&v!gOtIfH?(R6aUli0c|yiwx0Pc}_<+dV0CQh!~) zHNSLjd_LBKq*j+v%j&&1KdEJY+2>Az5ezxU=|uDY=<3+G8X>Mk!|pSM;Z^gSX9@Cd zU*E(%Q63JpFLy)Kadu-#XZ&E9kL73kF)(GWTKRUuZ5w_cB@_1fU5WC&@pZGWDemx*_A|*#dc^DR>G$BQnC@e}6|BI-EG#@>Xo^R%(2BN19v=?z`uv1odx^ z`N)lkV^1bUgLFI0SMc&Uf0FgJW0%_h>Bw`XR8`<`Bfvp29Q`OQ3U~x4<6%&ofZd_V zXVr{#Q3GmAeSgP>_i?#2@-)inRbm>=h=sKW(%6hPt=Q%MtnW~my;cZ2CmRE0&$|KA zp|ct!xd?c+0DB0FksIz8&rZ26q2z~TZ$#K4RUTr*&>}y013+&^zu?=PqlBD-Vd=aJ_N30 z!<=8bFm8;hFRija!n-0&K-$d5I=<`toWjTa`X3Hg7j?fZfdm8wE;qYw3;?r12lDay z`z$NnV zP3f?!1jA6Px>O*not$Zp4zV{a&`x*!R{H;F`UZzO-?;B;aV=w+CoN;yK55mK?X_yP z?3S&Q?OHh5Twb-yrOcLj~#7UL3raX7aPqD!;O+dFW0i^f0x z$yR39l8VXxZooi={wBt$2IW%Fh_9P;k+uE_{cg=FH zc0`kas(*c$^)U73^&-F4p!*ogn0ev1cE8|Ix~2hDNvTM^i;dKI+x2?8nraXpPfYL4 z`02HTjEcglD0Tn5e5c8wfQ#2!@ihXJkx-tzqSenBz8K|JQL`LctklDJm2e$?G3iKZ z?6ey!=7i{DOm(isp@f^(v1!ICa@pC@dipTeP;{sFQugs>F-|GEzV<|4I?3>~S3 zkpb=jCj8x+PluY_Psx;zLC{^bxj+IJ>QLDnU5~iHXxbC|6&@#OJ4fce`o8g&)QJ#< z{}zvXzaq)(q1gkGRN?F;3~lHs{m$uM1jKP(@5q#;nL@$!G6MzT{ybyakAx&pTlL*TJT~) zs+moiA@tz<&G%n0{6qyleCi#sE8TMwBX|^p2?4_77Eb{FL@y?C-$moA>oSLr+>AspZ~@69A5T2)#8d%4w@E3w1`((#fOPIuh(5rfd1TSxt>N-2$7> z1nz(U#p&3P4RFWcC8LWP7UJO?i8nTP6tkJ6@)(z=xT_f|)~SkW>nlK=qH|DqoGl`VO0*^p^U{B zlL&xL8gWhG1!pTl7EM{5nvx=h1?+r>cI*j)REL6*%_UWE)k+iW`MQMTRe>>j=5w3V zB0zKRW54zvzY^N;$lUuyNwH;=&dGq+Y&2>d^>7B7$dM!~F=!}Mwe(=Sadixmrj+{{ z1`@M1W!9;^7K)6jR^;uk>E#~bl{|_oVB(wVP8QoM?2)p?*+%~3D4>tmA8M4ldErX3 z<@4(UBblz2II^c3c9*As{qs$V4zZwPK3Q}EZZ|I>x{P+;h*z(Iyrwb*Z!ePCw`p}~QieuKZPH5g9~pUCU$N>2 zP@Q+Xtn`0veEv~uzhuyHaku(Vg=*`%decF!X}jNZl2pHM0u=?28N=b>`2=0D=gzx9; z<~51HmB^tOc~Qh15{*;Gz(Cf7bgo zHp zh{`kZeK+~mznUhalbCU1v_>}S8q6~@y;7iBN_Rt1hsYJ4_}kF8vJ(}*(|NN8Q_zq# z;^Z#}sfceF)m(FVi|2#=QhkNTqXnGA%X$?n90{b5;rbmN9UUd_L02HE zlU|-(Pi{$k^RF$$Pg`7y)l9+UDiHX|rawnBrW`_i!oq_5sY-NLy`Cz}iKPjXKn7Yy zAwO7_;nIPu3yo;@eZMNDiS=9)Rv7LiOqMNed zJoBIDBIP=dT5%j!Q0izIi%8>LfBThH$o`G3>+g{By(hA^7EVS9v^KaW8n2P3wHCn4 z`aam_w!H$d4tqTR`nK)k1zCGM!AO{1d7YOjH*g;!J|o=G5!jL(E%FT84$1iW;KEIsmq$EK@ z8D)>d&@h9n_mg*?7f7scJpfAcc6(~;xhc1xSRwMl2)K5?Ts%L}`78)N?;?%u?u+w7=+N&I@>62ERrh-FdAnIn%sIqd5;>6p36OuSeQ8y9f}U{oIkuoR~Hk=|5RQ z(zXl;f!lt zrWCUSab{Fna-zbb`Ne+y0#V}?kAR|rji-YeLK-J3j#F*4wR0l&?Yk|v?#F|j(A}bo zr=%ms%}M5V{i3jA0Y+s5-vjSQf1P0KHOlhne?{?qW@rd818Lvn?!&5!Pzbvd&p_sA zQ>M@aYGzIyd8gULn&c#HPb+7F{QPjRK_Mk2a*%wcp}f32z($f(P0b6a?9E5zE$5vZj8p-QcWVNx zL#$b8J9`yY8JX$n*$&cE^YthHMR6#%f0XjArXJ$hHltESY7kp;^35k3ypF6$fN&^I zfl%IPw56FcRaKikdjoz_R|F8*-t4MR7Xbe(LKj=v}+XKeX8;Pb(#!S zAKYQlL_Z*B?IynFGdnV_j09rjgKf^sN@rQf-R27V*Iu-Xu{*;;$UMeYW^0)%v|CK| z+BR`aF<$51Ub47-w#Z)_I^H~z^6SZ6*XG^|Y~A+~vz?u`EZ$awg&mzH!>*U9$?tb< zy`D5dTW^Ox&*~36ud7+liye*Gj!%PI29IbyhbL)Y=7nE!M6PGZFC+g7yakg#CW>78 zet8~SdyW)w_xA7{BPQ>lYmt+TU%o0ZctUu)^?CH~*z>sRf8EA-PGEf-JbSzv!FXP= zeS7EQ^aC=ng3)o-anET>C-5*s{zmNc!n#(jg=TOSRq@1W;AJa*JwNBQvwG)wH1|x9 z^;UiMu(Wo0Bz1=r?ejw3{O0l6V(V#tw(NS>DMPm4y^%2ZDA4*71W=DVjs@CZZiBto zzj)r*`M{YhC#cr`NA(jxtw1sVLM9}j7e6!AMa74G^3Fan;c z2aN4Xl7`&tbjuTw)e5qQuIaibgO)~`pZbe;owxdQDwf=5gD^X@R35QM(fE{J@ZB)P zupMQr{=JrC%!@?LEj#f@=8j`;yP*%hFJl8%)}|ayt{0mV6Ih4VRww>hZ!UiGm29A& z9r5MppZ-4=U?ZHfV7)2SUa+xfYm)aZz0eoq#hUvmFj|gSJBjfBix}NR?aepO+pMudCdhH$lR*zS5yKh-|+&D>bo^qZsV&o1NPCaXSt^J zQojm20=~d2Z1tHp$DUf=E1_;k%F~yhw2XK2t##JWN%xbz*Y-_epK1Psc%@`5u*B-y zs?PD6k?o~FPP=~}S376N8Nkf*Cx2eA@Uar%=YQPVXhOd=aXqmY;3O~2x-T5fbP+U8$%|Izc-=t*| z%+R4ubQ}m%a&y3e-i}Gu5iuivi$~JF#ZT-Z5_CYBf)FtD^72B=qyMVKo+!-K*;w#XR(684kC53M%$A$qk3f%E zJpMi4SB7lL$H%A+_FdtSW>lR3-6-G?Cc?`rD43eAaEozkyS57ab0zpQp29kxBM*i> z+39j6>HI+JGa$wINu?G>HAuedCu5#wgnuRRF@Pw8LOQkF>{QUr-|>$<1T-NV6{}#n z;FxjnA!rO3Piqq;6KA`G5+K@Ot0t?KQAZVNi*v$jaDbJril%q7V#L$E5Jdb@_h&)E zWM~le`;vLXdIAqxS(>^A(l3x6hz*)%HuF7>p4DQ#1^kBkz!eF*4F7~76n+zPI5^^f zie1{Ld()4|Bog)oer)-pMUN+hhEIaY1$<3rvqQ9AQ} z4%J?o?q!%m@Zt3Irx4J~Sb=a+PKU&LuM8qUaB= zm6y2kr#$x$wU|eHTooN}uw@=LOF%LIeSxtDd~}zBGV&N}FIAg#B-p!U67Uh8aib@H_AhATo!j(F#Re3r7D=Dxz_VJh&vX~qr)ZO9r{IBaz zLJ7Kgmo7ujd^49mM;l_nV1ASQc11oYi5$OZZ%P z(p+eBRd2Ick6O6fr)dIoS}3rLQD3LJ66@>7G5bS~-RUU`6RofyInq9S5(!fu;9(BM za1lPdJII$(5gn&3SYBJ}uzT&&yIZaS-cem0T7--hUc{0_mzk((M3oAKf*?Bu#vMey z!FjyVPMjwC4{~xu3`FjeI=Tq03Oc-^vzQ8O({bn10$P%)pw4QeS&)G$*R7m$yXh= zj;NDNTqz$9uShPSkuTS@Ys?Fn;A3DY16gKh)JB>{z|>(Hi~D9V>T)$=%OQ96@g6Vp zMR-8{BwGJf(@3;YEg%uz6!9ORfw^V9!Ora+KO)%gvIH|0bQjPUkaG8F2A3pe|C0{YA|Z^Nj-G_ zQMD=hMJ5*M!)8=hW~AjzF~>^6p#tvozvG<=dYYDUz_1hefhn^c`7>z2aM%>1pYq`_ z1fM{el|~nnCI+?1Bfpc9%upWj)#ZoTtC?CH4^+=K4RD3kekZ8fS+ZV|T!spc{Z|d` z?Ok16?J7HbDn&AslH`k!X0?kf6V2Q*&G^CM@WlMG=|ooCx@C`4$+>^kH&()Ni~q7= zogPYljLj7a{&!D8$QGFv9{|-&pk^wD5lx8U($wHXs`F`9`?+U~p zTvx}6{*05RQf-Yu%(_`wAw4EmEm>J<;~HVnYprc)LHh8nyxXSbP^hLAPt&>y?^^m? z&Ve#|BTyNRu%6p`IOe*_U^EP*y$zW1XDEHCZ=j0< z>&;22FyW&zm|9p{@MBM_ATf#*;OdS}GEw9An9j2?=EAq*_c;<&>eNG|(w!B>f%%y7 zgAM}?e8z7&<~YYG6JxQUlrkPdQ+zo&F;z%^10jR&eK-=Nz>G%BEc8&O;{;iwC+>?g zB{m4oG^(Z%QB-<|9Yvfr8&xg(d%9)nppqOVbcdx%&mxj5M>-g;g7aVaM4w~w#8UwE z9u!}2LU15B{r)N*y!;qBSnh~Vwb-sFCl9#t9jJMQ=NPl7L-v^zISqUW;mIcp4dMq>R>-RRW^v3xVF#2px_u;y~W z3Cx;Xh>tI2WKT^`Z6?<;6*K^m%v+UrOx>4cWZp)6KGFSE76`u#ZWHSKf{A(%IV!b= ze#3HrJKB1t=AUA+zRO-CFL)j&DsrI=%D)jaXTKW%e9M&F7%gzrP$W$2)~(39>K}kP z?rO3hEGGoUZjcRHSN(ls?H@QdRDhKEx?$U>DkDwtoc3Q)IKKb#hzW|QlFTqOb3=Hb zimeQ4nbqvJnJNVSuuov8#6p5+IynYtvRUga{JXfR0&e`z1NgiBM;}I~Zjo^XiF=x1 zP$iT;;P~gb%4W~6u4+Mv%vr+io3v3N${A78)VP?Lc8&G4kE0;#?Y4nMcXx%_PHY_$ zQUB}DZKVrLgcN;Xh%{Y5GIBkhDAG{%{K7)!@$qnB&4Q;eAMBAg(Dz0~MJL`=+qBG- zbQW7JBKF7(eO8K@Mfpq30JIkQ&-I<#ZTNp@t0Xtb%gm@Fa3P_3DU^XnnSv*AP=st5 z>%c8zZAaM7cfGtr_VwrbhKbzcVnS5AR%(RaRI>lPk&pgJV!7jL-n8%6O&^U}Tj$~b zq=eQcsJ~D7zH*SSW`k3V_52)AJDc4Lmw!wrdP)}K>b2ZJnT$gB>3F0zCD92fMa*EZ z0-?S~P7Uu=lQLiy3@HQyUC3Y}^k(a_{v_fc!iXv+R3)qm(|2d{;1&BCZYN976SlJ* zqXbOZLyaL4Ky1&SVf=}vAiziWTo?&H{F3yR!p-HuW-Nm`H$%yLvo3h(G*FD2m!Dsp zw4^-8VJmN z?M?XFn*ZWwQjrY)Z9G2sS<(sti&)+|4El)@7~ zesnd$o-b?csJR`eM|QkD#ln1iV)gW*44D<1izEskGG;!pyGC0g2Ot&N6S-R!5KNx`97b>PHG zl^4`nrZxv!LR}X{p_`9O+JBI2D%tYLh!*}fkkp@WX<})S2(Ts&5fF)CWq}4pN24%v znZgSX;6p*+{yddTvz%w02C^b$+X>6akI)vVzh+ zI@(tKTNjQT(8K0-yVL#s`}_Uv?QK&*GIBC9Ab6o!zccCGAA(i)sWRg*W*nXR`p+=W zf*!4Vi$UyAcEox{xlT{s#!U9YAydM1O!F;255bwgwX-q~aR|QC+2;t7W|1)QfP zHRVyjs@3t3e~>RuG9(N*&@|gy9dr6Ap+5zl3iP+upkMIxA2kMJy#$}|>!_tAKoK=x zPYc3EE!j){x^tud+;SSM#zE>aQ~K$?`15B;Q+^A{!Yniya@j`$-!gO zqRXr?^8O?Lm_r6gE7koTAOZ<~+lQD3#6;O{{k>lGnzW$Anm9c@HLem(2s-!*0re#V z&Z;y0##OSAZD3uEgoKpDqUYByb!lXg{d!!v@Zx9Hr~3>TIdBq1VmgI(N+p`rER-EJ zgTS}9x6*l7rj%gF@Sa18IqXNIc>Ou~ar1OO>Ka`PTGY-TgC68=)T9Sn1@!s4fgJRg zF}>ut8TLRP8h&_b?)Q`TDc3oZ+pZZ9NWT3oFs1rjSs6G*ZwFKs)Vs)*%9zwX4iL~7_X9D zT6RE~Zk~ub;S{Nc1@c?)3BAM+zpFucRfe|K*frVE9Q%T%PiPDDO^(nc@Piy8;kObJ zKI1-(A6_eaXqra;rG$Ht*`+-~(Fw2ywdF_OihkR-rc3NEV$wc7Xcc%nr;}D}@{_Ko z6aV=-m(r}SEf3?E@hsxhjw%%!9n@XT1Z6k;fsG|Tw@LadGKVZOVQChbVY3YxMpHp# zUbE6T%vQA1Gi8sdRLFX47@t=;H*S=G;aldOoaGdui8bU8TOepNrpNn7ujA7n)PwaT z-_86GrWxyV>plUQ(7brgJ?$b|9VtJO~zi^~R zE#hH5MVQDkk7>&%NlNn?ATa~uR|dg0!O0GyU=OBG7aiEIa#&cpM=-Gm%bq1<_8OUl zCCTh`gKP8vFFc%rWUVSw26tMk`RR+Gw8D}kC$+hunXnZN2}@{k1p-2NO!2<06gi4N zQKpHpW)}2Q`~J%p3RAN7MKdko*ZVEmPo% zESLm}8`!?w8Jb@OUpNfV+6LQ6Xd`H+&`7y|fwAgng62F z0vm)}dQn}<+_vbK8c9qnsOGZwxn5Jz;~#Jq-(=~t`_P%i;?s}`=C@3j7Vw>+xhZ!09|M`&(d zvFz$GG&CVhf-9sB5zu#2q4PwCdM-?ezeuzi-!p_Dpkk|5?>{i-IHIq)ltrFmv7mhB zGN}^TP4$#o4gFV}BZSOaRQDB<$Ac;Uoq4O2DIjK+z{+4$`Z&t$@&69QA;7IAKyI+s zC@r*US$7RF=2x6zk`MM5o8l_u)Qisp<=HAwYD;q&NNtUQ3kbnI#yriV$!Ba&| zO$C>2nwl#7d9)m%f$V1w;Cbx_I@|5HW=0+A)5PRwuDPx(H*q$6yP`6-Dl@X;<6>y- zbtOYB%idr>9VqWM<1}xjceg3yq5>4@iiEb)trG>tXyae;ZOc@S>d>_GUoRpJN z@2}%?j;}yuOTiuY0$TJ1yH{?1B0>QsVB6cv+1tL12vO0--#1HOKcii`1m*E|#vs4S z!%#R|&HPm0i%tu^oHvQ~dYsA{t+wXRU`djnrXhF*5EBygkKw(nFPBBJML3(y5u6s* zIg$~4Qn>I``!@Muld%P}KTJG>-|c;}FI)SQIpAWJ7SK?s0HvF-r(Y?n%k;Gvqu?mL#BPSf&OQjhEvAgxYZlSGhy z$&+x-)~qf!w0f*&e2*_mV@^v*i{v7ExWABPk?^?i3#bc{Tm&D){aoy*%S#ruaj4iL z*|ky={q5^?>lIBFowOPL?%@X51VV{_@ z?#OdzTsM93D~&hRO#I82bCR4?c=Qc!7fGw$PwKqs)S}Ki!;>%R&RYU4WlX%B^GEuO z?VOWrM51@(?M5IjK`cx$7RJD^M@x%#6W=9ZC}mvrr^KB*4R&C#x~#+s8*X7bgZ-xZ z=aN#4vg!edy)R!Ytf@+Mvb3_yjBGaTz$q)l=~46vqUkr4G$Gne?YDQFQ+{Nf|d~v{rg|g`YHhqPQvTN z_NkCEf=%vdcQ-Bg2`Z5gp}NnT#!eYxB`vtvp`fU83Dur~Ge;Q#w>wjPu({n;KPNs3 zAJgYBsxf;j8!Lq=t{eL%xb;Zv2d z86jeqylIlOD*ePVD#Pl|;=tZQJX=Wi-q9wr;(;D*l;Aoc{N8wZ#0epoUYcO*?@oak zky$U!md$zx_qe)B#!s)nTvFnP;SK?1Gv|ENhN`<|8a(%i^gDcJQX=y*P6i>%Pik9e zA=Z?YA5jSYK8BTg{>~+izzQEY$qjbY!bct+sRs5*>S~`;(n&~3Ny)Q@_pVB`Yi-hK zizhz~U4g(6Ra9)sm|*G2w;2NjaV!@1SIz19>jhQJXVI)kR3oMuF?HF&AYcg=9%9#uQcCA%*Jl-WCtvwiZ)fn)49g*;w~;^}@0uxu3I zBQtl&aTjWMY^#>Z|EmD2c_bfF3lCbI{0%rrh;vIy%B>P6OJ_<>77MjHeOheNIPwrZhiy?#4b2;FRdN_}uT~n38j+j==XvJ1dk>jL_YnHeNPCW$Si4zU!%>j*ht~L>VM%}p< z#!PU;q+Az9%7P|iUOCM-me`L$4#~Paf{C5D)Tf_>)@OAnh*@D0CKtjGYwS*frdX24 zTk7xpDOy=E?U>mgDDZ|rfo8CfXgt+l@G$*3+IAkO)4}vtc%L&--*s)nuYMo4j?{vx zs{sR_+FV_oy5%*4-2Ff4A^gIqQ3p;qKb2o>+g7s+ayT`(mqKUWbS3Q2&x7p?)ml7E(u(>{J@wI&*~wv-TbbaXfq zq(@kj4+>6f$Y@Qlz@!qL(HgQQ%KwDVRcoyR6UWV)eCTbn0I}9EP7Lu z^a3OLciOQL#1}w*H0jpc2xN_6U_=A^dJOd2=;-KoJgQ)X40^s*jbm;4g6l494G1bj zK1A5#pZo$}stuUo!(Fbu^Q6<(N+FYx@&Ho;@@;Z?#jaw-qyX7QI~J(S!RXHCBiUz} zPBNK}4Ri>6YL3|wAu&Ep_Dyr}If5J1&6Q4!m$dOl@*r$a)LjPLYvk!REA(PiV--C}#wFZYRC-J0U<%3sNR^s9YtlN_{!VetX zJv{}}Mrvn+gM){c%To_bb8AO0;Vyh9-y0=E!o@_ zb_Rxom_#O%ImgbMT>3D3w&5!(#VIbt73%JBi=uZ zHs0vn`y_@@PkC51rf(D6{}Gr{4RtOqzwdun#XTq#x;#Z9l@qO?s!h!%CubXmL!d)( zAzzHErJ;6nQ`Q4RPW-u1Sy3iyno_~#wl%OxXkAtadu}m%1s30RD$&MiYfS5Odd_zvc9Lb)< zY7k_aTk=VOb@j1y?;^d!aqM}uh1N+A7zp6913A|puJ%ex0N=Sk=aXE(%UfAnLsENL zl;`>D0h_$?J5<+e9w>?{Xeprx0v(<&N8R4=8&!x7Zqr%xE>! z-W4BbmVgU-x)byUDD#f|F9%r<1LuihROIMLW-9S!v4zFzshW;9F82R}9$f80{r&w* zw9C{Pd7RkQiL4OfYGdz|FzsW^xHFP;aZmwdM>8!?aVumL6ky0G7(7H|GVeUASs#S* z!po_{SXQTAW6Gcia{)&@$<8cRnZ=S??ZEe13==$;kKn9~xZ)+r7X{MC!I79HFEg*26Quf`KxNi(* zzyfLZ2AepWU2mygEx}An8@KmIT^HsuK^lmkLez-oM#Apis$yZ`Q3%34JBx~UyZ`^W z0LX$zOQx7SVe3%+ym_Ax7I|l~6?(Gj^zX#f; z#MX~sOskC^>c!#@7Fb`ASWd9XHbxBzTKz_oTj{0M+H|2xN=mr*}5PIParU4!nKqsSPL*W z&fIZJ{RmFQ8dxxnt%d&7E*9{yG(AsrPEgH9FzrKl-yog%R|-Ubf7 zypYx*h9cr1?!(M#srugJ)+XlO9bRDTB;^hbHu36wEciD|5FqVj`Us9P%f6fq6BVJM z^eCoiftv^wDc}sHCC@CWRoAAoG>))YGz)K>F6`vCiBQwF%E;IHRKTGhLYIKA3faHH z9gu;!-X?x~2i`of^^(_{6IHWaX`XQ+9X|#1-MU)&%d4x1MTGj~zsrL~uIPoQP^DbX zkZ#$RI$cN%$e}l{uii%tH+=xn? zwYVG1z|guNGQO5h2E%$(8GeCoWXk%FQclaT&7yXteeGu7&`72i&6GIBuQ7v&S3mc? z?M4ef{xd;BdV0I>_rC5uniC{ho>N0EKjwdTMWvBC^=JwXp_lrs&qkk)BTKv9hHTz} zY0O4IU(mO80o7@!2cCuo${8UMuVOQ$eAi!3gRif`eMDf$dUL!Pii0#Ltt;S{l~t)_ zDuC$Iy{(LGZdpMGf!oel8NYkOkQcs0e|E^dN^{t}X26sqYm6?=QcuHXiN2s#DZh4B zlX|$>5>itrC2tr_?3wK27?P z)^{?0vOa~Z>SzS~@G`;RFP$C(V22qG-X~Lr0%J;S)_xUjI!RqzGYH5smGV_c6T(_T zG>Z?oPYg{m$&1Y(N6at{)hRWP=38Q0M~jKuHA^(bE{;%Yxp#k^#WLsaON!DrPKI7& zM>?&-34v_Oj5d~G)oOLzG9epC zo9{L|Wml%bav**T&IUaT!9Ye$99r;V3c6I-mEz%qIkrhoL~bF;V=7bKNTe2dO!5T6yKYg{1k@Ci@Qs9# zpU;2yGaNSm{ExGN%7oh)L4*H0cemG$`Dax=k7Q2`0yi$LtG3m7y+1EyA~n3UfbC*R z&0cY+Q*|v`OsPTABg4Rh1Hk1G5TPHM({H*1PRDat=dd5M%c-1myH$}ar`%DGBcWJ{ z%fI7vr6L0PRUo8OMn(pZG5;|9PxaU{UJZ2VN2ia|9jboun9Si;cWs<{&=`~VvSbbs zK*VC;4O#;KF4^8_Mz>;q-RLA}sG4dFI9WhA46rc-4==cq@T1AXt)%Rlf z(|9@Dnyj1GeZD9EeC`GUn^45mH^W=l?Zpt07mG9@pbY&)zfOT+dJivl&g4LIW-i45 z^C0({(S7dFLa;^hqwUB=7b@$^Zq{~7`;mb6Invw4!hoQFw+=dT0tCdK7^-yyk2q^Y zs-kKJ#(zeG*4cIcDKWEXHl@*EL|bbB03WA5?Nk1xdTEA)!q6mnZF5yQ@eus4%9U6@ zw|)C#X}pQ|e<71UGX!8J`g%K0a2yJ!#!vcx&NN@NFjuxNA=TKcN?UU8sLbidkhmHF z7Ys3*g=O`-(^wi(`K@;f%l3{r3;mGoF|AX|uV$0dXSotvKp(UhCYzZt_ONRGOa=^b zKW!p|^EMp$C%|%}p3<7{EF6s#=Bmv~LC@n0Y&y_yxnDuUkeGCkbY}$2Hz&pbg6M|3 z(Tt^)r6nO3;i2~hI0aubXiE!eCKyZttp!Y)M;-gJOW68&Yhvi>dlq?Si^^Rm%~- z#E~#&7tBfaDn@&F0e`YvY(3Mzu5bL{o@oIKQYbiT9`ibN0B{!L-HGqD0Ib+7B8sm=qft{4P~$@pV~BB*#mXA5w7ZH5yXyfNl=^Ikgpe zLjU>aEdp%*?rEQ+=rkUmuf30~ubZst8QnEo4HtiRGeDsbY<0&MvH?>l^Q9^{aAf8z zq)&UvdF01}CUaUnSY0u(Ko5x%>63hoHWW~N=5B1@RcCChW`Ov$4<4-_l?(e5MW9{Y`(ZMx=lkyW+bVAAGR2>7_;Lr%>uqGZJ6(B!oAZAuW=jG~fI;t)fKISfr0~{y%-KTt}=)H{kHPP!IubL`VCD9?4_R~ z5q8lS`3R>CZb`3OF)9oIkV?ey+WaVlXIG|*-t*oj*=bkz(Pgx#OYe0t_*L^+b5{dmdT`Kq8qQr{F2v=9x~z^W&>A*lI-xe5{aS z4IJ6peK!VGZtl&uf4}}9XDH2Gl`0p%`#e_tf#m17y>fe=W`C)~D$yThO>?S4)QsH~ zH*qyvksSHW7X(HUhsP-Ao4sJ##gD~hX&dS8r8^vf; z%1gm$@NY9MAm*OfR6L#BbH2Hp^?5S5Q`r{WdOhxO7bLN-%zjZh3*3t+lw_Xgo%J@Q zCH(yST`336EMr&XZx`gKpqgr?hWfw73jj4lzEBl=I;o^25$K(P4|4r$Zw=~sGjqSM z)v*Ze;8%1#*T#L4kxw4Pv{A$~_HDZHxI3z-vXy4|)}*r%n!*S*@8OKAe&twZSP!J} zk$JyFx#TKmFFD~{^TP9t(ybaUHj4QEIh*b)i-*Wzqw-K6G59&U=Xn@!|}4%UTdgB*GLI*LkLR6F1$C-!*ibA*(#JeZ2+Ps-Lti=HTPGlVhz-$$Amb zahu$wV%LNUPZtiYhEtLlXT8iY5i4*{q+FedgNhd41ye?2U+~Bca)Bp7Mpog1Lsw-s zEr3@%5n6p;9zcuA%gBq1!-*Gj(sR*k(FMdHiGK67dP^~JwbjJ<;R-0Rg`uC-t!xY( z6`?Vfspf?6U1m*nbwaC)WRVStrF~2q-@^)P9{z)zcCS+WW!vcZS|UT@X}VSXVg#go z2N^Ims2+cWNZF=#XC9N{2BH^su{MWBkAW$%#Xnh=#mfzp$Enuq?RnH^GhLUc?|J=9 z&QO5b0&Qc&mOb@xXM5!Sj-js$l`iDHj7ws?DySGUms2m*JTN?%p<3`u^*6duOfG|O zR}cS1E$;ywr%3h>yjqwzTK0!nbHw-fL>1-YAoqQd2?};BmDEC@*BOUwUI|~1OJv>m z&}DxkixjZ+g+=%GrRY!c~;Z^i4%9T9H}o2Ls;&}`GDf&J5*vAlO<}F zUooy+{-XJuFLFqRNo>`Ewy+AJD?Vg-%7fD>%0&DH;N7=hi#+`WI4kaUl|DCtdzr7p zQ|Qt+`hQ5E*ssp>*F|Bp_9TRAO}2>aunZXX4+Ez52a^Rya}`NuDSHpbRWPDa#$JMC zYoFUTm<(8i0}g>eJY#qyy72+i+&XW-H5kBeZg08M$pbN$mX?NgR59ZyXm+ycgMcfO zizG4#U?qhrVXttFTwGiX3;=VD)@&Vxs;VsEhdDfH+Ie2xkGObsh9o!6^}cIW!upuL zHDn*&Gen36s)p&Ms=S@x_;tT@kx1kGJQ3?SHc;w`i-@G+Mg02M_FIqJ+0?0W_n!P3 zn>doDkYDVgbvE!lWdYafCH*=Kr9tGZmNN13V~yN@O91^7Bu*zA)JhVisy>1ZTE|ad zYzAg_{|_bc9MZ&7gn2MQL`w|C>*COOJt$GZC#oN*i6MWJfNVp>8ln$Kp-PMO@{9FH zkm})gcutD?HSNhiG5dv_joU6#C5&}bKmqnxxDf8TH!q{MD!4v$uZt+Mq=Tb~k5yRR zwd~fBnQP@&!khQ9)hg)Z2t%A$JM3W_742Nf&nZvS$(QrbR;LShTzkr? zJsv~-@pST+>BXK-L_62GHX{vZtW`$58EhySWGTh6>JNUnd%NbeQ=Kl$Qhm+r_Y7oc zh7HzF#3Z3lwMy}`s-KPy<>L?95iYl#mb1^t^r7m=!{WWq`v8b?GyOGX%AIySY~5qU zX=PLWBGJO-d{pH1@emDT;lUFuxpi?bbmlhp3 zNOL|UDz24MgRuvT|0)v#F!^^I18)Ag`Dj+IiZw;8T#MyWQ$Yd4CE@rFWas6YcRO4B zaLs-7$h5w%&eaNS46?1bvJB;|yLBH~bRA)ALH0EGJweP>k!V6BZBebD*vELps*C4x zWV1)eod|o10?+{}j6>_jz5GU~3YGy)1yDNB%Ie5`wzD>ii3`&(L~zDZ@`NvZr@?_e6o11zq96KHSGk)gDAwP3I1qGtsK zJ7TL_%liJJ?sQ$nD6{@&4N>(FgWC^@;YSUFj^tff8qz_Ox6x9|ZopL=MphZ$SY>Fb zsPikCB-wI*wKEaNH^J#L)UpL6%DCW3EIL8DX93AuPyk8&o zpmnUR=i-TGa}@@*skB4Y-Q5yAW~cm&+m1f`B-)K=06@m2sHNWEbD&YpBoW~BZ~ZqN z>237?CA;S2Zmo3r21Ti9up8y0#-?$jyCAx%wV{RA|~uEY+~2 zbG#kWcs}*&42pQ#-Cj@6cc(`jSCMu+vI%?D9T)BHH(#WlaCZWs(Ic+8AElq1{&IH_ zUJ6QM{1e#J7le<`g4U0!TiDq{S4uJ7B7_D;9MwI!LTG!Ms7EEV!Q)!x1Dz5g_ExYt zMGXmK7&f<{+xJChP0P+w64zJH9+C>7mk`cR)lZM4TKlMU&0SsmOEQ$w4!{oi=5T7$ zc~J)#T00!}Wm-48?<;x=LMO>tYuk`wcMp{4p`)cG`td+ul) z)#TrgesHcNJtDu+8xkdzmPkoP#{HLjC-Fy86jCwD-7eONIkH$v6)A3it3qmVo3iq0 z5d+Xf0{aN$KY!VpbQT-W9h%B5_lT-inkVWB&A>O#w|${|VjK7eu873=guRl&U6)Aw z*B1{Asbl{wWP%boI- zs#>wZr9+p_Jv`1k@*Y;kPE@l=J^sx?(MfCDvnUD9g{1FfGK8c#Jp1H|5s8GF*yXN8 zeXF!;m<&m{=b@t8goAL>q#@S#6$fx3G);z*l}Vedy~9WZiMX66BS#=b*e1WD-t#~4 zZakYX{1^$!m@qNV030GX@1k2~-jGV8Q+5Td5HRi8%Ao+`%~cX!=oEL$}Lx-#UB z0-B8Cbomkkdvp=~CxD1~b!7)gY?o1$K~+Vnbh3&04~onYo#v|OpTB=eOiVP=t7L{n z02g7aO_mxlrwb*9Iuvz$-^7K#UebtWR@1U z^yX6Ukefq~Onc0-x{T4ZS5J0wY&rvA( zaRkzPXkR4LhwbVEf_1U9T*6Od_D)$P4)uwtS`zQPX1hxf#%FV;qH$hj)4Cmlkaz=d$92=y9+JRzb_N@b##J}{}EJyH*K&>6^{>;n_FhD2Ms{!jpQc56S;oG-wWda_T13!0g?JoschW;Cbn8+W; zfi@2$C8FPN$DO1MpwAfRgy&C+MMPHWOAEeD4QwkW3@aV|XVGoqF`4``+2s_od^a z`!t7R0$^dA3cNHXAjV#?qLT5O%1IKxRKgd_W%Zs_D0}Sn!8a~k{Y60P2VM$rkjWk) z=?~W0907eDTe^0egYiS^N7KK!S0uC^!NupTtu5ep&N>QT66Y;~iIH=GgO3_2%7E|o zw!3R2W{j}IA@|>cl$#Jm(mbJA&T`pBhc{C$HU^l&06HOuHW;tGMw!1HUZB#d z7e95#fDUrz?9_S^J+Zci$#+>6jhQiNstgs{B;+|^?k4s7XxGQwqbFG(S`Y|JHlk7L zbjvl5n)Lu;qv$78O9Yd0))^Vp2VFm+SgRVB-L23yh6s-+?A%3s5dIIG8kgDucO%4yX>A@uAc4g+m;S74gNQ-k0rgIn@=r0$N9IFy1cx)Rq)8+u+qzwS;aG& zWJj~P@3&?g<>eLvxq=UCj==8H??|zgIdzOuI%N#J@cj7b#(@u616cF&{6~^cilV`S z!bYm$Qb7j7RY;l02?EmqS~v(fjbpjDi?V|VSP2(egahKZL z?$|=Y(gf=w&;;v`E+~)7T&)EO@&3~tCeKPI6>?$s#w8O@ioixvO(Ux`#Y_!;D%8gi z$q*UknEF>w^GBJQ*8SN*XA#f^D*bGYY1K8)kPg%HBycfRItuFPAFQL0Z@E-U3p;mLvI!O?F%Q23YrXc27R;1QtV)j8EH>S==sE zY3bR$XqY~+btCC5@l64b|8`qWF>O5#L|v#om1@Yb)AJd7ZV30cu@K<@W}$%(B$sYf zm64gLZU?sJKq=YY?gPF?M-eXI$z?E58u9fd{hGb!KG6@-0_r=CR}}JAr|-DiMPhk* zacBs4-;=id2Cd|%(@@}bq=bOL3;bJZDdB=U%TL>10M^V^RXo$71_CXmwC{_7M*X#! zabW_g>v4wXE)Ts#*t;oZJO5i-Yc?OrB!L#;<>pS4FIlYCSzTFqJ~I`}JakW>yV#z04VjOxeWj^bi!!-7-j~N|6Z41zJwJ+kz9Usce z^fYY?l6Es*`z98kZDo~9fSIWuBT;zlgs6sYGSrC_NSo9dIk*Fqdfm)AbDYyhJ1W6#jg;V{fVBQ@VKLM(d~xiv$G`4~UmwEZEkoI%jj?f< zvPhzbTW_kGdLHXypD$u`R=Up5Ulz1b?N=ON(77esN2ePBRp_=|*pd>1>Rw>b6;$5G zyfZ(3w2Q#qk1~C7w(rb*_h9iH=pVhZdGyd_XmzSUrl6-MuOdqB(>OD`78TV{nz05T zrsJE6kE*j!1+e;I09zfF1j=xW?PiXAi4awS7&}-5aff3@)4djYsY&e%h%CyEleffO ztp89PBq9}1Xx&h9pBM{DmXZ0wN%XR`TZwXDy4ry9Lc05P7HYACEI^|b1T)4EzSisKVexF6@Rq>$&-!Dl zrqgzOER*D=@ACQL@~Wk_?*DNCo+M*G)&*aCeVr6DqN%8+cmn=YX~im+6++F*807Z; zb$q!$pYpkHP)9WAm>mDFwD7?$Z%I7TZV4(iY0%B_J1nI1gIlGulMsO zY#RYFL<-2on4unG5*S~+L0{~9LueEB1_V)i)UgKJ91o*d(artQp&)Rlu>DeiJKD)c zCB3v{#yN-wqY@*llu{aCSwYkCsX$*JVfKJlxiw?Qf0^8(Sw5 zOAGb0<;={l59&vI`>wc{{{zvOXM=#w>K55wfu!~qiw5-d7okhH7E=5{s!!Dp8YxFw zy&nBVurcJoOHo$B!eQ1WM22$<-5V@i64{;I9|LngM;Nq*Fiz}R=>{C>oJ6w<{Hont zWw1U9Nf+B&CRB98dh1>qM24&}g$)%(d}7l<-2NJO!LPpKMt$F?f+1Eq-S>HhN7@NW zWW=j3ZOU|Zxw4#IrS5xCkO(7ra%bTWf>#H^;9hg|!fc%|<_{ebpd^(p3H^{b{cI+$ zR;>-JJ<3j>0ob{3!0!Av^`=Mu%y9U!d9wSZteBIN6O51SqI0dsZyk7>RXc8=rZbIU zY--c)dkLT^w!2!Bd;KIkWYM7xhM4#BotW5wPRw8LSA(FWUn7@JfJjAAD$XyA{7ROu z9((+K#!O!7@`>at0_P(qqA>8RR-f|Bz3pCeuHF@FVDPOJw$mjg1XwG$=L;M}di+D0 z=}NtXjIFj_U0>JnI+-zZva>^X3v|}8wYJVD%at#&<@Q3Yx%&HPL)m|Eel9!=1xFe} ztUeJ@0P#}IFa}&C@zlO>sE`^NSmL@^Px>sl!0vlHk0Em2qD>v(Wga^@INU5uXtmg$ zUtTJFq2?~rDM{y+`=K&scKH?+8HOvH&TgFCin5@-xQ&sw+{^^!pH@|&#ZM(Kwaqv$ zN}3Ugq#oIlq|0h>ARs^5_SDr?vNE&bb1fG@zA1!?k zsRg}_7QlxjAN;@zU_}v`|Q2=ZhgG|uKMY6J)w6u+;fN4?XAY_yI=D$b4l_R+;bQGP$G6d zPx5qd>24|W83E|9Iv~51@FD(x5E84=BER}kI>CF`f!}7*T>NJ6STKi zIrn!tz3aYwDw_3)ZAss=507KUp34eix~X>mhTWge5WmIW5P><4hjxFyLXA~=Q4`>S z86vbfpJJDD&2>+IJ3l)keaHzD(RU`L5v_q6qNCGM>B^hk;@2mD(;!bed!)v~%o8p| z|6LtbPXJ=l3?N0LBKHe}@KDMuKt2~Y*&u_2WkTEmS|gBwzxpPi|A?0)e%hlJ#LFCj zIfHSs_S+Puj95VxaC&6KDq9i{88GncGQ#IjJg;5OBSVl_)JQ=I6~)p`v)ug+2TP|C zSeou9P#_z=eFBkE$T~0uElh$-OpK?_n)e5$-qwuIP#kbZ?A^^Q_W#BuKW4=VfFFMr z7E)x@$ogN%mPn^*r$MaXtyhl*_5@0Gkje1_C&V8ghwlK92`%cYf8`1eWalU$l`zX_ zqYpb;Q`2e#1u$-Y-$?cTD|snZ17~C?9RQ2aCvO4ww;D_4SnO1V+CAk^BOcrabQP&T zb*2sgwP|x2b9p=90&@lKUF8^JLHLq_p8Q9^lS+()2WiZY1n@%X(&NsYu+!PP2rXE6 zRHR!I0kFfJ!N}cf+{$D?4s-vs*mZsH7v`dQ7r(fMn{LTv0|H}l%;GA*=HdLLun~N0 z-$BV8FE-YIBV*Hq^?D$?M2+F-U!-^a)%p8Zc&|Ds$+rBY>>oE}YzI?gzR3g!Ib_1_ zkR5qI`+1Fpq+g8wC8YfV_#k+F-=W_5a;F47o=o}0S#U9`SvSe6iqzTH9R-B*B`!Tx z7`UhX{i>V*KnZ{cFAy^#fKM`w9k>v$OWvKyTbn9_+%EDTKD+DwoCij?nNg!44C>|! zAgv5gxeRV1kxEvizK#L8k9BDY5q*w6pSKeC zh*C(DSrwDz_Ygx!GlE;yw11Jg6-FL3t_T5h7=j^7&M!GQ6sqK}DHdLL8yz?Nt~`fl z>%Lx|ACuiJe=Z=7IT|-KT#n}}cyr8sdoCZ|x)rb}$}Z3uN2ao4W(Pf2AiT6M^{Kid6orhg!bSox8!;@-|SJ75a`@B zR~V8P{Jn1ZxY2XF{L1Kkk0y94D)@54_3_tpbBX0#;r;f-C$RhOt><4pfknglp@QRI z|Iv=vw|_m4(+#d4TME9bL@2C2BDxP~`x*-5;&%${#+-bXxFmsiiBOPGCKo{31F zH+@@~jEv zo;!TD7cYBuJ8Z{upRQs*Lf@fDUXQr4)7}OpH*UIJ?ootJx=IAE>r7RN-4^eXy^orE zx`sIYJM3mo(SVdUuzIC`X>y>H;~&eI)86dXiSnx zk-Nz;7PQ#c0hJ?jHGHHD_RD|W|#c&}O+>ecbf&JG6Wx*Lag0qoh0+0)_{z z*xLQ163VZI%Rv#p!6%lf@_tAD`QJzsQDg>a+A< z6Lzus*hEUe$P@@K-VF+6jbd$EfZ`z(CZs7$a+34ubHUvECXYU&TUbF;r*FUz&8x~M!X<=LNv3dE;+TMyb+4F-8S0TNe_ZA=gX?O0D>Y2Yb zobiIztUYGf_9@1tdjPZ-&9&hM1dNe_@T1{m^l0L*PT*bjC<_!L zvQPXinj)5=Z^c6g$i`Fc-nZZkqkuMQd3}A5aiz^Cf;+~t$pbKu<|Np6kd`61oWFc< z0lolJFIU&l0i}fR4Gf?A=T5&~%-|XQ<1=!SS5e#z9*6$kn(e=k`fX#SmFa=q+^BIh zehk7SvycJ%VM(NLw5)ezbiXYQ+XhPb#^<0zkCl7-!s^w+MSJPd=WD^y>vDDO;6k$w zb>+c^w=2?0dLixmRXcyHlEz6Wqs^LKgI)7iU*n=2ftNntD-@F7p*+vMKr21~`Kig~ zErV-2H`Zq&(Dvy_f#1jAeQ4#XE>^JXeQT;`cgREti?H(;n>+(Usr{xb_r*Vy$JYBp zf!|H^C%T-T&ymtiG0FS0WqHDp^X4m>%}dwEK$nKos}90~Fm!1Roha;f`f?%B0S&QTSbzNTgliXuJ>u)>Kd8y z?)N@lw^M2XtIdN9+Yi^C4z%U_mc^~&^=C0kTv|f|AZfBhAs6mFBpqT7^{6V;0Cdd0 z1;j_6JMjRP;z3MMKT?){q<9>L>Ce{G%p}NK5rh6L?5DBxr_rpIyxHV3?-H0R}i{zUZr*_ z!4lBCoMlZlEl`F>Q5xZ{^Y$f>1eewwA!eocim&|}e)JQsfP9XkCc}4Y~o7cIr9{_9L8<)J_JlzSJdLX*|Z`-`LBo?5V1a(E^8(7vnY`1SAU9VZvp4WIAp z^)MO{&m54)pm6!{(rOG)6IL2>!?Vank2AZ6ifGFz)(lu60@IYqegm2JfL}e~aI^$8 zc+ynhPBJc1ObK_GwTM{>3(f#NwE(c%JH2aPw*iz&F1(4?0JMn`8m?SFLjxp*1)YgQ zrE+rmJ;{8-{S_6O+~gU>BBA-cMm*j#SS*NPs_MbQzn8h<4Bh!KvOTz=gCz1XXjUByyT zbIdmG()-;gx7_z!q4UjyHzFhUzIc8$(=97ZjjKXivUJ7cXB#|~#hoIw?~l8{(>^oT zB=2-II@t*}U8xZN5!1F&$&QAVbNbo>jQwa)=cd>>;1J%YSjr87*jQ5cYlkSMyRU+o z3HjWv&XyZUo3|yP3W!p?fI#gd6l9)4(OxqbABeA+#u^p#P+#CMIf-MhJs;EU8VF)+ zA?hKpxA<5Tj$KEup?@t4@FSy-@}Q^G*;rZmeKN%y;E=Oy!oOH&i8eTusPqCkiRA|j z=L-4~D}J`5WT6qYCdLSMq~iJ=9vg%Y-34kyVhKUglLf*m z;==CWCSc}}g+7+1xY6~G{M+i(>S`*7=8OgF973!w+e(GHf=Zy@pa<$MNTNNFOSh8% zkE{P^kXjr6u#;SX=-0`jkn*iX!T`O0XGm9x`P&fz| z5y^r_K>_QToGSu@9*v@v@_$9~0QEJ1E(L;jk&Jk7J=E6BHw`OPnou^E~4RUfG_+o zEs8dO>RdV$4g`$=2YO;+g85a#?xj~gt;_DPg1|jyt-z(j`}Ogf6a-N1?Fqq2(g}8= zRzTukz+Iny?~fv|GVN7C%t7mT@$8dT^Dq5F=<5QBcI0~Iw)JgzKj+&&+Pot4-~gez zID}nfzDI&FTsgY32(KTh!X~rAkwQeP`p88|AG5B$oADHCj)50-!^C$2d;O!w=@*~N z5dulUhHi~!6z<;ygTmdv{{xZz_g}CFA;YyWgQg`5mB7m1+^)az*_Slp&!4Q@w5V3x zdGM>4mDZ6(0D15O+jhpru%?D!<-VXgEG!yJZjxd9GOSekeP!AqzSwMMV$=jmyj#!0 zZAC<785(c_jhIphyMG64KSQ4RCJ4MVBQ8Z)jc1Vcl5oYJUNp^P`bWb}fKgV2)|X`t zE)bz7s%aZ)JVS2=E{UMlN@@ShGRf}xXAEiYuv38NkECp*jT25df)5KSW!0qp3nOLP ze_s^47!SSRIKkJRf&Xfj*w8H0)^D0Sc5npWUd`_R*uIVFt-9Z!z3tR|EJ*s^EDBup z7DHuhR34r;bQyD0p?1INz4m7NUiWlg3TDYf1@D6Q3xIsq!j z!UDDsyUiP*DcngJ{ROp`VT@-5xwSe1r7C5V&sSH?W{x=Eu-2SF2?^E9Z_a}IpWEiI z{yo-NViuAhWniHc)iZ?dQSOOq z><-4$32a*ZQNH^n2opG>Q|J-~VLQQ&U<)7jj}RnLZlum{FbJ92I=o_@;H6nXpa`mul)utWt38tGUHdnRc zCn*`R=x;Z|m4{9mO;HXiygLg5OT$-zW}+7IhP+6-fO|rRFuvh`Ly9CRh-N+n)=t%O z)zO?hv+gOz=5Tl+Gc0D48tCnLHmWij;vRJ{(u*zkI$~$_sPCZEJ|%SkSy`YZ;BN*Yq^3o&!OMlZ1dN~{+T)w^)UkDbeDO7j%( zXTDgfGqNYNwYBv;v~4UU5wK=uaCdUm&Zo80b<) zSAwy#y6hQ+;Xb6c^Rxvl`YY+&eHfJKXp<67oLkoWY~S{NCl4!GRq_zJaEXbzuKUoB>u$RMF$ufeL%+QeC})owSI+@Fyy1t%{;?o^{97@O?ThAG z5N~!2^Y3A9+9?Ugh@ohmq70Kq5mW|jY^V3aR4zgKgqgQ zOleP>4X0mk9j9@yE>@_fSDb*kG8zWizSVH2l%gbf_Py5R)26gb*4%TNjN;qH%JB5q zjtRCP9$LuG{ZVEFQ+5TRjbc`je6|UrwwOU&&!f`Up5pz_gxQxHOYd+E$jt(^mu+#8 zx2X~*t!(vATk})CJ2Sd(zg5!@3f&v+e^r#zT)qunzAb~3!lbG<-X>S?1)hO*nNM80 zm)G^&X!hLSM@zjYejw|50PXE4_Wj_-Nc8%;$C1nXUhQKGTsP{W@G)u2$KTcO)~elg zYQ3oaTBY}PHrSS~_j*?2bNd?Jve89X2+d^^o%4DV=~&Qt^EfQn^s=vh|M;lY)6e&M z&Fu75$>UwY_i&2Zrn&R&$oBo;rGOykORu%BXH}UV!(eGsreGkd6I(ifKHPfnb9aNy zBh(#Y5{5*~sLBmM@T}8}z_xCK)=hYA0U~3jQ(}lXL7+CqL5vfE3Y(zU(1G09&ZHFP zG1)#7dS@F;x${$p-|qUSk3MdQEdpX3+~MEqd)ot{kTrPSfxV)lPk^`3_ffynA*iAB zLWXt!+d)LqoiqbN_aB`QZ_^0@%%<=jLKceo^z`(?=#@1!(1_3%!}iFwU)^{CB5Eh- zH+$4sofZUsUvVIkX}W+WRktf;n4{?~Da5P>#c%c+^)uiqZb#XJ%JEy-h8P*Bvx)QeB|1$@nXj zkUG(_V5d_7b#Pt@YfuSG>pQUs8&;v$^@ywQY}t2P}~v&VUS zUkdIwZjVeCugRyX#!-9hZGpW!Tp&;*GYIdrD(3%7ot5KSce@)qq@KDPi`?Rpid#l&{=zMgd#yK ztW~X;x0nY4!srGoH;7R~-`?{!ff)P1Wh=TMj*NPhP=8~l0McHNtU*LU*H$tYRM2K{y1L`H)hsBD}e?f&pZ_cL9bWPj{{ zB8=)(lNvXYVl5InS{*+nd#Lu=jxj%OX!D=HIl@u`Zyf!yPih*x3=7;OOi)C za`O51gYHYO%a(QY;itgO_s@dY4M2c_l?_LRq-~oubV;lB%L$2_@8zNIw)e-?CMvCN z$CHlWt5FNbT8GWrhoCRZ$1;iAWh|`V-Mg*Ny6gK$%jc&kVFUd34=3O*NmLx$-&kg+M&7BtH%t_|^^2gPc!uxawiKfPS>vlCS*DkYY zdE}p}&FcZQ*R#;>2VNg*@N)Y>%3{r#W>L4GQhQIA1lRavdcV)Wfuuf@wWlY6$^&q% z9&SK0^y7tC4+12}O>8;!FpVdPQEYNx45G>UBsdNIs43*gDFXRwe1pvw1wRIHYVZp# z7(u9{$4*3OY=Nqlxp#}At!_jHj3KVnvTCe{|Jtou0ePp}?sS}CS?&I`pL)G8ecDhv zY&$KAF;H!A^+!>LOf=#vnqv8uQ6XZv3SB7|V5<21{H)JHT9BOlxl^`deMqghKZ?2@ z;R`XexC{Uac~TUM1LVLkEmF7Xxc@u@98dNdFP9koJh=bJ%3oO}`xQ|4sI*{x?x!}hs=K=KjL)G^3qB#xSal42?B|2(Dz-#l{*GQMZe9c4I z1@vE{)T~$|-tH7(QOSXTE71tU6s5G-^bvVg+?ib|{3f0i!((4tC6g1e)GvMdLhfo6 zx;p>@sn|~NFPpIvn8@n*1W}C`K#J^8)kLP6U5DWzOs~Axuu|i=cTUwu zFG!f9R-PSY?Fx$XQcYU5X@c>3D{jJmQ6d&1>MC@Vh(cvrxkw7uA;*VpJr-6U|8RTu(_qi|UEiae#E>nWfj}1Wm z()8rOHz35k{RTn!DSFt5rj~X8Sc^tvurJ$^`x){WN(`zmPy;>|N*w+p#GhgbH0}iT z&q0%nqk{nl5=Ph-$L#a52>O?PT;ed2H0Tp|6@0=s_RI+&nrzLIm)u+hb2Lpl6_?}Q2F#1VH4ATpRn)W7!b*_1?qQ0|$xaPH8l zoE;z9?ow1@*}Tlu++p|QAN09bQ{?OmO2STrpb7G`&6xOt%HQ@)ywkQ}8Kx?x*#|cS zeX{;R76@%c4-zhI!WJ=9V$V+|O-xLG3C#4F3mf}fUk^VaKQE6-@4yHq$B;oJ8x&FO zMBJg2Sml3B%+X$`(L8b(ZJDrlwsqACDjCVewP(nem= ztlrVKmKOM!|6U(YHs2ILp8`TSnKrzC^hBh3>>Q}Ym=r#F0SaROX3s9-NeO{qMNv+C z6fyu$^_!1 zk|q1i$fd1Sv-ngDuL-F50T#t77L54Wfl9?ZYK}LCAT?M*wOok@An_K?l-kkYKvfO; z^q|$o(A)44AG*KK{fMOp?QJQ2K#D;+z^!uOopvzcp7D{u54-+;R?m#Y=gpaZ&gYfO_k8YI?PK=tO=IfK+V{ma ze32;9T%8wn)~VMJly?msLh9ZG%@!yF!|JK-42ZW(q24%DFhW^|67i)u zE=kL}D=g8JSA$25acan4LZP!(oc@A-+UYEC{AjdD7JeoTZOzSaNbU?+S$*H|qp$wN zP1v2F&qf@f+yL1$JTx1+Gr+HjPr% z3UCvk6`x+)t$;joWFfm3lmQJH;4=1dGhoI^h4e3)&Uy$5#W=zKJIIL00#hI+D3>+X z*DKd7a&d9xTiS9~g-QT@AUcdNO;8+LvdH+Jwv0h7S0$8x3Ij>2^!YD(O#;0Fo1`s8 z8wx6ES}Ftt{2XKhtgp=KjANZz8z@M8(|#hObiqzysXFO>QPQq-hSVh*h;L;{Y!N%k zW!e=#$M$6ihlO!5!jH{h$bf(YjSLZGBRm14Mlx$Tf2gt~zvWK-MWpSzV{xUouMfVT zqlE3g_*j&Ep5Mbgy6V4d2?BGP9OhX>WXU)Jla3S zfkv*q7M@OHJqS+K4H}6y;2FT;W+&$}&`@opvDe5`Luk9oalIq|t|y}J1z!v0w797# z^VHVNpec$npn)=8x$70;(n{}iW`q5H-cZ3b z0a*{T$9^xp=df~g++~Fbz4=B>nsV6!8tlzU>uvjt(}VdcyHB>=)Qy^q$kC*}w|~L1 zCGz~R!9M{cWo+M~YQc&VpoTkw5wMN;460_m4G-2_VI2$~4wV`W-~R9Sm0Nu@A4 z8>R9+lK`B`3Ht|{0|BH2+zhIEg-;@O7yelFy<5cf@P9uCLrlg6zALLoRqyqS)evdU z7eyZ&D+uyvG7VKf{mCl0V)?SDiC_+*sI6`s_=yBhY-BVNL`G5xUEF|847i5n?{0F?J8=)5q|uphpHSH0fQi?-2sc9G8SZm7$v&Yv1A!SaS_0;7(^dU zDP2E)-^VJ0WQ$H4gh&pCf`!^(Ks{NONWE%sxcKgVzcmSzJJ=J`}q^QCP9fTi%W=trCFn*;8hje zGv47$8~T&aY&4gi?;8qs;{F+<)O*lQ!5fx-JE?-t1dI2~qcL73V64g^_wx4s=MQ3- zBQor~#n&|^#cR~ifuj#m3OChONQ}~dAU@3s-Sd|efsF`GbU* zHVX-JW$BRm8T%7MsAo=m`2xV$Kv^b;9R}!!j*ggEY`^(PGu=fvBFJ+>_&o2=>WqfN zMr`xh;>YQ{-gUdZNbG=95dcKSLo9Il_1lHQunrj&V}~DnLub)N#K%2zN#lePta~*v zGBUEYMXMQg0IcYx(ijtS=1H05h5qJE^?hSKor>Z;(sH%v-Vozq5Xmq5QSW^@4TdeM19_C4*0iKBwMs8&u9V<(u^55 zKFY8(Tjs=HryOGq^dOfIWql?_zZcg}{F++`F8#D(%(m?hD9V3yYeL(gROHMWAVdo( z1>CN-%sBd4uso7VI5FG8%failL90YNUsv&;x4wf-yqPiF-?O=`mcmxrfD`Q z-*>JDoQG>dcET_}1H%;E_gh1BV`JmsiC@4vy1-GdvdHMywo^?PJa4mZ&BKegmt_{5 zc?L1J9fb1=Fm(c-GO_1b9q=wuB52%9*D9B(Q~=*ePN-+_5eD z*TF1J14R6;t4f@H>HM|4TBk2j%Aj*EwKsqG4|Iknq$k+4`7S%j`FW!Syc~{U#(cO2 zW~wu*QIYyG4KqaZY2+@Slv92yEK5vs05X82@AvFnt4oqE_*fB_7yu5kb)I0~FJGhSP_a zP*kD-bNtgDB}%^pQ+}H+-B5;{P-YG0_``3NCVnSz8~DSlLFBjx(5WfKv?0dJ$i$^Y z`Lb@jlfDLEwoVGW(@-q*y?@`3PZ1q8c_~Vud;cRH#gZ+b%gb%rt(ktip z@f4CQnt&lFa7*jD?66Y!R33SL24{$;;|{bI;6nG}56f+LNJT{R0Op zezZ_Zg9>yxT3F_Cd2Hxj-UI|A{7K}xS}*)fCG{r*4XDb{grKG#tG)}@CHMRI^C4jw z10DN(>IBpEE66J%vU0f2-jn&$I~KWM7j}Jmf@sHfI_>R5z_r%O)^-y}bO)%;zsH~k zp=R?UAf|)z2!jzv9HuuqIsIz)@I$CA0ZU7+Yhl;hX~ zN37Ag@W_p`Nf`5)z*qS{s~xj}1F`Q8xdK9E7eSXkeK%NNSSl1nM^I-x)G$GAm(D=O zJ4V5lR4P=p{jYUK@`MPYQTYyRD>?9u0RTKPL8wfq{R4pvC{*hw0gPnQn?DAG-C4@G zn;>eUSpibh(+*A#D4(6~zu}uq46ym1xA+Hcy?%w$E%be9?i9$C|IvF25I}%6+cv;G z@$0n1BWLzGoz52pZUhxN{yRX^7wP0b*QPc!vJ|S}r14marj-hZGCJwXR3gkorlXp6 zh0?buX!o1Z0&X)t#J_%_4JAqEm4$25>89(U6LPa+-5d}=fH|~X?n88V(y5Fi?E=I0 zmSJWR0)K&(kMBIpwDL**0r7++{2o{v%ts*xsKTIpmnqI!7==!|iLU>t54i`n+6PAO zful>l2dPYdOUw$YZbE>9#6_;vjo6_v+_;tZ~X%^J0@z)d^P^|C44=_rRX% zYi)~1LZLg+GgA#xQY~+s{(CKfy5tysgBKAw#e3WANQz`H5bs*FZb1cBl+avb=EuZS z*j3QJMJT~$lNjJzXDCKLqqyr?xCgwo&n|=B&TTK7+uA$Y+C6<9rgeQI?*dwBcU=Ts z4Yu<1zikp{+oL+u7brwQ!baw5WC#4jG$Hj1|L($845JO9FvSY)eTza;;_DS7)bl?d zc-<$=zzow8(i7&Y2Uu@SO|a55T08+~p_QHMHb(Cl<*Ih$TP2VZ*YP{ta4pe9P=*AU zZn!3}Q4lsm7*I75tnIgO0n-r@;|n>Sk05cU z{Q$XtQ8QXOhapi(h{Oys(qNGrGMQAaEWLsCgC7_+f#muRW{XD*`3wKqj^3wtgoWOWb9*4OJ{<|BG3-b0nh< zlUhDYz#IQJomIRQo0=Y{pfiY>kC$!ERlXcd_xqa+?RPOkK_4%kY=N6`_9)zq=Y^L3 zD3X9|(L~igJQ06)!CzGjd?6eRUp|d4Hn8CXN)zliO~}$r7ZH zCbMtrpb!ZLjc!}fN+FR&Yg?={M1MS=;~$T|q#{bbH;OQ2js7)RlUb8*O1d~l#uj6; ztz;Q@*4-l9S8jC!ZJartd^k5hbU*OF@EQO!1bjnxlgqKPsbxz`xEAikUDzdL;A9+q z1i4wfeG4!+vgku5gsglvjGCXHCk4gz4!6ROG~AtL7CaS7;q zbl0s=W^kKu88^m$LzR|kYimQe=me&NAPJ7GlM_0YVck8H~iy2uF<)$d=ES*t*uZUB2#OF+$|TS|L+mkS+hbbud5wv)9b8h*CO_`uO3c zlnUYvfGT;iQA4Jl-vkKeMNJT2Cq%pW#Q!+9TWJj$VyJvsBZsKbt65x*i5m{+>!$b= z9!an62!&G^*SqZ(7^iGuWHbdJK`@E2GIqt7PKgKJf^3mSrCJT za6dXPt3&F_qWqGw(joF}U8Md}K@p5I4Vc4#2HKdgWK0G~gM%G9<-=fF9FkIs+2v*$ zwEq@kX!Jd2Us>A8$^#&{ECP9UEAfsZG{<{Ps)ZCqvCyqwXy13aySRM!)e3~|561Cs z{kIM)CsF{dsa(h0q8Gq?@+Z5516W#G4(c3kDKAQ-|jph{#x7y!9B zr&Yj>r$aiY0^0W2tCO_P5o*~rj3KwF2ir8@=fetVKU#$`cR@ZFqN4e;gvD{Brk7mt zwOoE{K(A1NAuzsq0#Y|9=iIsw+Y1Puc{kosxLP&-Qc4TlcaRjq-rx;{s|+OqeRcIw zzE9ip{*Yzt4Gd@{3c}jb(h_iBadpLM!3XKrGsq^+{PFTT)a7&F?Z#(vTwCUDK>m&B zaJ1!Uyq=P$7+YArPG?U$WM0}t9Gkelp8cPf@460h_wKBO5>~2VuZQ-FfCMb(msGIW zLhg*^s}xzpCxcYut#eG;U=Gf!#K5mh_d)O+DENLNX$5clYN{~4612Y!r$iIqay9-B zO{eGjdX*wG*Tj+3f%pjd(NvvhGX~xAD+F} zT64{S*mH8iw2<2qM~-T;d$<^1Lp|ijmz1_88{1D8{jGVDFRj}opGc1(ZhAX8-G_8y zjv!mDE=}|}Nie-MoUCL=R{8d$E#U3q?dPk~>h`Oq;|*u@ARi_}7MZR{Uq`23Ws`el z6J)v@C((csvF71%CqTa?^&5W$L9@Kg&F^}$&9AQ&4T-&riXr^Y$Nmk1R!>s1xHGg+x8fYHUQk2SL!M* z5kiGI1I)H|ogJz2j3TM259R2~_>c1}F*9NKBUZRb>mLikeD8{t!gHZAVIAGF^ijyj zyK(3e)(J_P3N;3*fIl9EC~GyZ(Wo|un1EnQcBz(N0*6V`!AW))I#x&&&~j=Ty( z9svh$GuXB0V~4>~98Mdux*3Xh4X%2wlF2}w`r0sbcUz+PX_%{8=h_`5trh|#G)Wl_ z;RFMZrlI8;4MQ}dw-ySyEn+^0c+Pj~O~2CKzH=~8FS7h>-#R7H+qk-V)-}Coh*0mh z#cNzn;(x?B_ z=4y9nkt>;jeVRE;8mu@`DlYbsHWTLlf)!`t2?%cmSn=V`n>n(sz2VF&2kvXufMw$$LB%)>XFa4~dXy4!gqN{rlVn_rbBJK+zY9lgFL`z6 z4}W=sM4rZ#Nd>(yq;yN>Av^%NnN`^=816je6eR(!y2$`^A5o05wZdFZz8Ndp|%QP=k$fV+-X+Q3(Z7h^=_b zvK%fwn2_gS5luPqIW&tLqFk|p6U`1L6f0^W_rsiz5S`<3lT_vD!-gQ!g?NY>3Okmm zY4XcbT{;`2RHLPbp@J&~dvI>JhCz=n&v?yGZ9rZ>N$QbJV&z30|K4}zlA}=Hm9I@4 znTCb|OVWGBf~&VrQT1AGJf*a>g_WPjPU@oJ;;*bbU3W%a#=<#4y`T z7=;pb)rw8aycNt3FASLeO2A*Q!ptEp7F3aU@A|1*1Gj{X{|+T&4;o?*9S%CtZ1rd? zod_+Ws;a6?4H1c?y2L3Vh#6K2dFdT}y7ssDWC#^RnE^{zKqnb<3FS0q2B5Av`>#P zM2?b%R4ovvmsmx#Z?`dqV2fed_blZ3GtAZ9)3eQ>PGWx;l83$)B(m9YO9cP6PJnpFCl0QrPLBLdUTek64@3|PuI;D4DvDItglB5o!E&yDNYh! z!us10O7US8M4XInrXPOJdVWjzcOBtJ9U@3LpDqlH6lR5>^*SVLz&5*AJ~1TIQ6^Gutwy&8W|k=l>cRx>A5?@MliE zfo?Om;+}JFgyB;x#2?Rb$v=iI+~SBLM<0pRlHXYXpW(GZ8SyomZev6mnmr;;WqT`V z$BF-~BA@5uH_vL^;B3F3<(K}SFM#dzy|ir`iE>fQ^vxG{cibvjpcFtH4JrhXptjz? zPVw7}xEeQ=rCWR&L@WdR*GEdcf<7_Fj9sp9;f8Nlk<@d17!<_0PrXJJ^o3qQq-`^eV#i-owzi7+z z;ge?Pa&uq0xzG_M6q5EVf2(=@Gp@+M$3m$GLVy@>YQV!*$u~)axIjysrt~^sHvTZ0 z4;%ql(Fc@7;X}l*$b~(O`nE@VVWVbLRRZ0-bXK93&)jeMG0?)=Y+H06`}55W-Sj3QRPj>BdYD*`TGaMYg-O&0~6r#p^w(B!3)$) zrd}toPG{pW>;MB22fjo=`l6g40X340!tk~gSxM6t`K$}2MClGh`@!~6mHd}h($QLo zs7dxMJIcR9i~RME)W}_??4wH2oAQGe@vi&tOFVuGkTcfK zuzS|eoPNj&`0iP_fa&4(EcaPZ&l7)ReGhNq6B6xMk(A!&&l2yeb!%S#j0OleNr1&* zizc`yf4Fo|hay0wnbRsR`fn3q7u|&8!@NOd_HxRdNK3&;c=!f+X>_I-e?0f4y4DTB zn&4=qX3xaF(^Y7#p@w;yi4w<9&`wK@`H?+I#hy(}6hq(#`L#>gPlq%Oe%UXUS@4a9 zv;u=vp)J!uz9>$^9|t3f-|LA+EnT_@>(N!vCq-Ft}gt3^=qQBXl)34%VJOY7|zI6W0B(0j50&U%OU+ zz>v{SvU}CbGN6+Qqrkgmwvk&{36fGJWBcM7l0_nQAs9kFJO0k%RJ`h4MWs zsMY2sF^F@W#}PZwC70SdI>rsCr8ufMVCf2}2bzylB_ND=UJrt13g<-YR^q z8j`@Q1@84A0pX}>)4Ub;DJXz7D1yeq1qpPEQPWJAd7gTzSsnOD!J zt@4QTY(=K$H$4^=ohCKqYiephx|lkkLU0l}vw*unf$_)R&T;Xh~NXn9Q>H(3}xOd{pFv0!BKg`eOI`aX|{bavBCNpfa;M}mX_tZH8wS1QW+T;0i7+IKUEn*NueI|C&n~TBbYM)%Lxis zMzwEcV-5U#`NslH>y&v6{K|NJ*W3!1aa?Eh zL6&|T1O&CRw4a1bsEWhM!)`f2k>OrXh+hzV5LmZr&$Y2;Lx{l7pp)>`ldoENpzVqYDdEBfQ}dizztoWAn!HH&ZNu-u z=!B0^Yh~+`Q`lzYC+HS#QS4Sc(J*& zJ54REhSWhg_=b3JH>*nimW;AiJ(i*PNRTjEs4wOla?q+YE}K}7-A zwq=udHlc(VhHRK-I|Vzn+)>!~Y-n$BENd~O1qK6|I5u%B%J#a*;v>8022oQLYm6i{ zNNKH>Wwmko=wee6dhSWKU+V$~80;a~DttBX$S6=HpZhYK{8UEv7(Id%hJMP_tpc=KiI{8 zgpER358yt1FD@Kd88{;m{>h4QtLRp}+<(+j^DGY!~F(-Ba(F{oEq~^y{=)i2ZaPhFRvI1a&epn|aiR`btt_eFoEJqzje?+Kt zY+oddnm$hLjl}r0&s%lhE_?*`wh&dtsj#@X-ZL6wEdTD6i_6k;SV70=w zi<86|8JKc#PXH}A#oUB1^ztl>x+J})eVp6A=UnU<-f-wzAQ=uQ1 zih%LmaaH~2lN)iO>*{zcRTzdb&U!3$PO79hqcJQup@9SvV13Hc&W2EnJj_he~hA6iIU+rb}iTDpq{ z2Yqal`6hi)Ja0u`*54=*>H*3M=*N6+Rmy%2$FG6q_shBg!~5^fUx0ms45>HFXpC(i zNU0gUdVc0t*4$A5?P7xPJ&X-vS@76tdP(6UbLb>ej*JFNtk?BE1yPbib~RlQ~ zY`2hL>&_E>m|F_;;QL=(z=PVXmH1rm`d{m;-^NDoOeY~07$VRE4l=CxJjX|VB8aIa z8n}5FMt;+!Oc2@?=K>o6=N6Ol-GvdHh-IRzIge(yqfdMd*ura3E8n+{(d5~+`SW?5 zp%%%(*$2e}P!ck)n+pCelA{dLBZ%XUs@CXQbDrMm=0(B{iM6fRdh(y&8vwZP&gaEH z;U^UD9Fjo9yRv_s^s}xA9I+G(HNhdVX01AjD|0(AZ1kO*^yg~a>5W{~arn#YN_mN5 z&IXdSPsy$`x|D7Ha<#B|49Hv3M;%Tr>hqnLlHx}4+N_^0gdiSv4{w75dyCN_^kU2_w=YWkL752|2<)*n@P9IAI_(yL%-%S^2YjbOCa43b zc_qpE7O*H0w3<}&cN47VU@MJeiD{Qy)^&Ox_~BADe?ULp-tw}S!~oeE#>%}dJ9*}2 z+zU$oPEfH-O;=X&o}4f*rNv-;fKN^=nAOuFmYaXJ#qAuhFRjF=OHrVt%o>@X74X%> z|0W;t$qHBgp8H^XCG=ieB0k~6^R~38H+DrKxa_JvjV%J*QH}10w7n}{LbQmGd3r)+ zT7dm3mRs}Bvg5)qAIo~H=}frVbLdGnl%|j`EPpt7Op*Xgf_8%4n@CMuVb)OTipatb z!0dmnT&%tE>h#m@Bx?81`@1^ooIKsK5kxr8E$^c*!XkdpoYKN7pJt9+k6Q*=?OJr} zfBoARc`7}4tS3hpOk^P$>xbavyRs2G+gqz~Sw}{9GKjbJn~w>QG3m{PY&hC!I{xl} zFjYp@d?4D%AbSDJWNvt|<@@JwVprsK#?jEB={(I>T6>?YfU7S!ivL447nFfSU_9fy zl{;jX?s~xTwc-TZzO}oB{H$_PSJoGgULD2qMF0wHpefC&mn#*iB7W4&&rO$Sq)AQY zvMdI~c+{*lH{m>m6cBKI{NMvtd>kZbnGy}8!D@{Chf*wBTUCD&F(+?!X zLn@ zC8{NP*PJ}yrnb}vN zG~~SO;k>eum^R=DsE?Yl1DA<0=!kaMRFQjXNdYgeFXCTFtJ~$0b43DP$C9Wnv&7;V z);I0qds|z>y#oPKwa5d*0Tk`aIZ$LJL}CHZPwLuUD!E3om|Zxk2bZ3s{P2l!Je2q_ zF{4gfNP5nqFoR7{;W-cw|ALY@60TYVCx6|nfrdYJ6!>3Re{)53;9KFJZuHK!mC$im zP{39tfCGRz7}wJ)-PO>|StyRf?&j~7lIA_ceF$^%F)i>yDZpfwM|^Kj zB12F*l9eE))~pT};@>AifF=W2Jz3LVZ@g>WD>c+wu@adc*hdaJxM}G~EvQ{`$?&|q zCs9X@WAeYAfHq^}oSQ_@IS_*~oRvvCGM~@&*YjE3DCSd$$YTh+;akn_5Z>3>TC%Tg z2^zId7{HJlhM9Y^kxC}M5X<**H-e(A9hlIvd0NFj{i90o#)1;%srU^|ia*{RhkN?b zt2S^QHauxzm(i6*@PHu}7Cqs*W?bzkCOknBh6N+w5^aRAP_O3N)0noAcL_)wZ+^(w zF)cZ9{`*H&V2X2?`6?c(l2tBQ%$@^ns=0`BCt=Rb70!4=*emhF`sv$Aw^ps-m+6+# zI(~%d&m^N@P2UcL=D;Nbc-XWo6ErcW$)BB_rHlhWj%jjlApYb+x77bUk3=p!$Wg() zWE4t(oE6hcv_sGTU|#tn%^-Qjip`yFjcQ$*d;{>P?%?(jBt?II5eool9&HNS$Jk)< z$P$EW+V_!tcJ)~8`nKXR5jbY>xU)s4{D{=xY1NMmQo)bdmsL z{XuRP49V+4;_`QpkK$jl%yr5a*H%~ikJIWxjcxHaUjqXNPKqmbRF$S?2M#efIW&rZ zS?Ivfy|%dtBYx`91-#sj=Sx5q7SzEWlk?O&D6QR^ zqLkfSTGmF{dMKfUh=ETjE#C@P=T(92JD|jFU+nAGZ#D+NqQxn)s@ed6Kn?zt<2R~W z)eq^RT{m{cBUgLQMq&4K6D=!y_L?T9oN}G?9HtdDS!1_~iQrgPrBnqoJ>G6MA}cKh z8W@H$m?X^Qtyo-^b*p;AsjZ@l&l9a?E;GNP-xG$bVn{lZXjR>5Rss8YpqolMzIz^; zuh=Gwm6l`AqfI&SVozhN_+CbiGB_4dV32{!dJs3FdKFcaU%5w`Ba9b<)igJ(syi7vLTY&tYX!r)BR^e7;>xek<~|Ve#mMv^gWFkRqi48f5Ton!&LR!9ZZNH zmDI?ej;z@Gt@6sh;ZXDXWLx)r41P75uHXySia@i?NG38qGiT29fKh!%N7R$o%Rzy* znaBA#ZLCvFU<;0gf1={#zJxJ>gS|a4$w|ZL(~wJTsVA{bqr4FBGf?H<3H6=tCh35wi_D{NKchV zkY9}bq0;L}m2w((I~LQ5i)l;#JaP>=vi*Vq!+;xmozHCTh*(w3n~O!>c|U}Z_a|Pb9SF(Q_A4&+jQUV5<;*ZC%2yEhgqtlCbNUqB!v_a~t-fI(A)o#i9>AvGhv-XYz8O zvM^&m@#q4lNsv@V6=n`mg5Rq)L`xW`{vy3GW_P|n^{6bkb?Hxe1+i9XFe;qiAVcwm z86z+}0lITw6)OS6iO4;WnS~I+Lp=-_%{jEG-n;R?`-hFk*Nso$hZg_+A6Vo{^)e-r zyeBLiALs?_U|HFL-1i>h$<$6+{e-YGO3TATxLX9!3^;MBUzD%K8|aXH8iw;LtIi)lNK<6sF3r7o}ndSunu! z?uR1=jCXMrI$3>tQNH`O8`_$-cRp1rQnlbn9eA{WrvpMfB2JYM8bIL=R72WPsFW`<7gdJ$0OT@+Fg<3kGeOWQP1XLM zq=}ju{u#a9MpP))7b>Mem7Kt2N4NUQ&KK%ER-i`suL{WixqTi$i~jSABq>tRo|GCE za*FX?H#z6trI8pfW;80f(W6u&Q@I8scx3WrF3-2tg`YFOip?#YxRI9+P*X}{6_IWM zoMmGpq?ZJZ+v!`laD)h=nw0U*>WN$XQ@;@WRB7W~mm1O}w+fN4G9YL_`~_XR?CO9o zWDg`HMB7zRpgQ%WI0PEGIZ-USh^8pM1r;!XLXQ3Tuo5z<%ENVtO_CVs*9xfC@}6D8L1!Lb{rHrxRMc ze25zMd)OK}8Un7Ym;*ZSxBA}1wb5BO0$oegDvitt zPpjq28XFry+82$}4LlkNfan-9CKFYY%1JeYex|CaY4c5d5r$tZm{I4pW7u1RMWia# z(Bx1+{>xxj{gGev4}q}p9ZxR4wU=KN}$ zRYD0tq#KFUzq(iSeO}U0wm+sn9q^fJ+cC?meJ*#zGIg#(efqWyb#w>=c9pN-T=ty| z>Ql_9 z{E>u4F z{K0hs-aOOfG(R}Z3N)kW!^9x2Kn4{iBR0-FJJ|ogInsmzpHl`wQt0Z;ymx33b8+-# zJ7>XJs;p{{tUU(ki)92@Qe;^|_P{`uWK0|Zjw1#!oe|6(b0JsiR>5iuxcT{#IM9xp5F z9ohOJ%msx-EQleN`CvH|)$=TMvXP2e5y<0$F|9CQ2oxq8NzDG)3G+ysS;u$4=N;v` zC3kTQ?6KO%1|}FL87WK3%VU+sk=0O!^3V>*Cd%=Tg5N#l|`1 zO1l2dZVn9D51$^i#Sy^IVqNd?$oOX_(^XZ>oT#f z&p7Al7ftU}0-`y&Ul`Ermy}g85Q0R-39w{C6B7?;J6!(==6Y9nueJd2@bCVb?~hu3 zp3FKa8n3famfYN>wH90DGw*^2?*h7k<3wF+B6bC{5f*(qZ#JJX2bQbuKOs^V_ZxSP z{^VcvW4`yjEsdhHOzpoYPR3&hSqL;NP#l&_N2(7Vo|$>MDJlm>Vp`f&Ym4I0=NIHD zjox$vNPq&5e!7q%bj@Vd;kiksJ_Wg>GG^iskT!x*mHA>ly+?a95ZDlpA-kucgv@7WoYJ)>DhUdd0gpMy{tJoc_!YLa(- zYj3?XMsDi<`{jCK@ceT_aygdt@$r$@-}LKMq6iY>yHpgSKb2`Y{X0;?Cf6t!7=jq& zT~R`Ved0cl%k|n!*@zVTfso0F8=N|&Dq|4uiGLP(ck8BqV#2%X82JpB+PCbpKN1I~ zt$NjzA)$94nG|q$Iz`9zbV^!p{*McQIfYj=Rk?CzH0`%7Ll~GoI5mZ0qKAqd6%tj3 zzl#5_&3QB=7G{Tdos?dA2OIqdDjM%5wL${aP~Di5RGpyIy)5*ys+6QE%mbpR$40BF zy9#?BEX=Y^i-Nhy(hY$xtePDskyVkXpnla4^30&E&NVwIx{lhIEF+RH3}yB@6RJ4u zBON(cf-KOg5$C+w+SKMC)za*rPY+}yad;99FV-*P5J#umM@l0_SzH+?!awUgds<-WIa*YNx*6h^Dop*QlI1z6{Uw@zzi>os?@ z=$mu}ZCP?s?BFZ!2}C=cY0~JTGQ@t5pHimq&P#Gd@gl3x6Wvrf+Z}#i5m~@uoAGZ) zjuvz5-_p5FA9C8dpN_UClXngl>6HDO7MGs{9q`IhQ}t|7Wk&o9X=$WsQ(Zg>mwrAp z@e^WFQG{C48)J~XNYnpGWDN^Onyvb`mbtg|{VF=o_g9u>G5vb4pTJD}#ot5`W0yd- zR@WmXl#rR(S<5D!GU}tv)(^9;9E2>Uh2C|a1 zXFKs2dKhdqd%LoEkuA-XBv`R2w9U``c63Lv9Qg<6iK)puqb0KxJ|a9*^UBGWQKN>N(TFGYewv&cZCJ8$)z#cipbe8a)m0u5o6P1ku)Nxon;Lsx zb7eN5H0p4{DJUp3Hb?w7AZ?4MEEQu2vi&IO`Dx{8rSBTqYi!j~Xd5}TNv`nT5v}Jp%~0ML4u2@+`pnLS`NH8h%d;<$WBI_ zLrJ1^(sGE^*8TLXs7pPoaJ%Vj!?@MPg;Kt@gU? zxztHFCyXFWWoxyUAV;=}?BG#(>k1y;?Z7gmex_0l$nufA_{C}49Qq(=IM=cqzD6Y z!M-FL<7R>)Dbwbz7{q~w4lNr$bW1erv~2H`cp@no(kMreU_~;zSz(jL%_80AkiRTs zM}Edjw8sIP&UOr7xjc06e0Al_aG1qmdHwVSM@m`f4(FRXW#?`eSrQgs7P z(8F%s3Dlt&7?Msi5Z+~gTudmHlxm%szaVv41o6-u(6P)Cs6wVOn)y2$hph^=Q9k6Z zB|3xaSAt(j!iIxyh^&zhj?~*ey0Gjx%qfQb?nCfL3;bFU|GmAAj=qjRosRY!%Vad1 z$uXSzn=33Fg7FFj;w`#)nVBFa*o$}Pn8J|&iD$C0TOGck%;?O#gsMb5638Lihf^ob z1&1RMpkKUPK#EDg)1)CY4iaE|9NKZ4>I^nAjW*nL=oKZh;9TdQfol-R7y-uf!=`EN zck_lAPv8n3k#25O=>!{gd&9%W1zuI>B9m{4%^#H)8cs{hh;UN-jC$#5$P)6*l9APH z73IT;K7|k+9}Igss5PL@DQBx~%Pki2V3s9yF3Zc0cpEyKpzy5mbxJs^GmG6gFEHpW zD!!__6dj9UXSxN7HeNjj9R@SQe!HP0@cnu5)hL3g6Qs|UHS`CAFi!PUIr*sF}a4ZER1I--4qoaaN zc8Bp7zd}w?*RiB|<55*8y&=p%HiR(|5d3+XUD1#l;l&maX9rmz`HsO=Fy$= zfyZvu=-8DbDRu&I4Xi$LNI&VNJBtm6nwtx<0LDP?1^Aj0l^R{jlqMf0-ZO7SKGOX2 zkDGvg4028Lf!a5E1gM%1)3BD&O!jsLqHpCa#LO^s)9NauF8CZ*=9^MZYi4>ZDdUfX z+l}ugTf@w;8*IQa;{t9H)Cqr&vv6V2>m@eTO;R`S7SE~5xGINB zF>_aL6jbT7x0~-{J=3$s6gfP%OJw!$h|<#4nLBx|3O!{nQH74q`b~4*;pg|npf_%HUO)^8V-hWQ@-FQ|jox8EW^O#%5C>#ZB=K`YAx5yV8|vvX;l)6NWxBz9 ziVcCtp5qPMr-Jw#ga)}HN|U{$+@1sZGDK9iagK)+2AD7%9ek!ph-xGiJ=#pnEG!aD zAo1zyai6~p9(V#6kUEkac8|#gSit*{V2Px=?%8o)5al z4R@j0Nwb$i{BYyc>0bcRR$yE|S87_j)>~;fwO z#mA!>=-AVxRdB+Z$5kIs>_DPm&p+xg7`f3~0q3pp!(^+k@seH3S)69iyj`m`iAKVGK$-I*wUo4wnSq?8mkg}%Z@uklI)I_CVAWf1BbSp@s7--*>@)?GiA z=*WeSxBB9zXQZkjUm&E~et!H0QuMnNSw<>`GBvf6)$tHQ^n{jrJNhKInslSMI{hhv z($!Bx0z~OTum#6tMW>KyQ@4i98Sm3f1SUJ4)>s1WAcrR%we>nLZ>Qqb%USZX1dd!? zZYCx=xI(T<)X~R%Rg5Gmq44&1BglGpf{|G><5yWq!@o0V&^?RzXH7$4S==|!J_m>u!~rA|XLJ;U~gjZZWA+Nb!OFiun5 zBnu~$)G28A9Y{IQk5z3 zJ(*1Aa!|(WN)I$%`RbLEPK#Xn_Wk`nF;nm~UC_DuS7a+%&*z|o%-d}*-t(uk&edPi znyQgk-`7WM%i7nqhfPlBUd3xljXtIy%8UFR{Ll6?A7a+SGYwCr$&b6E%yb zS8Drt!kKN~f2-LAjEx3meQJ-)LC<>Cjq-}86{A$q&56-qN30_of8=pCN$Tm8o{^C; zkI9%O&ntf^FxoI^4E*Wpe@RLPrZ&2HxSSp=YtuGVc6dFFdvpnjh!o5o84E`1HmlH+ zfRRs3qr(3NOk0);>R>%2q}HRNL%98^Lvg02aXnbvHXHTk}Y z($R#V{Ni>)0`j`ApLB|Kjkn?R%)-AxJ~p3cswq~=VWPgj0)3A6HwO~v25rCznNG>T z%i{hCWeHtDS*XkSW#Hswv7|(9KM9UT=t>XfBO<9=G3hYwr@9q3d0`O|GO79FV|ok3 z#F*c_XgNY70&xVbc3rvHkV*S+JXG+R&Jl1}#G@%r+pj`|dP#({4;+NELqjR9TNONb zzmBxD-lzSL2b^C^*4EqI{$pMFC}W+knY3Ry<;w1ysLxo_@=eO*tQC`Kyz6}`B8gZb z4)xHv+o#_Dj9?2eaiBNv9*wZW{=1GfgEc$S9Ms7Grvnu+{y2jY`>wQh!|W|>V2=Tb zyd(MVlAjN>e5K^{>_USK!%57rBnwTDU*O}*8PY%*w2uCEPHt!VX+d|?NYlfYUF}6f zLpOoHBKPnCF9$A#QDe;2UB{FB4s)1(_V{_($=cA}vDXHfVN= zKcn~M&FARQTUxTS<$@*PX0`yewfCGS;68d2xpb`KbA8Cj_}@SN&l3f`onx~h+xQzX zY|@lw3QT0kn)n%!RyIDlk-v`8BP#?|34Wd?BFuJ>d^H4dJevy(SeWN)O-HDXUPH(- zrxGl@Uk1qLyn+bbUCPuTr$frA2@Y3(^08UM+_D9okJvGv-$au2(?e%)jDP_tmDH#d zf=rCXm;YzOel1ML$L%)r9J0vO0JWMM9h$(4SK zkk*BXLlV48M4Q_bRcrbh9~;}hfZ6Zo;DDB#pvMd!{04$XM8yEk!HN(;WQdeVbO^tx z(SK}OBgV=|w2Y07?X)J*5v(j00yT%H56g7vWHMp`G0v2FW^@?zdgU97Bsx*t5`HlZ z?k|;h5+!UqKXwpRx~#q*~FUi&z`bS5H7-3j++H)&jNil<-?651+Q1xQh>kJ8HH6Adlt&E zAXUl26{}6G;yfv2f!$gw zc;N3-mmY)}`^Z`^-2>tNq)9`hIWa!zAbcVbsNsBi;*mg!#Ki^99pBNJZVs|<`F@zK zK5M`&K8FaFc;?+7fce^wrdb5<2>k`w z3m;Ty)nyZvEx}OJuuRR;y*k(g4GkhTZG~U%gf#=lg3_g41+lXxcJ`&=_B=W!R5%gA zNz$pf_~NWHtdUc^i#DPL;zSJjFDE0$M_LP{Xlx>dAu}ee60&)*L3; z8sd|qQnHlJa@$<%Q?aLF_L_Tx2zKbH@s!XWsmEHSif_gu(Fx}~&~R0G7wS-&wSrG+ z&_e5v;aUzZKTfiLy=PQzQWRTNlc4Xhf^sHc>NxZknsHEKnPM}m zPfw^(QL?oPdAruK_ddQr54ejud~d)-F(a{!Ph3Nq)R<~y;_PvEw0+$rdApnN!j73$ zK-XHMm991~(wMi>0~`hdUd{><_IxOsJB=4xmf_IEX{?QSN)JS{EVyy%QHa^BW5P`$ z3>N2ZMg)}@xY*gDu##NS;$V1HIr@=GL`~--KVeWMgxA2QM8l$}5!SEF;S#_KHcKOr ztTkINf-A<9fR-~G6flH4k1l5COQa{9_#R3fyikxCSI$PyY|63gmB0fYIYH8=85U6d2j0M)_9PKQp7X)n z6&P<^wAU_WBYw1g*RuX|_->)~ckRzGb_474zl2M6wfj&C0=1x~gUtqi5$GNXc@TnS zBFCh;V;=6bLlr90Q zdE#k2W{VAH68vj|j|c+;8`jeS(?Shl^y;rv7hS*tVoMX}-fe>PT6 zvhI@PI`q*axx_AOLB}s^6b%Uz7TTAyW3kQWO61vA6yROy@%{-_PQRXv)1Bst#u$V zi%Z7zKE9>jJu&_bZCK5UqNS;6H;J|BV#jlK^hMj&{JuC6_#ymN zl+WNU_O3KD{9PNTAe|-uiRdmSSsa1$Vefs^-gsQm-_tibHAkW6-nO59f8YKNoHfoS z@O|@reP#LM_e-IyYCLbftwEeazca}`%x2>%Ixmxh9BVqgDu_2AM z?PQ(jbvUPvw2eO`;4!AnF~~~v2f7H~$L6Q!JgVHn8r1wEk2KNLze({SLhmu37dy(NlCji;_a6|c@BSf4F4ZZ=NKMm+ji~P zP8!>`ZF8E&jcwbu)7Wa7#!edBw$V6^t?#;@Z+r7Azq-w&bDeV@>sV`F0Xr&>Iessm zw`Ebr;wLQ(E8T4opGJp&9kvF{yRT=o1qC&9lVx)|KZ^ri7BP|K1iOJZ&~^V%IV5>@ zCFJ3EI{I~-Nv^2&`Be9x@4VZYkZ}F}3*yS?z6#Or4Nf-qyl(+@WNxDwin%WlBeDKJQ;kGJWegff3HMB*KP19KreU@Z`wG=fAF zzYe}I9E?DMY~)0M^z|;E&&?+-n73xI{y{L(pgd{&Z8!^}rC~*gB=7!`m$N!e3#>B*k zKF_3?v*Z2l6adw4XkB@^0x@SW&Ea;Ps_H?zgZuKZx8Xf0s$z3uB0+~Ctj`bz_vcr*@A;yOPT zEjed+fLqT`;~g+a!62dOzs|t>&z>~%HPHH@9*xMHb`B$i_UtGC8{KFZ(FlXd5?X5~ z1Gl>Z>>2&3=Pz7=c8ua(o^1b)^`KovN?;#MnoL3GGkRsif&C%V8K3XLID z4Mv!bID6{erw^Q7$~=}$>u|2IUfhIBXo^Ebj`P2JQWOH!K9I{Jurvn4UI6GTN?}ocyhV{k)2o+a9{Led9 z_QKR)8q!~gxHb^B*-ybuVpXGB^{kPKsJMZ$LV(ys3c)$VGX1j!;v4UuZdmmf?M4awR0jf(yd<4@~I~q17 zIdOogq7{a;G1lud<&8^!3;~UDUb5hQ!e?Ni->GpV*M`n;RG#!n=o%yPal{j}2{YET zFX+70e&hQ~f3de{^42zB*U8a^s3$>R--UcUYs68vr8mtY{;8f)QoN#;6sc~Uo;Nqg zI+Z~_7{yR(TzOvtG%6E44p&fFD56u~S;c8b3yUQDN^1yER{rjG7@t?|+If$oSmgRdf%!ReoQNhRzsr)bG986T_+@5$%jcx#V`XKd%a4PLt?oS; z{buQ}iL{nSyx+%sz5tz!!`n%|=gCjO_f?UPGZ~FP$O7)i#jhmqEBQFfpL;g!M{g2E zj@KjPYF@8pgd}K-jhfR_+)*PBw#t(2ZU?)5b~=x1x(=1Oe*X$Bi1{9d?9yLGXX}<7 zSSASH$F_Z~mVLOhk*7smT9q3A9WMW)-J6#z%TVwe>Z2g(J}Xd?d{|)k*Lp#|?%RC2 zcr;xNCAs1Dn%WYtGZ{(SZB^p*vTh*YKc4$`mY}I^QO(mw%fAtG9(_*fVH^~e2YtT7+~F>k z>hvEvxl`$Ihlo0p z;l&LeSqvZJBu62~gI8o;5RJhx=AS5!Roao$Y}cPRC`)H(1pb6lY){LE1`bJS2UD&% zAmo@ZD#w&QUT}nYT@`1gKC}WPKfv?=^#q9$VhrjQ`Q+j4O|bTLtJ4QDtPikp0c4cY z)C_DUEQG)*^BH&Gel(;+=t(4bFNO2{Kk)}}9)Q4$zXLf~C_eY;fpkE4CtXJSEyx~4 z3LS(;j+R&F49pE+FFU!{ni(&QkP)G56OU@u>^KAbRu9*`_Uf)bp3I2)X_JbQ}w z^+-z>d7lA*xTy5@qtmwxuIYNl>G9ThhS0yf@pC$EZhNq__;F>_L!pLxX#4)*hOnei zH1&;h8qC9Z{b@57uEF++qky%gdC>~UTK;p*n#7Jg&?xUOS&-~xO_hf=!jcP9EQP9Q z)q^8rT(1+FcG+W_ef&Q!06-woD|Ks`hwuNnj0lWqz}l*5y-Fh{Qn%Smw>h(+5$Y&M zhCNw6oL*gLHZU+P(u!Bgxr#^0zV85R0AA#+U&I$^z?%;ExD{2{ktvkx>7h;Db>dQ1 zQUc6!Nkc0GEibI^3kr`6M9}xlTUP7t73#sdmcRzW2a5Z&xVU)5LcOioZkd3HV~IOb z<}3LDRMgl&BHLueysGv744mO9Z2v0in4vL(_sD}i6N-wRgJ+_-Wx|q zzL3v-#r&%N<;HXeLyaJ((7o9*{~sg#M7goZk`hls#|zC>qvDD%Q>eUQaE4TK8ZB5A){P{MjE$`jR*?72#rZo zY$JP}UF=C04~0nxa%BMXeN5B){pHi>4Uh1XK)%6>>zTk-=l(+e`|0_$~>2 zpeEELdaNdVzLKn#<-e|PzgNEdps3q-Szn<}%AGD&3KeZgHYY@BcHQ(Eyde1Bd2HO= zSjEWlpo%#Elp&~D=W46=Sv;07;JX@0TB1s)T647Mx7qSndV+oQy*DxF9ON*QZIT#3 zG|^U;q}0rRdQA|~$@ZVr-F7wd?O+mY2?&aev`+83c4GrA%Y3|P`jd5GmHF?$vP?ac zqqg5Oqvv=1Tb$>}UwfTN(S7Eyb9f}E)_EV8$TVkII8f@kDfj=ErXzK6^zi^0P;YUq zsPs=-#N@ql>t$Y3Tjt|mi}1^Z1+nl;f4ctR5zURHLY%xzl1HBUf43%S!M=W>B2|qIBtr={balnLOb3Z`q3jXjD>15x7VX4>d!XSXs2Xee3ckj6demugzG(mz zDlUgePvRqjsyc>&{~@d3B1pSdZTq;$ktBYn_Vj8A>}Ew^18^5|C!(FjSP&pH(d17P zRPYpqi8^E-N&sbl`gn)lfi_xtYz;BsU+<7(??}qffM~QHv&2K73)EMU0?t2}A?2h~ zcI!Zy5O6e=1rEoC5b*w?jV4v>tF6ckkTQWv`|=Bdlard7S~-_LOae*>#!;FOG~R~x zgNkvAcS%axiL@;B*OsMq<6=}&nc`3cewGW&-^yKTyK!g2dwA1Mo2p~9pn^Gp|D8tM zx`21^Bko7-%a)`#>kv7fSpWDJ9vxjeGafibGF*#3jAi`~kRiaxkd~HaE%Z5EpetQa z;@KSF3)qXIA$=6TfTH6F#Hx1&s7N*{c5e?<*Uq~mnd5occ6m&zRJ8Fxbre4E{%}`+ zw)#1Sh|(W=ZB;bf#<~a{=OwX!E1|TC9F|MbDQ=fW#|_^tIDsj74%HsuvWCrTR#OSO z;T>Cmv%>hAPWIO+tHs<(-cJdL>5NWHRL@(m_lYlvK$u&-j6KR)IB?qBd(q!QbHlF0OYVGf9^wG*zY4qb-wyY2KgL}{_ zeqXHX45V%6{ipaFh!XOJTcnOE^>d(oeBy8Kz z7i~PXvP9DUu4#-q&g}5t&wLW`_;qoVD-ahaHV@9``$mNmRUC0>c6ihBw$fA_EW3#6 zx1T||v>I?ZtgI?T86EF?+jjVm;db=8p2px~U!?KKPrT==7XknKPOE#w4;Gi+DK~}JcrL4#W{*Gqy3}rF(3629qjCD)f0ZBGEdG6P zs(rj@>I=GyP@FbFR2|RYe4Jt$2x!D~|01Xeva)q}>0^6&sE}?dri(F;0=)=c`LUfY zlrDaiC*Jbed))rSIr+TP75TL2e$u^MsqbK{%8QOXzjRMx<#kF3z(#;3g%Nc;Rw0cV zdY%0i@o&&}U;q!ocjvt)awn~q6k@nv6E`GQbq3-Q@-0(ItO8;HUQQ7=9QSwts|?*m z!T^P;9bTkQ{7X2QFU)@{a}fLN-nqtiDuxlyjR|33(W?F3b9W${Te1qhuAO^`fjT+M3drl)$3 zAd?gD)dwrUA;YH9<~aS7M3Wi_Q)sUu1qK{sM!jluXOW&hA-K{>B z)}FVIS=eq{VPqt4dH;}z_1Z78Ye9)FOC)4*!yg6gWpM;NS-NR1`jv}2cwucuo_)cu zfn6K7g0F2f#+(gi>BU?>!3FD8D~su1yTE902Hl18KVO!+_xP)+7>Avl+W=DK_>nWP z&uhwBw1&2l*;J-EzgJII8Ro<3b0%DOCtP>J#gR53DK`3oipT)NzTTrc8U7m&Gb0Zp zVc0@-U|6f?olf+8-AJaK#Y7<}$%E$$kjh|soeYJEzRSZ%+Tr;S= z_coFh^4WwX@!WwvU0CK^f~7y$ih31(KE`v~t#Sxhd`V;3x_?fYer?$c&aSZ+d|Fw) zd>J@2@PGZH-+YWNrEBomyln4|ht5_mXf`|1CbBg79Q^a^1?||drsPRIiTCih#pg|n zi2K#aw4mqh1CMRvDQvfwIQr~OVfnt1ZL&UYhu#{(KYLR|&p5wWRvd2=x*M(*QT?APT@2cfPAa#((wr>R#2REwEppBuH1(2v z4t16AJ0HU1GNp&8Pq}&E}$;37Z75tRP*)ee)b zdnb=(!N9eKc0nF02`N~gk>$DV^TR~)uG|0pGLrV#je>|4U9#}wANhR~IF%m#F9h&T{Rxxe>hAqj7-~Rso%;g>*G%W58s-dvz zpmZ#_VpKxlw!#`W`pTy1yWN9m9^ zqLo3@mmW`aC@taq8jVU?<+Ac}fHrpkL|n~GO`*WxhMSkqs;aBSzs9p^lSvk;_LNY| z-Zi@T0)7%~M_RCx9<6;p&t>(Q;EK@mH?p^Jvh2=SaQs*3;dF?@#;pDK(m6xYLz-y z<4<^a8b*fZ4Am^${a{EPxN#7OV@S}zJ)~#aoTKaVsD4wKXWM!afD1QdPBxw1BOUwZ z(1rKP4L94aJAF4=1v*xAJVNX{=B;cIZHJ)i!QRnE}?+R{`9ANhutc-MJ%Gx z`h)JjH@1l{xE@5uQ*5+?!vFnr)z`E0@Eo=OV=#Cgvu}CrfkZX@0hUi*Ix(G2lOK(Y zXU6>d t)=jH9JcjrIesf`UntmjnIW8>d={<{FuQk{M`3pE(P4qb}4GAcjL>Xa%r zF)2`PLKtbY?MIG*L(ru3FOt;8l)}U3i9WosDypEqWXcwQh;Aj;c?5rtoUFK8?xqHcTW#EK+K90K4`2!DHVTNy~e~)BPc%lJ~TY=YMKr$=~oA*5H{vY4nlglX3KTXV7=*EtJ{JHsH3Zi#I{PUlSVS zr2#F@%jC~HH_0s2kR31J{CjDj@uor1l(P*uffg<{ygo)y^BQmUA%5z5(odE({_~fe~*UqnP}eA*)niF6NF3#^$LSxJ(KM3;}(t11q#;OfGFXcI$vG z<|i%dH0*QGE#(LVU&lC z)CW7BBn7gaiIY2wJMzc(-e9y=^b1ae#^UmmC3}*fQP$X!xujGhTsQvBg5?wtc>{-V zg1k@OFmFP{%829y$5dNw>(ZKeyxF=DmYFZfb{!g28?fQBZpu<}WpZ@yV|5mqcG4S< zr#WTS#FtW=L2MVBIdLzXO$J%d{V)^wvA+^;w~o~17F8cZV;zLsVM8QmrHvg^B(VL| z541u7%Fe8%C=@i2i2O`N1>Jgc0*Q!yqZ}=nefPV2PVRrJN}V&q{4BvQ{jO;V)-`!_ zcJzQDFyvb&0B8cd%r4VH7IW6SQz+@gvCKPT=dS#~KkD;9Tw;38#yy+j%xbT=5*5L3 z$iL$13JC*EBcC}cY+iuR6Y|R{ht0BkWbS!bo~jz3nuwYzgWHnl09_}caLG)%{zP_!@Uq5#q|8g$|*Urs+fnFNs9XmKUh{B|CEVEq?_voUM zTzW)&_We)Zcllvfq2)Ib|I*5>FJUv_rmC@^ zCKS!LkrIx`do#dIdBn6tbNRYdw?B3`o)=E&_KI3<@ikU!Ue?EbVcBiZVUiLlV{qGi3+xA`cqxt3Q2GHDH z@7XM6dPLLGWx7Gthw)QGnMk40c~U`w{-I^x!1c_AN6>A0Rp!#?W%07h9ZLLBpN1SG zUdmLd`%vWlak=1{lu&HJ=5YX!nLY0_RfK$>>S~B6>Tl3}5_QPfc!_Y96L)rMJ%O4W{_$w2JC>p(5Ng8wJHXRmC=_SkdpsDoLtGu>=ma=u zdtFGxf#Rp6C`cv*V|Jxlo0{dy<+CAgRFpFTZ zkdXQ4N5e#{7rY!lOQ~3muI01dKOn7UYHYc|)Fnk3(0w0mEG6%~a(QLyDU8_f@1}wv z9jgnkyd_3=*~oI9wxuiv=&ugTZkcHEHp4C<_Gr>Z-1#9(f||6P1aTUbKqHboU6tK> z9pk!_(7F@RFklc6V}bJqKz*5C;XQY?;_di;m=(*<$k}X>x}_aZ$!lkc2&qMmkjp1FPmG>6+X3C0y=8`y$)*|H*2TaO1!zJHxY|j#9h2F>gvbq0lwgyGY zo^UdDyxojD_&&!SqKW`l72)^0JaCX_B0kT34_HIB9L-jel_6K?Y!sXr>`ZxKuG#uS zUmt`C(h>A`-atmJypvnD1^9}x`$nYq_T;cv8n z?Ocy6fBeON&ag2%?&W3I(bRQnyL|IU)Zq;Ia+Ut zyBMZxIzsraP}iZesb9Z#YavKrr@1CZ}oj`v6w(s!k=R9)pwt+R; zxA(({fcF#&p6gq_|{yuK9yAl8DZq*0GL%OMR&)kGIqN%ny zh_gJ(Jw^IbPP(f5pjUxaONl~N(jp))q{0tCrUEf*7`nj0r_#)QJv}`_ zJiH(j;=mzXPm?eXM(QQc-@(#pLBC1Vp{21QJ}@$10<@UZ{kDNMvd?KnIbb(a<04hJ zbat-SV$2ir!S1m3RSOJH0|E9aARwTXh$aDdUfrjb?w28O7OuY6rh(ROqIc9a4@ODxeIp# zw|f*l;sH4;B59+BMW6xoKk(Oos~1*;Fe<`fA|e8&w6Q^B^eFXs6M|1O`}2(#P2Qte z8|he=3arq!I6zCaHj*t^v<|6FAg|y8(qpUfXyma)0R9fSUF`D<^%~%3x9w#bY9-s9 ztMVlW=_pXS)vIKeaRYoMP{rL+OV<}-Nm+7^XE5`pLRDJNya;^Yx(x}EXj=3WHzUT2 zTg^~>9BESVlEP^rFz1-Lfj9)J<@!I)R~uk)CcbHYPa8EI`|Dh%Wy_tt{j`MHS0B1_ z$S9*GnZ-*%)@rBybLg7=g-yK#mvZo=|Dp!Qx4zAg{9DUizv*0%q*aUX)v;$H?hE%4 z5$hzbQ*T`-C#MeL&=OMGTw-`0+e`0%-+u7|6Pd~EFM|dzVUktFX~`gI5Kv>X>3G#v zbsOW+`Id#H3;s>K$a=;+C%IvlwEQU|D(V{e?|Zxhw4{2H8%lMh*7-tM8$dyYOwdB4 ziITPJQa5;}S8N!t5o_RMV+)Ehx+M+n#|WP0J%W7@;$jEo;F18U6&*H^Y@2#~SMKO+ zuV)wFaXGxJ0CEy(f785+nJKIU;xAgOkJ|ELMgs_qD$NQ;bAUfy$0pQ>-7mh>S{BTNI|pB| zz*Lm{1BSW*G3J|IE^Ds%sl;fRlZA}c7b$jtJ3ZNG9t*Nzu6}+p6xYosOw#H~$fjIX zY2u!6`-#1%^Z5e%frGvo@cF)7Q=lAc@L6_7{BdleLagPt8fUWoC@1>M{b}?oy~kv> zLyjQoyn!pruoL%RcM+G%6a@u^Skx@k0aWU$FL4PYsfZM@S z6Lf^qFv_};I=r0$2kiMGxNxoi!R_;ZX}aN_G{R^sSC}5>$;nA@AF@37Xb>UZU47i3 z{N6W4`ZNT}C)Gm3rjQZbV9Y76CY?d>2&Mlt0U48RL(a_UBfg_6d!8cz%>pJW5Ra+Q z<3;$PS)~DBbh5znBTdYFulrdAeVn4O%A!#4AMzA+A0W2wWCzK}&s?@q#lwJN4Mp&`wCGP#ARa?Gz#IL|f7n~+pFYl7# zHNs~yfzembGzCrJEQo{4XfUGNym@vnxINu0(5b(2;vP~^o{G^IU2+ZxQUDnSjx{T^ z3Sr20YWEtVQp%q8z{o+2TtRE#_$D`fKO4AN19iCxz6TV*7IazP$F6)n=pHtQM~!=D zFEclnDNWwR#pO6!6s-A1l;ZWk^G$1obgA3N_5r?o{shRg@3?^H`gCp`PG$$eF^vNS zPk>PsMtj|olX0Bi@8vFP-bJ!*%)rK89gMm;xBRz)8UUWkToQ++po}r%$8m}>b!DkL zE$j{=8@_|8s9caa79)^xSH^9A@JjP{tT5ssAU6h3;ZiypP7mkW5@FfX-5))>y7`{w zzh^0nYV_;h7cA*I!z9B{ONPGw2{6Dgv3-hFVxm-GbYHSC!Y#VMmYM}#8z9VfY)-9V z8}g&iE^U^jg#0iB_FEyFxHN;s7-UYJ`j>6}K1{vPN7ZLoF=66lm;A~z7tOkp8V$3* zdDg1jD_8AX*5$42wKwVwM{vU<9lo~aeG`Af&&Z?H5eqR@vtHtG7oN>(Jd|r7tCK$& zH%F_+(-m~isB!7#I~Q^lEFYcIRA=-e!I~QoqDTD zdqa=4ngh}Mx_M?k*65agISE2RJsOZ@jj4-dD@zsBbgaN{eUY=NN({!@hE=49{+69# zU_A6ky(Y8oX<5DdZTw`H1E=dmR-~^xh9d@kIBV})afb6 zZ5#@a1Gg?kV-supUx8fDq3lU){)O#tC0*1Rc-p9P5b)P5}7+YmAKP@pQuycO=8;XDF1@#kP|Eg#)tf?D;;uFU|`Dy54j;l?ND&6iS0h zRpsfcNK@sJVRg%h(hlfv8h>(jCT6)b`W%_nGX2u1yt?%G?&0Kgz2$QWI7EP_kV&06 zvH&P!lT9HaBKoeS)w391l6~mM{(8szg>x}8qb%-{DK|%;&Ssf;`;jEz?HZs<)GPxQ zx5g#e-aA2u$A6m{NYdlRpC9i)IuqF5SseY~8%BreO>f?!FiEGwkiz8T2zMQx#T8$q zV@Sv_k3&tt`&9Zf7h(8Pupo&XmR6?9Qao^PFWX@Y_O1i(P_(KFKVl;3djCz+Zmo6n z4}gC5e+u|O)k-c9-S9hj$|iX}wCudZz5Nv;bLsueRc08Od9UR?iFX}TtBn7&isbr76Y(_lS;NKqGA-)*$>NN5>K{`R+BUP}%qnwcqu6cU8uT3YR}PPkxT z?2BKmeL|BXct@=r0aOGqk~kb#LC!05GzYN1*|xK8XG=y;s9u+VA{9{t8HtDfkCseT z9qd6#S-E-L?hS@>9Y}IsLGid0?Myg|790$rOF#$zCRAtCf&efr3G6pRg%sitrF ztG!~0An|tyzC^X6{R8p{Xc=jF_|^pZSd4czS?@a`U>QZ70`NY8SO+u+2={b^_JVCc zDnWu9;(HUTqsP|iQ}P|jb0{fVl|`mf58t!v(dyc;e$UR`-5v5&67E%=*UhBjMR)u&;qTs^-lD$$gT*N>GkF5hIn-j%3h~m zXWR{~Cl@F+_5HsA{k`1Tps}>HFG!-r&3As?0H~eM#T@v!v-qrzQ`69NZ2ntVSh%@i zk9-&$l%k{Z=KWzN^(e69pAh+T>WP}~CdIz#tD5}opAE-;$!J!vi4$FZV;0`ygWmdOOY zt~J{Uis!Z!&y7av(`>j})oAoX{?cRi;Lim%Y`~z=ynX@XY<8T$W9WH-Iq{yuBL1L$ zH76fnX*Ju?QKcnk?X83=0~vEyRonpx${|h#NB0t}ukUrT9OUp$5lcD@WKb4Aw9!M+ z`lBg^I1eQzSmKCOf6bCj#N3*qw21snL=iXcXKV4R#D=Wlvxt@C@4fZfd2%eeNQ{bx z_}0TU2;Mg!z-uw zrz`(q(%$eZ2#~r=|Nlsu%Up;{uc2mDK3p3q!IK?=l?!*VRbz3i!@pu^STRzjE?@}# zl>`~* zo5+x-W7~xGwQW2v@ZXJsN%8<1gIx|40Wa8Y)Dk{*6cDK?1z9;cq0fO9$P!m~cxF0# zo}nt;nA7`rNFD7e7j?9>aEXY*f(o>iRX=+ah9CVb@5F-oS=TetL#TN&%g}nj4DnzV z>KXs=A@$pG$2e@Za32v0XIv#U+7Y0L&^9`fUoA3@X8}Li*+4$=IKLp%kd`NOyuG@k zv9Zx?92*Q;bp%*;0U}O<&;xE3WiBaJFrpEi68!_?Vf@+O7|Jw+e%ja)a)e-F^&BHg zA0x`(yl6-@V-J@Rt8aTj#a#1}7}Y4TR7N4Oh=p9xn*{_=Mp#myaNxi!QKvKVW*r$h z?P8LEpo)W7Y&_>X(lqcwX8uA5e%v%e-FIL~odWoGnXqGks6M~f%>iIT1ct1pfX@%- zHeaB(awNTwGbMlIYPD6hg?aWad`i5jzP0tZ{ol*|8L&!o?y&!JElu|qsJTc`_aYmh zNDyRaXAic)oyXa<=UL!&>Zy|-vy|-(M#TsQjD4%vqD%#RW54_t)S|ztj1EiDzvh;& z+W#E-9aw>%AD`bjtEedlTcsmo!0k@zb%A+Gz~&fyI5TB8#5 z-7NOI>*0hA@#{mF#Z+0o8(?Go@_6}&ceH|MQ0%uSxR#1Tz{TxtA7Ts8WUZ9V&BV-1 zo`kai2?Nx(BD@t$Q1of@Pxc2!rtVubU-ntbP^Vn`<+E|~@I;hjd&VhJr%alEUk;1> zw=(v4>Kb&gCwH597a(Z!u;R3Nqf$ zaywg+LYBfXOE_$l;)bnI^3P%#p##x^qcw2sE6a^R2nTt!}HOqv^^CgAD$a$>RbYG1hf7#jyC*MX-(0nB=_ zbMhY-$~lDK{syT7iuFmkKNe3F2)F?v=VC#92iVJYu`GKwLu{*yx48Qi^s3+mqG5NIu2$!~x z9UF%*K0yD-%FF~;b@>i-k7aj&<-I>C(8hFKg|X=QTr>^G6G?nnR;XJ~x*rJTH4&Cm zVpV%QqrzNpvtY->?*k;T{dm;Urps5JEl-n{bs_&Z&*IsPj0{$jB{Z2yM#d*X=;qiy zSpYwSBxS+}Wh%MFE>O?_auo|{L?oKp64}HFbHhh-TaKK)V z_-mjKts*SVg5#gjQJ}-lPxgmNp2elt^z`3b=mrskfF~P*^dH+#R}>Ps?+P6rzHg

    KU1Fe+#wE1!UAf2()Rx-O_tVWD!p& zCW7!?ES7Lb4g=K>2>8Au6L3#VPwW1uZLMWOEUEwk+7|3;SkSrln5vz#=k6Vy`n07` z^k%Vil5a@FLZT0*wvy#aI;r1tQ10Ce=Yr&#jOVAWWyK zv^l!xuYY9Wv2h;Zm%F6rrKl;#p*S+ZsAJ;*Zvx~8!$6cxSyUvZ6}E`zMCr&pre3UA z%oghE;x&hid}*4z@KkIa`&8JHX)He9(U8YNYZi(|U~D9>)#N8z?#ooJz$cx}r^xm6 zf1H}BZvBz7>W+UefJvb-6734dm#_Uow9^ng?u3OKBGT%-Q7pfh2sH#TQI0fQ4qw%Th5yxfF{cCcI8sm_jd(7S(jPe{DHaIW87-=!68PXAUOosd zidvXj;@+EDg8{YNtSkr?eOjzw(!c=3C0QhR(XUXpo$c+XyePjA_m$u^l?V}j8pN(5 zhP$dYie3Xf44eJFc5~9ps)S_jSTyKg(8rJ@m`rk}I6+{%wIV-%{{o`4uSx37cD)b~ zA4_7mYutqN>>w+$-=0fK6|(Z^QUfC(h+8XoX0&j)qgWRO?dBy(c`Kx-QAwM^lF%m| zxmD!@a3}X~MXE=A@;Ov{D>t|;R7iUGWd_Y>Hvrvg2$ww;a9miJo9iuCEm}(phG$!P zdwaXPW3#&=!T9bIY#YY*T8e1Wov8fv9Jz~&iOomYf;G)j4DEL0j9&F8|~pJ((my7K&)5w%2S6l948eiNk`mKvd(%6-9O5P z>n~K%d~+0ha~WqK_s^zJL?OdKxRT`XGwFezDLlVb9H`?Xf?9>!il}Z_li022uOgjZ z^X9jCTP6v1e%maYKMu%u@6*OT0zRTQk;xjPF}`)yu^H9X_=x<;D~)L>Tpo%$a}?>b zfZt-gy}iwt8w!D*mO%169xM8uoA7A&9#*V~rq;3^_KCWO#X6jT#_33CF`XyH$xdvU z8GGbqzclS#J+75QyKw;nRFVJ!>KStChPi7pCf%H^<7uEv85TWy94Bj%H+VDZ%0EhR zoE{Ypc15~rBKPX_*_sq$+7?>3E%d=KxPpNzwS0->sVGjiN%ALz9orM5{DP0n{Rv;% ze(nJdWD3O-ML4JrXbS=yuj^7FB;)b*ca9>0Mm$=AvBt~V_)B)Ju z*Ip5Do?RCRM8xxu-VW)1wq-g>d`21OkWh0c<&i{uK)01f4FHsMai!p5V`kWCP|E?N zBt<19CPqfXqDC!7e4va#xX&Qriv7~nFsx_I&yWgF!X62!s8XQb8x(H&g?iVA>V2;V*vI(g#i59n(oyIsit z2_8+h)z_;-mWpGDi&Mb|g(AUF8o}rq!WiA!nuwsTTsCQjSY_*9G^cCZiA>yhSFXn) zBM(7vWQf&^^_eG9vC0;Bw+#F~X^wf1>Zt)&pTq$zPGk%}uzDj)7|$z@ zWeb=3UW@C%sVi@C1y=MW_`6F1L}^;KEcI6_D6(DjideNZs339->6Fx^t_ANw%St@1 zaKgVZItnuMrQlp-?x?B3-G)1_KrY}QZb!t@sQnTXkBsQ5m3(XseJ5K2lOH2k|0x)8 zr?H`_DNG!W`J+{|Hs!xZ=@1FZ5GVlnsZm+Gu(7oz{Vn`dU5HvnMS6Ps#9+*GT!;*V zbxNj^GJSl}nk$C}xFZ7hSZnU=o&DGMkB|4)$BT83VIq&7c%bbBrwjp_hDRP|Yvl0{ z>6PEK$6wmUY}GL(QX|p!>i%AaAPq6JpQJrO<^(ysyGkkS*K#Gqy*lwGz6d&gw(88> zloIFdctd*eexBSZexnKo@{$IxYnn7qZXZw^LsR@VEuDo#Lh_gX9yc)tzW(Pf_992m zJO-}4=FFA9&txc3<2OjP>j~MKRO$>79Roy%kxV54BeTYxcc*+Q#60LuA0sMM*tLdg zq1>bFW)KS=91URO;Z*z4KfE|5)h=mP#X5eSpKBaUXQ2f-f3Dn(4 zq!Byy)EbfP39xd@+Z2|vn)V$tq<@;-E2vB5cFkw1COEB=-wlb(R6STEbHU0Pwtd1GTHy-Qmw|FFA|DY@p^#%_|Z7V+(2d;(%zRi`x{q=gxK(mT;agZa`gObd3 zzuMR8GXP_JkOt7~T=~D(EIXMN4oUAWoZZiG2L6HtA@TtX_*hX%dItCNBj1PZEwC=C&XriT;9A!X<$ zjuYH|^aK7hq*oFrv5iUPAUJZm(0yvclf*<*xX|r!=5FAXIXE~JhXl#P4_B^V7`u`s z$pSZ?{YFWwROqZ##-CqJC#|b+G^Vq>=CV>~c^m`G)rEP5a7O@MT+xV8hu=Uh#96UZ zP#qMOf_%k)$^1$4+m#9vUf(sYxo~azZI{2Y?0d8LJ{X){lu)P;W{oJm44~n@qKA1$ z{1p+|IPD_C#eR%gcAfc*?~TCcY`{MQi3&Mwu}{NUawub2?=}nAvN~7lJfDgTah?gL zSaW=B$YlKQNeK`E_#@W>>+i1*TaM2P*3W-HK`3X5wU~x91X^dr+@OKh$#Gsq9%Cmb zY%Ad5WMpCjypRCoPH#$ASCw?A&E{^G8JTUshEniUIa>a34! zmp8e^5OhoxhCXCj9Cv8^qfZXk7hkj4g7=&@Tn91sj-*47jbC$fD^q!U27yh;2NkG9;YY_{5bDM*>@MU2qgZEVd4$O-bGWC zmakk6G|rI~2Jt|EG*=70!v#GHMq-kVhgZV4?gEfAVpb_@cprAK#I$iUMXLHo#5on! z&Ole0Oz^xf{YHixbqapl5rW_4S1;Uw9N^Fp4DEv+b4znGHwOnWg_1=9B=(IZa8aXE zh`VqLrYmrF2x06JmUxH-Ud9seJ;_S&ComzXk-O*XC{%HN^6Lz)Cj2vZ$08prK#p!EA4FI`keCea^lH}NngX<5S)pI)8cKAtV)^rJ?VI7 zCnuG#qB9lCfK)OIxPf4*BCQyp4xb>56fkBZ-JZ)X^j&E|!L%({q|ubRfFBsjJ&)dQZ7b=0<|G8{VEO2sDa&m8QZE|UP<~)MOivOJkg#& zXkju*#!NTQDb&xGpvy35Bn(}`T}4@?r(t-%D(J}!4DOP+Iq8(TL|SR(VGGO?S12pL zYAN45RWvo~Y_X=V^gs5tapyZ_$p&l;yrrHKJ|cymdY?AWgN`oVPpNQf)GOK6<%mqe zD3%28OtG#F@=%ue)`>kJ9kGF099-|-O?Yk0DQZV zJj6t4RHiAHJN@eM{=#x4$P$FXoI6@FU$E#m4OHC$PG0@(fA_C>m(OBomS4g?L!t4M zDXYFb)GifTke@3NA}$TX-CyU_w3^W{6cqigXw~=Cn{g}HA+S-$ zz*K}_!g~(k3Rl@`@dTB~fK;2ul<|?;$e&?F9pz<>3;{1ox1x!jsv>xd(#UpxTD$hd ztb7c$J#pffF<^|2m@~+?4!6KqCd;NdrhoFJNIY!1ZxnbaNq)Uzk^tW2vVk!MgEk~j zXE{lB9z^?R{>0EMaFkUw<{gXxJG2TzyOZUPY14k$iEzhu`j(rU8_3od(URRTW5>iv zhuo8S;sX8jz|+#+jsOSO@dYZ0eLONbP@r5ADnucNZ_qfYTwLv9C!R&z^&4%kaG0bSFPf5#H1hi~FQ@}0Nw$1m)JBYSxD!2WU$)EK zZ~M`A`nHqwDovw@ba#9s$_F~$_COn*LR_lEt*)B!w@aM{fbx~b??3%vMr47^c=P=4 zu?y&%eRB=IzRAKrHq=Q{oEZndxRwly?*fN^bg?0hYq+s7O*v+W_@p@oRyt5RiQEI1FdJ3TASot-8M~jM9Z3F z*O)#XWD;Wek6ENFNi)PL;F3h-rJ;$#Q#HC-*5$Zbu2K#&VV0!o5MV?r{y&<|I?rte*lok+_mhLW6TpN&^7 z5j-*c!YYMk)(K=gz)c0C;;PcR4xgXhF6gYm%ueLt-X2w3?ddEKcGLB`5*tLKuz zLM$Z7vBD8XJxA(rd3Xtd@%;*u{Q60={WCm1yok&oLam<=<FXJmo3D2Oh(2oVgqO8$8HF_M00~sLKQVRmq3^!yt(g4S=Q~b8p(tXK2fUCvCl)Lda zCu%32;sqo3`?5ML}x`7 zZs$~tTBM)HZe6;BSzjj{-^1g(1WB?|bdzdEICU2DObkO3Na#O{5^LH>|IzDyXpDrK zpY=CTmK`L#B!Sv%$yiW(A5V$^Xr;- z&1<>YeqDV!IOA!<^l*97M0mTq=oIwpc=-pLBvw-@Sg*|ZKrtS5?-(cDtWl}^Z__DL zl{xiq&HSf=3FXfE#ZTV3gU3{EB41{5QRJx5$f*UPNvCOV;UY~Cf8i@8UEHu}_aC|e z&>^jI%=X!9$~|=61DQ2zRs~FGDTlTED7%ceY<*@diDvA2NYV*uTiNJ6^!teh{`%r; z}s}-tgmCw4U`^yzF~t~&rF1J){$D)_9TJ)aJKi`65JOY?&cx6 zMcX$kTO6JGK5p?|`72TOKHc~*YU!XPC?|Ob6@eftq_O^yXP{d(!Y%^%(@Z2#X-Hd( zJKGS{Uies6>W0u#2jF{<>q2ybK^*E0k^85Uqasep?_e83rS^dP9VhHGjBu?rDd>-$6k^v4eR$Q;BHF3fS-MBi7;!_>tOd$XV20M`o31-mY*ZUM;ah zh*>*)e0;P9mCi!&s1Bx!Y>C%1y`iC@mzS>AQ=^7~0o3VO{r!khyDsDs6%jONUM2Xg zm=J(q0m}*UpWKET3nh&`bV>pwLsh*$*-Y!(G+}ic3|B|J@D$I^1~pWUP19o79~yi& z^XOyLEGu6)s%b?ge02}a8-wjxZW)x0f{N%WMOlF`CMPp>wvk>InLthYVTzdMRoI3% z{c>E8cm1k4o^F~+XNzASJeHCazri2kNy zlVLfBD_TkUc&OT{NT13uHolpmQ%=zEbm%RS>~t_iB1|pm-m&>ChiN`uY|0d8NqVvN zhD#Jgk>Mq?Z>l{FUZ%F(Fpf{!?D;?3mZ|yijvl^tuO?}USh{XK%&tGnJAMvE|1m|H zS7XL1S2Qa*is#NiSXeOD`+>W%qf`A60hw@{=%#hqP5|)8c;GXJw+oVf%D0)j@0K~s z<>84XLFmGBeUvL$3T$fTjux9{=`dc&WqciwEoh5&+{l`bNY z;y@(7ceac#*Z0JLHmDAV&E9A2J$CJ117+C%K{o@7k^x%QIZF=!MiL zj~^zCeLQdWmi@MSK6s)KKa+C0FS?Qx8>@!@t+{g4)1IFcEpRc6hkZyYqp;@UZk>`U z@H@4%{UA3ik-qIev!3Olj<5@TX2}W;W`-Z3^UyNEgwufu9}pqh<7<~4-@`crPLnKB z4SL=yYZEx^`$us}q8%$(%ZYCO$ZftlOMqu5a~F(UA?f2f&zJM*$LoZ89LPL(aW(}d+>lXOS+9X!@6 z!m)m4;7*inFmN*@DGMsHhybvEDq$xiSK9fN6UU9}cRNNE^TN6qv5at;qV7jxE<2Et zoJuB1imp{isZoJzj>`(_PCtb?3z8d9%?~){uQw7a&zHN6EL!SY|4U&lNS-o+c(h8K zfklg?cG7iH(wZNr^iqxeZnwp+8;r``A8s5O zrcEq!fP)VSWJn-IyXU}najqrcwx>pbQ2OuLf1b`=8dLh--Op;Af7a4MRr;Q4{?~^R zM^dw*0_2zI6ax}4Tl!$@X^g{0#^NeWw|FvQX9<-?sc<}&zS?Oqgup#n?tvv9M)^@e zNikBE4NV(TG$OvRh9xO7d<|Q9ap6cQ;5RClNX!s1*bu4kzM<-i94XIjePwWdMb(zw zAC`Px`w?-=QK8jxj*_XFAAgw%6idb)79PBx*1a?1{4@MkQ+IYoccR>ne@HxPHD1lp zo;*LqEz^v>W129UdH!hos}EhrloDG7da3Xh_lv6@*g;~1bIIO8cOqRxurZl7h#3d! znQ7`A=AFgM46HG|Ta0qmL9k|^3&!c&dfQcESy_Yc0JZ^7H6S*gwf^f`1zf8Uf( zA76vsM%yy8`GPD$GVwp0(8a{LZUJs3Mn+y!CF_k!_KX2pG4l^RBFfBEi2Emc=v@4) z1$1&Jr1X_sh)B4hw2oZeJk9JL6 z-sdX5Q6n#x?tEcII6S=VtOr&9uG6g7`@sJ(warJ!^VH$#$yGEg=2L-HR?P6V;PLI) zw*Avl?x(ngwJ}dF|NVJCGx@Xk?VF{2&%3>CZI@4zS&BNtezO$IeuII^qh!@I4W~bt zhg*&g4#gNDR#nel76bUm@KbJPPCbmI=NyGUeZP?uf}|aa77{ECLK#dbXShskV;@5LFpuPc z!fCm|nHk2`B@P*DpAGmMu$z-2^}YQc-U?BY7=+^og(+e1jeQYb^%S_B|2Kc#gLIQF zl!b;-F9=||28ge20-2mt9)i9(at=da1f_vE5;`H@(%%0D;f;i^G@0NAJqba$35(Pd zCiYzec9oeBD}`za$HPHTL&y>6#%yd=2=|Sf0fsHgUH~#oq>nnliiQPNvH=t7jy)5@ zeL5A272+@YF%lZrXA7L>VVDnFtmKMG8FxrXk(xGsetsbNmCt2Gpr80)*JaMpuw7iz zO)=ssmb}}oT}9;TIhD9XULz{3vxAq4Wz+Mi|2l9&qtPR)uqFZOrCrq@jtXa1J6g8i z=-@rBZyMJndi$BZY(#I_=X|i_rMzOwfJNgX=N-Pn>ZUW67Mb3@=1+!#g*N}^tH;B! z>lDgmajSXf%d2EtS}o8A!chT%F&A94;+C54c|%-1RxynuI*I7umg^7Gi>Sf8=DXM+;BkzKctf1^M`DS5=zD4?0hSY&azjqi zYx8hb@dVXv>zVO_j}pd?5h9s5Ofm@r3`#FEA{72gbK(6sa9?~p1YP{$ZIF`(SfDAN zm5QbO;oRDlj2jK3$Ax&zD3W98==t|>x>_@)4#S|#Bppbi{HjoVL5=9HtnMA+4^A4r zq}mv!XjrfC6BTU7;P!LpKTBe%KSWe@{_(4)4~YyzS_m2WgH~XcT0zkGb4<1*K~rhQ zfcaa$Lg#k4F>^#jb!HXX%ZK<3J=X8{SN;^GG^g}`2+X;yTLBW`t4r6I5_yz_O1z5w2#((bVl3q zLR&9aOArnKi8=R;sTR3{5-lAVEun2$6wn9oJ`r4z|J42*qXqXXpt&PmdQ^im^)$mW zvS(po!GznoMh_g(#W7CMWF?+06mRS@z&AvMvKNGP(Fw#vn2ch#xygo`1xJ9nRrLlQ6emLx&3o_~5i*jqpoF$=;;}*B{lxnZq5fQ+wn{(VwjP;XpDTL zkm~)o9P2+Rl&tL-F$wiR8j&ChbBGXIM5nd0Vr2=OUC_D$tD(F|dE3?{h^(-+{p-32 zI(;gLXMTsa#`-_C#m~PE2cW)w70d^rWLt5CAfXj?a+&fiKk8N7Z1}ZKsUG?AUgA3; zFrx*<#Ki3GeymQ1CDR#TeI}Rmr^eGzT6CNL6e_(69BeGIuZH`MgJ~6h=8uAY2(Qyv ztT~o&Z$)RgLZdxGdQOs=i)1evt5ZWX27);#HxzC0zw>xwGUQg{$gdrE&~C@a1ZVMd z+e4k@#&iNPMQx?lw*m?M8k48>u^4KmUJR3B-Pb)#H5pyDG+D-GN3`Z^=HmLmkuLuE zJjcQA0gXZeLmz@4a-|V_W{*{-MF2>{|bRN?zh(Q=Wo4@}M(x z`e7m6xH0Ww`uJvnxz%UdCVOG6wb=jhoxjr(S?SVK&#>QR);fpQ()Dk_*2lsj_Nc2a z^+8w$7iqGWg$GPx<^W3R-jeSg?u!^6|ijOu&oVq=A9a_;Nebq0z@xJ!NrmGMXonM ziFs%Skt2zq{*ihMafngO*p+HG&*4iPuyb&z`W~hw5DMW&0Kj-3U6D+= zW;85lFfAOc4yj_@f|smF7CeM)%Y9g2>;ux(!ApZlmt>2W$+rQE_HaekVbSAe@XnV# zEaMi3joR8VNRGb>JUwLSl!o;R?MDbbvG@pDRRx;p$cSO&bi~GbdO-`#I>l1jh;N8b zoQq(R)0^j>6L2$^DT!kDnq+++N3X_gb5yTD;;q@mW59q^a zUe@Kf<+{w_WdK{SDTI#?eD|DC+5#7<)XZ3qS_&f-^Et=pfsY)ra<($k^}Zy9W!s*C z$KIMKtq$Q!NMvJ5>~g}A=Jh+O$Co{W6T(F<3r4S=nBLSV(Wj+XubESMdOlAKKI>vI z3u;#u`Cqr3y*f_T{Ou>hTJziKg|uqP4jMAIG{#5Dgs|6rqksB7*?7GAq=Vb@g)OiX zY#z5h)ZYY^t&{%i`!R;3Wo9DxL^a^dE;)&~mT3Ar`may?l+NYm;|oUD#!Aj|9ukJU z40P8uFz9Z9CJqo{genVwu)4$nhCdvA@m-@8|0RPA9v*^to-SwFNDEDyP0~Z%I=CrE zG$~DPQ{_%aO7rUYuugK_k(qWlHGVl6%*rwag9AKgR|b4M-9nZFciylRX1SB(5sUN@ zhKSBzXl?wxLJUb$nzrlY|G4Mx=Htg4734Xz3W!j0%!{|tOqoh%$xLlaW4PmAVvd)v zag!26p^vX;Ja!kVh@Ixv#q(;fTYnzb(<=HgcD1_|F+<&+%;%`_2orXV|5w1?G-RlH z8TZQNB8$uCu4MZ;98;(Dd7G|Ogk3~5 zncvSkUtP?t_Z>eR7!PM$9=%h^Y~1A%KP~n0+FfuS%nf&VPLE4*Yrg-rw>L<0x9>3Z zv)cKclkesdg*ai7-!X}?ZpEaTmwkgQd#Pyovo&BXwLPpMR(+JZuq$a$7^Im|k!?KP z=t`FjtxCa6$Qa97^wcx<|Gj0Lrj`Z&_gT*D0u)9HXgqXs{wPts>U@^b`*@?E7@>LU zad=2IzR!Lrlz50*)?KPejELSRyL|EY4?g-kB|641sXh;RKT`7w{1d7tjvNkCbObTf z0wD;gk18CY$*^YeWWdVkDsnw)Gvc>C`p>8A+%)^^9sN)o6xQo#+%(ya`CJz8fF4K& z;qbc53|QdP;!^|-OIbpS9Fb5!pIR=j61)NRTf_}0Bqqc7$@ENtZ&E-Ytriu($A&&@ zgcP_JuEBoQ?&8wh@qJbB(XUPSg&99_H(&9L)CM9;9;oPpfgZ8wjkeMbMf*=*@b>ZJ zN3aLr6Iz>}3=rzo2W)KZXkm4l(Sl}w*Cq-Px%$g1iM6j^EUyfT)39%^r zHhP5Tj)=)wm&OlZlgm`qcP9E>l`ku&Ffiw685BxO>=SN!ykl!?%zDG!InS8?c|Z?C zdXP4hzF<8UCx`?MAWx5pDAhi_Hj96L1vc@ z9M-)f0;RCupFNkDRk_3|y`OMDRipv6U%kw!CaMZ8ci%BHa$U#*dCg7pHCp`N50NaZ zjZ!&2%OEy>$$CR*h~=opiYMF>t)rIcRIk7LQCv9}vco z@*P9T$Czlc@F?{?9iCQvtN|vdE_(QpNON90X}K3phSS0>g~*hm zxGS~6M=H?xc3OGPR9k-XnZR8a&{CZ{ZNu%|^$TBB#d{-}$_DqDp*QX6G{`?F*POm)#tjW~N~0Dna$E^5ErrxhvAH=U zay)LRKqJNIB6is;ezap}BlUS>*nVDQ>cqGxiRq8_HD&W1<8ZnX#<=%Mt+%&!>l%sQ z>fUWf3(eE|Fipcb?05wS3cdC$zYle%Rv`F#l}T{CC*iVhNcG3?!M5#OAmzib;qB0J z4%hLb*r;Yj_qT=vjZx&uM1jAnwG{- zvCrqplf9)hKF`agi}$+gpEv!Vj55c#nvYVKny1B1e@fi$hadaqpZ>0Tx@~e*%DR7Z z?6-}Xz-$i^f!yYU>t0O>Kd(WjSQ;L_8MoHnN4B+H4>97yMLJ_g8210CZ&)dPa^oWdBge0;C&@0HbOhFc=Q{i+t>13F#@Bg!PE{bK|gaEFi*hjfweaQ=47xCIxK z=U`u99s*5)I3KTM^;Y2MAmz+m%MYN_Acrmk^A)MELCX zq0F#p?ohyBOe4Omv~<&{0Tegd)<92o|H$RL`-U_HMB|pb8S|1rDu zbFg#~e%ygw4jleI|T#!LkySdUO+>shaTUCdEQ6O{F~aS7jY0 zD@^#nQHSPjQ1qD&{xhy$g_S~vK{T&piECJe+cDF@p8m0Y0;PuqV>6-c(Q9#Ey?y;5 z;gy??Ps8)$YD}lw|IyfRRI`s4P7isu9rC)O=K{tVnfpg(1i^@anF%?PS+vrMHbm2> zAi&J3J4};!7Lz4qA;$bh%iRX`&gq{_UU*nKU8n7A0Y;C%NV4=BFg5(ZOZKT+@B}4T zs&2j%2;L^^YU}C*1qG9*WH;DSLlhViO9JIib3=IQqdlBciu9bba*QHPF$&gGOO49ta z*Ftj}j{1BggX{NU`|r}}-}3Z%d)Dt;bx(cA{(oCbm&tdi)=8#zkADdwey6%8d2jn& z6mX8Fvs*4zwrRO@A!U8MR4J4<68W@Vf)x$ zYyZ8jGw)-U;Nz{apDka*F?QQi3JGEUr+T!CDl6J^XBDhGM9s3o8n1^A5WLY^`4D^k zd?mm1_+%`$|G>KGB|@tt_BX?8XOAwJwjB)z%>eD_^Z?!l{wO31-vsZK7p;kyWqVlA zPh@X^_!z-KInNy4zO_;>J#h_ehij)&B3*gYF3R$W_HDRAz<|>Xo>vxXT?o)EA}q@g z#q?HBk=HKkG6tAng*BF8YOv-opqbQq^l{1Ojh>x30WWCp0U+0#neKY%D;Bga9Ac)_}*$#YJIWHB62;;kGrwm z+5&k?__o}6HY`Jsk*%W;|K04}ok(;XchTn*ZKlMp>FGc%`KE9j3^Q}Nu{pjfmz9-K z8wnHLrA7(W!VCq8^UXN2YsT2rNe5IIk~Aah?_ZK7DlpOFM%WHIE;1UJN6@MT<*KjT zv#oqn=;7F#h5O8`%fzBfEtrJ%1=khZEf)8Ccz@pL5>t(iBLmeoX7!Y@@U`TE`msyC zLT+ieW*|n8B(nLnkv?;`g<$P8M8K>B1u9U(C$8W%Rn}8e^D;-K-By+KbtQHSrHG;I z29>WY5;fjeWxC3GRAwxD(XYyu;J;W;^PN?w#SB7O<0XJmbRohC2yx)fFCB`QjZg#&v&8Z;9P?q-Ee%jDa) z5T}{-eTbq)R!QQ#@{gsbV$Jkt)EqXv3iN;I^RHAjM1vmQ>NzZ5hNe?5{W7{ru^o1& zemE#R+98Nn$abAXy zp$gkY=FZ5~z@fvFp2|WitE(sM1hPHWBI_$n1k#a57ymUJVs;&y$!^Qc)w=Q>1a2fFDTn~=0Aa6C#8+h$u9f}o+H8wp z^kO#@%wK$X_zCUwR4)B}lfb{H^XjIo)xW>IM^ijUbC!24T#38zK})*;lh=S}IDj5` z1{Kv_TO4RQTz_irMbh^bK$x}?NpZRyYuQ6xlMseUk&rSa#3u4a&LO2T9=%u}kkWD} zQxF7%+;pd|5!0{8KQL5UV`DR7R1rq>o*BF-Y(#0Ff( zqpR@84r^}GP0aT=iPFpa`KIpj}nDh z40l)(mKtJ|x}$~6U{*q+fH}*e`oA@}#k5lbIyc=sZTb$EFbGur^NN0+t|h&TLJ?nc zEn<$T086Vednxv3HC9GdJf6Ubb%~tl92oh0h&Q^UMy`%gZ=oya(s zvEP0Xdn8|3ts-l)ZXOC9o^Kz6B1D*RUu7xTA$ad^U5lT^i*_5l93{t(Pl7fbpE+v* z;^s+M+u{;mHhSaIkYKBAHmUqx<84b^Y#V#kb-}P2wcm!Q|5G3H)lfbCb?3ejJ!8B* zwZuh;#ys`t^*fs;t)?HlvB~R&US89?Fxd^DaV-W#yY1>e+ceN`(XC)3rX`M8CL zS&Hj}{&b@@pTVZ9g3nwn9(zOc)VDXN;`JE|LQCH_8n{Hi#4#yl-yHbgpV0rDZTK#_ zpj%2%km^QsF6y`Pa(WQ8)o(eVC`rikuT>fI_wLT*=~kO*>r354>%J_THLw@Na}Afs z`ddcHL7|LKC z{zLBV%*2C(W)BCSnHKO0IS7zi(gbT2s!EBy5)|x%5X4ckRCw+{NRgGPX3xt5k5#9zqde1${3EdlzTLjJ@NR6EKTh>~JFu1q(4WOpi9${@ zl?s0R_@SC5hK`J22cgpn)WY}`3%Zg(P*Gcpl7@+zK57kuBA`JB@Wi|IfAdI97BTx( z#XeNh_r_ z%}du))<>e*#7*Gq@fM32==o5)Fnu(bUH6$;XkBsE+D_k)Ix^V7MEK2Ui2;NvIR<J zW2km)QtL505nO{AJk=00x~iqEI+Ys-LP7qQgX1!MbRr~?unEVPxjIsXq0-q!^+fdE zooG(c{Qp!CCU;=$(ka>$1RvMdEos$Wqi6~ZK(f{I#}{6@G;0vl39bf?eo?XdZipu3 z#hW|O{q_|pb~ts5I?KPIAt;}zr6r1h()|3qq+PHM-?VO*ya!)X(8w{7U>$Jxafq@R zk=_Oib`T{ET8@2nVat@h)l z!vrxg|K%vv@nWKivyqOv$YwBYj|MspCkmy<&Z^QekeOS($+@dD%B(GhTHLsGO-WY5 zF@6>yE2MF!LmK+R-5#}_fE@p2EIuen{gnR0E20{_&e)D_#;w{QZaIp)PURQ2{6B*{ z;`?>(fYB+{$V2h>TfB}7rY&qPnaY;P7V3_FLEEsknncjG0;UKv;u{I9d?T+_in7+{ zL}Q5wG$p`Ua#i!Y+s9pc93+rcwf9;!i*3f{5xG2Rk&o0IA8y;TD$h{cAX$1U6ZAVh zH*VU#S!M3$IGQU^qevfLvR*SBc<7w>&wC6V_I+$62>+He?^~PYJDYCgxpuzn^UzdB z&7?#~JoN3af{n!bx2j#;A zG_M?gz1|>nGdLjtuX0dA&vhd;ZQySE3Hp6%74^8w;oEl06El09|FzKQ0`f3>)~WTw zDA)44$frjlUi;l!g7n6?G4uXcAA~LJ5Ps9g*anTr zlBr?lz)%Q0q|a&TBaEi3)YR01SI%vVM-s~4wUW6P{8b$ZhRM>7>~ib zBMYSq0jATt&IvAw@zrfARpZc%Mu@D-Nf73$6CWuS*ag9~3GSEJus6t!AtoUKZS1qn z%}vnH(Gcq=IuYJ<5=ILG@=#ENqtf_5W-uACl}haEM8W7He*7vo>sD`RHX;J=_+jYE zvk+jTE66JD{DEAhkaD^JOt2t#d8P>V6p1CJI<|g(;+d)rpFX|vyCFq+GASk{35;eA z(4@?qNktNYAmHrTE&U5+Oxm%lA{c*@!{bmrV!*lP6!wbV#EUY!hsqUhmUWBtQ@Iyw zjes7xpd~(jR1lI;svZTgdN;=hZT_${Yn<^IhL!gs4yFj19NL?Q>l+V zlcR*J<9lw;=7iMibM@1Uj(t=h^N@7hzHYVq&pmVHU5KyQJNNt_mTt;w5?3?k^}d0Q zeJE?QYSFHMoFY?Ns(ycu_4)Afig>5K#Us-V7K4LqV{n^02)TMqLCuhR}(zmspaWvkDv zk5}_t4I2qG8?(>-fR$pkl5FpHEaQK%E2CBJH+*bRb+b^Lf;-iA)gjT~>3p63eC}YR zBaArdzwwu1=>&yc`J$P^q50JKa>=b}(N#6${+r#-3+9^2=^|)?^v6={kLLgAjmb8G z73aHespZq)5dr+Vo{x2`=6U4vTKDMV3FEg`u2fobJ;w6u## z3}j9yoPU~sC$74e_nt{T!S^VNCQh$`Wu$NEj33^B3$$f zjIi0+_xV^*O2QEuGa^XJ81FZXCd@P}^%n`q%=nUluwNaC_?E0J8ssr374cJEetub( z+z0w`R#p%Ih(k6?oO#!dEm;hvvI-2q57djo?Gexw<7uFcX?OL#W~sq>du~pzKyzUG z9OTJ`+tTHCFu;lX0NUEk={l)I=rQ&c5v95M$M$kLG{NMc4Mbg~9#(ZflsBv^Yn?v? z6I-E#Vf)-hglmOmttix@+?IhqDD|sbTg#Hp#2h|+*d*~kC2>SCvv6~ECU8auD{Q0% zj8MVSJOR=-Ay_Zz#wXJ&exPJi`2!C7OWDAP{+EOiCN>j|E*y2DFX3pNK*_dml1@OT^ zKTmE3A{~5HFU1)b;$=EZkDGT1$ksNkm|!tzhM@=1o&bld;}-Qb(!@hr1Q|in8@ew2 zlqAicaO)k8r^?OdaNe#bsW&re-{%^iR6g&@tPY3#$_(u=_uFHLu9;l*oaL#=Qu+)+ z5D3S1{@YVV3C+4w(qt-@?=_iq67zA~9!K9*9#uX)lYMov6lu^?gAu2!9e z_D@ocf05@%Ai_7K-?jJ4GhcD!l}Lv1rd_GzW8cKxkY5D1<04QTvi39K3djC;M6a(G ziuwPW5N&E!m}ko+O)e{4ZxkSS1%-Aje9=_;NOa?70e!I0ecb?=G4U=Pw1$|dqc+$C zg^0H1xJm|9kD?5}GgleXNL3mrh}t;iC`jTVR~DA=xlIsWgi(2$o5iL`v-)^YROi** z$l=YYVaPvSIXrXX`EG)^4EIbQ+21}L6h@~pxPFIE_X0*W_3I7ITtTI%NAo$msm~X$ ztxWFX3h^JwQY?5IG9;d#xE2kICqweB&Dgx~De^vAdbz1xzFxFHesA!ppe90btRTrE z8kXV0*2A=rll^sk4Mu6Ao&$?WpUp?kd;}g+Bu@z56Oti3jNuDL{=b|MDNY2pbxVxh zDhPrS5%=lIlgtnfWt3yN#Uo20Vz29JrYfp<9O$s$QzqtsYVG8k>=&?ja@tEzY4GeW zJ(QG{0No!XXKVDXf*u#99|*98c)}=D&vFTVxxxfR^J+~tb*X6P*gk^T+mGF^ zAWY4ZMo$D>@b%pDh~>_x_CAi72P8Tf=~3s@7|bbq8vaemV$4iaN{V(sNv zz1+E`SPhbLh9)E!2nOnt$@5l`agH=-Za~};Lo_owD`?8hJ-%u6zA&DtPMtx5q?0)s9ahCoYr`^f6)2ug|nB&8zRI5X6d(U3Wp22IKWb~K*>6`cLquF>r z-J4o?4_S4Fy?!)m_S@HmQ#@AbtoCeh#(#mcjL*YEG-lpHYsb})P<{=sj-rbE6`P1j zmUe~LG%-k&#KZ+$N=eD*;5>>D|90Z3p~Vkx*VWan+Ju|IVIgq~{?l!@5qmi4x?!I& z+q#*>!QKBihr6&NC?J3zDO;fFXh>4cVl`m+QI4=J{FF0>>2LR6jvU}tTPHHVTb~x~l4`^@~IsiFR{xGCa z+6uw6QK>_;Y0ArS{3D9<+ z{lvT0;(cAK#{u^Z+^FM4B0l-h>x{WBg3i`rkVK7M=_<@)+Rz=|9#DbJjX}xaB9bYR zmEGzdXWjP#@d^u-!~r*9TIgiyezUn6_xrrpfKl>!7l4?$E7L z*TC3#8GI`f?f|+ifQ~Aj^g0;9(?Q0hQ%K-vC?MEMNsL^5C-B#NfdH|o!nyV-a;cwB zj(roxU3h#SDa#uVlUZ6!mX_Y8tRpqkd3i85|2|?oUgW&EUUMdsHG>v1WjhF$h!;O1 z_r@HV!@xuGL}q=lrepyY8eDi4g1Yinj}6*U^uO+z5j8~m|J#7oRUQ{oFeDh|TXyR`FB zJ;C|?^K<9=`0v$6ZX$!0#UQb&mI8dH&XL$WVkSi#wQy`S@@HXz^3-HGS@pzXT3YBQ ztdATDLedl;lcwV9>S7IcabXVI)ap8Sk=Zb(vN{qwnv$=;om3QopxT=~k9N{wSu zDreMnwIK=?p@W&LkpU~>Gk>H-vpXawYP2XZ6e+8&IKq9+HRf7C%j`uh_tf(+2?=B? zpp++HSB@S~mAs1N4I7qYQF~uu9{x3E>Kg<4IsLhozpBZ?*xJQ2O|4A+uc)7V5x2s# zbMg38!!(cY`dZqB|7J>8S%@VE7MMJvzJZK{m~aLL&t_8$CxiP#sm`gHs&G#TqlcHm zQlNduAR7cClaD>0}=ZNgjh9s?89MmdMvfp|rNiIq*kB_#=NA609pmc!$#$K9830f zY8gU!NF5g!E?`1By}yIV%>*<&k+N$EZ#YNw%)7~&>c)2io{lfQb_`eSP%RN+ekJ|- zHT$nrE3(G=+dwwCS8DA)Rf)ubqB7h~uTmYE;f;}88Sm?(*ROdXORBkwVX1EQX#y$SMC2viN0Ncf|u`;@W5ZUJjy?R{}XO-A!d{aHJ1^%&`{%;v5T zwbPHzpGUIL+-dL3a8*ks#U4OR2Q7B%tE~;3i+^0+F|Y3zWWb zs=#LI;=O2JJR9`xEnqj}pg1b3`D6r3wUP?G2-)oblrK*L|aBDu0ZSuuM>{w$#2chXzvqwF`kLeWbmt*vJEO zj$_K8()gs#)gngyIu-sO^=93EkoDq0_L3TWX;S(=19kI+T=W_v%9_5bbOz}*wr@oO za{5)XG{3F^69kZSJco*YNXNh*?I>&K|9=0(KBF!cLyHe5**8KLD(>r8iU4CXkTN;m z@uc1=J5l~)!TVDiLt{qIHb>FtrM>CFdCY+qY$NAZO1mo+CF2kHZ+2Vw6leyLP_OIR zAv4hI;8<0?C!|RGwGpVgpcd6*Rz8h*7JLar;gE6}ct8O8yUBYZs7zYv%$EEIj2V4K zGzLsu;M3bGD+52lJEs5LtZ%`*C#goO(C`q4Hx`KvrqpUTCXSGyjS_yxVgQb=dU$XE z07nQDldv+z6h9^FX9oHWe&B}&S}_KYoX}!)?fcvvNgyOLV-ay|%7i$p$eF6Irzhfd z!LrAroVUguxZRavmU$m6#r73uC?6b_peZue8V_aXms%@z@MUkLR8KS)Co=j9IES8| zx1;hjJq2~D>$4f2X&*R#2ad9z_$ULeMSWWf&D@Zh; zu&;;j2ccIgDk{5ytji7bj{KcFOa*mA!lQHVLEa^DUBFqGngbylFi4KQ;c_)}|MaPJ zd{^xGc9<(!scymPFF0X>o9WgEub(+kg z@ysYGC<>~%ErJ=aKk^}L$6)ZqDKVXf>mKt0V*)Ee0$!?K6X78l4g;TKhxXNt;{MS=v)Rw>)fbZ2{(q zLX3`gmHG=}j8HoP+iL2I`>xfTWk45IQ7{JEYTNR=z%jk33Kc@^QJdEr-BCq1?JPaK z9~9A$`>3H~D7|~|@w83`%+b$0geuQU_`UIoJsVoVu6(gQF%iuHW-n*DDX`;d=|dU9 zt4CJmT>t%Jjtvfl=uyyNwTs+P`7ylDrzXFmz}Hk-6&i~is|{FU?lzB}IK&|g+P3DA z6ELz{38_-ll08V`W4ae!{IliK_{vUa{kNuc^sdP;?f--5h-zA$PooP8_S4)Bp-uD? zisHq{(WAA#Zvj{Hm4E%_{B~Uk!FblMO;*DnJ}npti=!8Jbcx(RA}Vq}!Kp=WjB2yF z9?bBFd9S$RXuTd83&?`uGC=L{_&Yr6gT~DwO(962jse`UpfZv4LFqdzM>d@VdX8Bc z6ivwR`QD{hfu^YxvXiOX!AvFS`=jFLmwgWiEV8t**_){}2c3-~{w4V^bV2Gva2YbV znV29Hz+fa$12Yh6UIvySQ~c}!3+a8Cpc0x=xY{@Jf;5lV*4i`gsOP9_4Qa4Yz!#Nw zJO2cG+XirP5fRkso`c5Q%MbLzbWMG*plwfJn)dW#GS3{f``obJyprLJH{9T~b~E|T za1nUD4h8T!C@PK0L7fQL1DvVg2+=6jDM+%)bWPFR3q++3a8we>G}70fuQW%MMdQv3 zq4#SrIC2pgA0Hpt0OT^6a2z6xP#^*|L+rB#ztfQDF@LW`)hwveDD$=IQWMlR)~BQD z+L~&gBNT1c(>qKm0O8G4Yvvg&y?b!JkmAA&uXjfCzSx<@o^UvL{=J+wj?0rVU9pEC zl^RLJ!*UnRFnc1Iy&mwmkQ7fR22rQ(s@(cRYNsfxrF(4>lgGqw4}Q|z1a5mo%0h0W z*fLQL)?b=3j*$*4cYnz&cFEu_WA|N_!saHUBzx}uu@bP)ef3lPmku6zg={=dA-p@W0}q3JB6s{Fz%4w53$Qqo=0-6`E6jdV(P zBaI;4DUE_iNq2WicXxN(%bfqL8C>|qrEu}S=RC3ZZy!HCJ_6Xck$27>KnRYEjuH#| zdU|^kdZ(#XC5_`1#xbb)W1v2ES5#E!R%lhu0gn9HLpPN5-0w|WH|(;uTzR?-O9ty9 zCYuMiMnjUiRA9J?vEj{_sOon2arl|Ow|a?RVk%$w>V}V&@L7M+p{j_|mm#Om@ZI4p zm(dePEXZ$o*c!~Qb0@|#@tAW{{O9605EqwF82xO&UFfCS&{b9TL2S`V7_Tto$5;rR ze2Ds6{*-yHzY=uUp}ul0N?Qb_X1#Y4-GV}DB4;gE{&AKs==Zn(k*P*5S#*SNt70MR zq+NnUiu6igQQ72)sEc`3lW zbxhlRArI*Q?7kSyOJ0imw=Fa!B_%q%XoaDd!6r)IF?{j_VCiC~KeOV4<&n5xH{93r zpVD7obcz27qp2(pV&kMFje#2m|`iAu(IO?Ey@p%1`Z&GeFU(0&89ICRDsm*TBdqpkH7Wl!G96ERZry zuE^Ka@nJom@~8mM1G`>Uv>Y~4Jzg0p%p}S7(iwzG$}ttbC=B>&GxO;yKg@=b(oZ(_t`()6*V z_tG4>^6I&r^^yGuod$RPe#cC(VSEY+;U8Wta0qeoC3Q3Erv_K`c&JAf*2Gr@SC1cqiG^5&q z4oOyBwKVJ=`b=#8bevvK)9X-C|JIAPLa9vzPMC3#wY2w{)5ssbP*MI>Bc>QiW z@M#gkK86$LqG!REhSQ>Oa^p+DC-vucc)zMPMZs?G33&CD7Aq1^07OL4q3;sov-siB z+x**OiKv&gAI8vH5VoYEyFnZ}E2rH=kjIaLC`(#i2Qp`hSMrKKilWb+Sl!p-Y5F+( zz+2(#vgg2#7+?L;7eUquy1;)Vx|$X}3zP_~gtq}58FUVdC%0CdpjygudF>gmKm(ZY zz+}GTj4vJh5qAJC*vat&JiKw_w>>W+`>055W;o9s(ASJGt5U6N1d+Dvc{#fG%P_L* z8~NP)ia7Yf^!V z^@vLXncBkgvgF%F5L0|K2>#>m`F@v|qap@_-s}E+BYj){U~*w(!}*zzAo;QN>S)aW z3!+&4(T|#tTcs+nXaB~_CtZN~6F>kEniY5r^07K1n}Eg)tnMxz|9eh)cXmEc@O&h& z&8PKbPAtEYPpTOE8uwa0rlcinD+&iYgQvgsS186GV*ohDr!PeH%@m6ECuG@|u1f04 z4+qp%kJyCcrX!yKpIn!p%}u|Wo0=ZEgr+$PCS?fqs_ocPVmu{K`y4y-0$;m-rY3Ks zN?U$E%Py;x@E!|Gi>xQr?bB(D7d$fCJTLcmw!iP}WbB6Lsy`UF_EB2rWTg9x96muJwn^s&(5AklQAa(F(Z_nA(MR_Z z+TzD?MLJFG1tCb=v^uEpMpWzgM)S&ik-oH2TXQ`xbr&pFtf5ODjh-dzyl5WuUn^4md=T?$k8T~B) zD*^}2^3nb(S=x^vuZyXN&GkMA($jlQ1`cw5VMGvj_}Xn`>Ll|YUt>w(Fms0 zv|@Y}@x|IjXOn3)HRn(vZ4Q<>lg?-Ql{4b0V}?n&NZA<%If4&EsE4rB;YDJ;gaN6T zoY84&0ONpJ* z1PqixUa^bX8raIx88$P=%$NoQl58x5vMP00Hq1A9W}Gh0&R7K!he(2NvxDWTv|HRy z2urgI6~feG*g%=t+}sQhG!5Q2453J8ouXkqiky4{{&cAKKLt)3Oo4?4lz=Bl^PeO? zH|y9GBZ$s;c3&waF&N{2EnLCDE6uL?iiIpP1ok0;{?5(`Q(p;RFDpYC$=X)zC0M5y zK*Spo&$JuJ<`nAzuZKXMtjEd3#KgsgqsH`8mXD+k-wkj?H@hBS3G!=DKOwh|F~Rq6 zW3&S?x}svdjVmaVi~c3k=Hz-=cs)MGHH!w6)%iT>wz`6($e76+@9Yq!d^#O$g^7wf zZPL@Tvs_`njEx{5=cS05UtDyqQXiAL{wrYbP^as(9E)A*T0u2({QE@l$G!2A08hoP z@szQN8hu4KRiuITRA9w8nS27ix!rDQnv(OAm#n{3wz#OJS=zxDeV>?s*WIk&pPZIU zqMgLv5_}YkO6-v}Ns#Qx;Dwc1u$y9mm+__Iaf@omCa)tut46@?# z@)9TWlhA@$qq{_r`qDIv9Kzif1mKW<7YBR0HPFX9|n0!X5JHR;~-C3SEAEmQF>YSfd}+=E)5EheOMCY)_z2VZ$@f zwO0ubOU;l|sH>}Y@DA9aqyf$mDC`O*Mu2TXVGKbG#_R`mS2RmP^3~orz;x3^5ytd& zb#*;l?ZuJ^fgy645X^O&wz@gnYkoF1Hn3W%tJ`4`Q)R?-kw2fFERZHBLSRXF;uR8V z{rlGrFmAt^^l<=c*fee)erOwA4?g9J6tG&D!$x z-J@lzs-MJ`I}`kz?cmtcbSwT=S64ST1N)0s{cQ7!Qsvsw4PXlLL_YOV)jpv&t5`l4 z-RzS2Y1sI^j>_etBw(>LifbmSfX!-ZU9p$Py&WWXx10+subZ_vOC52sh{I>Vf*;sU z@NXag(i485AOCahOzh6)9j)x&-oA_Wh2z{QG~Fg5=|3|QWY%(K{IOCH#eAz9_)_su8m>V8|pJNghnFq#~Kdr5!C;2LLL_|cTHyVY^w1#4hN{%4?((D-i zHV6Z*mW}l&Td9PV4}4flEuLuAFIm^?&46sMvVROS-W7e+EELB0g-2U#-Taxjha1PJWN$HQ>P`Gjm%HQlchbvcY zq=Xm$+WKe&meg69;866ijU?BxPoHLW$8dJa`oddn)ijeVnOP`5kf}=0@{t30#vXEI zSes@`V1=01@$G;oZaxv$r}y_4nDuf0dlTdy9D(MXnb6wJZRRDOgIUmb_{xZmInb4b zQcXm#lv&4~gNgumQbC+7F^(=p_&)33T5kR7Un5D{w=IttjbAJbv>nUdvT^be7w zTTQvyL9vHE#G_Kw!P)#-ypT*LG2PKk!cz(KHQWbMyf~o;yij{0j~?=diD>g6_20FQ z50#}(6N3%H0^jM@KMyQ|Es7)2pB+{)9H|+bWb?hZ_V|G*2tGl7Gn4l=f-nUXQA4Pi zL*Xl(2;T^X$L$JWN)=3kwMi25`6-~6CiQFmlKP5jD`i9ZGxFD`%9P=qm6a8x5*IMb z0P~+RjnBpOgaqVn)^#iPcR;!TET2UEz>jY0>r1rRqQUSVOiJcNDcE-I_r}?RKWCZX zyKp@T-PBv()|;PjKII^sl2#WR=o7%Bc|}@pYqpc%AoW3P;|{X+0x41hk-;r33K>`_ z;5n(BIRY*9vDTfGUHjTm(A1LqwH{!s*-QCs_iAhR|r^@$5FXCHJi&^Y& z*f>=AaK7=f&V5r}^UzAdNjap2Xkw!sR%vFQkH@8N^2hH#W$qgGI_1?xTzd=IR>)zQ zR#ef*nqbPGM2dya8jhGhl6Io`N0(M9t&zdSVh$>h)-Xuh|I8R$E*H{!v1>?r&*BkD zhJ1T>_hZoDt{A|o3Ywam1*Vr3U*8;5=NJ&x<9cX>7<;UG?EwXQT|T2ZpLXev#hy2HkejlF!6O*q=Qnxti=Xv4ZhZ%%04W1geBr{c*UVn&(Y=~A0i%+KS04T-)% z;M8ZRY7vcI{NvPo^Nk4a`!CH!*8wHBM5^w-a|ZQNy%0$L#||I&FZ=~00Y3UFkvzOU z|926L-`*_Fwc!%?+5*NsX5s454NBG&0S?^WGP_ZZ>eRv3>EGLsN3T}??SW(ERC_m~zv2|e0D!}}L!#m%G_9HO#Bi;si$Xac# zqA&vTw8S(FEaI1Xg0*i7Tyt5SH8$jPG2shQc?)bkPZj(dUD72qA44IV5E zW#P%|YfhUui<&`;_4~ez_Cw9eCdZ9eX_03?hWL4TKR1?^;Xi`>9~@OBgr4B=_9^NK zUC_e!)G1ntDJUtKSixnEO~NNPi5b#K+|xe3HpVw>c8{6*I;nS9@7&nZ)D-nwmYxe} z-sY`=Tjh>_h{P0Cm_Y-X4r9NTiHRu?AzR+NV6tH^$LEh#;Ub8h0d=Cb#&B|M{ZlNu zPHKN>jzW5{08if;s)T99TkvBET+ixoA_A(!g3H{D3|#{QDeV?8E&*SN$+{AjG!n>u)q-xBL_GP-U}Vgya+BfAqK=sUIuJG5!`Aquv#{fklCJ z-!hTjv2@7^xE7GCosEA>#J@KIM@;-rMu_7pnL4KSC$?J-g~8RE ztu|iRTK0tEZY#^@{9w*OX~t0U2F6cVSzpxBtHYOiL#=g3cUdXYA_@ zJPG{7yMFfd^+hBXMHbd^8}a9o1SdBK-X!Q$aCCHwx?sQqx7GfcK6_o1OJkWnb5vL9 ziv6tZjc(E3_WC)Szgf#hNV>2nUl@d48PL!aF{}vEwFiD;uL(#+P7O62e5AgQJ~GCP z`qrZu)x$q7mZoGMXbFt|nT5*4#FYuIM3zp^3y)7@Iw#Gtz8O&une z0!6rVar9?GWjN0~U}R0@e64=EY#=%^vi$=h`U$QLsq@P2vpp8Q;Ja6e1*ad|+S|vU zE=XYYkixgEr6R2aEnVF})iTwsn zPnkuER>qwQlPEA#el*$Fe?!JsmkE=eq?c0V1lOBE_V7-e6j$b`udoq-FZFJMjKt$( zrlF9=#>S($%7X2MwKZB=XB(TJU=XBR0dmMqs_+F9(Q`8v7LKFIf)6jU?-e+7_Q9W) z?Q7TRQZEuq3DawM+Oo?i@lGaNKd z1ESgt~?-Z z_*cM+TFy0zks();*z!Y&Xu{9wySC|*)7pbY$GxsObqbk^7FJO?A;t?FMH< zR22;y4frHrmJ4O?D|Y$WO&vut*=n{K-YN3kGo)GgM{wbYw)&53J{Lq|&8R)@--XiK z17+St;&1ZjjsVRtN<8B*>Bd#89o2ax1w~SY>wV0}f>rA}r?nE;WGdODZ?#%|G{2D& z#$pj+U7PUKS^SksZf!WS`3f@ac)avj|1e!Eo=*Gv6xEHh#Xfs^#;**N+1f^^=~8BI zI{Iuo?e4PY2RVHV7uMjhpCG6oPdeZ!`zia2^LBQy7jcP>rz-CPsn(Y-T||Auox5t* zD!JD{TSU)>?8o3E_vv%}?4Rd^+iwX}vX43egB39D`M-@>37>9~MGpsWNnfVM1I(UI zNnaL71vsF1BqHgD*e?gE!uf0WcmCT!jpfr5tuJiEouHNV0owo0#E z4U-=D_A5i?AsmmmOwc#?|EW2$9?h?*I4w%t4N?*zmj$}vKcd95T|{COS^oN&ZceR2 zmS$|PEDm-mNcGLnA_=F{StVbIGFtW^zE$WcNIV2KYiwF2NmU>X8zw8hlJmfgI(>Ls zfLJF8;tYm&fWu*TcNgPbpb@OBOl~@~P*_J>8$iO!$>RuoQaSt5=PeL5ti?Bat zO`(Eg{?C3MjLWn*`4liGPZ>6!lJF{pGgLJq5^x6;Aaw5>J|)o~iB`dW=xAt<5aB7C z{c{e>F~OUE>M-fg`_oMoJSc0i|m_~-UB$_ws%}CPqX%Z8DC+KW75XaIi(})7HIh`mf zS+K&W((a*8u)tgi*7_AHSiEX&Qvu@w=ec^smx5D~$i{8EqlaFAZ>q>}-etI4{_&NKQCH4>Z>DcnxY0Vg7(Cf7mT=9ZRao4N!>%jER_sHmJ!+|fu=ipC^^XV3;?|zMuu0z@%*QYtZarA(3znX`GJOhE3AF+llPZb`D z%bPPVS%v^}Dd2Nk9`QVw`#c!YWB%p8kCWbple|ieKR%7k?X8p)^3uB?Hq}&G(gLq| zxWpOj+Tqd6??6V#w(@os_ z_F78raK*<^@@&{O&{j9E&`4oTW&2-)ZE6NKo%a1M$a>?(T0_5- z6HAYKjDCOlw%5eT!@~m%+d5yjeg$3z(4xdk=~m83nK?ND&=s5cQ5H(j)1L|%6>#g6 zOoN$N&_D?Xnztz%J@@)>knMvn6f|+*?`LI@zelh{pB^!xkUY415)cqLCUhiS^G+dr z*EZ|z;*!Yq!vN+Fug57-XiNkcb>}C=YIvk7zbuJJ= z!6xT(r(2`R#OuqA^iPcHBPO`_8ufG1(m-1V@~Q*8YbC6lquEMxz#%oi3vf?^gM%hj zyliY$_4VQN#VT~Hf4;RL+uA&$OUII|_~aLlzuRRVDgB+YJb_Jr$Ho5iB@v>wH>fPa zi1d{za;y69-!LmAIJ>op#Kt|fvf9?x7(4;PM2gG5^{p{ZX70Grt7mslSd7&6BpncA z_+mgQtqa3{2M?V&aBPX7la+qdK0(EoO~60PmI;p;MkF*wLDv(Ab)6SPdY74kJWIhd z$1ju6HXA8%(w9c{I)Q31eS$hw^>1VT7_1n}Y0_GjsRp5E!u#P~F!KZY8(P^%epQIS zLv88j;iP#xo*IZ^q&gf|W!2W-@Y8B~h4Iq0%$_f3{uFXaS;9^&x)uEJ(L9)KnhNGB zG(fjQhV0z@i^3%MkAO?ax?YnW5J_c~>JM*I8&@Vl`Q-ZgoGIddJ5??LX$M%>=~g&# zh~b3Z(}u3kVqM6OZj;Id-O8xc^YC$@TLB{&vd)u8?lb#f`Z^i(yCq+iw~x+pZ?>GMBbq#!yrtw>eF8mm&f zj%2li?r1K)0ywVmjgciL@fqDJYZ_RDFbfpX2R~TV1C82QT`Jk?uBiqh9V|^Z_hg+S z#Na|%6Z8@)NYQNBQs0A!cRBeEPs_${S+|3o7pNy>tNnHf{cLD{xoXSwq~hkr@Vwgb zdT5r#V1B%E*{d*MYja1r{YhxJz7=v)(th%Oj}+oy^xV_zS&uVW(HDXO!moZv&8@_Gnpnq2W= z>N(Z|DZ^uX2oZ=QA_Dc}F<_puvI3=vHK@lcE-svU`en@1B15XhOJHYWGHSGb8MOHl zd^jE(8v|0Ckr7l1RRvwqj*w*W{#US#=m6Hcz9StUI1Av<&8P*Dk*^gh=VoV@mBDZ8 z&;>l45jq<(b+1!);RY~qOV9#lZL&Tv>|>Y#mlsnyz{c88z`XS)7Y5G(ESJ0{%w(@5 zlS4>IY5)AKmBi@&^LBk0w14%m`ac*Y3y;Q@UUUaO{eIrl$jD zKMdBU#vCF}+<6+=|E~q`voNV4@@Uohn}dZ(Pv~bP;;G2q&R&`Hc#cGxU)5oTps586 z2{zcLq-^{R;ZegoEmPQJE;xPJ!LMqbj(6Uen(~Ebd5S&>@09(8_xzki>OwaAC z5o~0Gu!iF)gA7$-d0D8YJyH_|LDC&fgcOF!MCqBqVq}*oQ>l|SdjpbB->1nI+h`~l zB9E?UUlqk2vUN*%65+9@$~NlnMn8^N3cH-OdLZgDQU__Z+ArI2Usx7?HBTT%o**nr z*^6XjaPf9xVKkX~P~C#3D(hR^Yg{oaQPV9GMUs1q$RkxoB}*lr$kkWK#+$)j zgu^G+7HerE6Q=}&WS558PqhLX*y0alTU4>(vCa=~BHZ>14-? zGR4gX7XImvz5@^MM_?tjy-KO31cRdkHlB>~Th0FugM_u;&bB+-i1IGY&PcP+vIo2@^r}1-EVV)UU*<%hR*YjTYcH)LmvEIv zL-dgz?e`mNka;}jvzs^lMlZYVP)KEVtmI}ZEp)w=^f7?tQ)1-K)9Ss1$bC%z)tE_X zox9T~vrTCG)%W^UVVdGOHdQi;+ami$=2qw#~fl-cprx<;WVkE3Igc-+w?j zH1QH76M&U#A|m}qcHRImjh_)|#1pZ9k4bwfHSlz_Q*dpBg_a?^gzN{V3%GKBbs_?z znGmEGaGG3=i=YddXW<~(9-mLVTX#n8GkHV2G8|S#y$!|a$Ckq6ra@L(cU8{je4G;>LR-mCy!V2Ph+RZ-AAsK zYc1OCe{!o^yYah(HUj<<(+mBZbZeUJZyT^Q1V3jEySiRIRP%1CFKs*X6=Q;Q?DieK zwq9#zu;ADudFtvhTjjfrW_58qJdnlD{C7vqmh&r=DC|J=ZCI>}YSOS2_>60!TP{!( zw?@);$1AVoy*r_KF7+aCucTaX9q3uScV5---bhDAn8i0upku@_wuBfNN57j~I8K$L zrR)~1-DizZVCE>Pm-{yLb8T9;On8h+PCz=fhp=i0pRG)M#kgE!(X7`d^OaO3x2z_Q z(RYMlD?@5IonkbV9r93TmzgX$iY`A&REZk54?=5~>YW;q!!Hkex&H|$@V+-EIwJVp z*5npZ;z@Z(H`1YY`vZc=$dYb_Mg7vLyFjZU%Y-q8iHB))9lva?Z23DG>=G`MyOlUN zGWOBqBn?>#0_N?1Q`;scv6}+78UMKGLf11S;)vWyhV3|SFe;eyTQD`(K2HWnwoL>( zOCp`|C{KC87g2LbQ%w(zy3KcYmbRS~fW{W{aQ6?lT@T*W3~wKydF`aT)tE$M|Ngof zmhEvzG~M*81G1aYPdqF5nFjwPhHsL0{%P7fx43SeZkbl>jT=BV0kCwN5!z|{8?uT- zqBl2O+4NFs4}X;y^hM|{=;a*RpAour$~W!1yYO<6d6x5H>CoQpa&oZ8{oZugV}&mr zCl+UM4|+9FvWO>gf3^l`Y{H3MYs^bLNO!8>$4UYGggV0X7S8|oLj{Nc~@9@R$?&|9e4NJc{`aAVRfMi&2sPi$HSJkUZP)*$Go(jrg8 zB2LdeQ4#ZhEU}+1Kj9p_6v0w3_#j^8h0?&w2YsfJC!t=ShNa&W?AXyh3zBCYc8RX6 zS=$XmW7ruKOL_bG6~@S!u91=D{`va)`r*tk`w>^L(&*)0=H|bIKp=Ec6UG7@p1WFJ z4g5d84XaCLo|faYSrCwt=4NNNf&nkHK@)sgG#|f2sc2v4A5{whKd>>8D@qvO+n55+ zp4iDVE*TSDmbFq=qiW?>IF+L2J#6G^V6FKkW#Jx)Aore-oNRlyINGAB}AHz7v~$T3O*ppCWnVhxuki}_bs@< z+RKK{M_Q`6Ro*cY&AyH?X6g)T`BzJ|<2#Mn_peFA4u40|HoGT1(+j0ZO)*SOHjC!c z0-KXQnzOH1Hcmnlri=k<3>OSbPsd}?JH!1fP9?&MY6tLf@l ztgT!9(<=|gD#@fwYl)>&n#<{K7?Xzp*A&UuNLw5K{rhiSDvYw_vIz}KC!B;g9}7BB zWo;}f-7rGS=z*27&kbmmmqr#9j8lchL`;_i{+ZM)7c2Hs`-Lx5AdG{`cX!gv4QJga;ba zevvJI(jRcMC*rs>IXpT?@(%O$*?ms?g{ftql-ymH-`-(^*k!s?61%LclD&g~}8 z%lz7lh3)2S=-u;?k(ck&M=m}}3W_WA=ZQ5aHzYma&V_Wb!MDI#t2%zTux<{AepGo? zBcb}dLgcZ%?T7FApa*pM%s~)(+{r`oGJ$`Tw~%MHlhE*g!Y*y_fh_`Lxk~ z6>JGoW*$?%$v9knLl1y9MGR<<-I_4QqZH#7OLE_341O4R-n;fDXM6mn&1oTH5c%Ed zp zqah<`QrW#ig)WaKze}uF%qy5rs9b~^gAfZdC^4FacV zU~$rgsgd*|uq;eWUOD+L3Vq>@6x#em)&#=V!2F^iTSb-igJ_Ozqds^^`%lwt+qc}) z2xF63E@8Goi`M4m=D=6}O*vlzJPwzam%F<(2RIlvj92R%~7RziRyoaCFRjL~)=9;b+3L{f6@9LMS{~A}q%SEW~f#1VX`S z3-o0eFHS@vcgrq7SMPn^i4?;|`Zyr%0diRRWQ!dsym zrOl3`bS7VYt?0_u7eY|TVfV9&-U0>AmLic#7As5^tBA@{_n|!i-oyMi$;?9FU{2X9=XKtL00Y@6QT&eJoloYhhiX zBevS3r3qgiazGhE7obJ+=1rJ=L!%zmIH55(^anHbTEY}RWqM7>9C0NK_V3?t#kdwS zs#M~Xu@#%5TJ~@uwpI>B_SZiAx7mCkMWbLb)7I@{whh!(ruAV!S>&E2X9#-xFW3PG zGv4Q=7s*H;(Nyo#%e~Oq!+ol|`gXj0bcXlLo&VlR`|Vl|6yhNSnHb`M?5{y{dLcFx zYF_s*(Dd->*t(xzTwK#KMV`xA<(QnW$IMH(*lsL^AN9_jws&m2U+}-R(rHa5)?ia$ zc|7{_x)2)QbopT5q*zESSbbV*T{M)J%z2K<^<#(VG*2DQ-04zW_3vHDxjyui%M`WE zDVXsaXmR-;zYn-36*=EMQuci;c)4jedhR-FdwJ&p6}>T^cUGOQd@6gnvhz7x2={*w z5q=JT*@>??yZ`G|RQol%6(PNSv4@o=h3c3fQSk11Cg4svVEScp9P+QSb!!j0JLqGX z_{Y*Det&1Bn%tuTr%bQYEROjDpRXuvmq%bD5bBK}=Zi@jZfXPi{-PCU+F8gucgN01 zJx>mO0ddPBoG6^0ymi_vXvQcQ(*ZY$If$$IhJ<=zv^@sI=UchN;1~GV7xi5kg zZXt7hX=-IXSMMoE^}pMYx`?t~fPSg7vl9$pXrc$!=)+Y!yC*0WUKNawjhXNh^g9XX zt}QNh4W!R}hV9%58~{lISI-Yu(L+CW9Q~5t^Vnk)jcpd_c9tw-jx;0-M55I~fa>Yf zr%&-$U-48YnV6Y@k=MOMt!!O0Tt}sO1&CV;&^GXAK4n_SkJ}MxHjBBkGE?xh8ZXh6 zt+}Z@FZ$L}i5Z4B68+;9&P3JdkhQH4fgC8iJpOow6}fOVQ!Hhk*VW(qU+tql(={hx z&&05`Kb)?O?NEH?pQ>byenlLymo^rW*^R~=v+j{-c?5fc#S&TG_$zkxQHddu>{ z2Al)jZiZ}uB4oVN+d!t7m$hqFY)H*gK53vV(FP;6hgK*A;xqI+Ft|EN`u05 z_0D=&WfKN}$IuleIbqCwtDQro^+ZV}#|zM!&)#;*(#EWSE25S`vyLf`o>&dHRC7RE zppJo&8XtA~v`F_Wctdm|p2ex@VWhpc3G)O;F1$c9993ZHKAU0w(VsU-p&PlnCBKs*4sK!=0*>#5AB$El;Y6<2 zTRW%Ee8%^5Df0W2+b&LCE^TuIt_#|)j7T8YXMTrnFHcpn)CmDI!48nHUKvTrSe7JL zpKV6;02}ehW22SR>}*1H3M>cTOUMhv8M0sBcG9d|FY>fRDtISefI@;u!t(uFE#ryg zHUf>%lTRwQY5d@&8K({rUZk?$T&#b8BpWpa15Y!j;Roe`hsw8|_Y=x23|Unuhzkv_yZ8RD#d zubPGb(vkb!$VdcgsAK~VpxO*D2)-c0k(dkv)8r7=5ae9(6K9P9n`>iht72RIxXsnF zInty9#><$BY2}=N|1#G3Utyks%#zO&}FZ`**9*WN4(|SI4M@?80ec zSVTOdl**+h+6sIB;8sO{FIZjE;pEEh_&_%Xi)$q~a1G{~Ob3a|!jY9q zjrxXQ0ivfDoLNHf%F*&S%z!zEsj&)^G>SF$6(Uem0?YXuJW+n&pspehovOj>SXpB0XX@zp>5?ojm;Y7-gkL*u{B%`KlPb2%R5I8 zR2h;dehWgbr)!bZpjn_00D@a|V86!2#m({BO_wVYuL~U80}~h2_q=m?WXQl%o!jcl z7u6Mgg~qq9iqp7`7dY8*Su}Ta_Xq*iK|h)hy0NQR4p|wDq;zW*X! zYAhUM8Inw~Dc`f86D#p?Dpem+IX%eEjnZI3YfYv?l&Wv`S~rF>+^+7;kd;K>NA89R z5b9s7mhH~>O@1sW>HJtmq0^nMhiqbAQFw{kaEof%WMUTBY!t{d=ub-a9V5GQsozbz za_+)ER6p;OdT;>0JGAe?hz^H8l|;GS_ms{+Y$Ra$19j@KF$b_GFzQI+r0Riq)U*LT zTfI@OR#l)WZz!2YfBmWgPLYxt`4wY=CtO!UK{Kook04pMKMSt9M6z5X^?TN$Avpv| zliEzwI&M@c`pB&wsTd2|pD)+=`(24tRn}=`RbhNnwY|nQrabTwF>b1w63kg>L(MPc z+P~Nhk~DS6-%Ojp5#Kwfs%{5Hx$yEr}Y4tIXFV96QRC;qCmSwDE-duBYEm5&~ za(%Z@XdF>vOzE05qisy=dze@zy(C#kO*Mk#UvXelG~)@MuS)xGD^XM2%*c<&NG%B# zDD1pxzqQR(|F%=Q7{rjq3wi4iYrubZ9ROi@DoMF?DyYBwwC1n-meNiAp{o)-fFa;% zuARc;;o0&fH@DsC$#?$kna`1j^#>D%ITnLIgZ|3f!;E#^3)n7~jka@h8M{3j9%sI{ z9swr{eaXW8mF)qylgimI%I)`K zTa6V*nxL0Zv_uJxoO*Ni#MAEWZ)fbpe{5HA78y+{z-GYvm{8vW8F7Fv-JOkp7!Qe= zv8?Q8cj{lc`Z2%wc=ay6pk!$BgVnPo)Z2;r@tYoJR0I`6ykVAW?20P%BH%JFV%crn z8gpa3#ITWwc167=1UzuIXg3IbPf&Y?;z~A_lPZ)aombl z8OCU}LoX7qoNER?fpJwDgbQP;@9>WV6S0Lz{>1LM!tc2R^J)NhjuuXo#jpigoI(rx z<^kjg`hM^vWPRIGd@hP6=8zqyR3BUqlD%ereZs^2Z%%M{!%qxDCOpC%mzv#ciJ|%W znJwk;o&<0?9PI2Su!1oAXTvVw{)V%6>&pN92Zgq&&%yLK;Yufc9STJm9ZdtG@+eZd zP%2rF#MlO`7shr-)w0qSwqnM1at^+JQWMbo9KfNWPhyX{HjZ_ zd1Gn01ZkRWT096eEK41T?qNg(y%%{@mV2|}=V=fH0>+!gQFMm)9LCC^z}E1_cu{!8 z#KJO7F`+908L258wGvW^lUBtE3%arnaw1y4HUuitJD=7OvX#)`a~Z8R9LgE8Lf4u; zAtB_iKq=3P5{jfv$xbF@84q|e2b4Jk<| zD}Umpt^YS|7V9}QemLO)B@uSs07RyCMHXc0GCi+F*UOslkDNQQxcC+d?8tC`e=8Ry zaxQ!loW4~pJbh2|s9wYTap-~7Y$x_?En((wAC<{6yTE?s`M}8EwHGL6!YyOqzi*ZP zR{%%76ySP5#=Lq5x8`!u8gPA`>-!ic!^-F3?WN|e_Y?4E`zxcOM_V^zMD9oBRW}Bf zR-vCn?t_$lFCKT^fOQM6F4ZuLc4dAUI&esJlO{mt4noI}G! zkg~|#gR&uRWbyYb{Sn);*8LP*rFILQ-xb1-b~m=913oXpewVk6GryWYF~h;@9O*Oz`P$ZSGbM9=BC?gZ#@K!!W<5>@#!cXlF-p?XCp;*k9^^ZJ*kj4j<2oB>$f6Kts<$}!BbjzIdoE-nhgOZ0l0SvSW4nle3z*IDOIo?v2^ntxA zpvMRZ$b~}@ix3ftl)+z_xXW`i!ACQfYF^pZ2HxBhxgyXMMTq*dB;X(KeV%rT{^3gA zw-5eVV>;YbNDpZ%gB^4{rWsTg^w)Z!O*+wfS2LHFc7^}6rRx>n@RMGQL+;kv!S-0( z_;sEXDZ-R^)A^vX|CD0+>B-3kmqz6rEiLTt<> z<{hKU*B^aqyAfG*ZI1%}CB78SHOEMJiklkuukQdAH>Wjwi_34Gb5Yv0rw1)BI-1N<&oIw!aA=9J9$>$8#x%Fvich9YFV6q-62Y8gU<>5`^@X9;Z)t_@74QFR0mu<|50l@l zf3llQPlLw+&_VJKpTiRLIPNnSq)in7nHhTYN~J;l5pyV8sh^(h{DkH@2VWJR{vRPg zbs0Tx;;pQF0U5m>9&?Q?!G1ApJI?77p38!cb76L2@0S)9BDe6P2**&#PN_HnxiH8A z@k{U)LAu-D*gxxZY4LUI?B8Q~`L514!O{|l*bFPrPEXmLhIRQ|9)Yk*1XY3c1_m0d zq|h}_;D#26^+%YG&+A}{`jS1{%`br}SuWHj%DM~G8+!5}nD-eDJ61QCtABQ1kA&d^3tV9Dy7fKc=hltA*s`i}({Wy*e0 zkK4dqa{UqJx*u$+d(2N9$eh&_+iDNK{=UA^Egn3+vT@4w zO9$>v3Lma^(jD?%^xGqY3~b!+_VsagfFiyB>fu7rviJ>~%+qTv{uMNPLC-K?NB1Y5 zU%`7Fo#rSos>fi`mR?HixQqFn=8Bm%B;hj=R~%q=afn_nf2*C+jU0*rg9YTSS{CEz z16n`ya!^a;utipdq1zOF$>_JQW?OJ=h?DE1H6b4M*M2ea9d-U$RMl-In=}==j1Tz* z#xy`)iD_M@d;N%UFiB}bLfLq2cHZ-X5ntG%?=xE8tplnWR))jtAm-F~myQ!O*xrw;}JtaUBoZKd1dHfg5ieOA8N8Q&WyL<+|8)13ln(W(L1Y>-g zwq+|mW{LX2qV}g6qrMmy zC9!KoY9i-tQXSlF`B#$CR;e3X7gZle1V&7BzoTC|z&tF2#6Ow0g!7$~Z{7ZoM_jP< zp1J?*NA`jJWBG;nN4PctgQ6a7Q%E`vEtNod=|%gp?$h+kJ$QkDW53Vhb{W5)KG*WF z1ijDB^}LL%a4-^noN2+mI8|4+8(gmUUt7>)g|HN3L8J@;aKv+CmG)&_8SKE5Zo`j> z$4x8Z9~wi|cPgzpGgz*Qw;X9C+*QZiF%(|sBh&(|CJ+>533^Qp9*g>XmJ6Zar3y^G zc)vl?uTL|O7SE)6ONSD8?0Bd$FfoY7Vz{lo+{KWL;=lAiG@W%+Ro(mT>F(}sX^`%2 zDUp!wPHE{5>68uu>5}da>FzG+4u!kk?{D0}KRAw_age?CUhA22e&*W5XFoxVBzvcp z2cge_MR~$Xh?bU?T zUjq!vcy*HXA5OeB#2OX@5UPwfxAuTzks5MW&)}i`pJ=CiwOF zb|4x*KfZAR%=HQ}hB&Yr{#F6kzk9eDUdb4IXmd9{MC*b#U`zl{a0Z5HKdXbjtv)ke z;7g^}n2xusT1ai{WHP;R7S1!LMX&Ta=|%cf`jbPx&T;c>BD$cxv!#*NL*L#6c0Oe)=SgK9Q5HW1+SaHs_M2>5soHb5i1 zitKXv`dc`F(Pp+i=M=ZNI&0|kM~rtOjk73R9@i(P;4vx z=#G3@_DSv_Sb0_Q&uimOYMjGW20Crzx`j^^&$!X)zO3A5s|#VNMPlDFWE)#a359S{ zp`1KC4-%14L+57iq@{)VL;7oDa1x|(3k)Zm@jtt8!ic$l{Gs~HxnTVLzTX{Fa zQz;}9ed;k~{oRk=PEG-AOeS3*httr|P@j50=YH_Pg;#Opf@b^3NmNSf@LWxyj9T`` z&6D%N&+kz;AX^~?W3xmzA;KWGKR92Hhku-d;E`a%I43UR!FFb)^G(l;d9v=AO7xi zGok+e!KkT!o__tA0@T3*C17g*6#Jg~{$|_IB_Kuco>cT|wwhRw^WkGB#`a9po8#MU z&i!qIp3Hw0wD{jlZIk%_1==l@{ULs{F9JaTyC={PLC+c97gM`WIFy=1b zC(ggzb&6q2dEJl|j~KyA-919OS@`d}iTW@^U~S;jgNnh}d0}CpyYR>WBJF4;+hS0; z9k2n&0{!G6Y89&JC%M?UZw$)#GZ6$4+9latLHf28GQAH1j{{YTPkc3Bl|gK1!KM*- zQw^%&#muU&sEShaUX4>gR!*(#x?PqCd`tuslQ>Xjo3FaGu>pi8Dozlc5~XHwL_){s z=(}Y7CS1`6VskrqkDsPQv7y|ctz>Idi!@q-z^q8)lCMK#9V6!MFk%?=HV+h?&NrEsU$Z@YKq>kxW&d_9}rvo2Oc2<_uaRX=<@=)c{YS3Cv z$rsLK*<$E(5+ugnZ`Ly%h>%z6TD1KA^3T&~g=0Lo7|L<-Y4rz#d~vTS>Eq{SpYOy= zV2APBq8?~utM)~nms|l3$SQL~`%21+WjYKvbaZwk zL+dowzjVQB_!jB?pQ#=8!k$T>vO?Q5_VO)8en))VK9NR?nYWgCnQ2Pk7I%_S?v5}+ ziRWB}X4i&`!FGDb*RWlRd{O>teQ13|D3K`>?fZ(9&VH~pZ;xFiCatbD<<#hpD7O;V zd{(EgWcYi>+=Eztwl_d5X5|T!m=kicm?zdxDMny=N>;X$25^ z0|*1V=dIncun3!nVjkzgkSZZ^hBD+Kjm#u;V87)}^fa949b4SG#JFKfC26Iz>{I>Q z{BpxWY3(}&t5*mi7qm8tgUHB8kQ}mU1ikg0iN=g>dsIO~?BCXbwz_7PV8#ct#h^`d z>ZC#i^?0C$FFk#5@Z&}m-aS~SmK-jYa^Qdt&=qUT#C1>XkSKH4ey?W`w+6~Zm@&r# z5BbQk?|&OYzsK#*tg`Qe_Dz6PlQy=yyIX1kh9)(p@V&j=l+_*{dV6Aa1R=aI?2|75 zdGKF!5cY5Y<(x8oIKGoTKbpuAp_d4`RH9(& zPsv8iGA+eKfbZN-iPLyTc|7zo=riOUeL7lto(x$OT(H4H_=3^y8NoC^V$u19f|h$E zoV40eK~g}lkCGF!!E)PP1HWr2Q!H9tKwc?6jPs{mwFW_Qx^~Qa9(g4ylO&qRBoQZM zozPvoV^ls??11yzBOXPkF{zUct&yq9-{i!1PAzvmt?DOLt14h9W!T}3>r86S_4@M? za|*KTytFRKZ`ZTa=6$gvjx<;Ux2topp);deh1Jk3N+=9ko*-@xTLx_|k7F0G92loq{UA{e1jVG$#5SYR} z=S!IrW{jd*3AnNLQOuV#ktUtx;FFzvS-n`L&@E1$Z@!G+w64r+oQM}tU4Oo6?K2^M z2;C8keZKxae#YG#$yS7YV~TmwsGF=#HP~~T;5?I{hT#$TZ4IeGYXPhMPdRCF+cWy? zp&vybOOfB7FaLere3y78QN|i_b^T-Pk_;d-P!a-w*xuOC0Aq@3;BiY&4lmi~np6|q z40{LFk2`8~NQQv7yuL0yac-dm_BQ~@h+zrF^@aTWe0)xra&}wzEF_OjzaEp%HhzK=bKXv_7i!QWE;imk$V(};}NGrBR%?1xr!Wk(v>h9+y1%|?<_5LuZ9&!fBtl%p}g0M-E7dwC!5NXsZ&!;=gi~nfg8_1OtweDSJ@bOK))FXe6)J`HO z4li{!%sFqc7nwe{vr+funMpE@!!ng}gX^lO<*89=N*dXzWT-7jqB#(D#*)M!HpPlQ zjJ}XCJwAk(3OA9hyv_`AX^yJtgN(nQs{GJ?0)3>(fOB-}JP5QU)78=Uz4raf^Y}hx zFOrttln78k)C?Y&UB4$MJp{5raw+7agC;1&p^+C(iw-yj){c1xTKR$oBq;ls9h_*F z7IwiQ8BG!0V|Ju^xY)sJkr=AVJ{+VUlEuef(O1Qu33qgjqT^C=gUyH<#iz#l3v#%; zSoVKT1Ngkw5N4H$oBIy(1JROq(rhXluuRRZh-M%0zr8Ju(%C$EoO$@H5rj3$*wPlD zhx$LEu|yFtp5MzSPT5{dF>==7yfVYjC)}yy2qkII7E}_oprkYrNj4UjXE~M`I&}Q^ z)jov#W7wj!`fNO)MY^{Txa}iA+x_o${kHW^?>pcT`22k#`ZxNzq4~92~H`djB0)WjKZ_toezJT=szWS@84l?h>qZi0mW~1zK3Tyk@epq z$&mGh(P!@VwzG@*6@V;dR)m`o_2F3UZ;h}V^U@>Vx3si04|n(Y=Bc2(l*wO#Cwavj zvr+<+JD|q&uU^1c?r-87j~hn#r2paVEQ)$MxUk*cLp*~rI+7np;3V?1h#h5mr;S4p zNhk{58%j#5XB7NPtyO0iE6>c|bSG(`qM)L(a+)V!H%}js@IW_AFnhMHxuav8(GT#N z(A_PUVD3|vty3&Yw{>MKP2xfE60-%vjvG`knwkUEpst5^Q72mm%{hIfyihtTbw&iE z-bj^Bc>~fHRs^W**R-n1_%%`aQdhuENO+Dv8dxQjl`dgCCEIXejO+XsM9x3u$U?Cu zuY)#E09>vi{5=%xgLEq)gG&^&hL}##rR=Eb+&qLk;=6nkC-kNxtK7@}EAKjK-Z2pH7q#KY+z(2bd|vzmNY>rYaY65AKM& zu87&FOH^zpEa1w7GT^Aibqgur{R_AHlVA!5DG+i%T_K31WdlMIqBJvdx^l(hA3mo- zi?AJO-=I2kkRKzI)qdyawm*t1l}q7xnU(ZAfNUz4{V9B0*EUuJW-lCv>YSm6gZG$Bhj#lCA}BXXgYecz0hL8ymo<>XY4DVbw}4N#Gje9mI(S z6&};aZeS#k5B6xltWqnMjGiZMvoE6w`UPBw-~|#;eost*M+4G#5Gc={L9_n=l zoU|VY-FI~`AAFoi=v5$o&kBXA_FZxCaJdgMz)mBFietbCAgm)~M$mA;Q5;9#v@f2i zPd$&qz}slp2d20^xD9f-Bqbn0?q0qjmsj~!^7Oir~ zX3SP6u5A)Y=&+L**j&M-z51l4Y{Z+SmzNhMg0@-=EMicGK~G2bqof3~ZZKU!oY;1U z?|kSh!iz)GpD@ejslSYaJqkb69lz_=6}gM#qe0164#E3W%DCwqWAWwax413XRnlY= z@GKBuhlo?Gpka@6n|!7K&G(yIW;>@9q=YATnjg!QP_W7UE&9A(Hph`S)vj3|bfqek zlj}Mw6V!DE69}O?{S>gM8*?OoPlaAsU(4Em$mUk8BiXU5T++j%sXpUlDKpR@rpXleYguPPeeh1?CSwvbr)wKO zD$+$J(L6m@zj-^+LqngrzdYHNJ7+axHUx@h!!LZ*Gk+j6WFreRPX0IWshTb_P+2zT zoa(m*MScTT_BZRy@rzzmksrUDP-;WflA{Yg6UZ|I3ZLzix1OQM^1nyMJsNV+EU7M2`5bHn^eEXBN!3ws9U}C5vNm$R z$x-$wS2ua{!+z7)muaegX#{#_l+B8*+ZTeqh=K?qzGPG5beO>NyVgnzn~F%Oscch` zrj?6_q&cxEnh~*!z&u&%S}k41Y&c5+2D=y(#rH9_!LAavmYut318ioELr;*{GhF+Cd0) z|M8Ac=|M;!1xrx1kJwaQFw;)?@9KbZU+-t0C4~1mDsZbkevk{XwK^UWamkXe`(D^Z ze&=f~Y1gN3HrEiqK?A&iEWgJ8;8R{$5ZU1FKyjCy00;&DU6S#i zY(b-slZDxCU_PkXScR{70pk?(6m}HAq6PO7=MS>5$Ouk-X=@eM6k>yY*&4Z*ip#p~ zCVYMqF|dfEU>CHtAuCntw)4>lX37@^hw099K?jEA}&?RU-hCtoshnHaayAAG!8T3QVYz|~Wc6QSC! ztfWL?Z>Xkk z5OdC&Rq^N!Q_|*b4WMpLAW-d4-3VX=rt&A;R;jd-!;lY}Z0I;LR23B=9HWv0JPz2x z`S19?ow56zwFuf)Hj*~~h>6MxKJ{>l6{Oe+xz~k9k!J5WL|&TNK1QJy+?WYp`Nx-1 z6RizmOi>M5D@D2wc1vy){7qkz;YX1f)C18-bZ1t622$TqFl(4kS5YM@)W|xzlA*>K z3<;b`ApsH}phbKpmBQ|(aI)Z}0?fA247m>B_wdM5XYSDhR37LEXne3D6KO-vAQt92 zL^?)r)+9(u;=|B^W$K%iw&J75?)_ZgH(uwStPq2ygcCABo(!qt7_-sbU(!dmK}4HK zS;>XmT#%({qVdd2Dlkk{+8$|1ONZ?eV4#tbcDTHg!)t~xr86^XV}HiJ;!aqw(~|LA zo{;Ug^KOVUAm^WB9zgu|#80-~ADy^qf3_a-XltxlV4`j(gvgGKmBU+PqSo~q>Ot>r zUFbOytlwiKw7GlSC3uAy8+LuhEBWu-d6!01rYDa|pRArL&TfjKeNze-!XE*^2|z`4 zZ2?#O3JC1aVRHGhpFiS?Jnba`H5hE3jk`f09~0^kr6Ox1tQW&>R2UEz^_!iHLF!(s zJV7sHSX?Uoqxse~z-Ug0)Ghw$`AOvzz8N|i#0megCgEIsz>`XXv=b>(v2c1zmMZ9A zRaa10IGbh!C{O+sc<6{5= z_%YRN4qPkEogwuSmM@0~2UP|gQCj`F$RYMqq||Ot>nBxIRH&vg6F?hmOUqMgQ#)<$V={lEmbU0v^#*W~ew-X(ON@3NOmGXBBAvOzm&kRumhfICLomHhz1pWeUnDTa z!YsEhNunD&5`));Hx9@UD6G%Ok*;WDQq!X00Xr+*7Xxx4`vyrt)hEVYO^k*el-6v@ zm=9MLqNLNydi3Gcb|9YzQ0fbKnGoqB;69jvf9hDoV88tsiA`UV3`$rU!T=$#QCC`j zFj)wiXM9M{ma|8_dh^1=r^BIS_AoVFejGcA0*ynS>Bne5t32Zt1wsWw@fVV#ZWtvJ z9r?vo$DAeZTsI8flj#!$+rk*E@|Z=PQE!DZrL`~YGIYwbK}@dy8pfN;-B!AZ$XP9g z2~%pvS57e7CbuoBn-ZusrqBPe#v(vwzP>H_EHaE#)hk>I998{~}RiCsljBHraexfn_(o8=y#D(ASpWmn=w74B>H>A$V8&eKWHx1ROvZuriN zLa-WOrsp>zr&UJA^zkE;VFF=7!c}{m>%`xsL*EA}sgxQPNVsd(HZ3MjPO9@*;7;Fs zy>DttRzNxzaG`jI4}q;!60iW7#uCcitIBTin-m)EPd>`m(fi~Gl!Ure-w}@d%G@ih zYbF+-*^z70BENQ0$6OZTTVie4+(T>CxNfZT0bd_IvrMDn+Xsyu4yk74T~X%?nHh{d zJnb26j&Y07O07RfM^*sX0V<&ehMbfGIS4J+jlaOi8kA{*U>i+HH_Rd6j)fsm219PW zOHlv=W>Fy_DH!x>$oS@psw%2VY;(z+!!TMi2tBzU3kZ-RS_{QO?mFZ`M~4*nCTzvOy9tSIl2rR74MVz!nD3PUGM3rvDg$4gnE3Uce&-$SMdtpp8L#tP$zg3`~d zln}V<1fRbbUJ;x)F{WUsel^0YY1YRDuYMJmL)tz-#_W{D`y?>+2?z2cKQTi|cSHv! z>atMWwVVb8ES`iyK8DT-Swc|9Q6=p*9VF5bY7H5gOr%BMJUoE_#q1byZbZHDM|KD_YN7i9blsV zfdUu$g+rIhSdLvYA(B{CXLBzRFS_P$K^y{$bYreU@OuIY5j%W!r78`{x(6*q!wTXu z=@0{T+fBB7OF^P|foBxDcoOOHV~703-S;JOe|wI~1b?QwIaJJ>p{V)IDk4_*&2>6y z9Zs0jeO^QwyP|@a4-xzKLuF4$b`(E4y=b3sR+3m!dfZCPr9R&Wav|7oq95zZh5vZg zrb1I;SqC!iF80sXqm#LWG13f2$^RCLv|i>9SJ%6Lj|!IUcS0ZZDzdW1&MzL|*;;P| zHY0jh;g@a!K3#;uNFZ?)Fvd%rjWi;F!?tYkkC9hTCUrURP?fAZfJ+aW_GYxFiZh-~ z(gsBsv0-{jOtL>lP7MKKYw$7<-4~*hO7&Yo2t;p~Y7sDEZpVH=vlj*vG~7`{9^ycE zSRd4gIBQLe`z2CM4Q=OyHbiX6TllR5I7q|_O$zZIOOQVIBxTqI>H~Omu_Lbhxy!ri z9%lB&k%$-=kWTLo7=T$v<43jYb(S0=cqbwn&rw8Yha1-ld&}c}3(%_u)zn8grkR83 z|Nea?!Kl1DKX)jtV@VsEO0u)Jr(8uyaxc{bdo?t4bT9sXC-(4_Ua#!0(6ija&O7}e ztCxi!a(Ag@he4Oy@eHZQT3{Saal7X+ z(gfZ?l_y0U^_Ol)7o}aC6kHL60nB)Bl7ZSNj-3&sUfup@o9sW#W0EMs-`z@+>qPqI z5>q5pE+c4QTAKS*v$|t_D!=5k%_e_g<8m%CKovbpme{_`^-+!)lEEC8S)vh{{E~Ah zHt2`609Ao3KB%J;&P-n_K60e}NIKLeJ_W@?wC7U=%SnEf#h|VwC%!NsCyzO#MGS4w zQuCO%(|;c*(hmjaI5=F(H?T+E;`YG2xT33pMH}$(_$z;&S+E?+?*gx!H@krWr(&gM~S9c17V+mD>ng3IE8HoiY|iu zd3#Mz1%&S8wXcv$!@^)<@(hx(yp%+MM?Akby0|f2akiOzXrr0ronrjwv1K)J^~Sen z_CI_&>O{67wAP`uQf3WzUIi<#@$#EHp%KoT(~&%MOfF=ug6KLE zCjC^_i#jIq8XC0m*kJq#?2Em{Zwu!$w}@{K{Y>l)wtPq({i73}#eMHyv8xg3riwMR zb&bo?_n+!J9wKh{qH`1Wly*s6#TTGdB_z6^;n%F#9}#wv5(p0_DV9Ucku(Wwlu2S` zK7ly1^X}ksy(P#D0cwk!mDLdcIM!&CWsX-EDiXlDfdAoo=HN~8+u4YAaW@7Sg1lJc zVT2day_lU31q=etJ1{lO*UI_kmgJI1aA)}V_#E{S;!0-5CTW3RIo=^^o<-;}@_Qq; z3u>8r5(V*qg#x4=KzHujzT6v0>RylvSqWoV3JBQF0jT-_C~9R5Igvc8p+{y+dpkRT zfn~VZ&YN*)3jC^u##p@7i`K7NrU_2{FZT_r_TOMm9$xr#^;&amv)0)YWjL z$qe)&94dbe>YCc6?&mvY&2|#V$kFOB8C7HqGoadSN*wZ8u2`|eGvb_BXPR4cC=vw_ zqqvY4vUmE)Me;+q z2MY-m2Z^++%vxkl3*p5U(S4mWQ)t zNywsljK1jBt_A7OoXH>p*WbMbfM?G?LgwdI24?d11^??Jp& z)9Yi&>w2NBpuE}gi|3}d*AHiDU3c(ZF1wTb3d{E|ey^4ri;s@4$GmHL z_(R<{o-eoaY?Xz7+|--W$dfpuq)0~8o%z$bn=&|_c6x$+)@{oz{tbj4^>p-^a7OqR zgmf_yW8{)tM!t_3V&zbc@Dlfgtz#f*#%B5^G|8sl3K(8rU;la)MFl{^9U`rOXVT&2 zB}O`*JeHLZL^Sa7i@8zm0NoG%uL)=<3!%c<{=ckkz@j#3Ju~Q^A>t;OxA|giji`%r z^dEL)>)xnRUthliydoqCCI?_(=bRggP0RNJRsk852zrF;uo2KDNY?o0FunykBdt3Go#^Fa$`ALgj`kCQZPjz9` z*3oaEjBhkML-S0^sY_)tk6GlY4LU&eOIF97Kw-51*Qeg$(B$)cYwf90xRsTgYiMBL z4zaSTC9&3P*UDkx?2M^OoS<#@Ggudj1;3|a4mqbQB{kWUPtncVvu6dx3B&G_=<7|d9-Lbd z2Gdk=h*TkQ?Dx+b&^JRuW1QL@PUnmpa!|Pm2*oEF<*!AHIY#JqqJ+`bpB@-1Xzkrd zWOawUayXo=V}6w?D+NvoU%RTVx;CgJkvyI(UDoe;S;XK3HB2;qQ!HM>B{8sJE~dyY zN={{%bTvf{I?)mNCn52WuQe1)a@}QThx19?MNrj zT47ve2$7)WdY_bGXA4sxuYb1ZCh9OiSA)jrFiIu0VU-GIVPhjFCDm_n+3$S0=q^h) zcc9~&_wMu^C4P&S*>u7K&S z|06+UDw!@aBAnDP7-b#(yymICtZ}WYXH`ZAL(?lzBw{T-DBe7{@;#?jL#`DeI$LL@ zU8$I2OFu+AVcDD|W7#7EgF;Q4SgBov_uUT$f8q$^B{t8UzLtC(K`*v~?@Wm50mKd<-|n((tV)};^I zzcuYA&;-c=FA2mGz5m%4o9=nFe_i>G5u`~MveK2<04CWDowW*5f~zc4y1L&DMGUD@ z5Gf7*KHNP}ZOeRvsWyPv$;wCVB~Uh?uyZ;CBeQM?FE1~4f`D+iA~<(=_a2tU%?tli zQ*tn@E%}gZU|;|z1`|dWD+4TqN{MDbLASR@B{DzK9wz?UT}GM|fiWIn5mp6#%P%z6 zl7i?2x7O0!4ESZR%P5$@qKJiAT31*|ZB=+96#f&Q0lPjueu_d1P9Rk=ja6I>%B-Rh zPB?Bt3`{Sa`vN77gBU+rIRaD%s10@ElUlIIIZWRTsYTrS?-IWR&_kgx=LGa9HV1YB zh_*tK9jh5|asnzaOtXY~oYZ97c`G=Im4h~m$;s-LB&f-&$_D_Y;63t9A%e(x z#KCDuh-?!SUb9b0<%bfEo~{3SzmooWWLO*Q*DM&R6f0;W+{Mbni|HU(1&Km2!WXyL z&*|;z;M?nqC>le;-S~S(+lYdm7Pfs5n>oFI@tFx^@S^aG9{0)jbqZa`!Hv|_pUqAg zo8C2XbwIT)uMvwP7=IucV&#PwQT3yUJIjX_74*tX%V^vD1+f<7D^wTclU4WI$-=F-TGGHB~ z`kU*G@yx*=Zy_hRlXZ1cY2~Acb#o3Gh`&lo$dy$zsxvTtEYrl3*w-Cn9`kh%L9j^v zxZT3Hd%p8%|1fZwY@d#W%ZlXWP@5WbS~zknFPn`$!{7H#nla;0p#N7)O1lm(rh_tZ3nWv|35h8m4ir(7N4 zR%)Iwqf~za+W(!(p0N4O!jnG*fB50Hy7^YeWqy;e;Ac|S>FmDz%h68wDaX+FzVv>w z>o{j68qRyK_wa8AJTX3**DZRr??BV0p5Tx9xTX)^wI)ZTWDpyh=3nVI|6)tsUJCj} zL_8ig3aVrbr~e(O!uU)*v0gFlNR#^&0Ry;^^WorJQ3^6ml_}!Da$z5V6Gq9tEz>B` zt;Dl(WMHMZ?8fo|CvKD&mo;HkIg%k&CP^L00oWpZc3~+L4D~gR7uY5GV$k2*<+6{| zPmItB2|+7L+Sby7NXXmzH$IO7Taz&~VHP;5AKP|upZ~pr&JHVXF#1z9KfSn6Wc+g{ zP@!h@7|X15izoI2i4x2O^JIrEX>WO^8chwbWwByN`}yUr%p6HH1u1d@W8ztm2!#a@ zG5+F=+9WXF{up-zGOv?m@EQ7=8U8GK^{@ zMN$T`ZkoV&KWXBfoMoNVK)9HKrIu&|-=fBF^QufdZ{39bPK_HJd)^9>zd5bZmZh3G47=p-o;;yUA> z$_N8=1JIZF_y+!QD}z4bOzGh;IQhR8YPNj>uA@mvFqbTAc8k7{$F%q4elhscJt1+si+`lOZ`cgK%T}WJDQ3#r-4U?IOgx5Gb5|C zT2XTVuZ&{0>&@l2)rlQHEa_7p_DVmh13R+X?${#z;$@^Y8 z`_4K1T(ZY5d20i#K@H02&Mt%ox%SU10+(NYdYAo49@Iw*ClNHSI>1v+|!A(Gr@Z+*&t^;W$^R{Fr_gx-TC;t&I7&9`+bn=xkmTjiaqSM`d(NfS|{yxpZ}7X2qz`g@ORYlX=5=P zr}E)-)&HMiQ?9o!Z`L+`|Hr;^VdXmK16;$KO2@xJDG}pa*B5UkZ-2w_SG-zS zg_%crEOX>nFJ6ib{oXWqS4ePUL$f}Vy`cO0mRUS+LmH_larH@>yW}AdJpzOKt%^A8BnYkmIFf;;Y@M?98@@1 zO0J;zm<>h&M^3Oi!ZZgLR;j}vJe>N61c&7yniW9vDLijGMf`+NaUviV76MZ&nRoBr zS&>oJ9(TCjNRWAXLEez9lGpxK3w)e{zV-;+R(vE5j*irc^0xm>MPISif4YD< z4X{vyL8;#7&s2O;7%1_T6!P&GNbf?FX8Q>WuRrrye1a&GtgddHxL)&IN4AyL9u_GZ zW$0xi%;d`2Uy}3t#<9@!OezB(bcog#$9~3%-h8WBWsmA{k>0n5MY@OxsfoTg1+)fd@KYbf6)coqJ)~Jkensm=vGG1LabR<1PTRV z7ITI(N`HXEDbx^d6Q*00YSXR(q!%#`^C^isYntthIbTfqO{q2Io6r5SWqvcrM{uhg z2L}g(`o3SkLcCFx6S$QVe1f?Y7?-{(6sbxxX{phKBs0~ej+*y=Bxw`+NkW#zN6(>7 zF@=BqN_$C2Sx3X-6PT2HfRBAum9$rwOoe49gOwv8l#1&7o*t5;2Yn!-7Vfx^BmfuB z1?__9T?lSZcR4C_>R&{2k}D;WHodCgY>)g!BHrrCAg7j*) z3>MaR$07l;Cronk$VDg8&(;apJnt3$R5^Pa%l*^nAt^i?TNKC>ER?A3;?6UDMGrPhZfCrHJKR+39`w_3-1v41Kle^H`VngW|?@%XM!xfNtp% z$l7{ra4ohxj(3w*En9BPzU~cGH(6iZ`z&a>+0<(4wjXNV4&|=3uS|PXm;Y~n-5SJZ zTbLXH%#&AzqW^?Nuh-vl{O|tz)^cJ)Mv6yadgE*DJe&IuURf`S6WIDO4&LeiPf$#Q;wcc-Ne zT$>wD)3k0MKW4e0?^;hPC?|t7et7xUV-#?ujPZ2p9r*$6ySo$`I9nDM7X!{7P!@D6 z@1Jtto<4~F<7VgRM5|a(!}-#tf4R&zJmn+S167MrBa)|GKHuB6d$dh_>?ROD70?Cx zX~L56;F67Cz_abVdG{N@<#Z$0=~nhqV$LI63J_5&iN|CGkq;OfJF8{>ko}jV{?lh} zcF@K?r`0K;!{HfxBKA`^0fe-`aJMc|tMS;A`3Bv}#C=W0Xhgm`2_)kX;IZ4S)l?Wk zK;}ooTn$js32+@ZZVq}@xoyaY`NjnIk#tuNrPO%6k?eOXg}Q8@SP)_y7OB_bP z&a8mg0M9nJQ>E^^lpO}GX5=gSi5V#bAf4_I-z%Y{>R8A(1aU4FNg_?}U zHcTO-_+maVF3C=VF?!TDgFv#ZRHea@@{AunxBh42 zX@2vGRMG$W*V`Sh$E5GRhu`E_)xXoY_J6$-^D3|1_LiN`Ar|ad;V^QjPJlFRqfGPJy`R#0R)0pjb z=EL9KB=Q%t!?7--YxJjscrwx-Qm(dlP+a7Hdsh7}(JxKU%&Y(H#74|TviaORe9d_O zbh*R!Z)wuk?n36%rl99(8OKMFi?+@;JwvLT*Os>@%lHMN-y%0;R8+cOkBB?}yj#G* zR9n!_rY0gmapP0?pG-ofj!)yteV(L-_sT@rVoaUbGS6j9%9gBwUf4}aKGJHl8%xJW zg()s7!~jifQcKYRU&;lA@GGZHH!k2{| z{OVy*eGkSnKz5F!fT9Et=0I%*-n!5vp!Jrlt%KQ+2<33o1&FmwWCJ~45*IQ6jl~)~ z#wAFJzJrG~juOK<9}Ih<-&v z(?pv0GJ2*r%pZ~()T@SUf_Ovl^M~D7WAcYtZ1U#+)!92UWPR&py9_jkA>``m z;GopMCPx1ZEYtiRJn=nnMjbWOI8^GR+QQq&J$SA47~V<|2zx=bmOxYZBo)A9X+Vr9X5q^75p^1;h?_-Pr4i>`lq zh;{1l9Hm)bnSYtx2$`$QN%Qj4Hk4Ouk|g1_pkgNs8-Hb_Ss~(CoMA9;(U#5twQof@ zD|>7D(_U3(4cww}5$0|xtDKuk-VL$5fSHa_+9tDoCJw?#YC9q zg)s#!159c;2U_I5xB6X|ws9K-POEQPpL|z%rCiI)-%Cp^Pxr(}komvFiJbch3y^HM zoX@4K7>mVx{yMULave&l|8?to*A?zql+s1n=5we==YzsxhXOw@4>=jFlr3>ItvIZ1 z>oS)mWt`^D)BS;`;6{#NNmbz-!N1#F{eQe~vy2>}}OIl1vA7wa) z)T8nM?{y3R)6MO#^Y`7oUK;tl2!z?)fPrOibVWdr43L1<#Qv-S9JAgX8{lLn=iJUI z^T}8<#vHeS6+_e^6xeluk&^05yJyKPaJ9_a+^sa)#@8TI0^3?X8+ojZGYOD6(cz#= zRWT%BNRc=8x3(a-5`Z=$j}=o|rvP8+#M}q*F0UL2l%5kPHG*TD;|f$82q$SEBL1?1 zR1G&3z(AEu_1gm52w&_HfEM!R!E;lL#kNxXbo;EkL%cD_p98o1DUUB*wP4rr&)qZd z9Pl6d@dhKKE5}TJlcD}q*wZF99Wn^}**Wj62Q%yfRZvWl8Tn2TjJddpE|)_v>EZQc z)RJk+D0&Dqy)DHY8_ODh#fB}c(2R(4DqPz*#D;$HBuT5$l2Jop(zV^4>eN(__R8t8 zhniwaF5=?0EXUpuD$V9JW)RUM2_GrKTsE;t7#WbyZv9f9l30`iS*En09j&8K7ltC3 z8E!?L+<}A9PqkEX6!(FapYTlf6LdmwHEovt8j6yKod6N_=SVREpC9x8-wUwc8&o@< zG0yjJ&pa0U>1g)0I}10+;b#M)bNrYz9dDXR1J8<7LZW)Vvy_=p!S4JxQxwi65P5LT+@95KxV4mT@D+fL~gV0XUjoN3uIK`QVt z!QN;QT9h*exQAJ(IbpsgXCSzIWna7=FI)-&jb)N_w82dbgo?Z+wzdjRfNH zM-i)036uULGL<#j(4r9`HS@}k3rj|Jee$du!6Cmd{qAJP;pFyHJ}{iIls*c(0d%Z^P3y`sfq!mpj4x zUy9>P$L0&pmy_8~`$Zdc9nY&>*GH(Xi=X^nHif@jwmH82wsd@II=N@__qq@!_uX9G z^tuo4{CC527mB3j_gdb0c9G43Oodfkd>4_^_OzOMXcJ}S#>YA5^wRp+QvEi;w(;!$ zdMB9k{OIpBnYQ`#z^i-lFXiF$aklpzZ`b+6H1*r@Vh#mW)Ilb0!9CX`>KPGqf$t05 zWY+R+4HwPN_vJ$&&sX=yj$RhA3NG0+#{_Y{n{U^#QUH53_NF8yFEC+mqM2xUKOlXA z-61Ec+y9`$qXJp`yVY`-hk^+53gs5s3_J`8OJ_nc;?3DuSYT_%@g!p*5->b^iwVfi z#t#%26NZC_5)zjNUB;fw?3Vjqa`pg7X(xAPEhw&;14kb9}Kys8~=cKg@VM=E=@87W}@J_ zBVdxoz{=WfCPfLzF(*XBkGTXpdAwp!H~qoi(-VB|bhA)F8cbs;NIDj9+(vidFKHx; z8`4Qla@;8_H4+?P2yz>;sgx~rZuz|KNSdsWQdkIFNZ)p8zA4Vzgd!ZV+$(!x4S#YO zYs5`VPE?Q%n9%ro!)QK+Lochzm*sSrdF72GU4@JW=~S!pP2~5@S~}uH#;(e+YuKQT zA`Ik(6g3eXS()*=Z{+A@g(Fi)`*0{lN=u3{^OCya+wQAQGcw}H&+U(rWl)H_^3Y0oTQFa zOvOk$M=7NqAJ6Gxj=-NGfiuu8ss57zi+u}T{gdAb1#U7;WDSix0@k25`=+Y>z87#l z?Sr&2=vnpjj4;w4KZBV46w{{o=gGW*1ae4C4Z5r_CA>Os^$hfe9c>NmnsE~qGgb)Q zS#eL)&DFn5*vy(3E!bcY$hw>Bm5LhwgbljP^HLv<<)#tOTEu?z#$|yu{IeZ;MXGQ) zp+JG0D(P;VXC54ugFl@J17#dUw=X}cuaC@&9WS7j7*HK$*W`H<7)NJ(6{Y`XCS3|Iz=qsULw&t zE=`zH4sPvm`fs14=>>bxMh;e5vIz^5+~!QisLfq?uYVt1+`Jde^*pTh{rlIW^EQ9d z*7tPU((fhvLd4%@0xj%!_1__ns9QXLVz$jrDg2emQ#$ub-Ki7g+=sBm*J+Ke+Pe)8 z|HqGx{PeU5{Ox{E1@mXgrBYJGs|I(l$mIWKk>9TD(fy73K2NsjaNdj)=52hvZwZ-e zssH_-OYSS&cf8D*&-5i1x_)D#{?wQqd!2%j2%@?E$0MKVGu6Fo=@pPg_of1t1$O@f zG!{W78xxQO`50Lp33qP+IuUTvSm_4L#BhL2G5bLM3;RNp1_Spx4J@smst`k{P%V`&!Ux7j5QDAAy z*TDfzi)*-0+8A`f!3XzDOrVWM#(xZorF+HW!B@5C=*vEAsZFgInI##5QN+KjQK$Q+ zn1ZyQ!J5LfuU@QG{_qm4TWMIi06OH#aMId6!Y|kfDn}A)7Gy@LR^WP9rq-OaLPilh z7bXLhXNTdBR3<`{e_BJYRWybj8{}B(+Db))+Phv5TP>Ln`YDMrNz|k%zV?1uA|B&&`NUY<7)do& z8O-F$nANJxi-(%s!H-AGAEmvonulyr%7cc1m2GY%IH zhZpMD`}@{<VNN~a2%~Y1Xfcx;#qu7|9x!+(#@RF(gm{y zXbQzMh#NPNq~CiZ68uty&=3rEBQRo82l(Cu6BL{G7a zB(ZqYx=J*AbtZa5Vf8u+n%dqNOGug=Q?-_yRScz}suD&-XzEdg>@T;!&N)`XUm_K! zJ6{zV@ZTgG-t<45Ja?(bJx;09jG#4T>vc5Ld3c|nc=wizT%M8(-5L7c>??F0W4zpE z78u?gVSV)YM>TvuJj>kLFfLiS{P6qVN!!UtSPtRpP3`H~?1zr$?wiL;(}~Atucns; zo7GEv9^b1c6~EK=58;~w11-3kj3Z5*&t4trt9N?j-v2hGUTue{@65j~x?;`tp(9n= ztOyc$*d>d&$n|UVJe+cG^RZZV<@)vOc9m7P^CkIHQDlgwTT$IT^fh{vK>R zm+Tr?wfY+k$%=Yr^E$w3<9Y!Xl9@f{aE4J1-n_R(!1ki%^4hZIe|qzsIN~cI#L{(@1-= z46|&uQEEobEl%jTD60OpBe?XX5n*?po?ra2e*5C!!Wf`>6?O_aq z4(d|Vc%VeYLkY@BioVoCaZ(f?b(OUh<9SH3l+}z2$6qCN9fnZUK(^uE+Dj=T!^5cjPOZCC2G6qv^=yTyg($JqM9)tw*6_JEl59w8{W!>_}+bX~Z zewg?jenS7_+bD;7wWvYWH*Hyv6IJ9$Vw2YVwuoXl{M!)0%)1eRYhHu*O6q+^+a8z? zUL?Pur3i~@6Hd-Y{Mq9`^>6F%K+?O_U+?B19zEj3u;MVbc`@jKE<+9Jy7kWzaEq19 zG51KM*`gtg8`LEx;P_{YITs(FSkb5j`J`zEpCMS$nskx*CP$owYvJz(9}0&wv6%e% zWlhb;0;CAsW&a)&+|ob9-0~I}r<|rrQua9!RCd|J^SZoLI$7xQ@_BnO)%^L;>JTNi zlt=vK_$f0w=m&|hx}IFE+s2*_K5~?hjq=rD z7-WQ0f>hXwE3q^4Pi0SnqYc~v5xB_dK1j0d&m&Fk2gwsJNtRpXz?!0}X9CN6tru&( zWV`C+1D0RA*D3kq4c24OaHq#^uJGgJnBm5+1Hapi`PRX=tbSWJ9gi^+7h&BBS>C%* zJgYaED$m`6ORPS#L2ECkLC_;pLrsph?e05LJFU*Uy)1HD z&f}ir!tO*85B$yt1vH+sK6HLIAd?v1I+|WCOtMj+$Jo9Y;2Q zM3|YYElhjy<^r#7u9^U|iJFl{uGguEqHGEe>8MYGA7b(Mj*=6CMoF(e;P77(c6Bw3 zG_2KmGFhEO9w+QpyzwY9h;?BhMEuTD=Vbw|0xrhAyX9VC1jP|;SLWZ*<9y!Wx}D9%%S~F zoyMiK#Slq_FQY~xqgFAp?e1WOlOkXb7gBZ$h_H_=HebGJqvd~N7)PL)k@t{AzQk&k z(BxH<9!Q(Amkg}ukwbTt|2Cz;0^k=i`QtP9wwfA{c8SanBR4P(J79fMJZIaKsH-9(tb-g?$9Sit0<`}-dOb3jvY*H|Ah&EZY2Pwjlh3^EW|vK*q9P(aQpJ1#P?2Nab{n_&VBpAZ$F6q&g>zo!)%*XJ0bD2 z&t=39!Hf5XK6X!OY9gz`Ptxk8&KAedgMM4om0Ak2n<(e&K-8N*o7`|Qn!9#_W$^2u zk6w$HFy|uSYyK13Uu+m}(H&+wV@)0}Op}J7b%aS0d&2Ik_=NSUb3x?tm6IC~3-qW7 zw6kAn`23z9fdmhQg)mDPRT|68S3mAh{(Wu6-+r`8Ykqs^rb2PU$-obGW_LzK8LtNPlBelg=)~5EQ^;F z8YQVyc}$YH%^SqD;+8ohWBhw2=*XFSu*AsyXGVO%>Hy88NO9=LOu-2bN^oPm(hEIQ zzx3E;#GxYN8s*~;jqup9r_ZwS%IQrJ7_ObEnevbhG|CWz>p5dQ|C#^N0BLo6INn0pexwcPf-VTuso(=k1YuQX%M>zD|P<3SCNE9 zxrJA9tnpe`4@=8zV_S?eOX z$TJkv&kIlz1$a(z>LLxZclnfgN-(r5db=NYbdL4kH&j(XMc*&qNEhHdCTaHo(i#Ij zd}3@&EPfh9Mid-7^3zbMm(_eje_{w91Ry71$u>8sbiF|zKVZ&Ff|>eRLLLA|3U$n5 zjwG4~19I)F5p5bv7+0v|x{{LNFc+UnAp9C z*nW&-C(C{>m-VIclzL9N&)XAAuJ<;>i&cFhOQTGC$DWImLYWh%&3J;Igm{){qcjCy z40oTGKIxMl-G^lY`uV1AJeQgRW5@29skCOrL$j$EIsDWv^GJAx5U3-!>8%|TlwPg< z0OO?>tHZ+9=Zw{W*P!FcX6;@?IEl52)Mh5GX#%|zG$C}^xrV|w-ZQQ7PtPzML3-_& zGCvhvChR=Y-B$y`7F+xVo3JXT;`Zkg2^4VJ;S&`{XqH=jZK^o6ew?*B;XYPbX z_zsf$uOP|lyx;>EQ`SF)puGW}XaI<%py=+%a|F*OD8<52Bo8eu^N{99YQ(^l6m$u& zyK;$U0I%J&GP(iI3f0wT9tWMH3}Vs4+_6&5grKnhP{P4QoNvCX^I{{H{uqCwdqi^#DllEJ=+v2wtW zlNGMF7RCUgz%c;e^{jV*xDG6$c9w*Ba$EDc0copKQ#g^qQ&qI*nisv~;w+ zZO+@!iwRM}&(fGAWsedhixb+TZC69yZjqb*h#IBs$S7y?)tnElmhyO_Hf>nnw4S{M zN^APqOoLKOr~P(V`)g)Wv>H@tSjY}_y0`K67ttQxHE*Mo&jAPWZ)OEbMS8n5lZa?; zEmQ?*xm0v4kwH<^!!`bOAGE!wHyNC$!}Q$QJBzn9b;J8T>HF@JzG99 zrEWnPG4(JQh^DzdjSvzmwahP|EDfWi9shd#n5Yp?jGrtYAKmL(N|USs1;$rQ{YKqe zvdN=Gp6$Xw<`1&lw;yU(etgp5CWS(fK0H7APG@M@PXv3DnUtGBN}X0dG>47Y5mPllNtik(;lK+k_{a{?dcY zcmniE)Fp7QlXdS}2$IkjIPfb^b5R3sU>&OV#q(YLC0$q`ZJdzkwj&Rq)6F2eCTO4#FX-nv^g+$mvso5>LP;f+-U zXYEQYz<}o?%3$~(0WThGXOnDTRogr5Pt6_?B1jQFO6ebvhG33DftT{u$Yyt@b;Y)G z4LL=MijISKW5eI=#F?MXNmK=9Wgkp6#C_NZnBTqYcZe3mE5hqy$iX@cbjfZrq(LBS zH<-BSc-2OV6HpJ5Wd7sBl0+aUl3!s1si*=KNy5{elFkMFX3Gt({+PxEqzCzu5;?dJ zQIsQg_8TK}i_5|L;PjM*Ly+(!xkN!bU!EWtCP&M!y%H^W}#TgwW&U$I?0n!S<)@=q!;D&dePSsSsIE?Km9zP*hlF z!JN89Fi<>R$T8uPvaOR+7r^g&L`PE6X{hK>u09tN|4@J@=8V_2NBEPGaf?^H;j4Li z5>>2%doi|&u`$_GIgQ-Ee?$$7Q}$dL`wEb^{RZv`IRMO^^ESyG<=KeBXcW3;8e4&%!@pdpEETnelo-)d0sk&ufez zN69QlNh>RC@{P+Z0SAq?h&ffE*Vu)N=o{}D)TT6=BSqauv7u81$a_TIdI!N z09pJQ=l=evcHBJ}M=3$|9Gw!0r(Arb#f#U`nPU?01lZ$SsS< zvnEedbSr#StglVH=>t=?I73v!KqC^@gVhHlzF520dz3WcPM@_nMWa5r-pubj$es31K9c>2W~f z=(aMRUw|!?ethPwqGBTUfJ&4G#hOGN6&v?WV11w-7N75Ra_-MRG3*0I(esmq@4ard zeq?Tx`Fx>cg__DDxh0kATQGL&=_ULST#yzWW-savf}mnl|DOchPofb>p|JqtSunNR zQ04O_qqwU8>}bHPrvls=sN)3Biwy6JqHXNPeuSY%m=9AB`@*}xIyjc&Q91SnR_BpC zM*t`}5=jJuH~c-)t2e(W8kfH0y*{0uTLhyoWqL%Uz{(LoG6TAq?baPY63rR)y6?I^ zvT1jPfbG#gHn2q!Me*0c`yNw6P4XL|ol#nMgS#sk1ar`WJZ4qs* z$^TQ+8ExBvp~W}?Zp?oFmj9bP%EG-9T*NQcV!2z*wYOyPnv69|Y+NMjzh+hSh_> zt1e+lm5gtTXGOcG9ZvIY87~(BWqvnpT#jCY?pW=HJ=gvXa?pm6AQ6D+v@~S{+J042 zB|>%I8bu6Is&bf=%hBajQVg;aAI;#CLB@T}G3m~WNQtOIUcKp%3yggexcv_^>3-6S zGiub1$W2qR_FQoLbKhQ)R$n4*d1Z~kFa0#SyC_-wjzTGGSdWO8nKN`DT=u&!6_^V* zI>qDyj79ZkG2GH=lXKFjs+eX$>wybCjQnJ)U8R$oQ4!+?e_$ns&Mqjg9)K59$a?6T z+nvEBaOC?iEiJ7*yFN}@H-M6T^)!^HYnmDXfz@MJLHK?u?mvfcA+Kw#{Woh`R~)bt z_NVQc7(@PAdGG;t6f;EYncbQa@&@Iz+}zxvrV_~kvDYBcCaG4dT+A+}RJ9OIOr>Xd z3EUu(!5@%1mRDD$+XLib5Ckt8bW%u3NonOAfuGfFt7&8s=Who$SKKgNdO0{wWMj3bv}NST*duZRFnh`0ATOn4ik}k;Iua*NS zRDs6SxUvR{iZ9jeF*Kr?ZC>gY*_T$p9*Pv?yYK~o$$0%Ei8yAX$sChuVK|mVdU+%h za=Nd2h!mQ_VX?AG7=!V;drEKrrV7L26ycy5k;GmGx#5}Rhy9LHRUL;S=e_6llAi7* zfNvMJnO^aGeaA{uj2ef6C6A>~VpnGJsqz(n7ef-t+^fO$V3QoV`Rj;9{|OLyx z#mpOQta>cQ5KgBE$ggQ;xkNF)$&)Mge>tC8YP8DWSSE79j-6kLm&!^d-0UX^Q_Y}K zF(N9*`tLN>nJ4!~iR-zQY1_u1GrJQc;wv&l5!yV8Qor*4r(?{2SLX0~S_LES{K0WX z^bga9eA+~N^|A}+%s8f18K3lWhLPv$RW}{tu10hrG45X^RkrmgtV3l^M%sjHatEy^ zO%2ik!c*)7sI6n(`cR-G6H7{A8bf0&-__QU`@=yy*bweH3GX=l(Wm))O7ZA^K1}~Y zQh0nqz+7P7AuWpj55QH81QSS_IfRXIQJCH+a;_C@piiINuvejE zkP{%roOB!6Z}vq1=&p-(h_4!^7lTwxO7&fwG<9?=`}qJ`;+t$!H;NA-R1lRe`aZFN z(LmMUMucjz18i;k=7V+K^%Y?Mm&X|y07N~HOtGfCY6c(&X~h;ROrm*=jZlOHb3p?q zk|+rlTw>oV^3=nM-9bhMFG=7`)vPsum(=hy%V$A+r4t)LUQU3OX+|+YdgZJ&Gi*;V z)kq6NWY?sc@sDrOH6;7Td~5{`#3J#~e;%Q_H~=m?aHt5bhN70z__dq{;P%Mre@xAi z1*6!!hcVotl65tR@GXDjw?719BM4fB)mk)35h`~g!Gh-DYIG*5`ZyHz<7aq<8!&lq zdJD-!vH65q>Kn1~Hl2#!p>#M3`hI`x-tnfbbW(nAqEUFK_5p(b*KqfiEOuLMeI=GP zT|M`Y-lT#p0uvk+7>LdfkPo#jDV-j#lm4dpPyJdzeVswWAueA;wbzTFeZZ*`PKcn% z?}ZWei~d&s5Ocz4#u_AQOj$RK=Zb(tWfEsgi@KK1PAnXv z#Men6Y|_TX1*}Itx;4)yk8Xox^JX(J&z&}7BjB}T5Ig<#5B4dZo5gnEH{YHlLjzUF zXnLDfUUrsWnh=V9zh&i#&^B~T;K7p?VLG%) zwU&irR%r)On$*Mnf{?b2?B;*Eo|o_Z6*K52y`2v___6;}o6q^zTtOriaMoX^Ha6&1 zf>;Si*5zSibMx)ruPUq1i@@1cekRN>N*P&~pQ22#2cng$;qK0e;B_FD8eI<0y;GJm zpSf`y_zBQqmSN{8$&C6D4G_>WvA@k9051Swgkdan?Ai*dc<{MvFoCLC7*yTBA0GTV z5hn6zT%iY4(m=?Mz~@a&Sq&WQ?LA@TqBo5N$!;Ee7@PoG7mTes`qu+fT4b~qn6@p0 zaV0}owP70691U$~Hy>I#f1ny;sy18;{w<7KGTd|qE0Fp=u*J^n&hQazDe)w`?k!V; zzSB_|c}9Enm^y&xnu`d)rq!*WaU~PiJj(?uh!NZ*T%a!jm*2pun9>pusVT#-e{A=> zy4;)A##4idZ;EZ%iWM;Oit|_i>#x@y|0`SsVLy=1wyj5vV7`?_xm82lAlb*b^#14e z!aX4yW&L>XY^q9&;6%gt$Mx@e>-|QPRT?8;3aR@pb%Y)6mocyG9I8!7d`bnj7OIsT zf!^N}R7b8kJZ7WcEWtC;p$pOx>u*gOQYW=7TG@&H;d&P%BKW17zCOLhY0jx*m5XUXVT6 zb}iyBg~@aBlttNB7;f?NV^yKAW5n2{S=OASQ=v)A zhj#o6TAN>KE~T!h>q0c>Bu|(3)1wJf)bNV$JU37Y4<_V3L50(OyMp;y3`&j?aC^6* zjD)ABf*t%JonXkd$|Y{w(Hw&i(63I%mxeh=OI}>#X*y`C`~+apXX(#iL}5@xPDZwR z*~CWEK?|k7rH6Ff83kZDm89=mguv5`p1wsW20`IMCa>+BTlL9EgOn(P(foze=FVw! z*gv2ew9Fq|Jv{xF*Y_RAli=DapaeBk{=Y!($*^h?mUr)F4_y9G$TJ!X@Djy{ew9Fh zcO=Ti{md0Cq^-^l$t-4sq67$lX%T=sfgQf+Dts}ukOLcmC}J?TPznZi0C=HJnKowO zMzNT`vF}G}7lA%y2|Spa{ZYHRT@HwY7#{`Ns42q0cLQ38KkrGfnPrU*Mz=W>gF&yM zTHf`JeY6%xEhvJo!0OzRtTP15vwZfaci`;o&$-*5Bc%=pgDt8L``T$Pi|lKu`jnb1>3Ite=Cn4I&Bt??iU8>?1WVFm>7r&X>|PqV z=$gYhwfenV(spr}orraa&U0u?)WaE+5+aIzwMz0f9mVfQ(hr!9N|MjCrd;O;!PVlB@VB>;bl*xRAF9RVB?l}6bfzNyy^8%_ zEsQs-&8hPV^>u*#Ma04}BgLq!Tcdj#0}Y&h42CDiUmIqv_ch9Ns-1YRI7kq_G}wG2 z?4|lqn!z3KZe^P6q7q;Psp;lxNo|xv1dbo>uBXTsB7~ex&rGsf~!JUwR+N_EG9?m52 z`7a|a!S^~#1bf0Zycr5~r+{-nF$!pIeTW|`wDP<@)bU30H(HK$=(ND&<>47*7lr9g zmNy3`6PtwE(p||U;pBbQb3|K-!cpwq!c+^A^8e}k!R2Zep%Sit`qe%qhDhv>X*W`P zj1*dfSkBI8X-rL_e;;d31Rcs7{sSjt8P{H`LC18J>vNZab_K3~IA$i76 zP?QY)2F!#lHV%QrpNas8@`nx%^GCzNNsiNpjKn=b9v9ePPySt>g=wxCC3wf{_bj+< z2lB+X;zVL25vhv6xPtl>ehISnHvoC_kw6$jUInu>yh$`MtmhsQGAAdlY-m8h3B-mT zc!T9nSg&V$4&8QrQqnhBY{EC{G}xSG==cAG(-O*|CB5!C2PI$)Q^X3xRNk^jJS z&h!b@nBP!`x#QEMzXA%I57W5?)c#PgtweD%Ir5Jq0`j0`4EhX^W@WevDi6qk)jNq) z3UhqQw0d2Fl0RXQ+nc5k+d$@r8y#fc%A!5uV!LlJ?iM=Nb4?u$v)1ifq$mDA4|_t; z4h{~$WeE^yu!lhuEHoV97Zb1dboBUw5y{LIYu!MEq>G&oK3fYPVDZ2!NQ90Q)NP*> zT_-p#O+A3G70qoF>k~B~ZzWc!z2z#x`~VB*gQ5Xp>xozMGk{QWyf$m$p`Fo%5K>t& z(sT%+etj=we@Vf?#li9Q$KSt6OFdR&;+=UtR6@*Xg?Q5LLSu>zie_2CrS`m#0V#1} z_u=Qi%(m%24a7S=Ufw1V4WM#p#WxCu^jwKfB~)`2={mTKporkowCsN}Cs3r|na>xleSDnE4Q z3AC{;3EGQlCA55_3TYaVy#WT-uew-Qkybz;aK?W;0cXorO+gZ7m#jv;c+1 z%&E>`VB}0bFto_olMH|z!SzRaXD9k7U(|EU3-mZ2QEJ2Syd=RbDe1ZKd-z_FCa|BSSRo+HJ^m%&4wqz?hAQ^u%4YKds1 z3$u+%!ks@g=zRnX1lU}VeF7Vs7DHJwr=qiAcd+6(0SW)3Wp>A?qCQc`wWNNkYLDqBR8tK-WldU5=0jNlL)vDj-dssO-eSEu+ zqRpJ!PhKZDd&6&VOZC1)(}=xVz=ZXS!{;aI3rGuSfwYH{&KF=oo5t0DOKrsN z8^x!b=Rq)4J&bOIaDrIOJ#`{YfSbq1^c8qF!mUob}35CWzwE5u7fT{0wg zKqwVo;0&5z@KPv#5}(F;58>iGv_{_$V9N6CjH8CJ!eE0ndYkk_fP^T9xrF*%3+7%8 z-+oM;DH*1fuN)DT_WQ6H22}=5M45c4ZBrBu)IX6ow#uL#td#BD-60c%8Upb{TSq{M zw$ZX+$ptuxt1fsfL6;3jF>$Z)i6|<^Hmj<6@Mzai!0VWP#*-^D;~7DuxWs;)C z->9b0#Oc5>URy&!{~Vtr{yO?xN$8*WKjz1q;$jj>Wkn9-EWtfuPN{M)$Bbc%el;0T z^GDP-F7EXSB`N7xI9>c}?UZj1q?+f)QnE-2+Q%&B>?A;SCFC*{B#PUT-`Jg=z-xw=80?he{%;YRv#1o_}t6o~yw7juGF-X;bw>s-069dqp!4JB>DCBtiy zx+XmIhS!MoOsWNQp1@NPS}NM!WkTaB(67ona(Gt&@0}`v1B%Lpyw~%L)-#^%n5fjT zTLx7-ud?6eON1Nh7>6*2FEJ`~qxe9~rpvI)Z@FBF}7y8BRIL>LHssS^`7*K?ziIJKp=R}~f*h4^F$N<;pZaqCF#E>eS zhgWQ!4DArF$)C)9yCgWFCaa>q7=TrLHCxp`bR~I$R?$g6%I6u;&)1_ZaqLssXr|v+ z(W+k^8U84fM@X%FXo>Uw{SooQJX~oBkMGXQBi5Ufr)$64p8^Md=9c;=PaC~2OLoWY zhwnu0|9LU7u8uBF&8|Hya*t!9;SwTo^b?8 zRNx0J=bwB#myQA-6%q@lEYZUx7`I18M!*{P{QMledTF2Wm_TwHvNxD$M1BJltm-k` zJ+>6&Tr1$uP}5dIU@R?7tSN)aY4LaMaA434`%6qAXaKSBLJe=_`K9ircq--NcJjJg zXt;oi-LGG%rHXQ;5gPIkcqHbaFLWqu8q~c^UGT0Rm9?Y#KL%V=iCa_jir4FhYg&;_WCy9!uCpvn9<=ff#jdUMhiQi%PNe=Oi91GEudDI() z-}2j_V<)NUd^)l_d0X{STN{jPKj^z?E|MVIRnqX)#v|RayVI z!E0@sK+(6f1(v|=tA}k!W4?zEGSyOY=pp;5ks;@FhF`{4D?y}}=U_Pzez%S@`&p0s zlP+?zV!8}!(LaK{`l300G!%;gkuM|gJ+TE0u~c1bVqU!8Tbb{d6>UF_S|of<2)I+T zXk{cu+i215y3ESue>tvbC_;V?r*-TpU!eU4skd|ZT8>cWkThqYrEy;PZSM9=?0yF8#rq%oM&inFTHk*8*6p&>i)lyA{ z^~TTDtxq5 z%*rer%{U_N`*`R~V-V$bf=gJ^wcQD`$!uN50?KySn!}ICO8LQo$1x4G+-R4QhMVtz2$KIRg z1&n_B;;TVw8QW{*;ki;3-$UHor+w=Q)k$9G6(@r`_$HBppBD>mPXoxE!W2~BsvT~B z?zH`#Wo@;htZv2f-5h_pU+Zx7kgRoF57j$y?^PfwD)ib@CvV&Fu)E8VYKYUy^;M{B z^gLbn5l?Gq_~gPLmiyQ%4uRHSTVMQge>g|NA?0nBl}w%E4!5)|753AVWy(>aypw*j zhWroM_>SxBFo4{J1DfB)bo?$zuYdh;aHr9ry2XJ(4i(!d{!psH%MBq94J}+c+ALkP zXPL^2tla7pz;7@Y(~dllTw#B4M%$u=4nL>n`|1gQ;K& zl61PizrVR@QZfx_Uun&{_V$=5y&<)xyY_43(M77!!TWegIN#o7Z5kjE*YOf|4Fab)f8XH*s>4!<2p0D=GnFas)L1JoAy zvyf}5SW^=0=zS!y$%Csd)<)e*t#X&s_3pP-ZH^uuEznZ?OCE&}MJ~#b43YOwzDsQl>gR7h`Qw{(BQqO*rMa*lP84QF&*_RIWD z^5FR8xYPlQmf5^LWVf>sVWrl33a>-wPc5hT3Vy;-Hzk!Phn1!_ctqoo?MuWvpF7k@ z+T12nOItzKp*AOodZNMXCS5Ewu4u~HO#t#7{Hld4;wJBg0c=$H7w#vk2pR`2ixH_v zbZr$Lu4cR`=-Ybvu4y#tSD)JIIF&@PRsKx^^X>5lx7HPl-Z9{IEQe2K6XDhbwTD(v zjn!+FcN?L?mPe0H-S#X7Q7~xE-g^%6m23QDHzo)+&c_bbMdpo$W^mzXDE@keMrSB- z+-{}mBx%FpG?2^lt9_ECU(lot*@Hv%Wh|U@^!#Nk|Fb9Fp-N#9IomS0kcx(Fn$t*V z)^Dfl-Z`sGVaJ6yyCWtYwaqtlB;zw2}WPUt2o)sF1fT*MZ%w)+7n6@&p}fA!;5Ra_gT|CZI2$K zp7xR9mPcPZpEe3!?lI`gR0wkkz8Gqs+~^&@pbd52_<#{Q83|6vSP`Po@<*Rt??Qxx zy%WsvzmGNL`%?p3ZXNUI&40>0VJil+6&@j^ zs|Z2#qALKN4d;{EAh1n{H*YsUPL6d}gy`o9&glZrKA|nb3DI*LX3T}}X}M{@p6G3$ zFv4Dbvi$aPixU`MbB;OX0{eGh)|w_HWi|oe&_}3fDBxPEJ9h~v?!K!sfDxhnM*M$k z7#f5cJlN9Qyl#pPWEo6(JsTfjMJapXK%yFR`S1j?z*koEMO_(O{TwCgeF~3}U1_Qebd7|94NG9F=751776gC{ z8YDKr%=Gw4$n6bDtIb$7ZSe-;V#aFcV-Gmc(5|*x5|$|4p$IE1utM`+H*Wqy|u zBF}SH;JT8H4v9$JGs;>h3P5m(jSHc3+JW?8CP^jiq_DT$|T?3l6#!BjY`Qm%B zGl!Jod~xgc(uLK&FNvu4Fxk3x|N2}1(o0jW-vYGOb3*2Mm$k$B$5FCtzr<$g=XEO<$bYm|94aqrAq1$$m$FFO%wdH=-Cu`4dGO>KOe_y43 zARRvN{k!A4X_o$RG!wh_|5*S*d1qNF!DoFQJhJAO8J~lyj?L3&vye$|PA zvVIQyhG0b(twqqR89H)z=ix7ICf*Gty(>=34xvHetXf~e!A48<{8RIvSH%&?6awBZ zl6${@|L*AttkN{UejEACfeWylmZX=S?a-g0Q4w60(ApfoOBly8VUY0 z%=l6LfpfaU0EE}5VwWz=aAE!MvBxvO@Q;=|-CA8dEsxruYZ2d7KW@HjXNXV;Uy|c^ zze6H__t(=1(RHaglbRcYaj@v+Vw+v9<76vWml>d)UTT4n9rwTN-b|7ggQz4cTV;)+ zkDtn^nqm5ng)Ir07r(X7jsE6NB1Kmu74b!H`q!M5K=!Z0@jJd!N^zTBQ7eqoY#OB0 zpLOE|gT9QV^%E$kBVGG3(m}Yff4*S5IhShmypxtxjq2~U{h67JDb5!zd#tjI`z%-xW1!>a@wZLZA^+u41Tk zi|W1d!z?k?Zg?MSi}@KM?u^da1aqMsLKs>{A7nZfBlI*06$IseT(R_cf2$-niKm6O zluqd`n*NcHD-Fg=r%pd>#CvD>l4D+&Q?6S#X_BanEp54?;e*NEmh_6rspIL1HH){X z7zILA!Z2pp}A6H_;iDg##;+n&Sc%4+y{IV5sbmRvc}ag*)m`BK(#FVJ!E7k0Yc z`Tq0#pN%5U9arg%5tn&GwMF5ldGgx{Hz8ryc4XnleAXY*VamcgeDqqcU%wsc?MWqD zq0;^7TQnpv-F$6n{MeOE{`mV?(!y@Z?DBM*1?r%;!xuhgDI`;p45;|y^_{cc5zJc|$ zgSF~4PSSFAe|Nm6(s=`ab9}g$@y77y%LeRJ{)yK@1X80;GLfc`(;p>Z3Y638m@p*# zhuiLj1KvnSH6tk`f%50ASq zC%12&<5sU@{c76U6eX2q#=YxOM}k(xC6|-vYEKkaRUK67VcJJrD;nH}x#Ga-=!Yo?~95IW*NM8rt_ z{l~}0?t;R=SIM5YkA`7p)#%2UWns^m!V`%YqYJeXjT^;VkZg`k3ikbwR{%8(4w?em zX_>T8Uc*3awI=P~e|ftw-g=dmW`J(7C zcxKajo)N_ZT;SDo?M#u5rYFCdfnbstY|6v#nSPsr`-A+k^Dp^Wnb_@9hF8C1@DPe@HhrD4ZQ96F)nAjITcx~#O+5}INkl2;8WsYdp_@cJ6 zaMP<`5viXgRkTLwtc~6JJ!OVAN0wZDpUp|=zrtsYg}HC2Mz)g*K~kr3bwfg`RhjV= zr2ayZYHq zTnnve)MRkTH#Vlwp!{$R##(0&ME(GPrvg!VKBBn1FQfHWOvLnBx^GRtnBc+}NU`== zI#Q9)I+!FL^3$*ji6zMACZF$fBsZ%5)|f{rOA(jPZlr)3QXs;nLp#!WHcg%0QIGti z;KUt@APc3vI&7X`dgZI^xH#X}A|=R69Uaz>AY&O-*7->p7> z6*;TDyNVNW+=trL)^1gKUWl}^be!nhdA&#&J|2dA@a<$z`Of7xTW9Ch{oX16#;iK1 zk}RQYB9%t%=fYK{;miG;!0OX~5bU~KChQfm@P(>mRMS&=uFsw03);)}mrlR?94{8% zwWA4PvgMccUMySmK=nBE?~hrZNKqNvHZ?`=M80x5>^!?Yk06g%{J1`Jk(4}-eDg9* z?kSxxbfx0+uS58K=fjv?$5Gd5huc#tme73&=hLUELot6$w=l`t4%GxnNsEUlx91I^ zqafC&d_PAF;cCwtyQjg4SRSn=X~{8S6*AuX^8&lY=dQ35zK6Tk)r-4UU3$ZZEfM#F zd{sQXO1SI;yK9X1*K$`S6FuU+cA^pH2*U{Rwt`vm#H3hT8n%?UpAdYUDm;~+zSY+& zFAm8@Sd(M*I7cQWSA155fy)dbw|^SloKr{Ft(vE73*ALrgMXVA^@bIWxzIYn8TnO1<qTi8=wr!* zMn-%Sq(TGxgEzf-i7;e(X(9;YkaUrC-}F>tho*(}$+6<~nAD`v;KIHda<5FbdrWNk z&X+@9H;_ojUdo5)5lbulAe_0!IhwJvRy+OV`SLzaJ-#vWE6r6MZmF`w+jmJxIv9r% z*BS%xN%2wD?4dF$U$_hTzOH|FD*pF*H{#`9New1h}E0+N!_-Q9TJ@2qp?7Yi2r80LMR zJNCYIgUf2w+Wksx=hfdIU5WmcEsL}o=(b-pvI1SBb4p0 zCN$=dX9Fi;=uybqnrM)YMduKc6iw6*nV*5XRsa@TY=|T;GmD^kyOOe&Fs=>~XH8 z<7qG8MlNBM$J)&Tuc+LujQTfe0y_r(Wg|X+hQ!-RGnZ>@C}WOmSg@oLAAqL;RwU8f zi0tA@79mCK7-_uk3%a|*qAKT@F(yo15EOe9N~cdeB)rT|@vaf`3W?YZ#S_TbCjjI< z@W@dk;ePHeMv(xN)Ew8*cXS+r^a_Qbp+HW(2vxy7Ao!ybzKF;KVWFgs9W!f!pA-%XdOO9Yl@L#>MIdMnAYgLO&c39 z!-0r7Sr>w3)q~oipwWQPl(F)<1gR1lBduchZWX-<#+6XY15Z!JJZ{_R%AY24*rxl6 zS7Eu*g!$$l+utFGU5uCwxdkq0pus%iKy&IX&xp@29#k6cLRGv^Wk!d2|7hF6IePuq zP_o+lOa)egyrey}BBt`LoE}RR+pWIqYeZ-iW6WT&x*$a^6b6xli-$GgJW9y#{v7aE$CC>U z2E*BGb#HYUvQ??0QTEOkxnt2D5Fd8qqp=+@#&85`FydFveayLbYISNc`?G*dl!9z? z-ra`#jedoBq!NaMY)Z(^^6<OlGp14?uz1T}IKW*64jG#A~N%ww*HAaI}yNNLC6B<)VDeMxTLWDQv&%$gj zv-`(}zbO`~b$RF%ud<0gI}e}!U5Wkk71I{;Q2xyJZT04KO|S(we~})|6}!pCw?<0q zYkD&yh3|vv%jgxwzux@kzq!WuN7#Y8ZGZg#q4CP6lFAg7EXP3z{89r~@48Mi%l}^O zG&QBog)>i`4sI=vV4@(~5eZ7Cg;(P5R2e%-ZB&)N9-0S|Yu-Fe{wNaPnhAXD@ts(< zbNrVC&|3XBMJNMvqU7Ji3}Zbd6&F#dSL-6FA8gyLc^$ckOG7^^z7@a^8J4Y=OFwLufsT|v?z8{X+l1yQfbkN`0r-G9yt{6uWENzR8!cIJmfzM zvzm(31ul{V02+V)zL?dDpsTg6t`3N);v&wdUOVH<2ByFbKx_#;strICY%!=o_}099 zVo)=Gb_ZnOY48Tur9gX*iF|%5HHo+O8byM)*L7RT;3^_Gt$?27Vu(^Ml}QK17NvwL zCy^AXXJrM_p&UY`2UyQ!QRv{U_#|AU?6C4gZYH|_@@jm7NuBxvg=%#xp^#Qr4+KirYE6 zsdtbZ1)0T}F5$iLoU1CUieJz@zoiT_9#UI}Cf?tGe=FSmF!Pbll#pS7bix4LNQ)zR z>`i#X=76WMsjQ}gE%l=WjV&&B<0*QOi|@FJ$R66}(QZAOYEU8Z8W;yx*SS4ur(flC zpOa%I=jGe^ukQ>W!+4T3BpM1CWD^aJsCKeb_<@nANSIb7XLz5y(>$5!&-tYx3SW#@ z^$h!-HuOI5I|0X$aGRjy3PHYnPkww3g(R^{H7OK4myJ>=Q%F8bw5OiW_vpFv3g|n^11v zKnhhLZD~;{K~^c(IE!X%hRb={Gy^wWOaf6tPeOw~Q`zOJk;Z+xNe31`HyW?;otXlp z@)k064e+@&$8LH0NlL2vb6=7&;31*I=jcw<`OwaIi4{pR^6kS?WZ=<<@l)Dz zIW50kSFEE|-?f+1$>^Pj0+Ay7B3=06JIO8L0G3t8z}>Zgifo{ewNVsc?1C;ss^q$}tauIq zFH(W$i-?~B;Ggkjb{=&*pZ9go1fSa09!oV9Blor^c2g*l_n!gWhgiToD}@cgW(_)- z^x?X;Yu0A-Oged*uFl6N`Im$5Iimi{kB=i#k*Bmpb93+8SJS#abx0A%;Bt%ljX#V1 z3;%;V<<3XJK=b@iX$?{MwV)=wb}enI@}j{^n3if##SbdtH?y;jsI!^kdNi%!%`^OM zVpFsD7sHC3XC~ zLDV19W~{&Df9VT?0bn!O0beE~;rPZUC@)t9_Q;JZ#a`*%+Zy;Pvxy*=k=PJ)<}aLk3JrI0oBGI>*^=o6Gee!%c&W&&W_ zHl*uXscAr;I5N>#+#vM;E?W53vE>O6&8+xcjiX>w9N#@T*_euWB=`4i05J~m7et@K z4Vsti0hoY6A-G|TvOBt&4FhpEn&b$TTDF)|_CqLD(7vTXF--~nydZT0)^0WBL(`_8 zs)5K*@l#5%fI%+i@C$ZbNBziqbol>6)YWlZGl)5BP6 zY0xEgtmvz$2>$@zrQcHxtb0N%u3!Ks! zg{Tp{x<8F5-Ip^@M4C~Gfg$YgZMEM&FXBG=0pTJEl0*sgP(Hk=@HsiE`QG|XV^%AUInRlK4ly*FCUh`i5af&@!E$-R(8QUS=;;KFU=SKX|n4>G} zAQ5H98D~*%FD857>Srva@ASf6SMLUVPoI{E*kfx21>cI;`VWbDUzGoS-Aj*-vbYio z*k@P@blY1kpQx!E)Mob^Cvy~nfN==of9}6QzYB12-H~DE{~FCG?D2Huxca;`>3`Cg z|4JGyxiwt>poU-j`uayKa7*gW@c!`+@0Z<(?;bPR0f+Gke)}oLf}XoaB}Z}z23rU{peWwctehm<)oR=azEO!QVlQ?&=NXB1|`g5!MF(l7|v$LxLR~Zl2iyJbS6}| zE)K#rKmu7G2VicO00V1z6QFqT_ZPwVFU(Q+~B92(%vow4A9NaQk0L!oc@d#~_6ez?4$t0~GVS-1`J|!!AIslJllC z5;7@2u?7UG8iC^E_!usyr{j%G2=?#bdw3T0?Sj739AF&jRB|E02q2*(!JJ9nz%Zg; znBcRFP9LBz@)`qC1DO<4XLo09dwD=4uGgTc92M*nZ#GckfYU=KBJ~h-l7Z2JI{rJ- zxMH~kNezHot|+}Q1GGE5%8>!&WYHdh02SW5tT{rFoGk(vcmPt@qgcSFiHnqhruk3C`TiAjk;$hVX zS7&*FB*lpl=kLLJTdNP)onT1n$7E;_Rt_~BCwhcAgI4KqV!OOLfdZ>xj=(F$P#CA6 zLTl4P=xTd2J*U-X4u#wnqe7(67Rh4hwMOQx-aTvG+UJR!F3Z8qJ_+1bHkQd`Lx+Oq zoYCBo-?-S>Dw_+MuSQZ!c!a$LV6&#lmT{|=I1G9NbIf&(kL$FWjFFjN0G+I4;ctLd zxDUu^oswnxCE5&S??cHGM4J&|+e;Knvbk<(f*!=$FUy4|C%HM)doxQ-Gd+3VV|<$; zn%?;|^l#i#tfvLP)^Ey{?C#|zUG(MmiI~Tg;@V?2`_1=<-wvN%#+MsJstsR~DSeL= zttwumYVQZut|8UhN12|_*W72r{*~@yM}fCr{`dwuZ_o2}?#%P4gl1M50fC{{mzh2# zt(UpAFC%Au4grnjeD7ZNlZZMm%8fJnEMIEOVR)qc3 zA3z@yEF8v7qNWZa%Ua;Qbs20#y*yH~ z%PyNikx*kxAKJPAV!Im`kvy^LxuluASo4IvFAF0n+Wj85pi}=n5~htFZ|FCJGJ=A} ztx_1+fxEk87z23rFUl+`9P9OtJ$}^bBDw)`Y)nj_anG$q_0!ju>RdJK^wxL2qr7&&`B@V#0jYTP%gXWS#%m7NZ zw8M-5A=U)nG|v}IYNH{APx3rD;+hiIjiB3Xa$uNNi)Q*XrF0WHPBdEF!06jsQ}R+e zk5Rd-(BUYJw)dqz4YMn|?fJ$ybO|)!_M+rtZ6p7YzNIR~PFK&0ux%^W9N>DU<8ttU z3~fz$2?Hkzr^(~B>}bx~ZFSVVamA;}^bd3Ua3GqLR-nWDfCA5F;n?Db7Cm+fJ|&V;ibZt5)DQy1EL z_GK?ifnR3g3rlNr3bgHFkW45yex8)P4Tv2E)WOFK^^<yFD$ScMbvtU%$^K#&-SzR~@buCOd7G}O zFu`&^<#mqHZPXw484A|CkO8Jb;r$#PpGIC4U)VWz+`T0DT_~NES2XZP!Pa>k0x=C6o2g%d&SeS;#`-#f)cT1UHpN|>8 zUXJsvVI)RgNSm+^51F2UXb7cmR#sMkG|Vo^?t(^ip-z%m(Y!V)H^4shO4NM^FqJq& zkeXu=<#^8=jO}ZA-S4-wCC>k^1^CrXgi97A0sD0mLNY+@&};w<#s|!t?d*=~hbVyJR|*quB?!UF z-=BO3Zs#~mBU1kkk`TwqMsqq&E1A>^ z*E1;HnJ8Q7mN(}sM+^{$sxj>fw#QiSYu9}K^gnN*l45??}Gtr+ve}IVb#I`Xsm%Q8fEiZ5H z#p+xcU(;<6cBaqIfb(^Ucw#(B!*(}Yfc-mj(6LES+v;_(IX|yM9IU{G~8-s4z1`DG_(k;5l zjlK9!;}EJo+{Sj2V=9uk+E#GiaYZ*NrP6bD(hR7Q!b}A<U> zGK18unSD1kl7~f)v438UmyOcRF|j*0*PeG-Iwi{L1Fp#aUS3(fil5jH3w$1p6T6?! zUrSXS_m6uN)xhpEs$DCoI=mXnJB|Q1{5g_Zd`_Ku2tgoM0~_pBH%dU{qLF=&SrPw} zNpSK<4WU?Zk_1vsf>s>r_4*fRHsuR-0K|~w^SBL&N-eSTIzn#RE9Mm&ji*>YIr@7<%VpZ?CrY| za0d`45FTF@Du4tqC=Bp#udjEux1+6!edHznBhHQ_2uX!Pdh{g#8|aT!p#Ka3RT|Y^ zg^44BfeY3KK*c=yx2lFrpm1Eanw$uEbt8zO`{a~>V3``Tg9ft#_NdrH)`lgbQt@{z zunmkh1{>F@SQ&Fiuhb)LrK`IA@gZ$WX} zzGxief9k%Vne^RRZ0nz2@Q?aYyx`OJWFN2)y4*`CaPF+VrE^_o8n@Aepsqkepd?v=MNWFOouAhkm&`neZc=wT8O#RLK%Ai}s2C}k z@`qo7YXchcjIR&u+`IbSXTRBfMzbB=(!I?489jf|faaRm6I)Fy@p;q2u`UnIaRE@qTmVvMpzdJFFpqJo@>sV^Yf zN9+l-KNh^H3|@CZ=qQ@;ZK~_;dyucr=ckEg#m|gs3PD{qI9klW3N?_Xo9&1-vX5HW z!Gt_iTrDI1KP}Y@e7)$(io|NYJaRWFBVmuyg3J91ODQlAso#NU#;_rs<3M*|$w0@} zEfD!B6oJCQf7o0+DnuyK%ReB1qQo8GUA8O(%fyj}R{o8u6zB-BsYyKr?w3~FI*)6f zx~{}dxNBnb?=3B+vmlz5wKGrORmbvB)DQeS_-NrSBsWIXAcQ^E1tY7|#(nQGcK1?f zY88Oj+_EVOnl^x?kx)xHj6w}#I3U>hk2P-C1lvaEjR7C=@O~axdB&UN;C$J(x5zmw zqbdQbh-;i##h~yt*73dh*o83=VQ?VML`Q%w375qkE4o`aHzI5Gp2ztO^(3pgkNGn{ z*^alBV)U9Kc04D2{7jmxI=}*(7?|#h_uKblHq{8TDGe1zk;wRBI{dAW={!vF4cn8R zIer50@sz*TLKr{^baXrgLco{^0rcVLRuXmlgduYb4O(pzN5^kn-YRe41sKputr{QN z|NO)%-t($7fs%^|CgPv@u02sr{&3o$W(rSk&|}m)DoNgER7qxxfkkOmn3X2uFZUZ{ z6Ps77YY3UgHAAD61m)49J6%;kmW?D9I`WFtsj0o7;R{y-`W#Aya`f4L)!`pHnQgf~~|!^k1Lq?KvF#$RG>+J=W}LHwgXpe05^ z8i9rdd3q&7Gs=+y-q`(UYC3MzxX2aNj7J6 zSbCiyFD8S$pll1Ohj-PgalQzKd)P&sJ*wQe3lQ1-wBH;8nAORTDN*(@JYyvnCl4Cx zoh_yiw{8n=D|y5k1oHc^uld!ff4D6QuUQG!itWS-$x6>8GUF0QS--14xPRtEX2vJ{ z3HKqH!6QEa8k{_-5*fs&V8vQYFI6Re7%y)@IA@50CHJ4`8EC_{oRf+3fx(hrKbFqsxK7A4BR8$?FG=uv04)L#sM~EwU;)qOK73ML z-wQ-du~am%g_)ZDa^fe&h*aU1C@FDEjc*HKr7GfADeC!6l+H~A=$xZ7ap~w#O_Qb3 zlDsrN84o9^kBNVkR0v1?um{06&GU?Tb2Hu&tQEt4uixS_TKJ&k@#P0m*@OKWn*S#E zx76JPSgQJ4>-u0x98E^Sg5tU2<`UWu zBbE|y7O*!RXd2S`8zA~)!=_ds^HZCOf8e6=ZF(S&d~P)->d5unPL7%aG8@o{Qps)c z%c?PY3vAT&A!epFyG2KtxOO)F_re=;E}qgeG8)|80bss1Je4|C#PTu;uYiIITl9V% zC|sO3kxG_<`^`SMp{dCt7XCfZ(1F#^kcqNldQ9r->wBDKsGNhB;H{~_L%u{X5idG( zN8DDy=tx}pDV*Qn@@!O6pg6mBl76fXx+ z_S}*8z^LxkW4b%uxHfHF5OXR4mnd<-8*OZEcYEOgq8)gI*bEyKx=DM!?<8H}ca#`~ zoRyyuP#4HIl+{ipFG9FMOSrxMsfl~)FAG3fb zt(uO3{w_C+Q$XOmOOl2GO1UyFsDVIwV*D4+XMI>&c7LlvAVS!uR*?^dVPS>nB|524 zXOHC=Ly<`VIML=aymP$g8vOE%iH3tfF^w*uv+v6E{Kxlj1f1FpUC(!{XWo;(c?dV3 z!SU7gs3ej_Xi2jMrVT0e{93yvdYpxzVf5oxAoc45lB6rYx{a-^t+#h3w=&y@_L5Xm ztVrOJlK=zZU`8EYI9uh|V$U4MIQnH6%DlVp06u7iR{QOeooc>l-09o>hat+q4vh*R zlb2B>s1(Tk6F{$6wBMvd`;@6tK4Z_zX@nYvc}eVrMTc^|C>{flW)|&%z-r*g2O@TX zq3wD~s=yF;!SyO)#%h@7d*J7DACGUxvHYE!9h(h?<0RK0e_2`SfioAD46q`V8sgI7 zfmIL@4{Noh!fnPAa~Lm{10 z>r!4uCh_e@Y%MNf$snz7{3^-((M1_4T;7RnX9$_WiF~_1zVa zCGR{^ukcjEX%%(UzSL)FcnUnVJ^xcdST5C)j1UBcQZaC!o74L@*3(&}dMIBsI^xLPd@HV5kd`cI6dxp}fo+G? zX|hE^Q`Iy;M;2HLfTC*Wb9)n-ELvq9dBcoW`I>9MDgWt8hAFz=-1@BzhK)90C#-I!(%(pl5@o;QOSG0}lDOE^4#QA6 zzbHr*myvpgn`qTz4Jqrbvb40^0eB#QG7vB0iE3!AFh={;drf10v&riHZ|^6X)JU>X@b4SRLY?8g45m!W2SsNWImW6URyh z&6}ZwhiC6T z#2CnoZ>cy@I#rXAKGJxZ_3DvF0p|AOup}4>SjNsA6xG09^bdQ`#rJC(JiT(p#bD>pN+n=7B;6@HC9b$y z^7jR^zoyo(Kfg=HM|u^yLK>Z}3xP93y#>fz77&?xlso=W#F3>3C1vXHSp}gzpoieB zM!>`{G*fRyV?vLc|HgW2j`xMR56amrlifePIQl$Y(V7wV_U#Al_z-C4<6)Khk)*)w z!(<=@DK`yi!caONZ#Ab{nf_4|{(wewlp7cy{Y`0;Ympl37a;DoRFdfroH2QLGN4g0 zrESv(4q4{h9Ed)x`H`Y0Q=Lx=cJH&Jc*RQm&W31}D+x7g>| z7Xg&O(;4gQa3xe*{5fGx)YJ(Y_E&;76J)MXy^a+^osK=D;H8;i?a z`loL6iQg;TDwAE#z)4DpYNI{HA4;7O^#l8wKJ9TR$y-oZb|t4()scTmXV)?N+NmNj zp*+~A@PK7r9~W2N8Bnr(*#i($Kr=EWM>(KHw<$&)nwOtH1lk3#DQf(p$b}w2H1ZNq z>H#^4lCI)&z=sx4#{g~|auJ_v;CDn^wn4Hz1yvMSkr@L>?Q;fwRbKAy1pC|=eTXPn zz+6zTLYxc!k%Ts5y_}O|P(3T-^8hU|7*gprECW|oFN=?B_9tP87e_AKp+f0;l^P?VVnzkqCc6Hj*e^nlJ1HDc1{ULB6a-c; z31TX=!8&K^!t1SPZ#?T=Tu92HT*>R&%vPFwJ*{S&S3Gs|HYZ6=&KakAfVxh3=1&CR zymLj9YD}c$-!8eOnyHJf54j-Rvq9tRD+La$GM7KD7nd5KQVXz2rzW?OwW9l96}Azt z6YmxUnol0?4Uw!K!x}O(5*xDwj37kvIw6yf?06E`Vo8firHa$D83oO~HzV zP8Qk=3f!B%eCrL9!yv=3&gbRd`e{@z-{{Z zGX)ym_+5{cxfICsOwKT~T{*j%eiBs4saIj53nSq2z`{xwPR)VJjuMMN?HnKsPL>-F z@MX)~-IW@F9wwTZ9+@t$k^7&1x#i^4>nM5JKHK?jiqTqlhzP~1ac`;Mea`-w9Qszj z0erYl*MCX**!(@f!~z%*jgd|O((2o{Z<3gwVuKIeJUxlNVhI5QK+|53E{Xjlfv%zR z!E`B5CAT6;#$iHdk8a>@)IP0GF8F_AIe%IBvEc*~K&iz+Op+Ht!U*Rf#DM(vh79GZ zlpEFJsRP45L&GqJT>!JY4xjJ}hkv{NoH&ZKgJE;2Qr@SGXjNM%2Jn=eBw6v%>_fb- z_ox1oW1ZkYFlSMLA#f%=nfmD$%Bza_HJ87CvtmSv{NcQ_EOsl|sV#HpmRWY2AgJ(g`Bmp!y zsYs_4UCa~@o6kwgXmN=pQBe`miaAxb>gd}&AszMAzJvZhvxO-ZbNQXL9#iDyr;0u> zr zQF9hr$OS($e$3zkV~o?~us{kiOLgNsj4rH4t7$Z(91ffUeMbySMl#jZQ216sEXU=M zt|7<}hjSc9TXw{N5uGgG(;gTag^{ds8qZ@g>fL}Ru?@I_kl8Fnn}g^vvuCqxBf3=o zX`B;|{&Z>^F6Hv}w43mBFZyaN@PmEe;w5o7shKT1j9$Vbmmq-jTSivm#CV6xznDEf zei-GGeuA(r&{3C?=|$h0U$+S zkPS#P?C`}^ZA{?6!N8Hfxx2f2u{8v2LV_K`!GOMMH`M7JJW2wpqDQoZ39~rj^*&(t z1|bZ0CXvKj(+$BnM`^SfM!3^jP#hC;1GOeGMz^-7AbAimhGS6`T*v1Vm~w6@65g*i zX0LJ`=CqTO6F_c3__x3YJ{kEi9G@W45fEPaKvk@O4HzH-6N+-u>_7$V%o_PZHHGMs zQz4u1wQ-CwYPfJo=9Chp3^0ICm{=Tk6<*u>g*F`@--|c`SWqie0Dt(u7>nKC0d2ck zcAbxNwPuz4F=i0iQnxn4URK+Btq^P8Tbxevpo7edJASFXFep)7m7b8@yg&ysl;(#~ z8S>;d*JNvxX|7;!E6s-~&^A6fpCcsYxUhoVL_bRP z7vg{-?lx!#@6?RqvqcU1AA#56z1y;!}ryqiZ-R~u>W9)UIG)}&Ph~2@!^LU`JOa` z>|Eyt{d+d))VGU2L4IC}*Aomk;99=jMf9%wDm$3>DI?E$wO?lbrRC&8C)Gokt!s?il30)a=D&h>N~tik z!9cR1xl)&|WV0|SmS#r=aq_5uwX$G?eND3ha-o%-x5dP!blnGS@P74Ky69Dp96ybD z5}6fwn{685r0ILPUQ|gXc;g>t>`yX#;HETLE`2*c8Q;Grk$%SM_#u1O44QwC1!Q{D z%an@W@BQeo_MFs$9p{W!8`!FjlX)9)#zSOVYuxQwq3*PB1$Q}MSo;>MHjgc|WrBzT08RE&K`u9}(LX+p|Y*xfb5l1WDl$*Pno$o*6 z#4qeIJ~i7b&CE1c!`?n;86(A%hOdDJpoK2%x^B;cIO!W7jIVK@FGLE)uaQj6xA^3PuXn5mX#8#ZH(4zz7LLFv$Dt3EGCQr6Hsdxgr`EK&BhsBLp&$qiogCjbNBsFKoWTJH--2wj%e_9 zS#w&RaqsMpp&s6B@^I&%oblaV$PXJurd;rnw<8=!>Na1T26Oz3O(h3L94vOqv>;bA zOaUfXTB018kAb+aYD)b;1ce3KBFJ@$Jj$E*ZgAXw=lo_;K22hXWLw60Z+(T2R>U9bZpmC2(H z2nR_JsLyTs1Gkj1i!nxHaR_{C_*+nz0}+ro$ZYenQM2FL`fc-&ec3kVIGDOZRN(d` z3)$vFtYsxc@XqnT=8AUUbv3Qe&OeB35RJO-&2ZOrZGm}9iDI@`As<4_S4PXSO zQw4y;PYhs|Ig%2RDB@AgZY1(P+n?`|n+51epz+t5g=pkx$A1YEq#qWGp zH=H;q;$p%j8y6Yz(VTNI07^(bu?)^N2h1J`)voy0&AXZ)r1NIwtq+awjZ*NuoEr9N zL@X!hVYm$S41`&RE%7l0q3Dl3E{Mz!U96Z-jKKF49 zf0e|oyG1VZBGkEjSJ=}39r-^>G#^xO1=235QoeC3QWW!Bq3{L-h0KIc!U;%xc^@uc zXtHOUG{JZ0pHd!7FVEvL`+-ASJC|NGZNik z?4Y^%FGf;;SL5}w6i$mNere1p7NO(Hgan;sdNu3h&}wr3R~xIZ!~I{#jIiTl+14$m zkuBu$YihF13j^vdO0W3)6z1JfDsga(*j%cCETd%&4uY+aq+K{3d|^~PUJXJijWiLA zDXxCseKPClVKDGHT}^shIJVI0;0~C`z$NQfV>Jmr8`T*P8VGUAkD{S5(WQ`-mt!CWPmn z+D;duj1nOmiS~8zU$TB-k~M3nfMt#wQ(CHIaws@dEv+=PB(sS@yRY25jV4?qMIKUG zk}L@;bV{Nnr?G`}C|UlqCrtCw;bvsHAS?e7_ycc?Jv}BSih?{t4rTX_4Wsi@y_eLx z);5ag4??@f$5l>h@AZy9cQP&k8qO;WIpZQr6siGgAV5u5ePhF~f(sI3-Q#8~Z2-er*EmTh zbM$6?#}E2b2v4gJ1&RpmL~s4o!7H)Mv7-8JegbXC@ZAH=@uI?CB7J4l7ONuEvQkSE z@ooD_h5KMB)dJoT2RKWk#A;$|0vd*34!wN*m?%S+=}$Kn4kiehVbWU3(riB~!+#xl zSbdsX(RBM**}r_cLUHoHhwTV^C(fBz;+s3}A9});#w>I=OnZhgoEN<48iP{{g=9>n zeN@t{-e1OL1>H{=LDZT)%YrI`(Dc&gAFSsp1s_0{3(-nby}TxE56!;@|0v%mT#X4|?NsxM> zpL9CP?IXXhHIPCuZ(xVFk7Udro$_lm6xKSzgKT+?+M1Ku0{!JWh``@au5_&gqxY{=*vLnV`O4Cm4^T(vl8?baTC-UA) zM?{~ZE?kR9bhFA%ZUkIQxiq@vv7pz_Jzc{=9Emsml+PV-N8}%9)b79eu{Lf5;IL?L zS=+eGjDA_6bm}X}2os~=yU=$%%QiuyIr8Re5GFmrNy$KUDr5R_v?34p39j#&Du`9| zcd(9zrE6HP&*e3$QNk7!Mzu0}`hekpo64aeFT=sFrGWA#*6-QY(0OC_K|~GQ!k#AD zEbv%$!np9cp$6r0k7D5=_bemuuc4PQ!*`>e8%y=BZ-1SNsd0dCzb#!#z!{e7;cIRE zUh!vhvjFjR9A{q-6(~f#{;M|W*zc2DT=PNa*rXXMP^pHg9tc5XBnuQ$2)wa$b2dER z=lQKUzr%YP;By$cecN4{vD-}yrBxCnruHi0p82HYhzXlU+s4B|MbJn`>dznDF6dos ztm)6C6pM?ZqY+&@Htr_TBWeU_XqAdt6r_ZWG6)<#^hqtxi5t^2jU`GXM5D=s^mxsh zHE?-*CR~gT{HQRlooK_;ihZ({r|qBYD|_Fx+A-&+`?WnND*}&*u3z(@N2Y-fl)W@t zmj9sE{~v#ZI?D!cT4NXyt;}! zwl2Fuaig_Q1Mkk9f5#3ar1|QBKQ^cA(k_$<|8FDN+^q zUP;dQEe?#(0+YD6Ut$!PsG(W%z<>JsyiNs|w)D4wvkCL4K?c>7TO->*kE8-MDw8O< zbzOdBq(0w^DA|&m_@CdRmhxt7GyMgdOWFgca#fehTUx^59buBjVQ4zJI#YRYYa?4O zN%O>O*YQv91v*{rcb#{l<&~%BSR!S3g26}_S2+?0G)T|l!*{4ilmzPP$e7HHQ89?c zAzbLh8;BCp;i~kR(nuB@;xzJ9iD2qPFqhl(i;8DurR&7&OZ}vPd*!LW5IN?;^S;lc ztswhZ?qQx_GqB67rTfRnrt(jjJ#4sasG!t~u8cl9y7r^%NsD7Tx|J3}2=)qIXcM`U zDMN4+%?Zs}FfNH6N6Q6kh`A?5Mc`xtu*w``?|OF4e_9DfM2XLhE8bR9I9Y7mlMB3- zJM(Dy5zX*n?`!4Z<56wbcCz9G|5hxX3jYS9_wxMG(YGI`o1fWr6mp$l)k*#CL9qWAr#^ULH-N0E&Q1nJ;&LZ&lu8udzl+i(|oU68xI z?83AN(J~ie7rRSGBhUJ~ST<^A%H^J3g~vpXv%loSiVASpw{9bzYpUC3Ke|B?rD;C4Sl{i@N#79Boi0CcE`WDfJBUh4j z)fxsRRbhD>veF+t)3%NXWxl0q&&R~bChBOhOFt+_hN)=(xu8ZEkK>$h)}EU}`^gAU zv09s&ni?9W&+fuWi2T?^xl=|gct{flw?-^z90fG4Y-=80Iv1P?W!N`)ZNS9a-fU&Q zn{8|e3~hMjDnu9AtKV&RgX!2i-naDZNTPKLY`gCT+g`q9cM7(DlOEH|-@-VlLXd9s z=HS@CzL$s6L!GGeVUqvDy8U_HXT016=emQ~5s%}qJE4f&5Ag8a-;WDvAJ6>Ar;AW& zXZ7BGW>D^i{>5YPUWN43C<}B_(V9i3x4(pUv-ZQ{1;$a*gud@3B&0L@H`fQk#9y7MzhulKaYVQu>uXd0GUS z7$tTBzPv#xXGn!ASQiU9gN<44{C(Q2Kmh3o89bo2(jS_5aQ3!xg6!H+^YG0qhR#EM zxX6-N3%!(KO?4j|LZp&*-owYju@Q_w$>`mSb-2dD`vL^y-3|e{sEw1NPrNN{|3lMR z#>Dl9Sr{l*XmKd+?q1y8-QC^YDK@xUaW9m?-Q8UVclY8BJOAD6O(rCS4@2h8@4j-* zb0%xiUG9W7!9>#=HZY0-j8`r%%WeDjgR%X*t_YzNQDwb5P!QGsMAmS%-Sdh8un@Kh zua;siCNI*bovDkf2>#f;_%iJr9O5KQuPibTYCwG{g{eq`@a&x3>OZ9WY{DQpaUxe6dK9!~56a3m6TFWB$2`sdKDakqv60 zB~HTlITRHh4g`jYa1L1k0a8f|(S`X&c1PJB6H)N*O2i(xGo;N+nG&Qq!5j*<=xT@c zT8NR_W_}nA_mjabXx?qW3LS-NE$5&o_RrfP67F9f$0;iI zvRoOui?=P1SRXp4X0(fI@@UK@!{_KuF2k+63yTn2+KVjun#`mm83zAVpvD#H}{!0r7 z>4;$x&u(t;nh&=q-_Jd=HTg|l4<0SidTK$ElY9(IyaUi*Jas^yUBe+01AV4R1FjRYKwJy#gdp=R$xLXxM87fd{1}YgiyHVX}|iC5mvz97)#E};~V%$?n7kqn+YLwTeU7D z;Kh?%bOw*muQoehO^IHYJ*2?#hZq0Z;1RZ3$xkP5e>X$aR{`j`s~T^14K4nht+?^z z$d&G0dx8IKW_9&tb;yi|LQF;GE^zl`d|Mxelq~boO@}W3SaWhzfmQ~GB##Al`x&|o zUKksK`AJDCZ^iM0q$q(mJKHr4Mfh;41BcC;Xld78w9>V{uJ)|zOb7ZBHN~n#d6|+F zo_5D8uZQwCt`3r69I9}FP#sLf3x&gNPMQN9NqnlCRHwynmQAXblTdc+we4w!2nBf3 zDT@-XXCDVIrdMq45(L;E1pRVGLTxBkccy~;n_SvoY-4^Vp=Gkx*Edy;b&P}&*MJ-< ztK}{0+bSS~F-U|Lgodvua{B?Ih3yLTO}re&bw9kBT;(JHZ)y=`%G4w@%)i`WVZUVx z+h1ny1^g`IN`I9)nv;r9`f`S{g`K7i8EoUqhLk(!s9V8V!(z>NAxGZl=f7^ny?B(+4Hcie?{R_XmstyvfG;> zArT(WWVC1$OEwkWs*Q~AeWnypH(?xdP8(&>9S_YHu6*-Kl;3PadC3txSKh0i$(c#5<;8A1g93#k2h${8b*8x*k~GD zXzg^B4P4B`xtKX+S){o4Ut@H3GC0ZYyA%H!jr~RM2r(v&uHLXM$Q6Ym);P99A6jW* zVk9o-%karG?nX=0;k)&ofQcL4-HC`xy{$Ug3Hy#n4AdyJ!MEF}8(Z&ujz$&`Ks5OW zFjH!OxQ#&uUFQI!Sq4L7z1eZgjpyS2)&CIaBvY1V=&?kwmAR@&ME_iho0J|uDSmd} z|8P&(K^2e1!rdOw?Rk-^DfN`%N`J*V-?`83CpU-u1ZRzJJE2nWg>=X5>=`am0cF(+05_*;4{ zZ#r1)!D`J@P2HCk(~?r`JaNhXAz9zMouw2T`PWJARo}IEG;EXcV@##qeZ7iR^@ih$ zPG@u+J(~rxeeRF7)SA!N*gzIy^DAIYJFuKq)--3?5gfRP&*OEx9Shd?>EOjms;lFi zrKpHkOG^E+4T~~{o3&9=1Io}Ld5=qz)g^CWGr$v2;n+iN!D2cpb&!YX63%d_T-pq* zWLZ{lbPV0^xz*hyU|K!ka7>&R`i|0VC3du2fcTldo}`@8KIN^*)7_i){8TM~pODqXaz46k0g}DPe~*B#<3+o0 zTV@ykhFGMPp?h+9f>^>#ZGc)XE;roO#tToUl5RHnvg1N(ZC3DeWI^Vy)j+1rbfJ6# zFqUHo=M0VPLID!p*z>4ftU`Ue^(}E}PUnl0RTnmD=~5|z>SbNPdS4K&!>46TkPtc3 zKADJ>9BiPSCM-l&W4nvX{Kk0Vfvv?552r4&ee*K(y1Y|JoDCN}>vn?_acYZL7_hB#WH&)!%y|LhfdL44t4LY`@Wn zKn#ULjof|i-@A0u2|rFn&SWY=GAQLJr@zh*$_vwX?Ks!g*KuPdz>fuWb#da1qZOl>E993DVZ&T8 zDGdwD7!*auQ#bKe+2iEkx#&S{yhfQE^^DCL(a&K|r9whj^rlK)V-O|ckHkwvkF2l^ z*2NyT9xxTJ$6JB_KnzDHM%tM1OC@>(#%I`mz1{BE-JF@#K1#)8sbo?+hoDUiaIZ&} z?y8i`Cv&N1KqJU6(mQ|7bhvcyQ)^LOJ$>_bFnTez^3>Z}eni{WU{<#tT|=D%AE^<< zThK)a0U=v089^b+NtU$OB0UG@*9}SK9lL_3~U!wy{;x5M- z;BusrLgWCDBI0CS8mfU%z|kZdptHIqzdM8(2!n#}b%yEq5t0oJ@#IeR{oB_!l7_Ue z%O1Z~SRjchcn`ncEc7xzK#FKMR%W&@+3B1QUS-1bEV|hI`L*7~D8gG#!5cX!q_jqV zC#=ZRW>o?_#}0~=wvAFQQc$4p?`smOq?qI3Bz3nXAi53U4qu4(=iMTr_KS8sZMGu; z6JED;w6&+|Dl5+FDzn|SbIHK=R4ew?)%A70hNiB@Mh;v>%6aSRD_5HvdT`dpwmWW6 zkeFHam+CnC6H%RiJwL^3MbTk1q!3v;_dUmY0{7u5a@Tdx6Qddp?n$^YOh)lnk7dM` zNlF7WG~Kpc&VWJw|UKP#45m_7kBSpfrGgaN(b$LL}JlAH*RJL zkju*>oP!Y0;7l`2B-0qLj)6oaoV%DlPtyrARxk`0{C|P37>fr8V)Q?q28MA@%PB!; zUcQ#vlt;`w)}^X?8A0yH2>M)Y#-*JX#W3*^!K(y|?g(+bXt!ZP-9^EX=8JyCmO$PFs3aOV6TVk)w$oh(II7$2UJ42Mok1z@7 zeM&`)=<2l9Px+yXxRm4^iUK~(ELPq}9n5H%ATbYsM-GK=o|X-b+DsNch7DaT(s z0}>y>aD}mzO8RjiaB@{kL`*!v971amv%Vfgtx~6d=Of;|1lL19Zq_8Rt>3*R2>}P+ z10FMT>a7*ydTb~*i1%HG~TUCx1QmkBY`>y0{TqXpYm=e|DZUb0@FG|um(LWEoV48B4Ao& zFAhVZN2@33gO%d6{|;?obhI#ULJ?D1O6oECYQ9O>xu9~SKX{y7T|aj96I?n)tmSnC zetw`kdPeZB?;v@4kL3B8d#L{Pcv~sUeFk{qb6F4*uJRB7dz(LY!Iq@Y7tN3T^E|J` zK+vcAXy2kE_fgmMb6>;rFzR(Jp5a^8&%iex9A&2N2SYF9%N{|#!`|t3uZPch$D@(_ znzfFnNk#9c%txM!hWShX)h_`LgL!Lu@aGqvTMvKW1RkU3$@~QGJq6xM16%BF{Err@ z+iofx1JA}B4gUKwb?jz=UuWrtAC0n1@26mUYpmnj5vHc!S^HM!VNWogL(BEH8xH|E zEU>qR$>^`<2vE%r+YY<$dUMU5YQro75$PzwrsYSA&_tFQg|2sU{2zD9$o1Gw7U!m< zAF5(uaDJV9(<`m4p$o6e-bXzw(qpYpg~SjIWV_|}O#f(IiMVh*PoeXAOdO_bxnLza zB_S#|>-pZ+xhz*&xwJ99`+ixP2g0pN2VXxeG;03879doK)-R=5Q(fI&&Yb+JGkbCj z<=ITmKDL&ja3Qm;sz@|0{~=T&w$2RiT~}rKA{+gf1N)nX=6{!X0aA~18ao$T+)%PJ z9~IPmSU9-L3vt@_&gDWkReK)F$G`58!XvM>u$65~)CFe;E<2hUZoa%=-P#b$a0mA2 zX)K74O<@pC$m)<}ww^EJdgP2i&Mp4d8SxzdCU&!vTEH62g%w8vudbXVawI^3gAmo-wj=^i?HZ*pxIuHhcA5N>qIbgv)ZT@O4DOkp&!97ygbCWla6$ zyZ{%%B5lk4kWl2~uJ?xQXG(YAUtsi?`zp z9z6ro#a3V+P?6`P7+sOi;c9cE{lDsqZ`!A`Yx;Z=@o2w|HB@Q;8Jrq+8n+nGO|^Js zWoyfm8LHSf^&Cn=qf^NO%H*0XRQsE<$V#w2M>ZNB9)Py|(%sn}$8yf+CMje|7L#5e zbLVA1BaRS>QGSQHTZPj>L}O!$cC*acMR)6KwQmlu2VhP6$ZjEJyh2ip`-)_-5pv6ZT7|*2 z+D_b>IB@S@-VY8Ac8r$KqLGZj%iidYgbrI<0$z)OKV-#5CSeS+=x`*aBIiRzR<+hn zKJKPJk&0?rzvVJdVkj&ti^K2qGgKx|z?0&BdjUJvn6WWBbM3-*;k4i)9BmoU0AGuK za1BKgTRk&3)#@Y_&fP5RO|9FB{`2}9dgzPMj3ta6%pxXYiozC)RFWx6gEMdSi2nFY z$;p9j7$F`v>Fw+;#1r% zxVY8O&;XaUEci$i145gQ>=BuAl=a%$nwvl(D2MSnFb$K5f#G`u_-&#b`4?P>XQVH$o6Nj1Kj#FS1&y0-&Yjx_{##t@w-Q zD>1vGWyw%~hRwpjg9+@5lv2lPV38dkZ^sCM9Oi3!du}`>gR?;BWj+Fk%JYX^#6o5i zxbeC3)d~fDdi?2ljN?PgquY<7-&49sHy5W)Q);7T6~jk*5l;knUl!V>Y#V2f6>Szl zb(NIKkyEUuKrcLIHewnv;G)&viZK^g)1sv_Oz(n{`ya&ttYM@DkiR*?yqHMu>{yLR zVN3uLQ6oEeNFl9L&m(X(QJ4@YDA-PQBY5t5rZ?3>kPxiiXHsZorbK?B#8U?s?A!%aKgB<; zKdMeU@So-uJ${U4F+D#F%@g@wSE&--j-{{PItIR%zyI`mIw_m$b9@MPY`G9s?6~Az z()V}2u1W7cS$Wi^*q&tSyyErrUC)7a*z42GdrbMMU;40dIZ^*l)i7WoV)HiRoapGs z7dySD3M#?9i_a4m7umMwMw3xC7!PCoc)ht4qSV4 z?W#ts-|o!VVnk=)Q>52uhUi-zpDEQFBO3QvrD?)HM4On7ApX%wY`z*3Q`Zks=z6`C z4`$&jKyUfXm0M`xO&Y`G7|5bix5i!JTR}ZNdO~wuN6HU=!9i&=V0lGd#os!5Acx7x zuh>V{X06YvRQE6OB%?(4uEqBMQYwA`;H9`5P%I|Y6>RTvxP39&lK%#+L|>$xqyAFU;*gfcGwT-%lgx9Hp2T5A z|0vv_vE16kFa6HmJl|>esddiPH7QtQ`mzc6JzCw^m=VumYyivv+cW@#_)3P%_B%Nh zZ6vueieoT`SXcrp8Bt4zdAQpi>A#Jh2KIMi~r??$3LtwlPdW80DX6ewf;ut@CT%U2O$CSLzRL>R}?(J)9=eZL(^_ z{fuq*DhhbyNR9}22p8}c3T*%7Y%x{=9=?H@F8j3P#1=DEBQM&eu`J-AyM=I!d$^Et z_NG%Gc3hg0vARkic!R>pS=*v4qiYJ`W$vwQ3$A9PQW`0(%e5iTw9`tUYZ_zy81?YQ z5C+&OX7HzUY$gSGjG!%QKt7}RZE<;~@ZDtO#L%c%u+g*OW(sw6n6>*#buYTV9Lu776(#_0Q$$kx7zeM_jH#6TUBd(9~ zZuh2FUz-%)diA4;6pAmA{6D@#1l(y0s`Oy4_E;n#M&RE~e! z816oy)BG51H*lLK6nbvVda|gVp7I}FyKL{cuDuP|joBi9Z4e1qXIPuO!FBc2wx325dI*d?={?3S`uiFr2=eDL7Rv^yc+5LW(*&MQ(lgG5* zdZhf+VRHIUS-xBuwPC}e$$x{3Ugmh!GQ3&YQ%qZg@Af>KLn91H&1!kAt?IxxoyR^P z)b08iS!Y1YK^#*Rzb3g`{7gktU3>IX1Il=9-7-`?!>_GWE(*O}S)IVy(ts8;vvwwI$}&Rh43&&X2LNy82*%`EVM^Xj|h@ zPz?lV)u=w%55^>pF}Qe>K1z!FC``7FNnM@h_AXA82_}eu*NFs%ZbIKHMC;Q|%s7g* z_;*yG+Di`H%g|D)fI0Q~#q|a!n~1$aCk=AGY%>*L>v0A}SjA-zSL)D~xbZpu06$t% zI6+mU&{tT;2t)`^ATc1<2iu?_W3C++s-nXD%8FH6OARn3%&{f^SWA~1J>_LBHV8OF z|8d3jIB9uF9F!b*`n9a{&iu#5zX{hMjjLw>n+KYZ^O)jWOTbH6b=4P@JiUhxrmMg= zSp`E12x<=kO^D@ozJu86amCT?i2Y;Q0`EPR<*$Y3q{5Qn;m;)`ghs z<$#@C^kSi4UXw%ns$5A`DNc%E3vXmJEH}l%V@W_4%R_Sbj&vD2y?RsFBnN+}O8*W_ z1Bfukl`XzA;|x3SvgtCs2RN{&O#NQPB~##t-7w%`$EjU)<1x1oUKUS$)mx@VH+=At z>u1TDJgtbD`(eHJv~sYIGX1KSxQ?{o-mQ;=r_>kTDncZYN*LX$Y61qh*y(J(D15}BPrniMeM3o}4E1&D}N z`atx&xXW$u)xmNeK~N=#AZGxHrDD+rox>TsMpMSR+@4EgbTf3iF3y->MyUmg2F z7Le}?eG+tKxdGKgCOI$1vRAL5oWM&)(V&}umYBM{^6o2Vc@INxFjt>PaOWDfL{BHL z@AsUc)%^boww@aw*KaYe-osRH$O0EUt{|m+$z^56PFD_y-gdh_Z_f$f&!Qc9Z=*@N z-yJ(%RgpXY8GhdHUHP1b7~CFvc0QJSj>Ll;sYrlD8ji1$N5dP>AA;^jub+96oBn&} z=>bo=@%-}^WqgMRj=sD0zsE-d(#;Xsu{5S$Hhy*=2FPB2;u-b`;K64t-CqbsMEFkU zc>nwSsIBYR#n-iDiA?`NOWFi@4f$|t36*kZkV0~i@PH0-2K;qpJCqon!wm{Ck{$t& z7ANqQ-wJW$PkV)Y_c1{&Hr1`bV@bBGTse?2_twA&JI*32a{$K9r++{fZeb;7SWTCz zqH|z(eCq?P-_K;Q<;#6v5`VscYaRFs+55Zlro*@-mG-a74R20uOs(+r$09m~AS&x? zhLEzin~2a{ay(0!m=$pQJZt?A^Gi>03ui{4t#To!H79uHs%9=;Jb(ZMf?1~KDcNKs zQxvS_(jmy#(v2*;$YjHIJeWJO>grM$wXI%*@CNCu#651g5lw*OY?yEIWpO(?vPcW= z6psBS27kn*d2bT-aqNFGwxU!{i!MLwx0tpBcqMfuXA2m{l5-U6S;vy*=qjSz8(`y# zn{d-6-h5yJ8>0XTl}#WWAO{rJ+35^6OKI+>5~2mq8Z$qs`}1ZPF`%1?%$HJbReVGC z^qnYhqyPn*v>mR1iAy9QrM*~^AcfUvX-JmFc z7(nZb-e_ksc5y~|#TaM^)aaT9kOVEb>tlGAaBDj85x0ZrL) zn&y9FJ86_!3hg{YlyofAa*h<3Wl1I#bN*ge0C#{jp#~V)coxo3c<;z5u+$t4{}$we z(1RzRM7@&vwGW$~)pQSPU543e>G^|y+2Xw0L-;n=?YCPe|0o)@Fr5CjXWr~P zz@LT`s1d*BUhS&Twg3Io={W_mMUR*LFO}`$n7yKbx>42hGA|>cqi9*+y}ROD(HBLZ zd7{lgI7o2zCDSMsg%b!Gi)#k`H@?&($ed_}G^xsL%}COuapWWO6nCNAu4 z5l@!mmHVw0gRO_Ic(2{7&f}i}`@DJGE*^IQyae~MbmK+-6ICxya00#uf0{rVw&@0U z_U%Ul2Os6g-NW~Rx8aKVhT67gKu1Hrlio2Ns+fhYdcqc$-m^{TlMyXjOSrBVB2C2` zBJXAWYX8?Q!wzL#TMJt_iAHn&nfVaiM*fLfC&rI%?{DF<<8q0bDmsQ$dt736+77ReN`L^jgXxsFf6;diTQ zhH*sC-`-Du3B^b3(fVvkmvuV#2OmVrEsdKygBmY6_x$VCU=eS zg<5@0^=7`lo@*Jt4TA&5!QQUNd{>y@%>>>9SS94Rj33hF6&gJmrU7OM$Ro5~k&5uJ z9ssR7X!EtfVD~)VU>2z*AaW9ma4Ua8_Fr0~Bj$!9Gf)ghN$|eQf;&HMY#0I4I4h%a zNs19tBu^9)`~0XFJw5b_Vu%_6sz0M?TBL|RVeZgb%Qk8xytVIYE!z~XbnVe`&CFXQ z5nm2xzrET<@AqW%KT8u|n8+iM$q2Y(NG3#FI#vBA@%r4-_WHIIOB&ACKAd$D(7y+c z{}a#8rQ*ZMZVV`0#s(|f7Qu^IcY30k)cenW>U`TTpx*i^iECF2`3A zmSm91_+(KG#7>l=VAd~32|pJUujz}RRGMf9H%u5Gl%(p@l%Un>y(C1#-ih9WqAcU6 zp^2@W)w3}tBIph%xVVN16-NgL9b538{&xjuy*5YAXa&>XiYmW}3O3NgYe>n?+*A(l z<4CRVk|7IdIY68HjAJWO=UzBM_7#sACC>bE98+xChx@oF3 zZQBI=y5m;4`C!m8tt|g5!w0OWGqdG??41l~R`M;~<)=||%Sq7#HZ~-&=9I8>0yiLn zQ1I)s-5i5(>-%^216p7xJ=9~>73x$QiN_M1Pg`F0n7r<}6}^Yz^Ekh(yLVf@4LYu~ zM2O~lY#!_*=3RFi_#TkBwj2808|Dgx8p%ld53f!(&3zTTjJeIb*(O@^ z9v<%Aaew4K|GCD0N+PyZ z;rjWg8Th&Pla;64t-7r9C16~T`83_FsdTNKy83hCui;zY=Q{Mk`adM(z>nwv7i3J! z?rrrgpUr3@|A*TKi*^6JEiZ7REb&QyxhPxkPlMnVmeY=sgf^=$`J&cMKEg z_v{*Yv}391opu#Ckk|RKbmi49nVZai_9NiN@p1hq{^Qi!5~;bI(ZTsX8Wfc>r;Vl5 zNQE|#O-C(2f*=hsGF7Kzd+=cozshH%Sa4{jBsBZik8ea?XP-Zi{ z+{LM%h)l+gYus5I(rkU#ym3i)B><;KJC*BkkXS{U3k~21ym)*?wV_I*C+Bix$BjIY zl_OX0Rb-sL1*0)~ji?ds7eMmtIyW09+f$LDLIq^#9v1r6#`D zBPKy8SFzQX+p6N(F?FYHNV@cj@KS0R`N;f{JfB;MQq3Ubjt0$ewm1L>f!D(rWRX02 z8hZNaS1bP0(N3Oz`$?sFUB@%($lN<4gRp@Qv6Bma@6itB6M_5AdrWZ>WWf84OMg(e z;lHo8^!XD?FUg}2LP26dY{PmOVN+}#^v6mV0`B&wZG;bSApwD=rbYDQIy6v~`5vH5 z8(Q=7avKnCMk?up>t>fdwODohlbOZvKz;@R3%YF%BvcJx0X695J$EYAY9fXMNjTVS z*+;(6bqaPEXST2&uACeSja>Vybbyv#+Z0UAR1)d>;i-qrZG`Is}tFJs7V(0K7 z-7#}x+?1G%M6lcT)x8VfDH#aO{D*iG5$J`^Pu-%-lp}sSJ@jY)ebjaVl?e0$jY^wl z=lPNWOo7kiL=QC)gP$MgmV&QOU}-tvAwT5G`%d)ZBs1@AoJjYVspQe}^0L=|{M3ID zf_`8@E(F9ux}nol^ySk-_h+WRU;=E~;n+`s)6sg(_dQjIG8o`g%dxc+-jBB(?rHsi zJ;_|xVIWb>;6G4v*S&MR@A}(xH5e1++5Nh4l;dfjt}eOeJ9Yc^b~`QjxbCXRcP$3t zb(^*22hz5rDG_*?jThMYs;FgXsOV@-%8TXa+6(g|+jG;K$nR=RvGW!u=g9B*?WTkf*`J%KyKM9aoo#cdFb#JmcIc z8J@c7nmdvtA702H|CfBO)JTAhhi-{<1D=Tx)2#%Ch=h%5^!2D2YmVH|-t_?XUd(rI zcNuv66Y(H;!JJ~dhVzSjOiDDNuZ`LFJdb?~$IO_?&<8~-8)DqOHGQksaa4IvxH?r^sSa#R$D<2N8Ip}`@3yDsgY1m>0uu=TaB4&hoZia36#kh|pflj!hpzsWZ@?AN`O-JDn_J=#4i(U8RKkDPSe=&n}i%(!}a zx&vAoOcTtDSG@H<pIJmiS37qM^JpH@rb0oP5c)#Oii|clI=<@F*Ybz zMQzEsLiVR9zYgoM{F1|gjXIIs-CN?Fvp!boP%k{pT7EDdodhpg55_#jik2|p1Ti`8 zz1dNtybVspHH~vRG%{=y%bEnW7RkSf-h5o=cCDJOm82!geKiq&{l6BVzY z8QkiQj@yVAOLHH^l-sECo)w4A$ap7}ZqOZLl(Sv^5*ZCD}zK&ZT>U?zO@B;8?3SHg${jD8C=S2&9AFo{Vr3Nyx6 zhRV?%kal9BPum7JvI|&>;lL%}@sb+a*k=shMJA>riJ^fB|1!s| zbwY?jlj&%GKGea{aU1&m*Bgjd#zdLr0$U zQj%CKD(fC1FF{)>U?qR$ooHM9jX}JUNL$@DhlnRd7)nl3O+2g|Ks}#HNXvoo<_0f)A1?dYG6_= z9b8G>lwF<^oXG0vHl6-b@-8c4l+I=_)4>!^w9K61``QJr_>*6_@dT`l)#nFXCiA}r z9@*l3p0(t<+fhU%_p)fg!r84vWN<^kIo&T9@Vf(yG95QGHK*5U+mc75Vo9*4z(Pa! zxX2Y6<v<!%|*JcrzVrrKE6qfRzDLlBq5_{Xq3t< zLh6uRZP{@$k`)1-hSXgOHjmGB2m8=~@${zChHe3kMj-(hpXt8vmSAFH9rLnE7O-Y$K^y_6#4Wy*Uf{U#zYuc~4~b=lXjNN&e5CZWaPSt=JGboE zj~!PWdDsiZJGhcLn$+Ry@s*VdSM~juG$+jaAB{|htyAp53$%APmx@HIqaBe)!Fi(Q z^<6AR%b3bJbxpoj8kJ4-1M>Za#7XCFB76G5`^`81{v3Upuubyuaq!RJu>lEH)~b8 ztksfP6&AQffJj9sIs!=xPS=K@1d=SO<`&wC2UYK6dp`rFtS6-Nv8cOA}w`GGO@ti4+{z% z+rrrAS02yjU!`M^JN&pJy*C}+iEl7pxx~OLuMPJh~bbE4MmsnA%r#8~6fY zT4|O+jBA1R=w=$T{L6JOC^~^M*1=S(_D{T`vj!7^N{sv>^ApykZK8v5-UhlldJ-B# zGQeeI@n~M9Voa<5oLFJ**@0VPI7{h^*I3!8x_ns2EEQKA6}LxRYLo#xKq`U!QJEO2 zv2eoEM7apd3t_Xa=LZQII-REzsff5hKD!z=NQdQn5__`QI%nI(vvk$I#!|+L zv5|6yR~Up({q`W4wi8;+A`byUYMv-JS4VG-w8(9s1LhBhlz`jYIi+PWmh^0eGH}8` zVRCt2Wd(||$|#2TCUV3GgbLY|RHvjYP6=j%l98&H(LZMC4RT(zZ>3$WWYNNxJ zMQ=DP6V-8mVEcG1xMsd;fKoBTV!Je#A&IitJ&RJ}Eu|Uta%DwY^Kb4epw!NSkosLW z<229mAhn=Wmg{q>VnAf{K8lux5pZ(8_j$8cr0M5sYeJ$a$@5!@H((bS(S1)QYq0S?p0$aH33f2axI>GWxXDSy2$3J^PQ(Gt2UZu% zq-;wn$MoXhwR5F)DVY$={Yz4?o{KA4G^`~B_+*=?wmMPEWAc(9M(XINOBB!S*n{oY zE+k)r0Ws*GD-PZ8`H>YC4`@!(%kV4S@^RKFHDAq%>eEbo(89R?aH@C)sf4mas>uIc zbl-s4caV}~pX*=GVctDhO6vL{vpmC{&R8g`i`C zG88c{(kwX!e@CGQh11DKvK*^zmLG$P&&W8AskqwjUA$V-@Bs#|+!$oYlLIqavVwYA z{0Tn%2k^PtzoYbKU=k&n&4W3f4z@Vs`-R$Sr``MbNAe_{K+ST(=cPNHVnk?%a46Wh z4%AFF5q%Niy=2bpNO4Dle+rXejF4Qrr4hI9a@Xb8IvfA($T`XX`QR&pu|FUJlNm{n z-w={*IbT5W0CR&5AN^`X@RWtcmne|(8%H&bjSoE3%ecJ@nlh_Thl1PCvH6Abt)=65 z5Ze7;c7&&|4(>ALJTpW-8z$ev`(5+^p>%3hO2rw^9u$O&NZ7yq6Gv~pTFoJ19nS*&psI#eO21!vai z&@TXMB)H^Y(e54@CuJJ9SthdJQ56G=Kg1}#okz#$liI+T81zEn zEy)aR?i-SrifLymA9A9pB|(sBX%m@B)#!?u5J0z<7-+MDUH0M6b;H;Fe&HB+Qj*Td z#6%SMcD=^ZG8}hxYYgn%3CHXD7siww@N%+t4cfJGUT^_R?u#hle?=d&>S4g3L56^E zzL4lxXYdZY+lT&fm1fyHTI1Va&ctjX^pxr}zauIg+q%PO5!Qzo>KjR<@W3kyznwr2kE z8MqM_Nt7r`6eFXEt^owZS^tY=DXo&%*Q_Pig*G_ipM^w~GEO>~H=obiDqAKPj+0$o zcilBXoxrcp{iEbS3bgBbxXjap%lCl*{JEJ zNBI$5n?#U*8|xm_h+)9`fzAI)I*1+LRux;WTIF1zDv9lK&-u%FHw-1k=>eegcL)L2 znllSriW`(d2*D6IPx{qo2UI9c(?Y=t+4^?omXGmGKVGbPZudaW>5M`YtBv;zX%)%a zH#&dkVQVZ;gs-LiJ!#RCp8{n8Y?yMjjAfBX9!qKBpK6#B1J6}hGh?Wduf6o5_2tx) z=L}+YDw7G4aU$81n9}KqYf}HoS;|{ydk!CLOUXc_%ITsdf^f#^IV%c}#ZgmKc&KZ$ zTRb$>)l+RWrh2$rEe_6RK7O{cp~u6Eq3{pS>G1Hp6~`4tIw!Kj&E+cB$CT?+`&?)3 zg%aCL1gbhnCH>?I-f(UQ#Qq*);f}PCQP=8n+{OlE$IqgF7}UBZi9n2srO3vqeQ_N> zUWg}%fDsyuq{;;k=NVh~lcobdZif{{X6MhqO*_x~-F&>@$J2!x3wSBe0w!aEcL2`g zbxWW6nFzb;n)>d4bvI7afG>4mKfOqzO7U0B0ugfYT`Is%$qe=nPl2tgXqYd*B*Liu z*ge-(<~moX;7fyu-?unr&`t_!azDgl#cz_j?!tj7V+~_$Kuk#8qnP>@jx71I`Pj+H z``G&xH_Ay@)5R~;Jta61~N)7l^t;euhX-TUYU^RGNC-|nrLzb*`2Y`+wO6DYxEPk`jifv;FRaFtP z&(br6R$SxkV^N5tgY7S1r^KDcF=@`}eU#DO?DQ?^X3uWXz;J(L3W73izm*@!JPevU zhWvA3?OJwH7G!q(x*SP05tD5S^Gws|6~u0e8?q$?7H^w6H#Gguh zWPY37z0RIJNADqqazP>4j6#YF+su%No4BLf_gaW35o$eVAw;Z5w*Z3QAyADWg5LFz z^Cc8u>RXh7ArfL-c$oc*E#{}3_HWr1xweO{!D~U~>9p$Iq{9)WWBXHi+-B378Bi;f z4E7f7oPHjn>daXNN_=izl0v0bv>y$qZnol|{3}3b{lBY)l|S!{3@|+*NH-1>_)Dnq zoIN$_8tG67Sm#sOv3qzG<<0X{pvwi7gLLh2K3f71Q!ofb(i&taDy0&U{xD+U8CCw* zD&%QH19rDfG7P$ecLQ}|={YroJddjcT=zV5L*(i5slk8WA5G)_lX(@nidOk^DDnVp zE!r)Y*rHeEO20*b)0da^oQrm?>`s4ex&f<@*(Q&Kfl*^^2&>*wu^hB2(>;oEMrb6} zpLhQ1q9nlX(jdu}yT7A}*v#?b;Q(PUVJQ@nIDrDzyu5Uly2`Yvb6y71VYe(bZW7B_ zz~b_~&TAjr3(D_qQA2T!E{Mw=4gQBVv*&bSSSOlM1a=OFL^XC+I@W7hT{^!jD`+;QMv;_EfkfZ)uc5P@1K?h4r_je=r{DjO%Pdi)37pS+S6m`BKpb}ivb zu%9&TYG$Ei?zkI}uzyOqr%D43fLvN|)FJXYItng2=nHin8vjc@0z5gfiU>KZ@Gq%%|NtZLGS=Bym(NttSYc znr6b9)yS6`PGH&RH)0xZg(}5EiH=EsaeGb4L(bX~zVOqBHk@4VNj9BS#eZtPi!||rEe)G#5O4JY;CdRY>tuzbN0Ul?^?r7$9`*cLR-B?*+ynM^<@F5b9$N~$Nj6a{a0)Q_h`BCKdNv@c`XT{ z%eg>8LSW5zdeot6y(4hL1hzQes1nI9_E7VK2;2Gqd^hrVS1Xe;TwLi4YpCeLp*??< zRnsaoYNoCB?X|TnwK6CV<`iu68_I?xx#WmI@`F5-PO}#vfIwXu(%9^50qg|4KK8${ z83M5(l+TCNUdM~xS{Wi6tdkria&}rc;axpw2uQl=hwWi^QSHTjnGxdDnh|Kab~Wly z0;R-@Zn0Nbov z@EXTewk1DM{;REPB4SK7MCpqb1()Bvhs_+P4-sPVOr$Por)r4JD<7KJ6PV@LYM#@xqyTc1ew2ek)fYe* zF`(+s;-=8uXB>rl91Z~g`sp3i=y9mrMIfJ*?Obn52(yWi;!#t^N&Lx6%;gbQ;%Bw{ z%qNZFw&|9cPu3p=?JA+9#VKW`Z)k4;rc+`-ElX{pU1F6Z%+$ie-RFepQ^Bf@NcqRo@gA0a}#Q{Oy7(vb8RIt}@;J?@m$n&si`?XP$8r zg3a*LtzI=V>4JX@W3PxZk%?TYKXNjEoJmkb$pdx#g=|Rr#cam3{P=kXY(xMMNtP%n?P5+~9nHMH0!A(FAi@yHn9) za4Pg3v)S#NSa3-tkG$IMcF2Od5U!C34Aw2+C9#P10@30UW@_o`Xq~+gnq#&oZA;5> zp@ebD_($vxrD*ezk9eFCzgiU1=?B&9gFxc}IguoS*ZO&IfD-yy&E(UfvABx-7A?bR ztER@hXq(1bMpM(|v^XY))l4-kd0j`Aydbpn=H30svo37QpH5LM+?^o7^>JU`5kQDJ zJ5VP^le?IC!3>+u|B-oNWHDs2qz0x>fdRctoPlLoAeb70y0JOU6ab@QYX-{-aRSJxeoBY3$ZJVzO-=y$$t`$lN_|roTCQ z1rZ2;I7Q{&;tQ+sEA2_bj9sS)T-7T85jzS0xj!A6K2Iub??LHM%o&#~`R!fUj3I)pRU?`mrU8 zZxYJeh}j4Zjr`e*+UNTO6V%?G<}*>jiQ|p_-+}?wXs7uoddXsc%V}Pd{HI2OV=nnV zS9hup#+UWwHQWf|*!<=-?90nD%llK2;?PcQ{2L0u+h|Wuw+82)!!Em>9)+@bCZSAY z)Lv0btL5fq#|3^M{4b9Mz>b9w4sAq06Dg|QwpzzM!%~;EVSJ}F{TK}}vg@Liz5v}& ztr8Ow^!PVJK0Zn*>LQPG)U^=gHnW~kCYb5A{DsbE(u4Aw0ic31Eh-4~jKpGt*OCe@ z0SpAq395A>867zJAO99}_TDJ{EQzBey}w`m2d$VUgtB+&%Ylh7{_;ukba*=H|6+Bt zm3L+XN`HVV_C#(EM!Y5~GMrb#VKR31Td7=Q4~P6 zh#Y4$b2M7pCrJglILwO@1pW$ExJBTYh2$N^=41;g@9NdG^mwsHL@@&TKVpTYSu##? zn13~g8hi#(!>TG$iS4x(rC~i%sw-Qj{XxxdN-@{dX?YD%VUh|w2@{QN$^zKu?}N;| zv%XK`obfdI{P+aS63JF9U0?w2>t;N}AT8W98XLuenWZ-2o%UqQSZ?86*zF8 zw8h7d?WoN%{1m%;epHc5y!eG0uJ2Ef6zb>bWEGPIV2AMS;G|mX;86tumHXhI1h0ZN zv#?eJ3qhYwxCIJ#dwXN0iYfPkF8pvfAALI;o5_3csHWkbx$tIC9PRV0N!0;@O{7@+ z-YHT7rK(oa_0fDqY{rS%Tgr0ZI>XobVd4mqbUesy{Z!Z+wFD)uP>4|K=kx8tXm{RN zjl^|h@uQIBBsXX&i3X0{{1LEz{q@14wno+F!w%({Oc;5kb?fq%)9R*D9(ThTXu0Ca zRc@0ho}QkrnPw3?dU%nB?kZ52^wL|npD0pL)b3VS#?{z`DKg0G@WeB&MYm*}HDJvl z&lE{ZHEJ_k>a;YJGEW}cYip(R^?fma&7(Ivrx4^(`S9D8 zHJqJjE*_pDW|4Ne9^TLAux7CmIam+xgM@*33Sf<$2T+$E{gK$X9PHf7**IYOk1-+D zgY}-iBl!byc!=6$QJR@lq{z3~U{w4xHUR;WE^UQA=#1cu&*L?TZ0@GkMOVCz6DZwC z?G=gXB$|yZ4o^`0Ly(q*q?W0>MR2rFap+e9pQRDGkeK~YgX_CA;TF6slAcpOXtpIXzr@5wlZ2HUqDVqw7|Mp3 zPBJAZ3ZkWw`!_C?L=ggGD~!U3M4~_lt}P8u;HwWg`jr2qk3tL8?(HGAfsMBA^ zko=zdK?TVIKV8m`0Kf^qfs{<0hS(P5w#GLXjyCum;S)ktOG=AzBl2?(YIsc4^_rM4?jd8sqZ9y+41+Cjoy(f&wS7xiMRQ9>( z#!G*IH|G&5@wc`2PcU304IX&ev&WyLaIwBXYuD~IAX^!|gL%?RDjW0t3%@W*+|!eJ zIZ=;?5aO_xmhCN?<|E*i=!{R;S2lX06+Q3G3@D1BNh?P}QUhj$>$2j!D z^Qt!4u7#=tMg4lv#IYi{1>Fv+qI}7`YOG$<%Y6+__R!F?BOBwd%XiykDoLl@Sop4` z#&_6_89oT2ZbvEGyZh@If`h^ztQnbxff+gMzva}{Ic?RsaS_o^NztGl16I}iH@Bu* znjybcQ^`m;$E8H2!nX?5In>oEkz3D~QjQJJaO1g7{8`8;K zx;~Pdwdo^J9nl>9(;tcBs#%LVy7I>{UA_$Q`OPL<-~# z(5;lsk_c-c8izy88-$~yh)D*e%?wSSASpcc-7}nJ?|)LtUBX$+sxl^R^q;U*rU?#Q zwTm?cD_AOgkPZvm96^+D_&+XyAi!+4@NIx#2O7(U@)zvg>I5AX{HY{tE&?KmFeCS5V7uT?&W(Vnie&>I(!Q>OviUUPdJ4)_yx^wFG>iz-Bd ze5Zpsb8>k6>dI`6&-&cNZMVzK@yHitl>sRz1}RzUgz)EA2%#`NjR{FtqUN*FllN=< z!=|M=yy7?;HmsG@3FSxY@p_A6d#n%WK9K4q|EBpNkvCQ| z%(NurSIZB%-=o5-pXZ9d^+)nM?ojRmOAH=LSY-Vq7_BV64W@RryGO%23N3ObOh2OE zxI&_5k>zAK>E{jj)#ZiRLKb$%`Lh>7sFaCK9OE(G(nUOk$>~f+tM1nqqVuD`M_^s+7b}9qJHD+}A%I36t}mf?DHX6Ovm7peXEm>&zAC%Mw#fJWr1B zWIb+?J#yAL=$pSFnlLQAM1@+4e1@#V9^Z9PQdbLaA@W)+s4U({|IlnvaD*SN9&l>1 z{R6E;w!(<9A$NKU(B)<{Amf6DgR3a)E3e`HVqwi>B5at1@Uba#Gxj_An!d0zm$S(q zW$=B2_t`wR`uiKd$f4*z{jQe{vVd9N$7f9=vR=>8xFM{9K7m{+cbL;3xRjrMNbn;N zvwH9olL)s`N|0veTEosX{vIa9ftpQ|72{}!+n#)FFj!Q=op|(0X)8-(oRC0B(ZiQk z1AK4M78Iq=4U(2f4c3(f6Ds0gAyO!F^;2l+jonGTScmzPbID5G6O8%X|NR9Oog@7T zL4qv1PL`)@Rr(?J}`<1)A%;gBX=`0zXIK+-TWs5Qp}B- zv$sBQO86IA7Wzvf7se53<|Xh+`G$LAJ;jMkISFR*;7n`QuX+fSgZBcvttn?#?ZjZO zQI0BK43$A(-u$Go<}>?W8PL5N@Hx&v?S z($|)rE(1d&XcXJ?=+FItxdGj7>ei&IPU+<~)(XA&KX}9dsRI6ZDwr-6&-$FHgA3-yXM`10_Ge*o| zj!OlyE9Zg6G4ffh#Oi1CA=i17T{{GjgT7v`aXGnMm27xJs=KYo-NASEz^86Vw@C2H zDC8-*?gIlhi`M!Wg*Th+kWd}tRC^249z1A7H}2+IGl0Ec7ohI=NRh8D_Tk3j4)?3e?0|@L_9xyMxdlvfYwW5OisI~{p z$ziNMs+wxW_g*gs;%t7R07#7S(E;}JBr&AOr#{Ecn=(8%EPpbGYWMP+uF@Eh{G#0= z9~b)Lrbh3bL}-2nEq54wajLc@d8kWq3ew|seqY0`R)>T%RDs%h0BoQ47bMn;EMrJij!Dx<_KNTb(QOb**6`)F3 z_$U@IoJnGZm-Xgm(h4;!A3YoSE%-Srr`gKMN12`0B%kNpyZ$+A>Bz8vJnbQcRw!*V zpz+z#48O$Epd=pr!pSM0T$P{qa6-d72y6|98D38TDnQ#jVys->wEttVr;W*J1C|?0Yek7NOg-l&aG6SQq&G zl9qN1K39^<-Z3TU*r?rIw`vTJzj9v4`H5oVp8nB=B(%)1cX zh#~Ia6((Bl%&?CM5F^K=MPP_06W)h;y*Y_`KSN=rmZ2cH-|R9&u&{_KezM$d$P`V( z0zeN{S~R5oZYy(%n1DCxar@gUzQRugesaj@tejuoouoZ5nfj7;0(L|=+Rc%m?*&+D zCyX|zno$Cl!6{Ke^;Zx9NJz}dVO~j^S(CsnfWU!95 zdswyt*S1JR)mnHKL$mEc&e`0UXS%|k+T}z4+d!P|Y|i-;BYZF9F;DY0rocm_;M4fB z?ul7X?BUm%#|u1}HbeY2PmO=`sL@7V18&ljcq;sR^n z-9YB-+t6y261r6?Nu%nRAW;MiHLd{zq${>2`I=-oA@J(6aXO>1@s-Iz;N=Hik;8Yt zb};fgBZ`%&Bq?-^5A`)4OW+K;N$9!#9I!i12LVIezWF_@9{$_^O!lrJ|4r%2?BWG_ z^Qv9{$g#fWs8cn0?lHaDX(~o7t(hUMi&Mg`rM9T0l@ZQ>QlhDr0dAQ`kUJh&blCW| zVYYJK(R2PhU29mgEWQ5Kp|vwVjflae#qMKJsJr2My5+v#-x%Q=5E|6qPFr6DUIS-B z9!yc7+)A1@h+92plZt504b5f~rzqL3HF)Bk*cfR#N46xH!UN`)Y z9kLBsro#kFgt!|csQdJ})($tBr}S6&4LYJeR6tpqZZt97vLbDHq}dP-&0o~UA&VW` zP15In6e(70R<6rDV_B@vXx?R4U(t}XA(o2yQm!2xptZ@KTKaU2gAHBL+FtH3tyc(d zGR`Pz82oF0f}|K60aMLnh8h%?LRmcq_;T3nHV`=sc<6yd9vu)5pjug&9r7LehqwZg zvPqz2BLh9tl)ykP=Vsnbb45vO$vl+TRMF`Ql#V({1}COjf@r~m7K(1eXf{!cNG5vbXU^91jAulC=Xvze_3hL&rpV*tXe2$ zVY1iUJN&f#@E3K4|1OmH>04G1VYf(tureKByIX4Wp^q>MS?GxuLtCPhxOx_LZs7}t zO!y!*J#7my*hO3FshIjp*(dc9@Qe1I)>X@oSX!<2K5Blj*-CLn;Ss^VRY6CQ&c#F# zRq>%w)aME|pVy7vYm;Wx(1%TkhoFm@7sP3^>uHCs01+TPG&Qq2Y{t29ad|afc0sNn z7H{z_)Y=XaimYs%x2`XJT{`zTcRWRmrF4HVvV{tCYiVog@+dXg6Dm>5>BT7E?SQ{0qdsJw9AY9zyEmXzPV zGR0&=aP@MZ-qb2o>?0o2 zd>}U#t%~kf&1{=ztY>8nuMv3-;yvxwTU;bJIcg@SYWBIc(wgC4boIzc%L2(k*ubW` zN(CagAj7Rx^%%{fxNcALgKx^kSN#^J-~E!ECR3e3C}=*`a;tWu#n@Qv*I#jRBPI^Fjm4YZ82RSloEzC=HnmC2Hh9m+E_sgSxIii#ri0aLD zzieTyzI~-&QFGp5bnk>*;b~acTv=6G34N(o*|@@>1Y8R>{@{1Ud1b_?OIxD|WHQu= zM*OHH8fg6~0oyYC`h}-qVv=!xvUOsQvdGm!<9} z4Y@Kl@~<_7;7Vf{svMdki}78IL%wmXJH0>dkbp3 zXh4iGJ+iEW2xAq^>j8BIz3P7c+T_0^ejp;i{xA?&+)pIgocPd4>rCGW6e$Zvh*IjUL>z2dKP7?=g8w2kNczlCU2FZIg@0hgyhvDxOS8S z6kziGx9n=*%D$w1N6U_*49i3xER(P)_=o=r=-)F zn@KA$)ubt}ghCsKkuPs?HPvzKKzWS|fw9m?H)4kLDwudH*?D(N2J>&sYA7sfDWTaT zd}_(eq#M8rh>i{|S0GJHJZw&6l?M96^3~VR2#UL^q?AG9MqfIzN<}|WDvH8?B8%5f z^o>BHv33wlYLE8L@cH(a$Y+)y$C`Scev`wrKq{-u;=oDh%*c(-u~u+4*q78lRr1MT z8Iu3mYF`r~E#>M0rBdNYlhR^$aCWyXe^^`Q^pyc8&{^fSy$@`xtekv|f36Py*F|-+ zrblAOh?IfCBu#Y4o1s6;G)cC#wq>-ca(0Hea_@NPj`v$2NzT!^b3@?pq$8t?D$0dk z>hTpK^j4uFau>lHKuK{|oD+4MYR5W3#6bj?Isf8A;a>Mrw)u>~8n|FwCwJg4U?jGvJ7n ziL%>}fxu249Q?4*kELL$Xo;pTU}s!q%N;@tY+h`%WAThyvFwv5jM3BYO)fL+zJwQh z%ZEa1qDs|J^l{gZXYb*2!bg?l4t2)f)Bm4MUtva17$PaWh(459rrwax2Qf2CE1l#3 z&6GJI=9$P<=;mz(9CFu>5+UjWZ|>?1`b3s-43i~pJ4mkcnGB|;{wpv+AKw(Ue=}3K z;BWK+I?roQ*ZR@b!-b=_hKb$F9)vOEypi~Ff7Jq;M%2WwwJQN1Wfy2^UF2SIgaByE zl)m4N1{7EIPM;kCfD&jCnt#Bd_{kw7J75!s?mQE&ry;FpXI@RBSSG-rzUAntyA9ly z6OaD0I8k8Twk}Uo1bWju9l()ROS24Gc#7gF9}n#!AYXWrT0KwC;!Y=y77$&^RA_bm z_e0836HA7De|zHTFubAmE47_>HS*z5F$pVUM~qMJiQyCuHzKy-J-h$FUKDoR%<9;2 zC7BOqHAMP($d@IvGfvr7u|1ew&1GoKZCLqL(&|1%B=ugBZ^KE&Nahl?Q4?-^ECe#G z4^n!!hOo|lRgAxQ(wS*KMlPkZl*rnYLv-^p98*6_C;6~FnIG7G0}&*_^qe{aWc70h zBE*wZY=70hSH8if`Sx#rzeF9H6Gg9vu-DIdF2;fYcR$@Tn@kJ6u6cPedbGJVuFqeT zO`fefS1(#SH$3Rx-9tZ&j)_S@lcJW^Cyh)?jTOp(ib_2h?69S%lWKEz=Ey4X1yiCV> zP;kHR?OAoxrtfTmINT3)oRmNrZZxYE0x5Y4%47+a#i)8%Q1@uQTi@OwH?acl7kbh^ zow^)3LMMZx)s>6f@#D7XzB_ORGIc^AIewEPcxR&?_c85R*TNA&muE4;)J6VgF_Wb0 z1?Ix5^kjiL(Z@~5du{Japx#ZA4N0ieB!o?;! zVhiHZQbqynf}hdQ5Y@+BJZO=kp<8^#f%oPWh!o-ChDPlT1L%W3Q4qv7T^_HY#2o3nw zFBhttaz9$Za1&I_mH2T3@$>~3{0{T57H}{nr$D8cEgGU2aD~Y&bOTQQhW97nF9hM9 zRQ;~nUUyV!s^DPv`zEa;wTy19UowUw1^I!n4Vv@MdH2~7VMp$VQSx>=isSsfMn#aY z?VtTd#Vipg4>$mI;W?1BHCjUI0{}^nFMN*S@-iHk`ddq7C3L5L8D|*U*zGO z%)3t%;TE&FFCSgj7-8zU>Bh(mWnaAp56@J_cOW>!sLk}fE6S^Zc|{T z)$p|1@?OtQ(5ASBQW_z>=x-~cM?${mrr^+T1`7Fjh5oK&{DCRlASCnT5bKPbc5vHN zYidEh)b>FvE4dd!j*$~zG;fl>L{x|iI`x?L1ucdgDc>r4Q8KbT)1_R4LL6b*LjleY zS=dE|C;O&+JHwGV^{#_aC0LLIpDv>5vt)9|+mPtna^3rn+^x6b-rKubl4N1uchNvd zcT+>V8kU&(Bkd|!f|md>aQ|AX z!)U_9_$l$iz+Y!#MCzu%lW)lC*@_C}iDWW+eG6g-6R}6cxT*P*$@E`rOL2H8Eet1t_I(+=!`UsU8te68N9VtWceH{ zR$d*TnRd!*NlZg4qH+QN%zknqFV1UHxxCPDzO7d|UwBD^0XRONudZgd+~3}6MyUNq z8gW0(I1|E6rd5|>dz~TkIk$7N;~Wz%cc;73K6?Y*`mcL-LjRr@Jh>ZIo$K~5wVt6j z%f6@5%T{STBV0;NLV8fff(|Y)g_1f&D+;E|`nF(jqZ}ZaA_Rw10^E(7S2(}*=uE}l z^w=049)=Ebt-3d>R|Y|V6!i%k$uO|0odo>hhEcRgh{$E) z`)2Pu6zJ>ycjhLG1b80N@4e99LiwxH`wye{Mlj$pQ-!3!Z#(cIRP^>7;>8U2Q230$ zb#uOTlRDdGZ}i@>b@%W-vLYtR-9JWJJ-=?ycMPSJnd&fNfR3J+6uqTiWgCPZ`vV`JArLnhXdx!DglR& z2QTYO_~1`JS{?M;vD?;b?K)deJA?Bx#fYxfSO*%ab7gEBTo|Rko#o>Q(oeMcb7-ZS zNY&s{Cc7qdpQQ7wan@;9K_RxAn;U33fWF`PoM%g4Tg5R9uaI6Fz+^@CWMY)pD<`|o z@RyBwF9v^?0hGuc1Y_dKWPpZ_I!IF&2eD$tj&8s>*>I)-xTX_WW|tK9sC}|3qR}K) zMK)7hAQ)378f5dCm-^)(cnM0E)(XpvJ>BG~NIynO+H2yew*e=4XFTb<^dgr%0$q=( zbp$FRU_cZq>f)b>02*~;|GoF__Z-oegW_Y9#eWA|udRWq|5^&4TI#%CZ_D1Vb>4@e z@>9J}xrO-0?Si6D`R}`R0sD#F5IPZzz|%nghrp|?_l5Vfz;~IT?SExPZ#C~HPTe&y zK})j%Z}|V%0(TAr4)l!zYZCvL?*YmiddCO1oBD#_GxW@7FEc5J358L#$pg#y-QQQ3 zo%|o<x1_`XK>dt(U0)j!Pe6Mbg)yVmBA)XgYL!P%{FuWf_#mIZT! z0>MxR$_*Zm-plR01GEZXsMkq~MvBR`{nRID&FIS8l}~}^44;@{o=0Vvo00-I4+Q@b z#O#mL@oJ_6+T}v&RmRnhcz5Rf>d<-~kMgqMZ z3j3X7sc+fybV9*;-;%Mcxhi~aMuf&n2RdCx)-Ud%A%qeYqfyJHq(QgTw5!Hr+1Ydi zrJu-y;HKA;bw-gLcu<;C91oIiU&&22oG65mmdW<lLb)v56)(aj*Nx_U*gxi%ilWH(R8_IEY85SWR&ZfWrCiw_5$VAh) z@`AHHbuZ9$`@#0HtFgYxRAuN>+7;sNBUx?Do+9d-k6cJMvX4_+&R0eDjxc|3Z=303 zM#%yVVAJsE>RLM&Byt-;ZH^-JF^*E^Rt_=i`VZbyXCXS!d81?7h68V-%Vq;A0T7tF zS7MvfQ88J`I57`}5!fjBcyaILYKZ!NUL!?ZJoo!zz;C`ReRcQn@NjXtg3enIF-Y?Y z3ylp7Fx8q2h{+0Z!eJa0)x1vQmX#Kw3QJCX%+cZvXX2**5{kPLG+6-0So?LapT| zbIIkevu1b3@9n>Wa>`ZYSWNK^mFZTX!06=*e)6^jF=5?*5ZRb6lf+BKisl+2G@#Iq20UPR47IE~MmnbU>fnD)`+>MMg zoW6(VDCUh|`JON3D2co8GR;Nk`sNl-!jiK!PZoy-q5t3nP2d0`hO-!L0>iFrq4P%*e+BA9 za>36gxe%6zMttj+*-(==+`4n7Bj<$88DY8nU+@OD5+v-W6wD&X;)T6>#9Ay@U=E|> zoaxy?dLB7JwkIR0lasD7c7W?dDXIiv*-NB{RMWY}*DsTzS3-{*?ax;6WrLtG67u=F z#YVISg9?Zb<3-j&;9C*tDVP3AMAUC_e9!np?%+ui;7`mFFnUR-Y)6KYLt zkxg6O$xA7{XELv?{R1_}&tLjhFFj7sUkzn}1m^~@-A?uO?of*S= zXsDM=50695ch4Kpeb}YL`uUK6o0q+ngg?w35ucU<2H4am4ke`$Q_}7#Q|TxH#;D+c zHjHUqSd27Q_(93!AZ{cs?Irjg!H7@_%%OgI?5Cembgo>0(m8D+@-eTqD9x!>bcqRK zDBmo*d!e!|v|*WG*C3gLl{$8n!9gCrb82eP#1ne!Y&oxO`QiSHGqj}^@=^;mBVM;} zP2q0XaHP0-g~}OkJ6Wn>QFXhyh%efTA< zFv-5V`MAHX=tOBx@nC8c_!|3PDFm~4{jwE!2|1o5qOx`!J}H0RT&O*p)I-nF#TXf! zUGK-*Rf78N~gwE%-p5_lX@0%1pSap|Q*h|B0ucAw~ zrCw>%S5&j0F!)Q>Ql7C;)W-*#yLaM}n<+0?nuVo~Fjm_$@>^#>|6c zk>!7~53>RT8JluXchti{@KmDMr3O?Ly5Vs?vyl><*5Q<}=pTb5R!0SF1)K$UE#~6P zw+SFfK|%j8*_>(A*|uH}d*4`$-*n#Bd;@P^-lyDTCqy1w9$tS(_8jGIJt;rSzVG2f zdfp7%lmm|oU-SG&w|os@4ue5~3!R&{(SfhCBGA@l$L(>u@No{m;EmJCu}_KrNf7eV zjv;y{`+mdA<@GV8Ht}@#{h=7*n@Lmgna0-0(aQ$#(Qi17OmdlnlNcc2QiJQli-pA* z_klmapp%}-jnr1^$EN=n0A3Epq0u06n>v}2+R9_^EG&trN~PGqEY554x9k`f!;JtD zbVb*hfs$VR$1oKJ@BzIW=Yk!!NL>NgH1Wbg)reS-M?7^m$o>jCXAOCzd8);n^TuG^ zW1#+)`y2#bWd~4UY(Dk0nPI29(kH`zIR(#`JFG*oRwE~#T%~o7<0<-*j2#LGDC2ja zbEcI|`~s_ko?UHa+cL5$0?>z;Jy%|$;1SWST$JZE^SKp&@4Fy`Q192!Wz2zLSZwoU&IguzI(66I=%@nckJt!O{BXj~c(P+jwhz^j`Q z&UfW>4mcSpJU3V68sW!+)j)~|+QRJ%SH8sktG44gd>kBRGu>=(`Yf@~vW!f<|Lx_c z3`|nd&kyHPIhWEHB8`5qfsKA6S4`gMq@~_hLAU#dWIhY1?-?%*-KI^eP>$e#auK0q zuYaur@2#swN$qAKY0_%Ypgc+@oQ&>|k@&*>4? zG;>JLG3N}sHt^~3C>1x0tAlamim`(*tVND_`@9pu77WO%ZBl4wUFAES=RW=}0UiM! z(BlI=&_RuhOV6e~iaC-?w_c6TDP5tTt9SDkR{Y6*by7ly_5Wya`T2ML7)IX&^IPmo zoL14ucW!FWDv+V14u4|1+N^ym)Tu!EZkTYv2;Qq&(gjB zi2iN+9=-f~<_)~^EUfC_4;ai0ob-Gf-(UYXfdTy#FxuI3S;xUF`kov32=SZ4@^G=c z+FN<6fxO%~y_B*&B?sTx^*lShzP(@HeKN}Oo872;|7+Z_{6AiX^@M4S`|>^e+OG&% ziKCRfrG>o=4us9a%SJYn-#42yKVV@fRh6v|o+1}ytC?f_01UStQ=!q?oZfLjX;wJw zf3yWiA^fqY3NGF4cvw_Xg!v(IKYA17I1z$snqQ?9`CXzz(a1vy35ofphGNx<5-G?M zP1jWTwP8uj_}S@*Ls|AoP!77Vw*XGcRk_$CuBlUHux zI{?5VV_7j!L|4P5jSp|rlnaX9nL8>bp_{7{4~vek#1I$F_C4FL1}naxvcu^c zeZ9_|D71b8MMY8KZOyjRf%zufHodnTx9U3|p7!In4y0qB=bq&cW%na^ub!s|DGnKTP>OuGmnKxD zp>;jJDfGkbNNXnv1?Irq-1U){_vuJYWhHbZ_W1x%EFACir!?{4{mMz<{-Zxl;QSdNBD;qevGa33W9ma0MX~elbF}uf_ z$|TUvHc~_ZGc>eXt}&9UhDPf*4sHP;YfS{JY!FM>m>h^H&Bnqn>@VESaB@;e z6sSMT$&mylh&&Jl{DrEBB9;a|e+b-`4fw~l7g+Cgxb@a1N)x!vZG6)$ddIz$`(Ehu z+FJNFe6^LZdACazu);0W@gIJeBq`v22Kr{0$@3sVnpiON6MjY={|QrZd&tk#N7HRD zX0)T2`J?4PxyopW@;?KH;iw<6LPQ&*PGmhY-)3<9t@LcA4*kokKPxW>MeXWLR^}{l zcuSH}=hGqH2@RG%tAf)gqkftW;qC5X*w37l@SHuKCC$jP)6z8hk;z_!@&j$H2x*z? z^*tC1belgbFi1&|VmrCsrWfG)ue3Obofxh}zse^YF<0U&8KhepYAG3(c`}mepb?IW+NFy*oC6>?SOi8Rw|k*ntn62cqckR1A#SQg3MJ4FomC0X-@`w zP=`AyyrPS~W+}{?ttJP6{=(Fz^f3 zhgA5Oe(HlRDXd@|m(gDI1-ditHh*Zt9q5c9?lq$qHHmmw{rk2ZF`7gr$tE!?&XBpE zmw;J}k2PHFZ$3kW`T8DpWTO8q)d5RF@N8nU^!MeK_L$T)v38|ab6+yijD#U5)P(3G3EH<@27rr%szY$fkXJJk(lF#pCoR$VE}ZL>-j6i znIxZ>^3;tFoD?sAOc{(RO-KM~*K)}z5)$NU-F7uru1W}(oBDK;=^`XiUoz4e;y{6x zYMM~Bj*?}8IXT-`*oB{tJM8IOzDRYcFnw@7wuIJ~A@kNhmHw$qn7GiTex`c-&ci_T zGwhXgEc~xfj4HOlB#W^xGRq^q#S_)_A91meaU3SfFY>*7mqr|SP}KMN$7dSE)4Kmh z(^p4D^+szCNQ2UibPdwoB{}pE0s_(zSXLfAczn*0F&?>?k$UhLpQ_UD;tObz?_BFHx|C)E zXY50>!B|&-9ZRb1_===W(2Jzmx&ZzQ{26ZjLTdcPjD^YT2aN)v_xt7FycT%|hJ3A> z@CBRMu|ht`f34p*x~Gv@GlQT1-CNlZ8{nSz+-PyqBC@fuF?0a2j=MD*RxcrJ3IeX5 z9`9LLSfXuJwK5yHhq^MJ{%P0V_axHXb4cTY#&W?IP&lzMX#m_SNhIH9(NNb@dqLM& zNY^;S(^x0190DEVdqbcoV{fWPsq=B-AmB@(#i_Q@m(JiTZ*5w7K-tyIhSj)svctg| zVOZIp*m^SgVDX|7PKx9zd{3owx(BNE?ueD%i?)7HggPT#_5EppLY_nMfbdgN)xQ( zMw1&-)z8tCeV96Neh~Q-sBB-qm!}t?_M+eX90RsO{>KW9s)}}y0{?&3rhrMorL(os zyK7Y80a3u#l1`wSh?+NM_k$i!)|m`v%H+4pCTS)U^#;;ZHFgYa@ZZ-^`&V+>2~M)Z zV|=2rFK7blLmGRvwx}uvM1lgqaq@QonO$;$IfdM-N_yFUpsV&i$pK4#8sVHVZwWqA z{5@fm5zqMDud|<&8tubMhJTCa6v?=_YPldwpz)DS9oK1rS_!Ky8TR+~A;WgdKPH(M zK;KX_Q|_o%?b3KkxfM*j7T;vC5V@~^p))1W(zIMB47?7OBn<2gAtNChn7UYY%>TfM zj{KGv)ob%fgfx{AK}VHRAr;OQL^S{E9eBztT`+YA{=3=A=#25mk~vQbV@@&gR~h*C z=MIV;GN)4(*EHn$)R!K-m@j6E@om88pr~*LVX4$kmy^6xaq{bM=|%xIjoZO4Db=!b z)5f$qf`Es3V7k7`bFLhtb$&SP%26wVH7o`myrrQZY_N+SA!{_^#6SP{PuTIZ)IZ6d zwvPiJ&nMPMSP~2J^1A-?V}t4pt2=Ly-Gy@0mONvJwtz#aA#p_nTL134y;*u+wJV#< z7ORKI>-7MAOU#$@-Fo&pzm=M8sa9=8Q{Mh-LJ4r&^{jx%Z0!u>#Y%|X%kZxoD$YZh zk!01B6H~~94fM*5YPpI^w&o=sCST zmAnYMaUINtJ*TrfbSqyTANPmI%z&bV8?~}!W9o(P@XuzPO>c(Hn^5fAILkiV3sgszFE!;Bs2$oG=GnEvu%>kt}%pQbt0NO zg!7|-$-VphXc&bgj|Gc4#FVFOXP-Ud=WBsk?Jo0c3~Ne`;av?L%7Fip6zT!KuJ@jB zSo{`lL4{VoIYj~6$}|>;GlcDT&5L7&Bt~~Y`;>r++gD^66H%{ct%^S-(mx?H_IW|c z)p+(`v`=|Vp|Y4ijgE!y{k{&I@GG*8(qG5s#XZY>@k#=0*173$O6%WSjULHy_*hwJ za@nlKy38@rBeC12j#v~Cs!BT`eeZ4$^DY*x5or%ee9Y851@fwBS_kuje!1WIw3IxG zUZ3$g4}_As5=r}5KZiIr@%C+PH!*s`WYydD=&-b@$fS1WW5{d2JzoA;&-t#Ad)8{* zO+WO6wufUl{eNwxe2^eY3W9-704YT>aU>fhTsChLy zcTQHjU#AxMA3C}CA%H}L)fUgGuII-y4Yl?O{|jrS8Zj|3hio)_C$0OA0uQg{fGvjB z=|vzpw{@-5&cyeyq>we=XD{o-%g@7Or%OswGCc#JqXVc|c4=~616UBEQG6tQ(~=V( zUW`@m+%*@W1dZfE_iO%LZ+1rXXMv6R&P(Ot;9i>>FBd>lVe!=bcRi|FO&9 z0~P657O#^X^Ow~+JH%54L*C~2>%DOO#`5N*X_PK5n@%NiR6^wz=BQe*n-oLq7bh2F zdUPMXv@ZbtZ=-==*ax$$ey@axnvwA2r*$NnU$S0VoMmm(=DFEq^GjOTTkcpYj?g~H={w52BTm^8oy;)o(Vqwt~IEoErV}4=dty}5P%U#dGXxD+S`|1tTmC>6JX4=PC zWfEl|04o>0?hqYZ0tg6b1ANa1`SF>(qE-7P znfrDZwpSv(pBl=&9>n^MvDzFPA9Y+RZ0V%XIx7V-g@`>eOJE9LuPSIZ}ddjO6X8#%8BaYIJ+e z``V?=`&~Dm=ch;DyQ^#c+DS!)+ti7dSaq|Iio5Gx-WxAt*NZFw1*Q~o_CL0unKOg~ zHFAjbga6%OnG3x85ipkl_776`$H1-YRj+SkWCXJUqnvwrI=J5&SOu`;Dwn+@9Rl=1 zMzz4m>D=l*RRmbfa3b2PavGe+O2J2CFo51}OvZ?+6g(I`v1LP3Js>%cl6*tmrKpny z!o{08=s)<%K9(co42oLUsn+!=t3r$ya#xN6vuXqDYRiVRPyn2=Xy}pkT@`ev3%bdb zjh5N0XQ-u>Z9P+^m!YUQ-d@AFb#-|ha^o1+vUo?tjL37HB0uRQVe11peN|z>crzj5 zs@(SnieIS59ahG#8Rx9sJhFy+hc#=NWnH7o%|Vi@5(by&MA$rkW7gLp_yR(=zRfqN zT22MYZ|NFCSm*gH1W84OcRLi009NKXdcG!2hv+bRpk<*CbzME&S(w+(083QyGc}!G z{&Wu=0;;?bkK|Oc-hEkz&f=CZQnttL(9h>R^gayJn3R}jWbPlP!I}gz?U2!$mJ7(R zyfDdJy}Fqb_>W~B2FO=(CI0F{x`;AtFoYGoHVwpzxgnp?)qRkXtv(y@Se$xRWYfTv z*h^&gs~)tp$j%lr9jP^9IvMHLV~@hBS_O`22EmjaB}Qv4KQaqhEg@el%9Le~v_4DX z%1<2G!*oy+=+b6UIB8_b8heQ{)g$@PwWk?!Ctt$aOt7y#Dx+4;D;W>p%^ackJV{^Q zQbYE@uDRs`gR60kw$EWRhjUT|1+8x%6;mhvzA#pIQ>6V-6|d~Zy480;vFwohoBfk5 zf5nfybF#B&pDZ30Vt>_P%EqjZ1!@|R@m++%^)##{ywQR)Y&*e{s!9FfY}R*#lFtvr zgR+m5J?E5elP-dk(W4xSii(9a8Djkci7Vso*AxCV_Zt?85{sT2lQ}}oi;Jr)`QBT= zDed$`ECTg+tl{B6QL5dD^S(Q1FU#hx`#B9a@bY!Rg#vB+{Z$Bz(~>{=36O zUr~{bio$1WMG`Boy`-zV(dMU!!?tBi9%l@SYoThKCqT1bL|>q>}G_ z?$(MY!knOo)QVgIH~n`>)5t*X8O# zBx_&Ly(as#zVvh8ThaIIJ*qimd5_+#Y*{Z%$vvjxRlDC6S`NlUrGT$A_u)@N3-;Vd zRoY6}tRc3-J4neT+F6=S;;Z(+5&q;Nh*V^G)G`Sp&I`x<7r%s)dao`hbSBhQEKzx| zk8;=FzH^jh(YTKC)4;{aE*1au_s~j9_FfDH)-s$-GO^M}ZZh5Y0U4B%aC06moof_v zpop)*pgCxXzWD87^C&BNiamfDR7X(z?8pJ8Q2i|f5 zoLHvd2cQKNa$f)LiO|C^phs>8b|ML7`M1lJCN~dx9plaidG5vEDjc-aOW7+8p&zmv zYR21Ve|&*{!(e*-=3rY+Y*MSGZ{~9%8T5xSd(p4&QXviOcry5D@&-$Q=aDfdsjl%m zT_1ph)W8a?K~Mu~mJqQQv5k!vsoTSmfy>UVR$5B>N#9>I=}kmNJ8!h>rtdnprU^y@ z*MdhAFhQwLPXn5IuMP<*sn#jpw@c0WT{hdf8z&E@)$ZM_F%=cb(Mk^5;pjy8e5_+= z$-P?(%dGmptR70%)1wa`sDGy%WnfOZR$Z$~eZ-o(N#UVYRb;_-;N~veyl0r`#W6|nOKh0G?7r=>rA5*&R ziT5@j%uZ-BnvO5o`U3v1a%Um&wXk+@-g7&gdzzc)Q-Xkkh(){~x39vW^=f>58F)uP zqXe8t){rl}`q=*SHeI+8ayoRoPgfk(`Vt>~TX?{Cr)|Y?IF!3fM%W5WoszY07rTw) z6!%W5ZY_)VIadIg3davO0QvSq7FuPQR8qUv)|al{azHEdz0BCE|DbJ~-ngDXU~pp7 zN6(ooa>!h3=?ZW(N=!)5s{|Ic04%@r#%YaU#=5b7k&`B9HSmZ5bS!o2A9Rrgux$RT zs=#tKg^fY#{IIM*QbNL*Gh_4qUC-SDU@%7l=|+gg3gdWrwP<_J)NCxoqJ4(JQWOlk z?Cq^^?9>dul1+x-XNJPqbcFsClhd=Onh?B~u$+OTfII=3VcwPQ!u*wWo6&!;NQ9mt z?D^(Q%J!2J{Hk){4uDjTkJ<4+AUU@;{Z++V2ex)`CY(8?gAS z)z#e%Lobut>3kijPQVzYf1;JH3%`*!zz1&|X~Cj-KFLq;t#EKMPtIHQX@OETYMKNa zXjPQ;WT!r-j@5o3e;y%G|51G`VM&K%#x#*$)r35;IEn(lP-UqGC!b_hNa`89FagxV ziQ5}zPk*kI0d~SgB7a%V@l(+b6N?$0`wG>;4Y_C9^0WC|h+ z$AHxuWu(ec7-6abNgHVTR{X-6?F^?#E{DP9FODhIfEMfd+%3C_uoV)b;V0o&C}S)y zzFl=1eNo!C4^_>hs4S=w=R4YLMwe979a&x>H!WI9(Tp0(k$Bk&NxZ&D(xQn_423UK zAlc|zQ-Y9##mMnqpR=qa*)y>(gOVdT#N?_5={yBUv*JPpF+0BpMYiHCITDEL+;iK| z8$&VsY`i~R^Gg^>7MOWt2P_`)P}M%4L!|yq(xkWvcO<^*zYL3jgea6bYPfwv1_zCk z;0|#_-Ao7G4QeoU@EMe z*K_{>hHm#I&+LN|jlgRJP3P0jV(eevDuG4L5KTMdh2|t`LquT>P`i%W*;Sn4!18zW z+^@+qp+=C*MJv?rnUD0J6JZGIwq z5Q}=-qnLi_I%0f+A?`Pt5Fs@ufHNx#)?Hc{1so$rXNGnGI;PdeJfs|;EQ8=)I}-05 z)>_h6TvmPt11fZb-O43?9lufjAcr>Ebqf?77aEh>6d-1AkKFg0QUrFsiOmD4eO6_t!O9{5}28N(&{~vB?p}>S}W*z;_njUI(oyJHMvK% zzRru~^qpdU$Y&9u^2o3@C2fqG!NkZ9*$#-7N{qvJpEXZP!jMGvD+c99lp~27&u!Jx z#h3)zFkSjDeAR-H=+#EdsX+!FjcWBE7kicwd6~vkkyyboA;v?;lW7uAFXr8Eyp{s5 z!Z=kK;V=>FRno^ZH9J~dqZGJ@G0UvLelCx7y*@XftOa;uCwhOFKGd%|DSs`~#<3 z4|^MHE~4${1j(quLo-L?n^z88lFwE+RZSFC3lW04S~~QqTpkA5g+G5JK?^x8O=Yq0 z<9j=MqGGRpVgMd(mgL#K-z7rPS?$%}#<3!qD6iZ**^!ENqh_%LY4#~p8~XkeYE?W&QRFE?k*UizzjwqwXeoAz-Q~HyTB%(14Cn~+`$+G zn0fA!A~DN^J4ALrvlWKo#e?y*mBl{hFOzZTFvPc^vv%D~UB88U1uWed@8_j1?Mbke zY&{_{Au$L@eXe79gz*qd;vFd|;e1wI?Lgrr_d(lIe0z>$Ag6jb8u~$4v82wXb!4)X zT$N@4>cgg!Ri` zi59VqY#)8e#FaHascgOol4D|}NkN>($$>t+A9a4Qg9pd^CHCeRR+gE=Yhb9Tud=qL zYIvMkY_>zRO)U~b4SH~5!12&h=N>rut3!3yO-4pWVH6U`LUpZWcH{mxZqRpDEKh`| z5a%g!?@Sk|bKv!@lan_jnE2Xhp4ULw|O8rhOo#aHSFd5@HCH6|DX&qc0&3br2I6#zKuc1{YoBvU7iOFyE zIk8J9v30j%Onx}CadqM3`q=$i*?smCV>n}yq}B^1mS`F2{BQpVsg0t)VbGf-6->&@ z;A{FX1DSX?e%|#ms9~EZI7xWY+#%Akuawo@vU3~PnwM59D=S2X?=5sDvlpsf=ikV0 zTP;mn+Z1#yR_IPvx%h8W!dXgw{rg@uICQizssCDfnMhwtGfD(iPiQqClX!>|3I_~m zHeLoxV_^!TzSmc;ZxKizO&DKyc8wbT_-YWdA(GuH_chc&*HLPF?i+2YqKlE0n?!ts zXpCuB716}N%uFbe*HTCHh3Y*Vr-1x|@M20;>f%|zAz)E(;h3yw>^$`w5hRWNN)BAz zoFvN{BKt8n=H)tj!iwx*uL1v_3u`Og8?rwod$^kZ+!qB*u2gD2Qb&ceRhL2eH!Bz7 zPm5YacGaMy9__eAM=u!$RY0^_-D_hyF{Y8rrgzT zOoRrml{3eRQ>1t^-I0_8;aIf)@xYhV)$sY%T7&*rOJW}8yBWdACaL~^c?`udWZxdt z%&>k!9yqkVYN`qf^mFI$nqFb6cxZ{QOW8h%^SedbUNEU^p~wTMK0`HzSU(Uk{WN%r?r&n@YTKN=mP z%3v+NM(0(Lg5Y+7P>ARm=CReK7X${cpC=+EqNP)j6&}T}Si}E_3n_2uRknSvt7~hk zZ*N(}2vaC>Jw5>1YZ1OVyHAFW1apppGK9)>#YwO*&uZPfKxF)0&)38F(aVQT13z(P zdsZA@wM3<|9(i>nY=2K^Tsd*;e*{h^vtt;lta;IQ66erf4%@WmV?gsQ9qQj>gdBYc(nEPzz< z@S&=IaNS<^g$~ZYIPx)_`4qw_fqm2du?kg#e^ANsgPv_s7SmW#7&*cN=>jD4qRygy){x<|BiSMzS=x3!SIQygwq%MO)T+B2t;%||b_W9nodDVr z;F+ANuBy4q7sJ~cNoL4X&w1%Y5g&PWe<14kLYa|KsgyIC2%lli1IdDhjc!oY22HDu zZto*E4l>-ec;7ERZNa+n&?kT2Gt6|S{q&=-<(Bwo26}qZWwkf1DXa>hk0p%S0r-U= zFe9E@Z0}9LDFZMWvVej!YjzIhRSX?;jZCl_d0M>GZL%}@M{8u&=}zZA@4XS!C2*sS zY;MpGe+NMv(_aO#*vTmWZ0mR&wwP13>GWg$V*1)jRa`Zik1YQ)Ep9|(+|;DdBQu%TQ%3)Kr<+XMFwR zC}R?3F=wM1hTVNl@FKeqQD{{a-q&WYkz@#ysB)7ggb9M#H=&vGGQi$1opU?T06i>Q zlPC(kjBxa`lFpjZTCTT;ag5W~6V?VYOj<;U_~;4i25h7wnn!wpJ{Cx@9X8ZhY+dl|>N-3|@eLaqpY zy=jYFN||gnC)Rd@?Hn$a#HM+N@E)*B7Tc}fx%~DsBaO4pUo}tvv^Ddox6hzCJ=8fl ztJUUn3vv|?Xhh*$PBb@Tk2Tv&Bh+Zt`hy!g1FILew|GVcv~cyROxPc)Dmg`GecM5~ z>@*hEq-YawsS~Z*loqJlmN05eiG!v^1UTiMcljSL^IY3^o^{`o1x-&*);E-FIKL?w zT*=^u4oCGInmkoCHw#Q(_`^SZ_^@yDvbC6OrBSDA!Tz>eiVSB<*z57O?>bcGsCw$i zhZHVC)yW=5U()PRye~3RjsYb|S`<|#I8=%(vE>+#ur^wmOlMbNYN8;vhA0x+p@56= zq$!$UtoRYVLlJ=IW13!L8{5z1!X?COF)v56z`*JJq2C|zP@X1K6$wMF6-2Z%l0aw( z9TI)fggJXbk!8-IgZQ7g57v!s-Q6?x&1)y|latQNwvJ9$-&e@w>-DmW_1KhC7-Q(4 zVnnZ62ohkjv?)nYdRr8j?B7g|+6UznIjxDg61z^1!ssSuE8~I^WXZF|(xtRQ9fin< z;!QUF*5~qH1DTBCZ!PlM7WK#~R^*Qo?*+3|6R0KbdSBo=Iys$C$FqzuhugNU*#Lg2 z0QwgIhfB~3GC2ln+b-H9L2Ov#1c*`3*+~>u*si1X>E=(`cm|9eQm?epo4`nkUSuBQja0iEfvONC<7ml={rgQ+)nh@P&Qo|CnB|TZ5qJoC=SJrG(S+QN+%= zVsRTnz|Bd9Y}Lh3s$|yi=)z3!z(fUdG{5y<<9MItd`ur1APYJEVP;3CNG?Pcf{w47 zQn#i;B)_&oGOUb;(oOTdX1~1#_Ue9^t`M620STl<#G`*B0rxa|CmOHtwy1_7DM^}v zZZ|!=yw)-j=VHQ(&hxk&%=j8TmbFWRbY`=$PPuO2{M97*yLtUhai@8O}lBp zrfAno=hI=Kox@3|8V6bvbDpTJ-pKLsDW~0IGJo*Ik*(8@;FXzmw&<7R#x^bbB)nO zXKh0P;LYs-992|*gXr%MrT!%0vi1b6o>Hh>fErrO+Wq=XLdR72Gn?P;Co2;#mSCVE ziGx{Cc~fA^m=<2dPL;ShvNUbdwy4}D zHbp^S=6eVnVfS?$AT9 z)wj#}lS4oNgE9=3`rDMT*j$+a{*O(a(Va;)W&aKw23oWf|D&}t9_)kXJoE<_Qt3~{ zfE~uSO-k}>?@dfYAg|sk$(&LlvMQo>A&`aU7ismhi$`f`0utdz>;N1wCy zHpx3ctjLm-wR~xlU7%_rzcxn~mz(&OwXi1z4(-hDO?-olO^$b+%i5D|Nu7a$eo^_vh681*vrBrRV>}r; zC8+42kYLqG25+cV&b9neaq?ykI7p4w{_0?1TQlVgjM4y=Z?*x``zq(Jllk0^LT<3M zJ{1c4=s*Qa)1}{25RlN-eFg+|(;s<=wywKjgW?nz;5Pwq+<}i*CqcbIQsUc5pPolQ z9^GyRd_V#D|8bbwE%WFw?k<|7=%+r4R~VQmZ3NTNt24Xy^we3>q5e)npohp&Ta8wY zsqynH4M+9r{{*ka%Ns$ z7VzZdY{N?QD!c0Id8iWbSR?+3FWvalNz;F?Q7n%5Xt{dIfFcu| zQmh8Ebai2))L}+Wk)?MdersEgjx#3`FK}^ET_6vZr-xO{`D4jCs8-Kmn|A4+oE^>6 z1j%{B18z?GFIiTZOT>Y6iEzA68=gz~5`JFEqB_T>D%^Q2M*_CAM7Oi@ni1|71O_Y0IDxmsz6+B#BzDkckm@a%CQe}qej1UL5 zQqdav_3693V!o#K;`iint!R@mt#@X(*DQ}IJ8997d6C*iK+aI&Yo(Hh+96GclEN&D z%sw4zT|1lg^Q|U+!~P3bSx~H7brvRHR0bqRYrowPaUEVr_01#nNW$#cz>-~0dnMk! zr;!{-Ab6P-uPRRIZ7cTsBR$IG^bD$%GoL^T&_8P=(Da3G*CvqaZOMBs8RYD7(h4#~ zjMe4_9(T@^llK01Tmv3{KbNC_oyz5jPnQ z5Q;((|04k288|&Vkhf9bfWB-O;cYvumOCOSNk&b3gN;o<&t{K$ zp~qrfdIezuF_!FX@3ki&+7n=Yz${2gy1&1d@LG(ynCxZLutx5(pShi@Yw{aB_{~@L z3OdLq5t?=WDI_Rl$yM{q2&1YDo_GEd8IHBJwT*Qeb>43JG;Qte)Er z=0Ed*CHkO(RQE^8QBysDweJFB-NGvS=17p zLIQO`;_&EKhnM)@V32*3*vwger05ZGZ5T9_HCvS#D4o1nAAhrjV}yR0u@$5Q){HB* z{9D3{+5Oy9iNpE(6ahMbpQA9^WhYGUQv4IIYo*sb6V8~N4sjXDKJT1axQ+)5w=X2` z1|_WzPT*o+0J)f`gdU1by)tuVGx1s1V+)~hNl!8Fp0Cdu`<~H(Wjb^v>-nw8i-M6b zxOnS4rLXO(ARV<*$wjeFM**y_$T->kCOb|OldkK*@gydV#t{(;1nSkxH`Hm39wYN* z#Y7g0y?pZt6O!?A#iMzpz++a&VK!Xw(6p~858bY6C?Yz#?=G1^5zsmck>OCpqa_wp z*VaZA2!oaau|a60n^L!HfhY$PTw;`o$iW?d|JcG;%*Yh922FTAJl`#e1{ZFa`FtY^7OQ}j+~Px zuPS4Z50>kFJDLDHW-5V=Npm=u8iDocQY&h#twn1PKU@h=%*Y~7^vYK30Rrw-e7y6g z${AbWUfBDNzV>3tRX~<1Y=nNW7%ySlRwdtA&AQBbUzSKVVosR@T%5Eg^A=@9*&{nj z;-?3wnHl^QQu(gdiH}-yBU;+3{%53fE2Z3ZOYA%i7iiFb?ewd+IWK~F%=Jc=qh&2- zz-M)E-Ap+qYAE-sy*-QEc%{J$$q5TA?`*b&ZPo+}1zdI*&OqIQqX3246u~~c zZX+HLJR;f>1}J{AX0u9jycP_>9N<^@*6Vf-g)5 zqP-jYxk15pI@Q+@8<|&ok)rvf-0}BxXj^=wT60wt4nzJN3UaggEN?utc88F-N=hY$ z^rAX$6kLm4=r;DV!3*5RpB_Ul$^7_a>gVTuy<(FeaJ|yl*r=FDy({~Po9uhdS{JrW zPn*Vvk5r(R+V8_{x1s0C`z?ahsKI}h`}&mkmBE1LPY)cvz7Ei|gigRM>PI*C-DmEn zwfjD)!X$1`(Z(@VE@VvP!|2P(Ml=PCZ?BFC4DRSy<*9PoLXFPkBk~g#8Btc$Fl+XW zmtGFg;)JebtqcuGsQ4|?c>f6zR)#@=1W^QnG8Q|>jLfZ~9+omo@R~fEAy|6oew;`k zgt;1n-%>{i+0Hzz#gU&PmDO#9P;l9~+4CY&{{OfDtCQB18;2ep8$gRNIXMMH{~?5n zJ&5EDiy$ePOWKoN8kYeDgbLWHgXP>EEUEmt~94l8%=WTwSrHRk{7tBO_~Hp=rrt4q-R|BhY!;q8dg7xGKL zkx7skAIb8GHD~0lEve@FFDZVh3+M%4tQ=c@W#q2w{KX5vdzlP^MJhAu@lzQwuCBa2 zHU@hZj&`b+1crYJyATWQJj1su2kqc{bNtnjQd%ni0xJKW6qj=5^Jew?MIbaqxD<2G=O zXu4tZEy6BJk6Uk2S7&Iwq=zRe^k|FE!PIRf)%ECp?L`rBDHYv2~2@ zypg5|QA*{^`;ep8`qFHiTOw7LES*0#P<7W~&%G?7ckM%;zYHBpW$={9ey$?5Pq^8^ z?|~?!V7|E36R(HQFaCyZgX-KyU*EfQn=<6O2Y^9PQPc2N|DOGqJ{k|EPS#KPr+X1ut47GC*1DW^ydD@owo|a)xZ5*X z>RTbqC-Z`;Ao>onjPA%QIZVoyMakD2Bzu57m-K$^adJ{ku;JLNRZys-(cQh9X3+Jx zos;j4VTh}c76tVEmA?mZn|6llvgkq>9>#C)gt8JZR*Y<^&&OU^d zD%BH4qn^5FrZookBhm?3#TA*wrIWzYDPNdzh9CDHQR ze)_H$^5d3Gk$~6$+p)_!OqLmxW~0H_{Bc( z!8BGTw+8bK641g<0K(hZ&E2D!)5wN%tY4r2N?lC1V z#*Atyz5E#cJUoxVv@}j+2_+WZ`@u4#or+*}w4v3`Sx}8NL}S*~=&iUe!kSch{dKj6 z9qQb?ML1ET%r-jrDXB6YNqonhR_xEg(CbBM1F~XJ(IsnuGdMG~!89Dq*KHSKpE7-% zd37`;ZRNI<{V;Wog)3jomeCKy2j9Ko_^!Ih4mlPs2(WOpU;Ac5(l|(S)b6~{{rU*! z@WehGq)?>QxB`Q6a&R~~J7=fE77c^UR>-~Qs?F(odUs-PkJefr=b4^|t53J85>Y1SYJ5gDdTs@#g?FD>EW|cC5Me!k ze!!oPU70Xe_n-cp`5$D|V&Mk;)#&;7WBh|}V9_FX^HSqxSTRhhU1lR=?hS?OsdlTs=o=< zQpvn>KCAK;BY+|9*%Fr!R0|*}XLYmK(T^}?c3!wr-P}I{A9Ho}=0{y3D(5$!V(HKOQ!D|TS&40 zSAF`?dCy?%gzs3w(D1fGxPwu$95r-7gnJFI)O)kccLc`Ir#qvfo2C8r$4htTl;Jw1 zi8Zcyz05+_$_eve1QG9HE=qccfT0O}MDcq|%?O-Eh*JB`)&~`&%r__;zG4|WSn98T zF0i#BYcDH?<4Srw|O##0lfmiFjP)aWd;&t z`~PfoU4+ieogstnp2FPW;x2D#4ywd4Ku?QfCNx6LdwRt0W$Csod4E&Je6sNKdtX+L z-9BSmRXv^OZsO=wx*;;}DD}O~2Z{F2=%RE&Z>K{hR}O~u5i7)9MSJbrvDAtvu>q%S zF{b?KsC@a+fRPK}Vxhcs{{#RPd)BRUryi>S*5~D9(Y1tdak^@M-!*xvSH?#e8L#S2 zPn+kfD5nF#w+<6Mlwgt$n+0Db*{k#0DuJX;*|uGa8Dy0yR!>^ad_vAz-=Fm2=1f`x z(BYKV(vsla;}bCEob%B!zOQy)qJKF(q9>j#R+Y-b)e5oAs@5_E6JJ#Fa@f-vr#7R3 zeMa61zslCqEnTQyt8v`SHotVl$ZWXv(PsK)uHmPsF5y4>Ug{jTR(#>>dGcD|S?N;e zuaFz~-%T6#%=BD!eo^G-m%mKi;Aim5r}OE+ty3Dwp_22Njvsr#3A1q znk+`jJW%Xev5*VgQGC$j_?jkpZ2HGigxc!#yL2A1bZyWo2n@5D+Unn5t7pNHDavhM ze%8MvD=#(ZyTqSOp;SJJpo`I?T!4JBMSsPVrB?nZ;na#<;Ea{K1vm(4nYK>+Jl9gi(}(7NE; z_cd6?5^h&#g}w3Y{?y2QuF6SAoDQ^YS?Hq_V895&h5?33(~wzRgk5q;j4i*8zpW?lZwq!oj$ zEQgE-g`85brP)qi#*NmPYnbY}rXoa(WgL#0)}YbKc>lWL_5%BRdo6n{q9;?UtE-E8 z0BZ{%8L8BaQMIQqjwZE_&vjY^&YEO2W37aO9`YPAG&S(=}Hv7&5Rq z1X4I^kp6g-4PM*}83ntB%h4BL7IpGXXdInIdt$3UZ5H^!r@1yC@-<#-EI#l3h|Pa= zm%7pB3OXF$bVIC;mBD?tZ%hIfh&8${k7%B*G-_FusBcsEjc-~yen?Xm_^;TpNIe$~ z3k;&eZzjrm5Z$c%!>tL|U8(9hpO8Rdsri5BwL{O1&-{j~hkNd7GNhhwxgOKRo~~M5 zzF(hwibn#O{^N3KyCXjn%UsIh5Bvpqri8tdx@u72@>z8cdI}QfMgu|69#8&ZzUZMnF&ayz>+|8XuT@GJ=gnje#TzSi)cPMs3oj$<(fq7v^WK8G)G zO}8Hl6i|YspBFPeTwZ<%JmY#8aW8N^vC;^b%6Z!Rh*K2w7{Ap0+;=L~b(gKe*|s$l z^zmauz;r?9sey*beH`Dk=*?Ey^Cg_>zD7s@xa}kx0DsAnk`e$d@ZVveS=pVZp)7x~ z7ydqiv}&U_+o-fLOB$^g%)Lk2 zSjizX$b=zGct3c`g3GP>-_p$<=g%72vx4P){-P!4jG&|zb=y=xQ)$^ zQOm++tWcQRjd+GxJ05EU9)|3foDkP*Z_LnOrV7U|r}vT?S*4p!XnZjX*kUbS$=6p9YtnrZ^ZqVP6d7YlN7`3))x~&eOWO#`u#-l5NBA zPrnuThL8;mI_C&fPa2ajYZ}aw98LO<#c@>|i4TKY|AT6?Xtsp~x98`&o2$v^$iKih zHwAqxW$-2@CO-c5-Koq0h8pPB1v+&?;kQNg2%y7qwz;|w5WGMO zKKGs|;H7$1#Jak?EbMX65Qfe*lBM&>dzHMvk)LLMMVx^Ptct}qS? zjS>(cxG0{eZeSwacho|=HnurAa#OtTn~ykNX|yr>@8S6qP$Rv#xF{qj=-c&V%6)v( zS_CjCl&P5fA2KOSt&CGxpJ+B`6>-0g1!87dV1MW{beJs$;ORH?{Mqr=l_FA7JweaP z_cvSxUaKK|!1=wL(*R_D42rZ77Sf!Qdpw(`<N=-#5(FDekD zDClxS%*;)fX#{mW50D1l@`b4c9_mbY8f=f&-iOw{1xe^|@r}%XDLq2@xj|O|^zpxL!+h->5)w_Ngc>4`;P(V9&>qTtQ{btY{`hL*W z9+#w3q@LuJJD30V^Y$shSBx=>F!-^;M(>HrS}A7ir;1Vadq9+Zu+oMJ&nKX z`P1_-H6+w?)!&@B=`lB)9&|zo_wMT^EciE+@pOr}hCj??oW1FEeE7-n#^t`FCuphv z;LY<%TkYM|^u`}_q0Zgs_QOVn$HIi?A(fz;WtFF`(*kj!=%wxem)dyv!hySm#r9r~ ziylPc?+63vAWQQb@1j)nRfU&pqs~$27y^o6P@g|15WJPg4Dl%(EPL}f(LAy`G3zC!=-)L!ru@LIbR-{Y+|HZ5XiW z!Ub5<3q~IrLZHmzWNbeR3&%5F9{1kqJ(WWm^bAhe_9fyWt-bWBMMtq0(R)nv7Rh!L zH@IT*->hL2_;hsmL`MJI7>F!x3}WQC_uvxT2MHb^ zxCaQqJ-E9jxZm@BYu&S$-@u&i>aMD1?>g`W#x?`lC=d^9FJ`psE}phdPtmYHSVXYF zL`yLwCsZ-Ijatt*TDq(E_EjxiCd&C4NFpBzLSn@k_MW;A+Ee!}%D852!c7T&=#Ohx z&7a&X6~xkTtp2_X*l>jue?rE*hp|?4yBRd^HdI~4C)GmI`OdU1Y_DX8L?(7b5C=<* zl?!1B=hpZqNgj+iB}I89+U#Pk?FYBSwf9y)tI!yyJ0`m4qnfp4FJ2RP`-v~$GGXU; z`al%MC`g&zM(T)M;6x#-1Wr`d`W@tm z2EI+Qu3t^p6+9kq1ispa1j9`}JuJRXH;O%G?TG!OiXhq$yWB2lwUYpIPx?JV&sWX` zNdq>HBHl|ZsuLsi1a6ejiTS+sFX6KZM;c$gov*B}u8KVmh@D=3sq>hBVO>LRvTcT$ z=e<*uv(Y!Yy!pWiHfE2UC!Kk)QfU}9 zMdJT)J@&lBwI^0sumGUQlQS+;Vr$}iJ2kVvWd0FAQorR^tHa{#a66d!>T7B901b@CEKx;4glcP6-=)<^!h*tY`X#)tBWh)P z{40+uZrLFgrlQ1WtN2YR9^mg1q1jxJe=<$92}Q-YwTX3Dl9_D_-^wa*MrzZD;$^HP zE)82Sc@@gY#yr2KBr13yVAeRhtBUNEPTK&}8>;5b(3KjOI#U`#f;19s|I1W!IR zPr(JRYh2tqi?NBGURvO5C-hX>T;9dgBKtRJU0t{Sy z=j|{7f-hT!} zT6L8iP{>TBM;zI`I*FHH-rimSF>wwP6O(X^4**m|L=1}fX|J4R$?#tW^k5>!DhJ3> zCG8@pAlG1b2d798Z^-b{Slo|xBG|_J52dR_ho{XXOUZ>xBG1r+t*r#9oN$k7JkcUgU{GVZ<-y)g*+n*5LAuCv4!rT&AxHId^Y5Y}oVK}2So8FIea+t>v>!@PT(Q=BSkus&Z#N*f8JiVS4^RfQ=mL7yl zqp27{^cO~gr-g=wvvhY8*W6mAv`wd`*(%b=z6K04E&owP9eGO-qCgiHhZ%h61EXqo zg!Upg^5{Vkp7S$?iiD+E5|^O{3yNjwn)S=X5=hsEvwY&xs%^KDO4!jptgo1*SlY#G zA~Q_8T6C=43I}m!RZzp=0Qs~<;h4ErJUT+hA$?9EO)e3tg65-T8}0Iz-BK1#9V5NM zqFY33gq=&`OGb0b-8VmT+f4#b6(L`x`iVdV`0(%~S~;sqSRO`4pV-`O|8c=M5#eu8qLzwX7 ztU~g<0?&T=;79de`Mb6{QmgCh>y6g$gE9czi6rQ8wm>BX*n*c{4jZoWcMmNvy~~!y zt9~nb11<}BdN>C5AoiZm^?t{xIyyQlXSd$M`%@Y+P+;o;ZIGY=-^{B?u^>MoLp=do z+oR}*^Tx&~;6}P1MfMQlpiD8&?5^EQXmG@6=p9v>fXZ|AFYh!DjKFV5>T<+;?UQy=nU zse_P9oEl#EV8|18941IH(|={!l?i}ABx9fd&csn8!|qkEJKT3K+VQp^g#labYpZNI3id zHE*e-(SZedvIg$YLuy>w_PFnU%!`rf zCu-8e%ncRo$Un8?eTyk0sSFF*Rj@=ha;xxpyq)-mUKg~1Ubi?PD|&Ta;5)$fyoXEX z_b}2?q$m_J`spT4uP>`}K!K?m%$DzW{`8hNyW#FIFR#LJH4$!tFBz zWoFs6$+oRb3+k>_mSGtu$gpIpj0}#pUGIP}%Ku>@7kS4V0I<2hy3=a&2Lqj+s(Cv= z_-v(tl0_lOIjnk;i*_rFuO1$&s{$U50nd1dIN=eO8VUSUb0HdW^s_m@DD_FfJthm8 z{l;ex+x*(Ja9m%t9-Tz^Wue#(j;UM^aY-kJ=hm)QO4-~ln+1|}!26|rJbioa>+brW zta5&{^LkClmQD}qUP>0XVjiZ{2)OK3IGYKN!^?&ZZ)ExQy`?<^uS0JLqUC(+f}naVn<6MviB>*^eA`=CTRugg4Ic%~jSjDlekBiXae)tLd&SrQmqB&{ zdMIKTOvx=!9Ln`r&>Nr38<7(cJo-8G`gC~W7plSL5b#m}(<|ib(sXcY)mYh#F_1J~ zsI8+jzz#H#53rV9bN^$!jml>QPO2N7dS3ii&gL~#MZzm!dhh(o^E^k7AJf&F_?-P= zY$8_~s3$)=UL9>XQ0KGvByft+bTdbQk2G!ns`NXUL870JOq|Zx(dbeE(CO;R4KVTt zO#PXvsvy5dygS>L*8cnfOhriIhZv_5s2CLQ-Aj=NdOfI-E9J{0tUbr{mS7A2*s3eY z6TSO4@dYB^eq1)=Nxn&1$|MpKJ?>J83Ey=F%u`r9a(It8pi(~T)WQb>{vQ??x%}A6@SeaKA1cgF%Q{L zX8jbncKTQpS0^^_wyUMXw;p)+^?PPZ)DH&?|Ys@3orFALJJRyhC1OH`tc};>y-P2+Bb3V7pVvKGUP&C8xms2*Q!p(6W%-z; z79Q2Aq?oH>7x9xMM&k0s#BMwDvVxW56|Rov!EYe`e-;4gi-n#Xj8vxR5w3-T zTjLa0mQ-o9oI-NK?}jUUOk0S;ud(y_VL#82Q-P7+j10na28L4T5#7DV}$ zECaoAs_(`OA~*RIpw)XqgKRLr~ z*6&a1y^!jTYauZ^_5C5xtmX|e8JpngbI+te)XP$)4 z=uv=4v_Xw_%Zi7npXcWn2@rwdUGu)k zAl&dLTn30GY%eVlda|?UizzuFCog=KPYGg;%E_)`j^Ke%qRbRFW6elV_)lWfL({mp zJ{<7_hI>m6w@)vg9rI2tf_W1_L;Lj90dURt?2s>(DdBLVVUVPX-pSMf3<^*%KLzuQ z`t!z_y&t|RQMC7pQcJki#g%Y~6f&yoPUbd&-^k3obuD`zA8uwH`uiRQXzpk+LEIpSm-!HOV z*WI)6k!}XKs{{_xUC5=gmT%lA^tAo`5P>gt!gdj~fUWRi#@d{#;dLi=koB?=FpcX~ zv&k^|ytLu7hL9f$xOp2~2;MGubzXkwQ-0nXHNKtL@SW!TrkgxiX?;i{ew3zB9s#)8 zKPPsdwW&U!-<>W#KXj0p*j_U$Y2m@0BrEy{ScH1;rVdIJAZ{BcMmNt7 z^Lk!;q(d40p+5X&?`G-BA*X(YT-ln|+TBUEQ%ga76k*erlt3ck(e?AnfB!z+iV+2k z-c$!2`sDzw4mZ~^o4x3lx#t%+AipY^zBHV)oQ0#PG$c)Kki~(GZaQd7l^^qpPYb56 zTBoq=Uf2$;(Fmi_aH&RLZURwU=g-zR~WYrwN#BS~H~TDBh;wP=3_1L$^F5 zVve6#z-wuatxRF^dG~VA95@yUe4Xm7;NBxsj8|nzVFA+9;ZEc3O8--?(S}GMkwG9UL=DDwLZ)J>)Tq$ zC{3Lx5V)rS*^r5~cD?1&$0CM>?C?L`o|zvwlU{AMFaM`nkBNQ>6q8Tca=Gv(LF}Vn zkrxrV5)XPZb3*{b#5R%1s1aNiDRrt;3a?TBT#^HZEfvZMv1^8wA`cylj^-)^fq-lp zU|~AejCFN&^_KxS>%Hi8lD2}q$M(J?I1S>i+(Zn}bO=OnOv-{;rfqrB#Mg8-dz%_BdYNL_ zwU=69FAu}syY#R(y6v65%%sMW^U=F(^=y*IE1lOre%(I*s@_h0o?f|r^MA2~z*L6i z_B>h#?$K>nTy{c0tuEurWcRzu5BBMh?KGX|z4C|Q%jNg}=lXJPEuD04|H@x89v<3G zHvYY>-e#Qg^gM4_zkUBi@2|6Sot~b~*Zntsha<;7H0>W8*?lh%Br10rssb6lr%3xc z2>!^IQNr7PQHWl6G>sK-_i?YY_#&ON;4YIC8#g;tC&^k zV`QxFSIX&p1{lsswB(_h&X;1qSolg-?st1_V>pZmI(+42RZwS{OmR`UmUi-wz3eXPnkBc+Zz z^mHSlra|}9BDL5(FPk#&5n@CS&91HrO=6;7H0BFqTb9FW?81zIsQZV$I*D5Y3Mkcv zQnue>!T=8vdX`A8(cZ`uU1PkczZP^E61EX|DUYAq0{9a-wJ1sfYoi?v6lt6~-hsb6 zcmgWyxsbT~QNDeIKU35p-p)_T>{M|0R6a32jv#S)Sdu81Ffg!@u+yYp17tsEXO0WK z^`A!gx*Pb=3S8&4-e#|c0En#wt~}6idi8I*b?^eb^f(1Ho;?fF8No}DS+vpr2p?^m z!hrI-(h!sbYvrFi{;yamU4b$IoA)Ci`1ZR!J-T^X3F{jgiaha#g;M2B+id$7kqiR@ z<(LwyMh-r{mZl~ou<)dFb518!wj7vTfl@lnC}TeyNX3>>c`mwfB;jmo0PxY4wb>l4 zkAxworp(E4v!_Gx8&|Hp-&Qq`UB3pp}Cg()x$yZ)h##v)3TeI`zxp$?S)V^x>B zm+>KZK~Vd5b2ipPA<|bZy^%C&Hm$4*Nx>Pf>cEHh79y&^Jez>?;WzAo0;0V3>CB7o zYl#;>>g!$3nitpoF1nB~NWAa2q9(=O0R6fn*=@G=sTYgNk-J#ZiNmlOzA2BWP>PBF{f-V8fu*uTc^D zu87*S2VWsextKpe_9No)4u3+{=2ysLH`%?!CQ=9)3PqJ2xa{s!-5ZLf98O<~Lk=G* zZsEo6M3^RN-Go@f74H{9FTHCNZED~+upgVluQqPsin1UbFRDPi|2t4wUcpo-d;x1$ zs7j+ue!XgQ@ zB&M=V@*4Uel;L0XDf0sRC>C{D+dMR8Ljn7#-&dU&lP&e_7pj14hjTbxBgu*^BjxUUwBX0<~VEReR5Q{Bap3{IEXSi zA(dAV&=4SoZQYvGx3;!+0guSx-BYv~KS^C}?cde}NQ?p&g^R82`xdrP^8cJsKB#DD zBNyV>-l}rnh!Jt%LIt0N?cpd!31K&zP^91!ZCklfm4I=of}S_pr7mG(pK7+wE!!lIZ@orvDziM|C<8PAfuJSkay1U{ZJo`}c9LNP}Y;7e(fg)*K zkx?sGTVc=@wiHI6J>UkbNa|QlCV%my95s9RGsf*7@^p_e{D< zYdCBCa)01_Ez>Mt{vw*O0L?x!|4FKqtksNG%OY!!#7i1SK1rvgSh2d^vdl&UPpROy zE*L?csSu~OvR&KnVMH~|W{GH7wn!g~&cT_mA>d#y5zmA>aX{#%AabPtfxX4n~9_J`Reuu=Y=+f&8)pi;FFO4ZA0Ojs{qjgyirsO05ZNw-t9DN=Be zQ9sCKakU{cZ12c`J+z*`$H z+copE>mv8PeVspM9*Ew#zuX!ClnxLD=-kU)L35}7YQ_A@ne*A&mFlogejl9?6D;he zbWBoHLNleLEWh|eitgn!TRvcJrl73Zdu@xHZA+kll@%wNLK`nwk|o`-W~8f20Qi0M z6>eMrKp>#FRRGDSBs2mZAMk-y^M-nQw!AsOZ$w4C8knXhc^tPwMs~SX&*7D zXfU#WLS;a|_$>$UoX9X%*Ie>uAlN9d2C66cSJDS{a`CG9Gyrlw@G)v!0tAtH6H0(< z((380FZ$#SP;=_M#Xy8x;Bn1$B;eK6N*{D~RUtW23M+j_kv`{EOK+zPTGnNS;=3Ii zNqNd*#vZ}bMi4ysG>le?t>>hDwzAqkoGtWVWZJ-JDKVJ7El)2$$?Px zDN=e#kMAs{Ey-gIyZ-F^90NhF;I^5ej312TWYYTy#=FR(__p0iZoxQo+FNF5)Yq+p zyxrXhkuL@#P~A|gQ{unh?GnmYj4Sr$CwY%p(r5BB{?nuf(24Hqy@Q*)dKk4*0Q@5d zigr#>4TW>ELGa@Hyzfer8Rf;JLy_Nc&!I79s*(%EBUdxD&S;q%rWXC|z;^&E25w|1 zqwH}en4Od*)Rv_Pp=VI0+BuWJfzNvTm!HfYac&akKNA`xpG}L7>)Ij}8rtMjl$DlP z+G%Ro?mj5`NIQ@<&Nb)t{`kuJA^7;-VGE3zj>Z>JA7DOC0-s4#Dd=xT1~U<}OAa~5 z9wPLO zJLjI4-+;#_Yx^P7bCF(ltl*%_Jb^J@Ah`Tjqoxl8o*Jtbj+UtNGe}3Jt10@erg(qj#Mob z(EA5kl)z(cEvSxzP;}9*@*`G(0;=60jSDR(mI$WheivXHP!TML%--1JpMH5WYUYbx z$VJCAoDA%as%oJ4lBERb$AENy$-&8qH-OFMQ{BoLCnG`PumTOxMD*(S5UJrY(W zGP0JA7r*>aMHCjIxhbc}o~%V(EF6nGI5hE7MLm8xnEKl2g? zAgPt0RolN6lH0S~j-Y#>@Q4PerIhL{{bcms4zkFcpvdc#C<~0)`Q=)ghDj--o=YDO zn>JzH{EJA3Wr$<{N$=R|`>2Fbfyq$?3WbGsY^ErvETkkm8b>U(iPrR#YDrrFdu_;- zlPF%`%!V@y6e3OmMGH$3nH#9z;-4uFbaO<3is;Q`U{H8L5Ygddxj~;b_(sP#jZP!! z7U26AaxLEAhyD)nnm3SYYih^n?o&vYqCy3bNmb!{vsFeD@Q*PH+tMVWk(>HnsVWm~unc4RQ_n(=2h z<&a7&%8&Br?|`UaCog>Ibw9Ep7X98t0u?G4x4IO`rv~g9{?j7@2XxR4f6ND2T1HcQ z7p_s8Af77>qZD|F-m&(Rc9OsmGR#Pd6Vq@o;7#mRdhon6a^9E#>OE{T7P+}7AQ}F9 zUp=~P{6YsxN?ctLJz+3d-m!HSWyn>t3Oxr_9gehY0!iC`w!Qy`*k_B|;<$eUxQKMZ zchh~lW16I}70KQx@ap7;QqceMOS9QzwYk+{Due3GkyuU(2RE9B?=q!-1g9k!rXX{L zX({*vgAoXLm0leNfP`T|+nJxp5(RcnKXEvfUmozC+TY*5z4gSAjip!r?J=u`ACZ<2 zhTMw)N0>+jUXl|t?kuyLD+P(mMOlkKKn`Hwxa}m$f)~zMzQC4k4-1_%&R4+R2MMu%Z=4lJrHk|5RPMV4jQAWAkCZvn4(VAGQ_G+RyVGRn0 zL4wuH2kF|bml*HL2H$X^HA9bRL<99fvjAd{al_Y(P#u}5m1oJ3p8iqYJa2;PUHkq^ zBcE)sB)x9)x2#u8am~{Nc01Ma3Xe+0#=druNCQC}w34OYVJ(1I#=?zXGhs&!&(uU8 z;vfBoerR<$VW-~HkYV0|7n*iQ=5JCqy9|JcREfef4!k@3Ru4#+fFxIu;b@<0Q%@E| z-gceTseDq4|bqIlt$rZsU@LjIF8ZR#6mbc3$3E z$KCJ0_ZU>cFu@URK}*N^v~AcaDxIYRRT>xY~J`Swg1rv6c(p?TOncQjWZBg-*pQ$6% z=((H%2K1%w;9$AGj2|mkfB7Pp@?K;%>vKw-`$n2>-J-H7CWte@!_e2HNrqHH-&1lE zq2G?e%BeOSJcL{{s``V&*UtA%Hs4Jr?nv3=4ihDD+aAgB{l!YJw~C1-krmGtR?euQ z*2lMF+%K(8)Ne>euqPcL5QniY`!Di-{U*GZrjb3q4`_&s>6Zc9j@+y5_HzI@VpXcM zgm1Ji)2l<>2Z*68A~T2Ofj{4smO|W_V1%jsVw)(TgrZ>Zx3TFqDFRfA84iWy0DPuk)&V=<4IsV9HDXRvJLSW%!?180Fv}52nvB3>mny&ARcZ@pa zJg)F~VRP3nl9V_kuL&1Xc^63P$R8Tkdy``#z1 zp`0P9+rY0ELRo`x)={Zxx_^Q+S9PWsO4)H@YApcmNIp|Nic_il+50c_fGzI1#>b6h zSb0q>ls`fKh&rZuLHuS|Odczr!(1AL$|JwU3Lye)=HZc!J2|k$9!trvm*=%UqNwn8 zGO^8fJCmvc>TO_hK6*a$cnR!rUB`X>`brAA`~&CqG%3ITRT%}BtQR2m0TqBJZyLnO z*}0>(Dy{u$;-&lT?fc#S-;7UMZHJj|wN`a&xn$vx&H=#OHOtGO7(O|4)amnaP1<7RvjWb)XmRo(d3D-9Q zw+SAdMpf9?-lywoW9Hu)))!s3cKeS*K;1P!Rq$qxZP=9z)bDctXI8YM4h3!WP!LJU}8e&M2+Hf0c<`v~YcCZ3Q zLjL!703SMF2 zbqT$Zo}PphX0-5R2#k(DXVw&rM1qJZL2R)7UL4HyLvcn7JM&6ngF>ZVqnI!Eh-}VE z4>1m4Hw;V+sL6>kb9)jatSmv&(p}Q(m(x)s$aE|;sT9dXFSM{6y^0T0)WdYq9Z_?j zoiiQilL)#`EbBWQaeU*W&J(2gJQKu317IWOlE;$K;*8Md8G4%iwiE?8^EPTYbBURc z#3}s&F?8m=4bfg(xjuN_ye!{|8jgZoCmcawzTGO&e*e`NCU1qjIgm_bj2iwngq8g7 zSdTKri6#e!XjBN%o+lx6kC_X4BFoVu4zU!1*ccf6*F*}(k)9?`PLNA;sLXO8Tl z29Gv^+K;~sI4i~VJJ%f-?rxeO-@P^Zu9VxD6;p&cEkET+!18z)a`mOE)5j-M1n1C3g52){*)7P~faX4TiwU1wl`#Qlf) zzQ^UqN1u7-tfvb4U2E48iyuGy^?r_EGZf+Tx~To+)k;-ge^%Df{ltv(g{utx9pJ9R zR72mZ%w9yuX{pqs$521U-f9tfvi&Wf)z*P;ExnEhmYxA7+08T$2@PFUppci)-IJXl z;aV4jE$QBVwv=Tw<3uArqo8j}faTApa<+d2my2rhCHKlEus|DbLU<*hW3w<1_4gGT zrtMba$4Q%Q+3~@U3XV~?c!KEO+T8v2oh|!4tTeOy)fzm;TAS%8~{xDqJDKuXoI&zaD5NEy3_OR9KOwI5H9hvE-YE za@gtA%?lv>Hpi|+eO;-#C8snnATdmDLDH;~S1YzZA`x@}Eb(A(%C6z zWq)7jJ5TsH&f9K#ys~(yRsA3KJ(=3@bixOsIyH3N+vb#6?`B&7r25>p`Gq5)6N_JV zv-d0oy-sHFj_!(Q;3JhCd_35y4Vi!i?e|d5_ zntJ)3ENAD;ja`armTR#vRbDWwG?jT&?kk!$tYVWINpl4+h}=N7W@G>XCq7w#tkm|Q zF3@ejV|ZjH3#L)Y{$okWH_W;MQt`r;Oq3cXOtH;qae8zeCG2wY>omwTT zdg7|&Z&3MoOC1GmO~G1Yb#){WGp1^cg|2IlLKxY03@D^GQ)Zkf;d7B`<%UMYBeWH9 zEPb=W_aZ{8+^q*>`{fIQ^$tu$Q?_RU(Eus<`O9z$MU3ei3pI_i=!9;s@+TEEp}!?R zTY)tggk`R9%N8x?d8ELYbui=fv*f^M-Kk}9VZqAU8pg!QDPfnR$*{Vnra?8Aq`;2= zG^6nzesa0Me}8O!OzG{=+z;vEC%ek|^J7tCVEDgZ(L&{;!G&+$!cNWlkl)ibY1A>` z?F1oGw^diKB>fM`;}fF)2{gKna@ep#5sFO4z%6*yIbkJg_-eTcIH6t<#2sa3mGioo zE;gFEa4mFSSE6SP3D4Dp2h&XO=^{}c@rLugT5)LQ##Ed|`1W|d$WpjTUzR=ZR0-@RU z5M2)Mj~xfV^ibDuk6#JfwxoCh>G{lvg^$kzPzyUbu~)~bt*%bOe|_{N>s^B#rQ6X@952T-cN_*$OX8qtiIYi2Y#!7YN6bg+VGf-PcF?48rC2n1XpKb&JX=rSo?0C|V=tuBpE&s9Pn;oD~z=-=rA#aJ;V;5^`3? zu8`@ko!-wj=PEjv&cfmEsF44*C(&in+b_QQhOo+??`AF%Gw_Xdwlt7oVOTYw!4`@z z?JZUyb(u*>MOFJf!j1<>*MBp^oK7@kDu`ql#7>%637?&nRrJk( zp}DiOx|tN?&Pva7FWopd>xe6|#^N$lqfYGeed*JAm*EjP8tix$*ru<2yckq^{hg8p zxo;MmGwzI#P!!KATzOLJgg4?>+Cnd(wN+%)q1g~}uo(fOIsv@tloKH9_FRnxr6Fgk z2_s9D&z^e-bphM##M6%pctdOF@Ddg2GYa<5%C6#ZLY5TR(`sfoRkuC+8N*#LAJ<=~ zWU{SeaYVIj@l06}Jcw3|h^H8NKpYv~L>&ie%NTC*qi)8Du134Fa}^+)0D-)vWrQ2P zMO7p7j=z*Nk-5^PI6Ums*Q*D&%ZPDQ4k1rzp7$igScbk2w2(ImM_|Y=5~%$h-^<)v z;&QGZJ}4I$3z&oS^Pu+IGHx{-My?ejAB}bw;zG`K^DHQ1@N+zSo)3Q)HG<694a(R( z_-Ym<;NzE(pW@=I@E*lSOMALn|I~l{!U>VUL5j|HtL0{_vFz2V#o@cfl&T?2{e%cA zR1cFuG^A){=qz3lAEP096NOVFK(;D9$`5Rc&ZcXQ8H4_Yj$JX2HUd8mfCCuo@)^KY zp1ZgIPZKfdN&+7$*q;kGm?1|qZH2^RF^WGMQawa36y^;#$-`N#N0;GGa5jqaYj40_ zJH?XwcNMeDu*?&=g~fgMbn_fI=2&{*o;?8N!bmfcm9DCG^IuowbCzP=hndqKuhGSM zL!bUte;+4^)RK4QvO}6zg46MD|DF^W)**6`i!#wJvtihy$W~rt7Jqk3c8G(sHo3wMSSsmqXi{6h8R$pj$Zbso#WM&DscO^;!UQNZKW~ z68PJ~lS5f!2!L*8h&Z#9kUOwv--Aw0PM&V_9(L)1mfmLEuDnX0*wE5vC?bnM@W^8p zAs=R>nsrRA%}nW97?0MEKF9rgT0QXwUbv zgGtgd^fC}72;hZL!dh`}tp3Y-7Ef+{MP$mFXac%i!z8(f3Tw}Xz=pHm^P8=|;#h^W zzfiPkxmrDVn~xN$bDeM}R$P&U^>Xl_1xvds=@X~$PG16Ev>(tAsZB537am`3=I6CQ zc<@DO0wC;A`}kcQa(ZMm@8(GBh)-Q3OguLNp$*vVRCVc*TmM_Aw%MZ3mjhnwJ_nDF zkNea2rcMXBZWB%B69kGW7Ot+Y2NQWYgit7=$dws~LRz_HU9{|Oq*xVAsU|LRyc7En zQjI(mL<6rOywUKBkwuS<(_V21MLL{NWM+(9jp(SlkdiTilksdr-!tISjmS%zv$GJ?J2zbi4 ziwN21O1<$I+>CX0{=)bBiIJTSpI%rE(nyeF+{&i?(TjsB7!ZJsK=J}u0p{4XUdFv3M7RzZ|>NX zp#78!X*L~#Odi@hcqbT-5+IdfsZfb8{N@9cpwI>YuS~lt*uRXa)h4t@e(`g z;*l8iD^bk%lune`f3vvnG{IzeWP7R$G}U%c_P0&7q#m-kSlmRLBAV(-a<=PI@%1ZU zIP-N);?Iw>S8UbJ^Ye~^3LaRgeU*3N&eZ+A{Li}o2KQ_phttK)^u(+xJXcl=*9$p) zgRTtq22at&b)4si&Qn=*rUKsyjn^sDVWV+Ux>v3bL)$vhqn^U*Evs z8g352pZkX5jw^%nx`I zwHTxks>cvINyx6%`PofyKA*Y~J5}b=PO`k7_sz;=o^KJ~Iia15a(=!<0xN664-UJ6 z_RdTtMg%_P7!szw4_wPH{Y~_a|(tA>% z1h(`&;^!VMg?Dq6*yo3Pn#CP<^85!t zUBELtMZU?vk$n7yqt+#T~)ccF*VVl#zjr8JUzHB`(B1zfg9#yS#Wlp=D9N1 zJPE1y8W(KxbejkEkd3AtzEu4le4i9ngIK5s$?>&ka$;~3$H{fWC{l(4+&Q|8*w99T z>Bxu2$Tv;Fu!WMlhAu^LXfVkz&0t*iGF;e?PQ{5}a4T4iSCdB(rSY}D`sZGnoqb&s zw+Bv{vEb{jb##`On4`2==zemggV^0%@jcn3n7fi7GUJNXGCO&&_Z`8%7O6Z zzL0<{jha1+b0sF})r9#!{GO?8Fpz3I_47E3L;dj zYW5~yno~yj@Ize#IRxd#BBd7NS1C34~|HH zhQC!Kmcd&v?8u8rrc^{-1q_R8%XYoCT7*oaI{dOLI~@=E23;<(EpGp|aoK#Q z!Ds4&8)O^o4LP__ww(hK(Q}!JA{&fx=dOsIj7R^z?}b;hkiHLp$>)ZH^zZ-%0AMOz|jDntP?m4T#s#fK|m3JL3Zn zW((T(^(Orv!`_PmSv_EnY{FhhuW|6+Z}DkvJ3qqZLLH%AQV0Lk(x!oV3?qaF8Cpho*-*D|GS4{A(Nm0ervFyiBGOqI}moY2y@?plMwvbXU$=#zgKZ=VcWNIPnPtT**+l zk8=u$A;=&5cPJBz<#G0W_Tw8zTX9h-xb6B7tfRjmN%V%;LSaw?P|cO>r6QNl>5wK6 zmIfcMhHHn!5v7}cc!aQUierX+KRV5s3FoHUC!d5utok!!`T7rQO{fS>^AGY=gyaFQ z;;5uYKq`=^@!L92iPkn7aHe=yxuS<$OmmuKv)eqeZB?abzqA4RdtP0o!D z{?EtONiBs~aROE26_NuIHFGfX5cg~$kF^rE8h%}4CC=Z5)UudE1Z`y+F1{qP3W`(c%kakRW=Og#ZR zTX=Ib(^SHL$j4NlTAX)BbIA;#$es%g>YJ=msrK?T(J$uuBQ3>bv<0R2W9RTy70}wQUPyl zXPWF4Y?zfCbjDbGF|iPeuiAoUJ}Zy`2RQX^>06ET&ol$7R<(kB1A}TI33Z4Sm8-B-$RP*Em6-?g0_1WHa0d^ z*4i!ur>Bz=5U9LbCEwHj^Gn3Q;P53C(snZyh&^bM?|r@}LqwgW9R0#r6q=FsBQfd5lSC*odiK7ECKnDD>c74nuC(GxZo4F^6-v&b^{~ z+==Ilt;YlcHk#URLl__V_QLqaqHM`?yQSWB^B2yL!@5VVcIMqygW2ZAD zB~AxrQe@#DtnAIfPjb#iE=0jh6l;{ zmEm*gC~~El2Lk5gu%yGu#B)r#c<`XzFBBiOEA-S{Sko3lXftcmQaC5wD4?3XrF;DG zi3Fw;6wy6ie#a*yatlQgaM}6Y&B~J`kOGUWl-Nxv0z?UNDSBPZBMtA-`v;#_$70O3 zsH-vz{){%`{p9Q~OGpmr;X-c75Kr6j`auV6oc(@h{9KV627~PCUG>yjb3#^7A}EL+pU-p;T9p-e zrlU9aarvFz(I-A%42-thmC}Ck+uwG{AX?i{a*gpy(;L~I(<+?DB-#8xaa4T74&d*c z>I|=3V0SiiQp(h;u5B#r;W^;y&7rU0E%+Xx;2LJj@HpCm*SJ;1+Q!V)He@yFK0k}Z zL$>pG|9*$xVc*?`J&M*)s9=yGpIfSF$X*^^s=pn*7sf9=9Z!oMm?fdwdwY93J3HIk zD>IB66Z5cpJo$idg+HuDTou(|wNI$C+w4XUKqOj%tGph$QA*T39zgC3aFFQhZ!}sH zD7RZ=&=vpwohF~qcFyPXav!?-u+i~yS?6<0T=kZE<^M@3?@v_GS`uPDX9dVfD?*XB zum)FEt?E3{!%~5_qqC3Ka_R|R3kOo6t&g>J*tpw0tTY*tZA$k=4&1S? zpTXzMD>3}yc-IUY+J?NAt(G)SSim!*6|5}sexk`t00eTT!>AO1n=M^k_y8cqMqgZ{ zvSW{+vP=sH4N4plw~EG926x}}b;CGMW2v>wa>qaK-{<1}y#O$(?>+-qK+L&eL9fkS z;~z9-#gdSak&rxd96Apx{kOE(MhAX%F7~qaqSd=03zvmxbI`vd37h>n0jp>A=M+;67y?Xi82J@k>Lk-{$y2xk;G%!D*dvWEWY;;;!w?CT~KN`S#L8CGr&f zE+q59{5Q+@h!Q1&f`;Ef#1-3Ex#%I->UqFdT>7UX$4KiiOpiA|K=N&qyNDa zrr8Q;?bm~8hEL(S$2uIU)va}d0S#}c=Ugc-iG+~o+(5fwYN>cQXYCQz;F|CkAv7X8 zf4w7BkjKTJn-+r*mwVYJK)KHly*~4TW&{9vj^IIxA_uMpFR3{MP?=fpbCc= z&RRAAXdWCwP9|n%VtyAVpd1X`&w6_^!aCMrKK3wEl;rmg^Z|)Dt5Liwkv6Ii>$iYhNbE z$}U!#lxUp+>b38Yoc@eS?&dghyE)8D^G}-^rn|5Hq;{qQ)b)OLB)S|{B}jOm1_gaE zN-iS_dTy_~@G*B;eWM7*#@nequCyTMeN5vvdui}TBN_ z>2A98K2-Yw+#Pw)4u~d*OTo zkO<11qekBk$uIURC5j7fLXizT+^c@AYphX%JDB0i(ahHi=!mb|{>FTxp3ge3A%P2H zqh5myPIj;wS9CiWo~C3=j8_4k*o%ii5?qwf*}Oy*CI*HmVLQp!m?{WAuhp+lVB0`n zkJC>#)Mu7!v@;N(UmXX7p|{W+?b0{jqgdIzel@Mse->YtQg-S?#>w`&_6ePZFnEa} z=XY7Pf4s!wpv91gGijNR5KHZ2$(!~v40AC49q-Q)SnNVYp!4Mrxsn9(>z`d7>NT#y zZiI>GQffCzN?T(?GylbZjJ3BK>a*nrs|O=RVZb0e>9Gvl0uTsaec&MN zFLQ6))Q%FjSuIquS9;yObb+gc$#>(KU(XSl1uPaS*UW@(qJ15eo`35%x6GwnTPPZ4 zYLkDvbRH8D4uxx_`pK1!wkIRO5DczvbtM3mm*bT5+_u_lTMyMQp;a*E?KoRNpxLOy zkU-%CHG1zc-8C1FF=7&#B}N_A0~jw{B%rq9CZIS(TZS%Gh!zdJt}Bzt3|Y+N?Iej& z;n0FbF@yh$AL0%v)7vzh&07v|&`4JMsWK^#P>z2T@F`IDO^4kF@$FbySphRqO|E#A z1jP=p_2ifn05fjwKuKSGbiY<;XR8{BDX<+?$rYak4zQVaMUA>B9NX$(1qi?WI^MJO ztdfP$1T{HY^Z6zQ(~0TnOtJf_%V$_Mnq6cvMS3w3(A2JKU$7(gRj+gU2`vfW+reL@ z@a|n6S6)Qy#Dvs(BF$!75P6_r9(yZs3};1=a5?_IRDo);v{CiLX5B$K%Y$7)d7Zcd zD;rVIL5W#$DoLDOy#f8t;b!*mc;#0i3H>jsjg@oDo){lfPYzz(aI6pUth1}9uxp0xx)z!^&GOuMV@X*9Az4;%Vsc-t&QAcm7yJDy-`t7|g zo9hk>3+MXS*OBg5a1eng=rv&rbb9&>N& z?D^lob~Ro8S_cT0sK{8fe*V5iQ(QbF{Rw%0)=1DiWuDtL9M?J-@LyG6T1InV=O^)V zYVRL3{YnQiGWAVtlVE$kk=nhz;=Mg1Ik}-jx#AuBoIUrH7DrJ54^$`vHFv1-aAPz9 znm=%6YnIsfTAs40c$The%R>@#?y{fE>nvF|6z3(N%*88`l4R*BBCwXm{2+A+0PBV0 z|GwH>F8JPqFcf)?f_9X63>PYOhrTp90{!%XfncCohy#xt!UAKFp-6S!6ycW9j0b7C9s(;6*lj^><9-fdS3UIoJyq{*`keV=^vu=wCYJg6IaB|6=!Giw zI5=}f^7mT^fz6@-N-WgW^nH7aYSgOSUOtdewsz35z6DduFqpK}RF)%L(+) zG?nf=i*&RBEno8DWUMl67eYGGM%7lqZx3&OY3;s|iv|1rRbu<*LutezdFZ3}v0VSz z>3{A6EiO(5xV|alPC5x1M-Kd%XOShD{wiUwOO^vKU`)81A*))djCtoFSZMcngE%+k zS9$vJoRv1cw0gg_Jp$^kUv~LuS~AbZyyQx??!_f9$}z#SZ~*o^MyG=WRge4Jxw99O ztyP`Q+8?Kmw%VGSnm}qyPftcQaJr6RvQ|gdB#(D|-YQO3rq}_$tmZCH7;$St_Net6 zOiv1yCQKJN{M?BT5%^62O?}j{Op_o{G?+tIPY?JRz^P;O#*1y_THr>C$RVA-B8gFn zGvBHWAO7I&xW}fd{_Af6dmSOr@&J66>>q|}TPTW0GAwIjE9u2{r%0AjH= zvATL%xi)kLyyoof4G$*1{I`yP<@DbIJ8#|zD+KN?3~>|ER zY2SA2)Rty*w4Zc#p8CFcSG8YXndN%k^ZsbRRkG2U^DBJ2@ZC#3(6_rP#?gP=&HY#j zEfTms(s$p>T@&&+yx4f^@ol@f(EGrc^jWw1IDX&iAbtv7c)$CEF7l=A{XyU92#`8> z-edUe0&o!DFh99mul1!#z;LYpw2dS5GLkCzp{uXG0#aVkKL=043cuXr=+!&~+~nH5 ztNOk(cY>w-dQ$c5CouFM%7s7Jh2OwcADL|r9T$5_zT3sAI&SOGKi+!v*M-FVZdbZ| zj*6?iZkS(Bl|K5xOy0*>D*x(i(iWSv%_Y8aP|@ z>E;GCgKE!Yv#vE31erw3zanQ-9I?;Cr_OIbH^-(9I+N-^#@!J~1GL0fVUl0J$rdq> z{L}0cPR8}AM?Vs~-MJKDRX@{-)!3^eqQ%AXs@4-d_OUa%gtLQOmTa$5`#|}1% zdcz#Wp|ARBOV=te^&R#Y`yVDn%gtV;?|6xe)Ym%|T7-&BlJdIuP0e_ONunX-Wk|oS zavw%9 zK9ZYkborl>yy-{jt;);$dT1uiuZ9^-%9CeR=%St8{*YTb zMTT8nP&e>lcCurfSe}rcSBTju&`)^t8-DDN(|WSX zd-gSrxsCkA+iL0g*_pfit*!4R;zi_!$N2aUTkZD)efNFem$MH2SH{=6hcDi9rCnF5 z{LP9#V8yx(Jp|64ubSFVKQ*m?Onls}#M(m0-={Zez0BCQpA##-Br<#7*53QazO6dy zy_tCmKa@y(d+Xb}5qcM9I;+rqIWG4(Al82!!MU*HP_XcLs>(67fA;TsF5Vz`Z|ZtG zR>gjLURb}+;(ql_{kX|=`D85hgUS0P)Yq#GBq(rQ+2uRX7<7`%-1#)L{_Lvs)*smf zX)G0+eYdaFej?udqLljt_I0|c`*>-2c;BM;aeZp={b<0+!Y%KKzY8;K`Z%%@uHLi$ zc)jbWbKA|}etjemwjbGeJzZ^J=KXlcy?V0Jv+pgm#@Y?F>EP#o=cT5ct>$sRs2qW{ z;it=;b+nBWbi4UFZK1@&1O+naP@UA)Xx++z$Z5EhW?lsnmKV9|56F*G`z=qSMn?N# z;AU`E$`SvMzC;2$jlH)e7yy8O;WzyHSLy^=B=FlmH=kt5fxNN~8-w}_w@r=#+4$;4 zmKbU3vhTB*lvnbKy0*pNQK#JE(CNNu!HORCp`#cF!6G3LcJtz7K?lh6g!|m25fmrg zAKFzUWf>NCsF%<&Y(r?iIRu z<1x`mlbw%zYh{JM+U$hamM$jQpOa zKhs15Qt5+p+tUe5=gls0qBFWmh#D9ic=-WYO^eM3qsvysv^gec3ffRub-lP>0a}%N z?lw|#eOpsHS;ou5yu?T_K|Ao^M5Dra59f*v;;0GUm%mqT?Vbx-_(91yYVAvVao_~fMFkHxCLXP@!a_-W;B=)ihq@DG0droEk(;|wYvSW#YHDqb>{onb42&M9 zh=IgiWo0Fipa;crLnI>6A3w)`YFL=kqI?)95tC=ZTJZdz21QPKFR>uJ9%w%Q{WPLe ztwEN?Jz-ozRWAu7YtN_yJzO~-J*c^>mH z=_wotJNGrA6xz1=9O8YOenQ|9w#s|wZLR%%`l| ztkm3(O5x_KLuP&CpYQOKJZ2#fPD(;%C&#*S=o#@I;8EW_j>v7>_fT6wyVDQvImCA; z&@D}(8R4h_w}``F9kVW~h|bf;>-dkizOz7*S*gzqN1;^A>j+bPPk*S-5rAX=67{~m zfIvKK)rZ(~(njZVKQ2hz)t+egZ9(7h<o=@Pz;rx+&JB*{< znkvuTF_~tL{-J^g*fAkJ(}bI{2=RuNf(VNRR;_!g|UYF?|9tkK)ZDX!5T zj;z7*>rnMDm!*1$hI?3G&Um`Mb32OOw2r;puPmC#W1Oe z+(=?_duxrfXTi1|E;UlgRfDo&L}R<_A*T>-qV02HF<47T4R*h`RSJ3CQ2th9)cRyh z2)FB5w%+|Ko2>9*lm{pIgqD1=2%wBHk`(~Li!#fgg!TN53-F&>VBRuqF3#BvpoF?M zloBY~xQ~2|)4O)nL2$Y6Bn0PHZ++18X9n*%wh$st8(lr~J0XtzFK?am86m1@_B@0M zT5o_^9=NR6Sgi7Wvyb)u%XiVfl3*--SO*>f{0#iIug~Xq&Qn^HGU)$A=+A7jyP?EM z3JTbw9S4)pELlA-KCzIR<95@?^8}P2E@OvQa*`GsM+F;Fpi<&4Nn(Zo5JBLT?f$qa z3c~c)063!B`r5j>f-a{td$5d546?;RaZ%8w@n`{77*Y~7+afMvS^oEmOlDL^(qFA5 zm$IC|P`@d8Fm-zz$Q27Aq3~_*n4Li(NI-+2;n6A5{#uXYREW)%t_f^`NO~<0v!f%+ z%g+z~FXva=-Y%a4;<&~fQtlEa5hlBao?sIfspS~0l?tCttXscU%C*m`X>Xcv3fC2W z%0FR#p2w+r**5ci!|QV03axyK&W_bf{??B58EJDbU~5o)L4mocN%Q1%!S~WOw{7#S z4+QGP4i5O-b#=e+(MRihH6rZprL^(!PVD_&VQP(@|FE^(>Yt1wmez5~EquRD@A0mr zZKhkl=h-U`RRfC=MD*#~(KD15JEPuvG>?8x+86N79i~^2n*mfQ8)-=4C0{P6xkWKg+`U z?|dXJh1Ir|GuOWbB)I&MSmiL1;pFdp2;_rl`vRyCbqQxbl|aylLC74WH&PW?8KR7& z#oJl&_k&gw8IqMryv|n&c?nFlKaMVxG5yt5@(B=}s{aPud(}XJ64@T4;CT;3NwS<> z@&2B`cr;gIFf+kMBik3Be^|@2{ka6km{vX3Xu~>s(v`~#+(dR;2t0F`c0hu?A5scV zFB#vgHU>^p@_n4&6w6Z)q6eAP?71KgYBwSgBPsb3FQJl@JKGkr@FD)3eYCo4X!JY= z2{z@hO@MOK+x!4WTf-1EYn%J&8%6hb&0ar6&t6 z%V3Idt+ma;RnLHwA=SXa8REIH$x%u6)vNtkawr5z^B$s=neISfShMxDXZ~(>p;Roo z?*>pAQL)JIdEN1pDx3i4+*h5OkBybY3SYeYwv-e$OgQ2VDPzjbB$*fQsLO98I~EBm zD6*!lDh{?tW*~4^a54OS;C1Z70eu&19-TadOLigWUQ;ylv2g*;nJk1e3SIT}vp}>8 z7`d(#i;hvqa9AeI&|s%0(^<>{#$S~T`vIQl^qFm>m>>~hq%R$Xu>_3~( zCe!IA1_=cS62#!K{jbUjKL=~i45wvZOxUl^?Fo5f2th!50aF41pKV;k4grY)sXpa| z`d$`<0B7-z+FG%Q=bpUJc{g5U{SPIoO?f^Cl&P1@Ubk{mn7<44-wzM=)~UZtre1i6 zoUMD_O?F;c+qS#efxlSAs2tL zJf9FWYwpg7(N_5wzeMnUSY=C03fh%=@P65X_Y-)Xv#RW}y%j`q3E`g*qV%{N{Iq+J zu~^6NBmI!xA11j zauS(ue@FNXIFT^Q`*D}$k)sv51SA+$Z_DJA!zQXadbYp5M65?FX4{|J7ls5DNy(uG ziD4#O{TpntyLP3eR6cTNs$-zGa{L!h^f|O}%Z^Qvx{Q^d*?mhB5r2Whw&7<6YXkZ{ z3ovX%i(+rz|x)5V4FS+*y?iyasc412>O_F)(h<$%YZ#@?tlJ@aqQO``W8|3OnCBdI%m{) z6#~R`Gtkym)7UtFau4}b_S+9N7$vTsVjP?lv!)v}=3}Upo40)~w zQEh#c;;128z1!P>To|W`c?P7AVglS+@B@b0O)?`{*1qo*+!ou;r&VT#_1;uAu>!LpfP*(iQ}uEaNqIN zV|`sK&GlV>625LM&UK%x(p?-se|aRxaUYSu(f68Gvz7DRulR9c*PLnF_DbpbafXxo z++W(c8|bR-DaqwIu=0L*>}}h;{d#i`5CPk4A8!`2&;WA8&%#t#>dr@RU#~gFuGifT z9DRo^%1MtK>I=D1>JrbZOugjS5hcNo0pXi#*ERR+b2m#tyM5-jflQAJ&vgkLJ&&Wk z$+wD=A5QfL&cr@1N4ZZeqxX7VSHZw^=`5E&=~GnK+qwR8#U$~I-fN55edjIR)5yl# zqP2I+`&n%J346~RvtSh>3GwT#ukVo5eJn)(b~5vt=iw*c%QDZQr<$tvgNLrhwA&|bJY^K1B7V~^Re>lqwGn%B1P{N8UuSUy=I^RFQa7E#|HaT5Vk-7TJC&3Aag z0h64}Fw{1JEJVa{#5BdsFTYGG#qvHEQ_~2NE09PlVi;+%uJ68Ckpx(P6NUKYjQ%G5 zElMi5D)~>Q5+hZ}y7d`$KC*v^D*kJ5PciwK+X}+E>EDc7i0H<>PQy4=Z=)xxN0>w~ z-m}!FC4#@90#zh~f|u!&yOu7b$=y=7`PlG7_b&{w58j8654tI~-3FF+9UMd81fb z*zi8#+WFN=BBSJVEwzUP3K;6t>c4I;)9CWFDQ5afDT_r6{={zoiOZP4pOW;6}~Q|26yWDv|pohhn#q3daMsXhi;qZ9`;7=xcT_loXj&Kx~#M~ z9>f5j1~@p4zp|;@fpS+O1r?(4IkK}nwP~BubGK{G_jj}l!FM&^tKc6`!h9DMz7Km% z&%$ZGN2Oh2zAJC9!d>T2_d~W%y$46kD@-4AA5Y2pcltGVExr#G2N@l_M{^508`aF& zqwlZ#R;BF%i)TXiLu$59<>l)t9(!09T~7#}e0;HnS$Jueo#RT->Bq!4 zB94n^7R$1)o~F2ughZE|w(ARnBbU1@R&yMiI-v`z zLAHHyeS#$i;nOmVxYMwRtcVS%(*vYaa+n^k+s*Auxo-K{9cQLQQ9G~Sblz1M|M+0P zPVP#c5(W3YX{Zzc8WDz3GTL}Cd24hr%mKyE`>RHWokCu_i@lAE9MFnvv4OCk0YqoKS3tj5 z;fu!YddDTbJ_M-a;M;RR)ebci5)LuD>#hxG@w&UKBG;~S(H(s)p+he=kB*T%u*c7j zf5gG2d8=S=Zvdc9sjk^;0cc-_J8_gfWi~>pw{JZ{~M&+M+d9or^h5F2qOY6>gZ?9O+fyxLh zkz1Uk1F_HJ)>6w7qjuB8*qBpmb`c<+BY-GQ%3{R~K(yJ;4JMIX(OpriQt@1|Qzx;x z^`O%zD6DoE3S`fbAWyCp`#SC~>4%Gl#X~PcawqVJFUMYf`mE=~>UJ9de`4LV5>+FR z3hcQ7)CNo-30(6g8EUqor)f!3y%U21ATVVcnV~@-h6Z}pJ|KeJj!jPD)-BFGVyc6# zla!Y=culW=+Cug_+C+1R+)Yvi5%w4*!uUlfihdfwLQI_#O39-86>&bbT086>8Rv}* z*35=f!eK=|rfUdc68!?qW9^ZKB(OgZ-TP>4VjU;qSPfctrH;mF*=&La1`T7?NCG^$ zz#eDC&kzS0LE*;iB}oW@BAOVI9<3{f=>h&!UHB5l>Q|i8lDTXqy2m50J!c?NXY}(Kf^4A>MhC1~ad>tAFRwm;nAh z|CTjA&5v$eq2bWzTTL$x*+EFYN0SG1k5wZ~Kq$K}U}3&&Uij6W(qx-ZlYn+2>uPSi zCH{WzJzP((${jdSh5Lw;>~wSwtHfoAXS-ZEziB!Z)HZ~wcLR{u*|vtMJ8Fo35-Ayl3{pwXCxa-&m|>I3?z*`GlW&V! zF|1P{dGdo{G+szQvV?$nZa%g(8}2%PA$O)524Sa1mM`mtQZY6wF2k1eYfbai#d zZ)7rJ9Mi4I?#9o$pfon>%wj+Ktg1R(ZiXK-0S@S}yEn`%83Ab1g#mr~_e{EdNyXTc zC>o_68Dyz@6R%jWvIkfaiNK*Z-%UKzIa8F;HPNC174Kk7f6||~a)DItT(A^E(CD-8 zMiyrf^)hLlp+efoQ=V0Ep9pQHk|LejkR2i#*gRt52rG}_`9Oi3A#r8{H@86 z1uIc(_!D_GQ!#~{=~oUms$vRb5v4GXW_T>L?=UQb!Ej+upZsVL-lQ>!liZF=V6-vB zqlc^Qra9hYle3n$rzes#|1S&BTlP{zQV`u_oWmIF`1TdlU-qr0Cq15ZLN*W?I#7Gb zT?y@;#_G+oY!iH3(TZ`}1# zxY<~kZ?42o!Sp) zbYUZ2uWdA)@TYPcY$?;&b(iz=w*^B~@gsxtdjiQ)y;|oJ_3eGYs5~NcN+J~x+F%M-EQCKURyV)mx#w%S;h&lO|=Y@2i-8jFt%w5b5n zKVaUm0==* zHJa-7+l#~C0ho9H^I7x6gsU^JYT@o=(Nboo4CabBYhy~d2&s|(%&}Vj%FQ%pNt&KC4*uq_HgERoyOqWkApN0C9VTQ~yGF294;=*?9HJA9mP zLv6*bHkZn5xJ5N<-yeQiFzCOz>$u)wkHq+OmvlfHT6%L@u5D{RUChO+b!L;u+^ZrCJTkMt_w_%< zhsHZT2)1`2K$}&*%J1*&G0{X_ZWr7Td4d|t&gLH;7h-0J1W*tINtP8mJS7DlEVx02 zZhgp+534s>W&%4WX1U&pFWdYsQ7-3MtDd%E5Mx>F72~Z*GG$3(eu|}^kT}gr{n(+q zvu2__+ z-%A4L0It|RUxrdeuurCx5uM5cTwafxEV0N1XZ`jm;+;@SAKXiW2Mz+gF>+G+U z&-3Y>jW~;%u6hsZ+6OP+P-|`*!^Uu6+~NYN-9`*sISPL3?rf}1OQuD`fyAIdS<-yh zP~~2<#hhet6_klk;AE#GPc5q`BV*9AIloEHif|HZ3aO&tmr@nFvw?w7(X`PlRv3g@ z26E6A!Jvs|3Pt!##LrYftrt#17dPPc$&qNN<^&x|6yz7eyxVz!?D$Hb^o#FgNo^DP zvw`62Z$+P%;4J6Bulr@v86^?i_=|>f-4y!-!L5I)BGNL`p9?swljb;m$UT0yZ8(!d z%u1ATXXJ6^pQK$sSMkD4Si_XUK*6*maWwwAm4k_AFOKNe`bcqltR*D1yf5_9ujb>c zGBO8sEh%5y-hIY_71_k6;l_Nmn6iLZr{sx29!zyMQrO6HlBF&JSvr5ETYx3+vP(ah zsGXWVs5IKwSGLjC(gR32|C#L0v~61Uns;Kztz25qAo2iPxFq=#KTf!-7czDzh{XrY zN&i`|5~lQAzyk+F5qh2@e)if7meEEZVg;ezmXfHc_#{qyb_s9TOlEt#Tzv`r)^(b^ z(emD!*kyM%B1=z82`OD1l;n?;G&9^RX->&#AZ=W&f*<`nd809d4>7IiGE=rEHgzg^ zKn4d{1_?VKND@|<<~VKB)JIZuk1~EuB;Xb|F?~IAJ@Y!fw6vsH3NS>==MVx=K}88L z1y=0GRFTTz!K;mp zzZ~g0J+7|Of#`~P%)$iVpahj@M!94XfZQBwF@3q*f7K}zFz^Wql+K!g%b4-PE8+&_ z+aKN*LLRq=V`K8rt#7FnW```*KS}G}J+g36c4ZU)&HHXD5)adBMMRTFeN*JDZ8J0` ze_tentiBd8?h}vCtYp`fH}-SxSDo0bcUz8a?nB3(t*o-Jo|UOD;3T1|1}kc@Z|i0Z zDv8Pl!(|cBMxy`0Y+^FOg<2MMX7ix`);319#G^2DMDeB6FZj(JQv#*~qE%EyrM%Qa z)@4-8&X7z|1S-Hnaie!c%WLd_q?sU`ydw}*AcD;7`@u`%_mImxd>2F_Nh!O)ps^pB z98nb5dj&Xw7I(}(PH5dujcqXVa%t1BJxmnC`7%(2!LGmWUecV?O^5W5ctMadnwbc( zlEUN2;$K91onW-c44pF096ih*&Q8+igk!%=DuOO$ysNe?a3dIV(~+Z*bD!PbxE?&=23kM|Sbct+?foeP(oLDD0fPGAyWO77$c3fs79C~gugyNSjy1?W}X ztNz+1u5w&WU(kSQpF#piB*g@fGs*xsVNDSfn7}F@=Yt($-$D0-wNwgPka)bnTNJr= zV@yh_scna|Hk0G`2#eul1O+NoaG1&o4FZ~|ouSuN3-a46KFGnradz+o#_OB}39by* zJ&#PrK-a2%hv^ppGwT$Pq-|(zjR;GW@c<~ROD!z`VovNBV5T(=$(nX%%v(rE?i;s! zC2TrdZ?&@fbfAB5tKaE8<#=!l)0uwr1T_&iulM0nZL2js4Uy($Rp{e74r(euzbnF2 z6Gsr?SJqFc=P^^p1kRxx3e<`9Yc|0CllYV>2#}t$0|&c4qh3s)z(WZId+>-?*{r%x!O7!<3?OjqbVJ}C{Ej!u z?=;Wo3_$qt?@v3yy!P%oM$Iv=>J`K-qwK4aa_glt7o`0JC=Sj*(OE*1akH5<7HV{Sf_qM>MM}w$ zTaw}oydeG&u+~<@bBZlwi8D$PS&%Fa85O`Z2xXPwn!k{Yad(i0p<4<X@5iWc{*Atr|C7l7)YAFcpixe^i!B4#`NZu?|9Ee9te)cAzSn z$jX(dAl-~hwCB&?YOZaFp?QG^y#k(?SvGJm{??4xs0Ytz%d*%|13Mi(? zp4wC_Iq;`5KGq-3y(b)9gb#QZB;qY-nHi82`AnQQ-gh|sR1)lC{4`U@1H@*3C#zHx zVM&mZx$uiwK^4J4z>G2IxHA>Ah5(a;>X1f5)S&$7M;W|UH59Z$9y0hPpjvoH4bZ@M zDYBym$p;tz{kxu-nOR-cXx;M+_4?g{1SX=@=9$NlkJ#h{o8x-%GjBPXc6-xGOop(j z;Xk~4u1Efs7Pj2ZLvio~TDyb>bWEGh0?~s_azBP!_%vK?)k5`seiaQ>k<<5Ti_kMF zqjgm_%(KP$7j^Q2a2FhA+NF8Z|BDWl%*W`;9ycL^?8v{%UAAW6~f-#I1cBvlFnknzwKJ+T7fV%>K)p-B#P%PAT_6&Pr*UlIxu6 zl*-CIBe3pmv-~YoSEAV{ybHQ3`{x4s(nYFos!bOKQm@Ps`SOu`{ z1fiv}ZKL6kZLikKPw+z65oV&I+P{BBCCPI9z7$N_nlnmq=D(C;5h7ignP$%*@kfJI z0V9Y7*~r)!>LgTf0hn)P5AlsqZ~`%WJ~lQLU??!kh7_nG_AQvm*FFFcmxn0R6nAfB zL#P&}B-LKJnPM?(8GI#8l)F>)%Q?<-%`vrQoN8U+w9}WSiOi&>k=|56pCD)2hW=C> zg&H5_K^tj|3sVd^ifPDm@pipytBlF0+j_el$vofE{dDFETt4)x!jydK{-ajTWxZVQ zuqO*$J&Q>evT^%Z)4V{Uu*S?)=`<`hqEx*6PTsdq}gW3cvk3&jB4)vP>d|X89^hc>)izB(g zI3-D125X&6L?zj76S1eo(5^2G*9e^ifmKk#t_PTuyt2UcvM7Foj}QI&4*`#H@&=Wo zxia!ruj^vD(PX8>5I;(plREzor>U9@{9a)UA#>HtCRMbm_(&cnYD!_A?4Rzr%^!dM z*w3pIBoB!{o$Z!LDs+Pa$3$SRYsFnfsnaFZ$LRzc%jpAc(j5sm$%RDH6A9TVWq{># z1Fziqs7#|vwvyehh(Q}rX(d&pHygG0hCwL}DTW|pe2z!UFO?2DuNURk6rg^Oq&&!3 z<+eB?gBh>UO(cvv$ive9HyH89P`nD)+}ICF2E{~REZ zS*~-4MFya#?)nRjh)u|22TEoK_)$`3rAwLZ`LVz9E;_M5j}b@r{J!&#i|*u2`iP(u ze%DzH?azd741^e78@WKumWXIxIrNx+qjPP!#%QT7Cz9RP^?q}9mC=nRm_+bAh0sSXNkST$%lR+d7x`Wb+4p|VKPP@gK$OnZ+a1}|UsOEVB* z2W8j6A;to}zf{(|(n{XhQpXOS#19n`(p)kkdv6$V-vhrByof37X2{5^765`EgP%Z+ zdt^}&D@#HRj+gGWg8a+$B4mmuON(*D+ea)gsR~+q@cvtT`{F&y#<;>!!Lx@cm|w$C zQIk~zZLIjSNMFM#K@o{ET(W_VfdO&$qGyf_eo#sdHr>NU+IkN5iDJCJTyLL@POka5 z-d$e3dRfK2o-)RtgfgGQq~GWtfiWRNP8%)8wlzp2^cRki(6nk>GOdZlhF-Xf0JDnh zF)kFm^6bU-Kj=|egtD(c1^&=?I?!;1|BMn`cTbrW7Izjpj~Z+&t#NAa?N%;n{V?8@ zj-;ju6@sD@EH$D{{=IjODqDt0W}~2(6_vM4S>m*)Y)#Y>Pr)64jNEnQiA8 zg4DKa4H z0z8*i4f$LDeYLoZ-Uw1Vc>n|4Bd6uF{C!kxBn2>u2vQ(^2x;@b7bsF5!|-!)zq~lr zaw{w?m1fE?OB4lMN@;L>!oOMvtyC=}ahtp3O8>+ws$Ar?4kWJ1&zn(q^2Vrb-sPjwKrNQJlq3$6l^*U*QFq`CvCY8NmD*g0*2 z2$C?IPxb>BAd#uqBM%eTE~I6O}}oukPG!N_e%tun#1X$q=W8QO9L|r#TBhjl!bPIm z((*ZKAuW~jG?j99mHN=s#_(&3|Bx;yjk9u$V8`n@5}fgf32{@cY`+njlsGooy_ul* zkg&*=G5jEfkZ)O>j#xAVG=7CrnuKL+WOV$Ebdi%{52VJPA9r4G zn9}SBOV@0ykV)-^zPRRnkpG)IzT@+?3wwa$cSivAN2Hr?v9y`RgEOH)Ll=+Avuwxa z$E6f@DzZ9FSP^Z67%`Z2Pp@7od+6$XD_?-eDLnYg1ug`X63 zQ{j<{_mhvsbT1@6(@D}2aJYn#C4ppr(iBoCj~zA0kE!24Zrlh8!vTQgeZIM@4ApWY z4)K8U9ora30hk>6G;<@mLz}4O)xu6${MgT0d0#q352yP^szv<#C_Hk+><>T9ZDgU| z9OKQt@i`yRD)@g|ZieQ_oXlR=>IM115_{R@sOE0$Hwiy7!UZHM@>u}GF96pDJd)I) zzZx~$W9*ZJ1O#6r{bUuhmH+mY*XWg&C8^~naXe`r_YtaJz{f8}R27w~AQUJU^T8rx zQJyjo8I6BZ|CsItZ1C2TKJtT&3av(R7Yc zmA!u(KVhGGLtNY5UU@5`n0Gb9@jh8dqEcO zuwHuT6RJGJQ%Vdpm#2{j8freKdYOgGF&*(b+VUwZq6>tn3h!!V^m0p^pNvCqzGXQU zSE0)e20EwneyhlITZG+YlHg(x=@Ta=ma*HDS?JePm4zz9bW`0O`D~<$9B6JW%ev?e z!&mvmH^F;A9Z;qHF)wqxZ5#(VEf<){liSrHIgh1`gU&wY#5E~IV|hs-r@XuoXSN_nLk?C)a@N9~E`j&HE9q;(Jp zIPM3P_TD5sI46bY2VNzDebbIgVGKxv5;52c^73}S>LD=dwg*}aKm{p5rO#lHXp_u5 z6&p$Dd1L+(yZ6f>KQj&Q3NFHP`@yHycFnzKekaFl7B8>DCL_w^>tUm@z8X@B z!U2ELiP+qD0ezGK3L_tR3dR>)xiL;m91*34PoysW$5!P341F?lsVy1qA&175Ky#im zk|3ksNR>@44U>F<&=3{!u_dS6D&KSd&1bf=OAB|}l$DUjF)JkTSPZNPSpMF%kSV&- zD$~KT0Gr0E_M~0w(%xF2%mt}W@Jw7A$YB-KbF#pn^NDt{K?)$vgKA;ymi$#B9!cDVE)^~WV&@rKBHWvNImQHcB+nM|8(~%&q`2fl zu@;Q0NsnwXqku^6B$e(`^ayMjvq6xXdU;t;Kx<9&qyNrg;IBA)KBr9lmy$$+Gk4xn zYtw_Tq;B9Rm57+BPKVcOE-lTwJ4=kt8)>jMGYR=NZWe91v%rrpL^FHW3(dMotn;iL z1|luwmMfX6ljBR{0cbj$JwJI3jn6t%UDNx8K z!pZS-;Nf>PIa~{a#SqhbsWVn`BVAj(eH%*L8yY8@XnFYq*sM5;c54!p0;9!#?0q2o zrJ2+EnQ4I#WIA1=OiS|IQ&V?gwhzUs0Iu#|fnpS`$P~bOwvX073M2)APJJ&6$@1Ny zYkOE~?10u5RA1b@W`}}``qI1Y&;~T(`(-n+k^ziyxiBE-BS)eXz<*5x{iYLC?>Rah zkAH~v4cAAP`!Mg2qyv!9Ipl6IkKIu#+jZr-oFN znJstHm+UyRr%TP&ru)*G$8wvHNuuGZtMV!6E{i5L{V)A}c9olgPmy9kML z;7{VURZ1d7L$smP_y+n|CU8xSr-29_=~MgF4OX4eT-M*^El?vxQrVTY`gVxWu1Ob$ z8ONF3#bO6|bt{PFwL*K`&qbwW*wHdj{)qpvgN*iN(hk@s*x;}SZk_VRgv(z`97BU6 zEfkiKx@loS;wdVN?8kRmhaBINM$T22q>Z6f(V)w%MwR*z#9Dm|KkH2uT5nj?|33?0^G`V}<)?FPImalrR?BcjYXd$q&B`1bRo-9M zJ6EEL8n>$Q?SXx7r@z=ZQp9~TGG{Z=Bd3k>)T)rS@Mto!xBtL&Z5SLK(k8qq57p`P zpIk2hkfq7Z$$nIC_oB0GzQkDEP8ksLyJU~qm$}0Ia;PuM8N0677m!Eat%Wsm? zeqGakR`pVxQWPsBdA`5QPPBA5c})E=g^@|UBCMnt(u$*Wj&d2N_8R z`I2vqWD9uzFC%%Bek$Za;&XDRgo^7Yri9f1?kke5?Z9`h-*b5%A!G)oX?ar ztHB}!#YO9?QFd7cP=*SB$i71GwXr{hMPwPp{@*CqBncflGM{RZqcMwv=cgYvcj2H z7A>u^E+dRNic!{PGj!r=w|~EII)61t*~J=`?p#%{cA4CKuuD`W3fMRvj=@=PWdOSx zXu-|fwAig5{y1(%2O&CrCe@0UXj4Gnv7>n^`ctmWU5DAu=LOZ(o(q#Q?4 zmUL@Ic2|_m8L1(lbmEy~L6IiXBqh+MUtoreIBMnK6%a`>kirrja?rwiUqLx&raIW+ ziyS}}tcw+JY;1I86GVYYl<`3Drx-UoRGFXZOm=9ejc_iH4{2ZS-v_99 z5Je~NP3bB7znV52n{q*35`z908T_=+rK2T)Kb)Ivt#oRgpT&*7^Q@uQ3g;-dC8fI#03Q!*4Hg#S2j?5i$ ziI9N;*E}4}=Z|9iU2#C#CLjNL9_)<#SwXkn0;5j!lgI8|X%-SHp}7pBL_YLj*U`8L z!S^dLli$(8YVSSO@h^Ec{=21o|0g-6uA3Pg-+Pzsiq(@iv*J}D@DMvP`}?7|C>8`7 z3AqIUqMKFw%-#-<2n8laxwrsQILr7@T$*%dt$WgL84D{bD?h(#9akqXikkNC6XM`- z1Kwv*QCGUt1I!2JkV)eOiA#1-oHIkwF5_P0p>xeD{p3N~sm1B-vJOA?Kg=zwC+jAh z<-PQa$SP)<+Bc@%T*#I3-S==>wAo+kr^xQ8ECy4ruK!LRG7Vo~hZp&J4TdA*b2+HT z4+noje13cPB~2AH!Lh)nWz4fuH)ZssF02TRME=RMj}c$e5233D_04q#>~Ej&_fNFf z!EdP$>1%GZZqm2nZZO-sN305s%4mg}ZKN%FL6ysB!0z_$$zxxZbtgT=lxtJm(hP=b zh%}9GWHTZLD$y{lRb+T4{b`&;#tf3aQn`gn^$!u9c=y-V>GW@8;BDT1PXJ{@atj;7qSZG2l zHHU!z9IX2m==J~~SgAbwGg@H;hAET3BB&^90bRIlb18kG1KWiLx=>wcoR(3)Y&rQS z+!u|%l_r@<23NGH_b}#@sDHO(mVOgqrHTKAcgG{q=0Y-abxlEA0Fr3VeuuS271uc3 z6d#6veP;nB1S<4gV5{(1k1z9q3W!|e*ZThc8B`j{m<4v zwAB#8f7yR+7Pl5M+OOU0dQ=OR^H{d&J?TA0Ob-CsX%p`+y1hFl&WuPQ5Xy|uQE-RB zh$iq+{IJh8dj-(K(4Rs|DLdeyAXP`q=t0`0W?u}aE8^qg6y)ixT7LV@7N;mGC@2tS z@G`T^+i`{vm!#mqsCi;1t*F$z5my+%;dRMKCZ_!JrKb2~{1`T5mLpgUp2qH2DQ=cB zI6<66gam8GD8?E!!Ivg@W2Aub%w;_MHVuhi4uNYKeq}k3yYH2_kQ%?dhO4 z$(d|ra#z-aPTVqSGHnK&Qju6h8%GyZtmuElwpvJl`@eI$ImoOY$_FBDsy$iN zAc*xhq;XK333G{CY_0VdSwm7VrCDNE11l{*%zhg6u3j?c1*?ys4Cu?EOEmOjG2o~a zg=D>CD7P^T8p9M%6;vXF+}3cn>~SS)GzYhIwjZwQj_dXwGC5yD z?W!*-P7k2k9sf$&A%MqgH)8OsucyYU(X@o@J1YtBd}vJU%1A|7SM@GwJK zCOGFz{YpqCW!l z-&$mo?zR8j-b4f`c-;T z5=}H?07)#%#;bzjlG1|`MX)!;7`W9|=_d&Z@$|46x`LCJX{p1xCl;jnD{D>>s zR|@El!cLc15I6fwKAK$WD-%gfURxeaEX;iY^5kR zx&0Txk+>p_82j~c(#3lD#b$ZSdV(L(kqbcT$OH9+Bm0+Mo|Rp^mA^%U_SF*NA*Edn z)e7_nsS6@*kEGSbwD5Qic4~Hgm~QXDO#~!5xA_W!6Q&c~eVAq6X+;nc*pZ>fqzPr? zBS2UNR?#h?5Z{~NWaJjzW0(clyljUZHB=L#bwcII&0t`^tvTx4M}hx!V96xgx!HpF z;!JDz--*G06cWPbHGI@8u>H=2Tl8vH zrly*$v+@q7XQmWpr-1%9MU`ftQN9N^HBJON5}L7nCH?D(Jt$B$r2>BEu?Br);e|@U zc=8@YjHvYR+4VL;S3q1Awc=S_W@bo}&2d8LwBau802-`7aU<>L|MCF}0RkFRUHpH- zQ`v2_tBgY(w6S8qH7ep%z6(3kgW`Za`7{=jR_U0BP6fIYO`J0`1y>USNy5bEU>vnj zz>Y}*ERN1KjW$s0kQp582z}xS`Zr%eD)gP`uc&e&sT;>F9oZQ5Zi-|F1iMF;cJK}X zxik#>EF-39ppDumxN(7PK&e@K^4uGL>@`wuzaFb%$-Ky_e#J#`h_;|Q0S6Q&j~#J) zJNVx@CFlz&*KEu2^A9S)Q5ZpAn zV(LNu8ots@N5Zz3MPgnJn|u!fX~Vr3(oGT~X*GJ4iXBBu2?7|IxE;!8sh(%j<+2I1 z{a31UIX)p<*!nGYAt4+K`{mx$h>^g|Wp3*3@5ykG(Wd8Olx=(){Rv>+XVs#c;j3P^ z+7O8&F+VgU-eWkrYxrGHt^26?x0K@`jM~MWj|Y=}_v;`!`bOqf6Z!48IH7NLcGc@= zz_bQa6iCW*U)Z}{J#%OIaM9?L4(GAfOL z2dOMdCW~hgJ`g+qzoS@o_5v{ZfX2t6b=hi)-q6kzw#)j<^A9|sXno-?4}}wj)@n3p z5c=d$U%pI1O&qF!jl=kH!evO)7PzLQ+NLtQ`Zoa#i+AX>pSKe919`ktS1-W|)9LTF zo1^b^rG=7S)BRA(Xr1BBRC>=x=bOs1UXQ(z=dkq&SI*Ne>K2RFXkYK?(ziVKnS5X8 zs(>+Jl8u|Lob)7?yfJT}lOnBzkVoM*i2UY%E#(O?^*Owllo$YmLAk^D+AM^{Dsp z`6XWe<~(MlMjNoIIzH@vr+aYUFUVE*H62!@6}&<fQ{7)n|hhEA8n z3tiIO>{=~G=Z8C7h;{Rab*%l;KM{Fb#sc3)$f`S%*Kzjb!JsYMuE*TPVAail0$Pjn zI66CCi2*&joNK3pwxQi36COMijp8&xpe##5uGN{lZwLAau^VIr(kX&~hb4qrxJ&|M z48x%?$c}7qHxm}gjRTJ#k-gA~gp7=g`rj#5aq2PDDyyiHaH1?=r?gk;%^Ux^OmlvF zLLD&Ch=HSu)|rwGZy8v;G%;Mx_-z;F$dl}My<2(Bxz-0N= zy9dZQ?~O;kQNfbr|2Ytf0I!W=zElvqY|{et`Bzu)vp3%lYczcvS~`22N5Bzn)MdoZ}2#^-w9@v|j* zntAByd)pepe?O_QJr%hOl!{JET3me_1aswFuWfI%{RKXtWF{JOB5SGR5szrMl+_AA!Js4RnSNosO$pm)m+o-50O{jsa&J zj!*ei+=1Mei*oPBi)>6UBL}(b0bXl~LS8r9zGr{nh=1Kz^!c95YW04kue&?E&!#K- zpK4t6R4~wasJ=&i=Bs!dDg$-+-%NAOid~1mV_d_d04~~k;R|zWGBhI4^c$#RV11%$&vs^@$ixt!3M2}vFV`ow&-SXD=fZh5(yP(6}^-! zA>D~(63RM(WRrnVJsKzg%am|0rl=LHKJ!nXjRLT2-82bznUUZhf6SZpGS>m%q;Qjr zw2Ek`2GLxXSClu^bfGYV8P>u*6eIL%f!BF9?F+c$ozZhW~w%BtID@5#NvDq=7-Tru-*a7c=0oeJn@hRK&Sdmb_}fC@C* z+rtEYaq-B#t4FbG(WYg$kPk@&1B4(9jZ>Z+Ps%apJkuea<{CwbR>v?);#OPuu<Al+M8Y0>wyT0K3>UteMz3r6J$IFx@NoO*`w)ViraHNhfh?UiZ%%tK!k3p^ zh94sr=l4W!E8Dpr8;61q9RPX~i-G|@ASxZlhMch-Ai5PZf|c+&t4V-BBTHM@M!$%NL<(BSsiZI zU%FK#=kINXH@43kZ69|{*vk=d-hbA&zAwFPKMshQG#`fN^S2(mIr0Sj{q8qU1Ndlv zdZjX2TMCcPO$i`XKP`F1{HV9Sdpaw??V0Kh#yUlhItL+VO=_b&|LZ+~Vs1?l#ZfQE z0q@)J*N{Rk&n(SGJyVF@!*sC$7=Cmg;7et?!ZL*_FxkQ#&#(OrrZ|>a7B7YYDM5j& zg~25X*P>w=V!l|?%vFOqK%ELVg5`>N7rk((c`CGnYnjS4Jy2d3UL(8u-GbyQJ{qTo zJ|XA})+Z>)X~x}UX^dN%1B}Q}mZ($(zSED&67?4aSWhN@fC6VOzGw)r)S$W^=OC{pyAV4;H?WuR2kON^1+v zBoF7IFka7n4Fo9zLr0MFS<({{&0B=%y@=Z`WnzQIj0k~2!SBG9cDpeX*RyE20f~h? zhVc)F9IDRmj1PTa^T$B%F%cH;HO!Q@DJBC{X_||!fb|xkXZX_OUCd7JyJNC=erI#@ zp;mkPg2MF4xj8g2JJR4m0Kd}vY$dL7b?&B@0vbIg$oT$X^_5zq+5K6|Sg3#;&gSImBZ|fCiw1Ul&m}_u577U@jL%)W9NG@=H+l~v{Lx@khRDz*fOHsYaGY8b z;b=oHQ1>;=JFUC_KAYLl2X04TGU?t$7_NeK%^aK5>b&EW#)djb9sTq6Ntlwf^%EW1 zx@a^8kzf<}FIH+bo!Op@GUZ7WCsIu+YiRd9)?R>)ZeJrS=VKbtn9jq+$G;fGCw|0I zDn7c8gFZo*5_pLXNt~RAKk=LH>lDRCuLIedSv`8&zB7F}@6)#L<|@r++lkFWua zM=9t$Pm66mkAzwd?Z;ryK+xKv;O!j_(~7)G?4aT0$j$qnLYe*J!4crJ^1FlSZ4oDj zxfEqm`zm@e;1(h9UzF|k^=^RB;pQO&TD-y4LBQGD+j86cJn8TEX;>!T^}pX<_ZJ2) zUL)AHdoQ!Ox*t4W9`JE2V9GE1)6QJx5h_kDLHz;yahvb?br6{?`$!(!@8z&`U}))W z1#yqV&3M?^OzO>Xxtd0$eJYV7Mb4CfU6up>0zX5F{aoGXLI3@=q?uR!cSJ%=Jhi>uvLnpfAB}*=o{Nv2*l+oq zf`TZZDy_O!`XXl01v%>$Kqa$mQ&^_+tcUti@({RK&JDHPG0`q z8bz~Y6X^3_X-0y*HX(o54OS(b2X6RBod8fbJ6o^YlLg#tSQlaP7{PPh|{KUN~PO z3?7g4&flKOi~_b~1NLAIU03k^*)uIh!Cik{>Yn;Hwgc`2%Hoq&4nBHa9%}L**VFs< zDVThgr5urq1k@n7M|+Os@?R#&0{U3MJ=ag)P&VJknKqiYZ}QrouH(0{f>zIy8@}n+ zTVD4G-u0ZF6*TQ-DH&c-d!F?MJ|83Ij|aR*Ic{(ew#UDpF6Q^)6dA65o1F39TF5ne zopOus9GKeF@_mhH+G!CGnf$NVT%g{Td7_%>!V^qwBZ$h|dv#`<8SbM!rZZJ#ed$!> z#2Wt0doT%y-$*W{0#`We1uvQ!O(`OS^bSl5ap=}wWQEr*9_C#?Eq?-`@r~fd;;ECB z;zj4tP=vQ;mRe`P^zx*MEH2?Rez!1f5U$jb=RAe5h&6S?M_g&qon}YQ#EQC`%(h+7 z=$qg`wJM7HwL+NOk6s{0<27XVN$SghNQ$p0TdYt@mWG4KXSIb;Wk_~-pCs#*Hf0KP zojghidd4k`PsAp}E5*gAjoJw-dK8n+K5$fCfOGnQ}4mG0n-mT1%2$#(Dp zoZO~6Zy6k~_JNbdp=zqgkN5kZ>8X8qOKqC^4%Buu|IY$ATH%nm`O!=mCm1m++yLW+ z<7_QopUqCU|Dbbsd;_EZFp2qjl@aZ-MW_FeWZ=upeR=)6EIEEu#J>nn;QFt_%LW=~ zs^6g3tav^*i2NLRbP#w{6BE&qV29NAfFIW#jePEw%Wl0D3}9T2E86s3=gVgKE)L5F z8|c^B6$Y6@h;R9~&pOK0ty_NAXqIi-JOB{!;XTl(-MlmykDT2-*Pe9M0ySst$=!?p zHsa5O2$P|X{x1dg>vy`vhK}snVi^X!0s?GYT&p&2%4qS(4=Py41Co!>)DVT5@^bi% z%NDB?%y{$iQyErMKBwE@np?Q2j?YBvljKR&C*z3)vG-nN`ef)-gO^PJ4g|5hB<@!!41 za(#nZ3>Pr^cw~nF5jRMW@Ao^Fo033-4LT zw&$#n;q!=^(6$ZH%WJwpz3ZVFV)l~uZ6%Yx|Mt4z_diY_#3<{R*En@mMqS2{5C%ZP zq3_>9kJm-I6~CcuZIAh|!&tvn+?FW6jrHEEh7P$cpBa__M?$Ze{9e1irFuA=c(_V* z>oUVsqEEnV!-;4{FpNu9Mv)4%<{ED5ZIS3sdz~aIt-v4_Es~eX$eSP&U?!L(c`{cg zuR8TKPEK<`qXRzu#Xl={FMuSbUSD7}eQ~RLk_W_z+%4t!OzuH!jl0!WVx7_nD`$I48Zw|NB`~YpRWJ9PF7wT9S>wX zh(C;M=Ko`OE$aEl#_=U=(%n8w@IJP@w_yFODAyJ@yw!g1&=k(NX^nu8FgG)?@AdDo z%gh?D;MQ&qD4Ao#yagAmp85*c z>S{|Ni{~RKBMaeD98^#$G9eGC&AE){`n60x$03z!q0s607?pS3vAwwIU&g0!mIi0L z`zF;j8Q=4<>HOz&cP&U^Pveu#m&$Hq@sqr-Z>R5>aG;XDhgzS5 z@OXWzQrG9Ve4jImLMt<-0Z++fUdLZGY-(C-51`xi_=SCa#Jq-Ta zPV<*Cb#Je;7k=im#SaD#@5?W`lQV)QDUcbHhL^o`0XO~Uo2Xm&cR~j*Yw+K`9)Uo5 zm#1xhZzJ~cXI`E+58K=gt440;EN&oGJ-4gA_siOdd;V6xy|O$30fGA|we&3ImgH!q z>RZebw>aiaQPF01wD(aCK zL3ijLhag> zwQSYuUe8Nxqy;(1&{t($vjlRKp)sBN_IHvRAZl2ZPR`q#9vD7*5|MToW})cm=cl94 z({|BnxlFdSAX$Yn?CwESRYQC%iS4;yGr|hIRANL39_%DE0(nbRd7ed!N8e{uG5}wn zrZskjo6A8|sYwZ}Iv}HL*3F>9!sHDK=chRo$ase5k~d%*Rv*Bp8M`mM_oAez!NBb! zCMNdpUv$1k)iU#3^Xdt@s6)5Y+o(|Q0pGUH`jPfCJiTG}71@XH5cq=I7GNHq?#u(h zv|TmpXZPN<>nB}3{&k0)weh!Jb%*Xg|0b4C+zkkvyEYZK&$@bm*+f`m1j=ONmC$;t zt>W}UhNwJe>19{nE2TLyx0slH|g=R{2W`MA%{xU{G2WHPd zT_5`|jy?a1m%(HgtJt_}fU(%#X>>K<+WFMjC; zjk9FpxN>=K;j>2GMak5=o9pjqiyo~wckkz~j!?p9B>}I`A6_$beUC?@Odb2DYNFXr zov&eEpLgM<5@CD2kA&XdPnJS@vd>Qm8oV<({6;@tJnzh~33@-#A_mTG1*{iOYtTsz z8mzvp>(zeozgzzH106KK>9+3fwZsx*axpT=^rU}5Vbr_B41=by<@T~)WTwT=_YiO) zmcHdWg&)vZi;~Jm^Dz_+jLvtz9&qN1KKJcL!%S6x0kLs~0Zuh)#;}aQ|qbpojhsg+=g2aFS+N{@9ZM^njRxe!IXzB|{%=?k)Qw84Oo1$w zZOybxVK4D2Y0$BdD%jWwk8GwaUpR2bS^G<-h*OTPU5AM+ZQl~ql+6b%)Kj2&WHG zmIfO^T_srkL5Xfedlp|Spxmzz_N$?+E~iEJ@mRy}@v|@4z3GA$(bDNoQ38su;}Fl4 z3*xo+qDg#Y4<)I!Q;UvLYIdl`#juOV%JuwOT3wz<9gQKDsZh#Rs0?XjvZ$r9f`*k- zB%jBVJ8}t@8jEio<~@@14)9ErV2tq#hjDttN2L|1)`>6T(rE|yO=rcM^yZjt|2V5M1_s3(py3P@H0Pk_kD!uUe zHBJa!2#qERBl7PBf_909qSRV4v0oX{oNI1FAi7=61!;u37{nUQO)~Uf-wDuJNKKkm zfE^An@;h^l2oDb?X3v068vx-92*c@eEo595s!~Pma`gC5H{HN1Rj+7#X9b74kaOdb zi%HQMs@I4#WT&LDNy-ifKXDQjF(lk&r4h_!`Jt6;@t@G~JzyIV8GhW;Ir;;Fh`nu} zz1hpMk#ME$`|YbL;L&;;<6wG=d>>)!>wcOdt>J3@vrzZ(y0B4opXIT6i3kd;6VT?4 zra0_9SwHNhyIBZVa(utL5Mo5QfBp9s@YeEj5Zd7Rmf!nu{9w?Y0TF2B_`a}h6lFK7<$WbXE2KCl(z6En8?Wxtg;7}%#c7plrOTQK5n@GEO`Gt-wA->ZiLdz^kM~Xwx%usCCwq6@Q_;lD(N z(0)!vn?|BcSXffeq}C^SVu->O@|YmWNNruK{_&MOa&)m3JPBFd{1|wxI*8WtzgyA5 z-kQShxm4@({!>;^AL=!^oV^Vh(Vl$$U!gKg^*&H^BUU#x<2dey$L32U9ew2+>m9jlXna_y@6t6XaeDwLf4@G(x*9t{P<_4aUlsYQ^@qc}CP zn0I>M6i*7~^w-j*KgR`XVj2ur1<hHB>1wmBNsL1)v4y@&fCy?=Mh%dG15eg@q)G z>;SCs>le@k>j3*=fHxsN5|-dgCx-i<#X;U-rqLR)M=Wf>n=NQ(a5s_3BmGs+ei#4# z@s{juJ%G3Ed2I|unkKPq6vE!w8RI4?n7IA^_wdX88l6^a{!I=QK!Tzh};^()^3YJ6cfS4T? zA%-mS4~Yyqij+vg1S^aig;=}Ie%(DsTVo6t>q`vVY_WIa5@C|n-@8N@;Wc{-_AXji zaES7IZMM|$&AQrWS6PsDljV>1-MdvIp#Tfnx->OwKdndGMHV?M`SuLx7$-fNJS>=(-+y(D4Js!FQKYO0)VcG#b_}EGKT^E2~GQ>XRjHG|@^)988lgLt-GC+*Z}#Aj5?ErS+<&cV4hmVx<>CY_)w>Ca{QmW~U#wn`a3rxnWH_10!0OT#67=gMuGh!Z^^xMo?g@Y z0fnj{1rvuVhv5BGUS_3*PG{B1C0jEkS+;cmCEdW$A*o=&nCy7@opuc`2dh=_v}D-` z6otwrX$f0%6{d(nW@ST=UrmaeJw%PDm9LXxA0(((B^#a0kO7;i3Z#`bhs|i2>&geK z_eOOk2Gwsa92X`W!zXA89RdFktSe@BJ9Z0H-)PD1_lv=lLZ2x5#%H|5E9_i2FgdKS z`!;f7MHov|he z@RrkCrWVw=-3k7LHd3t_$%E(uBa~Mn>h1Dqmq&i)<4)ZLw?FK%{A>2EU}I0=o;$>e z=xCZet69oXPbMDi^~%EIq~RDBq?YnmR_sA2KB--g__>x|gH7DP9i0o2oa*in1&Jzf z%}io$WfkeNWzzy|h~sz;GKk^k+7Pxmfg>Pbj|-DD&F67$cWN7Z;rn;PHsGh05DF-l z?WvZIFQTu;A4kOQriNa8zR8vHccn+4S_!?4|w{C?VfT%mkfpq=TE+37d_-#p1` z-Tll5I?*szIaP*O8pm(=m-dYl^lJ>iMw6~PB`C2Vg^VrTNNu8$IxP(!A&wG(WmmOY zqfyjgDZ;y+O%jK5-^y)HydUhO*nUV1R}yRB5w@d(l~sxk z4e{KmEQ>r?lJYl}j~X0{7q#AOPXBWo=tWQNeR}d5p~HtV6VXU%&_p%ZZC0#V1o`!s zt%$bS*Q@c$)S=8>JO7o71)@<_UCI)Lk$+J8MoB=^J4^o1_!82X9j%W3qfvFfMpF~7 zIi2S{w3YT;M?@oQ!-G4O=r-d{Ov8TSXruZr(DL+*MuWuFB0-myE^EU#h>u>()08=~ z`qds%)m)-e`ThB%hip0JdmLI_aGyqPB-ps;(Wz2V^>lN|G-QG-`PMR3>=bI|tK_}8 z>sLVW1&v?=NueY@4vx!~p$2>VNn%aHR~qaUN)Z`4J)#c|4syE^0PfQ%3xH3BSaJ&B z>iVDdSV1AP6iD|0^wh=k%!9v&4h???EGwL|bUjMX>LH^Vtns`iNt&qztli^30Flj% zW-3^P5udS9;Yr^7158be*3VW>+(>rTx8IA6-j3UgWl@Bi`y zY%e+vH}L)4nl4^q@qP`Ot-B|g{`nt1cWn_GXsv64OK~;*(}}>hoqx98ezB3h?!qSz z6&~%vwG(Kg04@~u&U>)Yj-LEnL{b+%%7*!zTNOcabvPD~ zYrFYvi%sotD+04RA|h;2B#IvgJWZw5Jyn&KBRm!C=Nq&5o1(ReVk10*7+8M9F1bWE z(r@FzM}VehHctQmNi+Mt^i?q+i8as7On(KEHTp*#-!c9k=wiUPXbQhiQiVmz}n8UVSrc16)lsG7d`eKOgn$^um5cP z$ukLK0{R?Gm^@7RQ}xP9H!iS!8b`*9Cts*jZniY->UNO^2y%$V<2d|@Xy@{iZZWZPya_$?fU9atg%(u~6-Md+~ zwK|=yM}XLR_YPPo5>zPTvkCYOoo^y))^wf>VfO3?Cxhi4piYGV;Jo(&@d|SG#@}s^ zp+y&2N@#{h6GLE@4XJqXNScNR=gnU)F{8a-`EnK5Wf+GBu0H6m-th||{fvxYV{1yY z;8EOkvWZi3A%OM!oP2&cbRnlIQ<3m!jNvCMOEy@~JtBc6p)CwISigP(0QC3X0;^{v zWiw=kj{ir~Sw+RwL|M3TcL?qfB)A0#+PJ$*aEIXTZXvi!aA@2uxVr}n?hq`v&;8fT z^b1eD=(TR$I#uWF{q2SS6grm!`6#x~PaC_OA zICwCU>py7EcXs!`b;BFJ*OT8RO&1{=;p_o90c#*!Y8p0Xu)PYdf})}WAc36BNh4NNG)4xXOcUUi)N+d2Aoc5T8^VX~C4`1**sw;PIfhT;OqDY~|n zcc~ZgUl5ly&mersscCRxGVRt3my|;zhRqZDVCc?lhIcsOtSdwvU8SgpfQKLOE1=v0uK`Rxiv=yD9nbT7u zdTfNjQjrdFdXZIucoez0$1zdv;%H75J>B?h)8nmyd8p}lSjwQE-5}N*0hODPQD^Vt?*7|}gc5KxUkYG+ZE^5#Unjcwb#D37 z?37MIZj(=_`S7ju2h)11(=MP5?%r%+l0ytCFGj4#%5ATH?t#JZJ(g4I-U=R$6KdyV z$BK(9X=aNc?=rtWNGdG5k~+-ZZa*(scLEqfh3LjdHe_e3(w2J>fsa zz&p^tM*JtU0{DBMjtZqDC96Bm+dtL(a()Yb;b|!qJhR?>`rQJtc-5_H2Ba}jQBgo@ zYe1E3IR&lVNP?I0&)*G3ouQl}snUm~$UN?Z0@0=bI+Q(H%$-sKF`3CpyW1(xjEvtoK zLT3gh^BYyu@a~Ej7?dHRa}&Nd8?AFJLsarVI(MYuOYq5!JGXt<1}fWmm1q2M-x;Zi z%HeA@7Py5DGOj4~ER18Jl{<}p?j11EWBl8++d<5--4;9=t3AO+BXfch364*cmRVei z6UGEHK$TZ5HYI+j{%f+LL=awmYI0v{uCu$l3oOR$Yrs!H!F!MmSg5G#)=zIge*7pu zpWX4P(%`B7?X)Ihmk#Qup96uvsm*c3iRs!MpWe4@UAL3V0q{a^AqDZ7E%A5Bnx+1f zo@#?3OCgs6V}c8>>4V!-a`q%dG4K7?+01&1%k6IcI+hO0p7T}7_1oLV0MBUi zv%-8c(~_G?#r&DON;;8*3TAq&iUuOL!hF5_IL8$WT0bJOKuJjn;Od-M9!>?7e?CD9 z5tCQj+JObp=LZk$xhEoK^`3Guj23(>{f``#1N2ZbZ2{&fpv=QGHq%xK-G?jHY#=Sw ztN{>Me+nUiU!a0v`SZp3rfFzZNGlFelbyvZCK^S0n=Al(s}8^!mrG;meAtPJDS^FS zyKuw-KXeIW%*RY9CjbL;sSzi)6^o|1V+E)b5;)>}C{;*=otmqNXi>E)7^`ykrRo>T zZ4o8y_2Rq@g&zBoaRv16cANqsQAuN(u%F3g1(vu@O#D(_<`& zg#G&FJ^BPGdQjdg9`Etin6?$AV!CoSi*+i6H|G6+Ex_3j3wP?Q-*@T#Nop6PSIkqC z!J`%qIyJQK#lPjL7=%j#2IopF6LjEc5n|*f6)W@ZLh+soiSD{!79t`6t28rH1@Y<$>i41nHrGq*f8zpcAaV(z%N%-Nm# zt1Sjp*5WnbNC`YTzoYyJo2FF&A$fHyxxM-QGt1Xb?|?!q5a=G?cDiDL=$12(>nf9BkbC{W7UuqYf>IMmkMBiV546DzOH(=`nig02`a3 zMkX-*k5)|Q?LIhOCgN~oodnFedifOPWOb+c@zUUQhJ4SQ5Q-x=A5wcY=2{>p9v&%p z=Iq`!cL{Y@;q-lqt8DLp2MOCHtVt^OBZWXq@YLL~?!m|}x!t6$D#K3iH>!zm0ggt3 zpL4VxdGQ+D@5K;0rYzKWs)mkLMLKVFi4@@DtJka78j7zeTZNC3`dBMl)qN$gwxkeO1*A;S z^pqTgu<9WZ)kh2l%((e4`7?(aU&WmkwIBjip<6HoFRzXRjGED^Ge3+Gci~OgaEghk1OpJ0PHNHnL!(`K;|*9@9PBKZuW0 z#Iw-Wol9-ajLilEI3S zBRKYpOf!E$Ei{YgLd-YDl!4*TiQ_iM0`~(sj6f6N>Pkg6!%k$*|_)gcv^zg21X*@>t(^H!a)`;frQ_2>-sX6(xx}QD@ zJErrXPPDkxo?*L6d^zf;mZ+dz9RJ$bkxF!2v3$cQ91S}&ya+8z@L?H=vgs3y}h0xhldU`y9i~q}|)j_J-y`hiasopqD z9GZ+VLFn=~2!yd%_KyT?s(F)c>Mn1yeIW~H@Iu`_iX(J31tDuCV`zX}Dt>I#UFiK+ zGj96jf(e=M0@wmej1LWt5Yl04CPazfWY$UVG&`-xf*SnL6h|}RDF)wZ40{Op^Ww8Z zsM-#Vrg*csF36t!$L@`hEAg*uFmdeoHWQN>_pRPs+U01Cy$^%aBL|U_;)<2Ge3B-y z#sy8=GT+bxd3|EWnDe6?e;4&c)zMEOW1$Jn&K^-qXpXLPly|g9uin`9+}vo4=na2l z@#c`zYQ2quNlWwk7o0M@il~$DFjBat#qxD_X(@uH51_d+rpN{ayaVYFfw7=f-Adgi z$f6AzDynC01a0s6`FX~>{)(Sbn9Jk3?=2Td{_EeB;c&V4>OY;kD$^}z3YK?wcg?!Y zQ;$GzFHW~ub<`<)q&z-8?-jM{wrcJ=Pxz%5<4v8y4WwPaHw(00vNKOMn$NhV*PJ(B zF^I#1ro#Z|x)zrL&Lj!eeN31`#bTcn17dKx)o?&~HcWBRtQCFqPMcxFik%MgTJxur z`VoI;gHnAKoZuj3MxGs2qHC_vUWz*@x~_}y5J$UD;)JFEgp<((6=5_|#;RKT&*w0~ zDHTu7{A@O^ER$Fmd%4UaVwgQRy8@cjV|E>p6O^^SW|6X_$4jpjq$nCL!pG>aV3|(| zXe^Wu&Gs=113+cOnkAT(A8L>$Md<=tu^=WUn`t^A^;wHeeGb!RVfgI&ueCT2v=6F2 zq+FUROjSc$ae}?KBDPy|?=<|zlZCjFbal(+Y-fBn%Xe^5H?5JHgZQ8b64Af|)Bi-# z=6b=|3j0*i7_;Btq&ShpFTR&+$NEuPA6;J)Yxs^@;2_%5QY^OM1P!-C4Zm)oFID&y zp8ApTfK@wsl}GiEvAQPYFL$zy>$x)5NJ?RmrYIqwPTXJp@Z*QgDP$k6M`LWNgtSRg z7EIUr@=+wwalf>ei4vCYyg?GsP6?yL_h(o-^h{avrKvLInSt2`DZl=7qo?F{(2udC ztXa2Rb!PYyvU+0<5NYee&`g~Li6PvR^48i6M)&rL!tUfA0+8T^<}=x1RhBev1vOlA zN5|Slo5_iZ^b!CwHZ(kpfPiqS^jph+yGn}nt=#V^3A9D>DVa@aer0q;!E*5_!eEIx zMV9`nC>8}j7|334Y-s_sdskOu{TMYu0C1;OF1OUxjT>ZitQt}0<9=c2bU>&_Xxja- z|62Aa*$0>9g4!<<*R9T|lNwfuKzU|CS&6YVu>*)=Lsjv=GXQZk_JG^4qoxL*^c(Oi z+w|-0OVv3vG}sly=D9$MxXItuR-Et@3>viq>7Rbq=4~9q zB2n5PidabuPkpAXHn3&L=;&zqe;@1d`q0{3kg;(Q8%FTV{R;&m8VrHy(JQo!dE2s{ zEE4uftdoKY!H<8(GI~ROF`3-vKk(b)6Xg^`_N*zoK|b}KsL5put%T2T)X+sbqcsC$ zqKA&dkIAm}scSku{?;vDe8GLDbROl(q1?Lx97a~}={z{uNuCat(N|pfSquD!&GG-B zKSzb;nZ{`<6s6M5KKlOka7JMw9po#g{V*EJIlwBydThq16D|wNguVNR!)&K*%;LnC z7Mv#Y6ob5}?fPv(r9+x#_M?8)-iG(%T7w|c)xIJlTH&J8nvU&e5KOvOH2-(JPnz1P zVOGocet(Y}?SXmT4X;%HZBS56OwIw;o1X$?&-^q`{Tn)H37bMb~Y9V>73Kc{JgxL zXFvS)%hluahkq7RAi_=!DM`wG7y|BJ^t@Q)M{O**oC9M(N2J_ zb`YY@SYqwnrNyD3p%EBZK<|G9^CR4wy_F$4xa0?#geWU(!n7=+XdcUp+07wd+Xoe> z2+T-3DjDZ!%4BCrM03=|DDWbZfU`;LzYav2n7M+qFlybf^U8+VV zLf4m(Vgv`W$EgrSZp_FVnV2}6n9N=KW*i_WB5DAdp4+c|WEK4LN+4b*d z$J2-D)~|wYI1pr@dy6$RHNngmA!c=bl)Gw%>Q**+v_nB0LzFSzE}L1Wj@X1vpoFD( z(prnRLK>$&9TFtxH>>(`p2e*%blTHR68H?(6rWZHYpI|IU zu|Vlv%eFZmn4TR2jZX;tC#W{}n-mjcOLg66%zw2R=d8yi=$ zi^Cd^skpjrKgFd!ektO_2ud*06tLvlt2HV#0N_JMu#|necey%5lQH+gr#d1*KC=W8 z&1k#K7S>o%fg%X+Xw$QYkmv#vFlRz+$h=b@6VXrW*tT+! zQvqFf)t|U$xY#f#boRL2feZM}VfMyZdEMHFs=OjRS_OiZ_{H`fZ+pwZ3Q+-(4;Hge@RV4(3$ZkE-%QE0WoY|m1gcc9GJ!n?i!CNo~@F_26rm+ zdt*+mDLghlb>b!TH1=DrCGWz5#C|9aMNYji|MgK3ML0Z170L>&`B=P=*ToeRc+6bs z8jm*?hAlp|1KPt~XsEG^wmrc!LW*NwG-Fw5mNveHU^g)uVA6WeMpNDQPHb4T>H8>- z;o$>4;!xyJ&$FftICxe4L6vm47yIUsu|>8)%_P>qtvi?I`8GX^xpMxj|9@NtmfT9ei)e$9&m~ZBYLRh~Q8sD@ zjF1SC8xdc2o)ROgV9D>~iL>CMNCqi#Sz(GX;ElVLFM~}^m!_n1xXId{`pKVO45Ywg z`OVvj0dFUpxrY1?Ni~05CWsAv?D*c9ZzH;H`!lXLT&D`c;6QAiM{<|BO1)|yFkz+w zgkRR4^S=faF7>pt_I7>A$KNWi*#6TU(%lBP(dD%5%WT(8TSUfLB2y3(UkTsX8ia9( zm&qj%$7?}9f*k?vR~p+>w1f$w>g$K&XEh1l_d^dBfu*CgO`NMQy&?NIkZ#9r|T4tPW`T8vvGK5d>tuN22|{k!$| z`Xj{0x3aeOJjg2aZLN7bH}_agsVdKT49n@}^)=~}<{zMv-d%j%<&6RU zG0;=?>(*yclf{E1k83F0@)5|AHHFMrA2Cm0#`?tFC!xI zH?0=@HeK|k=D8cpQpbvA+y1sTU)-l#$SiU7N7BC}TJPWn(hV@Bc=MJf^JFRbiiY-S zNPLd1uCCSv_Cn3^{gEz%^C|4{TwDw)Esw#Q=uK&)Z7k}LLVWx-sB9PLY$)5(qRFU* z^_;wb>BH>%ch6_qaqjb2yMXLt&_*x$`?JSX_rsj&c$*k<){6V&;`8Tjf2eYpza7X^ z@3=2(la4F=m*~BD-LP+Lp&dehatU)EpnvVWw(+vg zJ1q~vv|-ZW=~KO{@`83Ym460fyM#7FAkZ^xW*pJjbCiO*cV7Id6MFv5yW&WJy3s3SU4qM~znPkt4W zLyZ;U-e>Y*NZOGG3Gx^5!{bgw!cD;CMBmL?5Ff@|An2mv_WM}i_MK#3iO?Ze%pamc zc7vZ$93{m-cnAv`{QZwWCO$S`hhBe-vzt|Q4xbsjUM@`FUY_M|KrS;zPJRz%7Wyhw zWlUJfOmnfTkn*4PT!Zn+fWwBazs}nsrDJ65+SAEm&gY+pc#9LtBe_&X{|yDIhp-@Y zxh$y-JNyBvv~m$J6SQB8+f9}&9vziY4?+-~nV%2&o??|!24SRnkWk7+58z(#T$_G` zFo3MG4~6|qO&<{$4ZfUP?owBoey#O={P+5NPp!S=wqDPa>{_E;7mUfl$M?8wdP*{^ z(|+R=$fJ63p4)jdmjyDivpdF7dI2K8hP%#`SUe2wi8o)Wtuwo@lp*OBNGiO=>i4(K zZFWZ`)maSDh~r@Z-?-m)`^}>t9<+5igLfIu+V|dx!eUSt_yNE9 zoibif44w9j$=SCnDHJoMKA}y2O`+>k#5*o5AE=gXp!>OtmD8}j8YO~h`jJ#Qsa1I@N`_@a@7VR+!=_3|Va<7h-S^2DMDgsTbMm1&1BqpqZ$OVb3y6 z&}>2pb_NmVU?Jy?Id!tg!Z>oe+!(>n?;>kDOc^hU{Jm|G--BTjwV1$L#FLb`>olA; z89W<@B6BKd@gtP7$u}`ZE57HW`aQT3*dIBq8h+Za1Y9Yy3F4bsHXeXNMb$au&&3Q0 zm{O>nww?3n6XqR%7RFGG?4-6PQ;@=h2=Evv(teU<%}ffMHZ8|tw`zNB;&@K?SuA7g z`sjk8r|RO+@sh&tc6~g=U=z$r_0}L95ABzz?}&MRU5Ctf`wOvHwSAP=Q0{Q^fCha9 z3OTet>5Drv5g9I{D2YHn+uw@|pr3FAiNg|peSJlYBQ*8%^8*Z~fKXsuSKvAAFzdnx zRnYiXvEB5&1wywKx}Seh{TZFqlHJ+GMT>nFCI>rvP!M)7+VSbBi-DHL;+OMfE&;n7 z?-PHJRnvs*V6Pu385y7VjSq1AkO1=K8kkO-(z?c+vdInZ)rPb&#P?95%?K<@RDQel zvjOUvDE;u$cB`ex65t9SrV4?mtKd%G>uRD@;ps7tUkey4o!quB0=S=Zh+E3|etZ~j zPwKe2Ku(#o3T|;tjnb0a^z{H*O&P?PKyp+Z`KyLT7$a2^^@-+Ar5Lt;BX5!e-Vh;M zJj}^Sn zlE05n5)1n*x#@kvoKSp*7rFjDuJl@(w&A>+SNV`ruuXhfQFvK`v(}*PhEr+X*DqxZ zBXaHFd93(wAm(^n4;R{6`>NSOf|+VuOHa!i^^*ypAP`K7<$u>!btRi#=z*fcmn_4* z?=?mLY{s;gO$iq_fYDe5!h!dqa7zH9i;PJFsX10hC?a}`6mSL2k$fP{6um;Qe<({# z0VMcy&@L~)pW*=d1^az%y-aM~AkFD#GXtqC+Yp3X>;F>5<{6ykf4*;Qmo85+jO;%#R~4}+6S}cq-x<|g7lraaQ!|`H@h?{8+NkT<;dw~!>&>ml%Y*Q{U5amrcZB~-ornK(0%1YYP;TciiK`I{VZ^G(j`hL& z>(O&;%+#0X7nG@0X((Aep}X&&o+45<>0He!!||Uk_sM(4HxTfkfoAC48p0`a!i~MPzNnAffsJlpR!O;vxoT8x zWO|_ainr`!Ff_qzUNkHc(RZYDmi9N%Xoktt%R=e+LIr|?OA5qUi{5%*5-T_j*!$cJ zGOEKPS)ivxH5l5jhd6z1-V@=-OOu_Ud-&iKwL4mS`7j8z2o94urvhPU6Fk3)dw;-_ ziQbZc#*rq9#f8XC3f4tnFD3__mlYe4E zo-nMhQ?}1@GCG3Ev|UTQ!&cy*uvAkY42y3Zyf*oLxMG)inL62X!=(MK=4%oi&F2mg z{Tlu2v5A$`?SPxA2ubw&TX$+o10a{XShZqNx4{C940z3~0k*t_3m|dnBgRTNT3A>B z(6XQHmf6~T0^jo7aMCt=D%@u{*Z7$|pN57Crjwt#?^{H37pC?KylY20Oja>&4VQ_319!RK(oT_ zqVva3Ot@aBHvOS(gLy761HyleGl)%QTy~6cdU0a;X?sa|W;J2SHgEHRO}5Lp4Hmd> z1}%7|K4<9fU%Lit9nFBR}p0zn(%}So|kPzxlom2h?8(UO2o@u04j` z`{}$t6FcyCe9d^fqP6rD#2J&MH>P~!L3MPm$$t9$d87S0&Et>L+TypTJq_}Q(Ir;B z-z~?DU7Lb8^Kh&L!CB4y@494y!jp7HN_dJy(4d*reyy5tk36^<_N|DE&^c&r{bhf> ztaNzQYkd<33Keu1e536BexcZ89L`2@`7w|@kBsfLj0`fS&Y|=tY}lX@IMFTJOd^a* zew`=y@ zynYoKN;W|)O^!@P(^!;mC^{{H*d#MTAY~A+m0bv8Pf&z0Vx|2dT}f0Rdmp%u!I7+q zbBN7Pk$6B|wUXDG;4e+4naqoIeVeF*jcRgR|L#2c*~>M$a+6gR{gS(L(=5kJaMAUT zN_|<;xymTnyKtpZ`h)3`(o1Vayn?{{Ny_FZ{enQgAk*e@qJFYn4FzZx3%rv-33zm` zuD@;k7X?|&e4)5D(vcLzw11gzRvsNVGhEh0-;!;i=LsthSKAL6%BBC7OC2N-%}O2% zP_D^{dM6mhD^ni0JvC<$s$LD5pz&}U=j04oB?x19nXj=o^!B)(kh;|S;X9Hm_(}g?3xdzZV?w}A%t*akdRQpc zx9MwF11TNfhLy@i8wkYzI;$d;$w^7T2^nOkM^0k5&BpRC`~S57QW+(kUe|>`1e@JV zOiTbVS@r2}o2K0#Up+Sc)&Q^uK7h1`_K>v}J~pKki(!@(SNk~2WuU>Wp#h}%x~@9{ z)D3&wWP~mZ5(|qHV}jLYK$0_W)128bY15<%u++T0L<@1s?-jEw@jYu^Uh8XUrgwjk<miJG|*u;yC>Kp(DYErsg)8?I%1Bq z@oLO_D|ngn{j$Aji#)j78-dA-JX01&p z_eS~;i{1+*(GNpl`HG=f+eowplEx1W_UioLU%6Py@v0K@wN@2G z;W{j7WBan@>O80hOVpoWhQRO%Q1S%feZmM59OW75$`Ftv1tD?zi(FC+E<J z1*k^dW@l7vT17)R{5TX8wUcvDFCAf7s5zZ^gi^%92yXooSR@!Q_k;dx`V@|ILaF8t zQpDR(8h)Op35nvi+Apja>6TtAmKs!Yb+rsaf*t69;rCGeSIhQSu7^+^Ou`r>| zh_}|v4rw?=u>AaufNSGEy<-m%)Y$B;w0Xq*Bwzk+`#Ay!p<}uuS#{NlOJExKa@o$c zKut%7&t{ij_H_o~!$N6urOrGX>h4ZV963M z)drTV{o2s>YF&yJtS*Gpec^^GgN|9ldD zWv$UKI!amUlnofJn0{K_LV3T+^yu=KT-)@$I+L>v%l>kB+s8MXhe>9`?;m>({#}1lgr7^!Ciqwz%}*l`(aphsR~@F zNRb`ZmWX(pT^yA&dJBz;kUdCT)saTU1_PS>S`rQxYgU?SJ(Di_&AJpZ=nxjdi7HmM zXkHX&Bxrs>ue2D;-l$cmzRd&;`#@QJisU=ZSE`ORsvI3G-c@3)%eOI8*rLvXCZ?r9 zYeqTHDVg06SzQ?Fa^7D3ham=*z*K(8O+$s34q4-$l|W*c-|>>sKG}Hf9ADaOuF-9@ z-8l6%HdyT=n@+iF^-s>vo`}e}&v&O?|2v6{ES6KO39u`q(I+Z) zjx&pa#SO!In3f{phF)pDb_ zIb|=uhb!)sw6o0iOLx&~rLTXPpU3Gex*x4AuTgZ~>jB-f0gypftXi&F@t=lDx2iyf zh0^SBYVPv#QccOLG>2zSlial_JiG*CG@1Dt&hGYl%gU5CzP`SmX843Gd)(6HR#kmk ztjb^mf-6&JjN1)|ailk7LhHm2}{bYA&1Z5##WgQ1mU~9%oRE{YVvB3 z&qP2$fh?9EXGod?5pGfTP04f4ZGV9QGyL#5{!r))yM>;zEE&Rz(`?ru;^4viav){< z*qk;^1r)WSVCJVw(Vy9lib=Tr0`cw5PxaIKJ~~e=O=|BuPY7>RPs1oe0ZE>{cn^8z zY5HD=v^$H3Z?9;FL&5>bAdunpW7gNC2a(rcasjvA3mW)>+WmFM>5lnsvM1`Yca<9# zFU~)%u29S@cHNyoo*H7g3_lc~I{n=b+vj!=93o*9->y2C7}u7pzD$c~kg8OA;Hb^- zTi+a1fMjengwe#-U};u}*8DlW-c??MF6<6wt;(#HCB|6XP}P?rf6IUnC5$-)0ujYz zls$T8QnZbxR>XtzXjKQt8ZxJ_k=6ipk)Bp`OKi_W)N`R>jMq~3*IKH1R6Qsi%Y!A|MV;!BQuGw<97)EYB9Z>EhFD% zNli?aEg1TeGu`^7_?}M1NbZ5{fMfHTi#yF^$&*DPz8xda{vmvADpV!{Gzs*`Y+#zVKtXIs)!1MXQwgONN zK;8?S)&bs%DCWz{;rQ78ypo_>8n6_xPtWYBe{$QRV}j$ehU?DHz6GdZ!fF{lE&^k{ zDosaYlamrlZ>BxbqonxOYD>Ll`!B%YNCg*qfK66irC+%)`K0~4-C?krpk3$Ng5VMy zdfch94b0)>%18J2!X^QKaFecv#-a<73a*CQER%L4AMFr5MXcOeA84jJyAj3i?9+Im zHy53NY%B~}Jtl8ysH2%V@93GoCQIv9u-obHr~q<)*Q328B|{Om|E`6?zCI7z5oxSn z<60GHo+Bd!P*n3a9<|@M<`yFU_&<||ikzF}B|>mkY{Qgi2~vo6wbRtj1G=y(<3!*eVY9a_X#;m14 zykbt?d0)-4&Sd9jr50gL8`oam@9AR`F;Ebws*exb5n+46Q zz3TB_){7^4?TN~8EO|xRY)hcvNkb0RzGV1ax{%jVCCEg)PWbg4Mgln^6{68D?q3LP z!F^}wKMSGhZc9lJN(Fpw3uqM%_o*nu;;sM|ZPc&y5w{A3&5|A0gukZPI42yCT_iIl z3UfCZM0t6|tP&x>*v8ANU8QNT1Q!?;h1Aam_}=1mhDFP3YB0h`lIMVSaOgTPcC7IE zaklP$GCRt?j2&e6TvY3yu+-$|?m4Wov8V(Qgn@wpP8HSaj0Oe<;l|11`|BMZfUufH zw{hhDwKR`xx#_gXevJnWRh~)jx8zA`F|!Uwv)gH$`MBi$1-ZMy4sTqEwO(`fFO$JU zdkmp50*sfy_~us@eja$^K!zfVa&g4CU&xd{=^+IW2n4wBDa@-&XaLxHGzpCm3K~${ z?s79;c>Zo{syTO-!g#%7EF2hm6QfTVeQ>;l=xRY-f}S#2@~W=L;5hQ!v(JQ^?&rAL zh|WkKTO{;BYchD44|H>n4h=wWI`HG4`kHHB->7ca96CC2Fld}ow#}+&TyqK)9M=yPy$H@J?P{G|f43LYdtWz(xW${I>N!_XgUPa8Zt{M_vHn*LqTW3C-zev#byF=9d{c4{yN#+`#aFi;q z1TeU7LgQ)W;1S^4G01r35oftbsk))aFWijuHQfF?TEd{45UH!D%$21_W%|r>6_U|~ zIZs(wS~@X`vXJK-6dLnfIu+q5s`c4Xc*AnG*xEd8Wk;0Z(1MB-=)#PXGemc`+T!c< z^LIoxXP{NTE`Ml-Q+$mpXe(8ABuuD;{RhI|E6zRum*GaHLGkpdIVq=$W~^aHMC3ia zxa%p;jnHBVrT6*_)FoqkCa1le7NtKp@&QQ%oB6T&ft6he*SRlRwSZ_0QOUS zYm!!?>iDx)?Ywtu->Wus$b>7Rx}VqmVJtwdx<6L^TDq*_dgW%o;V|a}{ZLryCNUXB zOv+eemVQio5E{vB_)h#!}gAjS@!koUjP~maNF|C)>m>|u%EC0t^J?w!p_il%rn%Pxe^aNEm*$xk0 z-QE56IM?rOIYu5CSZYZk$^T)86(%}tQyG5ruutTv>mCU{rV8JdNCNWbyv}GhhN`%W~nj5QPHZvH#wpv}L4^2`} za>!-&ej}XXy*GdMj&Y@;$jUp&K7-y&|HbTYj=eptk`ph&CKRP?^ed^GK83BFi;R|o zI{&97g&&-#d+s50z;*13Wx&0r$SlcwNs!?*~9m(Ntbsl%=m~G-97Srt))h{3L6Y$OS>8j&tibQ$%Tsj)h7L} zS(j5oq^rrFZq#qnPX7IvUd8!@0sE=R88726pz7P$*eEY&kWjH(+i0@YQc{|ZBOMlc zI?@G?pnQE;_+9l(iyqv)gXcjQe%4-0`bBZ0=~RB$36ZiUp#PKL^z$g1$Isa+NON6{ zX@}OLMCqu2Mj83u_6@FI@WkWtNC_5&QTFrl~i6on9 zA1D%W*R054c%X?K`O{L$&Ob0)-Nx{hwAXuff9uTCi)txBm9`Sy|D#SiI#SwLD`|CL zUz++#RN6#dmQv;17eiZF22<5+m7sQpdoGKM55EY?-(-i7XtPD)aPPUi>a9KQeRi92;;F!__Mn2C=qjL3ndp*>w?~-CmZfnhahk(yfu3c+& z3AOxr2tCiEaPv!{;>-bIdP1Ym{O2F?%$p=Eo4lNyfJwsA!eVT{{sOq_0b+OL{m<0Y z)IgM*fTNMo``cT}C%P+;zLs9+6X8pnKAF#6!qd^wkZduSp-Qvj+taSrTC)OT+X1m~ zf%=ue4@`)4&~9t{8GW=#syyncgcGG9kaAoMDR9)#Q1-fb?y@E-v2NC#WJALkiCXp9$mWqJm?i%Kk}25mw)kwWJqT~=d0X-U)H!-_Za_2(JxGpfvSjJ!;=V!##j z_BsnS{N}wNKf&H*ujd>Wg+0p-!g z3Eh)FgKaqXfQPf6jZ1+Om6~x^QYt}b8xw1R1TM1EuDx-%) z^=68Bq^&0V@H^u!xUHY^-o;ERfDq}b8JB)`IODxI%r?m@1&*IorI8qEQVfz07TU1$ zaT-HKKyI{gkvTl%T_cU7x~iO{Otoz|mI&u$vkb*CtmFz#{SfbUArFzNg{S?2JM-H| zPA)Fn8*6k{$nD=o)V3c_Hz9`!p~}H%J6>^S3+2jXlBdgonQpVG&YcWhPUOxl1){f) zkKblqZtia`wD}lxGJ(iF34jQQDz)n#C6^f>|@1m$x zx_crcSn?pH43Vqoe9b*nP*N&X_=0Y}e17b;u}omk6|S*Zy)^!Ok8yj~EK5r+T&jCp zTDm9}A-lf*=l)Y`gr^np4}{e!AVi2n|y!sfJ$+Sbt z7!l4}S$;eEZej!jJm)nhUtuGr8^28qXmI4kGcZK&r5fetG^JccE@Z<#q^SH5LD?@O zN@R_PeUB=^m8^ab8z>YcP-FBl9EtcV8Msxu(S6X=Ff>AS?3TDMSqmj z_jAaKQ6*y%5e`DLDTXHUm>HvPw579qP82{n4iR9A5FjVsdvRUnS4v3FQD3`(k<8O| zSZUwQ_sQu!L>J;9;$ASLLLB>5lq3Uc-T0X}y_(_1N6-G4z!;m8%w(M00a5@>DN69r zbL8_(L-(!;-c#L zm4)B@Vbp5j0hG)m$cv2W3`5DEh*j~+bl7YZVyS>f5|!!j&6p*bTrUZafp{5RQ@66w zbe?5j#yF{f;3V{RO z{R4broNg2=nW|H>d$8v53sAH|uTvfVSHIMhfHn2#4AO3ME;iQz=J-aDPf5ACWVq4k zB~g4O+NL*t-I^7*Z%2s-{XV6vzo@m@p+Hsh!OKHe;ZI{YV_CVI!1NpFMFc-+R&Wam zRa*l(I|34tU+?~{Z%?M0HHMvLQP0gSufJMaNaI~6*wuhcR8Gphk%YnfKi4N28HVh& zU!9N1tuhaIr&?+rmHraq2_Oc$Ys?2?fqFJ!0t=LfpcP_{F#6e0=jl7*cKIPCJ9QwD zErew@VQxNqJs_IqctteGD^wKU@Kr%Vz$uA_-73lNdTKnATm3vR(c;c~<@+IVhjw+3QJ>_f= zz8+dgf$~)%^t34$55gE-07=G{(3laG`;fQwhk`4TqYiD7qW(Beyro4%g>q zdRu4>d&U?f;cxrt1w&@r&)HP_iGEE97IW^UX?B(>u$0;vZ(29`bE;Aum5LkcAdbZ1u zl@*Jv=jubgxbNRfjR~BG)D`;wp%mkKfgTObDgTG2bB>Pdd%O4q4I10FZ5xe~2^uxF z?X*dg#xi(Kx-LwP<{tc(q`2~NLcZsbhU{lLmC+jY;0E=e zXyc-9XCLrKo2OHozyBqi%MPOQ3M90N`6x(4SK@VCcM-cc!4lWJ7-7x9*k+vK*d?uo z+vkiQ$2XK-@O8m6)BiQK4m`3B{0_y>8$oVvx8Eo)9d~AV8PNb#I2Y?jIAnx1$*r3wtKz z$`FA-v`2$J3DEr;5&`cS!jEqNx4p^k<1)0EL}<0!X~(rwDI{dQ@QcMDF)}jo*ZO^} zaxIc?k!Kt2PA~UdssGkDHvFD4Se_PnszVUib2n}M zq&So~Ry$$Uh71aXlyt!MbtGsQd}oCW{71_CEE$)UyoADzGXlV-P@@d>aKJ~=CvCJ_ zk_Ax#ZBU*46WnOK~Hudcd3SY?ye zRcE0n)f5_2tkLF3H=@LUB#kXja=ntJ6?0@5g=W?2==kbdbFjN(R;n_NvnwXBX_hYl z?Re%o$yFzSlrH}K16mz71n@f=;R5)Xe}?)?l^XPg^$NYP|L+B;rFzCO*jRsFo;b0G z0R4+iOYz}gdBFA?(si5E_8WvZ^;~w!1ZJ4?wQ%UihqL)*Wx|&|@XcGBl))WOlggmT zU-}E2AAJZ8Wg3G25d*vJavJT{#(=0J7@#{J6R>orqOuDJw4Z$^!qpD7&;^5G$aW&7 zHuVq#!ycKYT8&ag;qI(FP{7~~rq=9(m8K0_ZZy^AuT10aaNo^c7ViX?+}hjP0fRm; zib@%e-f?wv17xP7bRG8EcQHEDvDgBcyePF#qi~e-a={DvZ43s4(!A*up1B{oGRK*p zGRtlQP?L?xVh|R(LkST0z_R~vB54zQ`tJ4mU6(3~4Ys{D3+^Z2`wzZ=jqrO_iG>XWfcxpD&yplx0u%xxZT&hEATx8h#U0~=N7y-}c;?Hlg4R}kf*&I*eT0H^H8l*5gbt8RI>Ix-bqZ!Bl92dW zPg&TY$6fnK0-bBun#nPxjZ2?>qAHJT5^b{96qP2^BKu1x>3%d0v3~6!6CEFqRIM+e zwIFu(YeTL#aW9=qGaX`5xdZj5XT09JgQs9gS+NHBQ5{(#d^v&bK|V024qQeucvr50 z!wy$aOLG%DBElSG^?fx>K2(7bZMPL^NI+iYfqAR#n$2BaDGSzu8GFKod0bsUq&S+^ zZAt)<@yI1zu#Isb#bo@CzQ%6DG&*M1c#b-hGtfAQl6b zTnPUxWPW$7jL0xn4}~;`zEVV8!l{o$O}p3v`U_u>R|jV}s*g1tf*OH+rx_O`LDckY zp%d_016+$oF@Q=&Ig3`hV_98BUuIS#31nf%_Sg^fT3zh6-o`t5w&n!=Y5X7KP*!#v zJVL5liro+XUJVk2E;Q*B%e(({!FIVgse7mhd4H5l8pM z!@!vHIBfc_*$F+G@$4Rh>tx3i$lpDDJ3X_#nJ%`4dH;SK zrb`1Dlh0tmErg&MC&F7N0O~Wxxz+^Ha^fX}OoHr7^66wjzHt#OAr_#e18?>*=|*kB?4O4}w_ z%<4Cpos!vb#P5ymaamN4o`l;N*pqR*W2sWN(07#a>i$5dy;3l$ndt-~ml!FRgO73ep~ zM9)S)`utU+L{H_%4-sfF(z3!wC~1>|+m#Z}UZgCD88>ZQUbS!lrb4NX2uT?AMydii z2sHE5+ODxGLK(FIuG9S#rUgl8u0kia@95hus1rv}=gZ3}2wZhl3oV!o1qe8ayT#q$T_ZO60Lgj2_*5d=O2FE_Z=@)9jJ zC=tYRE1ZEz$pNFh>$kaj3$AK5PHW6juEmMqn)vndWc}9yTiwF0>5&OkS+ap-Ht(U4 z*zx`J*dwVVT{k%;J8BF4xI39}@R4j*aiyncofIei&p21%DqLX``5yzum8N2BXi=1v zY4y{Pt9`{&cyc*?LN5<2x(y@1M)?G=0OSkNhoFoo+N(|gQ3M!3{l|pM%p@cv9O%A( zcu-bSq7VPqR+UE!4Av78rY^Z~u6j*6mV^&k1U>_k1d_K@u11rkJOsdeP-CANsu?@~VL_NsC<`^-|3Dy4e5lvE-@I>n2?_aH zUk~-L?lN}U0L-V%bVf{B^cP`4GBMmgR8%oL(g|IDfq2OXX&7#~NfS%b%V@)^2zYC> z%CHdYL{)?Vnx6nSNT!Nt9L^x-;JM072O!`!sh2POAf*h(ZTp^mURL&Zut1eRAzjZ* zl?_QsD}>(jEnr+W3wE-U8YO3L8ZmnPibQLRz4mV^~Y`j zJ_Kmf`?Z{;`&soNmB;T@h(^oBoS*w`o9E-LZ6he)cD9)~qnq)czlkw7B05FYY+-Bt zi@*07MRCWQ*G6} zG9EQjFV6g`SQ{A@Al`SQ@M=(W?#Vugl-o+|P^czH>P99!>$c${G?aSM_A45aRPT?; zNIMO+^WSQkVhb8s#;MiZjXya9S_mD)Lq{2@p|Ejo-ht!rjF03#!M*-@v+8pVtfq-D zkykw^nBZK@5^-^nTR+1EjbV4&Iq9ImktbDk*?44{I0{8LQQnw_qque2^bv$kmTPg} z-}S#WJA@F^b~*ptUryoMdmJZ2{pFam7xZh&W@%k+9uXwCUI)3{bCe=}kBri98g22@ zR?T3HTmN%_9dN*YLMId51n<$O%;Nn^?Yc4%7^a1rWkWW3(J#5&j2Fxi47Qkp@v=-L zBicL<5+^Bnx3yO`$l$*WEv+~q#z!YV8PX3o!TTD57G1Qs6r2r{x|QxzfixqY=XHpz zpCDPVi#(iiC86^q&CPT`!wjWdvM{g(PrFS$eV;`Whnu&6frTC4V>h-0gNuuc0Z9!J z3RZgRX?Yo!IzG=Ke}`Aws)6wf7|@Q8!9^)d?|otCcmguhoot+TAjfE=2mOW9HnX+M zZs9Yl;$?|)K+XCenjg^aFaiGzP#_N=FWJ@J-yeM7bVm6MyL=ZyknGqddICGWIE+jC zgMucj{VGFm>=ox!s*Q1BOl!b7BAFQB%A0)o3x9e-lE(xg#UXHJLOoM>MTkO zAxp6PA_bzSnsr50G3=rVkfBxIClunH{bv&(r0M0n#-!|B^SWnI&AQxl1)m~eb~WZN z?B;kIw$@c!t@?g=!jlXS@}%f)Ibj9$jAT6!3h(TV7bI8+Jy%w**WM~m>l9EsUB4N= zO*H2?f^M^OAr`W6H@s$SA`~n?#uhq(C&ldB2x$eMkT5|YdyQ|J5fR>s&&OR3ffHv`*RmuM4DW4g{Ny7vKrm`@-FG7xL{MtEfUpAkT?R8$Z z*4=!v2uq_R>>;ZYxZVwDHPaUYztzl3T%_U*UhYKdFRAGp)eK%D+v-d7=IYz9Q^w@Y*bDz0_#? zw=4qV1pl+ho$ey)sfgdDO?#?z;d>@w;W{X1o?Nh7g`$zv;yX3V=kgyFeF87Fv)A7f z1pjt*Y^|&@9)v#fU;Z#w8oPs|EbpAJ+DFc<4Hxz!M;{Z7einAB%s&iUo{>{KmlP_Q zg`;_SmwO@o=Ix}Hh*`{l1>tF$fpBzp*B>L)=CxD%-^_c#ydLneU%Uhb1r@3towr}y z`;o|)=q~}i4=S8LjO6TXm6hl!mrlyF1^up~aR`MkhJt7|!gJPnr<h{zcUe zTR?`8e#{nk5jZhn4E!7Hq{vT*!_NWDl<S99lT53r+> zX*i$zHpzCnP3LqUtwwaeD;I0=i(z`)ZrXI;B)}p!$=dB%v9zBi>4vyLzR$h{Jl>sL z5Y#5t;e`wQ;&Oj~T@&drIS95uwD-QEsul?FOKNb}{~!_Z{Pq!y^<%Z$=tTM~O(vUn z{SS=tWB<5ez@l1^qsMKwO}EdS1nhB##hFg^dp-isgQSngg~i7|gFvhlzf5?I)$g8AG_aSx{Uur(evK-316gckp)BTJJl>s~C~tT?bfxGuEymU^ekbU< zzG)AYhiX}Nv0|3unw(xgci7mkhH{dnz>HOs&pvIGqx9oD<8 z^04EsAliBiWfAf{jO(1lL2(;S?Ba@g@p!B3A^&aXS+BRCo`F^J-|#VLh69m$ zzK)YTfhdy9iuGNe%9{~Ogfa|j(off3W}=U9P>>jFj{oZTAH=fidGhHMfRs4zgwmW z$;~86bIUyt>t-GDM1@W-GG;D4@J>_%|Lj5W6}i-#Zn87lk$_WeboC%rW0Be?CfsL; z%tpb-NKLxIJT({W=fPpx4Gt8I2GhjznN#*rCr*4~jwpk0!AHZUVxao9T!7|lao?=3 z5ijWF`IY*TF_E&49X~<-mz3;pJ|-wZuBCv1)1Vtq)@kh6tH+A#Er+P#PVkFZZ10(27zf& ze{{v>l~O-d3=r|g=lX2Q#-?aVp_jR$d4%5|j~>&n!bu~Clz#eaB9Oh_V6-zaF>!nA zYG`O!z99bZDHubk<)Z5a*QCjA$+{6B?f|as@w#U~Fq)oo^8?s`mO@H!e7=v4%D|Kw z$s)tUKKn69w|GgUN@?y}D$!G{onDK>6_!k2v6jF|Gog?-<}Bamf3xi9BBti%`@$6tXq19RU!J3vq_tM|L%UOnR_kI+bc7q{YcDDG@TW$*}_N#okOgf#Z(IQSe zDP7LfrXz2oLOwK%b(UwVWU1?S<%YtWr@HkW$5A5Q8y@Ew#_OwhK`g!>?@)iQCkb9G zfO^^_hjkGmpS8ORk)uR)r8U8l(7WR13%uqr25x)3cHh}}aB&5TSWUo7$#7QOStu`J zwyU0@0@jO6j_~K1W_KyDFrHuoHA)mWgeV8sXHdu8t$vJd&2EKAi=z!oL(^90a6B=( z-O;K)ulG2Q1OH+8*0W60MI9(P^Cn(#G@Nl2njFJ-m8jm7-OvDiKezP0#&f>Op{`TwzY%|4Ma;o(>1TNsvbVRG>(hO+ zA#+S9YxeXE5m>7))A?!nEhFRz)FUwkMgfI{hJL(9T*QCeJ{bBgU0$++92a)T0_;7w zP8>7GN6fjf!stRVWLKdO%;3u2>PCOF4;e?+#@5C{zz&S%6=Q^1>o8-u1(bd6^_+eT zmLVC`S%ZXxZJ}J3`!pQu+CgX%`SWlBJtX@ew>N^s0d6twq;CvVc2;{Ln|gg5Qf2eC zp%`$o;Pdx`APV-bOqj;QCrzD|R2M~xqvUnu7ZNCJrYeIXx~N8RNm8iv!kzzJ6)N~f zbcFshF{Kyk-FDh0jL!*cC1K1MnKK%l#Y^{i%v{&y@yV+z6+NPa#HWia+{tct<6sz) z^?Egt(4BpsuBD|1b+w8|3tGyq4%iJtjV|J;wPksUd!;hukUcyXMT_Hhho{a}SOny% z`$TiZyP~jenm0&UTJBTJ330~G$*MeR6m^uDW~?5H(n?)SyU#Q#-DCd<^eHCEjY?0W?2c#WB8W4f;%%3Gw6OWAV>;M3BIfeu+EFAAz~ zr1m;mlN)072By z;h|-x!Itm(vk6aylm7ILZ)Wc0wL1Rb=n?;WN*UT(Uhqr+XtZXwv``xEhAj{S=?X58~~uEes`Iy}SIIe0?a4@~kZAFN*dYI}{14LR8kk zcD2j&ar;-7JhJ`h2M10$sH64dJd2o7=@0|9IX*2ANw|7}n+SwE6vL zCG*pw`qp!3K)~Z+ueWE%XOO5?=1Ut7u?3{#$<>7*FG3R2#p9(J!5DBF;Y9@fuIfIl zbkO(PKKXbV3zf;qzRg*xTnMoS?bOe4L%Dp{_=xIr1#Oc-;7bZcG_ib)Hu_aCK_YoR zo}!N*a0Hpt)vm|i64pBlg2U((9sf8VTR{Ib3CEYAoxZ~?b3|5H4OS{rv}G_VnIVO< z!i^7vyyBzCyrk`}w`)SKvyw}t#MwKdIiYy^SoXQ$6{xyacoZsbYWLXMTv!GA2O`Wy z+dICU#@QiqNCI!1Kl$$$?;NqIv~3Yd-x~GR-)? znv&dBne2VhWn*_RLE^B`THLh8WP*O(dUBAnK7QtNqPb9c(=q+hF-E% z*t!c@-7y2U$4|ndfLm0;3otU<0(0{2CcBlU5Oc_~GV^*JQqb=KrQ)By=v1Sg-*lqC zW{09`ePc`3JYF8m4m!okHti=bdJ04(?qr?~R-(1fEsc_Ekc`Y2Pej+BcKk+Roq!&k z?GzMGsS*HFdX-ASQSKx6$}B~yRnh53%dB;-!$qeRA06Laj*2JBTaUTG*Mzxys7_o^ zZh}GCcP@>-x$9r2mN1*1YLQTe@q}W^Qy{I(O1@)tXi(rumOGUqoUP}sXXQ)jXJQ+# z^6J?vKLO6uIF01#RVWw^&PZePINHvI)2lQ~6zpC8xczd2j=Ra#n_2ECb%W~qj_0&sBo!|}#s_|@;a zBPV6+>C0>XXhuaEll#R1^09JeMHTObuRQ*N!KuFGKY!XycHI8N?(WmtFeROAw?PllEPg>rG8fp(H-yU^)~0 zY#KBQ+7^N-I155dc~YbvF!(M+vA$KINV9SQ%_ScT*O69>zECYqjh~AP2tFi?6>urq zSy|Cxe!YGY@3iNS&X6zkWx!40D6-;DP#DE0M%-0+n`clCcrKd0xbI%`n`;DtYX07M z43B)X#^7KUt*w@T?c-0u{5$x!bky3d4(4~$9dyIIy;lWd?3sRS;crZAH#}B7VkRDQ z#js7a8Hm%i$s`3`m~ZQ@+IGgPpHf%vyG5EOtC5OqI`W?gWSKf|GuIIW4E&#^{A&;g zZ>Hk}6>)D)oAFVKv&yyTLLYLR=LohwHX~NCK-~2oDKdJbjauh#n{27I5SbEdD9JpT z84nNOlde-ghk&b#^OgG=Pwf0y$dZXjFm3^@qs#4KZobKW!wf#l`ZG>W;sVQKx9i9A z=B$v+Sk1N_Nvprt*S4(;GYrw`#%dvtPN&Pl_6x`nL+3#qA{2B`xv?|M%f-hOiod_< zYWou&a)c{R`HnhrPanARC{-XMo~a0e-Yo+Pm68!}hqe1H-H0E=3ahtZJRx*>U8^hd z!t|sS@D}Fadt5E@r#W{L%(M@(tiBO`Im)i!GstO#V#dr7+i$F;%vZ-!vh$uxD=MVN zFZ@hFj5N*Xq8}53^T3Fi=BbJne$vJarp<+}Widi*5kVb<8qr-p6*oqYrPecf5+oz; z>FjIgMplBy&9wsl{Q4xfKpXK1h``y?)s#g9i+m-g4gXQESyqH<400rcjaRiQP@RHo zoINcLdn87KPSB*hoQ(I-6i$i@nUgTD^74VR-tW`Z0JUK*9)Uk6#ra3%9pC! zJ8G5@qIy-+%~>%2xU#Zx*;B94dSQNE1F$7BBCv!kE@}dOt-#i;i9r&jR+>0!I)e>k zb~0#OYf#OAQZd`?#(&}SJu3hbv<^w~s#bVevhae_t#^R=Fd50D?Sf2x2Mo)X+_WmR zdeuVtD$ zqD95UaqE0;WtpP|>PN1vdUQ!+OiW4Ml_B@Mz_m~nej0M8YUiKRkQ>A&=Xb(mJhHpf zeHP)@8rT(!xzgf@PoF|)qNCDrFqcQJbc}{KFUSvNkfz>jM`S^9ePh=;=h_pG(wJ+`+e9pwyzw6qf z6TBZ}5#oNW_i@kq5IBIp!7@)~0x?xuXmwbr1C=snmfeSc29MOfLe-2VbG_ci5R0gN z_1t^eYRYSR1EM&+S${A=n&sMrYS6M}v1A~OVd;vSYZ$rhuN@(xSb?UWhXixqPk=N3 z_Hrg&(N201csR%R)#c(-VD;-B5$M}jx6lj)HlmE~E?FTs4^buS%>3{AxD_-mKAtYO zZbac8x&`!98mP-;L;9%4d1jH_SgE)aSwiL5Vehs*ICSvL+|5*Qiv*c3n3|M`Ff+Q2M(-iK>eI_II zp@8N^{XC!YxDAU<@~PevX;9DkUD?wUnyMm+TvarNiiI8K|GfY*!n?{B&7-^!YHk&) zkCtEf%dNip`1mw_oiwjMa>YM`U>payz(9y$xz?oQp&xcTklO$Im0WsJk~~#qw(fPm zuDs8^^5!+%mnDdA<`MdQ0Yx`C6$srNZr6iOcbN=InY?0fbl4GqbqXMMs?Y+iD!|Iu zX*u&5Wl>zATy3DMtZYs`t?#FkaRu_WHoO*+xlM*SpELOvawv%^Vggt z`80fd5ij(i<8_BbiSa~Ez|7`qGN46VJ=tB2x8uOa@MU-~ZN1223-j;tLiU%cW1mwQ zC_--*K9Ozos>X-r-uJNlV#UoQd&X_14Ev7zFu#ZF*C!zXmbc|LiD}}4ndg0F|9hec zFo+e!?}4TJ`L&h^R{kK1$TN;%^RB4)V@X|ovnu`C~$vU)Bxbi3Og5c;>#aTtfWa4Ky-Iz_tSL7LTu5TM7q zy2j3Eo3?MgCqkaQN-

    W0x z%y9LFYZ=F#7^ixh7}dd?imF`TIk2lO;_NG$mH;)&W40>DDiB7tp+BV;DXuutc*QU+ zFzL!0wTP!i_E#$6otiH)`+C4%!4S+8_;*wo>-ZE-SVwLFxC9}IJm-{>k9ZzD&moFH2?Im?}3A@rdtaNjKwAL4Gy)5q*;edMV_WTv% z!7Ud?28a5t3jzS7ERPnro`>f}Mn}85x-K^XJwr(Ssp;|`yEH!wzXZgM^GQfVELHGP zUmW-Sq=)}UAYDp9#-`SMp|)EAg4T*s1id?aD1*;gQP#h_ zOdd;0ovUB=q%HR(q}Z`|o|8#|&y7eLlV3;(33%|e=oj?3fuk||k!xk8xsE1(mL`_e z0w<<&-UAh=B>dS%@|eo`S~05qGrk{X?zpLXUVC0=5UU19+VxF$y)-d`J`HXD zS+6%!lMdb6S8F)}&-FCOJ>^h@*C*WWKEvbMuAA~ZPaDJ8d@5gA67~iT*PM4&rhQ+` zNLme_UUDXcFXx8ciShBuK$cJEX5|7%KmhdH&TvemPk@erjYNbis+PXTWFF2rp7-;2 zecku%JWb3tT`pMBSun`0cOl@lwOo}W|L}7lxG^!C$8Lk&^FSRo`{@Y{#MJ$}T0oJk z@ioN5fw=SLC^zUux_#BUqvq-@fYoIwhIoU^)AMuPTlv}Y8cH>?pv%aQzVthyn^_r` zRe!3~=wZFe)rzkDf7wVGDQZ#_dVr#na?8Hd)M{1FuT@?h@Ez^Iorv8byZrWN#5yXu z%gyy_kDhrD6d?rRwjk9r6zLK3Ol$0KxH()1qd0k-SfW{xcRsaka#r%#I^qLaihCp~ zhFZ=_XaS%RL=Pt>OMJJhGvAQIajMm9MI%=Oty+B2TX7Cke`#h76l(s4#WN3WInh3d z`O82;SlCQDzRPnJ!-#!pzJbkGhx2+u=;c(}ULk>$48FpL`Q&?n2Wf58%f3XRqWm!B zEp|1bCBEL4ptI~b)-NTEU*ITLMAL_pA&~L5-8G-*=_6x#CM;n?L>O%mdNld~9`#iE zCjtiTcnvCc36lQBVPunm)0&w13`%V&{Y$(Ze?c~b+Qi`&mJk%H8^+Bca45;tH-5ES zBP5B1KtAvFYWyqM&CdE2=6R5>ZZXmG?n;h(f0&@+P;&onShVKaBfxRX?zFWYclX(oyEKU(dUxr3S;TwjQuUjZGI=_0YT~Ax2X4Bt zq0&1eXKOaoLLRkMCp600uk|7bW+SvDACCzUI5ChtmzUWxB%PK^RRHFjDPz)Dn+u@S z&6=C8qY$k)a8T>P_{u;mISKY-_p`#~M!IasqLo=kdbvYxPOg^#KK-^dc>rF4k6J^d zR=Eh0ZB)xhOCQ~@AB0BFzACt_oudD3P4QG4T9b zU3Y)6(f+`LB*j7PA&oe3HK zAwrp0@EB=6F0+;2bDJwvkSLu+tG6T-lcH8C2zWQSxb#akjvL$TR)STeazl)E5uWsf zbEXemS{cJhuaeJPUKtNDAp3+A%}Kll(j}gkV!&~ZU4naf2tnkQ3bbf~yktD&ly6Rv zeZia)=>)c!D7co4I=tm-RM@4Q-(8)2ur7N8TbfC1%F)Y)FRh1Bz8pflWBrWq>$jAO zPDlT#*Z&eT+|nxZ%bnRHQ}PM__+FB8MzkjbGg6)+E=?@re z2SgBTY{n06+Nw+j(BI3;!pmm9Ft_1?h}?EJK7-7ypSfy|+NxMa?L3b* z4`gIy;FFMG20r)l1x-a)nVlUZk0%+%fTVAKclwTL>kd&XWE4dI1`*2kEI=6XyQ2^} z{v!2KNjONsV28sFvlkcmg^EpwWI7Ynht+eRCn!cj^SXx$U!V}#0dd)B=D0rg!i{fF zLPd?{t}b62(zlFI8_w`~FH@iiDtisFUq?6Xi$vzqz*P0DQ4DE_^lh%`unc}rT5tm= zWv`V1rnCRHS_c^Q0QE~r=q#_q}F;1l>6J`<->zm;R9P zl}a7S{cCvWuIRS(ePL~C(g%_lH?!oOKlfKkqC{6p%5=SJ4yVG1;jRb_<&r`Y<-U_} zP0whoLeQ^%>YYvz+=;W?4@yUx&X*%5PkE4}Kj_?I-`*S+_GB6)qMCZ@>JLq3(K+T- zVoo6-AjnT_0!WxBC=d7d|Li){N&%Drke`htr3xnGca@#vEGP#acn_S35U9XwD1_^n zjd<^+u(_pIL_-7<#ro-aAA29T>{TS8a+~n@QB&JBZpEA3(S$Sw7>5ENfs!=#C*b{{ zFC2^J^UtyGP~*+Ee54od+&0b4)0u9Ia{aiQ-Q7!d{L=y#9YQ|$6?(1c!xH*Soritn z00pthP|#?l$)r7coN(AIQXqPKRzVxEzDSK(@n?}qiutdzT8|8*jPC&i=dVS8CD6miY+YOMqB z@EcYlkmXh0*30RiQdi}W36e;TPbbwzb8ek_RSkW0;y#A;bK;h*dSbaFCkS&C>fVx5 zgm#;8F-U#4DcB@PPTP?_)L&>-t`tjKx@$_qP1O%ysPnN^hR!{8VXY=OC5I5q(fHi{ zl2LHp);UPK6he>%v*9qMm~B{9z#3vgbG};B-XVEoMW8D#1@36a7o994iv2ExD{QB9 zgi}Bof;urTmX_Qa4Os42Ab}Abz^J4ygNx^sA|v|@-=m^24Xw8uUm)WGeKN}KL<(=b zN6C?JXg}b*=C7Wwx-v#+QDM|7Gw!WWUcqB28~qwK?O7>1Qlq?CPg|I^Yraf5^SQ&Q z&-_VgHd`UEBj)!9^+S|rE}z_K_=K6B8#6TDfEoAqUt;7}Df<12IihNZR=zQg-yLDT35AVT zl?VP;9v%-PBXG~r5$&99`bTZR4mUSD%LYW?%p2RPlob^LM1_)q!tRY1^vRQNmo{Tt zmB3AB_8>|?U6b4J^8VRlcv3_rhGEsNJE5-Q37wDkURZJ=XOg{@)hMtK^ro8Z#_O<| zzMASRjwWn`BJb6$RG8^7G0E`QS)VqU#eG~G`p<5Oz=PU70OI7Zm%2L8lrut><&r$e>jP)P*7;G3m8jYU#WH zZ@3SNJTIy&Wrmxcc@aX+r0J5I(4DPAON<|F%^Gt^L2d(zD|Hov5jdf*5N1fyvU!e{ zALD0Pe`D^|mEXwe*JL53C%N*Cjy}C-B1k!dV&TOCQ#)MsVw@jbnf^fS;`|n;KX=G| zV3rC0^>FS)+(Cx>b9dM4N^99^KW?C_pjtvkK^8%BvWL%NVla!-RS3YA)~~qoo8i)J zT#{$gVyQt8pD2)2!@wVV2LWbQ{ zaXCZ}4!}@By#>P#e8|7Yax>JDzQgYelL)4)Toou|_y<~Imc7JcKb{Kn<(4y))W^#s zquy{J^&( zW9x&N(8RO7iYDFe>Zk7~mH<-0Px1Z7D;HpGIk&E73;8&L|0|!NnqIMRSblm{S`)LP zS|#?3faLbnpDziY;1_3on3{8^569dpK53JtYqX1Sk^axnM!Q;}F&1s&GSy?qHDwUM z4I&iw^)%RE1uFR*w(r9lET#PB^7L0@A-obP6U@xc8HVPap3ij2)Gl<3ZW?6PKb9r`O7(rKJzAdK<}Fn9Yn4HIm6K{;Px{=CN2Hu@bXeD}#Ha8a*PO zM58_JvKnuti(w9WM%Mhu%$=LzW174-PVUYMA<38GAkGh0$rs{T2^sR@40#}ewv)s$ zDlO`=(z!n?E7z1Q={$i+ql~Bvvmx!pST6L1UVR3O{VPvM<`f<*{$r|l|H`B=HJT;S zm`eY6yc&M|CG`GCkV!r?qz;yz`*sS_N|43P?uZpAm6$eXYc(7K^T^fP+6o=r&BCcqcyIzYX=T*5rbNWehY3JRROK!-F|bscgmX2F+W6X z`R}-!wik)srWvf)uzv0d0mY&tV;-)qhi#i%TOw?1vl|MHcx7dPOZe|gBV&Tg zew$LGS`*Va=cFEYM1FJ2B*op6oxhL7+*7Sc1b@e*^(yYUz{^$QI?oY?|1>F8Q_b&v zUBvGYtL0(jVpAS6NQi%A5}l{4RKmyjhS_`-)$P`t^l?J(iR7hV5&{KKGngd>n>l~Z zSQ3#3-DxYjSe8nY;8sJ40(fL_$&X&SwjzT6h=E1)pTU?v^Zc`J2AoHNnrG$YnPHV< zhkg+Jg{3kHuPLGeReJH_$fY`>_a&4ZUhWpcUWPUNd6|uh5+&HW@v>)rSJlP<+P$O7 zP>?W(ik5>5@ZrO*HczXS30!iMte?B^X`-GRtQZwiq*VHLslwc%iQ3@wFKe;4XM7P! zTP+dKLzWoPd>HDFYT+BnO2XP`iK)H4D*iCa$<7J3aWRr%9J~BkM%s^Z9r>>Rcichg zs3w?m*%Nv4>9psCyvGyOXGbP^K%*%N#5kSwE0mecm$fj8CT0!qoa;a|5@Z4a#oU70 zfrd(4GrKDm!Q_MrjAC3`3H_rcymM80CMXo==##>Ya6JhsG|QiSiDkrzhVgK5Rltov z{B7~gM3-6VjnHvt)O!h>hX-H2SK-NMDB6WlGm+*)U?m(Y^r`K z%f>+;7ZVP0KH4!ko&oF+$V+_{@(v=CPUC!>07?OcaMskf>-{=3b<5kn&{@G$VnS{i z$jb^#(TN%MtsyvGixDvASdEGtsmMXDi3~j17aZp6AA;pzFc>I7<~wlkp37)**a8TU z{Du&s0M}&c1oRCThQH^xhY@u`>Cy=>0!fkwLb9G6To2=E`v(GNmnRog-q@b zmG^lv0p?L2eRT{KN`P?V-MRVa&p+O&e}fS~yE?836BE;(^V6&h%b4i|xZGebGl#cU zFryKz2ud{IV|PJ|gjlITw%^MGD-9f^?a#BuP zeCgls{jd1Ro>oxrG8A;<9N0zUr!9xr3zt=zhTFhYDePhwQ4OLO#s= zF6*E0-W464Qmm8pj$V@MJGCW;Nk$0kDUJUXRIn;d4+SSb6c`+ZX4307@l)Q{iU8Wm z4X$L9Ou7yiYO%0>SPEJ6)E0(JL;N`NcRr56VPtz%gpguv#lM8lxa-l~{PT0OVS+s2 zx+)m};q{=68QB;(hyNBNVzUAAf_u;N^O*Fetc-vtj{W&3pxt%c{F^|q8QOYo>3jx* zYOw2iS-^jM5;s{|>|V|*at>LT*0rZo2aTPKjUmrA+uPgi)|jy)OiYrh{p`m3e!@-x zS3WI+qxT-zE~<-4qj_%oOzkFHADK{ow%X?vizr~!KF8^#6=$dg#saPCIu{QYYk=>> ze?wpn_d<&VU-0Tn`vyUa|FTCN!rYjtl`LJbzVoj9stBy_%oaDjX8ZJLJ06K+pZn7% zF!sxqsK|eN9Pmzpg9swFrF0hy*T2Cv$>h?^rLByffzVefp^>Ly#|tuqD;9@7VSnt2 zr5H*b*Bf>UCe~NQtfCc#+vJz}T?z!ZPssTJF7_NJVXqeEU>zfh4SCWOuZe-lI0d@a#?kfxlN<~ssZMsJl2 zZE-AzHW?*}s|RKl99-Ip@5~>wNFM?`vOc ztfjyGRakoF_DJNRRR+%>CCAtCBgZT!We=YmRsbmg%x- zd*H=`6`b#(>7oE@B)^C@#nV6PjueeKzm#IK#pAaf=sFeXj4Dp?+s08;k{jPiO$;4V z?8>7BQ;M(~+Q2$!8TX0WBXWQ_EbhelF1L7^!% z{+xlr!HxzW%?Ka9GtSUQKyf33GrZG!#OjF0M`JmIUDOX0!mt95PA4S7Z^RI2b5fjM zinwj{;`%UjBC4t*&z0Hu#S7;N{VU$gidRz^q&q}o!ek=#bNpoB_p^%a6$`1Uhl?2h zUzR9f`Knd|bUI6`?|H@m7 z3r^eLuL?E@i8DWDrp-A$#BTTG7x&~ffFUVI=aI20_w27Xl@q*@qdrqA0J`-99JM() zIq*!ah8`XOb3yM<^`TFFg$*)@fNycy)4Dh4`v9uWpNBhvM}!g;0jWFF1}*tHz*fLe zQB@WF)$O=1G$al<#;3^;e|5vT&_iXD{hdKb1Q5S}i@=8l8R4Xu70;Eq@Y-d#s-0=3 zs52!W#J>R7*L#U=)YrF(aSj)k!lZ(JRkg{tjFuwD-zb?_fAPm{s1LK+a;{tUC`7|W z#AaxNTp^c}j9EEnO3D&pnh1xfLeRqVC7B4$|6V`*TR z)7j0TMYXy#ZZ91CFFe=na9zJQo#JKJG$|OZ)*#f}2O{bm>zvaBmKpz@fq!iwf3hR1 z-x;t8HO>um9>N`X;!h}P*@-J3sL&6AndycsG=ZI|O$k5m3y&lg>qU2lE^Dow9V4VE zj&crVTQW;h8Fm!g5-m&=rA=q7gKxP$rWKI_Hs}g=1(*mov=Ifi8y(Ns-A_=w{aY0{ zVfi#NKxvAVa!06kO7irf-V%qr^L1>ChM(j0Kg`v!(~h`8U_w&8Y;6B5Rqe3h^*{P% zcJ}7=S^n@bW!=Qf%i9i^#DU=E{_V4Nm4ws*y#bHKLiw$_I>+P&qYhDmJ4a?y#9(?w z^~%z!je_Fb>*Xaru>mv)kfu#cOqOlku6G74n_J8MzZScE#)Ap}{!=}!`+d$;hSm$( zBNc@-L`hz?3}^|KF1}M6>(L$rUYPZ)$DWs|zV}qu0$)~hNZ|;#mkJ5ve;6Usdls>i70z}3y(x%Fj@=fj6*SU zc5YaMCwTi@sO+8yop5f9Lu~?Tew0>MoU~i>aZX)qC6Lg;?H%B!#5>lafiRMlE_5m( zUqOfr5@i&#$U=&RTSgtiH-izo=s2bZu46u9u_RS7PwV}R9fA4(V+2A2 zfT!SVR3367;(=M(ln93+_(5d(^dZb*X226oFG1)r>jC^tB3KGnIcd5M@i&l=5gl^e z86_GYFK$PY)I5`3L5r4JWtQp6Ke<{WY?{owks?(PtVv8b2gD&k02xL~G`JPY4FUJ{R;7;wM6snP1m=+_)R^Eer|0l`u3y$p z1@F;AcDf^OdvKC#3b-a&!D|^X$h@jSEl{NAJ(awvtkfRUrqz+L=ySA2)AB@#{7|4j zj~A1rbIo>z(O$B$fT!Qi#wIf@?OUijZ#E}Fp?-}?H4ONpQ(GmCOp~^FwmWAgP^ng4 z-e=l;`^0xQ__Lhr@;5UMw2RZ5kLM0n@nN&eLwfe|X!b&&bE!sl;-vZQvrn;#@c2Vr zU7Z>o2Z#EIc|)kk4^z`ntB=1d<*gMp9e;gqCu?*)wo&|67dd@j&-Icc%mHp`Mwk%- zA|h~60u600yyx6g5yg=V<4$_+rcOhS1mEXyEHX+Q^9YJU!$Bsxs_Ni9X_5O8yWGuY zsq~oQ&yyoG`_+-viJxD&rU(?&WIhCPjr?9eVO5BiV(gB(w2k+EE3Tj-MITS3N)l0P zT%P`#&*b|vx`$zHNKt#yB9EJTDEy8?Wl9*Y=0H=NV&^;*fHH)WJcLqMVcSn8;V=~? zduM7gfz*w{Q^NW){{=sMfWq^GGfySdI!`4sf(143KEC0nL=04NW?%gJ1Js7@UtX@P zG*b3=sy90_m@x4QthB+_I5ERO=B#hsdnlhLxlNic>4BwOmVLa#SNv5)&3ox}(253bWau#Z`Yx7=lQET8=i98I`1f><+rKl8c~%{HFQO zpIps&^yT&FYt)3c7<5eHB$J7_jB?JOHjFPKi?7DNglY6)z(lyyi{yJF>qpD3OnrBXSct97oB(J?lOQ|6mBf0U`4%uKke8$Le#ThTPe|G6A8H z8S#@d9H``}<%j%=A<0i_k5V0bvjXeUG0U?-64i|u;1aMwsh=ppZqJN(t>u5j4 zlZOU>@fLdOwE&bbJ#Xv%vEEMa>5PmFYbz_GC?IXl&7C&BPenx)5-YExvkI)I+`Afo zeob{ub^N}Ir;xF;AO^b~!V-o7J4iq|UeEJIk86+YY!kL@RrK+*=JQ?i`Az6~VzIc} ziM!qT<+{f2IPfNv_;rsjwe+LPkU4YX{+xMTvgZBY7cO_2ntj-{>%%VpSKoUZ!RuLg z?azJ<`rFl0C&sUwyw2cW>){WFH0tUFWsTQm4r%)inO{q}{d!04t`!z#-v;A@#2q5#LeMm*(C)^R&@5AH6vM}!Dre)!`>sY-|OF9UlA*9{b` zxIK!z5&|9=vj)X5N3i4!KA+)Sr6K-2kzfjqtp1iOj*JV z)p$T5gy*tJj7}~5v6e8)k z_F_kO`{>Zuv@Op2CXWv%%gIFw{1;oH;sZoIR4&P8w?c#2Yi7@0V5it2Ms9Fqtb#fi zUDP^b4dcXOBWel^_39P(MaY>LoOagDVNfn;)s1KU*||8Kv?5TdB}{-GXEpWwq!5a; z_7d(SRD(I1i^P1~BdYM`v^1)c8n7pq;<54MsA^Xi7hpVcB)&L0`t}EBz7Qh72xq}M z**Qn1SRq%iiYCG;BLrnWcmCA1$fSPRc0ZnSD7YoAg}8jJkr4E&B8jAIijJFR}QN7feXp3Oz607oZU~gV-r7f6iZ)exJ8}t79pcf+d+;*rCx*A!BDHk6L?i>;!P{rLP{{Y`_`5!1TV4y3)?*29S`Uhk4=Uj0v6EINHoPx{8ZUe+ z*ls&s@V&`H0*uiMq6oiIOGtp_SqM{uvhawY0stcLD=Q(!YZL?0ff{pr^;s91vA-EM zjDI$0sx?k!;3(RFW(< zCR1J}i?wT(;$3bWXMo$}K7=f38nuh#M=l+&LdIZfYOdFu7R7;PT-1QpLOqZPs@ zgO-`rBX|Q^fa8Y?dQawt_J+#9^!rfjiPAHEE+Erms?d5vryxejJt*pe4tV-QL_Uv1 z;uJuI(Qa6ixw<}K*28Y)!9I%D4Lc$W(}5w$44NpA65y4^u2RmNAB}d#Pez0+1vhTU zGKLpH+YZQdXCtwMKprg<-8RAD$xxil4Pyjp)(wwXdjVCdGP|?;q8KJL!1DlpT7+=PTza zU3-}>Bccd*%x$9rIyIlSL6@>h<)n!InSI7J`)|qvnKw_-PU{SaNcW7|zwAjfCjmzw z;O)&jO-)k*CVNc=BqXFAl%)T_GVnhoL&hz81^M|aKP z%f{H3i+o)j&`wF_j`KZ6NsLoJP;wIlw+CQ|z?$?`xe>K_Wt4 zF!-T}Pnv=S&Tf?Bc>PCb{0na2OL+cVvdq`EuBBAF_jzjOI=+;~H=S)g{f*b7Db_~& z<$7M(wQ!5B`$7M83-B2^8|5;E9B%dR@81-1GStO!uZhZXj@h!R;d!G{of*M=4(CP&jB}%qWWiBiYw^H~ z(4btjk%ZcbnjH?bZJC3eib5-a;cI;69PxPsu@kd;&nq_~e+vOa?(#l1$EWM}a9XF- z!5sD9v04=9b_YwHjfY=?5`n=?=!+9VL;FhbjXYyInEk~*2o*V6!ULjGw>4xil?g($ zX6Lq2dofnCO}i?i1n>}VOw4M5txp0gU$%50@QzS24y-rCl>wc*fCjKUxUK_mF&EzK z&uiYo)@rA7=fsM>0~Wi_`FP@WB;+4IyDF?CSAjM^x@51jx?vPkbdeM$y%X*!QRHkP zw!*uI44`kDI@i{7+8gN?p?;&KX@6KgI<-d9xEYAs^Tw1e8JGc7)PaVl0Akhi_KOuv z`jh*Y{N3SDM-~%?Yz0+&U*NoA+~(CDHj&+r&EP94} z?j~$-v-o*)&1gr?ck!|Gnu}i<_x3lk+W#^d+r_);{jc-plfS=K-Q85f=FP`rr>9i} zD0BJqiqQSt=QGXBrTUN4sdu&hzS&Iu`{vUGHHf$7wLz$}gl}MwuaxNh=jZdt-OJ`{ zMJyA(?@{LF`+j_UJw&6~@-x1+LTBUa00PE$d(Y1=HF`N_g{vRaOBbtLR$!wH|6JC; zZ1`H$2)DXgA9lJ6-krt6!dtf6jh487JWQV6`gm=M3bk6ie#Bc__qHu{Uh1VXTEp0Q z-2Zcy)II9h>iB_q@`dQ>SP=c@(Dw-aa#>R?aJ870ucF~tZ}a`9zpvvwBn$7-d+B3` zJs>>e`(IS^5qTc}vrHB?zh}&SIcmec=XcqxJB-m_{+9%BHaBOa)+xoBFlHE62XaXy zh9~RgpA2Wz3?z(Xdx)GUn0IrxKoOdBJ#ysL)1{%qr9 z@Jbylz;Vmt8_Co-11roFQI_x^ z+RoW-N8_mO3z{@~wY&}iMMeU~&m{;8#-fdI-qBxox)+&MJ+|h1PSd0rba<~!JulG4<3z6k^&Az_&sUG6lwqr!iw z5gN$DEI@oa<&}{i+jj!2>lkpBML;=Ru}bf=g19mu05&{`+{B8rb<4eq_4*-y3K6RYO;lFX&eP<$n=kqkaHIf9Q2-)v`}_vf$pVfRWPXRl|47qC zb0xbSXgeK?)$9Hnp09|7oZSB$FFOzCPigr{Kr9>_$qJ=_W0vL8YImjS_n;6j`yMZn zbGi`@T=5$6U5~hoAZv|K=@i|tfuKXV?OnBgva1f(-UNiZ@BPnd^`w|$*?(KtrI$~5 zR-X-3k)2--Q?eE~{I>p$3%xJCzx(^$?i`nX9G?o|?=5e9JdB#u@Za6r?+f03!QLfj z8=vB-Sgoj$9z#e#E4o^re4O|*M(_`!3VaH4v1AOf$J47~)_eLX_R+GM<8eEs zgsb6n9ri_gq5UK^(>PJ*Va29@d(mT#?`+@8_%tCNH?PX!kMpw6+i1xzR*zbzf5IL* z93Ht;;6LB=#u2*NafDdUM7)k8IH4+g*T0m5I(4d7mDIpMzfzd3L54-qZv`9zxZY36 z{Wbho@54*)%lCwHKlOQ8wI>;QY~rW>{9)AwE?I&sURTTcjikB5?Gt>DU8ciwC=dX} zGiZHB{@8i!rt`ZGUHvp1{W}QiQIGu7z!H=DJYg}g)UxijdRB9~8EMuhQ4$eeit(6m zqU#`#gcedI_1oKl02f*GJBDeY`dc(MPthq3e~7#O6c4ZjC4jN0mK@F7Vjd&g)hE^b zGG)brp*plYqMo-h{qr#5;CFioZ8l6IYMY6ui=5Uw{J1U~ZnE(jX>@%0190 z|J@wGU#q))PJRb!G*ePioZ6x$yqHpfn)|bcX}{H$~49a%kzjE&B@Aw1nF8T zv0iW^2`#SNJleZ^KYri5;Wu#C-nvh>IeWOo1s+C~FPAG1$3OqHb7oeRSY-e@mXD7Q zfNGd65ZA;3EEcOTPfrP$^!#33+8pKT`z4uxi*g#&)9woRZ*NyOyDD{=3WEll?fO}O zi`i}!(Dx&M0>VXY!|lLT?J3~PfO$0xocD)P@SVzRzX?P3zpKQ!8XNz75`ntO6nZFg zXLf#kA2;xQAIw%nTDt-x1d;gndi%SdqB$Ra7y9h%2eOQQnO(2g!C4HxOP{yHsTf1V z-RJff0_}E7Pf({|pd$b}l7n2GT?p6de9PGFzWn4a_;{Zh?QH)%eK}A3`seeyq0WTd zwX1f2ZS&=+EsN)1#@GL`n0gqR>O9h1-=huk&*gb> z^P>maRriomvmf6d*W ztGNisQQ9+LAkee(kC$IulBWlMZa}3&^cVaZzJ=tj;Pb)>J(bHhH4_=<`x~l1|Hv=e zfC2!E7Gf(;P31uDyZt}f2*H{!q9nEKVJvaB5d|JBdUGy>>toljsJ*+D)M!MOk<~Ou zdL!jcbfj>H6OL&CX__n}2v`?7a<|`&iOp2jEZk|PQh8%ecw@@Tg#QM$RYwj&IO|O~ z!1dmtG|*Slp+tahlk9x&Oy-cFCn!)zoQ>rV+qY2*_M;u0O9}k&K=}o&wna3HZSqOY zZRCJ!k0X}%H0UlLLxs0vgp!g$x-O4q99+wgHUKF=1)(Y;=A;y5O7B+5W`)KD)7{}| z{<$JSqF`(`iAIKeAmKQgqAyY>44Y09&EiE@Ew;V0eSPw9@LlarMVihEuO}&v+fHS| z!)5M;&QP9vxZX%Z3;zD6W-G%|ih!v|Zb85y!$8o1rJmRhnN+5RstV5_*sCb}g&fCh z&sH0jbAG;l;>7w;kl(aygoBjC39DS{4MB%DL^CdKJpOHO%yVf?jWnE{&OKQZ4^FxQ~bQn^Zl9xDwPEA7nZd-beSzmUKsYMT*ovdUbaZ(M5R03%&+m@sBC#0paB;PoZI_Y#J+|jD z?(XH=tN(aEzQn{Rha9(7X|ZLEX60nim6!7ZNPVnFT>$M7W@E9R#$%UR)KOZ38!a22)8RohB>G46olOg+4Zy&eCqK*ZN9;QgM#Yu~A#)+`}$u!K8(;ufCOI zt!fY+CHc||;+1hEM+GowC0~#bq`fwUa}7~&AWJJcRfi8<5T?IvZknF3DHtd1QO^|_ z{t{#6Xb?hnJgK8*5`%C?d$_yC^y)KLQ)~V(3R&(*0FV75HT5%Mb}&3q_N^qu6cYEw zDcst2FLhUNMX@|6<0s}5ZMpnGDQv(Sh1f*q3zyDTysSb8{1A?#-gkAi?)ws&2b;)7jaXy~+vfL`Rh_kE8k^#j3Ak=c2Lg{ma3xOj(w5z;rmie>0j${rdV!pA2Ubn)|kQGde0gpXdM7 zZ<3#wps;H1IX>0ZHL5-7aW{LBpATQRZ1W#?9Y{B~=~j1l=Q;y*T^lPaFMG@_@KCf~ zq$3Jl&Y~yFlLkIdM#%NkC92521#^Qz;Qc`6eG(qdcJGNIVDT@Vu(pFmOfC&rW7A>d z|Aqhi_p@Be6wZ8-7EXygOlrqcPK-x7y_O~`I*;vYrO2YX;+alEA4*-7*BE&Z28vW7mZ<3 zf=J(B#AU(6M7Vt;WN>84>{JIe)RM{69{1UqoC(gNS&Q~y^TlAx9t4s*>>sJve(tnF z1%trQI^YkPsDC*UhBuxSZzhmXGM|H_n&1A$rN>o{RFvV6+-q+}!Bdc-JLNY+I2cAn zzA3Qc>r*>}?()+EO&R4$LItZYk?VreLBFUry0gCcf_Gj7$MHjvFoduAf4!s+ZF3Uo zxxEI&j@t~JHG?uS4T0VI^O4H$vW)t}bZ339uSLr}Fwl zi0Sl-{w}V}A)m?cpO_tuz3SEVTA=9-Mic5%G z2)d4;rD2z+nH{?^q0F808*_8FClxiUfVYI7)bw%#c!E1Eb?3T0lqDsHkLOAivj{j5 zATE2m-R>i~m(nr6+fER9_zj;M_%x*=A}*4;&+flN0|O~dr^_Rkmw5`&+xkp@f&O^DFhJ_K>)5WanFq`cM=#IQVYyGedc!G=f3+!HMYD;;N6 zQrvoCcB%ENYKsTgR$BCyowwpu`MPgI_1s&U$`1xieFyD*U(iHA<^7V#M3%TURO>Tz z)L%+KSWGrc2X!a-KF;CrDZ3ew8qJ>@xxoEiu~Y*By?HIK=nr$~)fzU3{{>1yd`?tz zGlKVV+2c(O-L)3^WZYG3-Bc9tPO*xU%HclZYoQznuy0u*YabHD^vY4hi!%zz@Mw#_0SF=w(t`Sxm1tH@x2R_L|`n4s2L`|vI?uyA-SpnWrKi5f+F0yJ0!ry zN`yA+bxIH#ccRI_2u7b4kYR|0-bt0c$tM0#2k#6)d}TS}fm0HxD;shg6^Y6NP9TEQ zx&8A@fa4&4D%m-ETz!RNO2aFYG@n%wjwnJrIs}GCN$UD+`*BMwPxmBF$-%dSrs5jb zIw=)q(KF9e#HU6k-i0l*o(FucAI6DuWFv$z$Aq~6)^P*!LEHo^LyUY-@2@fM%A5sy zE<#FnSy2OlQu2U-_>7zndh)x&v(hViqLC8O>jeph0;iYNu{ zMB|P;)OiZywxD$^f$JOR806Lc&8N9im zuJy;w(9&{YyZ`6w%hT~(x=gWghB@HS0C!hc2P`zF?SLy{{Y1UI{6fIvXo*i5FYv^| z?){&J(=Y_zmoL&ku0!p8r}@5@{L0j8?6BDUP^Cs9055c&T;S?@EhoavJB`?U&psh^ z7xLU1u&R2mv}x{otVe<}d`7(7;P*NNK(~+4ZcPhoOC58K_iI&L1g*QXsk#2vDBnii zDvu^rK*b(Ylm7MB<{4)1Ma*%x4=9kRW-?*Axu0 zp=jHK9yV%FJ6AQsgg5(?{r^3w{yD7LzUxgh*MMh*a|Z`nfypWi0XK_6l_}fl-UA3 zpp2s8oRk=DZ8;k5jr8<9pdu(Q=@2<2SP}DXLzXmRUu(hFLJ~> zxc2A4uoS;;*HDoYJ&AJW{Vz(FFJ##Q8?8NqgY@jo!W@KQ;!5C<$ST46`#rcUf2Hbr zs>=#~TRs(8@q!-7uV5??yc2%SUJEkZ9)VY~4Z#5Y(uSdxG!Z{=VCJp~Y2YX!86x2q zp{qQU)q}DC6F-m{|Cb5nuW=GVUyXx@M~4*|Rp-?9_E(k}FawcG#$-89@w8XBG&Sk9 z?)2IF?5e#6A1ZXe(;o6G8ake+HeEli=(U_yJsxGadL_HIE1vSV{Tb9-lc5!GJyGM$ z21L~vb~|I^{q8qetvU8NcEsJHQ|P4C>eGiiTcBkr*2Ps_Lee=_sOumU`vri^0bgkv zB+YinNJvDFI*#e@HHI8Wa4z79eD ze)(bV-`K{Dys+7`Ix!)qg{%9xh;Z$6MYBuv{R~`bhjnO%<;P`kQ)R<%B^uDTHrOt1-8l}lrq1~N72hiK- zy53?rAP)72@+VRMslg=Qfk5w#KeW{>->O>3(R%kKQdA_xPN#%6h2|?-1T&+CKv7^I z@S#7XYhV{GWX1{Rn_J+gQrx%dhV1vMLby(w%gx?m_IfY4h$8zBW4si#Yi(HgpLx`$uy!e$V0l z_~_vzpIK5yeeu(_N4FbKDI9-OGP8y$u)g_yQ>%k0_$mWl>Cw+c{V*aWDV$;-u7hjB z^jPH>h{A4#*h_0Fhz=0005F-To^c$;fb8LioPXwyw_)2by0@H!ps$5@^9)w&3ru zIMr)X*Ev%t23QPtcYvA2$5oDx4#2XnUG3>??9AQ<2WKM-`HZG8uD-lbT~R|o*a4w; zGd8yK_Ugj8Fy|jQ62M`%vvbvJsi=^hYoxE~K>IJCE_^S9^V^YHfB9o=+pyoiAF&%w z<&a61UiHgkws9UN5cXWusXoim<51Ay>e?+I{^7k>tXEodq4$)5RKV8ky<~ONdNXu; zVDy6T1E8a&fAq^f3JUS^%Fv8(c10fu{{M375V@DAbzK%P(mR5|)%uW!aggLYrw=Zx z&0l{Y#+?@KOYjth-j{#XIFm4lVOXh*KsBejU4twJYKa`SSYeN5F&25 zOrGqr%0dl|eEfQ*m@JBr_F5%3&eEo6^d=6)y}B##tIrhy&f-D092{6OhCCu8a}a|S zRjin=NWlq-6w6nHXKxA8$}46xBgH@_$t0xcJF+Y7lylWxIH{>;8|8G#L*YXwtORzU zy5$=pK|XX&0WZEA!DckMSbZsFZGLmgVdfel*X~}qGXrs_S)up)UFngNqDCTDa#Ft!q^MZvM zC^E5rg^HS%gzrS6&@m|KF4cY5d)pJ)kE$<3)^t{!AUx*qxqB(_9+#lAW~PTgqCw*( z!9e0->|AZ3?!7}|iu(oqR)j(odP@39qo~G$L&~i1tq%hnCR|!-gx`f%+P!_Q|D5kG zdx}TB>Cwx-a^;WP`HK3Zo4$ve!2?-t$t#kp^~Pq?qPuUmBQdCt#g-Fa#FSC#Hp=%i z$6Jxtj}6Rm%CmbjH!I7wNgG(j=xAz6&HcCeDv?2PTwFbWn3#w{Aw%c~!tJ)}?HuxR zK%fxlX4eNS=1l`8)N-FP+-?hJYl`oDpkNrUQYyud8q=+ZgRodmZDc5AAC~q{=k>+# z(Sc@ffGLiL$9r6q$eWFHt%-6SY0%+gWo0^^()kV`t=(;Nb2qC1a%7gr&fUW~{Nu(S zKNpMyQ^`N?Yx*_AJh^FUn!39DK2I#Or}xvuHbB9^5TDRPorP=U_6v6B`#UqQlS|X{ zu>bKAv+WN}biv(e-(%*_McnmmM184s^82B_z8xA{!W`~8CIM3)Bcr-mj}&{Hs!t7l ziY#=)-$n9w6^j&vD%i{j5Pft5ETpc^=NY{?i8Lqy*Bw`iH+7JUI*d`ftxJHpTLWEO z7$+=beN0x8*;=k-Oyj`F2~;M)!+q!y2VPvwm7020-dF2M zCVy=!%eI%U%TiUT72bbS*}rxUZmY8Yd`5sn5oGMTQM6A!PBrYI-)bQlQNCUxevdK? zYZg_5F(eH(K?)DgiZ+&z_v^l$w?a(|;iCF)9nH!X#XSsP^5 zwUaj(0xG6}{*KFlu3Mbp{!-(~ur(4}0|`yHe#-87T9c+)B8E13lN>6QaX)XhqHU^mF1+ThZp=_uqFfo!jBj0MmQ=) zU7MGQ;4cFLhc#`FL7mJmPM5{$58Ho3-?MWsk^Kda_3SxW(<+Zhv#JbWl7Ok6=cxrJ!KOhdrp`u22&~2 z(p4zNzf+YI)gu-P=8&q>Qi8sGn+)B`B4wRQtDK2y7*wPS@L1;VBr04&K2#<%j?=C4 z!@mG0#gOq*>O+kB>dMI~fEK#eJ>4i zg|Cq;Ws^4}T%>G^n~-Y0-$@_)x0*$rjSZ#P9z4sD0dMD9IIGdvi4GkNy;@}pLR7g^ z`HexAK#oXo-#k3SdI5*IW=e2L67FC%QAz6l^f6q=9=;+r&IsVv?gL* zWlTWzcd)vaiWk^@;f0J-@Mpr{>e0ROHE!oZCWA@cQbM>+u{m1B?$0K}RI6x7ckF9J_o1H%yRugR~C13Kbp0zRc8e@9}Z^bDMdC=h{DR9x{0ag|3%{ z8bODx9^kih&VALLdY+k?SzFWX-n?|-Z9lr5S5@S|Lo`lrSv{91{L04W4D4NiBUtmf zGG4%^|FCEFnV|bXbH2JJo6wd@f$qP=f5EIX`=*wpkX?H?dXbNAv6vl$?`UOZWo*1N zlP}uX*tB|1o$KS|<@Fjv_+?tqo7!$WhA)N~w>S4~)EoMX$$#CA`ZCYa_F3{jr4KEv ztjf^J41BH!iP)a694Cq*jW9x#8#t~I;7{r)xJnjSaMF|*=nu>Y5=4fVv%aXn(^(c( z+r=hO!1e{i@v6_2sZ>)EHq|nzFLKOrW#Wp=GaqqZK#*Kh6`M*Fv(eu=(c%K;+e9-6 zb8Rqg>})a0oyaf^I5f?ge1q>iz8ON_SbG(Ybk&`!h85ci@GA%i=NFh9=q7205*ekp zX`IcSzRA@rtt5w=Z&D^R=!o=i_)=++9Lj^+@Rd+-%Mgw7qPwvb0X zhk%Pz^aPEo#Yf^0q7+LU{;rS7I?S8#+=q22w!05g8poO=G+h5N9XKaEL7JphexEUR z$qBQF)GJ}wv>fM#O6R3qmocQ^w?aSBaP|lyLHQ&&3)lA=PE({(n?}H~Md5R2?Bq^M zcK(~E+SSBANOPB$oF2*<*!Cy z4LlFS33Lu@(uvZt=D zu7o~sD~NpW7Tvtv9xs589lm!&`_^DX-oX<2FI+#)hOhBxOXt|n-F`}ol-8GA^#6<{ z&Zbe%Oe-m;KL_fiiqbz{Ys-qpo1IWKn^0IDk3t4)5R;ZVMLXEVvZ0Y zC8PZ+ubPC0!;TltF8`N3dRGGFDl`+dYS&xhXMLztH5Bn#c>SxO+1Xi}>b8U1 z+)tl|rv; zxClS?rf)`b4RjwpedctES3Eo1NV*H{^r!Z*OmPnr+jwv)>;E7@0UX?n+h_1U;ESYwnvFHZ_y-%0a1}XJ)G{_KzNez`5yd-Ot?Q z{LWgnW|6Yc)Cwl-+Hhm{LuNsN6|2!a&Z7TAr9=cKJwgqJ_D)BKXF)d6QU9Sxt-oYa zf;^(2cJ>#E4VG-*X!$^{`am&5UMX29*SLsBbzEWkD(-LAUU!W$@i=Jg#iFjG`=;_N ztv%!h*5ZF{oT>h;aN-$qN+!ii6wz?vsA_I8gEuuLZWtW4al(vfLEwxn)>yb%JD7vE zrCuVb3#H!_2qn~FD$Jtoz7?!#OcABU8(i3yFRF-&sL~HHRI}+&^En%E{cNydB~S;J zdb}pZjbNISrp}Y+rn8Y18JP5P!l%ie<-~{@X2I_-n<0RL6eh{uDscUgM)5= zI%{iZegJ2LlZ+EN_VzMs-n(&-lcCQNdj*z#zmM{Get|Ws_dyg4#J(e11@U-o<>8fc znd1YX*0LS?VBz86fy#{&w?C8SY|;tG#|Mj5k)|o^Ld1TznWZ^y+LvSWmw5Q6(b4w` zJZ9~4y|c4R5IrWb0tfN!$izZ_r8>>i=bNL&AvH9u?u=`?MWBu=Utt44B5;(BInpku zk+UH;QlD&C!E%#w<^mTi2n96OEjo?w1v$Lf1#v=Gl|@N~MFj9h+!Sgm(^2K96Nr#U$jp4oGm4t7a*M_u&`%vRZS-oc(mE2uY@OuSP zD-V5dT}HumIP!cbJK@n;X)md)QqC8CB>lx$l5Xy4PtGa(sta-;XIvuEuB~UG+WJwH zB;a`S=`7G(t>U#1-D3N3JJH9}2ev?WJg&c-eB`IGk1TilBpa)k99rwrwz@bTteqNF zW}1%OU2#cvTCAK-T>TppuG!8yoYKC}B}Mkhg14$(zb#OqFF);I_6EXHtpfrY`^DOZ4r8`8z!=2#{={^ zi)>d7;GNKDm55>toP@8<=93wK+*wdoWYzBf=|@XBnVjHfj3Mqw5E~Um0N|aRot;k; z4(0T?`ml9uZ^03UKmmwf{l!^t@rW2A5NfCsBhPb>IBPUpnma9~-;0F#+1c3z1vh|p zXGvmj+x{GZv!1}F+z*%6Fno#4w*v@#&WRIMIx~oCYmt*-{?|~AclD@Zn)SQy0|xQL z5=xo%QH`ufzgZC-75a`#*gEy2^VR29uqm>F&_a^#Zmnd3SfViMEiu#+jS6U3XXpzt z6P>4U;_BEz646r3vg}ogY$ZT>Ol1%~;fO9CbEb}&Hk(eQi9@2rgq$9Z(-<^p%E~=Y z6V%)Rkxj`2F_iwVJTFWuw8$ppVQfCAe0#i{hPLylyP{usGQ6hpJ*8NAqK1zLIxNWu zs;;!zL1(bBt{N(+=;04kl61d>BWA7jPk5B_8Dko`t==1LCfj8v*K~hlwU>CzFW~pr z`~8)03F%1`ktp@L(D!ndvQzfzq-`%US2E>K>SBaCt+fNCVB$AJ)jk0wjHCTY(E`hODcW1g! z$x-=YW_+LEpUEK-fsru`LHR{OSy-KOY-f>T6@nrI|My3}WeJ}=mSZug#1NsHOlj=C za1VFtFA^w__iUtrgjx!_d}>MxQ^!@`Pa>~h(28J&rlu6~bI;GuZhz!$pZvOs!;D&1 z0TtecU>FofG5YcT3IHvL{GPT+VDPwdH@dHRu8U*YH(y|o?!ZXaYwzwZ`+98*`z1AZ zS653U^^t&-UlvLjb-~-vhyy(8Y*^faJymzfjAw5fi%2^H6Wy5e>ah?%B`;hKr2skXl#*AKv}cDjfYBns}L#-^&@D-tuUvlAc@Sp z|Fbhz%@a||{>_Z@A*$YkwO6hFt0xksCsa~J&D8ZW-jD*OJVE4MNW#A6b&|1yBj;^7 znPOX7T@r>uR+~H~l0Iis1sQi$$kdM*&K1+6KeA|;OWg#kr5>=h8{})S_(YbzD`IO9-HaoF)?-vgXH@W zp#yMh)^~itzLl6ru$B#m1uxf=7xLaJlbti$(aP_f0uYo1YvpU5X+bbUI!KGCYZB>% z2~Fmh?$^#$@Ar-URD+mb)Y&e7V+i>|P#|Xj3|jXlwe+w=A+RMWpyBnn+8P)bczSwT zTO**vtkQ^VT+N(3XeVSwx%B)vGi!;YzwGZ#yLwS24n7*CeX!@+Y0(D*S+&D%owS7x z$8L6bdw3WCx6tEjCYL?c%FAMvj)jFquGh&#S=nHCI1eZ->uk++sVr5`?Tq}MLK+Jj z8<~*TWjhr6$6Bl7{k90{K$q|9Mf)jJwA35s_4hrkOXP3nEVSd1?SJQLJJTB1TALlg z<}C3*fe@loxXK5|D1?Jk$jSsyq2Hlmh*lGS~i)vhHDcO zRi3kaGr#$314#@Ini^Tt#S!TCSwv0O=WqHGU6Rl#9Ik8#)fm#=^#Ub{UvU_p+pkg* zLOD2^QQ&H4{T+7E=GSFOM6*Obhc%=5`uD`)I|5R*(*d0{ujT5bMWf1-IPO9Jau;!F zx~^Xy&^0z=l$t^WY7yDVN%>avc9zougoRvEHmEte98~ zU`N{s{y5wrlO#rP@|y)4-!TNsP7przRwpeC`d>I zudTC&38rY}N2;kfIR6SfErW$zYzLz{ee&O}P zkwAeX{%(0Y8W(ZqC)oXL0@6Aq>RA-%MiZF3+!5q(n*mbh(a~^LeXlopF8LB`ujAPQ z3$`>G?$Clz)WVGmptSf=!>vlUrDo-f@YAG&pLpz8CU2j;k=hw&$b3n1X>g7~0lei| zKyrVV7kdKSkjry!xG3(R2~G>TyS`JW=Er_x&bz2EWLPwen|1nd z${3?}=b)7#dVvseZlT(rl1M1ruT(>v6^&gvrYdNlfzIM~ILXOVj8LlS?4}p1-JX;m z<`*uGevK+am{k~tW)($w23LhoRH+J2-m=Id;5V0*SJG^;$u^~vqvpA59cRYdjfW9eGGDJ0cb{-;31N0#qYWhSWaM&37Y6Hupto7jr z!VU6PSye2fmj=pZ91Vp@7_qARXmJy0@8f3?N9nXbz-6*(VXbQq^Pnq*l(5^m?G>Lk zG)Z&Jy$Ml9^0Qh7EVci^q&u-nA-zLJD#h~t%pvT^);2*6C^+3JF$^#ohoXP4cg*%q zGRI{-@-Uks06X6@79|9ySm&;B2CVNc?s2$rB~+}wYaFQ_`kIqlYwipuvo5lgPUBa- zd=D77s+d0id8$}ecU}_1n}@BhGB#N19~6~fzPZXUb0(uod5BSXt5x(iSjg_Z8!*q9 zFE@Za%W6HXh&_YroPp7vth85j*3zVni7?<_#w<;MokAc=YmN~DNGX$(lLOHpi+-*_ zBzb~eK8gMJefz6{kU}Cm=JLMW6R#qF%1IG17w5JWyHs(ATmuK&KeaWWAL`}hwNe9! zSj`2*9{{_fE`vBT;*PD~>&5}Ilb5V zL7~_uvwj$e5bLyeKJ5jxXD6;k;4a*scf*Lgj|-y|_^$^0$Gy)3qf@l@s$;n|Vi$o0 z1*6>33~d^xVRB$0{?jtEhjRpZZ2nIljr8r$3|0k9(>z~BaZKg3N_i^c^PGv`N%4_M zd?c+7NsCL}S%nzyzZxIWPb&xA2>WnUHBF#DtUpGraYq@hEE*^E5hHVYS zenbdhG*KbF>qLywRkl&J!eyDEP}a0TW#cBEkRA!#Czr6vWe74pC|r_)6I#Lrt)J^BcpOHsM)&sqfSa0z$R% z=(Mh%!;3FAuqEmfq{Mqa4`KH?fz;Bh2u~3p892>{F#D6)&9|(aC#a-;Zm)_>t3Oxi z#Y&!>;Q%K@5M`kS?y10T&jx7Qucl9seh;e z9WjoT8*dQsWB^BdphaXYlz%cA5LhD8+GWd8GX#iOOud>N>8LDAKPo6f^xjPO_*)n} zzY0d=Ct=S6wYA)Ddl5rJ;!i0wk-*XeVEEzS;F2hS(ikBD!MQ6hsLpn!rrCDI{%@LQ z%+B?TXl3bA+G6k)UiJgt<6T<6RyfxnZ%&{i# zt9{275snog9V@Yh84eMK9W#(`s}fN5fko*SUF zFvbamUcNz7nN}tBH{Taa?GBbjPoS@xW^JI1@kW5?l@dtnPIQKdmX0WO#Rltze<>Eu zEKTNshDd40wPZN^0M^39wFGD?@(V0T;q?l|%q#xzYVP8K z=CN{nDM(B^<*c-SV%g_ppU!jB&wNbn3ot%a>!WjAVl6Ke;kEPHsEwRK?bwO(NtMJvrN!wb4+JFINJAuE=NkmEh{E9H|h%eyG$Nv{QEh!aw~N6el4G# zq2azEwV#ka8dTI+?#wHH=`E#j76?ZnuR{|xY^N~i?XFaI=Br9=n{-mT_;&a+^2-}4 z*fyiM^PztsA)1RegS%5GJ}?Rh zqsH5NRW4aXdvxem|4=xK;-%>en&e0!m{m!TA`K!z5&^+aA|}thBboAxb>6^vknfdm zC{ig*Bq<8E0jcWV0gx>+$uB7USg>hMq!1qT?Ga*QYcw7R1^Pe0R@$Z+AUtq`fi19s zmKOW~i*H@qZm)XSvQX>a2EP5I2arF3fsv*Gv4N-0Q;S0ob2lak2N8GUc6C21c=hjS zk>NGR-BUR6(|+39py93W{gcDng9{u#hRS$xO)1LdeO|vY#Uh&oOKL8z(7DDN_4&T8_6#g5~k!Rp$AWWspQ?1HXx> zFUmW1p#aD%cu1J#A{w*kD}NXWxM6OYX;GzM0#b1e6HQ7iMo&1Y;_ZgxR&)`Gc>nC6 zhE9w4ERRealG<`z07*^=`w&f4Sq#C=aXG$0o3Hz63PXM%YKTL%c;4Sr9O=RphV?|^ zPJ9qE@SOE$Xc$J`XF^^$aWh=eVxP8cCt_EM-4dwZFAzM0;`X5kf1aI z&#B2T0qN6i)%YpXI?(QyNehJdj(pqhG zBJT=+dVR~}u(f(vuG0QA^0|BgHC8b(I57->#$31$u-Hw0&0Y04)xVNAUEycUbs^c< z$a}}|er+BTdP91i-&m~4#eu%mLzW_pM4z6qa3y|u5mKz#ne1`C5V#b0*qgQym@G2Z z#NXI?F7fj```~=N-SfUw>36fD&~f~fw?*(Wy8Z2)Rw+jqcfQ=2RdeCWGgz6XoISBr zMa57>hBjpMDb706#H}T5+e(EMyo&sP_K1;E?PWy5R!~WuZf5Lroh0Dw|eve?6BLr$e|x+rI=AV(~<}KP!ppV z4d11j7hB3q^posz)HJEGKmm5Hd_frS@JO-<6u+K+yk>+5%-}LGNaDE#CEi&}$Y*2| zj^)!;rc|!5G*qbkzJB5fl!lss7>7}(?=ax7v|dxTKI4ZLp3Y{9->488A_ahuBl?mR zviMl{%?IX@N?GNB?K~f4qsghza3Liv>Y)1w#At6nwVv81^3a%8oF}}e-jp-{&=PYk zaMOSn_K+eNDHSH_bLis%SFPDeD3>+vkiffgj3rvH*q8g$C<7st z$ejzZH#=OTg80FMjDU|i00(8e*xuXQE0xaz$ns%fVJCU6nBiY{tk{ph;AW_YKYtv7 z)b-A5=k2})aBef+8Zqq6eYjmj>|WStB?dVf(Y}Pd!_@Y0zHZq5%5rG>4d*Mjvgjw} zHZ|le^icBq@bdjav%$gletKX{GQ8aHJt?p2;GlYA#`lWD&*!~RXXoHWAkXXh@W)r5 zY238#N7ELC3DYyFxX{-FV;nIkAjoWGDFpraErbd+=-qQ&z}537x>~m-_rBlo@4}_R z2N3FWP1kkw%FB@9>-faXcDvj2&Cb)x!)3==l0(M}aBiOWP)BzieQDHZZ!q=F)xM>} zM*Cedxa)VzyPGDln=SGXY&$OrJ+c4O} z)rrF(0Tbj#>3-(SqFi#TB#8>EOb$4|R%tgpSl%2rmqM zBl%RdPzw({wepGV(uv&Dn@3NtzMG1P+<*xYZ3B{wb=ZdlDrvbMdh>hg3g7S$C*{W( zBjd1Y9ZlgBJdb-LUVio(`ZiCqWetx*q6`Od@KF4BTp&C>pf zkuFo)HK+u&O1bDV&_NZY@7Uon1c@0I_8codR39K~9J!?r8%ru7(&!KHe`ONhHirw3A`CTW zHK@ii|G>MnlRCXI@MIE$9C%j#xu$G4P_O7(EteIH0Kd@!O^<)l;CyQ0tG?r${%Yxq zY8w6N8%(=-`3OzR*B5Cxq9Y#S$J(HRNvp}~(C)STT%my30m^z==%8!=Me%Dib z$P?yz|CuASU9KXvmMSb}W@4HbMn*wN>Ws@?Mb4>GXTL=UvD73ZJR#?~hveo|}xzDJf8V zSoc%+yZc3NhyC|o2^;T6)b9Gv#4fJp*uVb{w7kcaa~XKdkPEf$_C(@$HweA%syS*t ziqQ_MKD^zyp>QdBZy!lq2E1S0^xR)8_&wO7094)59WCzx=J%&G6!Zq&b}(_?w-dvy z`{RfAx0E=azn0rCBR39hziTAzUmINc+8U6qYeAJQJY1xSN2$P`ST6d%Y= zR*Hoe=dz_nPZ03FW3R%5jt8WwP0)PiU2vM#NztBAXVW^&{f3;)+B!AKaTvNBjYrp6 zhHCbccL`}AMc4orhFjPcb9i1X)Lejk!bl$rpPXL0;H5ypJ7^uL+q9t(733`i^EvbC0IdzHJ ztr<_NEz<7AE0!IN66?zR1R)TarqW|6aoBL|>+nfVg@NtSs(FY-rzzF9kRN5qR2YIP zE^7W)*Y@ciQQa-K1CsBO4ts^mq$}?b4d>J_i7>#w;Ln^I8q2bhh5<7x#GOUb>7j}Y zDP@X<6fu>&s+e@-5&M@C)q-<3(qbibq6^!~35A0wLTE1=AvTuO#fX$P*h)bm4c>v0EILVr^mZmY!B6aX_|U=~TM~m2 z-qS)ifECE$aAlwYA0J?8)bH{3;eA1~rXrJ9u#(iW`ys<&kFxf?z93+s#>?sX=gg+F z5(!cFS-Y;}_FsCT=H?;1k)A#Mo^Q^<{^3z52JgsM4G*1%lOIuHJ8lVkz6&GfU2tRB zo=Q4?yNX58ce-BwI@9%wqv!qB_8mOpYx4EIZ)S_dZRq)J1964x+u7f=*Xs?gt=Eta zFe+M|+dA{hd>ru(g2YVsHRajCaOIBINjr_+^UI0>D*t`Z>t~|3H=!4Aa7@ot=>jjm z&O`tEr2zQy8SJ-#i<0v^EZf1Q|NaZzq5#_-zD7-z_TW6Fg9TR}*5NnsaSgTkm*XcG# z%GI2n1KH8h*N-6DoCU&k9&7wjQktjb(jG9N;q=r}fA!W5L8eC6mqy!GA8p~Kll-%- zYAv_x`dRd>)79J!CWVi=@>yz17aqq{57Qt6_AG-Dqmc)HA_v{W&s1EXoh-h#6KiQ~ zx8WdF1g<|Gx4!k5PCQQbzU#fh@i2h}rm5p~FC zwmKn@`a8Qe@c5uW5<7PIF)sX=(BYkQKj=i-a_it?EIj1pAQJdSXsC1ysWlj7iX7?@ z{tb^Ek9Qvw0XYV2rFldEL=Y46b+yje&dv_#=Kv5kfWH9F^=6uLZr`%c1RC`yXh6jt z$Wnmjb2ulP*9y71~`#fp1l&y3gVr2|`i2Ih}`WJBYdO5skbm{pGd3 zbH8*2Z|=H;9=+U+WEAWOQLJF?Z;S63LsiDj?oUb*qNtB2W_5bZDWFX!pV#1Ppf5Cb zFcZ)V>R-DI-&WomjDH6(cV1!(K9$$LrbQY0TCEhU@om2*M&UQLQ`|U?@0N&>iOgzm z7^}$i<}VQt5PwjXfkx6TIHn}i=5~})=;ZH^nAP)m`L&n3rj_fwjBk+M34Vgxb~#;5 zdw)CBkT(At^RspLcMkMdjb&%0Zo<=(v!5>KF-dXa184jS= z*mkkICRv72*;*_IzaXHY&uR##!1~BqS*p^+IG)(Zz*@wUHV#5xI7!Tpm5?$%l~X8u zk--HzIb^elnPsd_+2Lwsyu8lCQIinbRoW~Y$ruPKutwu>S=sKK- zW8;vM<_dL5L`DZ9WM@x!RN3}99@y%`o27?V$G4ty;$Edy6C7d17QObkWnu6(c1@i^ z>gwAK;{_=%b%~>)Nh*d-5$regO`UsN)Wx%RNjLcS)eDo@ROUYRUgE5(< zU^Vr>#_&?6UK`nBhIMq?L19XCF7ID{m&k4r(6IWMoX^PWK}#Gh9XkFSSq-OKLx6<7 z%n(;I)kOn6lD0NIrA_+|E?p?2!>pCoAoR-lYEuUpE~9H3l|qLAe_B`u9x`{pl|?V_ z^QXQg(IyqLm@=}Ne8>|ak%(%0EV0|*M0dVIy&nkyw;Dk5!Jau7|M|`=7(*Jp@;#A4 zUTS!56Ysc`W}m&qMh`R z#|a6tvoD_A0R=v5?P3?-Kfi>p1%R&MnR^GQ?sqIUlF!+T0C+RI`{enhRgi%99tch| z0$HI6COa#F&&02uokx$BupkoeE{vKkrw3a@zRy_Gmsv4G-=Im3?q>#RN>HmB?TxH= z>=>Zo{I_odV4ONJW_|`8)(`n=KVqV(K$6Ii1|_KaJq7hVrf9xgNEKr0z$JE z1IW)azANJ7G>%pS$GsU2&;4$-h7Jm~H81Vec=w19hgBl|=Q3aOr4Ee6X!vdMGE2Q~ zAycwde=u{dM*#)!Z1P)tC46DsOmna1SzDwFf7|`E3-ms1~{8QR1fa8>v_P4HL*U`&F&ro9aJ_>(cU=Jro_#t$RPp ztMKJ)3irSK*70X1(w3gY6hRl#Ep{fGIxC&Osw_9`MEb&beiC^&_wA}`j zTXPDyY_67}2Hv0i-H!u6p3HO00C0wlpP!$F1t{@55kU0pr@AgH34c+172%gWeSzs4)tB)_cuUsDDdX7FBKCa7iZMiPUbNSp= z=5>4R$NIgjj1)E2@OnHw`Tc#fi~E-K>3^^QWb==3HP0Q-Pc$K@bN8A(s6B5UJG`if zb6bzhd2ic=VzjwS+&{yyB)^GMK$?LOmplKa8DM^YoUteBI#mxcd<+6$9JZurSN#ED z-8Xj~RHmfKTUzcKpxcPlH6hsPx09%&o{Os5dxo^wVZ?`qgwcj5<1fUjPZEE&} z``pC|ecxJas}=IY3Gu(0*mmwy^?QSR|8`m6n|W{HzV(=r<>96Y#?=0KE&ew}i5aD} zd<-X87$-#7fChydjI~(QSTM%QZpxc);^^pTWfd-Fd6HveqPkT+`BdOa4uUjl`*}d& zdg^YISPE?BE+3v>TP4ra3~B+^2TiRQ9;dh|9*X?Nobv`gTG>t|{Z*;2oJ658$vst} zniPD7ZDy4mEMrSgrOqFY^W6Jc2wyArflHuG*9Mwk<~upWj`bVeV3<*Y)2XpSSw`ojzxGyd_LpStph969l<)bZTO)YY?Dq)M`j+I^`}Rz% z@3za#XyjsY2I#1aUmDOA*V&xC;(DFJY_0Ec(Jw3Lt00L00s18LR?w6FS|s!h9Odi4`jHP`(Wg(>_Y$2naLHX< zW0hc3<`lrCWBcw-5oO2sXxSzFQ4 zAq!0Qr=dtgLM<`V-bwkcnW5&BtH(1?be%_9>bXVC$tM0#%-!1zc*DzwG5%@VA)V` z4Vi7hUbC=IpPP6?I@8_KQ$^?FeOcx-gNIbAICvPP$hgtQdNCg>e`O^Q^GYMeGJ{Q< zaYvJ5vtr%_0Yrl)I^E3E>wL|D`H~%Jk=#9lTFsW%Q(DGl5i4U`+FB9LHvPpmFLOhA zjVB2mjRFh-^~7M|2tx_?kv}W#S6jJw&1w-_@TR=t)hNC)Me+Gvdl!(?UoLP{Y04Oz zmCjj-d3}t8gRnxA8!ppJub3Sonf@km0XdS zaz;i5P;_ON2cV8Xkq1LuWgIN@{>ZiSosCeraV=Q|z%Rg@fNd3@9l>6RH#2FN!a!$qUJc_%@@d{6L4Cx}-OdfsFiMYO_

    Z+`7v)S{UZXIy01H8EP)+62IMbo#qm@c+ns8g8p5=_0X@~Pkd*PQe z1{IAfG8>@f+GMP~cv$hbL512#oX^gfqr)P*yacT7LjKH<{ndgPEWnxBfz`8!^MP zxaOUgb_TX(&Dp${$4;=!FU%*@W<5;d^m6lb~Lbanbuk_UW&%uWZtWC4#h+u)?KTAB zY}tG81_1ywqx|Y6L^mp*%e-Pf&In;eNPNOhHsPL_;%!`MA?YLyu1k4NwvFI) zDd>TQu)#&}B37nni8Xyfq@9@0JF25KM(aYd4K-=|tI42RzN|-AUPL z`J%m6+;PT7T^%MC^N+2k)V#1Tr#$`F2#IDm_2KjB!hIR^6jqlOem^}Q`Dzna!T4YN zHd+wWBOi87>KlUBlw)o(Eb(QuAz7ibB7=Ub)I7r1%>#u98pw)kR$Znm-Ftg84oJZ} z)%0JP4J@_EjTx#}3|7903_rEgm#jxC-y&0$3%(*uV7=*&m~1R-Xvb%60Q{(7CFG&w zMj2hkooyxKF|(-;+*z_z;6aHj ztlSuI7blZh1F!2~kYk2>*dx=DB|h4Zk265skq?;uAt52YJv(-sNfbN)3TVwTPoC0m zcomS81@-^~EP8r+#U+luzTGQlFv38SpQ+17NZD($*U(S=1@qBZk5ye?V~)X@seHYUrzKRL2OKI(aQx6sdv1=E zf^lrY51(EUBKq?jR|_>tRPo7?9zewywd5{)BqQRoz>Y#w8x5!P6t-3EId^?9@l={o zKAUR7a{Ze9Jtm#@LO;mcxy}G$yi#i50w$UT#^RZg zhUW-7tN(mFeX{3i{F%k69S$yz%rq|V&jvc#G)YCIm83UWH44-B45DOR<&I%#t`<31 zhLOMKiuoDebWwl&?yiv8r7JCn02O_p#Vcjo!k~{0OC2EiT5GIwQXzhyv=plpGGK<} z{{dQT%w?D8+QtnZN|SQq@FGpof+ub&rlnyTpB`9I>9PGQTj)t>;w%@4gl9|Q6W8k? zIDAQ3E~gM~)<20#|0-iEZzmS+-RDkKp^&b6VCnekOl0wet;&_H64}|bREn+$S>#kj z215kW@sKB{5B;4{%VAWZ-Z0#Jfhk;$ir|E4bqIR5(5xJH13 zldq%Ru|-uly}7vw2zxiK{nHh*n;1~n?GwQIXVUV7#tu1mwt9VM}d_ z`&s;he4v3CT9o@C?4p0wH*3Of2KEpL)QkiXRPO~Go=JmqNL`5{bY$WlIs|J0{)L0oAo}7?Q)xL`tzB|S{v~Uy|j-w1QFY^ zj}*Eomk6!V(}m;(OihNu{#q*yGzMpS%kU)w!K3}hMhCYRhutzHDtV5`pKPy(`^&!s zueafq=GZRnN5HnVolY5X5EC$#lKX+P#M0zSxON0l={Q^BzNp@f8(}DW`_r{CVvva= zML}2FQNg3ZSje2_YjMd)NPK#aH@FEVmP@ZOeD=cQG?k+3Fzia8kPc^GxcsE2xIiHv z0$Q|&V!Qr&V=_n6oyu!Ijh6P(M$h>xTO8shDhxZ#AFdHG>caPZl5M7VcMj07tWbCB z&>vm}MzeNBS4U?rJL%}j=F6$;*gp50a@j8;`g3dmmnl%p#8$6o>y(0yW9F|ee@Y`Z zqTLHgP=(Nl{Mg@1M^JUPMQ}Jl}|sv=#P4K_ z6T8X>(m9F1c9Il?MyA9{h|h|FG`gT~;qi_Pa@W@L=TfeoB+QT?aEspA`_MR=VQt_< zZIu$bbg;*paCbtWj(C|v!LiNjJYATG>V-&4jLcv?O*Af}G@`@C$YYLJg_38bRNK{Q zLt1<&;ko;Tzx2AEHTpwe94ipoE$Q9XIAlW_Du+SE6|Px0Y;f*6?E1})uH?Lx82u~50w)ASU1W3Z-C~N3yf5qIsT;uvZcEoc z%^(1O_j|-C8CRMgyCRW8;w_Ln1*XlUCS>-P0ire8JaNF%Q8K?q8#bvaN8! zHA^?hL{Kr{(rF@-hXJLh&S7qb%Gs-|30rtaH5kz#fW(_&v#P8IWJYZ+ZQ93u^%qt# zlcGPHA#ua$TW~!es58Ift)AZI&y_GxBqGx768Y|EEjZ9DL}AW`cmJJ z>y`RvH7T|R2qH^;kY@@M7c@)wLuw^E=Q#NKKWlofncHpi7)*0)Q_*OOP5-8|+0tvR zK4#N3z9?9HXSmrw0&(1xSZ%8N{HjyA!#qPuzw@1n5q5+xSp7gTkpX*zlKzQsa>0H_EYG z-yUgNY2F;8r}=r6mJLc#r6F3n#P6ut5<0x);B4)t)J%JPI%_Ybt)F;(@=s3>mu(&! zsh<)l08z6GfF}aZHX}fDa&=XM7sh;8@?QiHbzJtF-zFGa^qj{i0kVk-PH0^_nf$_5 zhsTcd1mi#N{8+g97lrJjhGuQ`xj+byt#+VVm+R!AJsujG z=wVbsN^KxX@k&iD9P8Ox49)4t=e2zI4*etwnIM$R6)Q|{JsiydH@py5O2{$LQf|zI zUrfLTuQFy~x*2SXGBz`&wd$e0ip*3k4M~|-Lmxtkg0nH~C?!es){+DfJQJ(E&j;e0 zQqhmrnq(Q8{u4Gs^Fv%oek!J#ZFZkG9zCM4?SJyg{Fv)Lrtc&Op>w!X#?Y7P{)&>gm(Q&)ea3d9rneWZI#g|kp=gjAsu+B!WW z613+It&#=vEt8rkbt7o<*06ZjGP^`}ur_JUn=Q|u({2lgjQQRJ2d9QG|FE&4U-YM! zf6W|;v%1Vm3ZaS)7hffNj1FfVvjY#|38S(%_saemOunbnVyz1Q2%I zH@+Iao@#0uKBl^C0|;BYHCBLE$jZ9+4+K&OIy?8_`BoRle@?1QgR^*rMut`mF6lFo zI0(ja`G|4$PE4MlQs_Hh;hgx<~vO` zlOpo4uJK2#)qT|+&L#6GQ_%!=mMz`B>+=Y*ibd75XUGz*ED?l6!V#>$pwNx2}0G##j5;>W;R z!+p~FfhI>+_VDa;=!w1Xr^1HY;-h4#7jJ;|Ru#Q~_96mj((v~}e-|=M)`(bX*t5R! zhR}RsZ<`%o&}yeI;fG29XPNi?dQ4SSHM$e2iQ z7hOZL^J>n<_VVd8JVk0p!Q$2>s#GN;xfw4kE`)Sd0+iealwg(k>;ZFhB)FYk4jml^ z*o})26A81p-kQ4kHimLdzofR_r%0wSCMmWvcI_{y)khJ6CP{d~o*|#}cBiv&QsJda zse+X%kaYvaVVu0~u5>&(cCgQUVf=0K$}9XbCG{OAjopPLRVVBB@D4{6$6o|BQ#4K= z6MPh`xd>qFs=jgGEsZ%B+ll3B#^^2zrC>3&tkbH=rc`WLMBA`2mLr6&YwUhwU|Mt5 zu3yqE6FDu(McR**))@9w@S+X-8ArYmUge`~)KlbC!6x9I7tzBDthh5!3R7(2nk_`-y;8hD>dr+ z^HVZuVq#pNn+0hs3>WS0_y;Okw8%B1CbJ@%ctCQ7k{9ZMkv=&T9{PMzk=H@;a3a9! zlYb!%o@K%W%_mnk{}zT>=DD5}hIP)s#`|sB#u&z<8JT&!7hL0cDNL?bX<&DISW;MV z_Gz?f5>Qer9S_>7axjHmt)p2Ti55zeY*DcF*zcfAqQz9zufXPHty~NkyMeKo!r`vG zTS}f4u~*XPtMwGdv?8HbDWJ7*fT3JKpo`sajlP2A!!)6C5TK^zW8Y7+WnT1$(s$t$ zHa1vk3CJ&E+}~`S>h0U492su-^=G)jL3~fmfOodnc_meh()xXy>$+)0f6^Zd`;t9i2_iky#1% zv8GURkkq(zBqzC7or=pB=d(&R720*j9*L-ej|klf2$!<{i)M^k7u)4rUPZ*H@^)9 z2m007ID;ipm6!>T@de*5+2})V*n3csCuH~CprY9nE)?{k7GlLk;3HII3Z6>< zZ5-K{Cn|JVwqV;4?Cb~^9NjCY}X+s>J+WZsCdGHP;Y z>PlGH(q?TZ0wgk`t8-#$ZQrEUM(h0TilK+CC`S)xFbcx69B#Z=gCZ)FP|R>kGsRux zJIF>WCWrOi2*c_>>XyH3I76f!LT`ue3>2}<^i2b_43oBa?c{_>Zk z0>8_RylRk=%9Wj{+KOdjydq>=!t<~)JGUxUPx*g^!g~u6PzFn>3R_5qQ}n`&pGKyk zHF|E#T~ag(!78O=`EPD488e#j$^}HdeH`aXPnrI)r1SD7AjECH;j+hlFSP}L0`Fyv zI8_jha?V|oEm}Bo9o(eU`BE_H%6iNT2hz*QW-t#!++N*ncqw8L6x* zlu$a3%}zq*v!rCK{Pb6MyO^aLF+RYD6&9{166Ijn<*`RY!aW1wfeQB zbCdoVS`+T)g&7HR?ece~#>NuoWq*3I`Sf7o6lxa6DzjgXY`CAd^h=#1zNTMzcxF6_uV!fpB65maXKHJ#|z#uw1eL^E862HhiSX z#C$0Cx?`J34?=1*OzXxbyWmQtL|d71;V3!Ob-b%G7EVd^RjN_2G21SWz9F$%i~G!t zGzSM!4_Zl!w9%YrUUq2-!rP+21V7TtJo|kzFB07_Af$qYUJ8%*J_$dhCGrRNh@%n% ztq|1V<|#f>s(j3(knOsp)?yr(4vM2X z-DmWw4B{p)dn63&t#nHcV_sEuQf)Vfgz@U7SsH$?HnQRy-iC@u<}P1#ksM3j4A4uJ-Rk@;S z*E0E*c|2?{zTcZc{F%3?ZnRO-iwv5!$-?rJXd$_tNBK3tNBr;M`E%Cuq~M4C{qLV$ zK=G)EvsDO2@ZaA6k@5StVn7G!pBMl77$t7e=ie{>_0GSB_kTVjCMtja=Mw)uxqf`W zw&y>m5^P-c20dJU|2~4?_ibbO;zyo)sF3x4|G?jZk?9eSmtpVimVV;5QAweLgm%f( z|6E(}jTnZ^_g9?YU5vw)!3`U;?{3JY-@}sRoZy4k^|J2O+w;)dYu}nB95`p>=T~ow ztjvrI?R!fJNy)T3k?a4u(UC@i==#g;t6A$AZx}E?f>;M*DGFTqKO7h-kQ9vXzU~gc zSA2Wt&Gc=HpZBY*A@8?w+L!aj=MML&?+4^J_?+y%H(UivUa(<);2e+T)hh$XKA4d` z^Sl53CHv_pVn|S&f~>8cKJV(x=g}x}evch-?;`?1(8~}cn9e)OjV*gZZ$)=kaYA4Z zKdy_1g_Dzm-T)&zyZw#r<*w)7`VKy}H;s8As2;MU$KN1JP5MAH3g@W$f*0#9D*j`x^@qevCv}V7FT|nOp7r@qY%C4oF`I zpr+bF^78~456&ldANwr4n-=hj-a~aH$9yBR9JU>YFvki+PZksh_Q+g2>YAXVqFP&9 zU03w?)AWZ0pVutoOHi@E5}+@crAHod>#NPSX*Xxx|0r$!--iY-5W;mm#s@C$`ROZ4 zT-;#X1<@rEd-0%;qF|lxgtZD0BZr&kivGpd4X=ky^7~867zq}^X&fk8Vfc*FlXE+l zZ`?fJ(_^9u`synycmkYh%`;1H(*Up>bf2=Itk=`Y4`v32|9YhBWfFM9cKZ|;O430f zC{$@NVKpk2pRMezt>H1Kg~DG3Yq#!)+$-xn&rX0paW7Y(FM@j5V=H8f2}}^=kAhrZ zKx)NVzk}`lz&Sj;_xc&>XC#enC-4|9z+t z@b~z?6I#P1IEIQ0o)n#Q9%G=)ZMk$3-D-e_zspta+{|%|k}dCP5grVMZGiLs3$7Q( z6bS-wWOz=Lz4yJV+=UbRR=lye&Wz7xU)6UdscYr>dyV-&6T6b1spoIij|WA}o}c>f z7bo7Ad@}cJPot9V`aX9@vdo0vmnsJXpk^-{=adCG?{B%f=e);c``MNdX=X zt^-A2@#5|;oDhy6Ih*qIV+b~ri>pX@(ZL`2`KY%j%l{2wRntb%UGH0(J;2w>yH?{G zzs`N@Qlu}~Ln(YHhtJ6-GSAC~o%bo4%l$V0Pl{N^|9dZNfNjVdIq~c4zXPD8av&P? z`9YGO7*o>!ch@}AeBhUxX`Y?Dup<8KV(eFJfOqhpxVpP9L~SF*tbUIDdnWUL<1(?N z@qazmz}f#DJAq;R-`E7qwf_npz(-eh67c^#Cq+VN{}~m*?*!^sexQw|c?;gTWIhmZ NNQ*0o)rc4c{vS_P$YuZl literal 0 HcmV?d00001 diff --git a/docs/assets/images/mapviz_features.png b/docs/assets/images/mapviz_features.png new file mode 100644 index 0000000000000000000000000000000000000000..78a7ac60dcb16358bd19b01aa8893a2a0b37c0c5 GIT binary patch literal 274323 zcma%jWmFtnuyqI!G`MSU4Nh?P2|75zT>=Dm2<{NvodE`Smjn+k0fM`GaDScq?tS0i z@2tgQ(M&hf(^a*1)!v72Wks2{$VAAmUcGuNCo2hl^$Irp)vMREh_8Vo4h~w;z&98t zu#EVt$}y6C;0L5Hvf56sUZG(B{epRwo=E^4L~xc+Fq zHTQ+14y&)!njSRw%fxYB=4NKIvop);%Lmc|wbVgDFjPS`Z14O>stHZdKdf0052w}) zjQ2m7q!O|gq*)Lzy8jp!H0ghh?v5$=IZ&+oooM$v8>wiWW#AHeUMDpx0wRjN(Zq3a zG~rTMdt`Eu((;kt9E_X2cVlkCuBRP0{4p0pnw@`=KiReHGbA|w zcTGCH514WcqyGQh6&u^qukYW#uVo;g)MTt)@i5gp_e58D==>x>1I`Jo;%w%F`+MEk zZPhw8YD&iBk%3}=fBzpmucUdnfs42^(`UaFoO)^oOIwiZlOj6t0{7Sn?{G27gFR`Z zf016b(a^Jgc9HY)sIIA}4psXVtEum?U0`opJ4y`P%h@Qx4b$n%a+h{qi-nNe$u0iL zC-R@-7ZYaVZPu<=PE9Y1;iRz<6;zt~56haQ1+({47#pEa~@J+y-z04^*ao)!=FF+ z&1S4VFGb>&kB&c&zdUy;d9zt|p0`qMTT&dpw0h2DylfK3;LQp@;h%cG*q)x&@U-8T zel+mDtMK#Qy%$11@m<7yAKAT(aH>sLs{6e0@zb)2q+}mfLap=9PpdAr!C|tOr!N!s zPbUMK6`sKvI*Gs|ZFf45quf?pWq$G0FGER#6#=yev zJ|Dkh&)|96z}40D7ZnN$%HQXCa#H#44NKYcVdivh38a*CwK$67C9{agx{(Wbd>$6C5HX@aS#{~zz8ZrjsPVth zu!ApO~=-tD7z-BfNK`WSSK&CHv099)sI zglGDf%!XM`Tm+xlq;#%L3_RcWcHGzsT`X>Q+?-&LdOkNL`LK^nZLRm@Jbn-DY*uLa z*!4oE-^sghka5!o<`I% zOBYp!Z9}%^KSNBX?H7u}wPZ~2AApR#^`v}0!_51ZDJ!YQi5kRA-IW9eosJZXJnpl` zrjOsP8$7wCj3mBsd%S6SxpN3d7Z$8&Te-r|z{7-Jz9Pfq-XTuL5f<2mPr-RPT0Lod z_$B7*mlBcEzJ_?=17+16T0d9vUb8=4$eV(%@;xjYBeZq(xu~%Oa{YGmt-ZU%$tJq+ z?OK7s;Gw~br}sr3x=&bG=dM@hZkbltuE))?TaN8wg+^qUXUEF2+p5nGc>F|A>}>c8 zf#qimxFpc_lGC{Dhm4+eWkl5mpggeH-b|d2KR%rwaelDt zx;hEQ*B2aaJn1;Terr6eDdN;mY4FDQ*+Wy|X|ed^?smXRR26vq?TAYw7H2nQ`rcrfLsLWJ;L5W?qwRJh5|VfWyqPb&f-VQY zCJSW9VR?Km|LlI@U23w=+2k!bA|@ap5d4v;24c8*oLqU?IPG#hdyZXw?p*Ea5OkY# zVi6G~7s$F_6L24e&r<3*T`qp0P{(8SnlJ0x{nI^GNf-XQ>VBjQU*zhhOfSE$tg6J* zKSi5&9tTUs{n6gz_FD$2uY%6=m49p0pm0EdEn`;q(poZ$y(qiph2NBRl*|U2R<*^3>n6Aupet zGa`WxVcUK4r|au_Xz{e z#>OVW*IVr9a(A}nX`JE*7dS9d!f&Tk~SxB zckZ{qd!N3`{F~c%G;$;Z$k>0@+53R1(xUNlarO`)Ft-os^S#B&1&Y1*w#%H}O$5*L z9|La(P4BmhT7u5U4Rr%{cO%l&Bdr53>)2T+RerO~b2j&UHqNIn9psOBZhrGr@ohPe zEr(TJn>oT;nBf(ExBGL?OLVRfkDLEK=}!3OeX8zmUr_VR1PZJ{p ze#b9Qzpm%LE21FipT$4Xi8wCmh)QyKp1pM0y8j%mRK|S{w_$#-=h548SQ-5_GgQQ@ zbe3$z61+;+GqThM*B za`?x+rw_CFG`ApqyS}Sscqb2`2yYB}G!{@+&!>9I$e((xaxA~Rgoo+6@1#SYxKDI?`1 z889$exrYbrehO3UmAiVnz4XUEivB9ZL7iXkWGXpVFRPzDs;d%tQCfLWqBD3(AN_Pv z-T9QlQd%QZBQ5OngY%Q$b()FAz1wi4-_}rp+so)~r=#^b+38*eI?kw<{eRE0;=4kc zy6x!LsML{NYTZP?cimH#$c>DMhr``rLst9M$YIX&iOAz1K3dijc-!Mtu<8%}T=SQG zscRXLyYQ2f^*QFzF_D7%xhCH~>lLu90=nGx9Y8+)T|W}gRx!G)_V+$^)!noDopp}q zxKJZm?5?wVUq8p(E+qdfVrhGJyvgx>ST^{qdy(%1igk_dgIHuu-|fCUtv%L_L4P}~ zx{AG!3*Ra~r0psZ)twsC?VRU%XJuuM#CPaG zsq0yLd(84BveTyJwq$P5S|+DK-uNWqf+z~~Q8W8fVss>H7N_}txgAJH@mqms`7%DG zy_W>>zjP0z!y~^NlxgNe{@(=pn?qQFI~&(Puou6$55I2`MEjJcy}#M+`u|R0;PDaP z%U#d??-V8Y)b!4O-?+d3deMK!-@FOQAo^RP{#kYaw*0%Q@#PUafP2JG0tGvDc6R!X z3*CISwIvntZC^a*=pW1En?Aha-Ob)j0zueN`F0^-IYf#edK~2JU57E50u>CnOsD?T z#Hkw}K~BT~Hq;)rME0{=ORiemHk}HrI5X{JGfdz`J?qu0r`VH6N1q#X`fP;8>ulS= zP_5)X0+fJUjWVEjacvtVSX@|$2PcCdKMdC%I{&giW8$#E8=pCs9=3XBl*JLg6tGTm zAKz}~r(|_zyqe%`$29g31k!;Yfe0+bpVif!Mg>->Ro-#dNWaS}8e-MUbFM&xEW}NNfZ#ELsBlumC;U6lc8f6VS z6}l`u8Kc|V+i7WOf3d6^g|%FxEc2r2hrG-(sY+28C5|8vWQ`sVAm^QrUK;FpBnYTE;`Cu&UbwdH{qDb#RVlR{T) zdu^yLW75#JV~Z{WY@ab^F&>(sxt9dRCO0)5U9z;Kcn~F`6oI5oA{g|OfU2L6os3F2 zBq|Kjs9dt$hmuHLa3e|~%mzk2s>HY#*LpOL@u_yN=bVHN6VOS^mn5y14H|^sGk6jc zI^fxgG%7DX?OncWpI@-Qs)D9ae>9#nz}U@n=ucbN-BM3nAZvgeERT3gNai61BAw!3 zTG_)veSYMa?qrx|FnDlY;+LA0+UJuuh?I@Aa)=b6`&A53FVA?F1N9_V4u* z`}G4@7Ff*h*^#};%f!T#Tb#Y?(x!LDI9&Vvf-xy#llPXH2?rTG^bQd@__Z*J?V<*` zM6fuFNI(}yKaR)SfLBre>~Cm8w*%AGgF8>r-@p#nf*@F!4La}HHh&l@SIyO^*VWZQ zzzm21(gk9Yxr2?iUfK9?{-m(6WlDYx{9izejgfuEP_;c>@%*>sYo8)_U%I7(Sxe}jkapm-+vriqR{QeFTS`tsQkcG zeH5Uik6LHi`%Dm0Fj+EV{Wi3xrG;--+2^8Tw*-J4Z|5O|XZT-L|4F-Eh$Mw?Z z7oES>c3d_*C}lB;$m^8T`*|*?NFDC)gJrV7k=l>(OZ_bg(Eq(d?cN)s#UNtE30xBZhy|? zD(!)B9CoxqV7Sg$GBRaIXtX*|C_H~ZM~Fd1E4Neq7Nm%tm9fLZ%5T?fvyQ~RJ*hdS zC9eCWcP3lrhG74AYTVTa7i?+Wr)a;%!6e~Z$mPoId1iL-Zw9?yD`&44oT4v}QQfy9E1Ky+L+o;oZbU)9hhH&zUz zq%3kHR}2FuQtC_*Lz@E5H<+A4UcBpb(_%(OM!}?|rza86!Y?--1Ib@DljRWIy&8+6gM%_RON^{EkHo%S4m{nF{2QDfq;#o#Ddjv$Yqe~$r4dlA39^V zwUUFW(Cwm08B&IGuP|-p49FqZ2G09Ko0U=QF42>$vh$I6(`Hq-Wz-A|Ex*^pR7K^CaiX%%%NjW%Hz^>q0sCJ=yWU{me6=Mj|qHEFlo%AIBQY3>1;pDljW1kGx4@ zFFIic(*@qUcuxONbwZ5JFOIme9G4f$8JN<2Od4=jXCFg_i9WRgqnc-C_m^HsP8AG0 zZh|*%KmNkZ6-@h}kf(KDskmx$oHw#8moBMT=;nc=P{u4-EOo*XSa%@L)kDSURrrEy z3a>*s#FualXL1V*dZx#k(VsJOdgi}O+9@sF-0k`cRZ3Qw{4UluHiwt{)5~^lTts<} z#~x(ODo{0RE}|LhhQ(uX=b-$bdwKAeY6q4-L)xT1sw(fiAS7==LtX>Gtxrj|i_HBIO4Z!SW^8jQG$je2u^`hlhrCLy(DB_GswjcfLJ6|3fY1cD2!wKdfI$SsO$ z81weAnWZeLqYYO6RMKpgb$qkxe6jN@?gOZJXf12lJ(-ooyBT8W2=IuUo zo_cidBKQ(~&3%J`9}YljV?A};C}KOwFZxnX8-lI_nI*NhgIEJJDyc-N&-&ACj`i#` zS=PE@{o*AW&8E~e;bD8#sU(B$6xybPIb&JI%bYq;>B)TJ09`C-Z$(h5^$ps=NLsG~ zr$yvFMMWZQFV_dOtxQdm;vYz z^q+HH!~WCV)Hc67Kk)4WIa*d$cB_oigK>nhJ!xEn*nnOnuSW{!N0Sdcx9m_#;h-7) zs?b<6^=3B`1a7+t4rV`Ik`2DwcRQJZu~`YFM-#u06QAzrOzP``D5TKyd*9 z0U&2R0n%akSv<_HNr0Oh{*?BXy;rSTLe^PX+Q{T>fT6kho5feg(WGMU$#j<*k3Bm& zTUve+1dhYB(ptJfz%bkhb#M|DbB7)J=u$7hG}W8Fr!s;rWq5o2ixwk5i@;s0ZX`15 zWn$nw{=kP)+kS_PtgNgrebYlB=WSAiGxG7i%gH9paEUy#>szT4*lkj(_m;Zc3JJ>4 zxb~VPDRg9t9yZkO36$4!H$JN)*{Zw-2 zSPkJ(VcW7Jain5x_d|)_`%|$dt974hSyg8dL8L;_Fkg@J#L1s}3OY2#-$lGckrt07&fb@9R`FHa5Q5$DG=?E%)_Fk@T0- zitX;P zkYYq11|Oe_!GS7;5hR8IqM)=RJ#>gmV(&c4%SCn32%) zJ4I@Dkk3MMUZO_k@Z~Dn^(HUnV3YV8No$-Nl=*WTQQPc!b2`n=A^b&_I|LHvS^T1#&YZ>B!u>LJ-k%A;kSP7$C$IBL`5%+Ah!S7k~X0;+!Nek%*ncVPH7po^h1a1)_gWC0$Rba9&$Ufi^qfi`g^J_R6L=qFXk>~Ufd6_m()st}tYMn_eBDNSPDcP|VD#1I@- zk26N~+5#SCQ9L=Z$#X%R!lcvl>w}NX_((5)$6#0OCC7&GvP;WzbQEQV8+;c?hEt5%Px(oqmhaO^ zmd*jYbz#n+YN}3SR(O|x;yNhX&Ww(86QRP$Bs$laMn?RtbTYPKsIRyvF&+tTb-b5H zig~kH`9`93MoUQK;$-bE-9t)bzEkC{$ni1>{c)wNE3spq@Qsvv#RaeJJg0|iWm!sN?<|Ft{3DC6W4x^>1z5rcn zh&1I)YW~6$17H2@syWdPq`gp|)6Vh8|T0R+5%?nJps;kV!YUCS4W@ zTfI-80^<)Jo<~Mdo#!hm-ZL9{co6ETVi>DLR?Qt|@AAb2+Lh{5?6k5Vnzb$CiHi;g zp+=EYsFMkM6GT809ZgJN%~dZSuqVgH#!gP`AmFs@Y!)13!} zMMvUr^1c~e%7eCqjeE5+k^1VB`j2Fjt|tt~`8M%PG6@E#mKtr_zQ50KQ0$e|T|)0k z#r*2;*o$qoKtUx)wqIm<9xGHT9t5@q(OgrZN)d#yC5qFEX`ElzIE#r;*+3%us4vQq zenyKva$DVl;;7lC>rn~R&pa}FdetdmB8B1;=Nic|nd-y#lRpu^EHv5<7`z|eSgLi7 z$oaVAjQR0Xd(u8{zW{OTa8824%YXw-WgGoHb|^RCsFMY z@kzo8q10E6V|9XBv6PR8LnCPE6^xHtH}9JKlhw&GO3u%-A#YA39SKd}RjuTh!(u*@ zmMGqh8^+%sd01lk;OdEC-p`-Jxv1`EwjQ&tUTBg(boaEuB<--ckGWL6BF(B0Aj%1-5nU}Jg4WzouM!x zIpAOpaFxIxmR#bCZKn^`dH|$x;f(nMA^iSE(B8qp!ORSzQ!zF^Epp5v`2?NMMPuy{s(#j6TxZwN?Y@x%y*8)Nm?N}ea2QxTfM5Ek`lAHQ)-g2Xo5`T zzsdHY##!&<{lQcXb=>yjyUR?pB2*`oUgvb3+(|&Ptz4(zi)9BoGVpqXjdD*}{(2Nl0{AG2tE0B9*Hj;ovMa_2p>ZgKOQ&$(LrHoPF+ZC(BN$|DRIqx1dIb7$%FNHZ5nF7p+ ztG$IEyR>0|$Q1bF75q5}@>&R&h^|jgiC!xOMDvX^aZKfHsDhK1SKIV{rrU}Kz?Z>8 z5}{}w**rWvO|`X-8@)(eiWE;c0me02y4u=MHO5eMa#xbwqj_NFQHRI{bUXkRR%Y4V z-6b9HCyPp)UjOp@^9Kss{4V5$_n7L8xD=9QGud#EJ-LBS}54CY==+l|HJU> zW{4{=?g)7s$Pul<>5dBEEiZj}>)_T@mC(EMD0am9Qg&nJsm#8Vi*`xrp+Omr<*av3 zrWL%n3=|(3c`%jC&PuFXiorH4uUpnLIhm}p#PoP5(KFc@;lz|tpWZRU`Q|Az!*$9x zzK`IJ_IgP;$T2R_Ni+ckYzT&9$C~lRoy5%LOIu-)j?dw#>)V8wAwrWf*n#w{%LHqsS36H zI(YS|D97`H`ytYJv&a5nGFJCIBGAp}{&#;P=R+3H^F~Gvcf++?*Dd+W?XBoz3c0s! z941n+2>;9O%FW@p%{Q-&g0720zsGU9p6ff-_UFMA;rfeYk-NTOrVvU1At}E4VZwWE ztppm(9=a&goW1{*E@v|y`dgV9k2v~G=`oH49fNhS4IQFgi|!i=)t17wfG{dR_hcl% zWqO}7e3q9yY!;M}45H~BYpWC>K>hIH!}amvF7McSPbh%Ax!Pl+qgM|;%Kdgti z!wXAGpSg(G@&K3<|JvIbNOF2|67X12S*fU?kaxWQ3#!_nW9#aA4Rrl8)-LAeAx++G|+$R;mM%mX|XxhTPr9jd1dc< ztXy7l-H#;xE;k7EUaeANM1=dEj3CBVlmX&?V_gnIQ(zLVhNYItKkmrV!;Gn*t=6dt z0fRty^2NoaIx_UzPQx1-zdR~uO2f5adh6F7`tnI{U6p@Dw1}I@M$e#Q@2kB{2aN=? z+sn@RLRhNV-@wGzIn(&H6Y?blVx#Endk@sx5ruO(U~8mW7QF+lNeDV2<*3OhPO>q` zeayBftexa_99tewJy|KiY>+vv#jx!{v|T$@ zvpd+KkO|U;`@YaH=m%YlkmGh#K>ao}UXnx2Kb1|YwmBfV^BZT&J+l+fw(Nzp+I>ol zL-i}IA7?frcXplheDqxYPuktQQYSWRCvUiAE|bJD^4g^BqLZKFOPg5_1)8RkU}?vj z>s8Nz(XpGSxh~K7KYL?0?N43pn>!L+Pfwv?gC2XX=gBYEZTK2(IZx3|k1G$Aoks(# z?(+in$i9E*x^4sgu3vPuX=={bo1T8tg@v_m`d#I`?5&^P&fGkW_04Ju-^Mig^|mcl z{}n+KGXi8vvD*Jg21s_VAzCRTl^qn2^C`q^8Y1DKuS+6*8a;!%kccK;K2e5QraygWw{=e|ldYh`>JN&D`|SorMJ* zs9NcaHGsjR=1wjyE*>5&)BDWt-}{Sgq`fQnP4KyNllNPRg@px5uz2ybe<43WC?&p& zeRojSdpQ8ZBoS?tVZ5F%+azO`X1>db5*SFZ?vU?~j-Q~!miq}R9jDWgek_PWpjN^9 zS*b^rFD6SgxsJC<&}2nLA+l2xW#s{mQyzHVf94(O5DAxnBi*Wi6G`0?(HWtIt6Gn? z0|QsIvzMmrir|TCTzW}XaUg%cCpG0nLlG;z6s47%0b=0%Aj2TF5MD;7Egc7&u9#LJ zUnA*;4NgeV=86M^lPn7)SvvB4AsvUdB%Stb+(J_3zD38DL}6}j?#x89lT^pMJu1tY zaBLodVaEBY^Rv4nRCS>vjm@IF`G@*Bu5u*LQh@3HE=bS$D1Y(ui*ffBbDI4(G3#g5 zgKGxg3^T6rsLLvyM49+o^4N(mpIsfO=sMD-Y^Y*CjDn;%aH!Wc%7QzDeeSt1{RK8KN$5vv!ILV0 zfDs2zf4M1EQrKtgU}R+E(k|M1GIaQYVsl+$dF2gkR5OQ^p@Ofy%JyAtuiOtP|L9L0=dXP?47#P+^%fU#7Y@u&E*oQzJEgdST=bKbB{nzN zrFVV=VWuw$dL+4*5iF&`WthUt-}84;wKg~#W9sIlfB2Bi)RdcZA96_?++6u}kIM&9 zXUVD8eaF`H;7ea*#Ae0@v0QZakUUo?Wz_-AzSkHDVUB`b@o*L=Pi5XtR*5ks&-RS# z{HJ5jc*cFh_ZDqbMJYunTD~5xH5@vp2x@d2+vf0euULOGJNL-#YV-ak(YS7i(E4Iz z?KkZ?_)iH^^f z?^##?zZ-sJU!BD`3k%Bz@#+mg*!1S4;BY_aU#$h&QL?;x(!z+x41cw`|La%cVXLfc zpI9JH^as|NItbe55WCtE6DkccNCf#zM#%I@mzoEUPhKR}Rl;!UpEBCO-OW4x@ULmr zuuNe20%f)g3Y4$(a_R%WsQbfs{ZpmQJQbCZHc^C4ROm~>SS#bD{H0{IPH_V60vM19@gKgL~ z8)uY}(@@dEBvJ@kUs{p~MwdqWVVcXq zf@8Z(w0*zAl z4ed*If5xDCqCO$|7Q5J)|OZ0i_=R5>sVD@d6L%2sZ)?~;Y84e@Zm;EDT}5G ztLr9i@&Zw!%nm>Y@Hkce_^$aQu*u^xIqKa2ln3DDfT756#eJ!^9H8_rZOdtCgsBQm zO-+-j!A3BRwoQw+LGi7X0-T(x%y_^BfTHxRH9|B{qinmC<#Jf3qA0AuOq)(I^Og3} z(o%0Z)UicSK%lLm0Y0Lutu4}!;p`)UyzL@cw6wM2ks;gnLXBI>Z_FrfaZg`!sf}NJ zI|d{?`P5%T(7L#}7Vc@?eo(kyqW??Y*X%DeGZ$I9Up6MF?AV8mllxjm-wWKw(Y;`m z&}||vqO(02!THQj5P zwpLUh1XUwfBxg3%4JE3jMUc;Jey^uzW}8+Hq70gYcR@}<#6y1656VMi(_li4lP|Qu zqQNohE_XV@z$1^2nZclCm!ZU+NdkP=7xA4DvCt*sj(dKx?D763E8s?6XL55JJ|Ec#*e1D+inZrs{Ux<^BcxCPd4wnTI$Gn?2m>Q zg_sk5$riA+*_a%b{AoT^Jp3-$Y z^~3&U+|T>Rc!#OgZSc$0%d)`5BM&*f@-BO(VKD5tkKKjD>C>7Je%CYQVIE+{

    fr5Xk9-C zOb@O^Z2!Bt`8#54hkCENWEMRALT(T!T}bXS9}nRZZxg_-YvC zA|Jb9zIasrhv;1YGczTB9RaK`$llfA`$g65=?LJDoEZU5TC~xvLAcKOJnIpmh`_*5 zrRabLErz3&vFBm9j(p0fNA2js z@z)NHqe@-YA#B~(+L4>ra6)LwywZ_JaLMF+{+89hVdY~^w{M@+KMDDm{!?+WQr-~u zLf>w#SiTeSw5Fjave}u`S*kB8_52&gj@=R-wZ7cZV%+~AflJ@+1V*r}fY;P>bt|}m zGO|9q9jui8Hcac)jS6{&Z*72LnUYJgd3rzciFNn%WS~}NPi75cK2htPhR9Lb0j$|V zH9d~{O`{jFxaLfZ97U?ME71UuW+&gf${L#cS}B>269WIF#~%k4LogRm#r@5evPv`S zqV@Jx_t^`gX96`7?Ji`RbXBa-YW;Rrrn^hMod7}O5z4q<>Iu9GXZLFuvI)n>!>ch? zxLYUBbMm*wK8u4zh&3LzOS5xJRt?KAc{Bw=gE_G<7s9Ii3v&ZBj9N{ng7)lXF$nAD zSvS(_-e35Y);8+>3wD$RIq9&phY%u;v^sM?ICx#AcNLXLHgh)NjY^+ z3QwOreQ^nJy8Y9Nr+eo8tOh}p&82+IM~>U>c3K2R=@Z;V4{2p^6?!FB@;C<<4KYQ6 zr+5f{2D0|fJ9m>S%`MObIKI5bFIDRG*L?I6c<%(%+#&>;(P2}$Qz!gHsQjA{G(=0u zq;H66^5Z}!$gF*;@q0nS$R#|hK4o!sGF0$UEt<3VRyxn02evk)ZnFrkNr^tk95mQ4e8FCbHJVX~=sLF*7 z4ZkOJ*d^JdpL7$jiuoU_7=vD>Uq_t|OcscmhH9eL=gO-e@i0TAx#J>LM8`%)`7rf0 zaU8l3ZaYzs(ulvJ_+9V>`r71YL+M42O%UNJ8Rr+dbVyXk1_74G#HTwW|#lp~e$Dz>i=*@uW_YM^B z1OZd+;uRpnopOqDuwLtE*`6=9af;mBi-)0e=R22|P4^aL#iBQR;1Cv2mfbP3K83SV z(=V^38(?oBUMZgHN1jSTJrQI9{3sL(LBn}CbicKGd5S}!C%~(?nhOHQ3$h5#5URLX zpwK}vrBBQTc@roLfE|pEndV(PR zZpP0;lgq;dGu1I(7PVlEc2i1{$U}G+Q>rXOvd)_Am*>N8>{p|nWY!aHx2Pb@7}%QUta#9IvF)YOJxXZYH3JFj^=4kjNq5uPW@KM3T8Z zdk?)xDbA=*y;nQjW)>L{B!Dj<{R;D^bO6QP-ZUfWFu@tNu(|onf&c^)$G8tbbfsLy z@EcE*!Mg+I?N&Dqp1hm<%6Yd8Iyahkn&P&O;Ngwea{)V;@5V;MZafK zGZY*&h**T9jWUq#C{M6l$I|9&cBG7E>#fbr+Cz3u=ijLu{=2HZzq%^W+cCA=u-MEd z9;Mb+oJq$Sv!Vi(-Y1;Ez}lcE#+#}Soft2Pe}-a7=sizZRk3i~m>a%`F7MlJ3K>(^ z(6r2&t6yJO$lpKef|v8?ZpaJS>zg@{d;dM{?qyM9{Dx$rXOh0`Nj;_BAQ}|*8VkS$ zS45AJ<`C4UVy{g)a>w?5)n<;q4w~TjNC+1r^)Yh932AM&eJY0+I0>sWzSWJ_Q{Q?E z6Uu|>+)t6IjtXlJ4%w7MSxrKMw?c7iF@a9!3FX<)k5e;h(Z%xB3G z4k?5;zQJ)xdX-??KbuJrVkLB-S7Ck(lKZQ-l4Ac_S%HzIT2OB<`-JkY{AtgoOO~A(~Ot~au3j-#byb)j3E%BJm@rme`#e?(E)QTVHhQ0j| zdFZA5QZemtOPlFp?Y|FP?*#^a81_f8Fh&G%0Zr&qRzS@C@Ou}Wz6LD%YwymjCRLsr zo{5*`XeMf%0-d+8|w zm}?K+fO|&bV)kbT&#`{qtyI@;`F&Ugz0`S!ZZywn4ZiteS0e8aHLj@F(En~vIo%}2 zx6Y}xY*k~M<-11jMg>-F0-@FrV{n!Abbr!t|8`*gt@C_neX~*KPh!VFU*LC@^Gojv zg=l9WN}kJOyQ8K^X**S9a0G!v=K(hD?Ey&LYC_Tx$T!uK27BAH=t7V3^xNcYV}pV5 zk9X^qnH}DiR@LPT-9rKX{tL-LFNbU}Y$;vX$S|Ooc)z7DDX2c{IR3om!`3zy(b_J=o2^WG)!^J+OwCv zLPPKC$emlih4Esj0wf2D4C6a69s&;NT2FJ{0l|@f4w4J<)pNDRPiu2LD$jDr2uK%mWbiMxTA~4GsdQ zoyTezzdmr}fPI5?rr}f3utiFc59mNJH`Ua}FQ-G@ZIyzeiSx%QWsvq;ER9`96 zO#D34sVv}%1+VW??$*Xqc5!$2gtH#Ju-M~*$jO~6OC0|}Usc&S3y=+Mw>LmQA(DDZ z9FTQgQD}r>${J0X*c6mBBmd+~-XCftpxmoZOT;1*`99mFoZJET?PJWV#HFYEvt!}x z(y~&J%k4~X_Nu}wsTjAa$3xWo1lq8%AMYO38P~kfu9E;PrlAyRiEn}hZ_jp3f}3rv z*7iD;s+-2E0Y=en4?i?HwwoEqO%ZvhC4)4^1agO7+p?9l81*MkEV_d`oA=Sn07dd8 z0aiftpIi_d+tc&e;@w{wm}>j$tQ?TBu$H;n7g*KkbR10#hMs_r_pJ4VsysIbc=q=w z#8Jb9ah2ggVTX|!5Vg6Ny*ndz3%Gob!gPW$a+hA2RB9Hp zJ#0v78`t^TD6=_IGtbrSGTaD)Zp;G&cI>&Mv8bf_9!kBvPi6!s8nd5_fe%B@IjP|J$=&r<6I=dXy^cWRM1 zCbE7#c|s&(njg z^*SvcAUr$Xg@}ivd|ssZfkZ5_9m0ivj{~|$iANl8bc&SO$dB>l>MTp(6QsbTTPMbs zTe-pTJJivNHrwOh0g?=jVNqHl$>Mr&S3)483M`JmD@2K)**jZb-_Q`VJlO_JBKPX# zHxA}m%2lJ%)r@yngnN~!=3TqZV2!w((IH$Lu(u8U!oJhtb!xf-AH&3x4p#}KyJ^yfSWOJXb=jx#cB+}^1rmwg>_c=YGg5gI>;KilJFc-AX7AJ z4D&2&!9#9zxOrQqlV$i(m8<3nKTJ31O=QTrUOy))B0#Ga2!wSc|} z@~E_vG5Yhn55#*{BfkY3r$|Fn;SiuB(8vQ?tID`ANVL-_hd_l;UP&y?g~;PV+hHOE z0j%fv4USmv3}JUNRy=m*PQQ~?gtGo;C`=sHt91I!N>P_8zdHG z1VcY}25oEwMm-uL1vsO?>^a;y;rz`aO{pEzneQ(%rQBAPdLG8HFSb9U{T)|V->~y< zNSP{ol6!3D%|@ECo|0F_$YuVHSBJkn{D*YxiXCky@|j>Rqh`M2pb`0=1k%l(QTy^` zYhS2pW)R<*8yot=xNuauR>WWa6Ao(buM4J@$H%=yWpj`rm=H{{?9=Sn@qkk1-k{T- zzDQCgo4tHrQ}EbRUfvUYP2p>G7i#3YrgC%VgIiJHCSg1vl^n<0J-AX9^Y`Uy+jrYB zoVi?7SQN0K?{8O{wtT2>){a_ASFW)i&3n9=B(}SCUt>>ke|rClmPQ4=$0KO`KVMES z;6n|THHYuYJV}jfy*ec?BZbj}i9!=NB-5*KXI^l@%?*&!U}uFlKWj2jYS9$lrIG3W zs=B7=92y4r+Xnz|+6@Mi*)2PI=Ig<+`Sqx|L0e&Qh&Y^h1(rTeb+)y^os%~B5ys0` zR0O8iE>MmmKv#jAFEJjtqm_LE9|N#-K!6Kw{#IHs>%X0%mxC7l$kMPAg>P%qobk$o zBf2miP{^YEp}O`}&H?!7_CMcyde(eZhuYWoq*$i~{{C8DSeZS9zM&pOJLje>(Y+Hf zXoOdKe{9=XqZ3Aj@^+jtcoqLoY0+qONJvD(Fo?FGjB_?uel75Vb{;Yg5nNG8=Mobq zIwYTctF!F>wqrCJ;Ql}s{DDT-9*uy_!Cl9^KbmNygri=fG zfE@UGBjT3hdZl-We_4`9k-~O;eUW5~gHO}qsyM>%&sJrDfWS)|8=J-EpqI{2yc>Tj zJeYmq$z(l684O0!4MlVkV10B%00$&}a&hHBx+|ViNw;rDK*XQ8q2GtRHostbES8sW zoWLibc^rRnw()>CA{TK6;pRyZTQ`&tCnn`2415m@`5#T^9?$gq{_!`hOea&m83}V% z!X(Fq=9GmZ6y-RFB&Xy|q$M#4bBNJFD94!dv5^TO39*bUE#`d8`FDT*`1OB}GTVFi zeO<5D^SQaHOo&7f#h#g6`XC$}K`|{s7*0je!yGU`XgW`LB@>J3eL~Wvr5|!E)<-^$Eb<*FX#jtkglpdE z=3}|wBy;d!wjDCZ<@a0jN#kTiu+T?P;ZF_k-QR1dU%FZ4@q~Vs_TvVVta;%=_}pWtpa%DhbUVHcXrFQ5@W!B8^0LsQ+u9u9O;BC;!1Xzi5gdV&Ehkr{5R2 za|9OWR54t%jCq0(1kq$r_gq@KQ$K2w-!Ipt8)?#y1PxFVdNh=zX01@lqUh5rK%32s z-XZgBLX892~w6NlF&>;b%%~eb7Qcwe5O&8(b<8kdxhojuW+Z|6a_H(%x81 z0Drso%<`KWJG)+2KZ9ZFF3?Yt9B>_B8g1Hp8~MB}OKUHcfmUz(pG|&BFB5nxh~n_) zR&&ESY4+M-KXJjVwNu1blxQ>&Qnca84=v{656zP5pi+Oa`>QQ&k7M=ZV$B#8@xD@* zugSw*ZmXOeZ3;iv{f2t@en?12qm5S}T`hL~#PSvG9W~R5@{vjXrs^BU(#fE@uI?G< z6cP|15cl`@no%}j!QSW`ykR06Uql?d+74QVulLwSO@U<#mq=L6@ZDbdo(r&cRZ~I?w+l@m#&OgN z>1e99@Y+KY_UpdNb)2;~QaW&sVN+s-je%ZK80wc5%X*HKx+ca%@7DSq)dkKrZiB%a zGy(WS^MfruI^4u_SguEBFCtgVt9t@QpQjjV!QhE8p9WSfOTXu|^K{+gmtGVNk46mm z4^+)Mt9Yv@%u%MV* zw)Va#=dtcTl)PCzFg27BufMkrrt!A7?ALA10T54X4^^X@QS`(Q{ZR3WIsFVAm7peu zbRxN`M?%Mmit^R;#UKm5WMu_mt?*~uWj)*|4cX%J3~QK~b&AV{F9%0LOXGhL+l->P zc@vR#p&SJNQ2~#Lf2|@8@W9L?`4WHL$e-!_5keWT`k%F2eF@uUVATNh^fv;kU&HLl zw!r1b3B?+rwz7RyGE75qIrT8l-cD!v5zXCB(fDAWk*7X&Tc@INjsA?_;`4+^vnYgd zIpJ!?i49Q{(+tMlO4<({5UvWOYL5BeQ=?eVH>_*@+i7be?POk8z*GB`sc^k0Rok5& z&Gl#ALZb};KtnScV}p062jQuel<6_t-(fmM1W*in(itgaxycBsnpvTSnsHQbSm zRB!_N_<}eXKK2NLA{)O^pUA}KsP&Y8xs50O4+}J@uSJ1DjQP_#pH%0^@}jFWPS=j> zCZ7^7iZ5q$G>xT5@{9G}qahs$2u{>@oc*m^a%o*Wj0kO$3Cv~P1^b8{x0tVY%YM*r zB8*K{i#7DzK~SIfc$88(fJ%uE0(D%91oz|@jmt8RK~0q_THg|oWWyB%T=;n1 z!s*JPap5c>;2SCoZIkK#_FesWR9bmXx*)jXSlOVWr2364htj${aOwszh{GJuZCT+m zOHL8<<3O5zdHK>O8_>K?Qk!+*!60uB*_^~G=A=8gHi{%jgIBbuK%zS&m+XgVu`^!Tf3?@Iub?{+=J5&I?`af`2QT-(Oh_9a=UG_7kK zvzxHDSlT(dman~mf_~+2%_IB6=lc_i63f{QT#1)J^2TPcaxg?i*w0jV0TncCR9xwQ zROeIrU(0#2LM(O-cn#IqO~5nGs~;n3yfC@?_)v(($wmNVKWWJIF?03K`xGZaXNmon zbsF=9MF#gYx!X{muF^mJT@Vzp)L$6y(Y5zB$NwV5?)&>o($^TXbk%1(?0f4V4ri7) zFd*OCKYV|Cw)M$Kknw&;^lP()=iGo)u{*KK=67?;51jjHQ<9qgd^l{e?@@v*6Pz?i zv7XjzjU@%Np!OO?nylx6OSVu?Xnu--OOCP;3O4w{ahdt3t9)f?S_ma{YXL~;&<22% zZvsJ{^gG3mmf@(wywo3>X%bKUtYlq^^bt00$;upKwOX%}!WSMQlHB&Y-C8{ey$VUm zZT<8mpCU^I4;0$p;rr2$P?48W#-K@-9!Nidi`6dKj5A6Sl*(@Xug$q}M8gF+Suhl% z82dgjAi~=lb2^gCm+$iMk<|Ob+&mDfLas1yEVNfmSD?P8X$iH0^Hc#qBoItt+gf5{ z^yJ8u=?>!;s6et^G?%gnk+WY;2HO#1?bZO}v3u#w^}Lj6wqe4O({Eik$I;8&RB>6& z&U7vi`$9zVIHF&QM{(()5@3-ZZ=8fANM<h~LDM%$iq7=J*AJ zm~#yOv-mG}_CdxIpMnqZ+7w%vXXf|5>^%{u(E3d8|FZy2n2lLC``tClnEkEdxrSwV z{G0iTq!AepB0FR_;8c$C1m;aqnhB6g@M%ZvI#rIEsaBJ|$jCUg_wUX0Iwe!}siWY4C8NSJ6kK(Fgba8};6sHPqg*8(X)ujM$pZ z*%Aqh;T1@bcK)#iaB6xmRZm@+;aL@%b#ojzYjWVfU*_gm=}9nTPC2*0Ju^*>&gxmD z{EtfT;}9jjxwMKqbBg;{IGk~u$SX9_$DCI#wh6T5(z)S12th3|-wK8rc^Dc`(AnLt z%tfT*CFJNFP-PhnU+WBmXLjewl-Cv6VIoRMPQ)|#Sf`bljYG0q}Lqi6qK7J8tzX&y!B3GI<}Bl^kT;Nz4a_{!Incw|JI->Ed|pP88v zio80IJ1&Hu$-2^iS6Nun$b8UpRHY}Bb?WtZ!JNtovLjf>v>_ZXH5>{bax;n*Z3tzR zRKJ$>7!F_rQ){gb>URZQ5Nii37`cK+r{w9TeMb_U{}f4IJYNx3qN2Q>pO z+K=E;=^vr2WoF0c;9m7KbCdjQxfOoGsL#kr^4YY)2BcZ68^zt)lcMaNk;m4U$3$Jy zbLV?n&GPQLm!H)~t0-Uoc#aCj!x>)H!>3LO=laH?GmK*;Vyg@P7b*JmpR`ECQd-0! zKl05R8Tp=Gy9*KMmsjXjQ{WcdRZ#Tgg*ooUTcaUd6i{}VNq`{xr^n-*dr$U$l|J<6 zZIf0#D$Sf(2k*sJ9!83-Tcu=7(NH~qsU4Q^C@{w?7Cr6aL8Jod0|(fQ<=#gNcC-9s zbJt(FkElKS6Blf2NqR1K#jSs;qoae$XqwLLtMfQn%$H;A5$+$n)2+&rqXsyYA**-F zROjpFD81UD!0HM_=5Q(h(e2;T+DD+UwaGNqX9*c~AwGNI@NJnZ-a^8P*l)^fJ$vlt zoq+3A#-GGGp_Y*vXk11ld~uSM20n?``H6`VPv^(>94L(4>6d%M!Ou_RNcY-#b=@he z9`iUmamhU%z8|qx$0c)>hS2ln!$)%G4gPh^J0R+;A8_v;kiZNSW}oBW^Z~7>%0b=J zoAtShSOZx&1pBD&0R-h8O(Or>&o2aHWj#g!aVDI6h}H6y7p%h}E{sEli|r5^mokWS zEGDgcDG7p~UnaJoU}PqMxLCqgXOf%xJihc|%!o9(33H)z%p?+@HoPtk)m(t66z8)b4C znh?k9w_fx*&*`c@n<10qqCz!D0s{B6Uy$%zKQZas?RfOP9*Y6_rv%dIVjmiSMeb?6 zY%fD5w8LKk`*NLUTA?HpgG-X=BCmJ;co-mFfAr#Cph^MaD?B)49?^U5=T#8}9V1>Z zw6q?wq3^A{++EI*zM{3a4Pcj}tme(tW=zPobM37Q4^~z{$1*C;Sve!m=rxHG9tvs7 z7S^qaUd7^h-HYLl%NtQ~@8r0K#iih2dhFwW6CX=UE<;QJZzdNPSKW2Sh~b!)V1g9! z_{qDYD-1m1gHRaH#MddsYU3bRW)f z!#1bd{VhSp&tkpPM)T&E+VN_yu@~Je=G5C+=b^5y!me&t&*Ggnz}dO+MLM}7OLLu; zJbYJ6o!R3i@^kOiY=%P9wh&$j`@{3jz)2qHI4@PtqhDn;q)`c^e)NQD z$7>xPy~;vN+>Jy8v-T$-^L6*QQ3RB={LmxLAG@IvZb;v}WOqJ8{X~!4XGf0~`@iiBjS0CHOF&~o|^hti1o7xZhBerqPl9GTquXdmr|&U+~sNR-5g z_K1EO3}ydx*2pFLho5XmOVxN~Tyy{gEUT_2ZH&eeYGJV2To~b_ z`t?RVxkuODJJ!($Ds5eM+w4Ln`>ABH+r{$+ zyW2YZE%LR5sZ_Fh4kq^acJp@Y-VNue<{fsa_o&9F&%&pAbbZK5xcyNT?t-XKVB)c} zC8F~e1^bVDdV~XxP-iJ9lscCZ%Wxh8XJ{~SKF)NP;kzm+<>1zc{NH|Yiz?6B(NBpG z7?^G~&4=#i#9%aRW@dZ;P{4v}HGHo_`lYBI;FDAGd-qoIy;Hl+OWs;r`uo=>IQ&BA zvQgrr@nfhr>4&IWO_{x}X=#~G7=AH#m(mbRzQ^X};Gv3o@fA3JUT(ze;v78X9D; zj)cBSS*4xHK@lDa`#jf-9H%Isx@Rz${`!{!%#8r_hf(t`R}_^8gWTW-C>@*ttHJXo z6p1ji9U@bx7S6;)hAyHAZJIeSaNZ4LWKQrQN!Siaxocz??``Lo9_8WZda{+qx^7Yk zNeqSBKJ+l}J^CVv7e%N#p!2qvO1gyC7;p>jQ}#p)A5r3q5sefzxdsY0O4g-;Mj0OX z#$^T=*n`97be17M4V^!73N4)U&=H$K=ILGH{o29gI^`QDEm zkj#74hfoND7_V=SVNTyK1_J~!RM`Lf^bh#dW-aaiyG`lwx#{-+^K#92W?pgOL4uB~ zfLajPU_Q;NBs_meHh~X&27(l)ZGQ3A*j~ck@oTPGSH6+2f)a}QWO84S)|em1?qb3i zIm`9{kEs`<)~2M~jOygrSURl%J$F^lB`Z!B`7`p}W6@q21#HPrNa#k|z|tKf?wiG` z^Ns6Nuba;d_9uK|?1H8u zA70$3hV`z=WB4KxkWbR${X;`3n9F-x%{!U|QKpd2zqRd|nWd$fZSY~^)u#+wfUMA` zFfDKTpv@MbLrNJf+3&LVwq~ox1U+Cm%&FfU;0dn!%r$P~P9rB`KTq)@SsME(9g)Ll zAOnLUdzV*MGlz1fE}gDD(?y|F6U~b)NP4=dFwjgM1phH|8S*%+Y#n^?aPLX?93CGw zX{z&r7HkUh+%xJ9fWh3}3agYUq0wBUgV+xjaDh3_XIYKNTsUn&FwZ&FX0Z^%TM*An zo}ZuflNW{Mdz-HF9945mL}(F8=1mq5sLppWVEq1w``|}ER8{?1DY)2gvZo7|4gebc z+Yb%{{!wwtCLEDuN?k!alN)w5AnR^@-RXX{Q+AIOUn8UBF1rlrn-Sot<~@M+6-HCL zj*~3=Fu0#*ZGCM&e{d>KVlwr;6tWc|;Bvq8Pro|Mr~0fL<#FJ}fIE#NJ?nqqc&tn= zpJSBb;D}hvHwmzYpFi({0RzL3&6Q!-YjXjU-XM`Su_U zUh(bMVAMEPZyuBP;)l=u14|lR-y9>3K%bYkx1Ge_76*Wl2SgR4>2(HQ4T(-L4u}C{Du*FF*m=`V zzo#X?4?K#;!q=#Hg6wN8(4a;n3CLHV2#)u+p1nH0{js61adU#Au#CA(k<8c8# zhJrn)3H`Gj7Lt*C1c@cZPGc=1K&2W?L3L?UeFx&BowYZ;jrcSriG;=t`% zZK;Phwy+=y9v@eRuJWX7R(l1MhcEx>zE^w9SNT4sn(kS9MxPJNGYeHUf*{d@V@A|{ zZQnKbPSFnFVH^wcY9eHXuBDLLFfava-dzg>RbyTQ4pH8AqF-nFUW-RRzec#B?t2l(})0QN&h5*c)b`>1>nL|(R<(%#+WVY3IG ztk3U(1O4vGz;)jwMH*-pspJ*mAnLDQjE&*_heb_}K_46ItKZy^F#3Jbr)La+Fu{h~ zn|w$gU0YLAz?SNY)eM{i>!GE!EKMk~%?Y#(uDN9)faVDzh^pWc406D1EJ7p8%5wI? z-#XK&-SGv7`cZ4Q!1~cw*|LE*W47z(8CeRh5^L62W5|{VEjlbH~vMm$1qY+iM znnjWa)Z`!tri}RxL9K-!A-ccTN+TA2)5Ce_9`4B}4EEjJNJ(0{(rK8BkfYq2+Z4NX zP%Nj@?Sn)>QyOHmQ}bS!gQdJ$msqD_0{;DXRUQ#LTZLq0kR?!RaqHi>jnRh-<_hGv zCovjBwe9eE97%K!_g3sBw+d7cBppdg}aWB^8 zO(wcsZ>CDRC`U$$zGEjTO@rN=UZR?s+HK8^9?ki+@RziwW+S)vq3ZmX0h=FOY*gi? z8Z8J{Asuoa2|@UJr}lJpebwwpiNKv^OG{l?3I(*E%f8Vx4F$k*CpAJVC595wEvWEZJ;I%bNS2!6lz(sHE^KvYA9_(8Za%6Yd$`bapf zYltdvh(izFZYGFP9MOSiQ5^n$(}i<>u-XS#M7d{MvmVEwTB!S?E=jx@7czK$tVKO8 z>F@8~G&*H@;2~5w&Dk0!Ynt@wiRhMAEK?@lX8644K5Qi9 zL}bd`8w{|0`Bs40z&@|{RkK}O3Z$__VU6pz;MjLFl2IQ+y|Z$OpM0H*;+dbHydu@@ zQFkV%J8jN={mN@VLVJuZeAb0q;~_orIVl;Mvr3i^EHtd+O>=6XggUrJSg*YXVD7b?n=za~M?!fr+- z#W&@LMvz2BT8x9TPt%he&b$?%(pJcB27QKK_caD+$|k4sI|_#s*mWAsYML59o9i&D zILDaW85kbi>5M6QYf47_dGDEOeIqI+^>(wwHG)r0F=^UOd&@dQ!qO6;n`L4H=-+Of z(Q_uog8<3mU9Hm0KQl8wZN~1O(g73f2lHEF%}q^Jw9~nu2!7h$vN3pfB3J^Z_uSk- z_H5zlXE_{3GmjFI-_DMdpB8W-eY0Do{g5#wE|btWqiaJwp?sonsyf%B>)~;{Gb4X| zB3?QaStKZGgl-M0#VKm3VQT6cf;J{BCG`5g0|ooT2|*}mXByypz$$BWHXym<_h9i& z{lvZ9^_OWb!4HBrw%ZOd!^S*{Ju{rGz?**`F$OG0DWhKD9{^&lsJdsXK}Hcp8@8+J z5uoZzOx(F{LOTwB)i)SA^xZ_L9d{B1TI!q&ncW%$QCRO%m{Jx5M;Jf^iKpT4y=L1Y z_dCQ(*^}f&wb;_q>t9>j!cG){)M89wIRRlb?19fEi9I9xGy8so+7GSvE&hs6KFRKO zEvts3g5V(oJZP4A-M8v_J*h@HWBp*)r{a|etE$4^g#HSAw~(ub7>;4#Cxo47Xe25AkrH|#4njh@^p~WYI%KKbrf#;;t z{5TM^0PPKs(6{>Y2N^GhMf`f$T-VgHKGqm~ZyDHJC3uY_;8LVV*oS&L;yv}@n*sg-|!NZ=O_%C5v+7~XE z^ecBA!jF1gf7X6ZcFV3~!|B1jd;3u3^t)Z=W{z7Ygpl{(@gMG0STFdGaJN868~V0!Q5&ft*IaO~~Mxw_PIo%?yH0(gO3 zn@qXxB#HVun@xyJ$(&vL{rlgnZ9W#c&bh&KyUilmr*;D%jN zGPJd27_qDx!6NUJ?oDd%wOxq_d$79(j65~Z-P}LH7KFim@#NJ8!g$lX>ST}Za~Es6 za%*YLtj+iZx9=M4i_Z-N+$a*KYAWcfKqh-L5dQjgdudW7wr%LnHW7s9@q&bTKJ zt2TIyxbz`G;1TW?PDy6H6bKDgbtxFT3TLpe?UOu$%k9=?Kx)I zlWyL)JIhon_rt7+~}?#{d$#2TOleR+sayH24<|ETuJXPwwtIVNPe{8Glpj{`RQ# z(Mf65Y^~tU-yP?AlB!Y=ZzN0s<`hjOys_(8y+i+g78?|k89Lv{V|i^00u=}K>>i@O zag2nC7y0M&tgy`$>tpTKsg~f6i%@(0?1=Tv!PNlD5pa<3rU!U?Cv0!=AW+J3)%7KK zqA#_P2l1xi^FFBHIw?uHLkx^uN#$nQCQ|y9bagyMq7{Bww$dszPM_}opVW)k&Wl$g zG!6@KL~^^5j)6wyScq?yH`yN*E#@+jCYZ#IEf;wvYZ9F&4z@7N2?@vf= zQ76!hdDhY^J(FEKrs&m!)-j3S4mzbvJgsz957+qlUu2Rs~rb@+)#ClJdIg4-gmFoB3y)=fO`-a`e zU@9sH8)pPq2rT=si;&olN>8CSUMA9!)i4ucAb`Cj`xsH@2Y%yD-jrJ>Jt%U(K)&^d z?!EVKKtwe&$*-(BaA9qBc#7U%SF*S8M0@wwm54hdbIS_N5(Mvn$&#Yx@D-TYPmkQ9 zJ0n(~cy+D{w5eaA@a>I`?S}c7fA_C!R^12cfu*G->+5SHd7<0Cjp!XrW=@G`^vjra zVU&5QWobnpE%Z5S1HA7(`TlN9&?lgL2H_ycaE{6)B5Hty6d{{(OexzH)P7i@ncd*T zw)e=dD%tZtB2>AYbn;Z>@gp3@`IP1zdh^Nn@`&95?b-RWYN#Bu2f@K}omo6?!`bHQfmjUVCV0J{CN1^lNP{JNaiyqENLUy}j-5A!kV+o@84dAHzZE+D zkfFg0ZlTo_cqzU{h~E8q$owKeNtW%E@xeahefmesjg~garmNN0FM2!pC!QpdwKYq$+=1*-5M@;XuLT zN-u}_TQ?R^dPv7;gyi!ZA?op zkl$*mW@I|v*ask~USwkb(7?9A1BSha;3d9@GNB_*t(gWui<+P&fH|53HJ9$4RgL$7` z^0)P|IyuVrQtk|uMMaBEFsIZ`CWPej8dzRyH#>%jgbwGt4m^qlp%zjW>7EYxh6nH; zXu@9op$xlHyj+;%(!yy?JtYG19D7D5{LE4m8Wi?si<*P)CAkT}eS#~2>br2D(>e~_ zQLaq*S}_|?PuKjxAJy*uyEs8?akkYv=Y|>!48HHH=p&CCz^T-&ayeay@Vv@Bqe?cG zvqh0;U7kXEF7u2Ro7tV=AePH_%h?FH!)PHO?=fQIK>}!${wd|yHz%K{mMeFC)BChY zr9K>V)yh1wVc=nGIRwLFFCA+q`6lf5sO8vBY zZz@Y+spV#&g#xS{PFTp=PDe+h7g4u8L17CqTlCE)MsIEBzQz#_KKHdb&3U3*vJ>g- ziBPg3Sbxj08`~a?6^?EHxqkXW`u}GE#u@?@>@f8Wm_6!xGmA`x3FgF!HP_U9B;;93 zxik-_`j5)uYebQo*A-rtS`C2(j!4rsb71ly_Vk-uq2nCNg95oc&z@EJ8>x#E%{vRq z%W00peNg%__RsNySOjj^kjz8YnYXQ_2hWrGaPA_UQWhS%aD4zaLW<*Lb5}Y#;$?sd z*5IVBz+;3Ck?aTmRl=^QL^2UNLhUrLCLrAtZ9JNOm?x6Q@pkxez`xbKDbst8h=_Xb zJ6D7r;nP0~Eoe17SpG9T9ioyM#40R*L(&S~hQV|M>I3Jq2JZORMEt0T|7O$qpnepw zG-~VEI4nwhKkmzyrBG_TfYnos{1xA!UP`)%Jjvqfm2G<~f5uo*OhV@saZM49LKuL_ z1*Gmq`1)&!pm=}-38*NCk9&q-eNtJ20)TU#4X9gB;O@l&uY0y+o~D?i{>eN8+gUvH zYB2Wd=`CTM@rOLrYb__1^*`m@11^+rj}!&2Oh^ou0BxF#6E=oAJAp~>&Tlm9A68Q+ z9~kJY2fgmKH6D#z4lEoCCgs`agD445bXLd1UXOn%-KA^W+Lj7yhj;eh2;~86Cv;Ea zGU62n|M^$44SonttgnLRz-3s2e?a7_yC*`28Fp)Ebz`!vIziaZ-gaznp*7EwZY4%U zwb-0wU9>%KDa}h0j;dmhlu)VXVZPOPvfGFpMH75}xO|!&~$CbkvZw zvTkAZqw$8~Y;u{a1(8hYniPZu`S_@1nk1{milb`O!uo{ybqjLXo)7%0-3T+q~xD80^Ro@^hwK6DG7 zYmw?=LSGBlwx8)<=Le7|74~SrnG_+{{-*hU<*YAKNM<#QMISv88Oh5hCcpG1ISUO! z^tQESgBF%g5e~+XNJU@xn0U+qE)0FJD?adS*R^&kC8L+W ze)Q-?FdB`}Lx8zi3)1i2y%x0`lAW!+21_)ur!J0ih~Q&8zzCI<#9lpYd=u|1J(k_1 z55MhJJvm3~&ICEddU}af;i~JY279?b!P)voN?|ujF$C>Fr|4&+x@Ik&-laYtBCSqvdDElJbTZ zR7a{#u_pfhg^S&oQ?bstXBy=PYG!he5oEt%46~^utb=GzR1v)R-GA1nKGl<7-%0e5 zx`zPXq~C#9p~CDy9{((}in`6NPyr;$s&Fz;RuN+t?^V_XFT18niN%V-dg^72$m@f{ zwzXT+SL_8m_F;9!PH?`fTEk4N$)}A zRe^ZXw*(OX%w?!!!H?*9Qa0D`#Nka`OT{%VK;-?lvdrc<7W-eq zCGorp1VO)v!Sfho)H4`iy!i42$y^9}H@&(0h$|Q!O|bB1lN0pr7M02C5aRuz!z{!& zc`{1X|K{~oK$?o!YmJ+{R|PP@nE*B7OC^~Tt`gB=x1Y=E{&l5vJmTUZqOG%qMNWM; zammUy24$SZpb*~&N5ItkupAE*WuDY#iM+k#(t?(&J zmlsmLmZ^2uxwy6-Jz0-a&}z0TMdQuicL!V_IuAu2%W&JMpKmmTJCgtCGuDU z$;Oe0g|{L~Q_R82@(Hg9eug|mJ3ZW+*I!Ts&;$+;b|J=$TI*Mm{7q0g<%Adqq#tEy z_Onvy3fM}abUr@bOUPHz~1NHF*@>NA@2zM1HWBR zpMm#bKd$9KI(#{d-?CvlosZ_Q*)DMLp5U={PkPgTC+-!w-sQRiS*B6a z4OY4Gi(VG;mt!utvNWvMk5UDf7Y#*D79W?rUR^lr#g7*y{I*t6`~qRk4-y@-S(GVd zSOT}T9KZk2e`m>!yBd;2)4b!TPrEfYy;XFt94ClIe-xk+95{7}UH!@BU!E+%UP$oj zK%66AB|DG0@y3`HXJjh^5y3On z!W4Pj<;B)tb$||A4bc@)=<)?toy#EJ_QB&MYS>{*45sPUuN=o~05v8UiG>d2yPLw* ztt{ccmX^#x_|c_U{erqLqtimEXK(7|?gj`H7{IULGONsNcw-ghMTng(nrSR`gRjs8ZUKK`Gs#Sw!i#YT1^#?gil6YZc6WcviZG# zx&O7Y0G5vfLPH2~&LE!=ok;XShCblycR0Ki5X3LOO3s&!0y}|G&$u_Fjt}SOqC@8E z?u_K2fv0bRJXAMCgCXkdHV|kkJO|OZ9H97l6N#cRLOt%r^aUp%z8UZgZBQlE)Jowk zwnHw~Ro100Vo3ZW>oYC4$&vsANUx#{iV?j_y!$a@vjN(B)BL=VJVUDHAI2}>zi?^4 zFiuj|M~)TGOZRt#)z&mN>k_USZrD6^_Jq1fr#W z7Bs$i1&>YQWO3+R<>*(H&rmuL*wiSMF|L`S2Txf3j zt9m*xQBE9^cy%?y%oMJR&}558k`8;H=M?38`h74OnZq-f@wX9CJ~cugm>vRew>bNq z5RFV*Ex=lMUl4mvSa(JKlDrdfpHr*G%~OTLch?sBnC%HK^d9kFc;gC$BLO z7@js+`&?J}Q9}N4aH#iH7F6dimpf;0(t})$^?^_9jNU0zdtoePomy#9Pxp-2u7BB% zq*rzIH(b9E2?6(NDci>Vv0@Q@^TsK(!OQU7;n8U+gJ!yC)_M1gxj;?huLF~l_tbe% z4MB?&Ec+ddm`u_q4H3}_T7a#>cRuFP+Uu^>6O6KK`$>o ztRPm4F#XTlr6>(txNAmZ4nfIdXLG3M0c(~8|=jcyzM(gymoHCdD zpIpB_B%*Z#Uss|n#Dj`%U3^#RPWRG!$@6TudY<8gHAv=WVJ;_wz+h0tV6iG&wRB8_ zW!DfCjIluI;4KD(i_de^EZ!%vWMA_|>d30kBrFee;(z*wuOuQQz`rj_Om&l1G6C)P zNwMC3yg$Y^`{%8Q+iX{Ldtw|&y8tozd~*bF6Afk7^DEdNP01&fU;Lk@P=a;p`=%%G zJ9u;pFnKtRtr8F(-M@Sg=6_tMGL1J!j}%mKUA)A5F}>H#hTY_?dss^YE>6&Kx2&#Q z9aOI#n~xP!9r5WT-6<@XuJfwBC7-(7tF^W5qqb(l+;9p5TWHqQ;)nT>Kf}@@{^93; z3-N5}X1LbRI+g+abi6<9hDgh<4@RgEJ|3i0k|9n&8^Q1(lCXKx;1C%3Nvin`N-6mQ zm1?ERlU4v90eJqm-z>(i`%mh=BJ=ErWp)Sn_y^jqZ*MH`JlOlyx&^Llfua0PGUakc zxqhZ_4pGd7`meO6=BC-u&`>`vR6`92+U%^_?{yE^YkSkRMB>q?@KU0sb%r?(Sm_7_ zB}B9^Y@iT@=q5zMkD_%5j$nkUasL&_Q?1|yi)HctmPX(ne*miR)K%M$sL%~=;Nj^J zxo;cjzxu(Wo~k_<;Ca|g>YmP%Bd7n4TY+?=NCi4Pzg*e9{(%|_o@>$%LC72u0{+lX z{vX^)=;~dtF27)KDevj>Q5^zerXGAV`8Q4v1YyEASHxvqQYWDnQ0)X{&5j^YFnd$k z)Kr_Ov@zEfNZ*-To0IQ~Ymlilr-l-JQeACU2XDij;J&xd??;P4iY;U`L|r&4N;vHF z6tMjToyMack4O2TU?{!P5M#L14Jq@yr$?w7?Xup}2Ou48%Aipq1P8jKg9h)>AwkTe z-!C3U;fY`;2P`PuxkyJGG8Zgy2G)_kRyT#Oi9JS`-?vSZ?6|Acg0vhcL#A}KZRg}) zkwpjf}VVy9+U_P#+-#0W!dG$MWurL_{lMW1{a=OY{~W8VsEmi-B~$pY&V( z``W>nZMS+M=ZD5VgcIo@eEa#so(VDyt%>FCDmKAzaS?PH%U7NL)fW4=OmILqw0NQJ6nhJ8-^jUerkHX!ZEmfQM z<#H+C0RIWJT$Z)R?p6n9Ute8(0O-rbinJlsA)G*r(NG}oM?}l&>MG*kQS?zww1M^5 zI_cX*=QgBZaeYZL)`2jR=XUF`V-Aw(RGV(vj#~xv+sj^!i#>PnBTa0J>#Fg5m@Xx# z1pu@siY~&BEcZS6xc|aTAU{9Ivf61;VLh_Y8HmfXmhnU}tp3$#pMbG&R*JG_%gk zyvBw)F@k7Rab?{Q%yD!bST8RBc5F^Sp9p@P@+S(A65-cwSz4yL^iLIep2Q#4dnFSm zv4b+b=4?%`G>=ujEY0k=uL2&!z$WGLLg9~JOeCL}QF4O}3CKYZQ6z8^Q!lOL;Jqgg zmxQ$-S{8kTt{5P6b3>SNEiyrPiD?t`%{S%UNaG->J2uY|iKBzBKPzy*9a1@K@JW-0bp)Jkc!gBTBRDa2J zo12l(mmivctMFggotT*L`B`1COf>|q4LFw7s4^1F!=Z!VfFDDpOt&-5h`a_46~ZU_ z8CxPTJ2dm2=r4(A+?1)uc_`1OzuToRdY9tB72 zyyn0ozY@)RZuD0*PRCc0%sVDO2vgze^I#msi9b8}b4wJ)uIo_;V+|NTz55yZqCkD4 ztxK?q;1xz=M0HbheaOFsm%CH>?R9qYX*}}sUS3wvM+p<@uY z4LktkZr@w*J*w36O?jCrQrM}{g*O5}Bz9l_HeB*lQvQfVd2%eYq%vF!L9d`Ol zOnG|M^H3D4^@-7flX`PqUD*1c?$PNJku_=;ENPgqO#=5(R4hsl0nT;QF`U9@P0g$H zv@U(K6MNef1yO>r1SAT7MR|7c09r#h!8-eWNj&g-$Dg;ncCEz;u4JSr$-#-w@)I`r zR2zc|nx|kY83%hh#q7W2x3~V<*;)tEqFkjs<&T!d?Q)QrQK5-EsJ0N7?9w%Ub&41O`hLD5p{q4({w+qX+@Xpc{=0O<9J~qFQdtc)PieOb}IkZk2sdJCExruuFrM#e| zt51y+fhQnD34j6dKJPsR$abU5R6b;d>qQ&zcvj#^0(Rk2XbfqwZE` zV!8}n1h8L6)Yw^Nx4_PSHsm$ zQ{=??w#JDRZI~E02k(7bE{JR_)f2)#MT2vK(HmSJfr@&9KffZR&X#$-HCv)#Wu1{{ zjpGgn39M>`rqJybZn59p^{TL6m@5y&6P_u zFU&?u5uO_Lo!$#n=DFcIkV&8_V9V%huPf!wo#X+(R28z;g*~IU_a#_v90& zf-te@w?;Vbb0adj^1`5h>pKC}r{WC?2M%Jd4#ig&FGvf#Wz)YENr>*bNR5-;@Zv=#@~*+Qc2&{UrH(ci$oMXYj0gt z8^3e3erI!6D@f#`1nKc#UW1<6zx#k(BUo+5VoV<)%1PsbLou)9xD@7EKPr+x--fv9yKxJJuYcVE>mvvDxBJ)_x~|sfZF+Cs$M&XqUIUs9 z-jf)4`Jzm`Xq9c+TUkBDD7en|K?x^6@zx4jy3~aVG&i6ObKulgl_O{_*N&9o%nbO zMq(6YD!?JYX(Cz;`9uzEQJ`BIzvH<2fk@G4UC~2FIc}>JRdP#GLkWH0UNg3>y*KZy zQfYIOUk3(p%F9G8d>GS3EMw;Dv^dqWjUB;t(KE&BAm!m7Ls8g1x@wSjF(*o9R2R4r zq9}j}cvCK*K3qLZGWbB0E?k_5pc$~oXWK_Dq-`! zMRAH?Vt5@%630-a+$r`@DOdby6N-0p_~P2^R^F_1^5n0p^Xv7CLH8d7xW*6P9b$Ie zz%6bLcrY;p#jbPwx9BR&#UD2l(7rwI?Zh$Z4;-vh-BZaI)W9u1-^~rhIUhdcj{+xD zF&DTa9Ctc*38N4PnCsjZ5mn)>>if}<$o{k*LmV7+Lt^3&2uIxdubgKV-i&z>I?I`?p<|No6It$HhE4rL+`#=@8!?9a?Rd*y`Inez908G z0~rt!GCyCH^sQ`dd%2|5Z)ffkXeG+tjNADq&aSJ`5j)h5B*`xNnP=3TaZo7z>@~zs z;M2E#WC%g1(S4urROtn^@@!b`;9BOVNk}r9r zc#;tG(YHAtn7G{12YjaPsswp=$saMQ8kxqw7I6Z!3r)i_Wj;QT+n83=HlU;CTk*6U z-RII!SEq4C6WGm`uLmB0y+{gt#H!zlOdo;iDq`Ump&#Lhdy_G3z*fKrp}+Wi-zf(6 zyKdGy(4BG+W!Y}1A{Oy3{?S?PUFQu_q&tTH3~&2>J$8tGtHooi#({aryRvMCw#eQH z+x$H}*>TQnQPN?o)QLh*FDW^|^{GDC2c5sO?zl6Q`-yB3D-n+wEuGDyx)&CjIIKE6 zmNk-;$+v;ZfLp6fq3d?#U1df>j7kAzSp1Nc18+!OjR&wPuKu{xym|Qj8x67GdTrn_ z@J?e1!^Ugtv4F!JwLR4f%m@CU#$bj@R39oqw6wM-T`H;HnNZp`V@>q*Z1u!#4F5Io zTpa(oIXipEJY{N4eJt|CXF=3{zF8|?nCRiQXD{to)5S5cy_`o0Ys14v{euWYHm&NB zz_>HhdIHcsspeAPYI?F1>r!x%l0#Kd5JY zn-Ri^;6Xu(I{^o(1Jn$aje|Uoy@!)jV12Q|CQu9H62ljRlo~jJ2fdi@;sJRL4@v2w zVx4!x_`c9B1HCAFVAQFP$SUSc=)m=S7>stnbHwFspI!M7`_nD0m)hlLzF#$3nEcc_ ze3L&*4q0oG=^io{iE(^wqOXiX>cQ?(&)R+o+>N@vk?qudSN^^vJszXd!n?qH<#-T9 z?0i{E35dr`g};eB3Yb?C1_P_W5R6QJW-?@4m|8aTvRZLBTe=^ zR^jH8z{;mMr3>A8OD1Y;l9*q>Z1-P1LX|?mpt_g3LSpsl^kjrSvzUX`;5r}o3Rwx&BKNAgVG}uz!?FB-Lo}C##w>1gocmI zvhwMIZPerY#WnLSsst3dWgq&kU#MDEwTY%e2XEY+05!OJHkCe|u( zIc>L$XyF|a_xASA1{#yUnt0L$!rBj;-7qs#(?zYQn}N%-Gn)55)vNnBHb-m#LG@4r z7@H!q-M|4qlLk6<{YxilE?@huw^Ayw91G`(cC>K zEth-$W0-ki1sui>{a(*GnXk}=l+3-MCgxcR2;yOZ{{CF3KI;<$+%2i6P=aCNSW=;! zoWt12*vQEv2>@4$bH}>pnuGR;eoJ&#tWA#U|GWSoZ&0jZ9oO0fpqBO{ukoEpPjyO5 zNWdawoBcEk?D&A~6hV+6+dlGV013}howXa#R4!5{kSP2cPvE|&Cep7%x)A`rh#)r- zF&~(jms{F~7jCMF?S@Ghg3V>m)>ZvI!6;dy7)<2+&pmJ$T>fr)FU#7~@XyrL+QurU z{EYo&A#nBarPne8$5wZb7ZjC1dTTj{L}TGd zf*+9jG-IG^XFq+)&0y9{#mE|6rBu^#C41Zf8DZ4AEI1zi3{-RMNj#nJ5>KKaBsX@)%N+Ff6si9c@Eqt$Gc0NTbL+ zID4Q+TYH?>sGx;OokIO?&f`bNx4GYJvPbr}KSe>`eI0YWr+m=u!!@!}W9RR=8SQ z{E~wl(rAGTMwRw(7y=7{olTHMU;9~Yy}jOg5_(fqzgVRj-{%v#NK>iN!o6*Fl=IjN z)PLT?;SkS^n6pNfPT0zg=CMK#J8HhMYyTIM%LlR{M%=7CMOntczbw%xWzyzYBX8X$ zJb`sg_Uj&A2^h?dWm&EV3(2?xH3X#d;UPD;fHeOh?wg~$rPCBuND76e|3|3aK=jf;Q;FXa|GUojTH)XurO>41{4h0))vQ0 z2f^9T&$b`1oS6So-xoBJsqQ1Lb;~!@U*q_>R)l>wDdP}kHAHSt8b+7c_= zQ42gNe()Po5{}S=qi#&oahHzdCs%5S)z^TkaYcz3#anPbcOH^4H~QQZA}Y69X~m%RfVt;kTBflq zUb%GrH%;({%28)H1+c+5j?Kpn&zcJ&xX4cAf9&$+x8eVkd#YeCJQ9Y~rzqp0iHm=s zU52m^FRXSp*(_x0z*Zx#x$i^iqUpdZS527F5N#FGrCfw=U%bz4714`qBa0UA7HVK? zh&Nbk#6o;r%EXw4RmAgghq>DlwDS)OjE)PyTe==AMJ;b$k~Ct;$=$g(u@9)dpVo$5 zHIDD6gD%vnVI;}5R17+R*oDH9`v6w_HX`xd)Z;Td3p4e#Q7h%!2T0%Rd51#Gn?g2b zrx!lks*632n%ftpoN2| z4u!GWr@rC}sT$Vp#l?}=RLJl43<0zdn$dPsBW!1O>xIJ39PduDirtaBRR4fxkLkT6 z|K&Mzb81QbK!uL7;U0I}M_0zaXDdARy1dioxH(2k_;gK0%tQiT+|T${sct;xpLs?S1$=^CWz}Md?d`1?^2Nyz z$QcA&JL7(p4ougSm3(@!G^)~hzu~u4658mqAnfaEr%eK%9yDS0Utok6Db$L-j=yB5HZIpV>-1^9HQK zp~kSq2j>1?IpEZJ?ZbY$^|x@K!cOs#ddcC~zUvdTLMmW`$Pd(dsXpyZ#LyNIF*UMA z{Vf)c-GosF=&6`qa1|%O-i=HL&84&z%gwN`%L9i=o3~zYhBV$jLw6x>9ne%I{$?YmrVQ%JqdFkw+!J>awrbl`ZzKE^B|cC;BP0t?(Gkyga!!NG9S)`&7{Q}=-h3z!cbpqFx~9-Y z3mC+ay{$=#An9}U$u_v8Jn+i5BMxmuJaW5}aE!#W%Xcu(=;uq3{Iw4Mkgwv_>b0$0 zITqS67nk=-ow85<&pmp|D@({0#9wio-7u#YFT~5R4&@LKKsnl6=R4tCi11{hKcU)M z;ua;k>XEat@-MgLPt{Mr2RYcp@9$y zF7fZLKyT1KA3ieWv$<{fdPmhN=S=waFw1JhW(I6i4zLsiw8#h&92iAjV*o>uukGt^ zF+KzNKn8{p8>`BGx%h}*WxN7}!(2QM3O)DAK)O)GxOAaMZrh8Fn+uVRxXam3X*8*L znjhwn+`}onply@w*y+I2S*GJYs$H!jL+4nHtq60&Mahlnl5(|7P`{%**buRkGnAnm z8W7Nm+XoBZ*(%xCsIM#9DC@2KIn=x!3Y=c_2?Y~GEGX+}Bo1mYZoxloKq#>!If^;S zm|45A)#UN5zW%UK3}|7V-iT}*CL@s(c1(m``Il>_hG&8iEvcyj(eGSUwkL<>`sXL> zIag+Q+p8A)Pw^pPg1M^JtLq)9Nmm*-w}YzxYhM}XhCkC7q+#IBb3fMCf3*cGh0lHa ziX=HyBP3ybAHKd-&N5}!=tJrz0hRXF^>^OA92K)Kj~y1m7*JsFuF8KWb6fH}_JVe^ z*nmU$-y33F%9-6Lu9o^7KW3O2LM#cq@mgo&VN|0OH?(wLh*0i6Wf)u{mVsl53Uq5s zL_mX0+uO^4H?8*J6>|nzh=~QN@Ji5G?f`~((!j`dKuwE(==Z3j+a~iWI`*P3=4nr9 zg_V`CCsHl zECh_ju4soZ&HY##wjBy=FRmO7K<^ziE?-B)fIf8Pw_j0zj<}%JyN>`~d_cc8lv=uc;|q8; zD0HX=8B-zqA^9U&rOBb3S#VoD5bbboX|XXXK@&8cO&8lD)?#E?ORDvtaCnN z4c(t#bL;?zPd-hht8y2eAbcC<6cZN*903O&Kox^45k8a_Dhw*EA}hzwR}>Gj!zlA3 zBO_~T0IOF#L?v?cK@lsHpRlO4I(pFcaY;!Rn6k}n_oG%eMh4nI<^0yi&@k{Sjeb9T z){y&&(xZ(TJ}Eo#lBi|(DF4u!h9)4%HHP{6VV)Q}M(o(3W!#Q}_984RZO}Hwg_4L# z0{N;shOOq&r23lM&@tX~B;&bVB&~n_v1jx(A@ZxCVjXL^K>WC`%a(g`oOS3srGp~? zGdd7B^Srs)QG^6~QMo)50~pu3-ojutUWHU09PadBETS}!;s@uGwJAD+M?6p9bE4=+ zQ~cad(y?@>m-{h>un6epGlNTkk7NS_pYgsEb-%58`$|aI&W=1JN7KLftYfqVh}1yFI5?GK4){j{_P` zwJiOarCk0OdU4Y^=-@BG_=`Nd1a7<>uoEF6V0P?NMsLOqJ)xf<+rI=h2q&*D))XZU zdX3z2Pk4?XZf=1>hifW&u+0I-EvuoL#kI=f%=sIgZ(a{d!SvuTgLnx#M4F_Dh}oRY z-r?*p!P7zQBg2GvY{}mu|lyc1sOrXa7A-B z*4K+9(t&2*6?@h@B@gKwe-SRxRS9~{;iHB z5`U3^n+UmbtrR)&Y2Uyy>L0-4^KwSZy?uPj%NMl(3VHdb73|%u+PceI3{K?e=~5>_ zc;Atn*ZZ zl~GVJi0I5HP^J6RVPu9K;r!gFW?|wF+GATijA=@qeAkROsnMr?<<~Dz(fhkebuivi z*7iQP9uh;BfVHxc!OT}##I7rA48|CE-bisZ>9=m5Ui$mDBef9oFLS`b{HmL+vf;kh zJK>mG`Z*Z(vHqQV)v{z?|4Pvt2ceuYK&!oH>;fStm;=XJuBklvheYO@Ftf91KmnQj zGtq8xxzZ}V#s&cVy2fK)E|He5R};G-Q@U`W4j={tQTYR|!{Rfmm!HtvHR&nHn}>6phh8t!O{n~G$W79Q6mTXf#i*=W$j|648`-fCw)zTJcFCLSSwV#tVS}^C6dNtai z(6d-sbiD;xNO3ZbZH9Pn<&<%7x#4tB-9eOZnKB8x5&|R`R7!Ei)A(~Te%aGER+M~ z>&pWZa!G{=Zb+veh~2PV@d(3sT{s`?o%~(QJ0xIr97zbta085Oq$-N&)$OXX8=*^< z&mWja(%K;n4wPe?G2nG9Mnu$p@a_C9e*NERN6WCSp>kZm^-o#vhRf&bTgn*aCxdYk zu`6Ft-)?g1YNNJw`{H7iv`Jl)9MvTzvsm#yFsBz5xl&d1cEwXZ|8Pf=q|?v0+#OHt z$Wurt@Kh`p3nGZKk4oCqmL|veJy6E|T}6@oa7XM_I)zCS^Z!7RyD!$&nSsn|s=0B;k6W)9eE7Xc&lG7p@OZ(ZL$1I%cUHm4|9a4goHsr( zf31G>@5)A<=Mx0flCY0AZ;}jlG_0;Ys2kV3f(QK>lJU0Yuf3S3ysU=6B;uo%{%kpP zUCrxzGZ08HrG6CtnuqAMpKU+8?{2c&!D+t4{+>Swc7{$CG)=NHQMJ!=o$;o<(b`k=ki6_P3;C*)W*Lqp~4(CKG%|g3AZ_d#F4k zJh!&C_E{*%YgO}U6fl)!>=ghPt5`lp%}+cLWg6&3a8AC!CectBzE8G8ou{ zY$yL+4fFH@RiWRPkFmP1iQuu;R@sL~L-N;ue7=Xdo?+*C7A?jAi9=;W6usl-bqYY1 z*ef1^^u)DDWX$O6QtRu@V*>Xl5Wi)*7Jgui4(P!mn)(_!rsQCz&zQp^_f7eHzI?B880y#0g z@~btDz2)sg0XntFeXl%YV5~{93S1f2lLTHScXw9cNcjBJV^Hz%{!YR^)ElVvl_kbn z#B=+H__lfHf(DhOj7b70oHdXp9~W@yJf<`yK$#_ z7m+^^d8faD#YzCBGAAzhR_QvpdqeLPdP`S-^q0J?J%gB4AP98vg1Pp{I`1bz6f z7?p<%oL6_UX)9dDLj!rBF@b>tn>cCs8RbtT%3$5pLLOVwxPllF?~I)bhseqteXC3Q z9XZxOZ$wFw4?a_a={{sVetgNw3Pq^WV%ftGoY`3yo{%e879s`_PLqy6}L?p2)@(lm;6VbHnbIuSlDZC{reNHa|e-?m1TqiC5fwX6Ur^S3?#U;-YE1vyTAq8)rORchEY(P>qE_v z+dV#}roF(PJa9|puswnj5$`pm!Z6Gwo@kRd>9<_ouP4D@lz8>VM?tCFgMbyS>|2Rr zA#@obR#vu;JWDZ#`o|kA?q9r*S{WRVuaZ8XqtY3*%yx`i&ovWvzjTRrHymYXC=Zwx zV!WNATrf#Q^f|~g7ehy)7{d79GfW^8z3^tTdZPkfJlGWtf%X~=bypl7qRpc=MDbXV z3XYn4#?c^yyQSXT_RL11S@vL{S5_+p>w}@=?-vvuifdd{GXc3yP=zd{|D~~pK{TxX z47H5!ZUJBqwZPIaE9%)x>VUwpYvRVO!pJvoW0m(JY5=l+bR!yZecBG)hV5NYFad2j zAd05y+q?oar*yt=>OC*IdE4*!1)Vyo4>f=naTj=G-y^cJvn6>Vmp484aY@JXyHuZC zc>d9UL4>>Tk>uynHJx0FJ=4(8X;wH96wA=DH0|TvK%1sNbnH71D zo}&62qURafp-b1Iv_K`^6E{1yWG|YIw1`I-+^S{njz>rm{s2DslyH2s>Xk=RfBx9c z<#049ei;S!@p?9Yz8%qf&76@Smkbb2947tisci-~m7?kbg|6b_M+t86=AL)Bg=?ss zv1Wim3+olWgZYt}*Y>e1=Cw8WrH~Ucm7mvK1W%j3rJW@g2py-|dq5WGU5G#fxp#W`=V$Nzr&=3lF zufepmPyAW+qX55v2vX^3I}$ljjq8kK znoKXs{L+#jev)?KGyL7xRR@@}iU`AZ({IP$n$``cGh#rC&mhwdR;e__?+QTLL z!B?8snKiBr@58Ygh440>S&PKZA0@vU#9wJpDsBt$pgstOadyS)+o>5!Y*RQKn<>+8D@Kj&=R z<}FHmc+UV~>q(#B%QsjCZ(LQiXm^-_!x+HJ#oPVqa9seVCFj1~0OmH#2|jDCY=|vn zAV*3J7Jj#`4SV$0*wvE;Ue3;PIO>>~OJmJqFW&GOD)!fSZ*T8x)X#)2f*)_4{|Bgf z8#BN9&CVQF!3uxUzmL*~hU9_KmR**DqO?=X;NnzhuHWqqYfsDvIE zb@7G8*!GGYXJbRVSF+Bj`W~7ajmxhh2y2IM@TSI4JjD3;U^YCk(ymO|u;*nP@=s3G zdP|&8p}R~-Gjk>YFcE9KG77f0#lv}{1!F*7&5ljuZ!sWrq#2_%#Z`1M1(HW#I1~@Y zP}v=?41ZgiIpHi$($K_>&8|>7mj4U~RppbLL)QRB!vX-9w~KE8^6=43h=hB7b)VNvRR%s^TU%p?~ObMbwzmwnFc%=AXi zFE+0SM{WH$CoW(tBcubT@1KZn?03;mCO$yNj77bm@|*NuEB)_-b8OU$5}dvOsl5N^ ztEJp>!uGJ1ja7B13b}8~J5C}c%^1hXcvAJNWeOOvw&cv7UeS3I9u|1mC7I}&+?l?M z#H0EJgs7D1NL@Sxd*V+=FOI4jX4X9tzPS+By@`B!KD67-`mj!1Wb zj~FKaJahVV{O!ms*6!% zAa+fh%A$ev_g(&xz9Ey7?BjG@Zb|Ub;MfpuB-{ojhw8w%5yiG^rA!WQ;79=v@-ec% z%|E|7WNo0t1Bud2nA#7Un_gyDEiShDH4l61FF`qNpft;!`pD}VgmLdXW%Bm=($=fD zV|a4nX@?=Nm5nC0J|$udTo4Ju`ID~II<`+|YndKM)sMhjum3EuVsJ2U2Eg(4;mjIz zHo4Wi*+wDGS$=4$6?80!0v~al^G!xvGPO8-4hY(Ea_kcJ2~c*__BLSl=TCo(WA@A5 z(Wb^0qy+)TA`%!+f*)M$wkcA3w&iyzMeje*NMLBBB8XvL4gEZU%|ohu>_0_7DaQon zr$4K*Eh#?Ub~7q?XtgoBpyS$Rd(_;qiDOe=OefqOH=Y%J%>weME}xUS%nG!t+yfBw@QD*;dx+QQ%3D1a_A88EA7)QBxj;$Ifijeksase|$g zrR_gwwm7DygUpeYUn|?^&a7`xzRql^?Y>62hxSvPF1AxRGJy?>(;qvQh(S(lMLs1S zjdiAhUnk^;XDR9Usc9a*`xrY=1}w9u1s5mr_{$@JDekM8+1k=}S76SC`E*+u^nfMA6>qqRSlbtg7qY-+r;$jd@&|E^Z zlKDTRJ1N|i-#48c0Fp14Wo=@Wg$QRUZO#HQW@tN4!1%$(I}wIM#9g9=&&zPr<63|C zVwF2-e!SvZ*fW}01)~{$qo?H91AbAr7N>i_s(-pf2$@<^l3B)nsvV{1I#5#;G>OJQG{SKqDpDO@CvYM*!q`&;!XrfT{gXlo04}I>P4m)8 zy`@`!XVsWIy0H>>ZvH*wb@^ax1t$rZ*U@=7;@jJto!0PbVsZBCc?`d?K13c*my8z1 z+kBUY@C4t|;-PZKp!V&}&CRKjp&d@tX2){RjLTcm_IvwpL*I_Aps6c5sYFm>%VcI6 zCE<-=<2TgIFt@4ZMFswb2s*@Xa3GXV?;@I86#|d;l53=iW8we2020wHnxva^71HmY zj5D6Bz06NP6&SF!@~eD%p}c7;i(`L9=T-B$A9~PeT3nZ2NxYm(9+ixEJ?JhZR2#gS z8<^ggE})x?IjX-jC`k@5#_d8+Vh@dN57s(1M;=abR5*gpp9$*1E{>Mey+;N+JWeq~ zbGLNVXFoDTTtLyC&jStcg8CsTIP5&;tT>zmi|+3iAk1MOI0W0De5@X_iMgrX)XFTao$wI zlSQN;a!A1+pymFr-F9SOD|Mi9=Tn00<>|NP?*>H#M+7w5m5p6-=*_eiIo5E=YU&R7 zgSc3qo`?a<-(@rccpnM}m<#cagF_>b0}tNUQm=>^H) zY!2v*>6)kzp&N++^&Mx@Z_{yI)XoJbH2*sDOjlD_iY;*avs*U>FlL>C7iGzDl z-@h!+f5o}C`$>?UVo>nF(uURc2~-=TODB`Z6KmYWsTM(l+I8WOt}MAb<7(|l_cuWA z*ahWLtJR=)=aR$^psptD0X5^C%Z_q;{_cH05$7JW%ahK--{LB2NHVtQpgt!aZ%enJ z$HT=@x}Ww@lwrvdH(u`&zM;-+3vc-^!WFu#5=(WlB%J(pff0h~eZ&=H1vnFx9!I^p zr(F{z?90u7^-cDxhPsCrfc*J)?1FFgdFJXz2-$wcoA0pe7s71NNHb zSFZR3-?`ZH>(x`)-4bMku%~}#sAyxAvK#@5m1cc^ZL%gGhk$YrEycyLO-gUu&Dqo{ z%g-8e@ZRQgl4r#)tQi?u{UZtj#(W_KFy(ZI6fACm8yGVo@$mX=Z!@zASVSI z?+9br64AJ+G7+Igw+=tw7CBOR*(e!_Fi5kc&C~cP!tQ;8CimZF^@!W+eD?}MKHS>I z9-09A#DvG?8CQ?Eyky!kYdFn2pL&+P`n$!n!e7YgBaXjwiH6*?3cH_J+S|=E)PmZs zq^+y9XQA1e%ZBIo|4C44ZW!@)%cna_A}wP0;3m1)LOU}6WjWgZ_Ur5_cspG$P1Hlg zB{!^6KP7{zMU*|i_|#4QhNr#XNWnHQhqjbEZ4YwmJZNoQ9o4+K!R(3XFkDB_fGU?y z#j(;~rK`XpH(lk%$gl{1|4JK$ml#Z&pg?>G&he-=1|V4bu`xW@oa*9skK=lBGKU2u zS+oOII_HuX`VK1NOGnDV!Pm|!-XoNN?5s!aw!tUxp=kcksl*r*jPZ6YyyA>#)OMF+ zXK@h5s;4_d4l97axiOI&$BV+F8@h;`n#<%*B}3&9Ds>QXyNoloG2WP@vpy%(yg7`$ znI^a~qZVuLDl@v~m(lsK1kysq+zq_>m6KU;nr=J+HZm?ecAgZB!G9!%$N*-Nh1I~| z(cGSwSuHf-sq!n0qv8+r#{_`hy}JO*`rdt2I9f>Q3O^`qjTloej)gTugq_87N|*)x zOtC=8=c1%ZC*LFaUXO8ldwXA3fNq!$(3Uc8j}3}27DoNVr}rMg6!?jj)DQ^=^?6l& z>1B^DVo}X-Y`MKA>#}EN zK@VDh0N4({7DM_^0cN;uzVvP7DM7ph{5W_zDDx_oFG}e990$?_i}`y(8%;46@1Mvg zK4?~AiM|yCL*_+rDL5XVTyZ37;?Ks6%OMGP2WZ-rf_|=S&jKXKS>fahr995)!z>zx zfjn`;6S}?Hg1a0#G=8iY#)ltmil|TT9V$7En*96sMh3lhNF8^FX3_a%|9-y7ly>SY zXZG>p6qX0qCa7;!#AdRGUzTO=ceWW?J~gZqxvC|TuDZU~8}&B5e0!XCd+ygdJ*3L! zWaicF$@w^7iu8GM5nt?#1Q&H@NY__K&`AP?{6V{oaA~ynL*Xfacn;HrP9knjyj)hy zn`~5ipMbz)wkFf%QM7r)?wGzXGxWjH11NkvHF-gl%f|4{v&laRe~NDw6VBNXJW2)d z)TL0yaQk?pQnqnEmH0l)@#_4b4f)lo^U>4q`|K{DcX59o9pxkFcDAf>J(+pXF8NCy z^-xfUurKqfEgVbAsLeuTGYxc4_h2U9o0S*XNnPXKyLi`8VJL8 zl8MWwJo2Z1=T-#iIL;=;x%W1&H*a&AZ*Bh#3He*I%6zPJMJIAWIzP{{(dJ~ik9R;U z;I7ZT%<5%^j1+tSzS0z$7Eo#3%N%aq#~ZoG>^*R8A76?^3~nfJ>(e=L1)-{v5_R^# z^$Hv67z@xI(uiAFemrq6?751(qWZAE<}TPHl^c}pg&(cM;oE=;&aSTq3*dCUGY@p~ zy?TqiQt#!6 z-@VAdQ7Wi_apZE7K?08rLRQ-}lt!zND-j^9ZQt4)R*D)u#v3t|mHkwOpp1vTUnq-# zsW2=kj0|TaIO9tfo7XmjVX83aGsaLW&Bd2d4^y$}d5n117XIrFr+w7M!fHA)K;7}A zrGtp-+PHc>koD$E95-F6?JWs`TSz=yra4^&pNzTBr`VLUaMrwtVAik9Gq%O3U2lqm zVcl`8R_ufRIkWAKsQzQ?MxLzq6LMx(Xa26N2Z_p|EpKZdks8U-l!j4)zgp1#H2%{WbTKEgx*3?s~!A%jML_ zuG15_{PF%-8kTZLbXGQ{HC(QWg$oG5`Ke54P^%wBiOr!q|yx{CLt{k!h&N}} z+p#HpZL@@h+Dmqhcdlnj8sI6oJ3pT(hsH<<+1ROi%ICs9q^1UHmbfq4-WK`V5jn$l zyaUlixnwJ=7yFt8tCdS8##)BMlyfTkT06di2%zB3{#a3U=FG^JgE3#!VpZW|UZwikTOoeyzguwKOwrEufyL18JAFYOBiShYLKpHktmud)wXcPn{;5CZU^PV75P$F8oPc^!3@o#4SF4QB zCRYi<-B%NUS><&5M2^Q%LIw4B{;f#A(bYKk=JiH0YQawU!+j7 z8zoIs7$wc3AQbBR{D<@)XUb?}1G==B07TcCP#5Yu+TC$Ga3gK;ML`(Deyl{i%E!UF z;g>yVA^mF)JkkyEXane1H(JQPn<>nN5c&~L(5drJ(T%t9M3LQkVnNDZgH5$eNe~Qh z);f_-d6Fk69{KM|Fz~Y~Dl*b8It+Puy*y3*{JC_cr5(wQN-LK2${_gT?*yhCPy|&G z;??wYT~K9|&?Z^9`QO@;$yC2IWIQ(zdd#A!u`w0Tt%#erbje3dJ6!t2a{12kPDpU@ zK3EJaE?GC$>}e#IZurXI1Dz0SvLp9g$&`Q9u-MAJ96L#~Rf%{HwW?sw?ir-=(S`9vU&6qZEO=*IJaTnPm2m>9P#dgM z`58#7`kYoYtwER0hr@2RzQc*oE4rtlmOzUlLYp8!jZPvh_C8Uj?_m*fKxd!@kTIn1 znn{@VfbMx*=1wqDzzVH+7GqXy?biYx_nGD8$l!l;^``klhFrw^hxB0qlJY2kf~X&v zosF#06b;(QJ%G`BkyuJK#!RMTBnidf(-=6uFO#P0OwkxRBF16N9TvV&TU)y^0n+|j z4Go*W@9>T`MS96*?INHrS!pMpt+cYEyeTX0>gp=f{FVN=YwCLSB<HImgO0KTEqr8QSH-*Y-c5FRa;M%EWmE2l zgn!64;|P7|A$MexO;)y}Gz=8a20u`?`&W!4dGdUWHV?&$0^I0w$F?tUk%!V^BSqup zH~)5Pl;p`DJp(d}GGRsH+- zE^1^d$-CXP7qG}E@W4D3DSe9o_@Lwi6)#+=Db$qKAIh0MVrN2bMn>v@E8VKhBRpCg zXZu)5fINR4jOXiMi_m{6a&1Zo39dx=c$z?qjj~wy+^DT5YY}uS-GLMzCyY4v-i=3h zUkxDj+!zElbt|hzyOVF6(Cr?y2P5+f3kxeN4^(4OHl;_-a(S1c$XG84`08qK#Mtg+ zG40S7)v<_d+RNt9c`K_TL^!i1IJkCn1Btg7YHNx`++ZG&QUGRCEA>R`eqA2r2a2*! zGwLE2r``5DA3c{ZEej{TPk%MYjaqiq-8&lB->;f~TwIdG^B+Yf7a;|6I+|3-#+}#m zy${;ERO!E}aIj}(Y%qYf`>A&^Kuzk00D<9)hT=+f_7UsFhId$xc9>F;I)EWVGXM|x%i9mpX@UA zV)ww!-*7kul1&tX3k7`^royE>HF+libHwdQzyp5}#zKy`N;fKJMt(%4UP*7C5y4dzJ>$-gY%!sz^zon%c5tTa44Z86c4GD_# z%OxdE>>)N-U7a}ob^a@e^bW7>DdZyA7pWCC*pxM>51JC@&TO~v>KY#w8oK23xGR4V zLX?@Q~TiaUKB}Xg3|RqpQ3LwFP>HN#q?eN>FRK~# z1zy6ru$Xigzdh!Ls_^)6q*MVpAlv`A`!UXLw>-<@U1X|?S0d)9q!UHJei!uLBCViI zB_0>r@j^Aj#hyC@Z;aYNtQ)Q7)}VAL;CjqgdODwn>z#ZTM*B@TB0PL?J@B%+Arr~v zf^F5JkcPxdidRNYprQA)&r{)L)ocI$3}qI?N`T4-dwUuQuE%J*eL>g*%)s4bL^)VN zEle6=NG5igtcKN@mszzl16`NM$vl0lO*;|!Uv?IHcjS2d?ssfpGnE<_?O)NV4m|Lm z)ko6Ji|+G(9`tfR8;sw$q7RXbDF+nO4sL%=!3Cw?|m`jy~8Gc_|+hR3L;r;459oP>uQ-6tbM z5{&+S>M-eM{m2IdncDmG%wwWUOm+5joi#yTCaY>=#+qH^B8J zx;PBw$34rlS2!|rqb6Mmnd`-jMf_S^bCqR;Fd6#sXm^x!K{~)XR7GvJ6YshAW^1ZP z%>B!8N_Y8yD`)QoB8L$MPj*kh8Gt5B>|#qHjXC`HYasO#DHsm>k3T;}F@ymA3s|<~ zgD>=XSJ+5eroVvWpH;7Qm_^pndd$pvS2iN72B4Pu`moYKtD=#}FfFlJA0O_5lI4yc zzHs3X5g(4X`{M9*?Z+t?)8@4v&}8ZHZMuGJ%haJ`=jWLnFlG$xEJrOnZVxnXbxmyF z@(Zc3?=JlW#iTqqh|8jt6&kf84|Km_YvAWjnIK7y3MG&LULqQ`7s_#Jm{fxDEBPl* z!IHzFXHLJBr78S|E{YgI39@whhdD*{c!&;su22rWKAB|fq4G$z$wsl=(m5p6LRQ7xB$>V~%3KRqJJdMIZ=qq5TTE3A#XMyR-r>dEnR0P1-6M=J_U|M@ zGOiDg@=hQuUK>^MP2pyGxVm@F&(}%FRBNYjl?yDzZ zPl%OQ%K7jKZK7Pj1u64yIa8hNXZ*^tGcMiYOaGT+^~lYuwZa9?Ds`eQ64BHYaG{kS z9EAG_=k_b#P+!Hs@o1UJmD#;|bIh@b$bhI5C7n3A^f`u9yab?)2r+;~d14=Lw=yGh zW&775y%%z+#OLV}Fbhgr@?d&@Kd2cDU7IceYDPvt0o6D(T z`KQ4L1U^}1;tP&N60L4x{=L!^S#4i7$hIJ9$=XB4TY z&?H_(@ky%1ePXdozwakcAE=EGZ>!orVIX0I8X5B`_ny_+_!S(c4HT8DRs93u*xBVi zC6+24lKm2Lh9X7wZ60e!sAVRuZr{=x{r)|Cb7_KS@l;~4x_Zf)3jOBaSn;iyF|nHZ zu7nF@gsiKMqiZx|h-ouoCrdgDx=;|uw*>Ilc*Oj^@a}Gz^!;5|*4)@!h!@*nAgivF z0w5qztw8Hh&5^uQLHZ@dgaLaf-dBAIG07!H=60c!)J<>XrVxF1sp>)in?z}?&{Q1q zBs-lshhwd^vTJ2&`MuB?yl|n&w0k~l|z5$icmR4=TBga+Xr_ z1utLv@0EeI;Ch7-__xVK0!N$Gz=@;j4KvLN%we9%%@W70>-8f9w2!wpQl=H_M9C9G zk!ONb{}dI;0FCUQtN|#7iV+>^3c~r|^3iRT@keO8lP{$4!am}ZW}ovnk|=3qpTnEp z)YpT?hOiZ&<*(1q&Mqx2t*kJRcMx`pj|Ve^lt8F`+Ks`DmwW^8WuKCwHYfZ<4;TQoZ9ABmA~6+$qEgfVjYcgWp(?~gWV1TsF3lh4my%qu2s$9&p=A(y z!WrBsaEqcFvGKyM2K8WF-<4vGxpyO0B9i1$=?3EAfOGq^JO*);gy(^rVa^}X&p#kN zGi%uORF$*0e(!Awv0ZLQ9Jf7uXXZxJ3-+&><;#E}s+IQvdk)zq2$Ur^mKOY3aVBk- z`*&<6J_RosO)$VK7v}*r*Ap#e>`Rd6N><4T2pV*uNW4c%dj1W4dwu$9^_7Sj_EXW7 zxYf}xrNUDWq`1yQ4viSI+p^ z(pZ!ve1iH6zJ#r@%5wQSvr5-!Nzjm%<22R^3AvkG9{X;;Qy8`Il-iiJ>Wz$R63;7! z3qd~+xr+}ku6XO-cP^5Vuo=I&_Vt*!c4%I41~D=q;F5B#LsTA(KF*DzR(}4gC^VMN z|NiT~OyVRplv6*O9B{wIJsB;-NH;QDoZ=$oB`U7&tcAxaGjJ!Y+Ncs_^f^HFibbU8 zb>bdh2qC=nILgtMhFo$K;z@cH`Q=H*f|v=q>LrQQC%Vfxh8bM@>@DMjt_SD{ZX zJh>gu&ri%FBR#{R-sVtKNRRqp0_&)_p2KO+zNlgHO?V#>{6WaH1pINKpP98jL+mL~ zT)8JVBKZ60n5XuGi8prTD!M=q*D+v~1|D&iPO~c?bQrUUu{eZo6AX{~OLu+`jWsml zY)e;xgX9(ky*dHI?8jU*jm;V3tfqbf;FRA;DMM`Am*A~a4|M8)c&Wm0Yz~!jJ?&Vk zoKHyrc2ihzCNl@nIZ_9W=WP3($c4_xIut8>8zlR|*H4!#y^yXUGlz|WVeWz%^=A9T zDHDJ@3W{i;}u=VjYVfR|Jnt>91Jv9y#|FX7Ojolsr7OU3Uv zj|@XdZ_eAgmR9*&O6u>Q{-izbcAoj$4}s5-kdt%SXi$rkZiTJAYW0%>Eb;su5u zgVm*0crEeJr*>qfZL6>e?#IrL<{e<|^%^=Rb5^e8ti=hqp7HIA`%$O9N${vf!=gPh z?w5fY%Yo}|;NE|P*?+YP&AT}~JPazGJz?*#4@w5=h*q{I0SaNk0x)HC1@)1!KSaj< z(IcB{2g6r}-KohvS2Z6@xKvP6h7tivm*QzvZe|KL_|020oXt<-Tkqcf`St6*|9%*P zXk|irefarw{q`8B>;R>vf1hqGk8LKd&i8KrHRH^3fJ+vctK`_cq+{tdV^P;wpM=w+ zSR6m=knBQ6P!p3TQ(X4Lo>2vL!}dx{**oRlbr5ms#t0aLqSFm3a9yAb#PQ76cMV)h zPk!*Wx`c4{G=Xv&fX+60SFkGkRQI#8lFzd)l#@aM_>amDpdTaNQ4tXlK|zB_QUaS_ zkG(~-|3F&&r0iiK3=ls%kV4N-TdU|i?Lim}UW=Lk6Pkv%B;G~9CvdGE=~yAmIY_T4 z)5-Wy+?`_Tj4>3D!0Im(SJ}9$hLf?GsBi>*y^t%9SnZ~u$@hnIbj4jW~8_aWva7_26r_d z(gk*8qaN*{KU&WSBS&0;#LXf%$SchxHc@0GxI@SKS%_p9^{q`jBAXV_rg}M~vNpZ@ zhRN;RJL=|7GXXhjccf4lHrRbp1J=Th_}de{+{gHz_xM^-)mX(#cbkilUGhp347CqB z1q^nznEtOuLxdxANyEuZZ~NCc5Qc1p2i*^PjF8!v;U~THR!ZnUwG5~K(*m^IC}LMU z^>+}w$O)OXw;C8%O}a#IQ=`*$0IO5?kyRg;dl=#e_^Lp-P)zZTq{)a!db}2+K)jG#~8lh+J7bEqY`!7HHuuhwm9_BywWMUUp<3_ z7k@u!-tqT#hA}i*Tpm(O6;MS*y_rq$nvN54V{}6mQmzu8IT+$!o(&}0?}kJnkhtr0 z^@!5}{JHPB;lDBh${ZS~kiVK|UCpG9sG4x6i5vqT?#dQ8M12;SGLK?hZ=T~(l6j@H zKA}5B1iX9Lm)W5@tO*-G!8nmST{p=%274F;&6UoOXwdaSDYO_9wXhG|q|@{BX_xy} zSLaFc|GR~wvq2&Q4SS$XU-dr%*t+0fB6F|yYd@l^vA+1#W_H^Wtt+ed>;0r3ir)i~ z%YQTMS^HB@n`b|;!~z}IzfXKQ(M_NiOyAfT_PSXVO<=*6xdAb`V--*OftJM&Pgjf8 z7x;R;;A%T;nM0s3C9r#0$03f*=Os*)svVIl;eS4^?O$Cw(tysJx--RaG%@y!UF(xLc;&j+N|S zx2L{lPdhZ%uCJAa&nH;?&uYE#{qL&;jCAzKJ?j^y^3zY$^&z(IsyL*6oQ=){0SH|{(r(YoQ#!eyb=}8F&B{_Tga-$URQG>!b=%Fb zyD$gUL)HlDEa}HFlyXNJ5I*uaIxSJ?yctF{lqUq{UCP>cq^SEj5De5x7Xe?=%ONZ5jg$AB!`rz!92+Ywj;&{Y z{l30n~#fIaQm~5@~>}_v#=TjfD_P8 z?EX)|T5e(YBRXK`WDc-WD*OCVKbMvgu-q5~DNb(x_zP{V!8|&;WqRUF{?E|WvE0XX zPLW6)?UH1oKet+4w$-_o3dv8=-^=6i%!fUK?vqN2B_yAyjeHpFyiK&my2d_#vd}qx z0&9%>t!<8xS2h~r0EJ36ayRP*AcEe@gs063^tupQx24_>R;BkTS>&14t7XJdXx& zZK2=OwX8vkz|~XkB(q_|D}6h)nb+Z#_F9t@GZTIRTr_t)A(1H(SHu@uR<`EG z7W_Ux<#U4LeL8RK#+k;=zZx3w6xwx{V-U%@SmVh?YO#LEhR#mY{;T#}sh`Q+$CC@@ z+?MLb5dV1;v+$Pgy(YV}Ix9y79hJzXSAvmtUZIS6HwMCp{;_G+5EeEnd!R#7#R0f? zFytYwtE(guNQ59h^}|UW0gVpoEgdhLYiq+-=TNAtFt-L2J^B}^%XmE~Bv8<@u0c0w zWGjAW=4R;DbQaDuD{N`%<~Dn0>sFXatm+w4mwK%CoHqBV;a^ z9=u0TxcP-?_(G)B*>rMZh88z15KHD4&jQzf(2rnOxZpv^T)|GTPLh zLPcPb^^7ozG>o$b<&WV9xg+k9Y@1k_pYL>HAgU&WEn692Ezf9f8S>NnqkQv^g{ zDPY#V{%X`)^Q>$GLUF=O2N=FmS@S;@Kg7(9ea}rKQP*a=mv~tb;l92)G9p|vrpL{J zeqi_Q^A4L%-}5|?pd=LStm0&MVB83nfPJQj6V@w$IsTxUDj!%Ga&6xDv9oHua|an> zL&TayCO-cAYSf8}Bq0Q5w=~RKV!B<9;9e9B9^P%h!SoY}nWDJ&8s<`zy3*7!gtPkx zjXMy303|xTXh_uJoPk;X8!d=ZC@FALx=x&CXlnBQH0(n-QuF}`FW21O8kt*I=={ho zcBvEdb~SfJZ#`mr-TM%~mhP-=XAS;JG{V%6n zQBSS*$_TI@IG86iLG#tSsqDhu19>ZKwP5KUrY#-Qw6j>*BL)F_>&iob!)gd|qCG1F zI>hsvb8T)6Kh8wfw}7p(@Fn(4;DwiO>B}K_jD>N8?jpo6`*?JUSYZ`dKu?5g-VIAV z77X(IbQEBYFE9IH{P%XW=@}*a-=g1}g$U64=*LJN^|e8qe;!}JK;MJWu(xL?(YIwu zk~LNttmXiq5!pJVm7sFMP^u&eL)%tl{6Vqf#D ziglw~>M0|{RnCYYhykI*@A4APN!Ne%K-J2@tZ>o5aqeqS1p1NFcek9&-y*XzGp8&i zHv;FfjfNUUqE>@+@5cA5@iZQdYq+KC0_&@yVXx#XgR+5xI{2>|Q=r+*%E ze%A0R!M6)!;C_^Tx}x{M3>}Xl;W#}#mo0kI>U5+ZVULrF%MXKz;Xz8ruPRL}GlkIi znv=G*9Vu5_sCe(@ohm8)mWdA82w-FA@WmmpU2|ER^Fa`3VWDalEvNb#9l^XMHIQ^# zKNT^_7?>7EQJ++pnh3^AqL7TND$lQwKh;A=9d&hdwtfPY_u9{=@s<3#mqHnuOsLqK zhS0gES=)Jqg-gHJhc^~{u9sM7^G0Imq~LjHTHw%b$Q%%J4~gi7s<5v1_qzl^Vl`)e z$bubQ_-5|_GPzBa7;yG-UFi@KP&u7|@6j(PVr8y(ckEcaWKRYkPh@H{oWXI+t@9WtLOLPRq#s?$aHsO)FuUDVAvNbqc&dV>RXBZ#ntd z49&rPmoRN9A+ij9E!;rW03nDfDGz?`@mi){28C>Jr5(dngv1fzfSqS@GC)8s>N=WC zOJ%vGR#jfc8|VaZ@5|;qCfWm+8x!+ja{z)_3cEp+XHtc}H}1yl5A$9Wdw4UMIdd6m zXfn69_+qKz>uCri7M1hv`cU90$j6Rf3=u2>|7L9M&LhOC;pzQ`u`pDdHiXJl%qPp! zPT8KF#lFKrWd(Rg*#twpvCaBed`_fXushPAC+pmi4ou!^eezA&M;8)5jkh)aG*c5} z^oN{t_|v>Tr6n7&;44u6Pe_VBtyf3H;MzqeR32C11}mfczCs+_1Od`7=Ab|N#>d&- z4&mDmWdVcV?3fen%8!OJL1P#TW&qhEiGZ}o7YOG;cS$fVVisc6tg9CEW%adbBwG3O zdfWE(q^JNHT;iz=lo93P=nCaua;hkfue&>OGWcIC9<#uv`6m%7F7Hl69DQ=BBw3=h zLYb{=!S}HLX@~zHNYvHUYufxjiUnt_h*`$H=d3X31E&>ayE#OzeL zpAUjIxPx$UHe;m}4XDh#()(w!Fs=c8e?&T(WEVIAnJz8CoV*vf2hhy(_mz*A6~(Cz zF3o6I*j0>;pD8=P_1hwBZn_R!c;+OZ?>~M#aTK$APHj&Ve2Fj$8|dcy>8*6T)GM)z zYP?HJOB+OJ6$mThvtSPnrX%I9{j6Og;hC|{V%zY{@OK}NArA6_)I*rRvYPm%vLb&6 zm5`cYgV;&3*OW`&=dCYNxl%mBMGiV!SX|oq7EPr{W}RbOWW6;sy6tdKUUFf2G{P#0 zNV9Y=xcVSsxiTW#`W&sT-PZ#Ch08phCKd-dfO4cT2Dld#@0kIWX_U_h@3&29y{$WL zZlr^pT2jTe#Y{YITFp^($G_LUjKJY8j>!8dP((1y{}KBKY-4_<=U;?;)4i`Le2n}d z*t?`f!oMY2?n;6KuJ|du7Ar^gtc573b3~>@t4d%JaJyo$&#UP z>y!kU^vXjd2KEv*A8B>yt0-=O%n?ia_LYU~>1!DBBEhila?tcds5sqm(GoMk*xKax zL?O05ipQ1kb<9&|iR=bdkaKA9`0>VYrlkVaRB!JrGZ7^Fy(~|HgT*lSa^G<#pcb#H z9(d?z2Rk6Qs5g0#B+z;95}ar!2JE?Oo0pL!+HYb9V!dhSXP-r3MIzo$nSLeR#ow!E zV_1QC{aNA5OB^?0hv_AsFYU+zvTcGWNM7Uyq$W@F7g?tU3hLV?G0{ZY12HkunXI$! z!y4TL#o5g|U}!Hb8u1K*<)nx~Bg>^X_W-6`;)3J3_7`+BKz4{P4Asr}n+e(cK%saI?%AmcIH?ak|wDHL*sii*mySUVUb8}SWUlt;rHCS?E?Cc@d|pkZP| z5JaH!P4D`Gj|63BI9h700|EjX#ZMWT=-YDTY# zJ7;yg?Htsxekh5&<+B6Dz9hG#nj&m@^-hDc0I@RK6t*QpYOTGJc{B;@Ac))n4hlb zI5ie*ml(s!3_LmNFZ*@0E|Zd!lgJk__Q_EM6YM`7oyZQIBOM0Qq}a4dT@RIdX8()ZK~ z=xO=A@p{tB!6Oq7_aUwljgdD74nl61WHUtLHkw3Q+;b!50q1tQc{?36j2*M1qbSp+ z@U?$hr?u%F#39xyG%=aCc zsm8xd=k+uM;a^tID61&H<}!p}2G!5o5s-JRGZ08*=bo%eO~}#CwJ%E}x0Qc=e**{z zf2L=f>mzjKjqGAM!L8`*cQOAHJ^_%FvmaN?Xx(26r2X#4z5|bka*!gBcHzv0zMBhvXSrRhz}qN zK;#7EP^epT-|Ne6hVvJ0n8rT--9N1*`aBp*SLM9R_bM&R3fovXOX~!^ffz{u$mdG@ zxhcVE>G`QV;*k>ipm&h1yZphH<4mfY&&W}j1W%7ewy&xGC-Sy!5_rcl@)JWZ<5bub z_ymBoB3;daKsbX_pyfTPkeGMX=C_YtmURiB`H}E10}lbV_VC%xiLH%#t=SP_QiQI| zh7$y!nf)VEv4^Zavc8R;x7^zp1oGYeH6M}sJQzah-Pio~ipe3%Oiq?E0&pfTB)NmO?N#!#s7CqZ$rG>};(N?G0k15b60Z*@D!cjVI%r zGhHtK20D|VAy1Cnb$2_HC+nYAcB6FV-@b^1P+!J}OBTW(f$r-Pj zOExmojoj(AQ01$Z)&V01*Ih|?GVvK1+cVzq0e+mvNPM#J?Tw-ilc_jKR;1q^;xLn3@5jI|cOG#s zR!5@1welc9*6TrV{y{@s>1D~7c(Oe#+uX_!whk_X<-1yO3z~Q@b~Kyc)?5_$=v=3DT$n# zoGNy0;2?@>d8foO>NtIoR7Uqmn;D*IM2K1Km75z0b_H0=`mw&YwzZ*I2fzgx{d=H! zZDtlnNuT-NJ#-^BRf(OW^cu_K_h~=gm|51^S$#}@;wFvrDZ3d~mb}OC*6Z!9*{1D< z$J;iGO^Iq2IMH`~x1Q-y85xU&c3f#JI3SF!FG*08VgFD{w2OwjV@$;cUKfji) zWM2ALjw&aL%XhO)mVYW|7kJjmZs4@5@X_0}Q$$O2yHr^h9%cZ`r!Tg_P=7Zvv6BoC z4}f^P75*4|U}WDcidxom{~7K%orNeZ^R6o|OFMHSkWLREic yh%&DMvsn1G$IaF z?RmuD^~j;ZMNSF(PRU99#KRztHSwUK9MW5}Ti0S-`?crBRR77!L5uSn;Bl{a)v_kU z6<$G7kPmxJFy!KhmF;VX1Vt$b0YE;6%ky<{RA=G;&#FIh8xmPMT|tl{HGJ?NSVp`B zciUCLUZA_V?DJohP?3YE2~%;p@XVhed>o>I-etQ11VLWKJ3u2oU2&T>pB%9;k$iKz zvMik6Kf2j{Gh#becKF-3Kh+!HiW(gqImKT8J6sQ@&rkW|R)L4K-TB+PyI^v0@Kq$= z;avPX0$#THo>Nr|%v2stvIyHbztyuNB-*+mVfBQtK2}^A+&9@EA1fEz=!-^Ct}H@u ze!dN+sL$zzvS(!Nh5~t3_d}*0#@i35MO(q-jOF`>>sLam;!X-*4Ej5jLxFDmV*W^d zB`k{UuvAPXbbWjp%_i2vm?-u_@uFd|2e$(_6mMB+|uc#Iu<>!-hL<$ zNs?@!f4YAGvkSO#L^^~nrv@d7{V1-oEy5YVdJ6g~ln5A@zD-hA!|HpROR88~cM{;p z69Y2Z_Hn*!Y}|*T$g*c{@iz?yAE^#{YSKj|!v?A>3al)zayBGY^h&3@t4FR8-8R$8 z%Pk(C;OXXmlR6P~6-U5l%2+V|EuH2Y?{}7Peo+`wIdnX+xDv|>wvWSMm4U#FTZH&@ zwgc@s6lgO^e~wM_zjn1fu=ziH5)s3Ew==#oCmZc6fbguYx+)wQNm%c;ZpL&Kdfp%3 z1QnS|#F_}OIbMM5OoGU$nDd(t#+0jSV(L2bbfGCLqkJwpcS!O!(92Er*N(`>Sysx{e01ADDbV6jW#xJfj$ms>K`Zf z`w};YRl)-{=JGrp@oNai%2Ga{VgJMYv;E!D)P}fJahroQxej+rsANqAn8U-@IwI}{ z-QT#k^TJv@^xk}L2cl)hWxAn~gOMNdKP%i8lPW`E@O`DRICkC7Q0mG7l(gZ8(U9Pn zf&>=O|KNm?*}<9W`;0ESmF$6QyJK4cz>@%LdU+Ce8~=N1N)VTFe~EI5_m9E7`md+W zAEIn0Cnng*eBHA=mahQha^LIGnWW%o#2wGeJbz0G&rw&2{Vi|K)}UL)9-d|e-%OHk z{q^IA+TI@RZYgor*WdG)D0FQkq<9(+GnccZ0`Fama5S3kNV|FSygyeRhl64EVvOVT ztkfGs#x;PR!=``Md$z+(lk2a%ywRp%9$d3ew0OD>pnU2{0QqWwQ)P}d(x0gB64O4H z$t4>jh-C8XXqX_XD@T}fq*0KQ?{)x7!1wU1gxzeeQRmy+<#8#N+Y3X<>D?@C|1Yy; zrDY^2JLj==a>NQhYqa2@4*mbM0Oxc!7Yic1Xi*3;YDqbvi~d&jM+Wq$gjH*bBhHyt zYq}D#m9^86?|3tyX>sju%4X9BiMLG;9553AC|6hUfDb)SaIV&zJ2aF5Q- zs_--C3}6UWOFaxs*GTyJ@87=zDrK6BJaMQRaSUbb@*J6qk(ZOFi2{@6V=Slg*K+7G zi@-v(z~A+)(ZgUU=xiwM`;Vy?ORYM6Y#ba#`_+F>7M4$87jzUjdUB2IZ;tAo%V-c$ z$!tc}JrYxlq9XF4;5qbxl_%~Y$=(SrES3}K&L8p8N;e-C`G@Kgp-o_^9TztlqrpdN zX5hzel{|!$+VWCS%)4m{UD|D*zg|h|U;FF_*oAy;Z>=M)O6@7m9uIRVbz=xK2G;%b z_y?(trP=Tu5Z$+wGo7z@E+dJYO_v9z2>^#M8eO4@CcX`?UjaJN3@j9N8N+jK9y$g^ zy^{l4y7u{4#F=v$lWyM`9SD+H@a1&7_a_1{@=Usr-lN>!Ixm2gA^7#H=fBfFL45&S zUw|DP4Jcf7!J#2}R0uF+L7rE?XUkNW9*X{c(j7=d&B zhk4gQ!AuIGnt%K%cF|D4w|NwoLhC1f^-&-Qa}K+j9XjBHpO4s_-6=_I@R|Zva3cQi zxTIEyefZp0*Mh#j_W375Ygs$|hv`{TTx%+b(=&JOw*LYf+j5QN<2SO;`#KSb)s zLLgzIBU*i_n8p9XoJ0z2ni8fO1Jq7&VcNOyp#xJV^IY&Sa z6(^>~do=6vmUq+omi5i8QrYOCdJv_6`f#QPDS}11HwCZx*&H%cHM(t|z?}rs_trb^ z3AGJxe$p&)J5y!hlN27qLvzS_G;H=Y3yeH*_&zl!sLG?5CQplk%ESd9U%1@i4jZse zk_7u349E{=rE-f-YZg^I(^4EEErIpeqP=iOiX62zc&zvm2HUl;9&*@Zb}O(ZgI7x+ z&pFw1!K#~4qnmNLh%1LOdsPW)kDz++8XvtR4Pu3Ab6@1n7H&6B#iDk+#S~7)&|($T4p%Y*BrREoxntW z{EhNq0f|r}#4#Aas|1FH%`|EiIpo8gZWW(q(Z*x33wl@ZnC#S}z@GzLpSq{oG&Gl@ zeJ2gkMZhZs_HhNJ!?FkL-UB)Q#%Oc!8bNW%`us+XjiDhBR1 z8;`~m;*pHL9ztCH*Q3;~3g8L19e=&dC6d2p-eBD$g23c{^X@nILPKbX&qF47DJ#1r zTlBN|{YcWeGK#+-wm=~7CxygN=kV|OSAI=s`|>%!=Fn(!2(h2s|C#&M_g7EBh3I*& zdLc|L@+IAK!0K|0TSH?#la>^9lx|Dvs<0c7XF?p0!b;c##e<VAbj=y#^FK}VjP{4Hqb9eb^N&OP3bgmW83u8mPdeMaAKfiiT;5XO z5p#jFcIPzY`IS95xqJIix9Akua=oFw7Pl_^7Y4;WgSQdDNSa_x>^{0>`Z>cCBE?cz zaHG|GJ1O4>DE_QBidXUFvp~3+5nw*7?OIX}Yi*j9;;jYkf?P2Hai*W3VhUf{L3(+Z z@ZeM_XgCnZVtaE2pkk(SBK-+feHwCROr^M-TQraYaDiLfQ4j;LiTaxly0yDWaiS!8 zkAn?`KR5Sk$de#Yu>7Ick!CRt1uD(`<1o})q|OXF8=4zx7kux{Zma=hzIogFd?u^+ zI{#}y)>Oc^*))mJm+yi`BZBVVKYO5WtNsS9wr0BnNOR7w&1V6z`T}RF!TP-)(NjZQ zgLQlHaOm}m5$xxi{3lS-j5|Ou)gS)k%>!fV~k49A$+hbLu5K<)@znl z4oZTNhNe?--8nP;6XpW<9Jp@w=y9xoCk^XjKY$QWK;n=jIr?5uIONeMjIC_w2wd!# zb^;4Ynb$tBMsG<$7+caO8kCKREQyCg^a{j}x>6}E2;{@T-;V#7ytgq_jlYJN;Y#z6T4^+*>^Hd58LqhLGBAoHho=7|$lQuyb(7n~^S7IIY3`Oz9 zz4(`8`ya9&Khr+_0w&3v>9f%1VxJD5iuyo2Ncr#d84&jUJtXcpZFSoAr$hArqQmT8{2nVa;P!Je0U9IG_yab>I&1O`gsP*+j!2mJo zHdW_&Lw3`p{=41JqD=ayv&~AC4yVVz>FiV2P5e|k1L#YiKK%QgatznBHkp2YtJC7| zU)ho2k&KP+yz@KvOMm8n_2J|P3t&J1su2v;62)&p#$%lr?zxpOA*9X4RfN?~1~6NN zIJ`y|L7i~ub{N5#zK&eTJ%IWk08$oY3goDldFtbv->MP0?4qI+{q4UF1O4|qbcVbG zryDqZ3qRT~jKuh69)lG17Alg7Nda4TL*Buj5%(KB(yl9x@F?8tM3Y<4lcRklBHNYTJiMOm<5YxoRXN4r{P__Y4Y3f`y&G($!Tl=oLh{ zL;^AOds^Pxr01-RME_Jfs+M;=FO9qQty;&w2gan++EN;CZOkZZ`4pEEhwsgzv#lkq zRlz}r_(&IgYfNVWpWG-o0J;I5u>ZuQNdR7D{GBmw_o(ewf)EN>1RmFh4|eZ~?yN6$ zrF>n>E`2j@3VXc&_g&k3GFXT~8vS7?%!KMA=+keK-@K}IUPmy*bvB*sx*)eYY1CI$eGk$qx)I`k6nFzJ)iT;7>-ho2gLw&jBYQj zQZf%CZO(2_-8_V!5vkWIYf7dZ#P4-2u>l)DZPHH9`OUU?SCzVIE5i2ItSvYW3*BvS z1#gN`<5LKSoE<3zDfw-H}W9%L5RBW^A|GxBuyAGyQyAK4X=Ih+Z5{H7; z)B(*5u>5()ry3=W16k%j^Hr<4hoZW2Q-pEdVo9{MPP#%#cipeHZD(Xh^$eYEKkzKz zpp}MBqXf?7=Ya9QsER>kr64Cc_$Z8LByIx3{RGuiZD&VtVjQ{nTmK;)Gt53I3wxGYG^4EfDD}*3jcQ7f(BUTmr$7QM=z0~g!BpO-q61+PqG=@BB<%MjrLsTN`Oi6->!^PUt!LvQcN^TUw z0B3VB79oaHHKAdRE%l-7!mGwk3?V>s$>0O^D@h?;8`M`{?I5B?2;WXo%DBdISeE|b zn3g?Yj5;bZe*JU5Mi04fbG>=1CJRJk(kp$DauA#k?IQkP?BCFjMGACkikK;KT(|EL z*ir(aHyg zd7grxp;6O?Qpv2e(&--i`wexmm^y@NE+W@04eH9S0AtCPuclh&Pseg*quo;Up+&uV z#%8gJYFYm!lS4w^jD9|iL%dZrcZd8dB!jy`NHTV#v5>o=S(hy!t;wTJf9ei6{bCGx zX`)!<%#tdQ!HsPinxOz~d*_~9>Eo;0TO}X{J65%vo4@+qQ-TnOIWYdJ^rZZ8ChQml ze#aXUnK~Mc5@QH)mZR}qMu z8S3uv6=Hu|o1p+CFRyBn(N8=`dQNkW4TZ&Q8Q}jDx-1mOXo$k`v z4d$23t9=?B$X)sz8z8DhZw~IKkLIvK#iOgJgzXeSYe3<=rCNMeXr~QDvg98{x^Jt(t5Y?4Fzy}D(yq_aFluor%40g&V z?E^SL1*1ck)i`1hLTCIqd8nFJk%MmJbCHxzjYsvv4i}|Jg}^z)&{6tYilKrGy+5Ry8MQN>6lm4{3|R-bD53G8m$TlNDhp5Pg{Vbr^|)mAeazOlJ> z0rw)HAIqda;fLEFf@KGlPT!Yp9k>~hfUUoO?a;xT1^sP`5e(oL-wb;Jk%Ml}z<~A5(CykMckBlSydB^ehp-*RT}H@rRj1?t9-D&L zBO9H~qZa_650nJ;^=V4HQ|X4Aiz1l!sVXy8r2YtjO3tclGPtxb4m)M|5m;p4DBE;I zC@a#RH9%e(ITSVcxhm*#dX-XqOw2yk7quP+7XO8x?uyCZthJDvSeX2M_wPm%I!;$9 z3KKJV(UREhQqc9pR}}1Y45)AD$ktGKYkWz_X_E~{L^LdCY_|fHps6C{y1Bk?izXgA zNT&NMYd1I59nSCFr^19Hgxg*X{Z)QsZ9e={#0zM^+oFBr5DwP+<yuqm&zz6T??dFJ zsIq9jBzpmf(-Q~`YYNcul7TDKFt-x(nF3t`6`bS z?2;PyU=&mo7gj6;H_v?An(-uB+m>PWD$|Ajy~2_&U;uY-;6-roooV9Kt{hXiV{BnX zPRdb8fp49*1Krr^^`R(dnyVn4E`1D2xKsGVYO2vbsTMsAymLt0*ux8QL?V0_k{6uj zYBuLpbBe9Da}0T+7M-*!vxp0HrfgT`+{)fNM}a-?brqHwE}ieTp!fDXJvUb*7_kp0 zAm_`$xQ^^`9acLL)K;4A7QV6Rt#b72B4@b1w~5qmHxC z6m+{j>_E%z#JGw%uM$PK4CNxV2eIfDs*f^e9BT|rjOggANo1RAQDU~!TidFO_BN)} zF@UzvybLT>Qqe88G1$14Sz79$Z|m-G+AEZGZq8&}f(t}4_^BrnT{+a}h=(HKHA6lM6#x1y-=4%vsuQV2FE%et@W+0Y>lAqJEQu ziq^XIO)Bg={kE9?75hv}CrW}%dcFyA;$HRD*6Soji^NJ>qJC)TnTx1=Hvz;dLezxE z*P%$Lhe;gc+3DT7g7M<(Li+=;Dudp-mkR?*4J1oZNR+dI_($B(CUqo>0c zfIOgii5we}XVVac&ZuP9jf@PRnpP`gFZFk~jav<^h$?vgtsQYPY>1L9X5nRuger16p`N6g1K&O@Z?23EW{;<;hs6i)=x=~xzR;qFKY zS1$I+W0NEDKf~)QSst24N=~(C8$+!8xO+i5QzEXE<-_C>>wmE;Y!k?g4&(s2Gu4cz zYx>saF(L`fb&IPAe!Svpm$dv%j0OiK9OHDH?&2uM!(DvVnPBTq6=l-Z_oCh*gJ%hG zRD`S@-YL_y#YW({k|0K&a>b`bsv|{r=umjBDq$HUYUvg8x{+{K8?=RdxsEX zy+dAtJ!*Lq5ll_VCPipR4#hdde+51)62xyg}qPLVCZAd1B8qI-&6n zij2RAd4|(Ich0xPDo!+~zYdxcphQs*9a3gb)>bUP{%MZrAq*!VWHY;GTeSgiBI zG>EimPd+QqEJ8FWvOiohhT$M$M%)`OsY?g)-ox&{iHL-Jn3lFu#^9?#P1g|3Pm%4m7YDkj*Xb~=^~Gv!yQa?7g9V| zNj_3ka6}x(l;GM>%R!sA>=ev&?iAKI2)`aIR ze-mtZ-HZH=IH&*q3>*0v{*JCs;eq(CYy$nD z!n->?=!dZD-qtmY7=H)~mnh~)7kZgO#~!E6Yd@koBKo{)#O?BtOeHn-Jt$$whwMz` z!yw;G7n84rOLe6I_Q$B`0xAJFuiL|z2Q%qkyII;=Ct)nI4VI-dPA{*SbvQ-~NLd6&-RhBBtt2ApDB--gJu(NgR z_Rv4gxYU0T|M1dExTI!W+l+mSrc*QXT4}Jf$iX}FJUirY*O%`;Fx0!0YmI^}{^;Vb z8ZB!%R|qf=Heg`tRC20F5J%6d0%CQzke&j>Z#`S-j@d_T8niDs?U_=;N^){CirV%) zk#M-p_dVU)VSC+r z=ky6Rf*E5Tx!Lx69&9#iB{n+?vQS3Rz7!aFQ-`ea?kA&%{SbMyZI9HKmj-TH;iO2MdU8MVKZLkGQvVlFy*tzL=*S$iM=1q5`SfIouT@ti z+9xL3YtP-_4VLx|n)N9$k5eZ-ljs$0ph`!w`m_&{J9XHr2EeR)Ir!ZNZ88nsl9ee_ zQe|w(;P8Bru_Ec!>1az~X9nv5 zN&2BAjZ9Qlc)#xw%pMRRp5V#vBo%H+Uzp`*?-He`>qt!CHBqUrWdRn(kp^qQ#Ud#| zYaJ{k1_jF-3x%PKRlCJ$ZqjvS+w-zn_V(f_$0cD-tT$DM#Ov;~)xPGeBl!6Uak{=f z!lx@!Mn?YWXv9V#`VyvJJ7HQaM#9hx&_l-RN@33#_m5LQ2Mn)-?M25R@BLjD`&nGY zauFxQx>a$Qw=-(r)EU7-+~K&|a>%X}R{3lUP*8B`pJ;9Ru)UJVT#gRsIt3z%&WltP z#i`=hx|TQ?OBQ_-(@w9;_D)N17$`(9?6rIrb+u55T~J^JQ>M_h^7~Xxb&12Cq3UB>sJEQ% znz=FZ!;wN@*YXrs7@;u18-4& z)Y11l`^X?<{FNCiJ*ERRMpSM2M3wlKwO^Gq+=L2Ukx5KM!gxMABFPw2$0mwg-qVaMpr1S@0_`5ggDBn zvv3F%*mc#en_V170kZ4nrl!vQmeh}ZePB89(WT$k^=%D8;D2K@BXlnPXeE6G+2g1Fm;MonAmGJJSyL%EvrPXM?LBh4 zASe?_>*OufD_{l6wcS{}TfzM)?`tW6QJ8I0HDmn>u=fvop;S~?3LyD$IX)bqK0@Yd z+-Ne3ixkVx6Tp-JW%#?D?a{62cs6@9jDL#fm*$EGgpNL4lQB`Mtvkg{_<@>)q0H&$ zcCQjp`(lrxgav*vPR3D0_kua^1bi>A7)`HC64L}p*T6n@bE{dm(Wb|vGaz5G+%vk?r>F8Ub>Js~7hLWCJ0glJEEKb&KP?(-D7i5Ukl)Fq(|Z>F4i9RBxAbxaH6T!&WvIzuhefcyvV&*?|~s2wwSJkagI-7J+e{{x-98 zQ2w6QqB+qsU8*3}Pm1918mxZ=;A9>U%D+n_Tm#CRq3Q%|I|7*-aB}vqp3-zqVH_b^ zwRaF`lnn>&dJcO`n?c+g^XXkC`ymAq>>y zQMEL$;mn_r#$f)YPeib9s+!`)9KBKm4iOx$(ti)z#c~rYFHvkP4(a8rjU5|j_||!- zZ!7Ns5ZcM=8M$1BST0?_03%|UC0fBfbV48BX;X9lPrU3wRVIP@3zLf%boDfQ`C-MX z>q&fT&?|0IM6YfS=(yAKsc3oj0u6qrcrOi!+B1Hfy2#Dwam6qRg5sZ+G6>JWFDF{O zTP`bn9oSFVKuYJ&Y5Pc`;bzUqTE)_0D8W04tD|4$KVDF6So0O8$b`+$P@#psMG zoiA6+7DU!nx52`;+O4N6!WaMMx*eX*2Yk~g*>2>?6r{;7uNooLy;*TwkA+2mJ&(cl zJlXsOgm*lzAAWRYib1BUnk4XJt!P6Pu6o<9(|z+bY#!(fH_-|3cOQ)&quOt6o%f z_%k(8K2SC6RWr^wE1T~&ua{2;r@N=1*Jfxb~2vU;US;s*aj15n;?-}XB!g*QK5QSSQc4ciX=c0 z*%)TCtyTc>WeQCtrk5hoZ1vIveKUOk6a;t8ir?L#^+P~Kz0F^=S#pB z<`*gw&CG6w&rg7wu(gw%>MV@E*lLRJy}dtjsG4gl9+|bXIeTfmTSwOFgU&^H!?`_T zcXegJG99?SoU}d%9K`(^tVYB-(=2*=0P0OveGJ%SfSl>s)SZ8WSjhJg+cC}cqq6yY ziO@f34zThM?0aDId+)w~)n#_QmUnS4HtFC2I7;B7ge6{z>`^RkmnQ+(^5uSR7$;=z z(T_RMtMfWf}|75kbr{|$hb15gPm*2H_H4$<1Zv{a!qV4d8&-EmXPJWMYGHwSxO zdV{t4KS|K^?upOA7VxUUE1>Zs6&Dr-*zZY3v4Ce%I1VB+LegFC1CYdgENID$Ev1c zeZUlDNSWQ$)F%5mpmDVMu-YyZ9_DHW``b9mHHPiUtAk1Q_!Sw{VY>AHF|#z}*tN8*|Zdf$l+9cYT(qHrGsk zLpy~qkpFV?Agr0Te?hI~l{eT$0WGi{%#|L4dXOWxAu zF{+?MhN$cRn6i0ExOVA!ZeRHP`Q&6DwohM=5ymRi? zp1zgUS#<`dj3F2md{-o>K2g7xxfgpG>Zg|QYY}BgJc&ecE`X-;@$lsG0H=3aRQubr zoE>jW-Vf|d^}mT0zi=iH%YOACo^`Y%ZRE#GLkH5vWWliB(=KWcfKeu@@4P-WfD1Qx zYAj@9^YCfN%$=yu;^Yhc<8yOKYPFm_nC<(8>IOe)YO$|6r6x)8K|n$eGd?yZ-~2cJ z(&pUMTzMc$DVI>VE&5ONMX=BcDD+BkapkJ5|TA?pgS_f zi{N%8hm^W-E;SiB(D$)*<0RSy(@PEIRtpP11dsYL5Z@{(<5wU2@6OC%%(`&X>RdeO z1<1UQ1uDmJtqu?{&3XJas?)=EF=pWT6ELOWUXRR&1&>9Q*(-DY^{*TDU7+*kXUBoT z&8tRccWi|J&?05`q1={c^%q^8NP5}EOETTX#U*BhYz~!CotRLcGmioJXPqGbJ0cUV zo-o$i>%oL-`kXS{jUl@yNfsmN2@1ZV)Jn4Pf=a&Zn*>nD?_Wa7q8&E__ z&N1&_6dY%0coZ9bflEN2JT9u?i57E)8xOZ`HW_{opTBE=@xc-x;R<>J6vY4`^TBcS zEm`<>NOA{E^|c_uiJ6`z3NhUY=v=yQ6Su7YeCazx6e`b_X`GI{!f0b;Wo3nL28G|D z2Ad*Qd&0L04A)nWtNpE8Z)aUw3tL_YxqbV#8`vJgFmu5$X}l~faz4C6j0`KGD!l#J zTZR0N>kk5KusVHdLH19ToLIT5S{2HQ5@C>`^yKt&2?xvFP%5n~zM^}rp-gCvjr zxYqk6ArWLzs-(-ko zE`ctjuKw_i9e-xA zEt#FRtpyit`$HMaY%$$|kAMk?8rvo-*AB_S?_;dzFKl|Z&Ag$rSRDm+4^%w*%`uou z&g`@y`jBQe4H=96iL#^1G~8JRhpZr;9}AYLRO4m zc@FflT2_qP*Xn7m@USi~-wP1NgoT%*6k7q0wDyKF4DvU@I1nHo&po>ocWF&^VrkjQ6#PhP1k zIMe;JQX~-;2ubhEvN0WJ{y;UjqC2oYvvqjUE;8=lsiD4ZO~a`!o3*M|E)Br}+?!S| z{oHCs7q2x;qW%cnhkG`$9pPc-6g-_mJb39M=%i;pKuKJ_38U99gFgl|uZwD@INv~` z{R?V3vxlolyX^3cPJ@Pa@P&9GE)tMEsc`Pg@Qg4x@y0F7G&R(|-ULh>X2Rr}^?`fp zKcF@wqw3;$BT2CfCwgCfjK$+|vh>b|gV~IhpdrC}RWVPxdgLC1|J?9`62B)W3x8)H z#az005rX=3N)oz3Rjlq8`9CA9M(>NRD8@XWpK)n( z$`N}+p~&q75^qnxeLge5*@vD;6IuOtx+zmVo$Yk~{0S<-E6X!d#Ax$pZV;n+@>a<5 zA4=@qPyL}+I5>75t3x+lM3KQ1C()(N0v zT2J}Z{yWF1PnD3M&jQ^a!y(L%=}=2@GqReJY(7IJ@#z0K3hb+wd%eB8k<5X7eT1dVC#Da`k>#_o`Tks*z2 zaX0AzBe;8a!DEyZAzI2+A1pHxnEMsmDZrYs~&H z*W>OZ-{7X#Hhsd^dd4QdRDyB>d2k8M4*Po2z(ABB1?sVTG@nba86ymEmS~=NHbgc@ zpqbZ8T48}alH6nZwnL<%l;)Xfo=IVOl3y^ z8=>0ZXFOcMz{*+mkgVd>T#fqlWNBE!T^cGEw0MVVbF?D!!HEfFix3eQsy=qhM$O=1 z!9&BfTVEHQUs&0D8j)O%GAF2Iebu4u%nvwwn1U&$lG8a*H9fQOcbRAniJ(_v>hxNE zjrx9_S#G^yi?^QtH(ew1N9GWNdc2^gQiXd(EqY@VX&-j`HbhjNCpv1mI=pwxe<{9O z-V$*v<3n)P4j!sm-3Mi)-1fv=(yHfoX3fA2?oL!Losje^P!}k}NWCD}jjr^P;(RMF zeI8;eC{(vOIw?q|`Ck@)mN5VYlN3;DcJ$kRvo%)zir#l^Jc(Jg3pgQcL+qMH7 z&f~G^L}e%ka`vtdS|2oEzd8`@hH|&0aI@*rgR1g*3Efx5BJItXN!Vy;e)NAmY<@;Y zsTa0|{-19+^DP*JuN-RixNl=6cQ}gY)LIT)He8ll7XK?a#TQ)tO z((}JF*WnUJeDnFo#7)5Cv?mR!ACRR7>`1#z18=MN&iLbvD^`;4CZz4Hp@26uJH;ny z?XS~j@rZ&RJ0#toje?*EH3bM(Jg;sOFdP)h&4=7S(EJF$>Q%V;Pezn@9?m+zuFj|k zC}ka$h+IB|zL38gI((uz2E0UbW@36KFVmg+ zt5__Qe8*S4t|;B7T^W7-{U@;b5OLKH6-_;#UaBy>A+v*S{1@TISyAtz+0uLolbf4E zILBvho#phgl|LKn85tS$&l7=7TqmCYhvX#u-z08X)Ca5k%Z-!ZV9R2)+&BkfY>uM0 zht}m%op^gAzL0k|$Rj$a+DhWEDjNN#tku9{2_b}FtCj}`r)^(sw_ z{Z;pT(QfAVvsJD_>McJ>>+x!ky*2&)u6CUhW_r9lB6bJ!GA23(MT0!l%_MW76bVH- z7OBRTg>at0-RLo!Nv5TG^qTGAL=XObyfty;LabN%R5g64jbN zV(go>jW%Meq}im_6%but0@ZNM*DW4teLkEZTn;JAxv)A*D(0qC=5JFG+ zj+Pv359o0i(zA>WxWTwc?olZJfEnzI3Xmd875Mc?iJ4=hyl>VWgvl~WmLJ*(V-#|& zEGPerW~tv?U&?g27XIp2OyiBIjW8K|00b!YCSP~yzuf~T7g+`S!G%CN^eyfP{HWD^ z@qkAxHiO7PwWeyr*%Gj*6~Gp0B)CvWZV=)H~7r@jIIJ4q!&94YTg=*P=p zN9uU-@bpr1uxv4+qZ3)kVnJfCpO6k&LF^p@Q$9F9`8_B!`$~#{7XG={0RTPA_c07P zBdEh;&xV9j590r~POA0*u5zQ)REeQF52wbJsiP!EOJ8e22?lWjcm?*hs^;o zy8@mZW}>S4u&b?ZGsVOEjqmO=yw{y#$Buf3v)fivb3(_%>{qP{c!;%+#V5Ah_HO9z zbnmm;y}B_I+DE-Nl0(rg(OPXaTnp`Zed58MQwXQ(9WZKWyub9o+QgbV({*7#Sy%c$ z^jpzM)mV3c)M*q~BRjdmEHGM>PMicW2dr>Wcd3V9Yhk`@CA6Jt&9&~jwsB49Mw+H7f!TnDu*|9l7?5uC1id?^Bnf5qLKh$Y}w)DkL? z>MKa{r=lAy=kt3Y-I>f;M7FrSP+8)FjwgP%wWMc@(@~VL0W4ZnFAqBBof=%4kxon( zU7O{F8)0PHy-+vDbSPX!W^HZ#h5Vk*SskH`UNO+d|g*G!Zs7QP#vYYDUMz)PwB#{)^iUv#k7sphZe@OQ=!(s6^jfb^e z5VOZOr(O&-u3rT!i|sJ+RV}th_(Y^Iz050JDVwg&k%YO@;_n}0(`;{~*V3a2RrTKI zy^pb9mGT{pe9b65&!BtD5)!Ejra4s@^G)cYrvY7zjwI7GqWv%Of=>uRM0~TJPs1*= z{NU2VGwU2F`E#=eALn}|X#K1@`~cY|>Dera2kRoczCPDC$Gf^D(b+WBLy7d5FqqKL z9icRs9jQuXkE=r?0Mr#KlRtKLKJw!zfk69XJc_qIs5*YRGMfg*U)M^EW2r7@FvbW* zMZOnNko7Yp!~h^u?H(A2%3{nog+FsbE+EFeq@s`pudI9s=In23zq7KQ2Guq6)oL1n zgOghc)!M5kUH$BdkF~|)bgc)EvH7LmXj+AK8w&4gsnQt|zU)i&(|TCZePd8_n@W@| zez$6e*>3YkkMAS5$<_}~!&+BET2>e1qLER^f$Q`hDTgVUKfbh>E zM-0YE>$@!tgvv`2yHsCQ-Aq@Uae1Gr{gJ1Z zJ@AO-n0PN~4LoPHXHq)Efhd^mj^Nks5BNBHE=i)X^r#uemEqqQ{;GnLlCIsM)aF1U zO(votnL~%-_7>G^3q+&rtqV(w5{Z8KWE!WStn^xiq*<_tzB`>%Qd!+uU*+R@|t z4R?BZ7yj4$*nC)xBLPiY+Tb|ZASAo&JMIf+`9FiqJB~*i=T3pc!EW^T<+|W3T<*^! zhO3V4sbcc_xei*3vw>^BHtJ^ebD$KDwN20A?SNacx#?-B*0(<^5L=|{2}UFekb1`! z{L#_J#xtRGK{pe%!l`JY6h0&*@)V#qsEy9(?INJ8?xBDlvGYVUETT4fhz*KiuKc&-^ehLv3dMQEy`rN+0tK}T~ z)_E%K9CSU9TglLXDn>qh>mPPHP~uQk%>T4(W$(jP);WH}oUpnYm{OjeviQSS;Z=QO z<79g2j4oP-c^!3=Ut7}Ip%nBY|i zi4TJ82_8Dz5!sNK!doZD4{n?Rb=cd8JyKQIPjwurrbOGRnQ5?#|93NIvAC@DOPjo{ z#nzYtnSUceo2}t1@!=bfw+8giZ^q&)j>+h>=vusc@}zh`@M z=rs!2LLEeK&ZPTgf3K4Z(Z`&Wp9HY@*BCqksbIeF ztrdV?iO4B+tOkaR()W2@ae_>S`VoYr6gdN{{2&FD>7^( zE{>0iDtzfHNxG){5W@ubqhEvT53?S&gTr|mCFS`s$J{UeEN$l4ma#F*Epnp?Q7&M5#+c=W-iaGYj9GiZqVXJVgLafy0O@=U{5JY zCJ-=PV>(?G)Y4KuLu02oR*D=w_{kwz)hVOa8ru}URYpwi&cAB4P;J2kaH~3Sdb08X zX9FPMF(oQ9-$uAEC=~=h!Ls?~fB^w>1&q~PMzRC@YKv>o*OLwU$N8U^PckcuVenMM zcpA|~OETNT3Dj)WIbTa<>X!#lc4uTF#gjzR-8WY@+9^GYlwoS7YmS%Hf%*z`^w*&6 z9nZZ$gzr`s-kg3vKHk{UPrs{qS99CgM(b&r@ZXGMC;rv4YV!>b+JyESo@}t~n5s>| zkI>)AY|YB-l(A*wJcWMEu7Y&-v5cSkJ8QVq$j8FNVO-7W&ROOM%APcE)0_2Px+{uD zT+a}R^x;N}aFjF@iI#W^zO;vl^0%tN)xg{JO+1J;G9!}(h?ZgL*e9vefrpZbkSLjA zeP3M}lIG!ZL3lR8y#t6?od_0!`|u0R2grcj)%l|F-`v#NRJ-Bky{B8hd6;|_3#^>x zJL8uRAtvkYYDB|A5aUtl0nM+Ks0)lo+B;z!o)|mPjt!F}cYK=+;V6MztZ`s-6f$zT zY4Lnh&%#MnC??pc-_&BVA%L@Q6#=WHbRxRVeE1!x1b}sMkE7d5guMUFg!r|9)sL}& zDWQARQ=7kJ@H4Vy>gRDktEbg=M!HFNvD5R5fCrc8IXK?iTmE5QKh=?zHuj2x`Wq~5 zj1cr-e=9Em_Yb>wxI71pDIy-5LdNpG-|7FNm3!Sq8+N^92R)+}wB9S(`4He!dh@^6 z1xkjGJoMU7ZWvM`WBl4K{|rL`rxoLj5cui&v(Ui);}`@V3EH+l9BuMs$`d zuE^#o2T9MIWI|XLG$Kyq(CvhjXwUL?8>F~Bt0|RrznfGprbvH_Y*+?AX7w=!sFDa` zb{DF#;jO}rTU;doejIwJdfX?)`9*IP5VF+{d{@rxqml~2_PN$LP{orIr&L^^0N zPZg#SVsR+-Io=xAw%{`L@BleF`v7l;+Xa}yWF1phKF}$(wv-rWgvhRBooD{6outp! zQlKRKvt@%ytCA{Jn+}$jEeFHg7#$&W=CCTYC_N7NpNxJ=Xvpmr)cPY`LR9EW5;bEgF`_CRuYmE|kDRK$bs^={V_H1UIn{hsJc6OXOvy3xd zn4Flqavs2uebhVV)&D27M#*~SDMtw)cG5q!ZQ_rweOx>boL{{j)`f`T8tSoQA_o|L zOKVH{lnm5Z=cLCW-u$gAbV1byVKi-z_0Pt6+ntB6va}@`subRbhGE%_Vhg7DavrF|0ia z=LR*YgSTYvy-2HtuL5gn<9`HzIc2Kfi4Dk2*2h&%IeDCI;A(lE-u^0 zd)qiw8$2pKEcU?gu|&!DI57e_R!6?WD^8NE32aWE?;L^fMrskl2KmTbpNuulEJhG# z6`ISLt}F&pndcQAVSFHG@!k0$?{7DmASw%!4taxcN1)6_GS%3A)>XwR9-+6xa%ewj zQ?*0d2}os^?))1lk8+~wEwgXc6zFr3Nh~%Bsmw%;!NEmOQr_}vY#CpdY>6n7x!GBs zX0>d*^=&!a7EwWaQ_F!KjWmce0u&XR>gtZhtksrAK?-?bNa*p!`LX{%W#Lqu-Oh*| z67({krq%q?qPhCz=F}#XfHP@P$6AT304UoS1@sOiz_R!-2DKZmujyO2-nitrPr$eD zEfT?uumIGdqfsy+qPfpWvqWMN5iV1#H9i0yf9sBPLFCzTkPJE03vv$hhhyf5*Y)*> zY490t={`m_U1vNJ1Bqn+)Xxg>4U+j2#tRBt9v#K}Km{oOZ6MZvT}ZL3?(@eGtrJB! zuP?;5?D|PZ)7%#@rjW*ncztUGwnY*k&_E?m)(AC5`|N&OWw9^~Kl)NYK=yL_6&dhu z23Ex*Ml~KAxrYC84L8C!2T#uoH@$AySRLN@4W8+4oa{U}neZY{>%#8qPxeIn#|;tC zs!Me}UjGJx5Cp4G;5AMZSKQ0Kntp|I&iegTd&2OG>+y`vXP@po6}i}-Y)dqn*`aEy z;thR5kkKt#gq%b3m2z&MF4Wg@a8w`B>kvh4A_v&(7`Zyja)kejQ(VAK9 zj{*$3G+=(5Kg;W21XTL~%jwY<+UV@mfL&pH>{QA7LHB^jaYSVhkhvcI>RhT;+pmzT zb^m!-!rbYUemDB75&Zl1cAzz1T-3s&)Hs++E-p>_P5K4~)s!Ca*8c4iwswN9p{j%S z4G5?JxtrmbUw9#GEvi9V3I-J~)tv%qD(@*a?m&((_SG*8nT={u7?(x};-XL*Es&qt z+v=}rc1GXM-Jyn(Fq4@@tf>`$q2@hka%@cNT^P1+8w@!hyj|kQ^mIn~&c?br4gOT< zt@)+tNu572Cp*46)l8X^uJv|mc3JgaX8h0H>Q3LCDO>vvGgEh$sC!%td|#nrA*i*m z!D^55XN${w9 zL^ps>o&NZ7dh(W;q&yq}AmVH<WeLIqg=$#UjekywBw!>_l1baa#P5@M#cv}0o3bvO)JO4#Es8+?uDba^FcehcW}@}A@7+u@9&0< zVOVf*C8yUaw@P*GMfjABk&}Bn45frN*eUxAy39B~6C#A+rMY(qDqYl`pN^^981-GB zp!9y(nw{AMDw}Ulh1a)B#M$l-$e}Y)7yhDb?|V5?rU7+biHSKp6YA27&5w*|mGomr zQu*qh&`{Hz1EHTYN~fZ2qXp#Y31#@$wDPJ4L@AN1iElA);JfJd1aAJl0Lk1RRjqJ{ z$WEi%I@J&`xLl7_x6B^r?IWpUXM~!6CG3gDI`^BJM`^rGthPGuO^_Z5)K%rXH#{ad zB&%msgFJn__3x#RdvhVI!2@}o`}vyqR%TW8PlNPY%$;V@Y-=SFX`j6!4eXNeKk=GW z54tKGNB4bjAEwq(j5RyJIJJARR^nT=_(`(3yu(ytGRq%Nf5~EH1`#nrU(Z#1=zPhg zhVnwbSKh}^*fdlXmiDpaeHzE?hA543cu;Mf@J zKvYk$CsOyhuPtTx=ZoK-Wm9ImUy5AsgIcJDK6eO(cb} zL`6WHto3L6VvIo>g22kAC}V&)Xlqb2GyLD`49J4jk&c5$J zbQr1u2kK5wYu&=bw_NFDD4{3Ky*Tf8EeDtzAR=_rMY6z^j^v=!!1Me)swm?MSDR+n zao1L~z8yz~L1_86QAUDJd=_h9Iy&D=qj~w^!(L_6nrq3BDV7+3VbDGt$sG zLWKQU62bRI!ad@yFV%%povqnEdcY1MwvFl{LR+Z487gD1d+_Occ6&rW)k^6oGmaE` zz8^WJ`4MlPODz;tW)=ql&Ip(-1^diA%_=Pgduu!a5*ZV6bMT$RMgfo8bOO|}YYcea z-u_aHhK%U~U6cT(E5tb54sR=hUzVrceNdqKFh5WoYNnL`yu^*c1i6i&wt^VX zX}ZI1L~$pvkX7o963a#F`z^|-!)660G(r!#6U{Ows?_`6bR z_?zc(=;rn@{c#hF%fu7VyEH59aPv^D`X4#3se_!JCwmV0 zTjDr;QDZpGIF@*pvzn0sRIM;owjkNEzlt-k9m&5C_aEa zrgLW|Gk`Ko$rzfxIi`u5VTwoYnfYF?Lg;`(NEnV2LS$SB?hXoTEEb&Cmo9hG^G)f0 zjy+yEG+R8`Tq0&W?D~}ej&6|xPpN?ZNo@hs7A$p?N$C3`m0_=}e+iJP$AewY;$L6{oM!xv(NR>A0Q-9>0%{7A~8?2BB)o$;zNzErEazY z2V!>kHW-km{(I~zaB5YMOyA=y0`sO62XS80k&5u`4`i+8@M371gXis zjfoIYi>~%kQdkxa%J|ktJ(}9&B?XHNu*Otb?ST<7=(pv?h$i=f1niD0wJPytsyZ=h zhYB#vz@VUZ@N`!1z(zB+vt^@{^=JHdPOtp|?E~B{_}bt|!x-bzB^O6h?{dTZU6}O4 z*;EZv8PAe^krcj^eIO^L5-?4{ zrcB+s;f|@Ch^&>1#DX&Va=IcK&QmWaK5-ELwYntss~{RN4))J2W%a>Wbcg&~99Out zbMp0Mkxc039V_{M>MTbfF+To`>Mx*q(Cq5NJ$q|56L}wJM<80lG}qrEz?*9P-_rDX zPnStU@mT@3((OyXDviwDHr!~D!Uz#FB^U=4h1?C-Wdm{1Ys)$RILyv2rCF>wMlxHe zwrJyzaM(g?_-gyszm4^x*2bf*#x%bW%J}GySH>^K+|%6yIm#Gdk2!&!7@L&VNY6LL z?0~Hga&Tt^CEG24ntRL~ymNtfDHLcY>Mfy1`296~d60lD$q{n}_RnRP49y|pl8iHy zSj%EU!yy~gcaq!pUm&vU148?|=IcuXo;=&;S|O>>TV0B!Irlc}ZnK4fn0;T(G5I`i zE=nHEh$s9^FcwS>uY#(Y7wGqu2Zj7)nhq|yI8AAi8o1yKBoo&M|AZK5a7wD`28~b( z@Y?K(zJ#$n<#87^4p7zeT)cAIft#kY7Iy0RaRAtykoM>BYga~UC={+XPnsNy38cuw zB?y-p#zIgxi^cYXi0Z05ulJG~XdMY=*E17fPOB(!?oHNKgkK_&eE+PjI{Dl6@9prA zzh6>C6Gbazi;KN#YFg%;u&O92g8cQL;)OcZ+d(0Po3GJD%aWfE;cWXXz9{VWJ5{gmwo7p zkj_j1XZ*~6Fy@teL}fEHPu~nAj*ZnMYY)j^%}B9b%QzmE;HwB%w+8AwUxyzbx%ZQ!CI9ZpUo?+9>JkjH&YhAH2?dFMqQgL5fV3eK+7=zd7y_=y-uK z;!`XrOh)lCX6)(4#_`Qz!}TqM{T3K0hHtf9+60=t1#noI374vJ{94rj z1=C~9i)RJiO64jS)*KUigR-+mZ@+vP#e;%*WNS3Ms3v}6R2Ue{hd1AcZ_UlEY;BES z(k5->b{PV#WLP0USg3IrT0=NKgC(x`Hs-I3)YkwuII(GtGaBYI`bmy_b5Vb+dJW}(Q~ zw*1NTd`kKNYRn~#2d3pU)C{6H-nK)XV8vx{j=)~kzq&AyjGQ7D^VxS^K%zuVD=UQG zkekpit-8dH!yqno9@G&4rhWdyE2XSY{@;br`za=v4XEQJb0I_*$AgFz?!O~hLq!(l zhpoB-ro$HQ$I{J7s!41IFVlMKfQT~IZrOZp0^?5xvsKQO4_ zGUy_A)Z@9lOWk~ncXcUCwPMahdU@u~Fs~W3AYZvUr5rex*=?G|yfeM}4LEB6c)9XJ zCqHOr|Fm3J#o&zsh;TfNZ;3E4k&%B_0r+YX!BHY{0{Wp##qZ+B{mU+>05#{Db*u`= z?Wb~TO*YM7yE(EjN{_D@cnmn1$Tln8lE5PwG021}h94|~x6jYL&yApAl&PPDS6%vDI_vWh*@JgOJAL8{pBZbB7a|1i}3Wqig6~{E% zd=R(9TIe{#@_-hPpNZ{Lc&bch%>G;>YZ;bTkEX9RU~K-j8-{5;kjEQYBv&irV_P?k5C_*rUmB`)DB_&FLl=O#bDJ#B3315y z4SXD6DYcy+j{O3Y{++j&5r^djCz91p50YwWuJ?{sAZYmPgYt zg`@pYwacgU#hePy@-XyGZHby}80_y=awvN9+kCqm}`tRe;)50|;3^)HhW+@khtxOfY=*S_Q zXfY1DI<+>sdFsGkSc|6|>WNPIv2wE8p+$%)!CI^Da^ z?Q+eqgy|zohsl$>khg=V9wmAw^&S(f#&oRYjjpC2fsNj%IYK+hM~dud^#0C zM-_gbAPd1pGW86(mM)H$EiD8EG|iGd!fsaknRzk>8}Hm%TwByhAb7LWmeKG_XPIFA zCnTUgP)&L)xKlv0Z^9Hk{sBd19FdSg*m+02S%0?E1S#f_Op0qtCGEo}`v2F=9N%lc z%Ow^o$8qMVn5o@5tt5bqMiu3UEd8F07tSIhX-GJ6CKsz}7At7+5l6$`dWuhglWB>| zDRPGwFYIG33%L2;2|8}FG~`jB$wZ-l)nogR9ilNH63G5`qbdCBNu-%lE}e(~xnbm} z$=t#A?%<~b!-$@k7yvsZdYP?^wLg^1J?l-M)wFRwDr9S~6&W9h%%kPGKP5UNR9`8@ zrQ+-NVj_oVf?-#{B62`iC6vLSU$8CKI}rJ6Hc{fY>s{ znj7-#NNQDk)E(pY{kpX=;=YNlm6(ZZN|LB39{D5!CdjD~=6YrIl&!T21B&p;RuC9k zS`Ymp6N!2~f?jcx7659TxADrINv`@!+dbM2@y`prwQQU*oM1bsIc9zR0CS?CD@%?JAeRZq_Z2zs+TOp93#iole!vIYT(f+F zCn4drMky9R?tXM%#n9=6@Oo&9hx25wzk*IX5)DhhW<0i6NbX~~^a+DJMd9T~VatD9 z9!bpWQ?w6IfV_iSw~H4_ca@4+I4_2WNWH?_VRjZcp->Wujbc0fxLr_@iTtkDb^n}d z%5j5R0^9U|3kPQjx5CgPk)|j*Hj;;JX_TQ?J0C!f=60Uuob&iFd&>m*#T08bwsv`( z@xI*h{S(iBV-Lf177nsk#!n0%Ty}BkB@*~5<0hBgQ#8VsR{nL5D|q}`ESfn4eti?` z{r-JW08-xM)2a!64}Y;^{Zmk=qKUfqDFlL{_r9ShGl9M0aq8b?R3C)@peDosG5Sru92A4lZZmkIPk> z);CFmm9fvnk5`(ddi=?K!Igr2T|8)#C<=^gaSzFG$idV}7LLU`WifY%vP}qHCHJtE z6z_zcvXQ70p8Ut-{#lA8S_Q>Q1e#i|N@3noT>~-_TRUiQu7H^?|F=ienam`@@Rn+L z^H>%3%CGKRKa|+Pj$KW-LFu|b>y9tvV5Z5bq~s+yEYeVhDM|C~)}Gh*Yua^c*{hLjDwgmlWiex_}{coaanNI!S#!UxZ~wF7;)w0+Ev0L;A(&*o8Q%BP9Qg?7pW-{ z$Q)#jRlP7<(gOh_D8-71NeQGeOZgMGey7AM&|s%7SMEd#89%*#aPoqZPJ0?KbDsrw z|F7p`XC6wyw$ZTY3*I}B2GVtH*GMF-Y#}3u{>8BHmqSiI4a+e=OJX8v4{&1wE zZF$gt246ffuT_vpqLB%GbS&`81kuY{M{QHaM|~p@hh1ZYv-XrGORXI~@}W{2sz8ys zswj`pemx1K;`)YL**VJ|=~Hk-7ZIx}+cKc**#OL>MoQ!hMzJPYN8EkzU&wUw!q6Q8 zU_jh@;VCHal0#sM?yaUs5GEn$F)@0iF8g>~NLGPa1y-#{JdLjU5% z#)f_;>Xf>Cst1#b=k{)VT6Q_D)JEHesL}?pD+J=y`zOR}U^uDgNp$(_yhq@i>i(G_ z7oOaUjOYNr@Sr1UY3;LIpe6g)eR}9l$zHr~9kItS$6G7SO)~@fAcVk7ucj5o z>?rNs{CB@IV@v5KM3)ZWYbdcT)Q7gf?tr81nn@pR4r z_yiZ~bb|QDVl*{rfjNIX)K8t;^`W zhWqbcKx6S#7>ZT<+4+j(`cj7Bwvl;#V+6Lt7}2~7CY$}?&Wv$lMGk|FXxd!kFRle< z@nT}e!Z+%|)%L?bRFrS@oOn^W7b&M;6^KRc+KyoVKximJL~hJ_!SSrDi;QuP*ZMBu zEANH*q`KESb;Cm#=2FbbmiN!tIl_GdKPds6tkQliw=R5Z>mQZ0-*DyEJpelqB1y$maK$b`b zA~B=_Gi7RCCj1cN%zb(=RFGj$R^ds%d7hU;wmWDZ#0KAM^0Gv_u}gY`GkZ!M0${yr9VT+W`kLlc3+ z$Vog8_{i@cNkDb+A^t~^;YQiJIh8K?SdzOl~h&i>O8ZML$RCg2nz>3c05l;ZlQ(3Dx;!!bV+frNwkd!aLXs;ORm=DSF z$dVv-=y#?Tk@^>{DqtdV^akNEon(?2kni?W#n8J24G)GGE;yycAk~@)MH_DGoAiD1 zCbmbDK_1pCL%SqkPM=ySLQ|V&U%`2oJk<}*gT4@=kVWOnaV=7M560YT&h($={d@m@ z09P|S!wcrjf54sSdR!H)aY*13TQ;^_e-}3YlVXG)iXDq?M!AWDYOO21vpl_Ea`y2N zFKctj>4yh%7rs3P#~_164juuFul1-j zU;U_LPdEjO&K5>*L$-TaQ^5y8?2?|J8(s*ujrT$G;r-%wIvQ*|B3?fRv75urzK1f# zr^dH^oLxT^1J!#QtN)w`#Vk9 zrY_n+HOuH|Sj)H7*AGu2vQlxIo#Bgy!^6X(kp{OmKcM)TC)id!-&G~Z!(?$57`_>V z&ixv7I}gaYNZ7B?%XE9TNs7FQjwdJGi?Oxde`(Jnv6jZoo)fK_HWgAlNj!94`jmL6 z2~vY$`&}gZ??tzWk?>WY@bzEs$HsIH#f+*gWOUA_zGz$@Y1>uDwN4iN|17{p>C8hE zde^hFwIB9)x|pL3n41ORn_ZhfctBeC&=3r!emhcK*r-h5OW_*@x)V7^*sI#0E8zTz_pK(9 z2V=5X9S)67m3s(jphi1^+)le%b~U5=F6`igUF_G|x{>CX@klZOkCafooYl!SArrvb z7Kt3ZuH88f1|1+CoIkH~z~gLZufBD6j9jNGr>j_NLk$^OSDH$^M!r&rhavGZ_`d>f zbTGfsYeAvFIiFb5nje^=or&17KFkj9KYJXYgc$zF8+ z<7Q0@&Q(OV@|lxI;TCiIIm8qXNpvh0DU^wwMEE4IVVC8Mk-EGb;URD%B#V=uC$ow` z6IQXq?%S6Qod@$@y2hqAj86y!lXPYZf~_y~J7GLN=XdZ-u@+CpP2sR@S1Ya0Tm?kf zue!VB-XbT0**kg&1;)xe&@!qNJGhojNk(Zk$ zC(&udB%@1mVv|mIg#0%9;cw^ce~$aV{>fN2mN7P8;sjm@;HVQKml37}zmz>QA?o|` zw*J=4l+NX>6#QH6?X7z&CxCRt>+p<+{n$totDb7g(PZ60hL)8Ji5Y}mU8)bFcYnMx z&7h%JpnI=6XZS6M21a;@Oqs1pmue`o*wyDq)1FV^~LkKL`As?X4; z!5f~H7b__#_fJ1mjVa6Mz2LA9gjw~h$ypMQ8AY|0&Jm3>r~;9dz@+{7w}=TpqBGX4 zp`xf)R5T77`qiK~wKF(dMWgAngy2g|rzy z);X#F`;-M%Y!i?=nD69Hht8TlI^Zcs7ZDiO++3BA5!-g6z}qu{S}mh!`7WE^)n(Hj zOnc+4bux4=*7eh3>y?V&#i`y=puiGoVY?|8?Zm^~fBm;UKKC>J=|;<)zg)u*L6Hgr zxrln<;FMjwhCLSPS%C*YYW|m7Qw&1gx53d z*FS0R@UStRovFX%<#uqh^n=A2dWL#h&VO!l+x)5FP3v>~7clyCPVoA~;-!t=OCpvt zf2xTX525I{dNo(U>QerTliot>?5!_^gt4@INeee-@`FP^gYT-%9y&Lcp1)Ie$%WTo zc=F_d=)0oPNFs5csawgD@!$7OI5&l?9*azI6VB5WObY5^@>N4DFK$VHB+fKoC>;o4cGoa##PL~SV@TQ|LZ>_P|5>qlJi z8E_jEReMEXuu80KWVOq} zhASY|EPY&laZ$1)e0KhlLFm%;lz`#I_eZS|*a35pzNOxg$$jBA=n1D@V@EY@^D@m zc*y~Mif_#zhElxvbmP}N(Da6_Zv-LbTH0=h{wN+}++W^t{~fNKW?qO#pmNJqc)`{! z3(I@(WWg3RT-5||S3RYY*5?F&6!1VKQiK&Z_wV1r*MoqKDo?X;|9o#bR#*oAiLlQU z`#@gKL~=XwH#_^eGR+PV#$a0{Kw`ozYRdypRE~=xAldZ$IjRT5vw;$N{^kGCbngF5 z{{J5zt-3_H9Lkh88#$~bL)uCX!_so7X+jj1ga}JH(^`m?(sEqnoO8}OC1i?B5<(8; zuu7<$3E$V}hj0HtySZ(z>v}z(kH`H!qf9>VsA~`X}dS zW<1OK@qDpxNPtxG);R8-e+tY1^O4%=IGojF7M-;3$pG9WpH8MSK{6sb{80+HkU2eZvygF5LSzqjDF5{#EEr}(FcMbVJ(S4cn7 zn;x(O;kUNv)}@{BY%t<@+e__Z(-7b00Ij^Y?-rOi)gP&Jb;B^LHs&vPYj>>t=nrWC zQGwy%EAlz)!lTLTT3+d|$;rj8i46bP!Rf_s-wIU8&}*k^AD&+5qMg?(T>=Jq-go`y z0CfCDqs+adw@XylYRHSKJ?GG7Q8u2gD8}hd0ZAI zRUN&Bc_SCJ{K(3!!p^l2R1VsvL;6GwFYf8q5o2JCnzatN4)0sIB5ml!m1iojNXaK- z4toyQyC*4$bxKT)Z%pnokjWTh74;p2e%!nB67XR8cF$NHV;HOY;t9qUdPRUO?>yu!uwzwFQu<-T6h~BT# zI#h(10uy}w!bc4dynx)xAGzRZns?yo5hhHlFWK<>B{dyO7gP9Nvx~+}^!xMmD#)^948+F>b zmE6&-n&8FN_HC9f;~kQU_LeC;GVpx-FbEi{Mwb==?yL$EA$Hk@tMZ3;B6RWJN*TXz zwupvk+zy2;U2G#TAL!P2 zeEdrz(XtOtvi^iL=-oW&en`n^-w)2d2+(U`iXqM(biSX>emN=?ZMy_ zGm7*}l~iVWhl{a&9^f+5Er0~6m_5$8UM2d@8zz2J#`65+9XscAIwX{g4)&<+F{a)h z10K4~uhD#z0PlrW-diU9cG-K>tl_PVR~N5? zQ2Gwc#h~9oDOXs}D)(T-1^q09PRWB4sSyW`Qlk2{3zCVrZ361Mn!ya@$B(UJUn2Z& zg&zL<57fKC1^o>n=ZQJ~N+irRIzW|7?EPqaUeft2n|K*|jY{tYtiIVTwDO{ZQ*|Zb zK44v@E9t*W{=MsU5p2+Q6*`Nh9=Wd>Cx76%1M>;cbM$~ugApPA0@Af(Qwur*aCRo}BZn0;66(}H`Sdb#m`j8?Rh2cf)A6xyq}ouT{YOPM}Iz8nVWY2T#V0@>FDWA)nr(?p(eY#g<0=F#!%?cw@;+ zxq>qR>QJzt+8eF=bHEDu(xy1a^&=_gcO(U5p9&W~_@;&|{`mUh`k+#KnJcFpC--U@ z&}h6HL5)jXtZi#?raW^-bbI78n0Pr|^&rV+u$&m#@$=2qz|dQAG&|Ke{}de2&?~xf zf>q%=R=z$nQ3a(t%IL1o(+a60(-l^__{gtL{h!PX)Z^wdvr`<;NI8rAX(`L$^K+!) zU8G{vo>c0hA5n+FX7fT@uJ0c7_quy<0Q|eNVfhAX7Zl#HdJby_Sq|7v1&ff)=RO5* zWW?M#%EXXM%0f!6mes+Grv-hR(?=Vst3gcvaOj_yOB;>SbBjX@LqlrcJe&J$= zKx7D`8cPch`T$hPq^l|B5%}24LWtj(qP`sVM}I4vAYTv=VNnX-9}Hb7J0-ZwJXce# zeGb0!c1{XRiu5+)H)RA~zQnIDk4eoIUEi2)SfA?nu>$ZJ6fAx7#Rf9)eONXRD+o;*6I@VU4K@+i^viq&tUZ*+joK$1f+}? zWE#Ouu(Tql)Ohe_s{*Y+<@9Wj53H2O0JTYV3Sc}7am=;4{9 z%U8Pb;sE;T+C*b54qtGGxVBR|om~G1un-0&E-i^tZQ5*<0$_dh_9zIQrM1mO{TggO8#j|E1h+cLTNh6TYfMZ~wWnr+k|WQUWQ;Pogqi7Q3C|HY>LQVu9Er>hVc()|{YzSUNT*YXS*_B-GF~D z3*5**bUFq6h$Y$stq(oB6VOvSEuZ}(a84Wp*afRhurgbC*P1#!G-LoBP1YQf!CdB$ z$gb3!FcoKZz?8ZX4nPN@RnJq1OfYmwMSB@`z3E+iP+Wb z*ohAey?ldrtYJ{@eEx2!x}t-$Yi&Vs&R+}1*u3t{@=6|&HR-<%Cc@Hb&FXfXOMd(^ zmN55c%{H<5W(2|u13uGeYg+P?w!b>z)<=8Zt&acvISmdRyp(hQ!jP6(`-C_GIHxL( zv^_sJCyG%!f0_yG2liB}G5i&qi+i?`-yUTA57>J}{;11QMt5X(2{Irj z_D*`~sFMT`oH;GCyO8hL@9$j-#Cw%js*dAnTcsd*R9X`C)~`-&m*mG4bCvJu=0Ywq z&7c2^X{Bw)eAd;mv%4q>0OQAP4&Axc>lPNa5T{W(qYpFgwKs^MQdq(FM6`ZxV*Y5EQX?LB8< zOx>F#M3Q#luEO8I>h;~oJjaovJEqQ5H-Aj`OmP->%xsA%+2&ZMCo^2+^pSil?|AG z?_A3WHVwgRl?S3WJ}crBGH!ei;J;rTA73eRDdU9x?mEf-V8e6aCs%q5RNAQS0o>O) z)8A{0^I8_JNtqQX6P$^y%u&BzC_VsSvgt`7)-)AB0(uo#e5e(5fuEoEccWh0BZa>t zgl8hh(4;7#md}By&gsW*lHD7nBfD&+bnrF>=kuNIkH#E6yp}cqcoQ zPdG56YplJD^|(ZjfqHEJVISWPLcChtIHdFoc##$ss7y?W9uvOjh%q9m%ymVZIuPX% zxbRavZog}i0MdSh#wwGyw3VhoV1Iz@(&->~MiiCtG`M!ZaipxvDbXlHk*;GWv7K{& zqf>(%*#x~4yCo0p@kn%*l*kp~B8ie)5D29d3=?6=S)B!+UxE1A>xnwZ_pcEEx*pE~|J)uNCtW$lWt>#C&mb6WiXQ}n*j82CF z*jSO7`phu8m=mNMsjAGD2cOQ@KBgN5LPqwSOIHh>L>iV`IwQP|AoazN)hHqJWi`3m zCA}*u8fg{7vo{g1z4uP#wJ{wMSk2F#tSE0sJ zpAwxD>1vFtPc6xcWicGE?m{EDFDb{y`bG6t1xPA~u1ctm9LV@|jV0R(*fBi;6}rcF zBIbib|15v;4=l9}-W*!8c@zO_gUw>Uv6q0te7`6tI;U>b$#Ic2s#72RE}ZM>3;nlO z(C+eG`nIpA^v)@9OQ)y4U2E{~&EL^-5>e4C0zalTBw^gAx>EZLsj%z%NKl_ui(5Y$ z2{n!36+2Uw97}BLmcJXayob)AXl=_29qUWQ!@wfk2Y)RsD69Z<>X*GWa@hf0J232C z40rT|(GM>q0?`O&o>_5rUb9b^isS;NWSm7T8IU;f%h2#1n_UX}@LqRT6$m!>uQzYe z|LyhJjes`dpK6K3O|aEjLK7nT2!v{zxF8f1hEN?KdBwR%N1{9b=HHslb{#IT;P^t1 zKYjLFUoB*7oO(DrGc)O*#KqoD?YJcGT0^Tg) z5Gi>fAcX`exUj_b8k{4$NGIof&AIe%`Eo@h?#=hX$|Kw}M6B~#^CQg?o&NWf;NM*l zIeeFH9qEkjZ6PIg{)j8!GToh-UvPl=$XkhcMv|ap?Rx0%uc3~fKVBwjj?lAPvI3GB zIUI44*zExo(-##=T}}nK-0R2Pvp}w4F(TN0TyN!9x3T>hGKY>sGI5Nz)eoB)R^sNvHMkw|;l?+TTGNTTIodtEs2Qzs}Egp=w$|`e#(kShdt)WVI0^tKr{PFWj`u2ab;N>3X;<3y>R zZfNyS8EHPLVi>8Cg+Q*Yr)Vw?wO_|#7;~Qz?%@JPA3tqBF1JN>PD4T(2^-;eWl;Wl zedhaTmtSEXC@j;7!Bs~0+G=*psVY0~Rvhm%RGz$Z@aM+}G?sBE*o7 z;BeS{=80!0$aR5f`&C2vRoH0wRlOkWWU4)77LY4tY}04PdIUQablKMTdC+vs6c}B5 zX)KSyIJ)P30a&)yv%j)&rTpTN-UrRE@fj?c+6O{$COW`kmMDxtM1owp7#YboPHBbn zO4V)ek3AeOAB>2A85P{^IqWu#wDP1(Ua6_;)3zZ)J=lm_avdCiLxo9MT}dUG6-`JQ zc6XS%hd>1zLa@}4D%k8-%in~vCV});KQiei&eZa+j2M}P1C$N_f8+Oj&9N)ryIQ{b zy#TeEwO7eGHtvPx+o1We(ToU`05p(≥v=H3$axn?}7Z?A^|;_wT|(7e{1vMesXQ zbFNa)vg6}p%&nArYi)R3+qUPvm9G1yOp$3*pz)h^Ble^JNeGZ3+rUdfnVo8My3Qa+ zX$PBbzH3YwBm)0_1OEzC+NYBDr3gEp8!DIYj8i`7{=R2$3SbzQzX59tx$=hVWiC0EK?E!K+GCX=tLDA-^!t+cIk_v^!! zlyiz3?<{n|K4#?7g|RES&~A=Y*(cw@JpWGt+4zf`)Zmo~xd-bn`>z$0P<}psECCEU zBMss?RaHn-Q6`sPJmG{Wp_57Ggn$L{3>{=a0NgdBOcm~T$`)IMzz)7 zQWrFR@z%)6v&}W&?>Mf-Z|(O7x#N70v)R+`Y|~??7w3EmTU%dmm|$mTr?w|w%QK)j zQS=f05#Q#lBSUrulHG#PK!@}e zgi0aSDsFxDG%FB8X{o7*}@8caM%Yy z?1w19CWwh}`eZBR{G&d;%yeSna*7d@_3>7>7Mv#EUP#YLzOTtWezcQjGj5v?U9&%L zUlonMT>UyhAAys%b(I4*F9f1KWG?*7Buxuf=YMNAA`)IkWm-W7+_(5$zV?c}FSU1I zj8vv01ROqT-KRegCgDzT?&@^5*Nw6QW-;LcM(*}Qp9T{41N)Z)@I6!9Nz#bl|K?5G zeq`_gpUuiy2?csY@{s~Wp)R)HZ}3j|w5_2=SDoMoba%VLahHiyqcH1hMVJs6JNKJcG(%iQ6!BH)Tx95N$Q zGyCn|F+HJ|LfWK#G_E6r@xiDYHGfbDL%Jxp_kfzz!~vUP_QyG3fX$(hP0#3wH0x+` zD?TzGLSa=!9=1sR`4opH^}DcPq-B!#-U#NZ0A^C>B!ZgmmVZ;$<&m>;KDGN3g?IEQ zkV^x@oZeYmi6*W$2%%ZTC5)Dzyt-$nq8|{&eLit@dS+G@$!C}N$B8lXlikA{!^9l5 zOt(N?ZufDGs6eTL3N+Wa_5)eWlo8{9_A>GPoE`Pakt-=+8&w>#kUurJFN-bu735(c z`Sy>_N#201L{yo!1K~tr%<|_LxG6fiy?Nuiy~&ZVjw|$1yWuax`pk>3{!Okf{-^(X zd%U&x$LG_YfeVWVq@-ze9#SAEyguU>bSs!vp4%4Xu)2P$*!Zmd(3g};I;-DuF6py4 zw>TvWZY#guNt`f4w0O$Ov*aZJ?sp3qLD2s_2FWY-%8!7B-!HP5F2=hR0_eUyn$N%=9Lu!>68M+qPVkeF?4{(_m=N=Zw@ zHnq>C=ClqC_7V;vQz!2U^H8Z=Aw%muD}dTQG`)u?@25SVL04kJ2G(j)y~lDd|4z~D z{nYb$$^O<}i5s^6p9NsT*UT;M!fN3mC}0l=Q!&y{gaqDGW*1vc$75tqwEeA{+TJ*~ z5b$(a3#CB*0gxEtZ`=Kg**;(n0&%(D$8QS4%u$$#YLxHfdhhX%`>;M>&9!c_%c|I; zWaQc*9q8wWz=6?D)Bntsl2Vb4!^hB^mk1j(_yXowuTZ)j@uO&1HVBDATwi` zFzFr;(L{+Y4m+{1GzymG9R*UZC>rBWS=%J(nfQ`=B+7X;q>i4 z?hu;R9{P}+cO_~NpN|$qP3}M-G@n7I8VkD!%Dk4frKRp`A%FWj!%rD9Wo2atYHWOk z5wCyv9Tft21<;v-e74vd=&|69 zgd7{_9M4K*{yMLYdJEB=PYrp#wAEdhU6j~o*aJt<$d9TjZGAm1&Y~C0xzk?7nr66GkX!J_OBdgODbL>Vyh_G$(FU4X&aJ$`aCxrec@C zzR{6&s`E;}FQu);=?BQ~d-E)UEz}dU6XBYxweaJVg|*sRc3Fja#g4P`cRx?x!sd+q zz>D0WZ@lYPMl@+$3|U`YC|JmywR~?i$f0B%V4cl6mnQmaaqZU9>{R7N5391S;E{H+ zIM)eUTi>CAn8v!HT#Yh%{JBaMxXjRzW6SZ2ew%xW(d^MPk9 zQ-*t!>{u`mq6?ua2z{7#T++X@5r z6*U&8ozhAsH!l05c+KbX7oF&dJ_qz4P0xshiNHHBs(XZ4qhss!^qVDD2aAT}MDwh8 zYyDSEO+s~#&tmzkb~b(6ir=wUD_=YC5A6G7ceN6MyCr3{TL%mTeUh?AY3BXg;$b8r zt~nf*p{eA0lOe$md(V%j=rV1l$Yd!U?)NQbCX1E(p^~H)>_`fD^6jixVzsM3JgVf+s|b0fr-q5lHSiP zPTnaXS= z<-6>i=r+X8<^+lnvq(GHW(xIKly~(s1XM(<`$rVjjo~PqZguq!i(vAP)zuxCm$rq# zht!NxPS7^1x_HS1(>Ha*=(X*CmNm7ZOUug%`sP?Ui~2d;>@U8;tk;eW@pg6v+FcPt zi=zb=U~fV zVfy}>n2~L#S=EO!67*$gs1a$EztG$~CVD+|`RmXHQto1rTzK=JFsw22R}8rCi*c9V zbw{%^x>jH45vG{W(QlglukPDQ|57lJb3VRLDjzlE*|1f*gX`EdGdnw2sgN*<1iCq# zO$EU)YoK*{V`D~4^Oc@#o#@~YulmK%EUSXx!VeOI6(E{PK#~EE4clN-DbzmjeGf8~ z#yn>ep;k7%4b7;b^zu4WPt@1dsd#byIeV#69-d@}vKqT$?b(qbf(v9YV4528*E`(i zom;gnm(5MvoPTVwD*~+Qey-65E2-UewYACR+d!FH{4JL6odRW-#sbXysS#0Z)zl3J20a~GX6x#gApz_$I>JDW-NSG=2^%0RO((u32&jxnN(J%sp_Me% ztziWR_`y;4C`mrOTy`=tz9~=?9R`b=qSAP_56imd)H&+%JpYHc+28J5ksYgXHP4YC znyAaxMZjDbZj#m~M~=SVx?NMnZC1p;pNam&SUK>6$5V)dh@BF zI(7x;?FSD~*W39G>))bBJbF*_{Gp8(BSX5OR@5HwqXA8swK;t1s$;0mJKK9?l)HZJ zvm?_#ZpZ@}abDhmMy@p?7AMbw4%L^~-OJ--gK;>}qNivPpBH65`xvMa^_Fb>X)0cFAE!K|S!Evo67@dUE zR1C6yiQVP@Df)_7J)Z?6OzI5S(5OySL^I*`l4pw2!`LpRYkgu0d|!WbEIdxr zJB>jz)|x%*FJdA?{5H2pIen~|{{ZAf$IUFy9y-p)HL@uz94S&<^{&d3ldKo;wY{yO z|3o*x`r&squl(qCnY(r%S3RBRGi5rc-LTqItZodJl1XUbscB2_9d>Ia3>H{nUjA)+ zAeP2H^=`1pe|0{0?t$FEhTc-e&@`M8eXd<^&Sa(d-v^2edaiju!F{oY4hi-+ppC3zaO}If-iaCRGj_#id2Jv`a*ESNGiyDuQX&mpP88%%w8O} zWMUmhf|l--2+*#uQp@iNEshyUE3*V5x!yj*hDZZb$uSwH7iz6Ed0 zsg?dRpj5_Al-m~1YxU*@EY1r_eY>H%&n1CfT9i0mmIB_ZMgFR@dTl&zY!h<&tTvF) zt;1vgO%Oy%I|AtW$P)2wM}Vf8=9s+UZ-d4ZUCH1!sKmBeJN@$Fd)qs{GeON8F&V zcryfvw-s^5JsO8$qFE>fPWQUwphZSZ%IUQGU8D;%p~kz=(J34E`?#($8?FD|zc{6OY;|`8 zcfX;-{daI1nTrx@QXH_P{`8>>X#O5PO8xJS-qIG@FF?5buQfN%4d@21HjF5+7S~!q zKB#-hyK2ZI+1S0lU7A<6hsaGhtSyBIOVcZi&z~Nni3lJrv&;$8i^uuDHeR%%8vN(h zEp%7Lz1K$TXOnJnluS(ue|`jrm( zh)NHS8%#^$DXzmudRwBnAegJ1t7t=9rPUT0A|_A*My62CPQgTnIy=>i^+8=~1GQ^Q zOs6IxVppKBW96_jYqxFqxlP-RiSH> zCoZQgOnS=kEk(!FpK50dX|7}j5wG>I9JZxOL9{PdjM0Dcm zZcSyBglp&~SI25(Kf8Z6&xdF0?jwjJHA;uQ5P4Kkfy;*FvrP9%(8*YDvJbgB(p#)4 zfyKwRzK7Zg``lSaqFb8${!X`k zB9t|}ov)++VyXr_Y|-~{r_|ID7-oC)PSP3Zm0kJ7-Ha()(kYzxjcCuZ>VJ#1vmPRm zI8zheGnx9*JfMvz0arJ?%u9!I2zyABormXWH|Ym-y;C< zL;Z-l{sds)*V>R07NXJ0+nNoFv)H|?F#+hT@ z6BI%68bJ~@DD71z5%^%C(}5k)@n4)-59FVSk3H=#n^Saw42U}26BAjufFxzcAE)X! zl6o_;?mb$*W5Lf7G|0hF!{*r z(Pv&#=xa6FSxmHQgH0of@qy5%bwp|Wo0IP^izl&-Qd20{?hQxy{s-HAP6-v}1TLrD zeh=-7ugCl=tu|^QjKmr7{N~?*hE$=^1ZRCQ85{|A&pG--pLRc!2!vXAh7&#E3534XQ^}7)-hcC154bEe-pqw z<@c-5yK%*~2isD0JrvDEL&*3Fx0nc;WfgNY+X`jiQpk=yd$F$rpAy}%o5n(aW3|9~ zA?s%gf3ADVF{CJ_bKg0}P|B(V=JPRHeYX|;-RW@)EEQ3V{il3rW^WcghiAi0 ztazZQmVe;Q3v1PaBZwyQTdBhr@$N(sDit`|c=+?_mmwO>EbooS#D?fkl>Xk9M&9?*tC|gFIB>lSC(E@w$*cYefFhn?N`kM3vZ|x&Q#*A|=P^*0F z1B2Lk49R^ig-cKJFirUjH3chTNM3EW`xVWV(fd_qeRy}A0fPANacbSQset;6Cv>`MwYnckq3eBzp>Qbdm0s|l;!6d+@uugPXAYn+ z`?ugbEms|^w-8*&iLgeCbza8il{=R?@eLsmb-&yvJq< zzKBF;vEi_+QkWK-{#RG6W_RP|>hE=QOgM;R)Z|){)t1xuDKP_P1rT-+pQF7EBWbAO zji6E?jC*0pv8?Br6pF3;om+~h)6d<3_t<5_DZ2hXOB=yM+GBWeGK$|AQL55Tpb<5Y z#<%wpAq<6lzl3vd!pFX^E#ckw#53ZSf`rpHPdoW2c}1pEI{zL3^8|u)KCq$$)yb`X zU0wC5{*Gqc-MUL43>M}8i5Uq>MubUjfiR4T$DB?V#A_`;C~;y*XW4cRuQ{UBF@Vo@ zLMh>FIGT*L;iJQS?d5hwOhxCfd!EnD^BC+azCi2WcX%<%LC5NGxC!wKa0w%We!(t3+1_nwW~TXv)^T1GR5eHmu<1G44aU%&M&Z zhfi{DWjqwux>2}A=6;F5gJ38*uUwI5J1OO;h=wg5BOl2VH zhg*f3^Q$8F(DC~QtRK^5gZ{lBNV~3MF+mljefk7i&%?C|e^-KvsKLR$hwjR(Hm*68 zzXJSQ$vYhBEZBh9KeYZ|7{Xz^zK>){7DHtHCxm%}%1VG4Yzmc1ngXG{+w3QK1r^Qe zXj2RmL=w<0>7H)fd){-MA&dPbdcpr=Nv}2kxmwtPwdm&f$V0_(!g60i8Uh!7F4O`t ztaAd)I?KalJJ^RIwDQ6sU?u3|&n40UY*gwaYP;AZI2;Q~RGPCrv;Ebs1_5Ky#kK={ z8N*RlYA3(QBlv+`RE_&ceP}cRYpgOGWZHNvULc`@3n){`HF^1aCB~n+C)ujY27xrM znSJQmP!;Z2qy`40(#^U9DpIoFMJ#^}K8!?msn2stvVX8C6JesmhimTAQz!v}YeBVx zuI``!3N?vL+DMqz-9phoY#LlehxERf1*9|XN)~A9;%PfwBsW3d>*LjRF#GF}Ysh9h zG6#y1v)`fWt+kMo(a~Gm4Ah+}jttC*t}Xaf+Z5k**j#Vetje)SUGF~};*Vcg8`GDb zjd=B*0=b}Qk!U0J2{y$X%V)Q%C~Yy3KA*P>H>4B%v#t}XN!sedz`2-43A`4;XaPDa z7SlCQx+NZvl6EMYc_v8!0cUXphyyPZd`zVui}Le* z_aL5~yRZHLOGF5mKx3nJ(1wl()@AIy7LQ_LDtz>WWCXoB^xw;&ds}lsryq-hT9($C`rJ`GrvCPmPHZ^VbLNFg6vj>I!|rAabGLxZ|?;-63>Wig(_hy6FDY>6q*;i&UK>Wks1E0%mGvKu&))Wa;>cPTge--Ho?| z)6xXdE#WU5j=TcHo}oXVRrjoIoI5)G=SCFn3~|yXqbcx?7l+q7P?Jlbk+FqGNLNej zu6j_S!0ZRn1ms|zQBqS2djFdB?Cd-Sj6Di$)Gp+MIY;)lfBlb>J3$^F@Iqa6`lv0^ z*QZt&@?%iDb6y?g*1((vBAJLopl^%*sgx%dQxypj1R?W-?^wN5s-r3S_pB4$K)Nx( z#AYY|)bUxn?-2sTH`OW*ze-Qtg-H)V%!*1K_IE$jxW6UAk^~7RNK0_;wMXxx_TXBk zJ(Zcyz_P2=`+z$r?^X_abbY?AJq2pM8B4NZbvDHZv9#YULW9~n6^-1@uxV_!{L}v( z$;O+_IhCN9l45(q!ZbY#4$=EiPAu0XEmDFw1CAs(fL_tN9Ld|a#4dlREbP@(+|NIU zug2aXt1w=Sa~$d}s@BmP2Pb?45DDBw$^-PIsm_-X3^P2fuZ$3*z#~Q0%<8ME-sAknn1OFa7yM?Q zQ0%)?%#~>cOXkocIuYK=XNVF_kQnC6={;rIV_KRZcbf1pIeDKg`M63&;c8CkD!=qE zXR_Mk0`Y2FA{e-gvwhk!VWJlgh!RJMi|b+Poio(DbHzlc zR2+!9LoO|cJNIipP(UIwMKJQLW3x3q8aZFI7Xqq@sEx@>U_siGUs<@;oF@KlCgNyq zM8t~DgW%0S`7r~PCphLDp~9i$qkx!jIQ6>Rt!8{-U$V$;O5U#$pKSz}hniszaeyI) z)Fcm((qs&Ow@{`zipY_nk>mW~SG9qw^NSPteIpIQBU*n`iHt%}Zq#p4`K5Mu@lDF>7RwYsRc8*f89Xd|S?xP@qn zKYXc|?0RB1`#Araj7#InAFuuF9XuMutBn=cAhqWm2+j@dcBfJ&>RKbiN{@7G-7j#u zN-AB%(g@Z^IA`gTc!9G`-VK)yTjg}WLzVSkL+exCf?F_0Kmqhi@Gd#7<-L#^8iCM9 zMvf9oqx4OL9$?OJ^J?1QOm@^xVKEl^$~n#h<=LmBI@@Bc&57o>f}`T8^^-Gm?{Y*rl)?xc7grTNsug`)u2Ku3v3WXKF(M^~8L$PN%vH`MXo~ zwd8Pk2STIw*HT1x?h;RcsX`n0tZ{G`=DVvo7FgDI$Dg!3iepx~)_Ff+0~px~SOj%+ zba=_`*ddL;cWUx~ef@e7yOKPz@mM%*zo z11no5RWEeoXAckt5nPh938@kO95@`Cm7kwnWY0`cm(Nl?8@VHgR(yGPume~s)>Iy` z?R#Q-_i(-Y|f<=a3P1@cDin8KyP6M-x zd~XwMkyYW+Hic2cZ+34a6Gx@>O-;x+MVO-M`*Z_8&cR|VJX3=Hb%BZbs=Fz)|Bc_8 z-{)xZPuGB;&%G7mtaoH_GMEX6J6d~K#SBjS%W5K|$BA#$PFc}JHoEmzGG{GJ+ZF=; z3x17?Ps{AJ?9)^A6jR#cB8EAl`DVS!opyyjObqMuJv)jt($^_w_v|dMzR% zw*T;@NRB4L0gK|I2vQT9mgdf(5aM|zq*f4rFk`2SQ71j>RFB)<&OGtp5k9Q9_A6%u zq`%eg!;Yq(L8`=~Pps|c+EAu%c$m)&ZJe{S`Apm?_J=ujn260{l>(>pC-*{uH$cHI zL1Tfn`{Hoxs5%4rNRk$H%14Nv&dh|xnwTZ&Rm)*|fQo%?z5<&?emA;>@xkVTrwLXG z_?q6K#tMvKZC^{l8I-&^7Lkb4?y$^VpOQ1=GX9_xTtFIE9ibj=n<+`4F}%!|voC;+ zhaf>2Y-2xMJy;zn=0HrU5kPpgIYmORf!(kIew~+xccJXy+u0v%^p84AjlyvwVV0ce z+Mvr(kHK(Ma<(Fqj8)01$lE%Gbd3CP?TQD`L98VY-Mr=NYb@mdcRXC!$6H!xyqBX2cH>fM=ZvGPnD_tUB^S#+y<2pF!=UKZrviCc1 z0pP+=`umw)YF=tAZAQsxy(Sp!vWbbF2GBfU>etrP*&aHNbOOl}9Oh-h9`z=VzKfSG zp2kq3Y^PA&9UYJTwJ}CqCP;1B1@ISi$Y&=+4p6<-1}dNA$usvD0zQuZr88kr_-Onp32OOaGaKnAVxO>% ze?jma8msHG1-LE@%Bf97aeU*e0P*F}3{ENQ`T2y$kOTrl{7g8Us50k<@PQhSccLUX zQpeLNdGl45sb|T;n!mu~H#qb_lOZOdfC<7EN|Q*j2e>^Kr4*6bH~hU_%SrH=D6uBa z94%Bn;gi{k&NA;JJr1R9Y9aPa-PPJxdV3pY-cI0|1z zXwoF#$Pk^_Pb1Ps2}xGo1{En&H78Qc`Q9wV<%jl=bXWo%oVq^vl=s&dbBgligVU9@ z_F11w^a!w63pWWRpPeAg!>_H&h0NBc-oM$k1&Ya$kjFP(`xOzSU#*(O`2#{gf)Fr< zdOQ`zjQ_ad_H%F38K+XA9_D8(i3HRCh-fa>r^ha(e81BgK3XTlBM{a8i2-S`8 z9YReZ5U?PWMqg|mK41tO-s4-m(JoO!VK5`}q?yp4VF@P8n8;=z?26A1uXX=f{-KmB9(wGyRm2=OKe zv+i|;6Ay^3GM4i^Ak%7s(mAmXUr^oJg}8y%=Rc3}uN9gRD8$oA&;B_mdcDWDgWJ4Q zq=*FTVd9YtmVRd54o96%O`^#TG4O`EZB~rShFM;1?>>uSgaOe!O(s0cyc0Tw#f0tc z34>IWU_owT$zB5^p(%?kMsEX8s^6CWC0AvZg-Rm;#N(rPmG)&93n3EL_(TWb6|=h4 zm83F6IkCyn`9(AM-RL__&>oJIL@fN?za4cK>Ilf@1pob!gWJOU;na1^9c|Lfdm;&A z+Li%OQOXjCA6Ss=ssWi`Apvl%mkaM>(8Pi=&L7m6PA6KKagRcEEN+o(cYw#opGvVd z`#U$s<3m^bbBZrw9;Vva`SCqdPvpB(`=Wei?reTtHw4h=wY9a@Y0p~#C!ux)6zJqI zOn4iQV5$P_gm%LRF-#_!3lS0HChCHOln2Tu_C=WtY605TbcChJsU80K`PtzUy+i3! zfDKqLL6m3Q$6;M~i4^fL)l4I#w1UTo=fP4?L*lAMySIsvmp5$t58Yq>UyZu;9x)~fx zVIs|0&cEm9dtJY)KcEY*z4m-Q9{2n0_Ufrdn8%;99MXX$Rla81c@_@3kbT3>#wIW2 zS}qmqW6SB=E_1=Z_GTWv`s+n5`t&2!?;PeDQQU0A)ymrUweuKo?#qOG zXv`BdwSMS5)sSA&JQC9_`#mUD#}E$X&?}f?1f!vU1e78Rq?Ok)lq^E?6AKv&#+W#a zJ>|}M-lvZymNczrm6}KQLtd)MMt(q_mv|zYcE~Zf(xyIiJBH|WHeEu}kJdMof{+du zJ5nF?LlBRaVWp&{0UyXb51t=seVS!Ed^)+CzO=4cs_ufvaPWoB^!(82BEVx4nR}*E zn7=*{o2+Q}!%YG7&v!S&R5~fj#szB<4u8_wG$TyD=T{a@c(_KgYIx3T$PBL}rJ?8I z+W!tC1LNT=uddH2hOIkVZ}u0&W1NamEl+Q88sY_cKj3c2TRgK&TRF>Eo{CaO?cQwi4^~;@w(W z?4gL)t}_9BbQNy;Eqz$ung5#Sfz5;n`nDjsaEqGz`bob1TbqWk-DvpDn|6*6xU9iK zD$fK}n#z~8a6#!VzhDHlyILb_yFipqia5~t_L=z;4C8}_qDppN!DeG7M@;wMuhjta zg0iL^!((%L#t@U|Mp$#gWXf%sv{H@B9IIZsO3s;1$dq_}6rkL6YZg-fkqCGT%tOx% ztS-lMBI00y!!qC-l3{|p7x_{-smLFdvHc4aL0*^?RM#|DClcAIk(4b(l4s~BnY{gX z9wL3Mw}Q2iGbqW|yqDcRdM8c>agY(=O~2Coul>$(QXAA=K>;4Yyw1d3wDLNvtOL`5 zh-JkQm0DN45<{e-!y}AWSZ6QrhAA1s66%~0eKOcdJ>9$So zu4eA^`f>keHu-}oT>dV5wrn?r$N$IqEdZ7q^kpFa3%phHE9`TX&?iJLhz3J*XxYSqd67%Awqt8PB?wY=bv1oykpb2*c?&-(OA1e7 z9{K&%d@{N}mv+YVSiizq#{0J~Zk>H{B$x73Ku0>_v9NM}a7c)WQagy=^tN8H^x1gY zMWOYLKRm;8ygHV!Aiw3UkOq;#~&tX^e+X^JSTvSI<2oijY_p zrWnx7JS}>#`5X8c##K(fRw&|m`XJ*>Gmdc`cN~9_^3maoAf85K1~3re5c~TQy=;#R zPR;CD{w&rDZ|2_2JEtGbqp0kFFQ4z(lBVd*@sWSk%}qClZkl z7J^NY+shT1024B@($nKxXMzOV4^uhFt$x+^Kz=U;h&e=;U`~7?v3Y281@#$cN3I}v?6(5mXGp4tLjSPGx$O^kCV;Y5m;Hmz~twa>Rv@byjJdj zbE3n2mUT|Un(d&!BkeZy!Cb3twGFpw6GRsqC22$yh1(dmG#s{WJM8w#S+5hrL)um~ z1?ZG3U6^*53T!mhN)M)_3p-+XooWUMR~NBBJ6RE%=aiO2TwVUy4@PGg8Hf^ecWZrV zczBr8d-KN+&48e_P_@V_U1E}v-UJPBkbRxDv9O?PK7hLnJn!tlx8aaa{Zy0}b3`k| z;$sY-TE+!Njq^-*+OZOou{FMkTBnn_Ui(@-UT_`*n!qWMhrpoH<9r%wNigf0sp8pN zemM5i?>(VfZM&JT)i*0of8^FXJo(SXE{Lo0Bj_(ZQO~^Q&JC-ogiE{+up-+!eh=>! z9s3e4Pd(jyE@J-)>+PE__hsBIFq5vd{)VVNUFVT(tB~AX+STWEXV9tI>xawL_j8}tQS?zM-QNW2XkA^!IpP9N}@c^P~ zU?&{F7^?qNFp^FdgM|w@$9+WHEVHnf4LF*vR#bX=X|W@0gWni?Bdu|y_Q zg0Aj*&ZK|ApYk#4pibS)9ZY2<W}>_tRs;iX5;Kx>Vj1A zX5Fw`L!aRu*w~LB%dH>KeoQbsO3&ncJm>d~iv!?<1hQr~6pwqf?}$+Q*3B%H z6!<~d;Aefm^$|RN9?@Tpww&z`uzM2q0L%Is2ZqaLA{sf%8ykTM-T$M;Ux4UP7%9SJ zu_!=zb2+2~!e-p_B=PY3Tk))-MAlIxA_NISj7=Ka=K%1x^$HCHot);<6=S9T>A(4WjVb4cjIqfA))4C?lpqD4C=$jsoSYj2u?tolcL0p-BM>#T7i^`bL+h3ZGXzSNBtAo}0C;vpWYU5BZLq z%#c;kz=Z6iWrdDRzKmYZ(2QLlCDaPXGsWJ4B)s2DKB6We@ zUa|ab+$VOM^3M3ry_8O?vbZejUQk!0^m%3&C`dv2l{bNC&FHML(%dHd#!df)t)YHy z2sa2!fFaFQv%Z^qx^dy31G!YOCm~&7`VbKr`>t>vk8g9sRhL#p46U+T27UHQ-F;D2 zICJYr<|&2P6VQh+0FjZ3#6+feXPBwQ{cm5nqEOaVly++Nc&`D-@9Sgs!aSJph|#)$ z)I^Jvm-f?=n)NTKxqprsqzD~Ay~x9)-dVVzn1Q5%O{2dguWYf~S%f|8aL)XIV#A)C zu+?P^dn+>vjx+WPHHsfgeyX zoEd<4KopXuafWJLD*KoLgy}Vq(QWzjnL`TC9mp+F-d`F_^fR-NX?nH zmdk@xC&kkZVd!$2@$K$;{)e4Viq4It=`RKj7_1>DKm>n_TA~7Lwh=Zmx>s_V(n*Qd zBI08JlX!IWhkUnk&%t&C!#~t_b^g!2>V^(PZ#O-G}iv3{eUecxL9e+*doUU3!glBVEX=xIM-%i8s(wc;(KQj4|^3ez` zt0)f;*R>d>BU{sDVH?b0_wBB-t-hWC$K5}fJN;uDJ-dH8!j>!rOx3MV8NOb_LJ)We z#3332Mc8-2_Q6|HJWCU=5#n3_jc=jwSDaFbN2L^ZS2B0jRZlULU8!%6UX@Bzh;gVM zHY4EYA^Oy(YSsje-U{ML#aK#*ro@x~iJ6nhD2jYH9*p7sdEx~fVlp+u@)Bc|0KA?- zugG&DMYD093{$nV&CR-Ty^*gh4YoKw1ui80ZO)fZF5${Heu9|_&t^rc=)z)oa3mF` zATQF;v83{_lsFGCLl+-lPOpZF2ESoEmhXVX$e)UlVmzG|>Q@E5AI}#;$74YHdXM1f zhcD@9%oj zhSj^!Boi|lCU~|!pAx`%eo5W%X7c)HNo4fqND{ez_B3@I8`IkKB|%lojDeC{vJrRH^b-|M3~?>Yl2?fh*0ni}frnqrYZevBNCj|!a*p$>1m z(HZvQ&zCz9M;!Q(Crdy#Q+gJ_!2Fu(8XH45+d-jU1}*yIWSn5g`p2R{OZUY>Wi6U{ zk3SP}GimSDnTK+SsBt)D^c+0rnzH|Fi7xUA)8RfSejxMZArQWUg8s)wgBBh=i`D+O zJ?1k?f!o!uI8=`b5;z7Y$xmAEmV^bY51r%Ir}3@kk8PK-y3gJ85B)ZB(9~fb*c~rE zh8aXdq9HnP@K1=J7r_%v6@q5lh$ys8-G9jU<$I@9W8g|{;n~>_+5By|#PsgM+nUdb zlL3cyXt5D6d+MTQHB-$*Pa`c^CLE}i@*ZEQ)&BEb_z+6oF?AvphLX(gi%~i`nf4AH78=b4l79*=RYgDpQgg6a8 z7A_+tmd*)~HhDI!514P(k)l80dNJ>;Ts9lmnze)f&Hwu4P-zWPV)E?a&5`Y$48Dxc z@2nx%2b{6V2!d=e=PbeS8KgZzmv8-Qe#rjZ>m|lXy<_8an(~sW7rx;s-}NKvWu=|S z%J|Pm57iF-9z$Ui(8*?ne=ZT|O%S9JGnAOyf_2y_0_fYGtbdb5C96&{^ z(cZw%%c`dH9wh;Hk~WnY;2Kv|J7+;XKz*zhX|}ldJQ>TVEloDC29pjLFFv}GVSV*K znPyc6!nPB^ePKwbnW^1gJLx)Q({?NF9SC7JsrII#SWWvAvOKfXcO^{ob_C5GhLcR^aWt&H_tJ zeXCf$x6Bt4#ZNv5#6#399>U-hsII&5M`dBN^g-8wK(4FDQn`)o*eBvK4qS?saE)eW zoj>F09DfDx0EOhh@wOJjbIhZpcYCoLr4xd9Pq+<@>-7fQ3u(?D&C5pH z*>P1&1DHXE_fE~hZyL$;da_xbj_EVGb~qxpc~h}|+oJYVfIDt;>rI!{!7Q!6|33@h zLbLO6Vd9$GHm@Yf;L!#j^kA@Gg@r<5=U430mk=!o_WF7%ad9$V^3v&K@;-R(=$PiE z+-vip4R-22X^UkcV*+|*m65QAfCdeRByb!Bn3hE=zSZt8SXOmo-0s4{G{dxBQT>oH z6@_QEG&8_^B2JknSVSAChGPXWrDALVT`LTsvc%vImH-MDhGN!iFWgGMr1Sxy2mNq& zkMuZg)COD<&YN|Eh5rS~U@)+Wo(~$^^!}ug^-eMg_DhN^OYxEYiKlcDN$NODa0%fD zYsDC)eQ*aVB0Inu0!)F%zwPUSR;L%5HX3%j&*@<%r8WVxOQaw;I$Pc~+Gc`Lvo^Z< zYna>U7Z_M;=VNl!$F>!>_Jt!AG&`qwV(vUUb&08w_Q8?{u(T9G=@dtCy_XZ3iU;-m z5sdPaO`9EI$~}wgOVt(if!-ng?~Vi6bZXzsH?U(Bb9I1HJ)v*TxMg(Mi*MM!867Yo zmH3Qi7OS%mkX!e)*u2thVwOZh2!b?PpS^H$>-q`E9Ywi*7K0za{)G2B;(U{R}x~C(xaiUn~%AxjWzk)=>Rl z%LY#Y&%}qL58)>$Zhpf64hy9%-CywM(!KG*s5bfTzO*9*9p|6^HwMjzD`EDt;-q`x z7Zj9p2S5YxZ~#*6-(X zWp=hiX8iWkPx+ch49_`+9QYB1ASxk98yky0gZCdRsq!~mn+XldME_3d%a#|!o7>8q zz(#z&u{Pekhq^H7nC#kr-Q}S-+w<;>^(7Nb(M&D8{qtqWhYRtUKYolR`-C7i;P(CZ z=}Z6Ta9Z#WhsE{NI5p3lD>Ry6?Qo&HY2J3C|3%-Lj-nh*;qd9{EBTJ10OWxMlto95 zE{KNy6h%wd&7IFu9ePO|JtQTZ-cK;2@V#=BG#9j;$WG&ZOV-+jL6s>CZE}nZ)OKURVEENRXeTGz=>ekZ}tp2#LUEoq%%Fm$Xh; z%S509EpG?RXWaUFW=_>qs+X$rSgoLv0bl8m&Jqs$-5^TC=J-&5_M{b2yHSDS0PtaszWQ0G1uQ_`B+SAlLK6_&zZ;faFD=7=J?Ww?izxxOS z*qi()-AA34BhDF9sso3xzP54$MDxkmYP%C(x?hR7o(V@YI?Ig#YwBbX;pBe~PrU@C z(l|1YWRV|`E#o=ZTFL!j75GGjD9lUxq%!(-PSu22v*O%fT^5Js^Dx33&j%xSI`916Ou;W87clJV}j7zgSA#kOAW>0bT&x4puViZnG! zdb~0ou^o zG_kbw@eK6!^7UPu|MfFR?sB>DR?p>7Jot14ade?@UhZiUlmvayftbSkJ3jkogUNk& zhX(FgDL9Su+N=FICfQcZWy2nZwD76yBzu=zO&HH}E_fLwC0r>%K}p6*WVUKMyjyc^ zRLqr6A0FNlNO~u+@xb#ARZvPmD*~ZGYTkR=2Nh#pU0YYHuB`^Y=Rthk;d^6qGH2Z zfY~*36FxH{11JqaPAP@sF+uJ@{Es6_te=3MP; z<9eL?=*W-l>9UXJDHL71|6c@<)<=YK6vEZ_DfARqJ40w!H?!*q9+-0+A9iB8r$BBgj~ zYqZXN(!j06>XmRrq5+?D7vi*cqm`w3>e%SW?n=Ct|JHKAaH++txjx|42%>1tY@sv= zNgn`2!x5-x+AV%FDoT`>^6$^WRpt=L1#(*#Z~(xJg*3y$V|9NmnQT^2Y zUjp|-qLKR~BSSB4US(R%+nv6&4E{r@Ya%sjFW^F?XvjWpG64S5$UZo66s2e&hM2^p z<6)!g#?hoO`jnUsqW%Irx0b)RoSf0j$v^W=sNSljV;*ACCG~RdU8R zs3|?az-{K*`$*VoYdD|nE1K6Gs%6p=Fw&Za(V{^PFN~GL0zD73_e!Kx1}T-F#KOQGY}|!I9@~1&}E}WpJ_&U z7{||cjL+ORTg;j@Pn$7eMmgC55SD89UPjwGglBowMLKSf;=m}kN5p~_47^1zJVi+q z!nQdb<4{ObV~x0TwL(^mP=#Sz@jFrOp=_6?o!O?1bZ#)G=;o&3a7j#|h*Ss7Bvzl| zJS##Ly8etPPHICKAR5+KHL!46cYNrwdeMOF>2G2CN)OPlQXv$<=1z@C=*ZZZ6REdX zG8{&)w02>%OKyJwr=5H&J6ZVSXUa!fa4IH8dhd>{!KEO);3FTWRK=8;{t95si~uiF zA!90bv?g2rQ73V91lPJ3bTcu;w^n7dwIX=o05R#80L@$Pm)fbIU8kurbiL&Hd@;QJ zPGxGO+59KxR;7|9p*=qY8n8)1hKM-0y6cUvWZ0MWr;{z#WmJVFyh6FlxynvY@$ZFa zzE9ybgLbwCiY~dhLc-Fwf}*H=X!wsn=XKQ&gnUx7rzJu>TM~EK+#$3Lx2^{87Hu`_sF8rH5>!V^k(;Yt> z6dR-9AiM+IlYp(Bd)sb;sgYY5FQHF!Y;RpU2qd-6sgA(?6l0e6>UZtRX91rP+-y>S zUDD)6&l#Bsk8c94pVj6rNQMZLY{~|GuFBQ3KK?GCEzZnrY;B42B6Qn?^D;7P~C79MjWv>(`F*#$EeLsJ3GOoF*iTU!NDl@!b+Mtw|>cO#8(o`sePL` zHYeC6U#u~Yk$)_X=Yz&HysP4q^K80h;A8Mg?~CNunbwj!RI&Y22Q3XtA}3gE6wt?1 z8x7@5P2G8s>`6zH zog{iRE1nC`o6Ad4Q0()i+ae4l^qXzS9wPnle zXWZZz&+MaIQTOqhx+8TEyQ~)$5^@Mjrh5_+EdVHlC#xQP5^9Fh_YmQ!mtTCNE&imV zVo8M~9`2EFscSD?+yCXe!1a%E=C)+~J?`2_;K?dSGOfrUnPX9fMLRQaFfiHR@l{aBpK=>soqDV~Y-UHQk9F^9G?L`vt+W*G$YdZS} z5{0b*Ne+!d07}i2SQJwH@aBMX#X0e~Gba7WXqs}-%143SjSf}-`ID*%9@d4{c_SYi zkn!#dON=|GvWD z>-NI1;3E2=g3}AYurS>T4a0vcj%6Ao*Fgr$~~RH%3i;9>k33a!2|rNMYA8Xz<_VbD0@iZUdgtU;T; zC+3~(u5yCR7xmQ21O94J_LOn7u`zp`DnrqM%+xY*$09R`8&exE##Kx9vc9q3N-{iO za5Q_P?DY|w2qpaY8Bh9Dz$@y;crJ~t>V@hnHYZroYC4q(-#!cco>=|TZeVNP9JR6m zB`t2Xd+R?{R*rxOQeb<+=Qp`w-H#v;{^nz(*;*khx37!dHv{EFKUoKPds}{Wg+yab zRkV7RE`yWeV*h146(Up;=V>bZ>!5qXnJ0V5ubf<%<4SIe6Plcf(Vwg z#B#8PaNS&hzutf&zcMdGTgausBGwcNJkdEkZAHWC6*eJ_+ zSi+}zM0Q?biRb7h;EE$q6uytjhaoR1{@nDpMQ*vYYt~`D0qe`ZA7Kkmo&vM0Uw^j# zPPc?1d*qwCWnF?E|2Jx!- ziQnvgpJbIt9=MgE*xKPp2sX>lZ!>Lpu8tc52s|r_+lx(R)kVfIU|fdS3*$df{=Ev} z6V!Q~xc)Id?1!rBmJRD55-RAAhdBzPboiLwKZ_Se&vLrTBLSSc_$|c2WjouLs`R^O zruHv*s5ct9d@?XyywZm^uL+D43t8Ur`h(bu81>mo>{-PF)GG-bLII_B&`^LK4r5s# zAuv2?hH?{^lO7v%&AFXAkg#PR5(e7$KqGl|2P{m$`Z3Rmucf>G8aa{fOkV81Ei81e z!5}3XkK=+x?9}oJPajMUO_{{c8NyMOBB-3Afuks*@cQ=1`Ih%{-+}SUb8T%6xSSP* zBHy08l)JO5pb>#H94~%OEKzrXWc79JlZ%tc*VU*%iwSywD;AJLzB~7ahXTx*lp`i5 zvz}MTyQJMgL^>T6BSW8$KlB^5dI;ow7Uq+5AQ}*tMYRD5b&S-p{QqINw`ypX*M^pXNk^M9O;LmvHe$@auU&AQdncbQ4~ZspmCKW&70!0O-h;xl@U;}YNxXFs-je4;twcPBeJGc2 z#i2_=U_>MKpW@rv{Ml%vEMYb|v;He#d$Bsqscxjo_23tdT{QsMHZ>$$tF+|V|D=nN z(9%92oL6!NiRYgl8hRM;!gu%_B?|~BtU3^p_Wo-letP`fk9Hmcn`mCxnv8oXqZ%Q3cRJ`o2tp#x=PmFoDxqggsIY8QBiTEWTj`tgwZ}X zcRn0`>pCj{%Dmpt*&a1cZ@sxblUz=lc z3Y02Se_4+{)IeYXk|>5Cgz&pu9^^@FyH!fxegDfvMHH93FqzC#G1yj%*~Vu`JPhHb0l>+xmFyWLZWuCfqQ~<4Qd^eJEPj=T9E@__A)-Ea(Z-d=3X2>)DMM;KG;D?#r z25zkUrScCjJ}E;n(*60rQ$1+{VH?eZjf=TWYm&QByW^5ujI!PDWm-Y^?Tf!!=pk~d z#iYIfZuV||*kaSxkKT}m(z>uk?cK7m&B3wV<;9hrxe)V8$>8M$zoyOI{}DGPH@Quc zAxc07BNYK}&OBfDke)1{z4gA-nd$*ULIni%VP*u7Iq-))=)|?(Z5kGvovAg^-RE-8 zinX~7PSI)g=(H*mn_T!0@GI3AvANmw7<=8ZUZuPKt}DV3mIad{6&IhJm5;`vv^RF9 zA9|09IR?*bvI&?1nvaE8gZw2bHgXyWDBc!#ZHFp)=^}c(7gowb*f|2)RKegmmz(>M zLU;^nNj0~0V_+Z=-lB0(qnu^jt!(<-hlQI3N)vz?4zQwogMo{IXv7lKtfZ3YY<1fz ziSQd9(RY$pN6Bb5#gmStP_a3OARdTFa;kf&ds?lLGhg&)<;!pgsYgoGbtPK{4@bU? zOCTI26?;3GnwvlBOES9?_mfJdk|Kcdj}axHNb93rp@h@(3QuAqEPfZMyJu*I)_ADVrY>1cv2sWbGFt%^QV)Ipozbvwa8PN6Za_EMx`F~N{8Or-0FR5o; zbg5!wG@kmVzpCU|gwbFX3&GXoi1S>dtyed$lqiNSoF}=PIRQzD1_QLo)}{UUXn>SZT;k^e z>9|Lq>$r_Bm9yVX6}o>9i9xOu7<}9-Ep&cDUYc^W1V^HIp~~3{ow(z93nPA`S+v!V zn}guOXPs6G=(|?3N~qLMIK|Qu%z9B!SJhmwoyz_WiKy>Hwwaq-xy;sn=lU9$;USfM zWCb^Ow|7Kp9|A(MiT(ll6`rO+?(rSc5bVG3rtR3K&yqo;dY^r$a5(Wh-A#?a#9k-y z%cc@TwGR)^xmlfP`5GXKx}6FZt`H;?%9dxhe$M9uVOz61K&5!g7(|_KxF3S1c-t5A zK>Qs881~fW3pqU>fAi@-b)=gm#T-SjLAgSnjro%NCZ1)@Tz9VYVs=2#B-dfAVTrdP zhAN1H;r~r9kQibu2&9d9+){?uKB*U++|so2VkE`-V{IuGUsRPy6vR(TEtOwPH7XE} z#{TEtum&YbYEDvBzOOx0QIo0ktve5$|1)76T`zwM!TuZSLJM73*2vZGnw;7=L<&xI zeD*?K_yU|y1~9m60S&)RB>{OExi80O(H)ZuEJ1h<-q!rfehQpJRk5HY(v-=?iO*oV zoRQCK1(iBV7S^R|Mel5H(|gq>{^pZ7qA3Qa<}y&z^YfNNez4)qL-< zJ#{DbYf*CYa9vQPJUjwe?;3VDn%2{sc8~3T8QY9&+5|Un%;G1sSOj0Qvz&Bv#Famv zHM_!AqQbU@W;f%3EMjBI)TK^-=C7N&(RyWB7<-r-w&}0AHLe&oKj+>Q78H_}oGSqC zdJXX?xPI`w^-QnAO<+=@An}hG$8|p-R0t3%B%-kMA=dhoBm{LIcUUPRK5XNsTUhYU zuafM0A_ZC@K2}NOK+e*B&aB&Bq>>>3%97wnJOZL))f&24=2iFgnQD^1i|-JY9s-B=mhX%S_b_SUbZ^=zy! zas2%Jtcy17(-<}>LdHruIxxGWb`HU~L>J1&iMis~MQ*1lNMP{J6|vm-h9IG0GS}x2 z5ID&p?mxT|2(1aFUi<;2T$#7ekafKehVP){3r9HC3#1?+W*MO11yy2<7fVz2aR!Ud z%3!2Q1pZ~yj!kq6Vcg9n!+FOnHig1nJ zVX61Sf3IqK4O9{^?1lph`ft#wLid?70^;dWzIOKxva;KyCH}rgHQMbRW=w1-rCCl$Y!Hr*3?S;!% zOi(>Dc;G-E3zqPW^t=M+;cWSbOCe(qVR|sZHqWE++nykiu&LGT$?&{QtwA6SS=O%i zBCJsqbaOvW3X)7#h~cHAz|PDLFzy}_T>RcxQ@im~Anf{}PZ&-sY)72bf-4#RySnOj zv_nobUWvgBivBP)aYA(6x4QdLr+%Y6!R0s!-LZw4CL6^FhrdWFKp&Vb`5NovM&Hk{f+7P^vbp2lC?(k0T=$5sh_t5|NmKl05SY4nwU!>&9(oUxh;5f>=a@x0N>TU!H;=PovLS* zD4-xwU(?9auIoTi<5VCJ#``lOB;tey4{?7JWTJS>Ljx+ zjmt1=@HB}sz9F*D$eMgb=K`4`>T$TeP)Mgifaa>4V_Ip^Dp-|&IU3Y7?8Usy?3Fkl zT0TnG1oD;k3J%#Sbm<0Q7j3VF%~tOg?Ji61$c?Qt6$gCmXsKtcF?{wE>@9?}2S9qf zRhQ6Mp5OW+x%)9QByfGG{Poyw)9(16<)7tuT|e!7uC`qRM2vj0xt(U<@^85^2qgBJ zRIeBt>rc4&;+t{n*6)tYcP0lR5s+6clKK$R#fyuXZRPSXO4NuJ1xqRC;cQUbV?+zoGOZ0M0c{W^^ zHnEQdc)s?pXn|aG9?YJBAbr{!hLgba_bZQ$i~=_xM81N5)QPkj)vDZ!Y-2A>(~m`t z;?fH9ww2$*TR7UKdy%pZ{T-5_z{KQbVQwzddNSfY7g!%?aIS-u1$G~!h6TmqVn&5tBmCAOMcRCiSCo?UGiOHB;0r-?@;AlqQQ{*1eZ=&o2HJgwZa`B9ZyZPh`o z(z-J(o!3MD1j!`FM#a;;&CQRxM!vo2&eGHNO5h4ya16PIF_e)Neq~#qFyeNaBP{$F!0vqm7?qc{*OoWCaf4@^kCGmf+hIj8wX48X~r_Ich zVOdTYVau(Oo=izCe;og|TlFK@X#!{nwIkGL0adXh<;QlDYJ+73`C~v{^39D;RDA8{bbOPZkY1m*n89>p)=%`E6HNGt|CDw2Jbl@G zzhBkH&&O|_R5jL}d)ci zZHw+MfKAN6hY z)a!#Xx%%N4c1PZ+Sue_dQ`t%%rqu<+A&ighxhkk3`=&O(2Dw>d-JZWDLV=cl*2xiQ>ZGdA+@3AQQFHisE9Nm$6)p(yHDF#%T2CP+>mb2yrqvZB9 z3r&vnlj$DyY(EA9lk2U}77Y`k+v@Xj>HU?8X!boDSM|T+)YWuWON?pBAdRM&NmK3xDcAy*3@FC|fg$$nq)aiy$iVpU1y^h1gR|=xklM zGPrX8Y&(K05X5bGw)m|IGnriomR#c1q-C1&Q4&b^Ax6e$3Xg6`zzL|vrRn3RD}`J5 z)pB0ZY)V)m>VTnAkm6uQ8;vL0He8oC^u0Og8=`#?1wk>_5jP!ZKSoEdbMh)ahBnP^ zjQZ>0K5FEOV;r#;jEy|(ZBX6}8OsPy!`BnWg!5iQb&V>F0}8ZjsL0yVMB3#{t&$k9 z*DA~~rm>hfLrm_89C(EL3+Y>LSfEI8cg%-KaGblRHn*wO;m_HsKUYOBH!=(4oV3*n z<#^g&gS>Zo0&7+R`n4{n9~Y=k{(wPF%XF}sAB#gJexjEnc=LZO8+zC|pHKNYHDyQ$ z@bWqup?yxnhY1vC@!gXc-V-OD#~j22&$|v171FBCov-u8z3U)xgI~v-tkuB)AU2%@ zyk`!C+R{rJ-i$agB2fRGmSOWlz>m--xOec+nsq1Mg(kF5yxxy>3e&I>v1DYf7n$dT zX{S8h6!=^18jGco&zx;6s*P?2B_!j#{**p2Ak}WF4+7SO*xJ&@^&WSVSw8#a<*oab zcG^J;_p8TtrprQK#g@<3mZPUChAxL~ROD$W6B<`51?-wa55W$Um}k+~7`}y1F$QdT z-U;v*{BwAdR^k1`Gx7n|aExx&f1mJsDb`yun1Ia!D6)M;_a9%$Ljb}XiHV58IMS~g zj)rauIqHa=BbD83sBNg-8E_9hp|Ra9xpV7HRcW5O`VGuP=l0Ad7+T;s8d(Gn3{)2; zopRZw6Z5DIeGtW$rNr1)qME29U(!y{qoOxP--E&ju-Ji>Lv*Fck-qyS@u9(e->X1% z4h2==w=TfXBBYxAtuJ38(16#AVVLFZCO^l^u<;vn_3{lF)|yug^<#ybX=clHADtOvJPd`CoW~m7)OtZ4fVFQa;xh zvyK303*m2K$zGaj`%&hfJT;SZ;W*MA1nnAukb6QloR5i6YEFT>05>3P{MWAtl_cT> zy`eTVL{lwgJo|I_6TcBix|31 zoX(!zFz!6ZZP;v%;#STHqW+NdQ(y%?=TnWR{J3@&E4OV9@G>5Hv-Ug29ShXGxM<2p z-d8>J$8VElWkLidkgliqe%w>j-u~U&xElqad>iJ*Z!1F17u1#hPZW{X?zJ=h^M=4! zsE212?tH3>q3LA~bTM=Lccym0V*9XwM|+B;WX(Fj!k@DCLP`q((S`HZ zV6eLNGe`WA?GxAgF8q!^&Zb>4LaPPio~9-CpB?>dahg^^Rn5p1{WtAukLL0*?R#W6*(Jr)E{!=l0y6!EnSB`eYC z;)jgE_HlYV3Vg{zVW68aSaD07bQJ%Y_>(`eFNeR^s#oj+Lbks^MZ`;jn~eI`y!`wl zR7qm@8is-Q9H}%J7MHAFu`m-388kw@0&t`+H&lH&a?h>#hALf6ou&h220jKq#*P-N zRS&91v9bC0ic!>&QcD9XUt7Nr?;doz@eJMDD$&P$rQtDH!A|`qs@kyuHs{4dK%DAlAurK03-j z6D;{$j1!DJeL_qylX(5i`(|y3+B^d>!4G=c;=Xm+pRxbOkL&$=Gj@dFZD{j)^_yu| zV6mQf`~~)(_H_(f7!tx&Zxq!725it!-A|Ixd>_yEH|j65-3pJU+%4Xn8S3wU-oN7f zAATzhL|&>T>QBG=CINOG7NQ&A4eB!Db2?v~d`*OGd->Hkw|?`VzowhoF@}HF$NiaC z{%q_!BJ6F9*%O(e2h<>A}SktesF z1;2t_;MBj(@7~*-LX^T?z<4V}HltA;fxAllgoC6wVY-*Stqz0&3dWQ7!@fz=(yB0B zQhC#Q$mJeQ3j7xsn@rGhpLVqJpxQ8!=Rc30WBSMZE-Gsb-kgiF9TPQ3@M46QV5!O< zDMDR0Zr(lbrgfFSIf!cXE`gF;j?doRowjje%M-=lF5eZ*1_d-g@6^XZtJjw-QF zpZ_0C=l;m#`~UGdq>(c5&O|Y!tpgi!EQcwFpj7;+dn=UmQn zn2gwo}*-nvjh`IanI0PQF zN%6Wa$0hk8@L31T#DG$Yy(O9cNAGu`bT$wD^N^(iUH4rZ{FdLf6Q@YBL;xcEZAUTV zGAKLK>%}VQGwO#$M+!IJ1cDK~9y?T2NA(m=dsS;YOIAK6l^1`b2)DUDKcBfJVyBbm z#?GQe-hmtbcSVsXXY-rAU@_JTae)&y@8xp6n{pkWSIi#x@Nv~YLxss48Y9cJ zPzDTB&NnU}7#{pFeD~bCcXR&laDo8No5TVYeIF?!iB9>=3vT^Q+EEFrq1#e4w zzcsl`%unyF9?pX~@oxC`hx4L(O@V7-!2*PjR(TZd08?%j7A{pC+7qGtALN-F@bqB0 zWK%Jy3vYFlj_^18P&n1$Y_@IOeCN!#zy$<%q<0FolM?zH{Ds2Ih8aPtY>>0At4-a+ ze0Y7v^4QqeTA=Gh3VL2sM=2mI**kr}k@2qF8BK3oHow`AYK;gwTwie*{R^KNt9I%@ z>!8jjgNoR3#1{^2z!xBY@;ZV(!BJ9tIyUFyksXJDAAwgtJDBNTkmZhCe=UE7UaH`t zhZdX3owbHx?e)-BHqa-CJ9nls`W=tlq6I~99{K7QW=tkm7r3q1+(~gb_d=Lcui|d& zlv_RV>2~N!^R&ByhbaXz*m!q)_-@$2o)YAb%>dkw!2&_#7Z*=t+*bejZ6c}EFH8YV zH%RGQ@J*EYvv0(I4x~J)##~8$f;n|AVce886#?dKI-!0dScGg!;-s@vDY9M-ibabJ zE<%u>69$PK4;GKvKwx^v+0Wd~m6BA86!251?k>rKNE0{0)bIiEBjCR#JeD1i*9UTM z;V6M9LKHaQpks@R?Qw8%tS9afruWDIGHLr$jtDX*<^tLlMIDLxm<~xqND17G0vPOc zgY(r3aUw0NO_|b;Lt|hcu_lsG^}~8;Yj;5HaIb?$HMQS~86X|7+W~r2l!(ZQOD5g5wLV@(IHLRJ@E0#rFB}7ExQle6)F0cOR5ALOw=4vH z6W7K>v=#pmNGI7eCt!E-!1Jo56pBh{k#sOkaj-PcSf+!sHeg>he02+;td%cz|I^ZY zX7tM~wSV49;KykArVwqXb$>$Ss0X5ZcWWj5-$5gopOh`7c;XnlI!H}H;ytL*^d@|E zMwkO#5WyTIV4Wvw;Tj}M=FH-yx19C}z%bx-GR8_EQH1iMvw1JmAPa8m5EQ)54|iM)^# zyJ1|;dkCb{>eqiF()sU|FxYbfnxnjJN=z8Rk~G_Enlg9rCgNZ($Y!(y4ObyKgt&b8 z=K1jk#@hiVO6Y$ZNFdrlFzw%==2oqto1awbC){6<8G=L>bS~u>ihxsPw>d?ImHCnE zE+s;+U?MV|@I!QwKBBn=9e@^(?GYyN(>sz3R$Z_UnRHRg=0Cyp`*t4V=BWP&OO2{s zrZ0gxd2#bXfjX)S$`j2S#TVscfb8n9Q!B8ApF`g08WWllh!U=TB^FbfPY1VY>;!(# zoIf??EVDhKRo8@NsMGr^^_=}gu=#??BxY-JL3lkmC?~5H5+iAYl)A3xmCwh?Fjr8x zC4E;);22?f%@gT|h{-1{Un(-gec z!s4w8PDG>zSBeiP^#*zG?9B~7@X6OBJ3Pbt0(MR280$gZ`-s0yFwt|HNU9)|-80~1Lo?_B z4p3F5=_nsoXVlNb97VJM{Cx-Ge15^aWZfsgt(KV1gX(mZzvAyXm7ST*(iM$C9ex_h z#FL)cVxdxfGXL5l?IQ=@M{{QBoexvno1%`;GBN{0yw43 zy1tobG&jz&N)uD@OS|Fktmi2}XymIrZ1p7f2KN4F01>u$75njcv#Ct%&t?HieHafE z!A;)4e7aKRqLFs*YEI}?;azuIy-SYgNpFfv=QoP#LFW6+iCq<@08*1=xfo?TpBeGz z-?zER#*$$-V}ATiEz6-AfCMKN3@w26pPE`B`4u;v8}GSlV>61Q%QCtF{l#W z{#rl)OXTN}h0qY!ssGU=sQjgkAzlIUnQj3pxCJD475&FmeCW{r(Jj-Qw?EYO5?a43 z^CSnaug~>uhaPNJMEnt&-d#ceiP)%DJJ{<3uFx#}6 z#eSR);|LQEqeE!n_0qm`B&I1uEUsYr1N!y{p6@NM}AJF%-tat>0+lLXb~?B9_0n`1A_}GUqDa_V4C^J6FRD zP$ww|BOV7#p6TE>l!4Lui}Ws6`B8_#x-+(~*zve%L3Z-i~0#%l>a zNgS-Y5W}y;q`^@RYTQH&gSr8p^cTu!d5BLJT*oYrg;2UQkZO63)f;)px&>@oI8qu)t zO&fHXUJ^#oXf%L4IOcnSXu)tA(mjKXN6OO50`jgOWobeX&z`{PV8MQEu2b+B!V>}0 znu>$Ze%$Kb|F*Zs?O8W+j0(-03Sj{9D8S>}OxSCcZtTwgTi@Ial@}RAh!1g#doq-r zFtNp@EVI1rWWsO89HqEQ0?z*5(`Wp-F6kT9L)ibSdrCk5r_p&kiKPVVZ=((2!xrbl z!;(}viW0O}TQZpY)>Qb{{Vc4X&Fv^KJUAFV}v46BwsmG=P(utE-PzoSL==cXfe zP&vY>?PS?rdv2bU$=jDsIT$0)y^uPIt1mI@eZ9Dw`e`ljt2@X<^!@ep9hquux;^TL z+xD-0kWql-BGKYJ!@Yn#N)+l!<|svRy>_w|L4 z2lw3tuojmLWTFOCckSye{P#tv_ecUaG*J4yW)8KJ?wr7^h@g%HqdVMNHxO`_vT8vD zYB)a&(jIAKX{Hnl6bdvVtc~4H7~kN-bRY7aikSA>}dwHG6(j&7Vyd|n-uS=&?tPUz4v~a=m@nG>d~vdR ztOj{ZMAJimLS89n(%pm96$z@m6%`fP;hS^et%r?uK^@cm0FO`)n-&`4i^{AfMtaG!{fc`C z!@sN*)Z+@eUP}d66wR_kd$ao@QETPP4Z$)F+CSIc?Pmqw#kxSE?4%ymYcC=aG z5*uITDgFqB*;|^L~xueUA6Wfno(Zyu*P=ukKk`_`a4`?`cp!dJ84NooavDx_I%? z)AnGMox85T8AoXjj7SzVtSrG;MJZD+oxn%9Wx*RR(JKdD&GKV zKbNw{b{Ct;RRJ$vuksWk7bBOa#Yd%K8x`_75*$kt0O^+Oa>Hs-LL zG*klS#K>Pqur9VUevvdC28wIYS!=*&HALNOBOZ%^B?`tw#?tK6dsIkX@pn#jIf3KS zEwzI+07SH^lm0No8B_kYo2L}F(s}y=XMV5g;c(Hf`b~Yz|NRUfrWnVHMA_ms9 z8baWn#d0-|FZBjTVOBECxdb(THJl|}<@gQjh0l^c&Xfwq61^=`qH77zH%Od|HPGxq z5f1Sz2w@XCoKG()F3-GJNgfQ85W6;VVoQB0_=p*KPX({SyF4xlQ3PE|f}i8(NiI~u za})i+%0+JeZlf3m7j?iunw<}Gk1FTTTrz!b7#sD1j|==*KFOAw zQk{B|zzsvUv(LV`KoV>ym?NIldUC~P+K$!gqDw6HB1*zZj_T`O6}n5?pYz7tz4R6~ zqJ&G6`lIMt`m3S57|w?v%D6WZ@&=#d^^9=aacX@nCXgJ_G7 z0g9Kvj|~WESnSY z)W~l@q+OM&q;_YE>7%D0kHK%g#Mx> z2_;T6Ix)q99pQ#YOFbt04ArG3r^?#?M$suq>TG=LM~9qRm>8Xm*HitK3yFFM+wHJx zoJ@Ro$>lhco6p-dVfAhT)kk9( zW1GR6sL5sj-HwMR*H;ggR}a@j_NM{!?O0QaX3(F+(_a*qV{&(d&pWxe~8+ZFPNPPq8FOZ3!}=?q6fs&wnl_xZnn!QH=1 znpmXW8)Qdtv*4ARqlZ#H_Kvg@VeHam%(o3`g`(Fiz$}VRe7-4fF>AAF1nF=*O=1dLwY6ZD(M_eh1HZ z-Tq#WQ{UYB=I|o%=@oNa5nx`TsCYfY)?oi?kTrrjSod-V`uXhhL~I4L9%OpB6unI7 znhiKRP%yOYu9n82fXEUbHxX7gJT{hAJ-@!bqQe7-qc8iwZ?L@K38rLt=f|J?#c^2E z6-oBPZ=-5UJMKS^LoRS#DZ&xg?JMu6N6&C;04VnsSW2}hB#E@jW(=Th3CC&w4)%99 zwwGp;)b2G}b7%59g zPV!h3o;PeM{S-u(mi|}gU;<#s4#pc-0~L_8@Y#@Qq4ANB)zX_tFG;|QwtDi_f%tL8 zb*Oga9sf{Ik9X~OYB-X7mV?jew9_TRw@QU*elEnv1_=^PC^!O0n#g4Hkp^z$lb;0j zsqI{(w;m41u&^1m85NX8QVmiP$e-NnZ{d{*2=OxV#+?gu&Djjc#*T;R$C3GzrU3R1 z;N=Vd*U|d3;cO%n0fcK-!&J0sucf-kw1Px$9N_W7LyxJ>--0R1E!G0!Hf8v7*oJtuL|Oy>KRm zI9hSXn8xXV)uCMz} z(5;pOT3lhFlM*vvDroil_Z8O`>oNtAh`j(HdZ=bfXE)9~sYcvbyga+~rFN*;>e8v9 zh0j*44b4HD>*Kqrp$!cUI|mW}4nz)UV5co|@NXdEx4`sa-l0ptl9cpxmh?R1PZV#Y z9vs6sTxmVH_R`qWkkbKoL01XKiI-F_zjHTiv+EXkh{2QAsAhBlkF!yLNP^(sg9)1D zP3Ub8c}+Fz=9csUCsHNWIlKLvVz`8n!6Vr${MY5Jtra!+@od7sC$Q%Lk#3A-$)T`1 zH5si}g#Q6m50Qa+AKBDriq_=0N@unGo`J|W9q!UZ;UhWVg})Tc7Kw@G$yu0~N*}bo z0p$c&^pTv9d@=@s=zR9)x}atxWeYmT8+sIK=_K0=7w=8oItxLNqPHSNyGz09kdJiH z22D3IAjvS^ZH0&8V`*>Up*7vJ#;7Nlw9h81(S9rUf}WqmDK*0GGzSKS``>vn{Gj%e z6_eBimI=m|?TU-B{`C_t%uv+(yXEC2+o7kL6A%}u=mOk-sZU!(;CbZ1kgXL?1k`b3 z`;(@M zS|szETHdJ&|3y&i7XP>An5|qJbW-m?bMLBXi=c4#Lgl3U zuZHJ%YfAQQm&dtZ+_u0e9r#VZtm3)NZ2sCbPP%F5zwcvKq|S7p!H#G7}3@$L@jQf~Xp?RxA=sf4dNee>t%@3_jd4mD9^7e+1*V_CLyXV;6Ig zy;U`g=9UKUDIU5lmiQD16?H9NSjW$o||@@t@qvMbo`TfXE!;SDm&kkeBQy#y-vvHRNf6q zw#O(Ft;`LIkJgvW1QmuAaN8Q-hUJdt{IFL&bkIo6k}{-J#+VlNC3m(qc*I(1Nd**Ot4n8NFf3VsX#56jrQM zgPOx6zMU4y#}DbcEq|=JY^V3~Na3aK_kt=)*ZP!>o%74#gwPe8h!_JDn(}6rU`tzhk8B-oqr3_L;hF4c==_pYNnC`*Z3aPmK!CeGkddIWG9ssxO;yH5+JGG z27qfr2V@#jrRETX1N%O;ca}2t4Ea8YlvB@!jfbssjAv-$6d5Q?uLN`UJdR6)^B6{y zh~>Uv3=szIDV9iKDD$vIiH(Fr=yoZb%PCFn!aZ(c?TlLNK zckFB_f*uiTV@`VOoBo8RfT@ZRp|T&^cSF>uHFqiqI(}xH2p^8sj__7(C4Df@IVPJJ zV8DS2n`-*vioCc{!&8v*3iAm`=51%^!(|3odt%@3@A81}j^!ekjf_@OceDB4`qbn^ zMoGw)ltABHsA>`dL*wOGw6T1F(T>Vl-1*;%EJ0dp>FYh2h28MRNhG)k4^`xj=CP|$ z_e9`q!1W3TR(GNX0&9{cKhA4zf4A&kNajL(4fzdNE`H0#x?>=~oa*J6Db6q3`?3%4 zRr>8B?k8$vb*BA>7XHivapG?4;Zdy4kX%An6n=e%77gl45(Cg-zbD>*X)mn?oHn$R z&Q5-{mZg))NT;FW?r5h%r{rAa8twM6jPchn@>5t;072yqjSSN=IomTX*Yy!-(77S+ zW_Wv}7dX3+jy*B_))#M}o{`w1u+A>A<;&6rtE8+q;7-Tdn&KZ8?JaruJv(e`Z0J1V zACKC<-+sFO|rK8Ji2fIaVp8m*WS0XjB~GOk8Tnvd0hqCrN~nppP&Gceyl* z8{{2dpXXy<>jfP6lB(Ce!w+tt^dq(OkC8%8mr(?F2)mm+s@E}3OjgSm%gf7uXLO|^ z;Pv{qQ*M}{5@!wN~C~&nsS9~FQ!yOLNElgoP+&ihq!g=O9^S^#AEiFw3OxI3%)Hluu z_o50!&oL<}4uf*X39ibSdc}`KC_*IJDN7;a5i{C3ZMYrR)L6WX=V>4RL2*c#?=+aZ z5ZBF2!N>ztqLYZg#+K%j+y*JK^tJ8GjWKVp?UAtSKRfDI1_~S)80L?t!}`PS)oeJhi$FOB@eg3aw z^|+~@z98V)GT%o6hT~VBP!qI|qsTZ6r*rz0Y4dXq0sBZtu<{)l*s=T+#n_+@0yMiEMjw+6nk?}y= z0FI9Iw|6Suy-IGlGg*#>;&9w(Wg(x(hS_09A_Zq7jr25Jt~@^v%nKju+-iYX1AM%7 zfvA&UZPZRbbAe-T=HNE@)7pREN;CQ;$&Pdc+&zS>ZS zAS$kE#xsSN>Ob|B8hRNw&25pf>n9?eA{!;i84mlEuj4s`V)*nUhY!fT2d5X@iT$XPJCzuqB=0i6isPx&HXw z1&?$8XcgizLCAZ1KSMGGNe$imxn{52+HB=Oj+se1+Z>a73;zS&qcGJRa5!~i^iRD) z{Zu;a>x73|;2%a_>iQ6KK(_sc8B0$0d_1JQq9W5riP>@RipY-*-$~B?nG3^F`8jDL zmUO|K>(Caf3SZ-sZ5Uu(tZ=_ouQ|O9qqCIwoS+hUNmMn1F-5zd{ZD<)YE!0nMga6B z@Eb*%Yq`0k_(A<-t(!`wLHFGs&El?BqT3!RH)oZrM!x z+Gs*s0)o80uAcWB_B&2vr}F1Xm&izZEPwRV)~m#XS@Jh80K|(piG?MX+zF=(+GwSb zj-q=%*!EVD7)*Y_bK)Ap5POpTkWLXOp-?-!LD0rpucYDH*=QerzTPj$W=XgvJ^8_R z%~wP@w+?oZff={aw=*#?B%7!$Ih}^4cgt2`Qe@@Ne$kGpB;z~>>)ikv#Oy+uySqo0 zT8O+=zde^zVIdq0{c5{o1O5|kX8e#;WAkFxNb(IYe}Df*n~UdQF~)L+C=ECQ3yTHw zr*HKH49j2)yn70Nb8<%{V%=HIH=&2r;&qfy&+|`stJ-OiV5jMbt;w-`y}?tpJ4s*= z8_M4Q{^LjPHGiv95r?yeiu3vk64yzbBVCgR_d&yB`9x#JaDQ;)JDalbwS!j~AeO*nY_>?77Z)_B}HEjf}PQ82AoUZpk$Xc)H5(p%%VN1Efmc{|st__->3PmW1 zL)4X?l&%cwh#gT|*-HJ`-%Yj}yFAUTjwD(p_!%;O~O_JQC09 z3>Srh8ZMk8g6R6C;djjO!{cl%HS7;rPT97<63w95CWwuR4KJ$}?h-RElr@cz#Ch(1 z82T;pnsp={?h-y7IL)M4xvW~J%vq-B7x3YJZg0l`Hj0MT!`<@#`4|8x3YNR5Ot*lx z!TV6hM?#nhO{oJ;u*i+->Pi0+aCHR&vw)G5@BCb{XU!9Ssab#M#P<5^nhs}I{0FCm z0(aAj{HMc3ckW!`RR^}dNIyo5(JeDeG7v>P(>3OYMSt`%l^*KRhXht4wkHt z*fOmYCy}N@RqW5dD|IIOj`djsPQ=`Xaz*iG{0&QWm{Y>LUyX6Qjg$V;`F{|9o1>t> zIsp5DC3W*Tk<1?i1#K>ECsbF*$QLgZ*STqsNN8Bjpre=nNF9Jfr7{YjG@#&a4%=Pv zEpFa;ejaR-ul~nvvNJ!aKMfXq6E)2r`pqr&5Jj%n6pJmX@=~A}AKo z8PKwM8Mm-JdFJ}lljAj)iAddQ7-i6EtJrP4+!?|Ch&&Z1p}Q`o09yTv4duTcC}+Er ziAGMnTex@9-nGHt;k*psKR79MA{@_4T+vU)0>q3XrxtT&00+~pT1{Rx>J z@Bo{a1!-I1)mHWTlQm@+4%UyR$Hn!GI7Eq%@tLz~L0IHN*bNB9r+VyC@POhm+HDsx z$T$*$h&R6IqX;@t@2kkiI9P<;V~9_mC(ItG^BTPUFyyM7c4;qAEump?xQw6Ewp@QfBSFA zq#02u&T&ay`3pY68qZQJ)5}ImE?wraF@rurvksou#lp?3G)VHhmziRn;6LI;J6v1f z`E^m^da2P!+s~r~VqF&XVd(`$dS~ixfNyVM-dcD)Fwk#?r4;6Q31UfYE+wc!x7$Jl z@RqE!niMBy6cjDSs_*^$r5yRXENJ`S=3LF+Q}#cax5q1vUCX)p?fVnr6$^~uiYzAJ9d-x~w zUHD$<##`Bfg%_VDjEz-;eVeWCyvQ?tCSd($?H*Y`iOJ21ya$Fw>6d-r&cl&&_Cv_- z^j>wu-}4dc=NmhC3GGTRovT!q1PRY8XTQBFJNN7z%){M%I%GW+28BeyEL;TXZ21>B zL^RRk_sgJjeI*yy{L&`f>O&Aed}S8LRkhSkKlvLMU01Bv3!#1cV&TC;ghi7Jn;#$@ z5bOr;cpl0Y)K-q1_Q>qkEJ~5(uxIC0hd?E#l(9P3?;gFYiJrRM+toHO2Q26ah&8l~ ze@>XS6DnQx$zsU=S`-BP(f@cZ8UHxa2~-+DDV-Vm&bn73Xm`aX>*d|^?No{Z)66V0 zJDX>A(lAy+F|{f#WS`wyZ>-)C7YQ)w` zW|DztB4_#HI6OK3B$yPn;!8(`aJn{`_bwbv547Cn7mS?xqN)$qfJFZGjF1%?uz&7) zA}($-SUw}+`hAB4W6R;;iHQK>Q>I~-8nZSlIEN!JCfpm2x7tp z71kb9SoTb2ZR)m@VIiMG4S0{04M`|1ZLuMp8YfjlR=YYL%#{VamouxLUaq=23wn1i z%y;)6p2T0-T>ox-d)PAN0pY$_{ls#Dfb_41@W8i2=HMR$+YtZO0W!!P{IjbcUD$Hfxa z1=##PhPalUxkM>8Nwue%LLXvq=x;;_lmOLQygD%56lB65^FgLvj&|Khuvtg|1ONuh z%T(a@=>^VKa<9ji{ez72ok9Q0{I*NA+-wvVYPvb>WzSb75sFDbdd>+_^Ls5TK=~KO5>?ZnvZ8$br75_YPta|DsiBT?>JF$sdHyBjZp=tvrJO zgcdfQ$3SpdBOW4{$9X#3C}t>(-Skbq^53b3Xw0oXpG14V@l7GWwVz(ltdqZ@4Ez50 z7VCL5-r2Axa|T^K%iC_CGQ7#$7`wZ2a5`{D=zoOIy}s5zppYB_fk_>q)?Dh9yBU`t z44o0Zc?`o2dL}Gl5YfjFpu^=x|JIQ{B>=B%xRN9#)llwVoS|RPJzIY1SQ@7r(64&R zydOuf9l@c9uyejoB^<=OM!e|*rxFxArbXGKx1b%bqE|u?=Mb3d(_0q? zOmHCH-qhG=c+Wf~Xw;9^rN^~;Cg%%$mLfF&4^aUCNfUKUCNp(r_`$We$0TQqwp!k6 zk(1$hwww>iKJH~2;BEmNR_-YHzZvzyR~yoKf3ab#%0_k;hM1dcHEP0Wy6$rb6q-lz(HlJQ{TXr&q~&GJ!?p}t zcLARDHkU4}=drO#MS7i$#|V^M;({M6Ep2$7}bm12LZ{Ysr4|11EPsA<>}ZpM0(GxuM0^qu9BuI;p6{wI{;L4&bFksXPD7R(f}xf7tzhT%H< zx~?Lrb~e#a5+wk;PP?DtpqmAFuuehWHRZr@BF^-EkIK zHe${x0_V5C+|Ne1B;ueyJscLt=@#Nw91{P&v9Yn({khyV^Wiqg8N=@Gp+O~;vq`3- zH&!R=q}DGfisWuhA>y01o+p&My};9sY8Cw;*|!Tm5siX~M#8`U4E=*ptROj?wKg?@ z(4*?Vj)h2sB=LS32H~9kw^@>?lV;%(EAiUrlwBm|J7|GmNm>`R9$nGuWfzx-c|~jr z-%w_suC5+E?CuvUUtBLPMvCj(XvR;}U0!ce&K$2hV~}RIluQwH z`y{tHa*Uo7C(bGwJ5xG`g}`h)dD-b>-vV75{~jE;%Vl{Y6lWR1S{7OJ6Py0kljK=% z+aT`U+mUwh4{tKy9Z=%^k_O$X$}Ok~DA{Zu{sx=VU597;zlRP3!&UnM9bv*Yj9vZq zkniO}aLU8b$O<@p`fT>WUj^}xQM3OmN%VS zuf}bBWBdEg&Nw`Vqc04KQP;yjSTrJ^Ig$3_S`Vkzy|?QlwiNPubaYy#N-+h=3$6i* z|IHye2B1CbAOohSTM;a9mB}p@j|SToZeA=q0m9<+Rf&f;3eGM9E(=daA)r|>nXd#p z(i3?YEAi1F2OmhF#-GJ-KzZ{%pO(EELRq_B5M z1U=Ug(XdfqG-|AyD(DZ@se9m94)dB{ywmoj~9MvduBJR?Dit|?B;gd;>)`_IhApsf{GjN0u>r5LW88*{3VioeHunot&Lj;|66V&w_fOOp zHe@nDx`HW?aCM-hn4bDx;+k+`>*no4-JzP2xDdudk#g^Kb2FRT{sYgSWJi*`Ump2R znMkjf((Mo6iR>G+i!cgXZ7Rv&LhutjM;t9rg?(M|uO5>ytgc%n1ypyHF6F=FfQ8TwC8#TRq0ogb7v zk!XLQ$=Un7Qz)9#dxQv=Z}f||gE~5;UClh(xwy0teM9I!k2J7Vn9u`G!ShY|O7xveH4ATJ2nFf$=4a;oojYDg8)wfsu<2n}phF?kh@Ky&o+b|0Kz81Lmb8vWev77wn(m+yo zvbm#t#!H8H)5|aLXjYU2O;HPW^(mf%c{EmkdK1ms`*x(jZK4Y9hqDyW%3E`9tw?uN zw6}$x)gl^C$frKNI-o(q;+S9k8*e~QD661=l-pK}s54aKoIVrA{ZLE{E}c;I!G|{X z`qD)C@{8w>MEOm$O8uJ6$A1;L*JYIXxHpb@_GbDuPOhx4<0YeDACwfvVWg4*7Era$ z;~6~4Zujh^mE~fd%pKIm;ok7w{k6jbZI7vDrPkC&+srk~^k`@_k8V0JK0YNsg+KJ0 z;)w9~|Ldc+>*f>!ZC6k`pl{C2&R~apb<-pM4H_ay5#DCeu{z)y4QQ()>Ij5Q znEXc+3(L)ePJ_39;UP0yvgmU|9P)2*2i(T`au~FE#B7)~{+$jOTeW6&vm8ZZH6{gf z&jSenj6KSj*yi6Dv^v+Pom7EAkc?5C-69cx=5AFOnjJ;h$FFRu^eAwSVKgV0Rh>_|86aY!PBGl9Y(Ee9R`QpwUT?ENo_jw>#E2 zP;_D;6%NrXZw>#KBNzEP*x`u=TdeULFnK;8oMJKuwVg737?xoDjMmb;62AZ2bN>g3 z#O^z)oPGhz>vv~^UcIt>|Ejy$be+xfdqF8GgeV_8m)jrz`fDmGP848CQ2lyM_{8}h zli`bH$05c#G^J$DQ7yv)KGLguxgL!T%3UzDhGj|&9Ps;yda&zLv0~CE8uxwW$5!hc zEbH`dq7>*F;3u&ewRCw4BY&D(FE%MIUd(@gRNx`7YYA!m(2Pj-VLqvhJs;&gvRUkQ zd)174<@+8hf&}|JC2JrK^h4l6`#Fq@Whn#vsnZR#MUEIwwS>KN>UzrS)=*q-sQOl- zf4#=__T?er!@nN;JG0tJ8Gu1O5>!#6+6ojCEB3#A)RVIW@Shxpe}z7=Mnng2!p&=b|S6O3Z1zS-c!IVOGAmH*K0RBy+5GDrtQkKN1NK><%amx;pr|4{g1{>0mGJ;d`TYvH_Rbg`WD>-RX-_11 ztvFM?`xpoLrg#BSURA1V63U&AHk&MXkxZry@?d@5|Q#b2uv*1X|hjD;E&nm``P zSPd6K#jhLP=Cd<3uNWzTM?Yod`E`t>ka1k{-}?HxuX33J$d1B@Fa&68hgv5xP9;d_ zDi3dEu1o!JZn@eRxZ0J_A51k>yKu~@lw4JO5z@3N6&a{_#=y_#>RFaZ%3781T##KU z6})TbGhKca6el@t#3-E7`nYwC%FRj?6-&(*d!#B=AOHdZIw_94?98QaZxS&1x>y*e zYMs7(D z{tE{ylm&u`LM$8;y$(B32LtIDUiF#0XvEUWXvDvx5vg-UUJt5oUo0b4LvxCYsd_ti z#PwSKtzTSZ)%pQsPMW%3LwFFvikz^{8R4k4>AeiK|FGeI*0dWZPl%;b(|p3c>b|Z3 zQ81~p7Gz7B;{sosX)uKgUEll>gR?|N<4>6=f6f6O7;YmH94kSzBeFo?CeTWGf1Og^ zSW%7U9t4#t%=PdXFX2@D}t}&vXk}JHQLXGWEVtdsA~Px zQqoa+TJ;@24%T>4EW4yLUg64hBT1Q?Ce#LELSse$QwlJJ|D6xYv8yJ6C(k^ZH*cIG}hVgfs&zme36dKGs+W3e!G%Pb8|`EykHUR zXaFLRUE_Dv%3?z8^PX(k zi6$#E(O5=fLwWNC85U(E7IS51dEyq?mhfU^dHws|`ucO@lX-`;Y6p30ha0VLo0~)a z?ll)0W*zKLA8ZDwZqNJ5xo5}+i@xI*y8#yx5NoI0gtHL15qg5%{9DacQ>Z)+SZ<}` z+X+7g)%mnN1ad#GFL%be&PE%>sQ#=dLdd6>(2u%mr{_P?`y^r3JZ~KdE%hJN##sRR zOVsc$4V(t&BMg>wPwZDY3w+qdWcUR}xo<;z^cL0=(zf6$?B5F{vjF({Oy(_Gsv8k2 zk-RwE@fujGw470(^Ql4V+o1jc$~I87_~DF$-KiL5v%MvWSLw({k0>&C@1)uNs;^tN zqHW)kixoZjm=D!!{0PAcfxAT|RkQ?~+^QWJajBm;YcMgi-yhtnO8I-91nYQTe8=0d z;o!}+mHO_wg^|Vn{mEYkb`F~NWKi@NGmgmDBm|{7^l)zA@auprI~)P06)1;o{^|!@ zVudZ9-H7#!LuZnwkxs<57QD?9}lN8;Mmu&Pa)HwCFj`oi<^3)to9SQ>%c=@`gzoL zzdcQQi8qiW5ag)&%9#yyYORXePzTE?zvfTH%gRLK-z<=srffY)^6~FDVHVL;y+S@} z4aTt&oZZH1mqS%Wj`v3p`lUAn0hL{o?awuVv=8(f2Le8ZkXF27Z^I5Z4 z48@WdD&dt=<(yMFO%akzEa$XXLQXk<9`ElD-#@_R!e#S(J|6e`?RLF_N3RRj?a4~Z zm3e)za9(E@6cgvyrVoV%Uy-`!sn*Dt=%vl4xb8mcj1~2 zEJ+<0^%h3iw&V(%nqoRm1&{x!WjIOQM;KI9v*st;-Kv&bH%c<_N+x{ZE>=tCZ4D=Nxf)>h-&r zsEZ-QUp4Uv;PUdz|gWE%R49xhUVVv6Jh$ z^T^}fQj@chi@CjmdU>MjYI5+rV_$4E^NsDBw~`c#QXYB6#O}XGU4n0vB*LB86WKgS z?2(ITNbi~>Jopt@Xv5@AF+X|mxk#XR9D7?9F?jOIob$C*nhvtT_c#lG^Flj6{?HBX zIJ7=t*?bL-!Fg$s(OZK3`TKo~JL@24sg#q(iP7Ad;@Nw=zvh5{3ZN!2QvbA2`@{QN z`~UtXztZ?O36T3&{`$Y;r2_bS7VwV*U#at%DIYT8;W8188mra8$aDF5U?Z3*L+u;L zyBDsBlNwrPr~63oOvbS<`Q+?Rld{2v4IS+<56!GYVA$+RzmHkn#jK}g5 zqA4^=hD3(V%L*S1gvJ}G6v&!b4#|LdmYcfBn$P~wV~5<_+~)9=gn$IjpXp}`9GYWN z5KhE9t!7;jsyX1o`i4GQDUDxhzD9bA(BZ-!TKY3~l%Tux;^ocqliK`YM0Ei&AH00t zYLH#@c|iJM)a#+~#`g!MvMgyAA;wIAl3a7mc=+k8W#5)8jhG#emDd%iUAw-4C8qk@ zu^Yp&!y)T+vCL46E`je~#`5jSeLV&BUokg$*%6pFWnIL9R-7)6g54eW?+QsNzRVw;b4=-i9gvztebkAff!TwBV@-+Nm~UMB|r*IKpw*If}l%&%vSt> z$Ih>j~Eg1eV$v^K{yqd|G zd*~mwjzls&{tpiMMTO(N*7PMB${61Iz+6%I2H}WYhe87evV5X1D(zNsg@_is)1~HGQ=SwPWch&=qI^e$B_UgCjA|DSx)O zorJ}gfF~QHk7(PSf}jt#(tkb~h^QGq3~+0h4*2^ZRWLFKGIL8Kqq&gAn?7_6qQqsJ zp_@!Z0vYLbv`~VGYO2$h@@&Ih<{eQwPXt2`Ioz{v;a=1y#!_LQa2_$z` zQ?;Pv0RsuKHk_7s%^NYpLgUPyGqlb3XTtYqdj|e{4|vp4Gask?i3my0^cVM6##Lff zMHscaveLtpNr}stwt9I zi#CB4dkH^mIY=qnqREGy?T(wL37#`$J+~$_UzAbDlzKgQX?Cf1Q8WW`f z-YAHU-I)Bx;w)!IFqkT&V4lu4u~LqA2v7irp9Enf>Vfa`4jabwR{Dz(Zw(MkWdD4| zwM>r!mvPNLU0%}gGW!r3<*Y88M*D_v&UDpD_#Xqb19im+E_ol(w~cbiHgG?W39GW- z9RjcW<*voCiRSI)G>r_-{S=4&dsk{+W#0}D-UKM5MLBuVA(O!9==CN49A@~K5`DCl z^dAL};$HlzfTy9DJAbBHN=yNKd+GC_@OY&Q7d06X#g%8CgqYvvc2U2PP#!un7c_a3 zr&o&bG47Q<+_TU4fAQ0>caM*j5G^9Ql10g|azuXx5rt{&2bXVa(bh-q5 z#xD3@p~Kca3kw3IO*Rxm>Nk!p-<;Uo1fk%)VaAx}TXlCzT)y|g#1o=$N7w*|8F13? zbUN(Jf&uqL^Tyv(w9i8E@TB)gbQK@&Oo{Gb<0eOvyFjKDcQO^NTY6rK>^PqrO5-&? zpat+VKo-&2xw&&YyrMyb9b`&~PvNLy7_E1HZ#hE>f*>bhiZ+(N6K8k?3K**f1<;I& zMKWC&iI#` z{cjD3pS}cX9?^JW3`~A9U??!E>P3BMI33@`U)s_Rvm_%S9|jSXq?m6^JHRjM z6ckbmmaDoSBs{nNeEmv#kh9%bCapR&(G=MTf)L0J$}t4HqKsCOiL1~#=yOLFedHNbkFQp|olK7|1bK!+F2K+tRW}2MZ1DF%z`H}?*^5P0eW3!|jfPJ>A8&=+o?n>_PnYx?Z*iiA z8f~JaXGS;SjuWMW%S&GGwn{PeIXQI$+dZ=dEvz!YjuegB-`3&(V11omj}hFSkZ(Eq zHRZwIJ8x}YUB~Kw?DVZ09Cak(;duYndsTn#gma38?aup5tdW;>|GrAQLi{2jPBM^F zDI`>0>gl;8`1qPvn~dvM)kL^1s>a7eCAVJ^OI(W>1H&2+Ig5{7W=#B!3|19>`v4M` zb0s-8+jk*!;BsN^c0?p*XAR4Xp@l6CSsE*}QIB8>S9}rO$Tncc#61e2-BY07F1YVV z`!*TB5pxv;9DN3z)$8$xmQG=^_+8nYm5kKfWnAC|v$LJk-Yqs`ZZCK4IsDr!HWLlh zekJPA+wVrH1iPtUKY#w2cHW%sEU>WtK6cTc*33h`FKg1+!iqeoMaJ?PCn`g_kRv~S z38O{EF?B$5m4G!GglRo}^tbhhT-1_p{S|Jf_y1|Zwp*Cgc!ad;cqE{6qhVbKA6p{G z(#6E-$+I&QptCrHsBNCcC%p2s37Nc%CD2PbXa?yL;|EG9PpMkE*oqRqHUqc0sW6XG zI>+_lORf&g4P=PDud5^=gZk{C0ynagu{i z-W0JK5#n)AJx}{6G0WygN1Q8CPMQ^=9){M1l9N#w2t;N$d654(sui%u8J%#kEB0|W z_Ve+&IuvRLjIzaRw+Gjb2mFbAVaCUvq z)l76XV-Wxl-p9emU34jT_LoFsKd&`E;4D-!OmFcjd_bJ6o#U0^xO=de%gI=}oK;fc z#me2t3&<=Ezg}ngp=A-F@Bcxx6Nh`yw1KHd;aBBM(q%7KDVf#Bu@!lWy+ysiP+m`p zYh?x0+WR30|Ia5Py8r7EMS*z$h7gYm4bAyLvG6VL9i*bunQxy)89XmG6w|AmSk!?d zvB`4L~WBEB;Uakdak;*q+wB9}DD^n#A!f7l2011`c`-W` zZ8>~ivc9Agt~E$E+5j4*ZPdk97&}hMJ{h#FK1-~D;7=Kpg6 zey%MC1-0gnj&>oS*L}0rwT$20cfJmf)e9S9s8zrN=9#@_$AkVd%7sJeD-hoJuqu2s z!}jAD3`UWsoSai-%XrBQl52^^Fal zx=?^6ARfAS5r1PX_krb!W`-~5Nu7C!!{I}=)=Dny!b1HTVfoaWBAU&Ym(a2A` zwAv%N>13v?n))e?ZDOXfX?Tzy5QMi%jDtc;HLE@0ji35nBaTTViRgLCJ zRuMPycDan}(97e;TwoRxXNc$>&dukG+i(aBGfRRNn|oGv!qf%yK>s}&&xxhQYz{qk zXRZv?8&~RjiD#^?mDXwQtX?s4%zlw3s;MGuTI@1ZYnNS!VJ}o_%{r$+d4tubk1F+7 zW7~&V{vjUaNTOxZT_+dveYB+!vJEw5|5AJ48oz70>Zw8l-nr%z5|P#qkGcBh zM%Ta7%v%T7YPH9%AA5UmLhqvj5)>Zd(d4a`GnWd6{p@G0jf6zLheBC)@3fMGpC)e4|qFoHXs z$?lBai(D;N8Ww^{+Hf{(b*mu;K`BEzo&hY5O~`_U6A)LyB+5s^-nl->|Z} zDcaytz|aq7?KYIK^yij?lyBP0R%E6*sK@S2MW*GcZ_fEeZ(oSn6&2Lm91+x%lgjwt zsOsOl{Y6lG-`N1!pDl;o$K6>~RWe*?{f;Ljw1oBFKR-2kY1=x3)${H#>&5%~LM*Ah z5^Wj&<|=(1V$AaO7@wFo`~(N!FCT(vi1^7UrM%tb{RM|l@&ZORb`$jATuD#3Mt|~v zM^jTnwyC=YZ07gMV-U#?SI;+g=CV0M07@drvHZ<7KYHon{_aG-pgUvi&)i_~{u0kV z+O{9a`1jKHkT+PU!tw2V z5BF%ehT)4NF*kPk0L+h;rQ6-&D^zsgiM>G!!#A31aKu>R&{2Iitog_9b&iZY5YDiqAs7{g>9-mg)-04O zxss$sepA8%r3yzx^a6Jz(55=o*dG*SgW=)C2RukIrKS(Z3sz*W+kkO88EE>XpZ^G# z)Km241}Dg8vzuVppdj|-1v#M5DpS%jsX+t773}xunswgxWErr%umNZ1@&JZVUUkcS zu=Cr7k>}YACHd}JR#Y6Z5`lqBKfGV33`>;p4rUc>D4^M83fSr;_~_tU2qrKl3aY}~ zec>2h{0-QE$Js)2yPV>Y9zl5^{yH9oQqu8Zh?~|Xg5jpN0Vjf=nxC3DI0xP{ef|AF zjG1JS_oDT!g#|s>NBb#AdACIEK2lV@T(uD41w^j2<2^8j_XT35wxTKLpHUmhrizl< zKk#Sd!@AOKM67@V2UzXZ;~~&vdcUr9t6o=jM)jpJqJP$ zt>4?=KFKEL!B`K&A&8=X7K^LE)Z1iG8aScu8w-isF?fxo+bMSnR_CrtDb6);vq_^I z#wO}aa*7PE{opCJf% za(w#}lRLmA^~0y`lCrm@Qnk`azPz6ulb;`blHhdU&~HIAzl1%(6Nh9E)E>O}Pfu}5 za*X#D>GriN!r8a_tsYqejetM%++z6l)UBFhX3PA87Xvo-T59Nio_YO;uG5+zqaH#1BFzXyh3w9!%qBcd)@H>lCJ*L|hMEBlbV07tPq(;;e8Dd|ezTSf4?sEfXt=_-{- zT9Gi!>^U{{aAW-7B=x|1SL>0Um@4~#R&DshN#XQ|shT;xInm6!7xX*BZEsmK{(>Hd zen3#vo$AtcsNLD}s?}J~*|?>h-@oUox=7Py25gY!WoGk=>6Li6oa8BS3a690d3W?K zOVs)YH;;R${GYQ$iLMVhIJ{r03xGf(4yNUwpwL0YV$hN#OWl#VDP+i=!``0e_P>Jd ziT&%b2FxB|(2&Fazb?Ipk?t~uayJAa33q65wbRtaQk&yPp${wHRdf(SW56YybRQuG^UFO& zLAiuj9Yn%J%=J?&0{9=#!gOHK5Z&yjp4Bjl*TDbPE%EJ6?G_uK=A$DXxu;i(Ua~>s zs;6d+fV2z5z9zOOb4R?#m5+jw&d*Fs)tp`!6KFx&(L6tsolw+3qtksjtq0};P`0sT zPHzIDa?E$d(D%i|_#%Qfd75;lygAT>ar#uU#F=he?j&=|3nu(h5PnAK?vE5jjw#

    UFk*xrGbx?lpz6|$~O?wY^f-}k~4I+ zRoCWX#4UEXXLg9yIU8siN4H6Y^fmgj8j!XyQJ5=Zp~Tb6vydn6k{HSaHP;Ai19s>* ze%H;_smBwW>!A%57}9&_(bZ-p623K@p@clfu_ErbEFZIe51VkL`=HnMHN4l|F7h|W z0_ljI>6cH-PHb(Ahi`0ctxxya85vBhhG*_?I_yasUOD}(rNq7^##+FYU$19q{#Jl7 zGst$dgdoT69Cnp*5YYJz3U+m*#jUIrkPvV*`xIM=+g zJ@zN#RkY79wZfxC{>|3K;Xuc5Tq=4Z(DaQ?wC1XuBmN$#YlwiDo^*@}-rbs?Kb`s) zXDXQiG}NO)XOBhAd_C%-xlPIx#5Zk>M}j3UUBC0qx5Ya8DAJw_!48?@SJW?Mp=ReB z=C>pbpR-u3k*L$t(*2U{PgCfGs+PsZ5;yW0W+B}y|KcG1?<9s;+$9Cz12uN%P0r=? zs*MB5k&I8H0HAK)M_?!zJO&TlgYb6OsRM=WiYxF%f1_fwbT`ysq{0SK_TXI>GkoW(P^CP z<0@WXWHA&jOUrKZc8L{n;EpApD?`1!B=`JrJY<2YKBVwLJH)OB)t_Egl3nCe%K)UO zVVVaaKv-}4wjlmPGNJ4F?QHpcbprY~>!Re<6Um$c0ZJkam*t%xMZ>|bZ(lPu@?)3h zLt_Bry&(2qBN(_0Y;NYx1?l7NPvg45FV6R~?1~MBP*&CbA5d~sl#i}&t~^FOn|rZS zy#GU#^=xxSbnj-euCgXogkS1Xq1L2(>}EzMK=4XWt555)*r0k_xs}SDanU`^*!|GG z)}2WMe~k!Y+p7}6sc*mTld*tS_)joDx^~=qFJof6St+%th5{n1Tyf~X{rj&b_BZ8Y zT5wbh7Z0}p5kY#ugXuZPimz?RxXAar72JmeIYQ;-uz2|UrDNGVP@2Vubkx?+%`{+KUm<6Iwa#-GjYj+UvJ<}crsd<9%9FV z5q_**U?L0|$ecXs9Ki2x*ewLwc7-5ilPI0ERjY=};xkV9LJp9FF`b+3+aa>D3-f$j zoa6826Ssu2Ho+A<%A4PGUFw?H*{ZWwj|ExY8KQY5j%sJ0x6d-$ zM~QX7Tq)p-=1RdH#(+nKj}Dv>5ql>lTVN#Q-HAg&mkh0c*vOQU>8dwgMLsGHe>jUL zHI!gF>aJgSAE|w?6^4Hg&wVtgo})!-2w7r-O$rtCMU=k)?O;>*qh?(wjOmQ@*|=F) zxKZ?YYj< zmGA%j{=!Gd1K!G3 zUp^HDdfCBS!;d(|K@lt-0S-38(Ctp#V{lU`DQS4yVqHEg#%p(h{MzW$P;Sps$ujp7tN1O`ItTG?U9I`DYVYZ&_+*!t+2$uPGOI}F*{ zx7|>VrCHfo1xE*kNzWqmz$uXEd)Hp(D25+za4I)c?q2}5?H*~GWI7X~iwLbg1NCt`)dmB+Uyn?vOcrz=?1 znU+S(F|?XXN{EP)V%rQgnBPLC@O-Lb-Yp^h58-i$`36bTX~t}@-J(o;pBg5NQ7dxD z_+_AS*gKo?BoYTqnNf4~@D(m3h%2?mgV~5eH(IyyI`qC}Q5p{ur{QSdjz@>pdu*HD zoPi|BmiqORuGokAm&+#*tvXupb|_u?utv2>0cHGmVo9aLKJC?`s5z;~(QW*y$P1wmlZ+uMF%t1`U`s8SQn>S|o$_I6{k z0*QS$jbHO{i**RauJ0Ta{OAA{0=vBv|9Tt!noVSAa6G&n=co;Dtv{cDcsetaVb-!f zHL%KQAy5>;sw@hUKeI5BVsy{pXt#@=HjZjab1VBKp+G52`|5XsQW<3ja5W)OZd{ zBeK8jv_vWbHWb5b8X89$*}|KJaZE&8g=g+EsH;Dnq+V$l_m*~{R6=+-+Qb>0v%Z>G zS#;z0C||%tyxIzy+WMJo-lpQmI0V)yUo8VAD<$~wH(W0IYi@7$Beeh!&XYx*rL;oT zSI2GGEhdig&*bEsz{6qwSWU+)bX=vh-K$~YE58v^4>Lz^3hK#*4Jr-YQan#n6e#um z)!4F_P*5;4;%%y;gL;cVwEfS+A&!}r&g*B|lt#RJ-2NVZ5TP7=<+_yx|Ds0N(q?{(Td(}&d^_iLGx3&18~X-q=(i-NqyOgqTgfw;@NW1oRY_G+*>E zo`~W=*up^`lUKIB9#oP(Fx$X^F9INhvssmPG=6u7Ce z|3nSkrSK|$7x367;bth7E=uqRmd_~>8@r(m&!VHFkFsa=@&KO*22(aSr10PD!f3dH zOfl^SG~gWL9~D$>b5?4Q6BdWHp9^@lk!?J&l zTLb01{Yw%2V$;g_kcp0vIB~UdvC-6DA3lC9Aym#=0bQeLba#;fpIyD|lkcRY2x2l(p9a&BR{;OttbNecG zRKdZKOQOvie;6B&=IdA|oxVmSBZ2^jT*1lbf_m(7#M@Dk{JhxR6BBqx*|CFD`@@xO zq?Xq-lC(3~#R!n;$&xaM*|iXNp}n>J?N=hv%X-$dzAQr(fb0}F!t?%?;{E9lH*(xQ z&Pb&pbzeEOMC>n=H>-*lTlPgjB3|;j5(I3X zG1+de)}{c34JZ^?+EC2K*8E!Mre5|>>YF03s3nas9(D-Q?hrb`YLa1U{9FDQ3hwF( z7&aJ0xOQBdh)IBBjM?>lG|iFCO%Zd1OJTB0I<1LHhEZ^z!GDgqp*^#_+PHZ>JltIe zasq^+!;r-6=ipor-U}p~GeT%6!u_k=9It9LR8*c(lufSiA7tA4Ka_kj)GfV05Zz)E z_pT`W%|#$+zwtT~>et1P-R!6Vv8vEsWBtPr{$k52s>QCgGCcLG;E_6^Sh1 za+z*E+IrLHs{(A%&GkN_gC8WEwLjua$aK8_#fES zTRS^nybxr2{;Kn|YLlKzm{iI3-eIY~S0H}g zu*-JyVdz;<3pw>2srO$_TFUr%!(T5ZZvKYC9xz`{3bVf+^H%7zU6Soj)CQ-5ez(D% zp5$7;ciT7j^LR9p!p6>LeAHF5J0Cn83{t=&rPr^Ef9MUrKD@SD_a_liQgVAf;;pSJ zQ{-ZJP(9AOF%Qd)f1gE?9=-m^(&)BNSxL@rXQyX+M_)s&&QAFJpJ6BCmfc(jDauKa zlYmLZ_i2~~iU~%5m~nmh(WE*rm&@wv9G^^N-^k|3$6Jbkdu%Ao0nd1b%oC>}goZUCN5k45g1Gbf3h5CZeu$h6+QuO^AQf=XRfo>@) z`eS&eMsFSTh*|jH$+GJ<6mK|Te*wday?%R;6|RAMG@vkbCXfW zPu)h{8cwlm4rZL0T^wr+4T;eb66Rn*R30bt?bbL92=iVLyMl^7;}~VKu{}0eoHoCk z%DdISx4GfQ(G@&+F=}C!~ zr~+*2!ATD!(LsmIy{Mgy#@7BraJM@$+fIx@t1}x9cbirEZU@XZBY$C*DT- z)iD-Bg0p{Y{27z!p(@_a%{4Bzwpktf{PmcmG{k|1gI>JM%=iJ9vcQ-i25%b#H1+{A zFKgNm9HLr4t@eziA{acF0HxH8eP)A8w~{TqxK43tfBou{{Q~K}GGZ(fd?(7g+QJAp z6W>^#?i(R_ifBhcaUdCqx%N@`2kW{j}=cvJ?Ub0Y^lj7##5t=0;RQ{W6&)Uws1Bd)+UzA=kj^lBe57{9F zJOw01uUvQ>DlZzd>EU3ts}MAXCi;)_88=jbC~$DLWV9v%KPU^(444j;Dtf}Cj5q>X z6sD1QRoDAF1JXM@?S>I}l~oW~jdzsAv;JmRYPr@I_LSCRZY z%f#L0Wzz>nQLu)tg)wIh9Zn-#lD|9*emk-F+#qTuXQKY?+ltbY?#8Dd=?+Xe4=9@~ z-M!*lv#_mA`t@@?!SQz)i%|ir4uZ*I{n$2$I1-fY>X|Nq!kn4~h~YnDjjZNZB`4j> zd`w(+dXSC1>1833Wkoc2aVxCRZ&>xSU*k3Ky9Pz$j)x6li-NHsGnC#l~ zx>bED>%0BLZP$btRK$~_Cp>-Df%|*AJR1L&R#$bs0Qn1b%H&EU3s*pJG5S2F7Fv%O ze&zQ_+4cop1!8xVND3bc3ZNRCYUYU^J_udZZQRws`Bkf2ycqrW$D6or!yEX#SHyZERU`~6RzEOOMk~gA>!OEK*v}K- zaZ7F`OMc^HTQRoEsaHkZ%XQ$EMigPKC0p}?8lm8SVrCg%ggN9>Zk zSRTUYmHj(^`RVtkf4CC2NSZhUvj1YD)i zkfE;jRY^XhrIERj&AB({vMr{&G7hv&-o=ipG&2^~b9~Y}{3hOAzrH=$_PK|ZbCXC4 zHod7M<4)0x+4-PyqU+<(&@qC<*`znKFc$-qZzDIJq!7Y}CL+bi0krxWZYYlPxLr6J zO3Jd340}L=hiPG#>1sak)}fdSIRciKPo2W>he7P0yA`^51dp6L1({!tj*PsFkn6c1 z@p`a|k6_5J=W-DZ^p&cFs}xJ(gJoxa{I6||-Y@ptJlKbC1r5qN?&CLh-imo^3 zz!CxEAei4rM#9IgT3PY5gWBPa$=;VpGwFxz3Ur+-c#5TGrcohrvi-9-p{a`g1ee;h zff6Ubre|U+UL+M5_?yB-;y;0huhHh@!gj{TA45Yd?bL(y4+25GO7C>!BgwgHD(YpK za{O;V%QZ7K%V|Jbz%aT9G?)zlU!x7{*@;6kk20-l5)rx&4Kjd3!}l7iCpnqHa9wh& z8{rf=c~T_UZlaX!%5g0~91GwFLbS9wZ=*RW(b%Sm>zBH^fJB25LuU=ebMOG@a?Ses zdM!&WP9g1i(cJoW5;&4dCw-S53dzNC>!{0AHGQ!49|Q}hj@Ic(fWh}v>jPV7Ad3;L z9!L|3{&;W@cntE6IFT=EHae2uMJ+3uR3Qk6fwkTmOI3k^3oUylr_Q^xyQrTn9uFsc z2BX`8_I9y;M#XxcUH}YPNf#<$)T(8Peg)m{zZ$556$z{O@4nYF)MJ^sk&ExP$7kg8 zn__~;)(<=bBgR7hXJtMhGcPHdDpvX<$TH7?TBzqs?X8T8TCi^k`*_cPT#e;E_;RCy zbsPiRTfelZ9=jEF-O85q@m8kf$M#D+Y_MRv&B;gf@o@6z8=YRw!Q+O7oQ0zv@Horc zpBzE$M;G<1Wl_j=Wi#rkdGKo%~jfA{7#b{X< zzMB#5A*`%Yx^>|qM1|UyiZp3g#37=Sa6tL7R+8hlP`kWhV0SUvZeg)P6lG>eKFVjv zT6PP7Wj%sRDv((3JK%z%Azf@v!yNg$=r8C( zsIc5m(0M0sggn^&IPx*W-7HduO&31pxI5J=+ zD;1sKBqCD3>+qwA4pHly%=}oIxa929nh~Em*N3MJr@KUuqIA}=_8%;VZPI(kPrvGy z=|rsC2}ldB%@dMS{##9D6?8479UR6^zvOfpMG?&{DAB{my~tR3hj$U%3mnk2gkecT z`fV-PX)nq^p9+Ni*L_kU9g%y^B~qCAUFAfSzs3v0`P>X6Yp+W$R0;o$F80gI19XfS z=6|u!MK;*4h3!QN3$C^s&C;X3S*8GquYFpkP*}o+pLepUfPACi(U&_YD9*iDeDr(7 zqQ2=RYXRD5B~bOOg)}A?d{9+;{@J}sMS^6W?j{8ML6#I(MljKQ@qgPo0P{Gh{vPqj z8i|K6@YdY(mLEH(A1F%BK46XjW>nM0U?o3ZSVUy}ZQ$mwsRG%4B#nBc4@9Zj40Mt1 zzn7MNEiI9F6BKIcH9mZu*jA6m2@F_gf%EqiYW;c8r(;tMzSwZ$QK=6Q>R7QK} zfWn8#+#@2$vTDFLIVJRL<>SuuZ*F(>WZ*V(p#*?aO;f1l%StL)Y8ue|Tb4h9-FdZ_ znrXPzFb#!YzNP5dSj18_0`5lE+WNnxTLG_eHo_^pJ;rd!8xZ(dpbpq<_yCZlXKwFS zh$f`HTd&DsFe-eeai-Jti;0ir^NT&ZRYY$lM4tZ!eUZ=s(~yIOM%>bIN+xDzsm+0n zw*zB9D!jRovCyX)8yQ(O;w$Y+u`D<`6V;*2ZFC4Ks|vRWvP(pQ24ZWXK}X|)DI9s< z<5$A$!s+^@y=_tNx|{f4-iqyTUOc>wmi=t8p`~=*NSAQrPn7>SmR6&vXK`(NzAJV& zqZYi8;CC|yXVlI5`^^0O{9-ppnA_0@*}>P_m{H+Qc2akvy-DxBnc?nf{Ub5Cz1H(F ztENhX{Q;OhFV7V45nftGsOI|Cc@G+nOBSPPtjx2jzD z;9HI4r9~~FboA#8R>;puSU2)rD3u9wkKzxWMRz3>YjY!>7x@%k^OVrJ+YJ|S zxrEw8VAuHiS#2?7+egbOsw^ddfBMb9pusWl$GyxsL_{Y#Ve>&yJ@S3LlF6XNMRnUx zOb#aVv7kHCI=$Gi4gRnlVtZi2hAJDh&XaMu#yT&^3BQYu+T9wpzKrOk@ET)uL8_=i z$Q@#jo4OO8Gs}se-rdj`{R2QhZ4Vqjp^0z{k`u&+Cqb|2sa2A?(oHXME0{1cnxLVD zkeb^7n3|!8BZNz^=+&uhu;qGxV%Lq-#V=O&Nc8G|InO*32IM2d!}BBuUK!M*AyIYw zeS_dFxazD5yH}RXV3n^{=W$@1WlJHqL_AnkF2vjd(V;h zU{aR$Yj;CLmy9GMVdA$2ZTeB7RSqah@5~&!r0UH2>b>hAEsaF1{pXNKsvodDf>&20U`dt3NjtxWcnjLb4V@GTiPX zrhonv(7tL_bMk8Pi>S2mNr=H^i7J_}nv%t*nvS*}M9mk4Xejv%eoe8ol$k9voJMI^k9lvm z1h<|kz!3Vji#+222*QPUt#s(l+nrE(M1XLYp)Q_Y;n#|gRCSS*PV5)&$^4YeSr%h)+bK( zzj7TlHB(S9vG*qw*t!>bQ))8JC1J4}%^W>z>CU&S?;%c}JXvU{oJ|a2TqKeZWb8m6 z$^}6nVqHF=wxU>jyQQUPm{ij9t~AjjeN{@GaM6<|$KLH{TFwK-kD#ESVYUr3r-%kg z1>g~u?GHNeM-@$Y%az2HK29&hZ1?oXjBK<&PJ5?|vY<5<32ogy*D~?H9jX&kolh9) zoZC(WMXab=gD(J4B%OqZW@=w9Ha@&ROJ$9k9{me4eb_WH%xJ|MI&5;~IZECPoG9;O zLoE9stt8eTf^xLXWghgbz z1(PL`kOa2(5fiwXxQ(2(1~0~%TjyH@;kwn(+F6!rCmSSs1Z03ZARUjt!(Z=Ex54g;Pb~LU!>c3!KePw&gyoc8tuj;4GHL^ z=eYYBlkD!!HWb(FIeT6bwm=88WBSw>LzQ0HgH?mQF+5nEIMnR*3#HGcGb9=VH_o=< z1i?gVB%WijC3=6MF?8ZE8&x>pv9SEZ_>rv=0Cy zLrWwMQr8Y^Y9-?bJZhEJk5*rR_2W)f8)p1A)7W+T)B#c}brUD^^Nf>rHZ!CeeVXlu zL5XJzq&SNE9WKVMZ%wtk>#0O8^+g6Z=l6E2U+z+meAf)rj{xh=j*ksU5a!|Y5-l!ay8OD5TeI_D!u9Y4wRPPO(@p%s+ zC59$Xax*xlm7_1rp5LWGL&rINVhIz;ORAe~hV7gA` zI_VP7p^;$X=Zcfuf{7;Ja5y7Pr~A@#;yb6RnEiKoL=tc*xd8~VBu?l<(-eGlbkN&n+V8VZ2BQq0755%3_I4DQoJdVQl(^? z64JLhFeiA*P^7rz@tp_6*Xq6cl@todhuizXi{MWy7Wz!hR@9Sc{{8!9aAxygj}+*p z$Uc+k9b9%DTU>v)Gb;}W{{_-Tl-uRNP>eu=f_mo9ku23o!X^Ucu4nycecM16#C?vf zJsS@!2AlJ)$E8+AsLsxmCqFjVN+0XXz~6(}!#@BDBs;~i zIcG^2$`@WeEuYj-lA)vr$1#7PbBd4;9jTF%8M0#_F<=KCe+#vdaHtS;qz^#gHYf@b zo-_xEpLo)LJ~rh0l;(6x&+|E^=}Out8~1pgm3S2wXVecgM{7M8GTGn}n5$m*5agNq zMJr)f+P5N>(2NladKUaMr1=H4{K6Tse=}I^>@CeE3xZqb=GMH8j2(ZWg=Et6Nqlx8 z^sK^52kx24?;7Ke>)IcSU5hkKmrLcL%mXn6P$$ay`5k)64!JN+9NPOc8!qpvxk^za zPJTEqT9`X23m9!><=QA-qq2Z*X*}txYR@?%Pv|ZdP_7lYMt>=pDA2+)Q|trC%Mmq| zKo)TmZ%CD}CGEC+p>=D=tk$HZoHtCj8rmBg@)DhVs?=7!SV*_wISl%bX?j;P`O44Z zalBE@HbUha!9(l0Uun3y(hvw9qKOv_%LmrD35f{X=9t~)#puOFxnHIRu#>*$MIDty!&eY{#-uRNVI9CPd;Y( z$<=JjH?M%>>J>;`vHffDYFS=0%LC20`61Te%sJxAFZ#NKJJWZYTbg~dC6fxEr*94c zMNcIi50CO^gJFo*iWVC{FPkR725U`x(-Ft3EOKY&8VB1A0X{CU%WpY>a-$t*${yeU zIld9?@WXl{bjIqd%45Os%vlWN#TEBKMT!`QR_H4!`8$3P>Zzm}OO8jfey=e5%WB%| zd9=()@I#{P?@=HT{xOJ#N|`~4+h)2B*HRP<$#igwka>9zQPBMB@89Xw-?}Ge?CK*o z&Vt+OdzEB_(kPlJR7f8!@>S&^TiZWyp>RB8#nE3Cl`Qr!S zY}vg`)O15d${VAX48{qd`cO(8lr|czeMWrYc{^oqXQf}og;uZBlddF_^xV^{+{9|w zkg611{6dUK3BQlL(`T6k@xe*dFEbX-ZvXvNX@cJ}tG zI*I#?{lB7_8J4;r-nR|524|9sN(#ToCfUKsiocqFkAm6vYn$?1aBq$9!nUHx-1a;= z2;2I8e>9zoKhyvJ{^w9u zIgETVhcIVSMshBhLy2~d=bGY$5@kB=XfV`Yfsf|RV6=TuCuet`vj{9 zy>b7xI`AO`nJCZTh1~@uO+Hrndj8O7S4I$O3glQJR=%Q-6_r3EvIPCKj0f=DkZZ;@ zugC>bk`je6*(JviiE^wk8ROO6KUnBxu!LEeD65&gC4y`t5^Whz8YGC1Y;dADA+r1$ zhbtUnaMG}11-Pg><%*uJ%upBKwuOqZJ}nSCSjb1kwXfwmAJWv@u@Mnh3>@TpriuhR zyhXOA^dV#(sQWny+#4GqNfc5Bs_jKm_U9C5LHi<(cJ7r|Ig_L13*hW7DO~Qi_~L1r z4AUQK)GWDEP?V{7m)zMTIg_^i&+TK4L4hHh%3TEIuCDMP4rXuvg|54cGNQgh;=k}< zR`R<9O7R5giPujZG1SDK*ThY-*6UG?^QU#A z^pvL-0G`(TA(@fG0JX;le}C+2qsug&RFn^m6Z42)&2BVdQ+qI@Uol+bsC& zP!{&qFqj^gKY+ct(v_HENt$Leg0n*JEnkX*4XK{(=VO)I>lD5suRd;?W7$ zsd?2mM8xpk=o6Da-^NYlQ`m1==|N^SHZLt!+{?Hff4-Oye9r8o?<8^^u+Z=Aenro= zo~NN8prFvS1T$Q3W_Ij`$sk_yEjRJyOJg7Tq zt~#^&bMv-O?uBs(@QUDThG%EJzT~Co&H%ZQ!8ijIUxq+b|LPd22vVSNNI7G9X7F-yxf|2ap@~Cf{)=<3A4v)$M^`WMW2pHT}c=ds#~|3v>s_7&T0S1 zYf-8_>QtpwprlYxVPSo{jmg~7NqA0c#@I7VN3lA5j-}a+DZ?R1q05l4utrcTKBw}8 zuWu|RM;(d~$fO5~XmT9ge+9GT+Y;3Y-`S~~O`AQ*dyM`)K%)rf;Pi^BrNuZBoqg;$k%yp)riTF`p6-s^L6~H^!+eE!82^To4va{E#4n# z%x9r4v-gN&EMTCX%e~ddUfQ#bT2U^s{dLpL%N28g2Q=kaFXFSr2m~K+Ns$&Mo zw``X?;K5WlhUPg~_C&=d!*f^_>!>7fjdXLk-Z%q5AqwH{JS^^&m3<=$PiM1SBwCJ! z536DGs__?uh3n+Z!GL-Z;%OJj!7=v6N1O34y5`&W@2y$R+*kBXmEQv|+>YCQWzna- z9Z@F~J^5Wxg^6pgF`i=tYsbe|aXHck&rUSjo~u>tiQN)tzfJ1=WI|t)jyckHvNME^OX;%_U_0|BY6%Tgw&EW)>;p| z_RJ=Z-qV0^yBf%|P=hH5NdMfBmTzvF)e(c+A5J{@R=;@j`ZIW;g#|Fp=7nGji*~2? zd3MP$*+pq9@9lYX;-;!I&H&lGEmMY567!2fQC%t~)RbUuMVx#4W-1gzXY&ChL>&a~ zx?*us+BczYX`ppHIG;7TXBF5i*E3Bz>xGbzqeO?_C#`t?Je`nE4Hmz*X$hTX=6L06s0-51Z zdC!9?>(QhWn`lR56^nt4RBr@z#dV$Ga7}#K)B)|x)4BIYL_7V2j_1&{8(ZP~WflMJlpi%*bc$Ts9vz|`!^%j;9#36KHDsP$h9 z;TlA<(nJ{USOMorhbo)@xM#ET!r7(2|o@to75X+tkciO-yU8ew=^}W->&;8WuPkGY0@WWP8b0Ws~R;58z9O+S(s4N zT5@u;VoTMq(U11Spi~dSBtLR$LVP>e5F%w8|LA-EqoO6BCZ-1Ss>0{iu*(mLFd)6xTC6tgU^<^`XT+kr9Es zx66(BWQ|>3m8lv7;zVUb+RCr-gP0F2x5=NbE|JBa8i6Q;ue>WTz+4>--BDnU-vu8H zrnxFPO|?H#BB{3WRz|T^wiPRjIDpfSH@e~-jT!y5nVv-D;tk60-yteoVZ*9s$`mUT z)9cphxKug5Eis+&&~?)@W=L+%Bfd+ZmncyJvlyU*gP~{fjdRW4e@rmF_8S-EJdNx+ z3l~DzK@iRc1eZcGIKMP1FmsprsZA$lPZ-S zT$qyTC?&ycy+9Spq?Eyc5tH3A(KgIc!0w6v5vOaIcv?H1&3QNFPV_(JDvbCq}it`r8sN50#B<&cwskFC`Te z*!sHH+n@#UutL@O<0RVj9lpe7^P}cgSv!wD2m*ofY;h$c8!R7BixnfH>Zkmc@q>nlcquo&mBZ@8S_rrBk>}vmEPwdWl-TjeK@UW7N-ThpBZ~x4XZHmQy zihs<)8((ivFAXg~fH=kJZ>?^8zGH`A2J>#Ktw2O0UX8=tGA1B101xbHFS z+jmQ2H@&w0w%xqdFc_)z;;7-N|M`V^aX8ss^?Qxco92z{U}Ne{G_x93SkBj@!& zU*Ua-i0I-KVn)O{INOwD;A#I zHRJ40^vt!Mg7V|251lie9x8u4ee5zAwO?uCoGBwv$-{+EF1=sm6EWsE@vf}vKS?}a zPWO3tM1|AI*nx<77e3j!$Xv>?_z(8eq%-{rN$(?bc^Gxgu z_#Wd`Orgt{z64Wy()~M{HJk>z0xs-u?hx}vZ1AZA{Qbzyvhw>HWiv0_I zLI*9Ws)jH(lcd@>$Y!JS&@fJEc=l`!=!;`72D2?| z$?tjuyZK|6ySJPp7o4m!h&A<@e5e$)S-;(N=P+qptNrXJI^>k=2@1Bft0MR0eEhao#RMHOMjh!kK*0$Zx5Dd^o!H6e}DeO zUzgDE&)E#FKD4D>lSKUe-gY_}8adFw)k$z+6@ULK=*Z>Q&)Mi~14s05NHv-Y6%r5h z{yTCdfg%lN!yqP`b(xa|uOUE00|nxs^B|9);9UKMN+r-t6lCBOc7!)c&FIWnsM!cp znqzcRwC%7Bn*mFu`%-L2Lm}buiHlMJm-sCC3~?@`3x*wb$(O~sT@qh%T=v0Ka((E0 zX`pNrOzD2iXIRrKoQd)W0MfPXYwF(~AoO@$)Zrrf3 zZ{wCU3Db)Zhy*G9rb=Z%s?@OsHs~wm%`2q>kPdsXhc#0XV~w72@b)oIUC_*5SYrf2a^yz0f|nW3TGk= zUR5!O#aXt6nzJTlq@}addP3G}kY|qO%lboZLMudSW@Y8Lmp8LhFfd~jJ zj{EX2gest4!9p%$SJU^Z|Iyn2E&Vvi1+hurFc5O`VDshF`}MIk-H%MG_A_zayi7zi*uDip(2m~`HRh*5>psrN5VpHpeKoM=PirTL>5&q7x`&dlT z5KyZCKv%--hCBFlEfp)nAgs)b@lZYZfqpmlTd*-Ht|P2Y5W`$~=PTDJu5qm!f&3?^ znzJ4H)2%mE9uG?yYtVC3%|@{pVYhkk!?qs9ibg_T)l~V|7vEGelP@;$0e#BeNO(P_ zqQNAp?B*RE(IdZ8rlZs8z^%YZ{|@hehopQkN0T(^t{;0fdf`|{?HqGbL#;1>B-fUt zW4>8R8-K@Q+Vd?<7$ruD^=1i(_c#Mf{!_(zmjoVv5SnP@GKhnr)3G3V;Y+_b`yD=v zT?)|}L0fwo%VTmL2J^BWcF(;2!PI85#8Yi?&ldq+XLiLyN2Dni1&iRpU4_09&at;D z-%#12fqiIJQASE>wLbq&Ay}G~2bP*~MkE2^H#)h8@XfKrh}URmN;$adGK;OKg~LR3S##sEi{< zM<|L}S9#0k0rvO7er9HcNW=KL?EgZ ze%_=}LR2QErl!7scM@QfSFu16X5xYhQj*f3;j$8g%&q)OQCe^=2s?NdnfxrNP?pAw z22oN5k#B>Qxr@vUuJT>M*eltbAkF=+c0`+$jz#-Ch+Pn9%PYFb^U|u14G!yv#Va`L zMEv7L^05M|<&|CwvEmve1(o>6gi1dHT@F_j;@VYul5bBMFELB4uM(2J03sn!VmH)B znoWyEj~yZfT|1LQ;92)9OD6zdgsU13`Gl@bU1YR|in{;IRc9g1vLG~yT=ajWDgP#N zy`sbPKSaKuDJ(vNQnrt$8xT2YntgAFD1bT`O1<}QW!C(TX_l2%v^Z4SNC5@y;YW1{ z%EFfXmVn~N4Pi2xZ{vToVq2E9c=V~CA4#qrN6nn>e2vLYURwhhWdG<{VSn<54bedK zGJUdVPTDitE12=)U;dAsMMl2Yhr>r%yocEx&#OJ%v^M9^}!XWH#!tz}HF%H*9K|5^! zO3|(VNe6(QviN0jVa4BTDJdyrvM)8F7@NIu7AFcZkz>Ces`d4J?s@*15(O{|Iwm3n z2E$cOb5n8`PxT*p^?|KJ;*wCxtP~0!NFDxfVAR#nyhzGcTiAGFVGfChgquFc-pBiq z*PyQS-2GTo!gsmTDp9WAO^~;l6m+ml6XtLQWN9&W5xC5e?F5wTi4viv#=MX z8mBtED2Uq{IDvo`f3e6@cg)$?qh{4A#`3#Vl$$`Gdy=adG{%Ov>h5;o6=PyJQ)bx5 z&W7S0X6>giR9~6`pfR?+@GI;#S@6_aFr)%-sE%Q2DCezPUG318p*-4F&`&()%I>J447$`aI%s_$0X}yr|@zf~xESIqQkPi;H(EzMONC zBCqd15)+UAFPN#35+8f+%Pq{r!)62+@7zf8$yUA(5F#G?Vh78QaF*^4{IU^kmvnSm zBW54kM7~1{`jXTTM}yw9e_^+;%t+)*d|CIKyfvjAxv5CFz*ZDelO=0h*)X1EW>aBE zlo3eQyeytH+*k$p3zzc0SU3Z9#2;&-OeLMK{qOw$G+(zrIl9f^e^@i<|BU${>ChR^ zwruL{@$sr97zOkNH>tc8Jl4(yayb{W2K9dE?g-2}aHYdt8Fi*Qa+-N?m@FkWZUE&THW zTS-nt9FSB@DrN$_@82*wLn<$kBHl1!OX6|Y6}gQ*BWrx|?Cy`LvFypWF)-P|v9Tk? z{O&;Cx;c7pCOF@^c455P`Zx;DTWTN`C;?|kqZ+xcm^P@~<_!S0h6Au1J%pisi48Q{ zc?4_X4XbodC1YL*hR##NU*uALJ70FMu)p86bfZ?bKT4YTSlalEr%`?}HoAFqMV>sA zc(TdET^_BO%XzEcunnz>@vL8+x?&j*!VOq&Eq$ntL!%&#T5UqFj z=rj)<3M9bvck*0r=HHVDMH~)fDc2#qi(pyvB&#kWyP7XKbSQJ*x@jSgrRhUaBm5AT z$_FsEIMB-!1cAL`b&rR=!pmAl?*5Ed`FnAZ5JW{mNXjg|UU*MD)4ApMMelLYE95k8 zubAPGI1$E-gaU6k48*-DksKhbhhmZj(F-#!0nDjfxl`Z*-i@^^u~Wdku6TG%`7~Gi zzVP9MKuS?;oSkwXwZjUBpAU?&IbrE#O&J)&5BAzY3#H9?^qk z;lq_LP;=10D~URWfJ?wDOZ1SuCA}gYJYV%#?cUn`ErS%;ZuR*|d_VRNcyZ?cx z&o@ob9h(?VR|W(G`2T!TkrZX4j>8YhOHpK}Hfrziid)0Cu?c0`Yjc)q`BEC%6gjuP z_^(yY1UeX${)IBT60Rch1are(|8|1jy^Ui2jdZ*!pMJBad7ZjB z6z(3ZZ$MNIS{irCs|GRIuJCuZ?3c_Z8Y^^^l33ktj;04!jb6(Q_Q}?w-yVLv_0m_` z00ycnC?vTdMXrwU;wP%~p+ixELj-8%MgM7Bb2KKC@4#ufA*i= z!$PIaTBotEo|C|c>8#s&uK4@+@yLzy)pwVcfXNYC&Ok$=`3^d^gMHfKCtVQtwK$6>U#izQU#J{0^r9r?^AvfU5UyF2>a~Hd-&es zSlz&5o7y$%G2UZcaYs7P^R41VWhU&9*~;=WJbL`HQ~G0Nb3r|YiALWeMn9gCn9qFx zGc`Jikm&P1(^9L@U%tq-OI&OAiT@+_C3vinUBB=q!9eeao?s#1gf?rbQiwN?yA}~} zA2L1fJGa$c6y>g~?3DvMJHDl4shQ@jFE4`=#}UsL>Zu8FU6~yW(P@sE?Rb4x^#k`- zm}al#`%%v)%IEvgOQcX<0d;>7?%jJ8s-5gCszP}9Tw!O2eFELq`#&&>E^9 z{2w&qsE?vFR1fdt^0?~OyQWhJ@X;rb$1opksbH{Hb*Kr}_slX+5QWIX7;emz&4@yClI*ZsK$|0u8w|TlRrSM=-J846wYF zZd3lF|I*fu5?&^)Gu$utJQb7_uu{>cP}DcJr--j;J!nO(U-mAjp72yO9{Ly}B=oZ` z<#SB-0gVY**`Fsy!_*Jy{`VNZx*NYKAw}cIBfn@Ca|)h4`2@Z^(5xuvq_|ccvvkH- zNYGslp{sy)TuGb$-~0VLHFP%WWE8}5`(zyR-xM=HH#ZsgR5qbek*JL8XbHP}>226v z`Yq?XIlJ>8(_;6v+hY%lTc)C}zPTXtH64EeZ;5|i_t33U`yIMkPO^U|NGsRc^BtP> zc6!Sx(pVv4eK8`nh~$?WW*6&{tHhw_y|t}Gk8nMbJO`9hnouFvL%1s*mWm$1TthyD zz)b6{Py+*c^^_|*Km+;DYOt5UJ6B)cmt5Bmkz$8Dp`?x6;Zj~~eqz<9Nvi1kbKPdm zE(5UY@C#moo$L}{8J@iER(;P}FGIKX?vWY@rx6~(!8d$AzkptPS+0;K#Ve6&BIph+ zfpwHDK-gi9o~N~?$y>tONDGR;*kys(6@iM4-H}nJ1kp?P{@paNyfK=42mHPPVz8;DPT<(epNi^8fB8aB>kW=> zuioBqEtEV82I-Ycs};7O(1h46g-VYJIF1IQ>MUc^mA;%)>TAB!68a7uNNpH|&p=+R zcYqRUWkbu&M{Ed#JoU1jTCXt4d&?iw3QI7c*lR*XhCrieCGvJ6DEtuH zkp{Kn`f#D&04wt10u6pTIZ;{2#tzDQ^$qQgsz?L_YQ&FVcg-m2(DD}njjQ=m^6nxM z@DrWLpm9Ql^~9f?CgzIjV27ZWI0Y&ZkBrwKn(EE)*2e243Q*pvW8qoCf6k^Pfktx6iX2x)5;HN-X;1n>Ck_Emz zJ-YA2wr{Pdww8itv?3#Mcx!xZ{r|fW7ha zsIMu~-Oo3Q@i9%-Y*K}?xw$1*SnB0vJ$w^0dtZIZmqZMPJs%9$Ic=Wo$xW06=n`=V zS&D1qA{5c}!Oj;i$O#%@IUw$Cmz+VwVaCx=Fxfz7o+o|CN&$ClmU!YheJ4aMA}}(w zm|R|oq=1aKpDsgtwo+vu%ojpD4|8vVGB*c@_chn8`Wg-4BiLc%28Sx*TF3oq;S-9- zATw_77Ps~g#S7o9nP*MYhEyG^gXN_SmREna%AJ5(4l!KgQ)rk`P3Ei|cvsuo+YhgV zL`AhQ#&_mCC)L27_$9dP>%l>TfD(09<9B@Z+IMYcrPw-$p2k2ZsZl0rw!ED6d9KxM z64ym@3^wbfkh_K#S&>U>yT|P@)X9PRsBna2dy)aEsH{j*ZX+^nE3Ah?nXg z@YIvFwx(C0jIB>$JK#dTk#^eaw`PD21bO2p2TOuZ>y_P$Jd-hcb0^1FpiXg31 zC=X$7?;JF|c({3#Q5=u11!!m^L+D;4Q{R13v(!U9*SvCgZBE4fz2ub7W275Vkb&&l z9?`ZZJ3WNm$(G^!E(9tli&BYoGcIqO=yn-s-#^WLyLSAKt11wn$U@)6P~vEJ+sz;^ zuRZFLwk1*3EI25dv-J!uV%P@yQlqGzJdypRO6)IptrRanF24#!Hx93OlhLPkBE7BHlJ=_Gb$0?M)DW zHkS*YNtf=?c%}}Y z#h*YyPwF^yA|JvLoto=YLO1?rtz=wUIJikMn)q6~1h6D`ikll5mFmQrxgeI@CZk)1 zFH$IbqdayZ51Jn<3$Y}!)Y2Z+bKIW)(t&RHRhf@0@hr z`FMCBc2H>Tbie~p@cXw8H>#s|t~u{|wXZCF^!|E*3o*U8=%FI0YTbFHqMT0xG%vW| z>!=7w{Sd5cFhJvl=~TqtMN{K5BO$?cWxgn%tJ3VZ`IaG)>JJ14Py!OgZUpZPi4sY+g*&qU!yTgC!8Z^r*d;T{-~x*lvI^pz_pdx5P#}!@9Tyy zjf{Q~sIcF<>%a5~YB2Nbz;cK^Ch2awNfhhl>)XN{EXVcDM@E?KTOhEegHQX_Fe>_; z9J4f+`FDyOJRFqKE4YE`VT;jtoUc*nctDdDKORXvy+yL`NtSEOg_EH~;q-91i_ODwT1foJsx5^rTjR>wkVjYb6o?IxUN)$IB zT!-j*DX!0v>!>@;ckwkQ718Ok#(c*RDYf7osIIP--7HOTLnReljj9QzYE7tO=hXr! zyeQ*T+$&|=YhP{XbcojEy<@1xsbK#<|>gd)m{U=q`^ty@5}dXmumi4B%* zgy&^WM&_3Kl%Ms^esbmcO$D+>GAeW)WrdhXnCiT-1SK*o5=BL;qNcKi z<=|fzd#~N<_QLFlRulDM%I$f)JF2|-ZVn}aNi4<(QZd_eZfDuApSd8yolXGss}7K& z08$zYZYOeos)dA^gmrk;;mu=!cU(JiivqHbBujpcRDj6KA03@f59Ux z?5Xlyvhk6yQ}3U@p(;}wtSH&_nJ8#FEifBBeT>yoND}f>RfeDeO$jE)Fz2@;Xu_;K zf4`4=v1>7!n!+A-4~oSypYjIGMPd(&qgp1;$ItL(FWGY#SwmiOZ2iD%a6rOH(SZ>M zz-i9pP~BTDsFj(E!s24Ysn*4?+0`IW60%yB&y@E4%2C~vd#yq z^n-PawymN4D9C>-JiXZEe`71*I<9zoW_h_~t{|5Yp>E)4HKX}8c%tdAcSoFIug-4H zxbPIGoN@eb(K^fqdnAtG!Kjyky3VJJI@hlhusGzKkHU+AsU4>p*`b zv6f6GgY+A)y(g@Ae^dQjc*Vl$;FA{#3+08}4?eiF`TI0Q%6lCW2Pt@F=RKj;U)vJK zjNl;*0bp3oE8hRRhK^R`ZgTs!nY{h<={Qlz zU!>sa8(O5TTZqjwtq84$pP;HV(usC!x4OP zCBjLLG%Tk^D{GX7hG4G9k!a}?5bMbRlR`Na>T!}zd_>-rnzzj;1!GuJ!RvCN;tRNE zfwZ!72Dl>2+|8sqYHY0Am+PfxOgl-i)+Ml`^`9XIaiuZgx;S zx_@bYi(K~{_8bPv)BEoX^xqb)KH5$}7BnQmOEbtKvBE?S?w1YK3cf1ipXk!J7l$Q`jM>JYnobY#$Lj15U%P2a3( z;=r1K5@oh5;iWA-!WxCwVfU$)EmrN*px0IMAWVjxCROcd%&qf~%XaBIcWN3mJNbWr zxLjJVMO1>N!cXus1ah|5l`CsK(xvqk+BCYb@bDNVWW_6Z%$Ni&J9I+O zBoZIZvKRvEv(B|TTZ7F02lvO}M~Jfobm6d+P3;Y<$mwAzOLP+^te6j*ukbb92*Q1o zO@0K7YL271`T0DuC*uctqFGoHhd3qQhZBL*>y%lkJ0uR=00rU;v5x1Ba!PVdWz4nd zMBiMO=e5mpCn&bVBb02X@ru4XYA;BmnuUZ^0`d<20i=3OB^**243{9CEyA5dk2YA2 z+a|}(=^n~Rf7Qx)A2^{#Yc474e)NsStMY7lA7E01iUytg)A+HLQ+yiIf&ZLY(Qlo% z8Cf_ZZYF`4_t47wOqrS(2@2ezF6A_Fry78*^7_l0!iKGit0`lCzQIONhqIZm-H|&8 ziEPh>%(nHO?(T$JP7$6uqDH)8Pab9__i%_sFK@4$q)*F24qFj*E$n#xQ zPS?WU-=BT$GQe&8QF4Tnwb^hz0513VxzDZ!$s2rS^2ilpCXSAnDHgosKi=}Z3R66U zE5$yNTJ;!I~fA{_)+rv`dsTscP(-l{qM>eo%T&NDa8_ftxx{HvQS({ zfW}vo2dA9)kCjPzR#q}vwwS1-`a!6Kd-c^*2g921gAiS@po9)KT-;&ERrv8P8anYA zma6sim<$dAg+8=V9UCpySJvh_2|d`U+|Jjjs{=<;^LcDDke4+*0lb+Q>_uqseZB8)o}mAH|p?T z44o&10X@g|(9q{w5J{2xR2Zv?;OxJ_!rtT_K9oitUS8T*s%@(`_9*nQtoq=6^}f>K z`Zec+pPw0{^>_Qqf0@EQrK)=JBc|KeqGH4MDf@-PYknH7_x64tCI?0tV%k}cMT*%( zOqYwC`W7|QFqgcsI=MA<$Y`2+lIC$qw>@?brj;gTIYFCi#?OMDF=6$)w)EUJ!im|+ zrYBZ+NOjcbZ!{C0x$p;vhJ<)j26Aig^wl~kX6|=RZ*Om(uRi=XT*&XTzJ~>daB+82crh`U{{5wHErnhA_I61i zm4&r%C7{L@XjB_2^waLYu6*lWHU#EVf}th5&i>EX8|_wB`_cT7Z@J zCZWeg;~DzsHghgICOWznO@bDZ?r4pXM&AvcF7|teKF)gqqb3ll8~ZkPSO2+PY7gH@=V;NMXwhyN^>@fLa#Z|H(MA|#8S+Hhjj9n~ zl!ZNJ`!&ICb^t2tgmucD(zc(Vy#2g1xwLdzTG}flDtL`bngB-+%)|&5`0b-FW!6UR z{`%P98|70yYFt+DCJ{un^G~?%WbBUTLK_;DT~ISgC4K(fh|wB5dU!{umoQXPMN+mh z;b~PCIw^GNDrN%Bi1c}CDP-uTBE%E5Kj&sQg00Rp9z&s;t7ZW);`Nf07jf+aIvH6& z$gl?A_Q@)Sn!0-Rl5>uEX{Q4of-eM+jA*hEI~%m}Ji*fF#h_MF!I{$dI-IyKCoa({ zgZ@tWp(RRw5Pin0Xb1x7gzLS{l-lms4c(fbpHH*6gkYC7j*N&1EWUhH6f)mhN|ZDO z+-0f9X;~^qA+=MQJfns?qyC4};DPS{;~j(i*!^$okpVTc1o8Q1n%%|rR%A&qm48mb zI8EcRpqJwWZqjGyT2i?bdwza?Q*9k}ZYNSzsF*x8v$1~=usuI0>7Ed5hD`eG%wFF89M42B)PR2Ws#4fj#`^YjtfsjH<5?-ok` zdlvImEM}_(_Pi%LkWO7Hlzqy>!=2N-Nn84R7a%3BOr`Be=xVfXZhw>|`>9M^g5&of zQK*ll0ms;NLZ<9M43>etn^MMj82E>r|0UBk^85=^2#!}e_TZMkv*K$0zD3M#{{CpzY_@ygV9;!@l{*w+tr zYmn@aa9NFyYa7h{sj#EnGXYsk{&-DEE0g$-TFz`d!}avmFzPMrq!?%Y3QWT2Mevlq zk_4~00jn$D<0{{#u%<#er?YD-04JfuXr|EsVrFYEb|(`pjQSR?Q&yg;+)NDy+k1zg zWcYhQHi)3t**B!rq4IJc^jIT?L2NKmMjD9U zm6MZ0JqG9*ty{@GDoF)MEx`Zl6h{=1a{58kF6=MCQ?N_hbZWVr=H*(@ko&4a)>&%K{Mxq^;~XBfkx8o?C`AIW6}t) zM3kpmg_=CMqEGjmr1jN=LJ`jZV#S}^uA@sHg?jYvaDZ$OQgIq=zoSudUu{djFW?SAuMWfe~)TC znpkRD-a)vGolX&LpqODz(AsFTNJ=C|+jfj^Jx1CzsNO)Ba-@Zj4mi zGMb%PJW=H@9MT+ z+W^`fkbVZ(m={YwMa3afa}A)SKD*!CpEj9&7F?tK&+vs&%^>ado?bN1%Z4WaleSp) zLk|WoBsB)6!pqe9H>fn52~}!jB23002 z%;b8QJA{?2jSiUk*`sPE*aKz3@OKReO@wZB@0qS@a`@-<|Qi7$yI4r6~KNtvPt z^Cl71j8i!|*eEaNi)u<&b@B%A%W>kr^}?OYs1X*0^Jlcg>K=9I;&PZ1F)Z`y zYbNrj|0YA=4+4j1cj)wk6ZADj{dVC zV{ODU9_12d`{B8`aqV9h@ddz*bt4IM<51ImpK5rtt!2g@{8G{xQU6EUWZ~&6M~Yr% zmzOb4g%@{=-?S2T2Q_AN9ViNioSi2%O~o#aG_|jMcHZfZJ>&o(^HQ<5(Se%IcQ6(f zpgDuvIc6>$1jVCtcL#Z5H|uU~QXL&fm%@ER=T<$9G+Nu06BuTQbk1%lYX0=UaJ6sw z=!?xqHUeb40FLIs;&9;$kh2?nGkfJZrffWWplq=HU$RPmNkIVrbi?L9Bxy;cheq+f z?ePs!NW7&(|Z75z?x(+IcvG2CYKe-Lrw z0-bB2p^aW?g6Hh<5 znR0VfE!1mTb5+v8?_?O7bjy<8+Il3JP}#7r^UO*p0GQc|2!J*1Zj~X8`XH1h6=-b@ zQp>r>#Ov^*5!t@(sZy?l0P1hA(y6gpMR9|v7F9FF08v(iHh|s|V5U%R)`#NwG!K>2 z{^b%MRp?ye-Z!dFL#R=hdaKhVw!Sa8teB@IRg=2f2EqcupUv5cU9Cz|;4G+B)R+ZS zs=MOssP&!GuTwO&wAP_oP$2}g&^TKQ(p+^CwT@S1{7shBC?*cIS!I+MTc!#iSVQ4K?sI#r}(s+LM;>Naj@AhMEz(gaI;; zCQp(>)GmPp`Apmq{*%-9YS8{R!h@!Y{sL5$$lV2JH$1!E_0bESpCX&cb^3DMxT88! zgi3mU9?vhLKrVm5wN$`jL|69~S~3@gjLuVGMjiU3N~|br9Bk2JIK(V_&cufl0%ONc ze#L6TIg@KuXh^C+zhMUVRODVRa9a%5?YO-w&$+E3l$)2=6KFNciV9)S&W_1TUnpE( z4#?-*?oo;b8|#m1Mm93E@tgOocn9kB-gjSAq_e`SPns5jDYI8i#$=Ut17UCdD+8wX z8hu_p!e4h!S-S+Dyl!oF=hoyjCw2d+AO4O#Z9ySeN`qzs$8#BIkR!`3%6f^Mri_!< z=z^ZIrM=yHPBwGi8tA(=H0?f(SANYGmRgF9CJrWnVhP`Rs>AsTyQLSuPhZFv*gq(= z;N0Y?J{aIjnSX2uG@+}q?496rz-s`N8;kHI2gBlHuC=!`2`sx@a&9QNsHwR(-`%1v z79AHD4+Cv0=0mx;r0RRKV`oP1KD0a~tN%h(mXGCK*^++jqVP$8N6Qu*m2iY2SA~Sc+oaTVKm> z-=x|%Z89ev6~Plvnd_WmOJuWy!`twcT{a#AXMk~K^VxG$Np7nTLaACoMIpU zYpi13<1EXNNa!;T2!w+;LFf@X9L&cBepl^rSFet&7*;(ZYUoNVT1abOemoZmw5ByZ zBf*nHmwA+B?nT6@{H#RaU?5QFmmP}yaI63GKR-R=j_~P=eui}pqymi>N*Ry9oz6^8 z(|E|^odYoaemP|ranSW{cJ{^~)-Hqh_yh0JigfI`Cz9?LWWEVaBs4Tv1y5Amampgb(_eRvOh_HAQ7JbEeCf~l00u5_WR-PFT9bOQf-Se`sBb z;$K#;5Vgaq{IyOXDwPfG8iB($o7#AP%hTEwM+(exK?Ue;;$ScwaqZ&Fb@}v?1#hJ3 zY`Bg{kFiOl>iI5Lcxx2HWWd+5M&>#45L^m#c~*k$%tf3%DikYZTU>;5F()pezdjuHYLqW3}&#DQd z!0QEX>CWk{`lWU*XzVLC+mpB!6~=VM=ai886pT+Y6ieP~K6?3uBjJ)94#rB2^z9bE zUK)78(j{m90493bWI@~l0U->Or0s~yva>+4jUaJFU%R7W z>^fpa#;J0cqY3wwL+hqo@bYuArCzWu@PD}5S6i7g=#d0_VcN9C!wnES^i4Q$ID#A!yYjKB;+5IzuoLL<8z5A*_01+36pY3H6{1!5?N6QA#%z6p8H*_h)FRKMq%VKav8bbGNC49LWU%_ zScv8RJKsNkfA&{P-tV3BdOe?y2R;m}axoEVS!2Ow5|7LL~f#{Mlu0 zG3YJ(owuSIo5;HzYK(&g#sM{S6uJhE#J8MJG9pAM2022GB>9}7Iud7>z1e75Z{`W1 zBS>VSz>iRrAB)jNkmQ+6aV+gY?_RxS$AgaAVbYCk0AC^q^|^B|rx@=gU)R;J{2 zd`tO|P(fk9{^M@2h%#Y?FmnDgDfAl(ew6aeNZOHo!)>1ejmp^VaRutY5W9#||ihUQ) znq!PHv&wa}C-&b!x|Gk; zO@W_+e*D4fraUxHm$?EqbuHw(!f}Y`$)PqVR{p)glQ4vg`7!K2%PO;AvNvGezYM&v}!1yK| z2w!>8fA0*G%JO!Cgy$82+B}N1BAHV%C7-nf8}pI93h=QIONNorGp^I3|HcB`@x0`_ z=gsFDztP8+8WIeLLl{m{k(IY0)9b`@e)yYG!$wEv%kK<@3jFb9>}{hGn>TXS38WRk zKC+LkmW%vDNgfH?-kR{aC3SKHNI_~Omj?4&wCz^dHD?|ETmfEK5n-VH1?(r zln%|LvLtVeUfZOSn0ZkB~STgHD%$jt1QC)I(o$(i|m}9ePIU!%%qU{u#{$67U!eX(iEw?9^@ed z5mPj-3J&q&mUx>{FH6G7V;}Z?TTx>+bF!Z#exEv6VQL+255Uo_8w7^>_D@Ik7@#}~ z%Y`-TyS;4LUY!t|Y^`q!Ut8L|L6@D5so`-HVMl%laq-E3qh+p`uuK!k``H8Ea*sJ$ zA?|r{Kpt-SG8NCUX1)Wk_YhRhI z%*fbY&+5q4J>pDA#O6+*C>9@QE6eSlWApXwU-t3{UD}v^$l1L?F`=nDP59< zFloiwr|t56xfU89C^hd~Oq4&1almTBHj#MM=qZ7vmiV{91aU0w5d^xklAYOj_>ah(u#~eXN@fg}S z^V&=}ANFbJ|7QV2eKB{nUzxZE2WP;Aun{e`^(J*DA&^>gT2oX*SWpl}Wy({rVC}72 zmQg~T8*rDhD|wy7HVd$^LZy*9aQmCQodCx7dgF_GPiTASyBcy5q@r|O`V{f0zfr(Y zSe{b}8~Cb9R`_(NFMRZd%TgoFN?-0Tk2n_irj{C|xp~ppX=UzMab1L& zmkqzuOPJBEfudPU#1og|V*GQ3rz*sjoYoR|^i%(eTXx`?yAA8#>WX+vCiO235pT5E zl~>48*(lqqbUGMxY0Dhz`f}Ii&Y2JYi^d!L?4WvjxPT*}LMKWR zubqICr;W#@If_0W7n+rGx*5=^HW2zPaMII5Pg+GoZCGz$zF0{#;`X^S*l+YPA{Knp zJ)}xg)T}S-si5fA0`W2hf7gk}1gLrUD+R&@wxIfA^aE*J>}Hsuv?Yl@({A1iab*0h z5hj+`<*Tp&r#-)v+jBsXP!K*I&psP37WMW&!_;mwYg1~-N0wMGn;SBMXQ8akoqp&RQ)h8&%5%Qa!v%^UJeAv^$*xF>l%0((>OCIm6D1laY>j z#(fCW@ru!I&v2gxIU^%}>xm}693(EIKX9~!G!|r|M4hmGAx=Enh2nO^yuIVznwh5+ z{YJX4sAQ>#o6YLVXJMb#E3dqjk{{$et?;LwzFu0yk5-@9zWMml^sb*6JN)2qh<{q_wuuJiHuMo{ zbCZ5@S|C^z|fFY`U%tWsM#w!Xz?uc9c0g2p;Aqh>b}sfmQCZbmJ1q=drvBjp4B=8w zZwYh@&*^?c)AR6;2n)NECq~Fo!K$;{i`ZlEb?s_6W5zMYkv=NI&MTKvuk}wlF}0`^ z+F@;NDx;>`Tl7{HFrNF|6RXlEeNi!VQ(bz*=I8Cjhli^(-ANg2KwH5)mKPGHK4C)m zrT%Uli$96oP+-!4w6lu-N>mDp)P*`EB-0S~3o-SgX!cVdhw#RIg2n{NOoSKejEQ>! zoQOXGl2yv{`laN&Wp*Z zD>VgX8GX}9H*WFM-&M5o^12PUk*dm?4dK26I%34ZqHiC~bz*>Y{ARJ2afr)AQF70%rC(q-&E2de-OD-F3^zLOk)K6}FpnFWMP&h+_6gAe%ZCB3n{;o2txO z;@TwFo3v>KWns~#3VT42ZdogE%k$tmuG1pwik=4reKJ8bE|X656(4%w4avr`XsBt^S@mD z5IFs=?mfBBre4SG`A&;q2Rml`ERPZIrSepF{PAqPcfrCcd&J#;X73F8I-XLqLTV%> zUq;OKhLqyDS$VilSP40TQ6uOh1ki3$YW&p%K+fFROnJ726Z)daJ5{oZ^1;9}*|Ji} z?WG;AQ~XovgG-`HfsVB$rQo$WdIj=YzuAK{QE_9a*26mXh2j&xvt&ieZEE@@0^UHx zjTl~Jd=AffU1$Za_F*eiv^dr(JL>pw!pkEffM3rF5l43^2lLdT zFIZ%!0d{uUaNWw;w6%i+&A-|h^1bu9A?t6VnbG@AJz~*Iy;6BX$wP5*YAzeyo{dsi z5hFeQo(&z%$qB+^W4m-pCigln{)HliMIYJ?wP#PJ?Z!L`36MTo~z-RubF)8Sen zQJ1ohu=J+d1&8;sUAW`eTt|~gz|q8-nYOvdY1iD6r^YpcHy;Tbi=6)1Qk6Lkz83#7 zqYs%il3bw>V%Hw>r66X;X%f) z5`XicSi9djrx9M}%QZD%*!#k%AwGt4?}fhTtAT->8k##%64IJxlSM=)9K49Geaz z=PxIg-aBuR`9=9=&IZDPx(&AE!|Gz5US7-(OO4*r_SA;P3SJ$*)QZuv-0Kv}b^zX0 zG|ZlF2yQLytCp<~4!Ur^RTt$wPP^+tu$JQ&xNuLw$`nJT{)!Zw9qbXkLM;be!3TxO z6s$J3+A~J}YQhtHg;(BZ+$hpm+OTV^*&RPTVs`ZIXRXtUC&b}UCK{^>#247vkzD`^IkoiiD&q% z{8pY%zD&Ry^RckAilQiI(|Y%Q-;|Xp6nUl>-lS%k73g&g83ROV=`@2JxzX&jv~7nf z4#<^cxJh-)jWe7DGXddEZrOt&5x&0dDi`}YWlzPg_4cm0Duk_d3t;hpk1MC*6llt+ z{wYLX-d-c%p`PBy6r+{pgdP}JNXyT#&h zIMuc@Fict*bal-so8Y&<$9IOPFl~RLIBxK^^=wPrntMhEiRjHv19 zD9z`8XCMx^O*)cYoZZR;XKeW&&64^pqTyim{y~PA#^J2R{m}j7(J57p>^u>%w)OQg z1N;Yj$t8;NM&-dsn_PeQ!2PH*JT;@Xkt=C!f3bnBpWSaUk%?i82RUH3C&*H?=pa7NCv_EE?aO>_ zBSpNDYoaIPHgT5cGz3Xuhy3Y0c9BP~OVVIi;X-1kT9W+I=LK}%V958chWJ9u-1)e@ zAKf?TJAfAwB^Oe_u;}9k?_p zCKxeetjQhvT=&HlMMIFiVr~V^N{6jB%;T04OYL&f1C!<7It1YIp)|Fi_w}cPqFiB~BSy>Z&<;^C_pO!%e|Bcwq7u@Fhn{ zGZ-b~YJmO#60@LtXt1uJrJ-T?BZPeKWguB2n?pSY;*fx=HVIIhn9!5e6O6GHn*6#+ zU0tPZ8Hq?WfzrfWb-Any!5@s8hzdw{NSkeCEsc`7LO8XYv$6X3ZvaXplmRMCY9(Yv z5*`gLsU0k`xbUl2{HO%UtZMAKOl-_Ropa!XHn$8BTV>?#u|i)}!MqB#yEG1pWXP1h zO=o2h^}UY;_1=?5yP)>pj}G=ymAjPvfg+@|^Z|}3pwAF-R3BJ>9*;Ys0~cD(GXMSi zH!V=(Bd7V|qHCvM)Ba#QFW6%!JPT%S<)gfXdDo$=?2z{n+kLLe5|zz6<3)G1Hqu?* zfO2GXzvZxCN%E)a-@V16W1i-qQyFxE1G+8F4S`_ou!GJmGc2QI6LS~`8EQ zQAC84DRn=w_arQrHhQ|xg9c{r;-cj!fPpQja(?kucE|qjEI0VY)sdj4qVjb1-#&8+ z)@2v23hJ)R;xzDtfed>}+V{}gFP(A=_p@i`Ebc$ef7=$~-6t^+Z!9A0i2qu>-0W|_ z$5d(G4Ab~{dHUW(9eV}oG7h`toV<(tmRVO5p!P`E>ka(vne>G+%t^EL!TE9^TEoV|ER@!4}8R?rHc`wvhxDqzR2VqY_GV<|gXt*?H7TP2brc-5Yd4h)B#g zA)#Hd+*jyg%-{e5@VdZYre0DzmdLZ>Kra@Wl z)H9ATaq!5MEjLQ{Y0H4*(CR=<--Bbv5Sw72_)vHnrz;nX~Ox~bu>RJ zISD?ow;3H?yb~B}ashk0Pa&BdqHA1;E5hkYYUkwSp0egPyTeNSG;$gZ=?sf+( z>UE*L`qA0nTP`t z+ni2*fIopvmS-Ot^yOAxr@I$Cb{$e!IXsQO(?9Z1S?E}ax^JIri8}JDWpUxSkfBr> zsI0R<>=dp8>IfKazPl?If^a1jr!B6n`N4|YqV~rl$gX9LqyODq=7{4pGBI+Us8we5 z<4YeY;s^83mLteoifwBImpI=w`_ZS;Myr#PF1VA4g?N*o|514Z+SW)4?1iOSMQ-Is zNS>+crdAgdlR>LY$l8P8hfF4Hu)xGZf4(Riy%7DU1N6;KXe$XN8wqSI1{9J1V^y7f zvi({n`*Q?u_p8A$6oTLBylO*BO_OaUQV;vWTmi1LEO!1C+k1Z({bir}rV-s^Doc;*%$H($>7MkXkhZF*LpQ5{qCIsqmV1y_gxK0Y8_!(f3q z_H``=G+I^?{LQoJZQTfuEY$&jO6G`=d*UijCJH>GsNt+QhdwrD=bN9h zF0?v~s>VZpOFfEA#{2O=7T5%-V+W%w_P<{+7JrF`6m0$ocq$+H=TW?E=%&+8W6O&4 z=K~RQH_B>=roTLAh*+d~LSHX78o760{aOpy zJxULF3*pMYlY8KYu>V=Ve`Wh5)UDvdHpv$2gSzg!zm|Q{voXS8)|T@D{KlFDK+tHx zvmvJG`o+8S>z*xx6*ZKQ;DGm9&>zFYj%ayyi2N_OA3~5JuZtZPPn0>Xcx?C--w7jyi0%F${qu>v`6r0f__P6d@HSR}$lO zD^^guEJ}XqWB1VZovfpjkOo_cm_)%j?={}@ST2`GT%E1;qg{=WUuonyx%7zfNF0uK z5&3Z4y?ZEzBSKxY-mA+k2BoOC5u>m3-nOEAM6F59UL?^-*FIo(i_jZVp1fGQRP|#P zVD?J8y1K?ZX(ON4dO-veQ={NC*3rR2{2J~X@bD&zW>rt}tvky%;9N5s*M&ODxh)Qj ztuB9AW{A)=8{r#K^|tQgqF^PCs%t~9*ab2M$ zpY0OIg|X^tm$+u@DRes@7ym2jOC45dsgGt<>5JVM{@pELE6(Q^=B_LRmK}fpez<$8*w1Bd?1$XZF4D@FyJmd*V`K5sAkF(Bu%NBFYB`$= z{BibCyQ}(yOOQ9HqgDRO-inhT59{M^P63Iqq6= zM|6(#yAWSs91Gw2syfS&W+`&bX)=Vt<|J)IEMerGnDZny6&!i%CbI3Xf za(+p6*d+qOV?#Y<_8X$+-i1GmL%LQrwMeHO^~f^UrXgs%w;0TmO7wv;Wd7N$XN`3Y zA>PcHc%Ms{5IDjE5);grw5~9xjZf73T!jFOa>wh#&~Q}*Vt16HEo)#wSle0_z@FF$jl5k#=?*VvF^Y(ui53G0& z+!`qK)H-}z9GB^O9wcRYkcBB)2dJ1Gvc>($a`&rNKqdSebnw zbDC8!s8;WRZ)(&XxO}ua_L@;28HwkGK#;NRPxW{>fKhxkcs4*`qHiECn}st~@?zE! z>|h!ey)&EfzlB58?m*ivxG55H36l{EzvetFifVw(YA;RfV46X1*jycm+Vb!FCeZem z$m#PP0j4V*b}d$iy?Og%9fO0F`!!SlKDk7#E&eake6A8$WcJ(;)frJ+KgJdpoyn5W zxzKSL@?FAHb3{SiSw{@uMZ#G{7IZlYu-K0}+z?5Ga6xh)933n3_X1bf^O}*c$hGyk z?uQrf&0Fo{rug`c5sbAI`4V;Qxf*zVXMbKAtJK`x1aNQ~$r^!1HYyl`q(O(W8OF=& zb5_xa71N-mw3HX5s7)yHXWX*#KFtH=2F?WIDk9ag7|?Q$_hw%{F72CDS>V*Y^5w>7 z`B2B-l$W50}zNf=(HZa*Y9`!kJF z&r&Chg8HN>u5D&uR15aa)JBj)S?C``L0KWM2ZgR8;>w>*iPR5}`IY#4KIYI_<;3wKx5ut(#^z^;Uqc1- z>?i6dme_axtx{_G_O1k2{x_>>7QTFc9tWJ@Y5R}F1?jWa6BDDAHWw3zRFp(gQl347 z&N`W$K<6;gK_DI`=pm2%=YLBpEFj_!SPX{!dy}2{L!7(Z>{``0{gph2{NEIYH9{iPl<_zGQzJqY9d^TsRN%r#{Yj7Kw+{x zY4O1i7I^;WAMEIFb?4tGaI=!gsY6y>%Jp<|wLjbndUj%XYDb`Lvt(dzh;8(O$1u_d z`ozgHa(7~?VW<7-gjzMl_^#ybNo zrzWSO7w0QQf9FO0>maPTvc6!S#Xa{MQB^aKbOozDrH{+J!0VbmC^HDMTWCGyO-(N|qK7(Z{hp|W9eq36S>nG% zU*0`9oMMy|=c=o!Jo`c48mj@J)&Gcphls~wIl%$<5i@1=E+td3xL;+IbVoq@k88@D z8e#Q*f8y9u|gJI`S2 zwlkEEGA3KEAb527j07&12w$HDxf*6i@^YD((PI=%v6M^qqqLcc8%b;Z-^sGMASj3TC@))?;)^L$9izPYvT zLWpZ^Z*>l@d#&XKfk|(sapCjl!b%l+nvt@6EFIrm&zI?)Be&I$GKd84u-&Z{a3W;D z(j-+hH3gGt&Hna$7cy?#ygmFiQ+zq6rmp*@9Zvmk&aqh3S?nds``4M5&>Z`Zyzkgt z@ykgN_Z3ArmeB>teg< zE45NM8Blc(j!kL?P_Gisxc{-kc6NlYxu`^Wp3XlrRNIM1ygGKttnH`SrJrC*qAJxy zx#d4N+5WPmt!(|;m>a8c0fN|oh=HH2-gs7(-viC*gpya};W%Ucd-tX$WyA|)Jp@V=JHX@s5IJ{hxa=-Q7PZc!c^m{V7 z>Mm7Gy_xZ5biCI2`pxTQtR3u0+BfI@`(ELz&qM{Po^qUgJ!Og!c6`K%tEwF(m07V% zJY(w!H63MtG3Xi)5^`PUG~PM1weJ$vFGtey1=}>~vSn*Nj{6DQUfJQ=d<%2Z*2=tl zXFMxN&-$d^n=21@|CV?cpFH{qKxs(k{rn+9*p7!)xPrUBgUeeu`9K@CsBv;GPcL;F<0aj`>vkr6omxdZ z_h=9}=qNi+@av!_0{?+KgE)yvPhII~9$gWdeGfNI_4Lk*dRNc9oOd`j5P9GdKdX~< zmMVl6hfrO2eO(x3(Hnt|kuNh^Z1?(ZMgEA_+C!pUtL{RPwTfM~w`j@cmw0C1tF1$) z8pC%fr0|}e{_Ofy5z$iwt>~)JQ~S)ruET%nZQK3HoAMC>bJ6UNj)?Im5o4};* z>)t*VVLfYRg@%?5-3w*XJ*Fa;3Fj=WDUn2Kae?uNlw~^Zmek{e8$rvQntH>=@q6JGmNDk*rr-ck76~HWz)eA$o1k z(u40m{KH2m74=-#d7OW!<$Nez;j?W2OG`xpwZAmS(4~KSZ=XrG`Q(D-CH~ym$wYNt z^JN^w>B*o41tj42t_&e2RwSKrCtJdcOP1#xp7OH7zqdszL1R(eFc^#lxYa)Ysu>K) zak4Zs1D*o!UmI>CUm*~N*KXiu`}vG>K7<-YgA+Kv37UIxY>qz#F)xDtCc8ZTB+5+D z>s}{9xX16t+0WI@qonMlPU5W{1?Q=PSUUhAJ9$1(9P59uSez@7>3&|=@-$Yj;1LZt4LE6` zB>{D^laqu9GWUCNC^F_wfp|M^UB~BbvMKdt=nL@3jdmTNplml~ocMU(e=_e$ zbL2e=Rc9CHjvINX@*6fJ={381KHV5kMwgPX4~433(bR zbEYT(g+Z`Ew6CK&+jotI1Y!F9Bh_Yi=0i0_D=isHib@;#H;2K^Qj)u%v9yKkF*_5^ zXiesgSpF>b$>s9dyJi-CCrqA%!V#bXkN0;>=ClRnbR}~&7mYtTN!kgDF_YI-@;;aQ zgUYJ?*C+;FKCQP`)*AZ=^n~)EM|30y{2e{v?D)0X(f*BcY0S;%RTR~J1ZnvMIw5*? zG|E^oaOp4qhj-HFAliJ7X@Wka(sK)s%7qu+1XhePe7rr?zmLiEfg?~h93yiLatYlW z$aj)>r%9tRYDGxz?g;2Poct~^sO*9@(R&5`a6mse=$IJh6?!XL*tx z@CGs&NoJC<;?VR<*bQ%`E3|-co9W1jNAd87dOswOK3;%vRJ*Yvt(vwR$P#!~s6`n! zC{=D!&z%vRzh;Zo!OsJD-o(lYbgHB=#u$ye95}4ZKsed+$&y%N%OpnW2SWk?^RU*# z>-D1esH3FEQ{*E!ld~XicRMc{Y@~PN=wMkK!B-7L8nPFY@^52wpd2k7o~p^6c9FHt zIWfw6-{-XsC)#%Jx9uzi1B#zm^ma zg6P*@5+A4fk0lm})%V?pX7YpQ&u#l0HccH8ruGT5U1{A8YXgTh_YdjJR-0dAiz~?i z@X4qUCP^t8K{5esmBn;RhR|23^_ei(5ndcDLYPI?+A&JJ&1 zxh#bK7#oCp!iz>A9nTZ_PNQY6rR<6GpKgEqug534erTlfU_9d)PmtMU2&a)x9#6rS zu#B^W(oaYfqKnbIlOk}@CSsnz+}Y2qd-CU9`KHf4t?ggNVRzeJ_u&E{YZ5OWaB3Zj z0RYzFr{P-~6DylcCeM-snK^xsygbSb3PN`CTOoC&p8e0`(?H1R2Ajpl8!lSgy(t_l zCu0TYA;|H@{eqL74MB7@NV61H0*C6z*(fa~T!|e_QD6JkU)j7j9(?GAT8RE(D#oPi z`#lT@@FeNO=PdP5BUXNTf@d{s9l?@gHi)%+r)(J?TL7b+9ymWz{W+FKoMwiJ(bP)an2yQHjc++FbK<)gy z*M`LU%jfj2nJUGnwSb2cS^E)_=!Vdxvy>U~v71?j{g2^ss?$_&JRAmzBH#OE>72~c z9=&9m*BZ##z}J%{3+wr zvahBA#qe<|M&>cx95_^+3LcCobN(nS0F-==d$q&^aN=S2Q@;NRTEG)ha>gF-$006` z6Dr{9fNMj=^$;v}xDz>7OzMWOQW7 zV(fIePQmot#?AU1(CLZ^+Oq+c=~m~Ky)4t0vxWOdI)#owT-)lWI#hky=(MsJxiX($0ls?jm7l=bb$lZpV#V|EI*_T*`IfbD ztLQJL7zb{oUgim2cEi&Xc2FeN&gy4(NbSqHv4|=N{Y;C|q{8{Y%2FXJ_AoQuw(#^fZfo9_at$_1oHQ1iemLdRQzF>a^-i%q!XjC00~ z2AaLx9$fPqGRO%o8@UA4wVX>^{1B>@_qiY#t2>Grlhq4UNxy_v!!mLzgPE) z5BHR4ib^b4fV0=ogNCs~CQ9OOIrR8O({4D>NsVf5E)LvlSf2%xw&<-t9fZ=mwRIHzSu*U(laS(BT1ha!0pt-xyV;l10bOuA~ee|VQ|9gctZT#_mF?X@`p91fK z@YEi~v+ii;*U)^tKUHgYFKyPiK07FDh=~w;^e^fxX^O7Gh>=2!1{z53QiBf+N`5h;nD_seR~`d%Sb-NCU+NOKGApLWb1r57*{|=pn9tJrOSB^ajeg zufvBWC=XJ!p~w$rmPpWWCDhhL23gB=t5jxlT<&C}Yu1b!dXY+&66JwMcv*b}W9cYe z00m1j{|XY@jS}&gxC8NN3GTSAt^(9if&Ry|FqDX^W4^RG%~!OxP92L9h=`0V_=v&! zTFd&-o$fS?T70#UEX}OwEu(A&F0F+S0ye*jNB(Rfm7dU^lAy2AcBX$mI5-#qa-?x)rA^yL{r%ltaDOu_ z-jJ(=r5OD%3iAy?baTx}La$=iLTdRr?32VBBj=6E_{+4BB#38za=D3`KJ})MByC`3iUHKB=HRBLChU+ncYi6+%d)}I3BSNA+uF%el*0R` zRrZ|6&0z(0d-U~OCnqywy&Ab2;gdm1PvDr;pL@ile$P!`AEr|DvR2!_Z%$5foe0MT zQulN182O_1tMe>x5T-v{UX~6u79lLIZSF8zwH9E|vmVRB{oSm}z7ZiZ`e3EV{dGJzFFYqxScdzeaK>I&`Vnzj?65j1QS|ks zJRgIfkVk2~f1gU_JueN}CDaSagirphJX{)>mB!M+D{Yvkp)z_y82!QN4eA#zp*y0X zRrA|-#0BS?b6R03P`?c-fzfghH=i5Ldy<>C9f+Edx{xp|n5qEt-d}1ctd<7Pr`@F4 ze$5%=zw7n8iP4e~l$sLxx1pe5ayz0UvmFb<_H*0rn%VrJw*1{vn%hsowB4{M?Xn9M z+OeU&L7VFz`TcWYKe(cKhY;Nyx<5{hi?^Uh?j|d>M*G$tcI<-MaimS}(hQaAt6sX) zhlq^0^aguRIT|^T^f}oOO5i*gPxb)a^N3CIXl+%fZGh@2JDekPNA zYYMX{ov1RO*89~mUd(IVa8iNdegUC(d)XPakP%vCb)nfm_HyFW4QJF+3Wp>0h)c(> zkn_`>);)qrvv*|zH)zK(Z^?R!C+vTglPQI6N-L5e)qA_|dvoA~s*n0zxeUM53mIkA z6&(8q4_lv`Jh6w@r*Y{ONEhLb*k4C!s%mbDqV)Q!f8K-Z;uNW>NOlVLwyf@S`Q<)8 zN>bxl#AS4oTm48wlsrqfHY$fLG-C>1HI|vJ4jD5+<$S!&Vb&MU?sohBVcads2 zD+0hpO`5is$8*)fx2FHJTiuW`XmXppuKO{93_cAY{sn4Se+mXNY|-Dh`-Y4#&=tv& z;Hav*xKaJ#ZQyXh-Ol+S0TmhvVVv^K6z?mcQNr)OG=pQ|`T5dNB5hZ%Wc%Tu(b|T( z$AjS&CU^l^_52D^(1Tw5N&+i`w1?-YwHeCLCnwI}5RU8lSpx#ecq?I?pHw2w+^Vly zx-|c~8lkZq#U5J6m*X~h2mHUB=b{)*l*-k3u6^>qCAP}22-JagVT&fc&G|Fio9_x1 zJkn=3_QJ)*z**raO07n|#K8ZwYV6`?l`kgp_Yd_|0|J;xk4ax?DWV|Lq~uQV@M3@} z#r4d8L{9~wk-+oBI~a%9W`AQ5*)#pszSOJie?p#v*%V@)CDx2sTLlN0CDNveEM$6d zWyR^`{Iv?)(YSXd?hufeym+u)S$m~xaA9Fu9IgXDVpXPYZI1!?%C71QmhCyg6hRUn zyCOdtrMU!SyHIhjp<2`GMt)&w|C%e}8gD-P$(u5kaxY(ZUo(y6q982HydE8&wQIOn zcMwZnlRk=`7WwmxcgS#9`k9gQuw4IoK6fWn;{836cud#eZH!DhT9hyJ#e66qmLwtM zc&{IW&6hsb2Zh)Q{}-5=wupPu@xKCoWuEHf^~YQfaQJIa)meG0JjB^)pulqWo!JkS z^KY26Z??s|>CuPjpiI%69mMhhyeaJ;B)9m^I1umT6kW4C*t7sV%X-_ka3(z^`tJdZ zzS9AG#mVP<+S=M`4p-BIZNnD3>jZx1c-h>B*Dg&4-AS;*@7}r-PiLENCi6fNP?M_R zxh9$ffJ#m4me?JHO|^#4|4I*zig4ZqQ!{mPP4pp|5v{}()-J(q$#*u+mQiebAj$q~ z4@3y3_I19m(8jHf4cveKeT7K5KCQv}k&Tga#rCvrL|Jw~jNJoLWB^?E8xYsW)2}8H z@u0nPICSwq!grmd)W+al*wn`?NgtK&wuf_vX~Ygb2tx~=;j=Jo*qCNHEt!1MlE3Zo5XHQ+%s6ayW*Z1$Q8rVZxWiA?D|h3v)dea@3*^TFOSL1daNpCV`$) zxP=L=s2-u^^D$7iuZUw1TCv!hmYYBB{CRG&gd-xX=R@Gi^UN)#5{<^IYf`qk8R$`716E;Y4N?U_H=(rD zDC-htLn8hsZ}%rQ*z0<#I|%|=fsoF;G^XIa5iXf<$MdtzA3^HN-^imTb0AHU3pDLM zs|eWNrGXy31-ZUV&f|e&`5TMG0KD*k_j1dN=tJ-AAYaT@4CMKK(1Ub&*$@T zf86i4`;q;C#y@{tztS8U8?f`w4$Mh_p}qaX?^w9pnpm*CiR2W{@%dkM#bclCugx@x zB*5j;hgl4vE&JE0IoQ~Qy=zTE0z!lQT~2qno$vHou(PQ3tuUvULvF@d}~Ugt(fuWHVnW9lfso?&w>z*g zE8zh^GE9vv`Up>`^6?RH9Zy7Y5&&Cm9ktSe52N&Sr0C;ZOLg)_Md2egWRv8$r72M|V)B>@Q7S7y)D+)A=CwGu!D zZ?Ak%nS*OVg^eHDjVe}8uadPBb^_0nz8!VR+Em{k2^sxeXi>lCPv3k~F;;ypo=#Zp zySLsOb*O*x$Ki<9xi@yQqIfdPzkKxfraiA=;Akn7mp?R5xWY8NuP+ME0K>Vtd5=VE1zzR9~P zvTnDST26Nc?*Dynoz>^RwmWC?D3>OSVO~NBXF>(#3>^io0@m#B?qR zZm1UQYHh99N+3#@i8rYyheaC}KeWF|`hZBo)3U zEn0Ob2#SDn@|Uy+Jcfd~38`E5NcBt4lL}$% z@r2Z2QPVAh(={?CVZz={Y6O z+)na??g#cfE2-aA^pRFB6-|ER(~1^494;a@;-r9!+`@n&e#*n&+!CZcdXwlq^|>fb z1bx;NPj3X`t!VmkN+wRT87OR5J6HNU#7QdFJZY)=(`PWItLPM9- zqkXQXCRg?+I${A^B{L%%v)y7x2}yssCnuB0rDZ5S=TuyEj<8B~1jEFvAA(JJ^hotv zUmG!f+nX~`A}3O%{*k|1=@z_%vDkop;%~9 z<|zi#TX0%zE>HvZ?}^iwEI3I5ImvI5LQEnbnnbN?<|{|dMjcHbPj#OBnI@#}?vHgG zADnFO0PiU+Sjf>q4FYm-l(*Ai#47TgOKdg1O?y+^jY)%@JMvwR9wgwPXnMbD`pD~e zt8*_+bFT=1P%+M(%m8&a{|htQNA8)`wC|e?cCHo&{5h%+^5#-L_ju>v;NYcB z34(c$2iOfff4?6+km$wTd6IMfbwwFtT9WXr^#N%7!39 zxa3t%PR@i%i3>nQFc~vtRdgi<^vC2pAoyF0kTqe-% z#CAUzQ`JIH$5EBMYcoqx?TziIlc1>md9&vMBb(b*lW9P|`bL*y3h(Jv00?3=MpXu< zK($965MBq_%T@zr;7^fTAYGqF?LA=rrEc+01f_(A0I5wF=v{5&?BgKlmqkCIMWbm! zjvrtA2u?slq%L6Iy#cJKGepw~MwwpTDR(5<$j+h7+v#M+Q6<*^FKye#EQigrADaQ%_r zn1P}>_N5E3!h8ZXC^O42=ZVv^5(Xnn=GI`$4;s>OJwEydD{a>Xx^2e38`X^MP?;Du zJ?updZz?i2J(5=f4mQTGKXb<1ZMrLPS)e+3?3?k`8g~E)A^FU?gtYVFlxtn=a3{JGktH*NPID5?&5m0Ilj=DH&8#jc+dxk_?5>jWhS}jV?T#jT8zt^XnuqMu`&Cq zx~AFJxepueJ@%#m0b9V@ya88I&I{&PT}WDr`-mvH%RjO#N>%|CK)`cq1}ZLgoalyc zV_xAYp9-idEB**D2`UYa2IQ7(%Aay7xw7udsoOjuc}pw$;cBpeU%`RCzALdnPLJc+ zvuFK)d`s$!5vfmx*m^8XAJ<;{&Gd z809YXY`+<4w;#09XQc;@*f(Egek?0Tu`thC%F<7PEJ9a-^kj}7(aadAFrq2}rQwUS zl#k{eY(+zN%@hMhK6_4>Lt+QQ8LrXpXN@#3jSpXKj?Lj6*}3~AFwL9WCStC3bQ{y z&oStrmR}|A6OTCUH~NvIfmy0%z{QJWg2_6ey+{= zVcS`jKz9y+fU12S^%pM_wLkK4R-8Td__d5;}^x#bp8^EHiQ{*mxpC;?f3ULQV>UhUS1hncHIY!%~Vdq$rR`(kZ=Oj zm%_Y+EFjIcNB}AlL!R$~EEXw>3HNX^)VoauKyW?&|<`Qum?^AW@QBfR-x z_ZzL1i^R2$JbCel-+Jv;BK9{`8J+nrU834Bu&}i!OXQDT{-NQ(hm9#(doxn@(#lxe zi^Nv+*@~XKL%ZTboZbJUd{6v?&q*4jnP&ia-Z_j7^V3G)hcH7R zPAiQa)%-+nkt?o5zkXH`$VHdsHcgGJ+Z0)`jXt9MpPc7u|9wtssb(!Qw>#|w0u5P9 zR27QjC~%^{s-ZVaxM>CsiG46xsn{=S%9RL012g*-mzuFtAAqK343)?UQWt}X7_#o1 ze^lk=P3{IzT8}(El^98N*U6h5E z?58G}kJm}eiIx%(#0CZaY#S#Yx&HM+SaKY=Kwjz$Cs~kW-OnME2INbwV=_(8fOKhQ==&pl_%=xi`WNzk zsGXw0|E_-X06WDSC3haW0Lk;RT+(fcbOH8w7kg&VQaxYf{?nv!Hv?H_==E}|stg}4 z`L5g`m(+MuakLLm1}@49yXpfwOQ|Rao|H0m+h07Bljl-U#(ZhmfL3+#gR2JCjZbGb zzb{(65WU)~Pg-3FPj&4HZyLht8_cVdtn*ugXTK@}#(DS60ii$%Z-J^~axv?_Yh zm?7NQBBfHoVhAgO%l2M{x#{8v01CRKYw9ltjB6-|FYD!>`)&E2uy*mNy0XMF>3aMH z%6e6EDT{BUh_xgms|*5^9Yv5eYRySfTG?bd8gXr60tc8ir*>u_ldVtU{Z{^bKF|kU zAj%Tnil61kZM=xTM|x#w`~s*4BJQRj9(pzlr;F6V0%Pe(f8yNw4&f?ONVE zb&VgnMjRKD<{F1@Lp-atJ~SwGSzI{zY@U?j_Z-5|d~X@C%OAo~?0LW9BLM7_`T0I* zCHI;aUzL5x!a_4`|M+?2D%oFd>W2WHtw;%w_e|{Cyq6aS!}rq%kH7oLsGa=X7*uFs zf@p4hIXejWp7$qqH{X~+K3>)EU0z?@l+D8MKl}kk#;}QU1 z574v~O+4&EcBW(#FCho&u)i|nyG3dm3kcG@*TApqrJvymaLiB`OUe!?FGqlz7%R&> zR8jgba3u28`GW}eFMacwsAs4GlKNI^SzElhmFf~)m)a8eHj&j$&jC^Zhrrh%+ENS7 zs7Z}hBbYg^7dRdy>K>_N=c)#EOf$yJrMexJ1Prg5MQf2hH9opnalz@kHMg$Q)OVk& zVmZp7^}68I87KT5Q%iGmDa%`s)LMYvtiKli{=q$NF(1>50e1ZOOIA*V_8o1w+bGyc zOT2_wU6pJimbSHZgA+`0tV(Brv!6nLrcxKVO~U7ADd(387cSo>x9|7}I7BeofpT}z zh_w=4B>>pUrF}?A52^|(0`Osi*RC8)`TODLCPq0R2rGNr&VXw~;j`*4x(eS;<(FP| zPp-U%Va0FG%)FjTlqZwEW3j~4jSN=bV1HS=FQ7O5`qu^rg%fZJ+t@ zY5*~NJFiQ*7hFH-GYm9@T!BsvMHopMQ6D7efL{~0;wa)(EuN#Ip zyeY!JTA-hR6N`z)y{M7HJcPwnVf&TK8k?xd5}|SaHr232z;L9go^5P7knUFOHcwqF z4ccBCcy4Zm99X1OwOUNpRfZmQ?cI9$Pc!&8!dlw0eq62wOSh$$ngYWm@TB7YseBgk zU;6cLeuBW91t!);b}C*vAG8x#Bpw5O>7vJHCz-Jl*R3Sgcm`taPRUWXv?v+A#Qh1D zj%7nA@p|+Kv+Dr0Q5}BwBPhHNtmS!={f|JnBR*0zyLP*5BHbBw{ar$wSG z{_3mb|FHeoQ9}qQ`c6k$U^g5H4Iyg&JW7|Uc4&{>piZ^7AB|0i>p(90;$H5h2Tf}z ztGo-NZ+FrD`TMQ|?9P?svCgOs>esf9t zB~XOlV=G)kvpwL?_vLeBKHeO;Gps<)1@Ll{oISp~)n3|UffOpSpW;*q_$Z!gR8;(E z>^=GJk`%@pm7Srd4F`1Es+FAuON|i=(l7D%{%gJhS2=*49(uA5$8YT(kcBls--JDR z4E=C0`&vkU_JPMCkiY$3;HATV&Dm^BKR({Y%HWOI$nu+&6=21CPG3jtoeu?MsbFNE zo?gjBkc2i?!pVX$?XgGZO~OQjswzLiH-*!Rm!8jwO4l9EtfsJpr`M>h;%+TT>Hb#^ zoE|=8{Da)f&wH)2)8_D?S>N{`U?HycYCwtvj3NVF%g{o=ybFiyw`+jjR{jw+&Z+f* zxm9^ibpQm>YP-(b`c}(ZB~{6VHy`@R<^KEk?`MY({yK24$4<2$i7)HsK0DQsu{GQE zxHb-6+!$Exfl^+I;L#(G10*}E#j2WDp=yGo0X<5&GQ1R3j_6u)NH0tzQx20n3eiSn zZgfcXHCf<@rmsZ7MRnrV$ue3q!J)PTghPt&K!q8$19gAM%Z{?5kWrTlVCLW`Ipt-Jmb5;DFz0B96<)U3+|*Av z?x>(15SxX;Ab;A806S8N-}b+$R$2(hq2mur>&7oQtSlHlc$OS;c1W%tmpJ*jex^-g zL!6y>L!0L=Ll^$4RE%JSXC;p;|4+mG_c7jMsJXmcmI#a`Ka`9=#CymiKDD<76|jV4 za3+w83j91ZvYa7FmH%B^t~>>)sqwlOQqbs8`~qi2$(n(74F?N=AEU$u>szXcsN_eL zjYJ=gHb+w!Av+s@WnrM$arQVsUCG_rI!D&EB3X4r&z!jY`RXib#MtNvn(kP5)EKmd zYd10(6!zifwK|K$KFfhU`=xum()QEidic#8&{G-TY`7&wulO#CtCu&96Imy0r6rmQ zJk+^v6e{VQS9Ttx*jK!qFwWgrVH_|1qC5Q*zy7DRBHGV5ig6HiJh&0|?e#&+8zom5 z9%MEa1Y&Z{ZB)_q%AL#Eo6(LDK@7GgK)G-^dBF9Z<1>63^KjiM%pH%)?oA=0XkcC) z!p!?NK4Gy>cVnT#Bw>Ph3HBzX2gWEM@)eb&>@L`hiH-ENSbH)4J*aXig=&MMN8JKK zeZ!Z(=^=ZDhwEc2EOCiIUKy3`*Tn>?*!nYEq%Scbs2SqiP(V_4)o<3bvjlwrKIy73 zWL18*#sa-o8td;uGN<&>!b%Sc$UsoT+;DIW8k0-30hV>)ZSbFgQORo+1~+4FQ1+Bj=CK z4!YBSZS;&nCgY)x!DK&wp2o=U#akl7w+&Jav{@H&bU;cjU``VBjFQw4vv@mqYe_c(xMM0&6ljrwlt9bLhcDvI7N6vLAGBM4`pUZVLqRa)R=x3xivv{UfZ4hIJ%x= zisR9Pr1~~lS64f<(iH5f6CY}fPfm@+8lgC`r6Mxr?tFOQv##RMwuwbCL$r4f1zEYh zDPI=rXFfg<7Q#=^_IU8?J~*C_vZA2!Qo+Zrpy;9^Jh3(fcbj@6H{gtuTDEaAinW;Y zZAGJWBG7u{5!dpj%8z2*53s@bv-yD!)*Z~<{dsS%+@n=e=1#^FQexly+DMsI9*~&V zR1H0Y>Q5}Zybt`@cgtQ8C4Yvww^~3roi`DIMrT2fvZ<T%jt=?dp~q=8Gmy2AS5Fm z=1lY$!(oB*1!&k)P*ir!K_NalYt)qQj}O;(2ua(uG}xQ7ekd;w43u#+{L}Ib#RSq$ z49Rn1f8xl9TD70v0(CceG@!EXlwB=L>jP^!=3W-LRDPSvhd1 z5_OjXB>?ZY>*R}iYlnx?DS)i(O}Sf@uO1;G9>&NG;zL+vaD1Gp?1Cw)eu8eaeP(mE zlY!|+e}Y0W2to>gHWLBL-!f;Gtn8FppxQA|Gz}P6(J}!_?T* zG{d$Z`6(Ri_S(0yL&ua)dRkqKX$UtSyQ+;2?c1u_{{rjRZ(cDrd@3@3)@Vh>#pEF`QVQu4+CfH>ZtBrsz@0>+ZCBYSIvmyhFVWrlwpl*^i~eign_3b# z>JT{QvNBhcD1K%44}yrtLPP*Bhf?WvX4S%-98On5a5P&aotjh=b+C2SB<~LWM%O*p zpdH}b{Y#@g0Um-0GaGJOGpngd1!JL~bW|CyN}YJjjB|rTG6RZ-;-G{XAcMqy1N5)_BVO>mFzbuTE|0y%G}z!lK*I}J6#7t ze;+YmbFyTKfh}3XQZvF(L(X-hY+gN>X%(zOaxjUR`-N{ubWgHYRmPYtWNKiHe7WBXaFp3~eF?jYJ#x&5J;pz1(H5~F<;gS=W z>&pf^NcP3|_IjE!`XPYdcuR_|RVe+P8`QO=$2q)#^+aB|0tOY6u&7W5A|~ZEpd5Pt zK63b?-t_g`**HJU}@tS_|C!hBy39 z$0;rA8VN*?bFCxsqDw&|2B1f1%U+5T1pT-Jln*vRnYI37QD+MRN?i=b0wvP!+$KP~ z=EsLk6PNds`JW4_-6MK1{%-1Uz+ZVu{s%>nQ?zPW5TAVC^8mTKxDHJl876G3V4ELN zo{>8vOcpOr!Ifqvs^ycoA&4$rNXW^tI=OF={A(@kD!p6|bC#migZ`#A*dPcgAk098 z39MaUTn^9a$Kv}y#^S{r$tx*n$vSqXyJHu+667)P3nYAkT#3TPr22*Nqk|o!i#30= zX$=dW_~IKZ79|+=nF~bt1`{cfB)|y}gfo$-U}QI!o10u!B~|b}nP1TkqCseK4+;vp zKVp!zWK~TfMU3$?gmp3eU0Gb+EctNpM7a|G7BzK;YCI&w{+?By%b#C8M_<1h@g7pP zsmtTbZOq@Low!*SogM++o#*;bgO#OODmfNiQMjZ{_;kyGq*F9?JMm0pizGZF997e=<9^tnE~GB|%e4JX0%u_#PaE!>;Y zmsYf~u|<1wO&U{@n7=okANN5sbai#W;dp|&C@mHa`_f2PgcMn2@p%cUD~HcM;eBRo zoOfAB+0`LpZ*-=+Ok?}$!t%IK#MZT!GXK0Dd8(;voI_B}jbsfFzF%%L4?iIe@O*0! zFJB00x7S}XV;{^@e?z|^_AZA9U<-Bx9?hh`1X5?|mc0BMD=Qwz_cLt_75Cg53ULXX ze7Ee{ce?aJ@Gf2CX~Z3@Hn>+>7sLcgk$Z)62C_b^n4~>hiS(B}X8T23Pfw38 zrD=d@TzmItdzgu8MHN1#b;c}_@M~U&8Kj+A@d#%O?FKNr5!2k*JdH57*k+nj%z=}5 zl5?fczg0=&hEYK#d=h>YA*=%1GJ#orqN z5OYO9y6eI=HE=Z#rv|I4(s0OCW%RDT^+OF@&=!5n6Jv(s zUfsGjc0Qb)US4N0$eUF4wQ9zB6ZH-b18jvKQ*b$ht{&4(9s|mL6fGi)dq#!1A+qPQ z_~nK`Dykobml!Z(b{&wXya^zyvT*X?v0i~iN*!FRFZC=CtP3nD0hN1>2>=bLp{hpkcK!^!XU z%k#_iy)vDf-$t&QtV{0DTyaK;hsz^Zk#PnnZK$VY6NIcY9pI4!TBWk}Cl!9#2*=~` z0fEL)>XEGf<(_+}T&er=U|CE86pIogRF<0?;xD_iL(gOI1V{;#nK<)+bPnN&h9HVm zL%(dm2{Aih?!&$OBioqO*^l}{;j57lCwD)Q$GXU;v>w=YU|@R?FtacCtK^!LExEd; z8B`a4;;~_vVX+cZ?kO(rx2M30;4eLeH~t{9UEQBOMG|&z()X~ zU98;jIybE{N-}XotP8MLD6A*PYl&N6la(|K#l?y}Cpy;@k5_KJta%3u--H7FrahUc z(#G=$q7%gZGJ*#U!xIs19Ubjw)$R~&yAfYo4=|^ZSHN&)i0DkN4(z#o;Oa1Bx5&!-(|N)C zoTKf|!^=b~D+*kgR>nW(5X@*7x}LQWNlU7}kT}qMb;p1muhW83T zPX?TJ1{fMkiNf+^I2M=4DrP8)Cz?Lv+y)k9;s{nzaB517{CVyKgf6ebBEQVfw!LE( zhN~4ud?j9+KZ#Ya=0CjZO1MTD>A7eD=iImJMw5ZmmX)tk>aeA+ZUNitw`5S*G5U?t zzmFPYAbT*_RhYJ+cmfJM9i$#}6SCZ{sitNtJ%~cEg8B_66`-Oq24WWqt`F4JdUXSO z+sDjZC~=qoy?#a({wd)uo)v@t^z{;+D4nSG=`IlDv^97NubY^+ao~bn+c?Bd2dEBU=#Def8qr~94p+mh_dyj@*)_*&FLOWngg?XDm?&nri z01qb5#1vt+JP`qIprhKq!~TLxAHkc3y&{e`AIr(hd!~*hnIZ@Q6lGp~A`*)vK=HZE z`0v&%AMUn++G}BjR;D;eY=DdX7gxV4JZBO(`(;~K3V*+e z#9YUI&4d=lYrD6%+O$#7%*XRBj!E@@%Ucdv_uVVX!p5o>c-?BZBm|5DE? za>mpzOIki@M3^aqmh1D6zFcee;;=J80f!F3HEq0DeDLMKzyWWw!bQD2RxBsMLUrm~ zn)A1&b1vUAXT#fn;T*|O1gRD!oQ3nJN|eCCgm1fQk+0CJlyN9VC*~?)#?rpSDQ9Ym zmS>Fh^02x{g~iKpolak(Lu;Um3bJZc zXWCsIEEK2xQm^378KxofE`aVeZ!G2E#sC?e2YCO4Jg5LJhO`S+dP#;+_U^(xaxbTz z!(s6aeim%w0d~qrda1dbpT_ZzUd`iSPe`2UQw}Fd=LAkT0YQe$!4997Goc|LWr=^; z`^C{i%GodCWt|`#9743cuH2@FtYRW<(LRZ?rNa8fA7X$ucF*``TIkM7kml~j7yyS; z?AV~RdYL3Sqw=3?a%&&vbO705@m<-#WX+dMnu$*8&+nC7?=K(ByL?$A)Zg1X-L%Qx ze5>643$M;Jcg*?o)c|Ju=^7;Zgz6rZ)yI75ZxxWJ{uX)%whlzb3tu zwpUlWEg`hWi7e61hW@%~mCOq0?w6JxY9TKNnS#&+N5eiAq5Po64=Cx6d}k3*q7ySz zIBNhvdXmL&KIS5FCUlu$#Ss8l;&Arm$vkz17ig3{S0Qz#_)F6Gy;r#JRNGFUqlskt z)X-Ga>TTpg&KNMRBePz^Zb@IP=L53>@xWRPHzrxZ);s35zrDBg`x%1gqeqU3h#0C{ zcfuEv!X@-?q6h&EY72k}gAq$@Zf-HG2~Rn#%YXgd{5vz_*l6t{C!{>AXA14cVTn)I zd?>IYqLpj!@T~s1VQ|{Wh#B!_q6Szo|0^JIJg7Vc^+lAIK0}(u;5N|^hAn$4XOoJ< zW!sMZnd4I)?7AP6v$f`ddZzWZ55aBPbE9q^xhwlLmO-T()E*co#$%ETgNBgrcI`o! zQgOh`0O2-?L7p~chCE~NegvOVVkh^4v|mZxr~cvm%!B*8kI;*jMFEMboMwo25ewFU zEtOLt-%D~a8;GX;-uyy*GbT`zZc>OaKh3@3=}twCZA!X5W$lQh&Tf)Yk6@5xnCOT z!al4jq;ng0*fHbF6PDfR1=Iw;1@;(bQ{R_8VmX7o_UbEb9 zvU&F9ycn!NFE2erFeeC;w)82#`_fAs4toxB>xwPAbm+~S*r715%5yYcJ&i~;;8{Ua zE$0~w5F!sM-?I^nT7Qh*X8j;6REnLCeNH=NzpS2Eq`BGSR6^gqaThI~gTl5W&tX za+Ws=b&X9(O|U(kQj&=V`0MB&vg{~r!<#knP#xyC^e{Y;BlWgiH#>^l6$W7f!{ZU2sybd6IEwp=aQwXXoa6e&j}D)TZW1 z(e%O8$r5>s4ni*-D#4$t--Q+W=-wPG2!6O3@rgwK^&D2jAs7wD?b3oe9WqW|5mgEc z-)s=FUfOikIC_)ZGYPW>e;N}im{r` zwf5#v?uwQpfcW@$1{!hF6~-XXB%%%a_N!ZcyKS-0SK=zSxE0AGVJieoVE79FfxpURDbUw1pp(*vR~B0YqWvj=uK- zn^64s3ALK*Ox}|7SP%hJ;g(w!iu z0?Tz7-xc4{m@$nt(lXFP9vt#&YEJ r@|*W576Zw>TL@mX{4+^^v0Pl}BlNJ{SU z4amR&)3CJYb;KuFQdbd49F1fK8yG5;h>FWkfayvLAFeX@73V;tS;bsX%WeGY96gM6y0>Ml8c$S3_(&30ok^G{|x zfCXtg2ke)d6`nBBqz7@I!V{mopk}QZ-Sf zD*Pbacpm({hHV-mfp4}~zZdbTrMhh6p<$QOz!jS+OHyqCLwbd=WK~MAma+s?#~yGs z)m0*mzOSb1Rp~JiD5-pwrYc0C0N1z2b+F@Kwx=jc=?G6Dsl3{KsdD%fxtL*t{H`Q) zmU2)!mx+{?LnNvB(JYN}wc6fA)mE32zKyTjE{-cz^D*+4yp=VTm0d^_UcZ#rJY47p z4T59b|HD_9FL$^fNOOPV8w-kH_lfeVc~epS@M6;5@>=cAGr1OPOAS53Z9|_=$JmlH zQ+|{N!I&Mii^R2cAgT;JFQXXUp#ijWI$+bAOpyOxu{js7e;L>Mj~T>#Q#jgn;D%Q5 zn^#3;y*q+xZQg5zTvizi*4Z;LH%dRV#mFw9*?O|Hp!n_A`LZWHyb~D3941Q26RmZHea+G0W=uMhIFDKnMcWWpq{(` zcB<>fp7Y=+pYhLX{5 zp=w3DyT5n4X|$0teaJ6hx5f;zO`w-gj<>o=9&eo-jdgAYMJ+__jXE3%oy4Ck3jq!C zt38v=C(TjoCdX3_`!>^28(*uwp6((*v9bs-HyVzH_rOl+f^?x~i3l+e93!MGgNZ{k zgYKb!zKaa-3JP)!qfa!t=O1kXid3y-)St4*_4S3L(l@1P;qI>Ioq{)1y+YHJ%s`?` z{>(^Sn6{d-dIX(idU_%cUXJ%^8xkLF!9s}2Ijqz8?kiMi13m}_q8Spm-# z*pj)0Y~It#&+7(bJx6C*sAmj+Oa?{XzGxK?xgFcNZ*NnjRH8cBN<2$^y(1kQ58-=0 z*#X%3=>pvk)E;Agc(JpBv>=zmm`3y=Gqv=4JgsZ`Cys})a3bmwzNLEPqwKH2)@uGZ z&hM469MqPz8v^=SsCqrXgLbl(f9S5e_A+ws<^43dv|sbTmy;`4IQ|{2&dkVleYUcz zv8dR%p?i~fs}ej>I!o-G+3@A!5|`<_JI&Alu^;h z$6mq?(nX16TF@_v{Aw>EaK%&wQQwtT^Vai;RDQli+3QI<7%}ki4Hq!G)DQADRZMrU|hF7^6>UffzwPNF){?jK#w^RMjbEEl& zKYoB2A>_ynf;oPnFwYL}T%VS53#bm_ed8JQOfo(u1nAAgz5#Y*WKx5mp{96x$^3y+ zGz4f;_D9BWb>uC41J_}A*cGWZvjh$Y~!(t3m^U8-v45E8}o8t;gN{})bG2Yt9F7eH|$#O{oYvvcD}J%7SI8u=<__6v5pY?ctEc4bHx+f`IpJZPSv z1tB&fzzMgpr~zQ>=ZK~3kqU1p44w@?*gk9PD|7_3rw>_I+$p_71x4f>coK;0lf4;U7MAKBaksh?@ z?JXk?0C;PIfF|4Yo_j-L14#gC{A0`VdZ9qWB5@}|J?l#jhtcFi_mY0Vgyhyv#oR&& z3TW8Z&_~^jAP*;`^`K}`LX%xhU7N?GlPvXJHN6pqWFjERqGXaY2@Pf}E`UW6pp-lR zY~M<=1H6@pUupSZD3pjqzzTTu|CXKth8}Ue^g9yQk}XHq<(dO z?=1Txen+Tsa4?;O?4pl(JxO>cX=#2!156!)d1?`X_ElT)LbRyWnXW1unecyp`Nmyv zFb^K=#QqjVOZY}v6s*15aUMQ@)1d}Qa_6ydu`2f)g?{owc@;Wj;XgURW8P;Scl zzo{@F&MxlT`2KxuYx4k7A95806$V5~@I=!BmKb2=>Uv8khQBMqC<%J$h9MZy4dn(X zY?z%Xc*#1A;pvb$cu|9(&mlA)l7SwwzJ-95gn#;AnM}&T;mk+<6|NBO(h+E=6TX*n zk3Z%mmOMiXJDHl4=?M1sZ+QQ{Ud^Ee3Y?#kgSf;lRYvTK@o)vr$Ut3L-az)K4dw=ALf?R+AzENZIZPNd zr#UkX;tUZKc~lh(_BI9znfMW@>w39c^wZ~0 z`e_7c7SwJ`>i&iyw!&yE(8zot%WX2$&pq~b;g)Qcv65@WRw9nbnKyVJSz7IGVr;_M zMf^4szMiK=M0^WP;8a@T0$FpwL=f}uepJ&{2IN3oR}8&T3V@n&FYiXg5+0tjV=Y2V zR@m4R9`wUL4SL4;2f*Lu=GWkF+D*o%^!tAMz7?(@6ld(>w#mxxzTTFZF>;GnMm>BN ze#U{vO+^Z@tkH9-DoQ_ZG|}xg1Ez6g@)if^1I*00l)@729rLz2yT_RVD}jYETB_5q z=oDu*C{y(7X4I~1Ut$4W+=&1Mh?V9pS@AO)hQ1Vx#!{K)(L7~`JVln?!;cc&bTr0kbKpB!hToZf1E+ZTRjiEjPJ8q`J<&dtn zp8>(Ft+jsKe=1zz9Ob^8SNV4LKTquPM-I)Luch?;aCdjS%C(XgR;98SptfTONaVHD zN4kbBeH5Z;YN&@DB{OV0BR3AFPrBN}fX#hqc<}E0{CopF4$9@itYtfv%u_eE-#1bO z%#Z59!4InN#DyNwD>FJN=tmxu5>my6xh8wSq@bXnuQY?!nZL9!zAgawUzjOJk?(3s z;ESM~&VLUC(V1{r%=7H$K%XlI4?e~DEyXH{>2GWG7kNxbLf?b4OnJtxQ9G8AC6ZW% zz)euGBhe-207_B9rmR0WieExEI>;zTEHJsflFJqYg&_D=HmQFlK*H&*)eq3q{R6r?<2m zeOsBa1Dwnd&S;2+;x#dt*`?h3_-mtgU3Y$}XM)Jzt%aO#qMQ>e>ydgyA9Tv?#rD?F z6*jSD+7ZiuOGzDW^0Dlrwq8;X$@VSlr>2JlQs`Tw$@cJrbYPit&}$#z;_m*@rrzEn zJ1JK!pR#Df38iaI{XSXjJYqy01Vx@OPFzp+wzrQvPi}Q?0=P>*8CuI;W6kkw&(YLM z)stWBOs_LH6@17{m;^@<0sxyBiW`Bn2smaG6GI2f%6y&5lbp^~RLScc138t_omm8k zHPJmJ4APs0>-MJnNMl`8T3-h6V<38g1NOaxrcB9xfxP#}?_5J4>vxSc-qn z;Sj#|2tY9H`On#2kq%od+pnVF0H_UljDB0Yk zpiS%wBfbry9SmKU0!pF{kn%vp_-u@U<|b()5~f=kzDoL*>U9}CME365@6d;tVUsF9 zKsghVo5ZyNnjva>g0?xV=%LDP4YA5dE2WDUQOAAd`V!F`mzaOIH&e6;Rr9pn3B$iBu+3;FYu_mdaYP|>r7DTZnSjD%YVky@ ziz$8i9cuS7Bo)n0GsW~9MEd&@#Qz^n=N`}W|Ni08%9JuvMq-nM#D<)6n6psGVa_Z` z$oWjfikO5ELdofqV_}kG$b?MDgv>eQu#ofV_xk?v^S6fw^M1b$_x-%D3ya_+@)RIZ zFnHcCMIDhgC{IcETO>fs8mg*6ZZn4uP`ei%1oPv84#FwPMF7z7cR~(Yd$>#2A*~B{ zr9`iM>Qcaqe#srWmH50;@D>CPP_8X|h^f0$t0+sn0^ZOz1|h7a@Y_1ecX2QTkJoVX zAR3D)DJflz%kox{w+QqY3xu@5orbnB`5Qju^xoa_JVFlN#UZn0A~zN$p~iga3p=*9 zk-VIx0HzNOgbjzp3U(duXP)^&62-|4I;k}Nd6gme|5*U<>5;?3CxZ`W@&7PqqK5%t zb$f;f73+J#kQOGP(3PKq)Q=t&Fxsn@3J%bap9~&u%tD;i5n>B%~1@zGU zPrYFyih!GFs|&!z6(vs==QLpb?d(d-B|tsv z$^{G!VR(u4ask2}2~7zST;Hu;*JDwqm7F8!UdSW=jvB8GZd_C%zVW4;vGSsQ%${gHt|M}~?*bmQ)YY;7ksns; zpEWRnP5Y~~&osCYjkUwsh*eysUgaM3A-1P&Z^5aW0AE-|{(#B;o&KH?wl!vd(9wLD zpn5E9$-9xRNi08Luw$C4)2g_e%S z=Me+*KR218690>)SyS#CusTVxX~%vGj+pIgB9D0<{yrM39;yAlSbm|-Zjs|+Wx8R_ zN7+-U*%x1%w5n`Q3k1?^>-^q{S5^&7Z`7F=^Hu8*G&EUfNvEdU%0@p%Odstg+k07ErhECqm ze6!B{B^eJ`y^_+c*D3|1gw3IWfhzId(mtR_eUt2@m|;`FKTtuMAxvLi)Jamf(uA4|EC_2PzijK}<9kactB>3a5))Ryh$1r$8Ue%s)Ow zKVuvD3@(^oO>;Du*fx(&=YI0xxvy~<4dK|5;XiUE5$4z8jRO2Jj8Ru7dLEH%@&IuH z#zYBPdMyN^%?|o;t0fj^NO!2gP!uYEd8CGc)cp9cS(%L&a);}(?hDRo3##`4?x zTR$p3N`sBU3u}3D(3nuxv*WkB8`yM-U{h8Cv}aFd(CT%Ico+iD`1KXFMs>yo%u%z` z!SsgVs6J(=#B6*Eil+_(HsW>Rf*|jsesYP$(A?Frt)UA0#kzY(Qw7Qv{$`HQ<1UG> zmH8Q6V%^oWOOKrW-pJ2EvA1Nu9)i4##4Mp@ZmwE9;j$e#;X!X&-`u3hYR-d#j=)8gpUpvi$B&lg zGfq83t6yMe+N3n?ZPrHsczafj?SM=1w%h9+x4}C8Iwm3Xb4g4TN$sy_Z6y4jW&So_ zybcUkK1AE&xEIG-ws=Bap6!6*RQIv|l!;Xi7=?YZa($YQxwP`v&U}`fm0Ou89)cBU zFcEt!Bz?{)5=McWGDBPEZ|J`uHr1ue=i$N1{v2LMCi`x0>lt&s-k-U0L>=ErzOy#j zwr6v@)0vpdQ0%%-WWB_Pe?y>f;n_$gi~H#+Pjm2UIZFFus>~M3;Ua2uB+9Mq6@Fpjlh+7MMvC`ZAcNMit0}xJ{( zzdmw`R@c*W`rWqW&_&ZY4t34XU)?p~oWB-VW?$N~_4$W4e!THYY-^?^l)j-a<#J8; zyOjX;q$q_;Ct4u3x0w?<&2kLI#-xTgi=EK1&R8wrcl$UMdu&Gzw*h%Rdlf?@yqT-% zBu(k`h%e~aBq#FeAOuM!Yd|K+#OcJRH;Uwp$_h;G>tGis9h!S7Y4<+}#r!;OOg4Lg zd-N4!eDA$<+ve}IzTNrxyW|HpQ8r(ppApLXD40Y*V89c&$LN_x{!8HywJwC34Co4O`rK z(Sij(!Sr92?owi<8wB`VSmB+2EjYQ#H`S|ItoowbLH>{I%*cuSoYg;V*sL!7Q|7t& zc8l&5b=Cm&)cfde_+RR+E$s?VoeTFrAD&v`Zoa->fjGf-;qT3ETFLR;!Lb6`j{+yNB=P5+ z-@c-LE9Hb1-tbgiLRvr8Y|xsb`!W>VD#%TYEj_{qS&9;Oqz)1ZZK%>pvd;U{BW#qI z?HimNGFL`+&7{5JMR7%Tz{no>1j8q>8HrJ=)-gI8A$dT`(h$B!y>D`Tw9NakFYn`k zOnse|?5L66Kwv*EkxB7}l0fwt#Az$fk!#rbrF~F*3HonJ4-3OsaYS7*qbY##a+<4$ zh%*B3EQGSu&$z4yi)5wWbk6pr^MtQQ0lwQUBO`PRyhTWF@!n#Ch4vNKlW-rJlr{u5 z``^-@k-jJ=2Ub3K)yGs09QOzV<%^WOKP45-#d5C(EGmEqw4^L!<=efz`jWwZo-x^; z!xo@Ifk3!|1KvkWWN%Tgk1oG?DswY6nK*H95M5Hzt-i?so%|9D$@*Nz2tWRp+;U%^ zV*n}5u`CjEO`-X-jN{}Em}HWQ&| zx?h%+KIZdENLC;T^kC{I=}Zi7$0g%j-qiCdpky}W#|j9zo{fQynAdJ)t3f7TMr+4q ztHv6u)_paSoz;6=y)X;+w8e@D%Ns&r53B6xiYk>O#E$90 z;RglP7@rqO*Lk=RGY8-CXt-x3X#6i1ke*7P!|j!t`|b#P^NZHw%6&kXTl| zfu;HR^O1i+VsZnN=BY;Z&5t%7e5zGZRCFR~XIaUJDZ1T&LDbyF0!DS;VT3RO=BLHV z_oux9W@t;ghEem-VQukIm}ify_vYk{QdrPwgz00k;fuS2wKt@?@*=;^Jv55 z7eVj`z&u(hJ0gfdt4nOClb*^U`1*??9L@?VP5z;Qf#BdlTOQr&>bvjhsoHIVcON>v zaj)L03>8JOj734eN2{SXK#?!Ymp^FEBQj0uNA*?8B-))vc63K>W6j+=e5K57^zm&Y z(Jhz)9P$)$9LfQe`^-;7Ysxo03xd@?Lv8g{F5uhaq&4QUj<`{d$j`6NEZ!42*<62q zK6KJxNqyDu!Kv70b(rx7W)uv)J#lFy##kTzUH`b7%F(~7EqZu`M}47djo~qjs7~Hk zTU&}n#q;N$mq}aEvghy5is17)EnPcdkD280@_2vSvzmbc0dEb(dgFx*GYb>KZsFNb z>9?J#nGpBOY`>jmp15}^;TbtVF+0R#q;9!p^q}z|G;l?-f*XcqlxYN9*Ov+RUHhvDnCP?X+j~i#h$Px8Ci!eEG*cZExZ>I`fr|tfbOmIs5%Y#av{Z6LOxLm z5E!xO=gio@uvYNPfDVwtj21_9`dJhxFuhamX$bT#?u7Z%)DZbgqvb8>ceFlPm1<^M zF7DREsC>C)oZl+X4FPal{Tq;x`$if4amH*QW)f*T6sU0oxCsOdfkQ%L@8QqvW%bCc zD&zl-!~0v*i8r7mOf0+3&O0`% zs(n9XzJ6?&=wm(v)P4^z5nlf*AZ=C3T-UbmowHh44FYnep^b>Ws@KK_bs$D?wD9^s zf#4;Tfhd!EmB9WOZk3>|muzEWW97!t8k}=ew4$P7F+}>6(JXRZoCW^i8hA87q5{oE zydCv!P^?!243t@v`oP0{Hm!^EcW!-R<1{l{^=;+{lmRm{3>Cwm<-|- zk0G<^2d19H!Dkb2tagUn;qb>Rz_;PjygOU;I(+Sw>fyBN2yM}#!U#-x1FJ@(RrxLZ z?2|2J{&@?Upsu2?IhFm=#8eZJM|&X9_8n0~yx^Ao5%L+XW;^6Dio-Yfnq^=iqlGu* zb*u4=}ywj;(r`345c)<-Z7-Cb&|t~DL5m5ASrS02!3*SH0%p#=$$OlXP> zWnu9kc+XGmSLy!C4MP;dM2b)@(T9r0!kOHNTbsiJo(i+#CdZk0tD{BmPHQm{|3dvo zvz3(&KxiTwEF`qviVC^)?&T2RP(#R{WO~X`G$-0Z51lv`=kX=5gcowS*j(Gw0{OBa z0{N`rRkeLw&gH}$n@iXy8+$uD&yR*|k}G>nuA_ynWMdQ2#jKd`$70b;a1Q-w_N4EK zsE;Gs2RR=lpzKV@bU1MkDf(1IRwq(Ek<0`)Cg?^Y32Guw;Yci64Qfgd%;Bbx?<_R>D~V{^vLt;sUa6mDrB*jNY} zlG|scr^kAlI_J9iKRN8wPP|Scy`iazKKAOGdAIR({se6w#O^}~3W3+j6VnTVN}L6Z z_*D=;O*KcLD3$}&gb5)%{>D{wFJM5c@Fu4APp{s!^~C<=o|}uGZB?2(4PoNvzgXi@ z?@>d`TwHV$oeh%VPZWmXlkx%KASBxvXFCLJZvM7c3#!v-KWmox{!*+6UZf0?787=Y zi0Mj}IgSzsuczUq+8aHl*mr?vpvV~TQn)4~L8``MR9iu0`WNq6h)7reF$mg@SE8Cf} zxU~Pgpz!9vB47NtHyQ{;0oI;tGU|wc zaEl=~Mx!@P{-sc`IjLmOq}x%7mpxpd^kV8I&*)@D$y0>R2UR9k#u6)I5uZN+@>9n~ z4ganR?~MSZ@~(;Sp#WSa76RC?miQ%P!9?d>(%f_0T{ldwfvOO30D z%dO_{wDUZ|LnuEoxT`> zT}ZOH86^l#GNxGRJGG|tQ5@nFT&OHO3CFW8KZ}HzUi=4ao#QceU>XL?(WE6D_x z7QFcOys7mi=v)>)3Q2(C;mTNuMv%8RQ?z8(VI}khE{S-OF%(Wsl2o`$UCY&DCl(-ItlTK?t4=(*aQzaLNf0vi`D|n?6$%j~ zFhN$saUQAWCawiN$kaRfJiq~=-7(rZ_Ctc9@%Ky+ik+U=@Ss{=BPBu<@Ey zN8n1y?tYGU;vms|FvzY%BwUTL~p4&*dSvYPZ5Q{ z0MUk@%aGO4TKm;OcALKs5oz6*^SDl+MX%V7YAru%O+kd`_naQ|sv1@!Q1X&UCSt=f zqe6xp+Rny^GSJsN3xVW*5dB*WI-YBEy8G7JertUsMz6p6!rkOJnVz>XjUru5j4GK~ zV*Aa~yY8k9y8R6z5GVyfxSd%@nJ-`5yjLYASzcbjT0q?cx6L**TO-^?2zxVCn5T%@ zw0i6zge}@VI?y!@Ly1uj9J}rL5i6ASEW|Xi7}F|}7PESvhy*k%QyREjT?b8oJ|~q9 z*iBI$M`}7DUWP;470>l0cKt%-F_?;DsW{+$iK2*76kOOUZAAAMqwWlz55fj9X+`9c zR?C+|u8ZV#zlB2N7r`!PiG{JDde;OcA6^{qsx-KIoP%_5dnVY7go>P=wst8h!U|zy zYutJzB;v#bNJ}iPWrmzg5X93QhpahVj*E9IP1a+eTB!<`bB;0sc_VFp^|Jh}6u!Iu2=?}p1SrSG!K_D4O<5sVlC zl9_)@nxN*cm|bl+ofUr6xYbZ)b>aHgyu7@Q#BomW z_nxqsAEAm}h_WtABfWq#11MPcuzQ-z4zR%aN%d4I2dF%FL3#lW-w%y4PoPPPm7vw(sB)O`gJ_q5DIxY28#%5{6wi7K^Q6Pr{c{~OIYD+Z%A z*D3N4iMgRw&x&e51U0%1ZC)HIRWu>?38r4ob}hpejKW7Q^jwP;p(biMt$ z-oV(a0ky~i64|2}=b5bet3GsYW+vYwGkch5Tu8E#pn>HLL<;rA+?LU7ddXiO#hw|j z9dya!!5^O{nM8fKb1X04vp#-(y$Jy3yLZAGqzl=ez)SsM)&NZJ^${l_K`p1+Wi7R(jlQ(|4EJ$=LZ4tav2RuN1NAs#8hfSg8PJR2yz-h(Va$g^ z1>P}1@m-dg&bTCRDtN4oi5~(twda}CphCN^a%DclVkV{>PG16`JeUUJdPs|cOKCz5 z*h&PUQ4{#IZ1QcPHU`VVy6drmR_BgqVcaB*tR!tLq znIP3F(wdGmfE5t%MEF|*6X6(^4Rzu}%-6QaGMb5=OSUgRCCR~k1jLV&8BtrG6^?G4 zv4`*^HxrNk-m*XZT~gl>D1w^(uQmNw zy>Eo|knIrNeKad@1h0$H&N7`F`(Bf0Tu??$c5fWkw3l`vaSG19uaX9`HH``~ui0SG zozn*s00p72h;IG<#MrngWVK7gBS9~@lyO2>UhRFcJ_P}J0nZfboSd9|K+ZG}&ce8T z^OIVRc`Ox&q01T)<2B*5SBiu;sbXtOuRNO`)aQ6Nd02I&!=1=hfObP!$K|BDX8zL{ zVlUH8-#U*?7sjP=8xCN)MDb?VM@r>_({OInA>Wi#*`g<$5Ft5*LqqGDLU2f)VbZ;p zVE9ArUvw)Jfh2V=CF+6@i|mNJTSC7xj^bT@N9y@PlTM(vlOt)uJ*^~N%kH_DM>UJO z>p3u?+b7g39oHEo^EO>53m+>y-RbT^`(e%J@|(7@@{MZu8XF5<-FKfB!~dq(1F?8+aByU?+;{$27;Q% z4gN$>Vx~Q4v@0{eS@vUgw*6jJQ~1_%ObxvT)H1)u@BjP96%^?GXmx4S#peaQMg6p( z-qT0&Dk>7)Vke)Ml5uwW@A_r5;LfgphzFZ9qX3DCW2{;(>M+Y$iO;uKQcJ|ro2y~Qo#*Wjwe2TbhJwF5ic~8}m z)4Ox;3f4iNGpWYoD%8}NrIiN)s#`>zvzIUD`jOvBR+LLhNLDFF9PS5a7FG=#4b;2} zIfjfAh%ifqwAPjDm|gda_LYFZjzO6sAwUEqXaH-Khd4A|n1MiQLm8WSI*H6gL%pw+ zr6O@2rb=`9cL1@$Sb8{#1tJYd&HHYl@L<9x|uZG>9n~rJ@+5Pl+ zrLiM0nx4-rI-IJtyP|aK#ITkKb!A0@fb2Gr*nZF$_lMoBlpR_8kwcxvyC@#{9mm}? z?x!A9^=Ze*d9I;~CP;{6=Qzd=>_(dNP8Fc7jthYCe1!=nsK|CCe3QB} z0gp;Y!ZiN2utcJV-TxH2C2p~g)%}lMI6WZQjl z`~rMUVLMav+aeH2&YUZs$PcA*%(ard&NuY-e+#uA+IaKS5fS%RWX78zYCnB9sa^1jm-*O>uki)E#B`90bUjrD+sgHPtDiMI?0RA^7Z~TSLz~| zo6ef_)s9n}L?dxVB8%MbkPvTo2D3OQ=$S(Ze zcWk}NH|jmhWZwAB{OWWE`--Zvy!=mhS@=}VGFrGN;3j5ySLJyigso(-i^Vg$ozc7} zRLozL(iiq9qi|_=YX8raiCzLk`-O;eT}_9~{*3*>{MI8zU?uT*QMR$|s1qcVmih>I;0=@1*ep_j>tC1Ql-^*e!fK1OwS zVkKLN_TOrd-_~Jvu~>P9Bq=>lXmmaE#hN+)PHo=NK<7B1md}jw$y5@^7^AM>fsm^8zB~o)T z$_){xj@di2p4{AaV5vRh_}FsaQV;AQ}$TeCczidTkB-kXhlb_)616bf%xr~UU| zmj=dznHh4dHP!@+7KUoX?mh}yT^sD{>)Y4}Q?PFc*{KuhC>i{HMRjKZFduv$J!-12 zFCn7{+wjtLik0XfTDKtImx^;scouw9zpGbuFHAWDNqD=&j^|QR@ye59`k=8kL3weG zIf@@L5BGz>-E1LpU$lrHwx|dVk;icPMG+ML_A7o2b=XroNsc#RBP8W^KtxE;#?s)u z4{2TEcCQcrCUlgn`+l295m0d~fFNXFDe9%jjX(NUHPaFu%3Wc9$%Q@fOu$ya(8h>@ zTVsXxB@e?)XTpp7Vj76!3{ac>-0oAJ>O>SRC?#viAgLsc4IkAeYAGfH0%YK$|t z%5Z!^vAle})iQswfYvlf^rEnV!nXMKq|RKY>tiPLf>R1X{#7Wa%`xn!dO zEZ$1@J(R`j7Pjs1i7e(RQy&ub*^#DhrJ5s8O~u z*aq(tSe=MFwFRehytNS?HKU*ggN>CtFW-Uo1v?{1HY>s$h$ zFgGq$@Lb>uT_yODAj>nP{yG;v?1sHc=;p7OiH2x6Yf=#Rn)vv`kE1n)RR*pF1^-&` z`u{m>PezZ@6bUc3eh-$U^!W72kSCUaK*7{ytbON+?`GLY{-cSQTVPddg&9x^;B2k8 zD`?&A{k*T8XCHjhPX<8B+pc=B^Y75+r>KqVxJ+iq({lTYMIpWXI|JFnNR}v8Y%FIh zY?7$xb_^Tk3vKgM*_+uc%WL1~RllEo9A={5xB-9r5WxpkzWJvRL$!8sgmwi(n1ud4 zHHl_@C!7~Z51;GHlat329Adxwe3DmD?AO-f3`?8!R>{cMV>7Nciuh=wPIw_>SYM-b zLurc&AinBnD4B1?i8PqH{cfv`zJ6)I&V-({O1!aCFPFiH;7P2rwyQmK=MZ zslUtUiZs^CozmM&JALpD)pr)eX}$t z(Uc@O8OMaTDSpq;kfT98zO%JQ?Qy3l8FtE_>6W#SNVFygmh_^d>7@F6HpubilPGf-zw2jy~+*942?GQMHI^kN`5Oladvo6{EOI7*1wgzFe zd=V7G-QE@W*NAto-c{yFjH~>q`g3f2{Dz9kNcQr5=My}Sx8UQ%$f=Xukqo+{<_MmE z#(wUIJfDbGdjXl?&_sfsrrNf5?cFkGjLx}8#wR0VHG#*k`eugwui=+==IkdS7OxBy zMt43QEjAzg9xVa_lTc69kU1SyHE5tlGp@97;NmyLF3{u=^Zy;U3c!o&PX1;<_X9gg07i@%f4UF6cTv$wT!d}2Ig&3x34 zTEDpXb+VZoagQJ*a3{I zEi4X=tAvK^ZLTgW1s0gE?=Yj-kZ})x$>^;stNv6iUE~GK$MQtaF{6|$CvDO3hrDbU ztjMnCNKHI>+%n}JZs-ir2YcU!1qz945Ls8A)Jx*t3k~HO5bWU;7C}{Y)_z^AS?Tm0laTCj9VFFPl#i2L(z~E z7MWK3^`zUfzZEGZp9xyL=6rWv(db>@y+D^Dw-LSTR4u3K=T2Cn_kceobM>xMY1yJ;ua5^? z?vIcd$fiWKM?A+$-BTnfHedYab&)7=WBw;W(&E8J!igo`LmM6g=FU6dwqicX7YQl}eSApY|AMiG_00+rJBF!WQ-%$#wv1#7!B_W%L@|vM2#R(9W1E ze0-}dk}-ZGfaXK7DA`z8wCL!F5jdd5cq#`ukVAI=jjHaXjE`p|z)o+i2t1@&FqDJ; zEmTA_;;wDE)Z@|=E<~}=Kfzmlnsf(#gx1@Y0r?#K-JPU!#x-U$PyA_$S7%@3vkHUx z(EyKqD+C^0V5@o;CpL@Dxl@(>4)bTWggYHx017<>sl{+uOVn+mw#!TI$$A~}zf3V| z=vh5|k;SKHBE1+Z+0h4M6U#NOL~r716QemiM6f__U~Q*!VX`k<{2GLi4q==os;eP>cSGrgY~mo`lEjCYeF6k2R^=tGQ_2Z;25fi>=#%Vy`eBcK+$kV=07nLN$PtqyHI=I~h;Oy*xAG*#RpaK0m%=nHi=>$;yo zbll*ELNtp!2Ck=11dfL(Id|R--0W*UT>Q zejXa=o%xRD@UAA1061-Z;2uTv6hqfFipo0=I!?GTBB*Ja( z*083mPY8lUB_y z49I{CMyykTU*;Tek$0)Vk|Nn|{5Lc@HtcRa^m$LlFrROvFk^WsKMGImu4LmsN#$te zFhlbsYWy|Boq&LXeO+BsmShEnqIJEJA8CLhfEHky{>axp$O~`U^#tickvMjhZLj*W zD&^iTW(Pr*VHrahKV%|GwO&33?oDlA2Wljhps06m#LsoM5AUp}%-KKMxO`UpT7Uc6 zu0upx(G+!gG=4F7pc=*jL4sYjq>Gs;%p3Hx|NJlax09#3AC6c`jM$$94*22Giy$YM zEhjL3?dqYmz+t3s7tBuLx9X9ks^pqe#L?}mV`N)FPU7u)4}>$Sw)3vwECh0w;9ACt zLU0Hu6W~sK*xJ=N5Z2a)?Z8hceBrTZ&6r@r%V!(BDz^pf9%jLB2zGwB_JHzfRJAPw zAHYR`sYPKZKZifd8*)kzg8uz(o5&_fJ@~g+ryUD{C9K+qA1nzRu5!bwDtU{Z!CG)7 zQ@*`8c4a6NQ!E%`l2#m0pD;PzywMlqnuJ01zs;g<7P3e$b7}wJxth>NJ8d-{u}z^LqVUgT zpPQUVzRhBeMMhCSS(aq^V|1_9n63!lKZb(fxE>?97C{6_L-XM`J*Llavu)D%?YoK9 zIPCl62Ue zLCr_|gbvpn%+t`}v&7;DLK_K!k_Hf!R(yPL7D$hy_Lqsf&|r_f6_U> zvy=U+mS;ahbx45xQThbxjH4xrj}V~W@h9vFfd?2 z8!3F4Z-UFzF1k4sK$P|zbNbY8#b7XWYSl&qSXfx#1d*Z|3N$fAW|i)OJBbp4N>Mo? zosA~-4{LTTE_J8YbbRZeW|$YB?F-1PCWX}x z>V*wWTXw*ImBB3dMV_6B88U;00OIJ-%aQg+tsY_jbY zaumD{4$Gya|Hprl>Apu-r62*IIUw|4ghS4(IS&+$eF0~SYy;Q8OXy6_w*}OoD9Equ zo?`HQzk@l}ZL_!FxsT>Y%g?!TGLJm`h=fpUub=OC#~cdpb=%Qeq?Qp|z3*75}ibBUavv$5lXP0wAq zQZ+VKz6gBa>2F2gbx9eP9)gB_h&GX-k*|(#2+y_8L2m1%p4+LR!}ZD6ak!;#0ic*7 zR+g}Iu3+ZRS~7Pksw$~STLz^M{Z3_t<{O0guT(-_H&7Y^;5tuZtkoH`<;c?&uNrjC;-WQ>E|dP zs$&#bkSf0ga|c@}Rb2!PP0b7VtTOGqzWa9)v|o9g<`CDpd|AG`%A&%~wCjm(s_Zk} zzY%*ZN1%ncy)@8EwSR3KS6(4Ok2un6v=d?-d-#&H+bOfIPHzruu(83j?Ufs9RyKb; z>Qy}oBHI{V0Z7f0SO=0ZwWcS)#U;c$7*#t#yeS$FdZ4@>5GdBG?40wr82Ak{Y^=Io z8CLy4owv_U{Zsfb-P%Q|B_cwT(iIW+GQERXATe~WKmgI9&*&e zuKIIy{4v_nEw3c7>fLl56zk{hy|MoK=xwp~_@i|{1$&Z~@yzjQo110iXb6UK>4LJ# z#9Mfzi3Dg(AoBA`!g_BL+M$<-W#l9o*fCwGoRyZsb_lSHpGQoqcO^dB9~C&5xdM4A zaI~3tIFWexchx$vqP*f*B*{m2{td~SqJbFPL6|OrJsHaecI@_lX9d)RHm?>OQ^S~F z>PO!G_BiH+32%iqF^O1XMTAr2&--(|e2n0T63rte3+aLROM^mOnrRfsv~bFPoz!XG zn0$S(@cPl_@Riq(b~|^57r0*^0q0bRTfDdnQQmF0Nt!a_{3s-3mzHv6L~-$AB=t!o zPc}7xyW3yRFF3>Vj<`AoN&vpLh$84#|B)k(MrVYhC$hR#K%f9oU*KxE&n| z9Idpmt5{0>E|~=%tY_V$frsjRL`pLLGAMeSA31Ygk;;eN%yr8suUN&J`vUT+VOp1z4D9w^$qpTr+B2+>jM(J9;np zJml*d7N)LXU2XxLbe#WRy4>Hkh>>X1l|)ZmVY1C4;u(i zuLg0o&8Y1BOMzpPos(RbG#p5&TJI8^Nsb0l>=a<6fuSayY!XUoW;n636mb;P8oyWG z7AsPgN}?YxDl^`72pqq!AqvJs4kF=C$1lc%UQT!MKa^&4Gy0K^^(L8GT0l9T&2EVUEA<3qN~LQ*^_Ct_>VJz6Eo_yQj^%W+FA6(v5JW;G}r* zjTXidwb+}Lg`RA1yWsNe!H1B=9yyFKBBdv!N3>&J zJ2eIceh9SV(ctzU{Y_bnNSh86q zUP$;d1d)Or#=WXF#?ho_M;<40(cLXd^j?jLVU^|hChx9ltd zIv1DLF3k;_oS0YhlC}T#5*XDte&H%eALz&7B6%$uY+f@{sMzRJRu3+d)5OH8c;@;o zr^N+-9_J3dLOqVfd`mf%ldpFMbC2|Nf~Or!zMu<)WK9s4s5oJ0k+}9KXz;yL*_o-5 zY})@b>iPN<)jWQ&-6<*G=|eiV*5Us|uP!bwwnN?&_RTHOX8gBYV|Vp33MTuLThji~ z`o9Ihk4q389v-`KBZ3v)(9rbs1();2NHwMQl9C+&9W0f7Wf+a-x0se}+73IK_^jBikf?Hv=zvS8u6z}88ufE*OjWgcyZNy9 zXb&izs#+QkW;#P|?6)87SwtKK9#z+?UQCdJsa2mig%Z5duE6bo6{?}Y_V+i-lM8QA zaavb{JQHSdH5Yf=18yJ;5f{&CQNWb2&7Hx3(MNkd1IpLX6nLH-Jxs$bRd`{xeXx$s zDZ#95a@7Eh`Vu{X_c||34_;h)@Tnnm@A<_3+Abj5Mfa||EAva9k8k%04i7Io@ySMF zw8mP(95z|A+%fH)oNqX$IhaMR;Y}DRPc$`zeEv?h9W8x%mGWO8ou|b1zmL`^f^V8s zf1vHq2EvhAyQQMyxEL~>x5CF`;7=VLh(I&1P{gWjJ8(y<1=fP}GsKsE@?S(7CPOr?%u-h*01)EW zRy5yT!TyP8a?@}PF4J2Raf_UVTzlvpG)6Dc|?;mTfpXohb0+qda-6_p%=BG=^W z{wXl;+CceoZArT(ku^cy@O)DG3wWzjBNQ$%bW>Q<__=(2-$9^a`n7HcwrKy_8!y|AyKYrI2Y~d2lZvshn)yla67XRV#eN2=v;q0EK4*2 zuSLS2I*>LUE%c`QQu7QiE5hH#oc0w8bQ7bL@L zMtBiodWxFX-R{11AO? z3S~UI!7BB9{H}7q;bSN)3ZfUO9;wcjD6LI`N^c5n2Bln%OV-U46qT5w3WrvdFPjhA zMl24mPsu!K@Z{pP4QD9K1vicNg7DIwj{qwl-aSf|CT)$*6z^iRsYEA%mIob^Sv zn3T?$s#~hzAz>#`!Xzi`+`86q_2YPLk%f&AP}D6$?a%49^uL%1qqJqPoA$ee|~XTP^8sT#K9G}^=JZNVRUKir>e^$p7X zxW($4ei@hc?Ep^Z^g>r#+TI?E?UfkNX`Ji>iI&5bN46IJxEpKpdE62<@}U8Hja#ag z_T%5J6kI@Uh_AZE_-^U5>Hj=N(V2S5;>sNI6htnWJlGzVb5858?=e`}I!ysDt}SoG z2~sh#?J%Y}Q3_LouIj-)JgQPi9hNpI_;rE_LU<rbojhC0aJBGCOd4pM-Fir9yOcl zJi$l#cfek8IFtJNaJBi6+PvEqaq!DmGHic!%&v*M}q>kjUoPFilO^mrUDURh5?)3Xv4*2{2}veeg8?^ ztPWpk5~4I>gXXgR;gO)DVT6U0ZoyDpJpcHyT!nJE&1|ST?hX)m0^((2rNOZ|OcV?S zQE;?13-qu5&+WXHKQ3aeuLIb--E)RB&El2n>#6A<>H9p+%)aG~ax{?wIOT=I;zcih zEG+BRlx2;Nk7An1GhL`6D+OqF(9frY^w5-|jw}3X6O(`bgrv=4HLWgyf&me3K9nFU z+r!BbZ&U*bnGjbOdHz<$aIyGX6&v=xvZb}Xt@!V@$-gr}Tqk3L(?C37Cu{{Zku?{b zTjrQ`t8k#D$Na4M|7QWb;9AD=4Q=`ix+x$2e@m)2U+>(hIW-}I?-{kv3a@+TCWG}w z6Q(WohZi@Bi=`-~&WOi%VFoA`VXNu^N~^EN27H2-pu5dJrvcNO_0g4q=TwiW;h z^pZ98z92k{i-Dv&*H_jk8B|;dB5{wBxV19hnZMIUoia`O7f0{xbWPfd+~7!j+8&8K ziK1CuaW(lDLP$QyJCNz+d!N0OEObU{%EztC~98sysbn7`8eD!kO+xb-I1r?9v+xl8ua)xI? zZx~DxmbFu3G^i#Z$@O+NF&TqwV}{WEHBQf&LKo?%Z!I9n~q=#^Bq=JLgH z0TK?1l zky32dF}en$CBgb*^Ijw4pzGtK4d2%Xzdkl^{2x!}9Z&WDzyD*zX>mv#5{`LJ5hv@A zJu{24j_j;th0M$&;-ENW98^}}5XZ;1Xie!uG0U;Wd$9na_U zaXqf5+P{d z#3fp!6qihEB=Eq(SaYjTraPDX_>~uD%j8$KF=#REp zImvqk|6-wy(Se2etX*QwtvW}oL5#-I#``NEo#}xI$M}eSO!*^x|4xNt6>K%CvTDu+oO*{H{HU{+*-1vkN@B@!meUl>NoK~YY6r7 z#}!uEwAMRGEKKJe+^$F7l@W_S*OAUTQ@u@=HF3Zt1l~5c(8N9KS*pAhH_<;482rLV zvVU-Kv1)QzyqL>Kcn16+zgi7E@pUy=MWPL?3NlUm?<{6GQ5~1kMNl7I{W%W_pw6HY zXTAV8XPL!!Jq@#vV2BX;MZnCAGO>$A8z0>Y-L3U(c>aknIETFHK$PWEpuyFoIy z5R2@%P74_+cg=h$J_m}5f#xIv1e6|geBt|V)kLB?qA$)~AwyJ5OclIb-v%`?(1ce{ z=nxWW4Mv44yjq`IjUpVIE(VV%^hfM~`64CqE~)*LN!Tu1&PS5uWwQ-t;cN1)r8>#x z9Rmc*+QfVJ__Subf2*Ui`hi|bTNFKyv3^61Fg@MhtQsvgGCL8d$1KXfO_mck|BKyj z?ecz_O#?xfa26Opr$E=UcVrUzofAxNvz28_0&yn4@^2;e&nZ5n_F^rsHN0M>zFVJM z7v?+1MXa}pNmSd9VDSQgK%Y1Z?R_7 zqoRwaA!ujmj_29RSRK*kWW+3W<#aXoI19xJ=IcSten*Wi8M;YBFBxiypfmg@1A`r2 zsOy}g`90p`fTiKl@GhU}7|1XC(|w1x)l2OQ475Mi_p*1uw4iKC919jw zNqT~C9CiideY5gVyr4xI`_1KLQhGvPU(KpaZOwlK86PScrvKsYcj~rbkDwla-V~x2 z!6bG$0L6ldtmt8bZ=!eqAl3LH9j)Z1N`Y}e?Gq&vS(q9Lf#$(z!L;ObBo|Nu7Tr3z z+yF8k-Z|L5V`9P@S#1ot;vo9|I}JUHQiIRwtD+ovc`ggLmdylD`%5-~JE^ERFRzT@ z9jfvf&iM9N^YxAC69(nZf6+p(8K-;|tZ{QaTesgo)RD{9FEyo4iS>!Rn^~Zlb_Gkb z0ke^n%WmA8XsGp=7@Ji7xEv&7r2#w!V?b)yR0;^hAyGcTn2`d&ehaED{5g?eiUiTl zva(n>q@cQ!p8~`A)P{uDIZvQuYCxN}oZt@NlBHICZv!#LkfT-qu>IM$)`2_!dvE%$ zt*u_?nHU)_(EkbGR1W4Trk)b!Kd)+hOu3C!nH2<5(>(q2%h#>}J&%AA)vvhMq}tNO zIs0gAVmx6GWyt?aXZ^Yssv|L`SFcHRojl$&mwI)*Z8yVbHf6Ek=vFB8PS_)}c=3?w z?Lahyd;F|b;A|!LWX~@paX}j(3u+4RAv0g)qodpLozPnm6gYtL1#&3e_ zWVv=uLR&<8`9v5%wvl)5`=~D98G+nM`%{VIG+4OtbCcl?9eu?}l6s^Cw~(t+2KjWC zvHuJxl^D{#Wpj(eWW4HY>Q%-UEjADg5tTCX1XNP2peV=0+aBI{q3fy^yo$A}-Kzy0KAT1e*HWN~V zC(NSaMCozHf2y%lg{~+^@XJR+h&Z)a7hr7ht1Rw03u~3{kN0|X?#RY!xNXu7>qlm0 zh!RXZ5A(C)Xo{f7gWl4BtVS(7&kIjefBKDAB}mqIEX@@Zm}>xUx@G7rK7Kak3X7&r za?pC-T|R7LVj@IUCk>uQsI^FYUTMeX)0S?Fm1I=tlwy7JCR38~Q%p6Mb!JNOy()Lt z&?5G>E_77+w`Zo4qhDZHn9UQh>I<0c`#YLoL_yUcc)I(k8u(?aIQw>uTM==wi7j_; zA~^DX4wW3W0UAVW0?#GR_vAnTP4VuQ9@$(_TwGMunf|7r$mH}=y6oGsQ9 zjno2rdwKC;!XfvyqHxl$W4wfxA6k4)zmJecfFIG`-d?w5 zH`mOk?(XbOGb?pKHTs%px#)Srmg55PBG>0Zx677mQWJhYk;&@OvIi5YEi(H!;_Hj~ z!tvWgOXqnar&{cJ20pyL2+oIq1GqK7u{(sj{gS0;Xk{g1^>f(!bj)A$x2&Ijzm~6Z zh+9jc{VUb!`<#YQiH$xGT9RDo{Kb10$V>nT@3W6gf8}eq%m}oAFo02`w}LG5g|n!E z!zE;|JVG&&b6f7GRpXo#vaL`4&c^W6VF z;UM;1y+eOgqQU9XIpw)6yz|=c6+U`M^tGGbMa)!o zKfXv)Mh(9#{VD5J^K%NGOg0rZ5{G>roPmhvmA@{a23If)eMU|E4f(M>ohs7eF zlrnip>wda;Ea_fa0d=5SEHvX2w3ZpXfN$DD4;(Y97F@Q zD}Sr^%Pw*T1!#7zqm6I?X!EAi-lK{<_|rn~JfMk`xq(=c_&uADT3!)+UgZ1jk4MYO z-7mdOBUFzBfMCK9yPs8;?Qq^6QE$fRFcJm%W^C@G=w%Fq4AlL$hlC<+O2x__{jS^C zZSb^e^yN`?DQyTnAuTQf9fKMFJtxQR1W&gg5S{zIV35|}BS!k6s=FL>_}g6C$hLe! zrl1buedIRkRm{nBfC2^0{E}{c^(nHp)xsI6rR4_ua*@}opemVuT2u#13C!_x=jeG7 z(OF$36*BWmB!9(Yvi_=wj+HE%kro{D@sr!1>iu||FOfioVRz)7&74}k4!7pm69c3@ zn>t8?%|Ra;ucny7ry)^8PUuSMBM=UrGVv*JT`%)|O450@Jm0sv>I1m^y({3=0~TrD zorc=p^+OFRMMI?DI$qUeAqh(8B@5Dke66%0^k8!;24chwbci9D_VPC7ST$K->8$*y z81R29T~(;k#uQzW^5*{hyy<^-mzora9Vx>n=YD92e9qfG+2(_rngi+pVDfa%x#i#V zuOy}WI-N~E}X#}(U}3_ zVQoKb3eDlbZU`Eln^oHYgrBfo=dj&84r^dZYiVVpSLxdfKZ>Fe)&NgORGXHUmdQ^Y zMZsWFy^^Hp&9XJF_3YBp~2En`WK)w=&0A)Vc(0dHGt)S#XQ8yuv%E zRpaMv(zWvLnt@778_PSvn+jJ$d=-j&HMuq4#EQ%g`8f9jL9l{3I};O4BW~V=K|zDO z{e>wPH=o&?{Ypnb;QXxiY&`62P_Nvo{@)L3&OyjcOSdZjGWatM3DP&Zeol3W3dkmO zac*^W6*%F~#X!`;OTE3hFR}pL^PXj8rT4mss^Vc&5f?ohH+dXi2nS?t>g_3Rg`G}@ zZ5ExKmYc=+raOQXJ5)Z^z~cZQ5zOF0FbMDO%@)ikA*}T71>vZUe~^wjJdZ7*Yj)c9 z)sKaQ+KHpAb>*|^uHm4lw)JCj*p8mfS*K^%ky-P0*Vz$=^4UR|d+^D`At@-w5ghr% zNUSGFA$#XYvF(#j=vX*tQxZ3nmanFY}fx`f?dJ=py2D9?057OLHaQeN0SZ%+dG#AZqOK(K7N? zKeDTJyK^60V~A26m6^Ds>)J9YUa2obFbYE2sDPS$Fsuki&|B0LXv3RT@0W?Y0TfYk zyN}hKjf%H@+7v&VUwXscH#5IAqO!PpknKU97%9N$R=pwGc}O9P?Br;HUcU~aaI(D8 ztouBHAY@EUYw97c=i;@DI-ptoRH!-ui2Q=ig=c7iUGuWN-^2o=cQqw49`H=Q0UGKp zhGhUvbi(N&gXy_;faOYhJ3qK( zmbp9d^f_-oL&i*4HwHAjEf*K_G;F!xN&e40Th7`TnQeexbY`U=y1>`W6M#9pdvIUp zVNvsV)N(rJ(?9ON$@=fH=h|(DyaV zTH1NlePXfqZ#rgnI+LHe5QJx4bLN10o~5gul#IUIrX42}vP}Qee{m1HYuukiLcR+2 zRt{~terZ4mWz`6!2TYX?=w{Wp0ph&`*ytN?*psAA$i&wloNlGkuYg|cIoHEh0FB^x z{i%-b4KQ$UFUoTY>6p}tHy!tQ9!G__l#Y*&8w~v;+U#=|x&-?Dp{Wh~A_6`5e&t@{ z=|~Aje{M=Kz;z+u>1gs;SqI5=8-vEib-{#pt;y%(ygte!P|Qi1tYd)~5V)ZXM*kqP z$$y%kmm)GD=b-;%qRSf#*`m-)MbMGuv0kxzfz-*MWkT-B$|^_b@ytD&lf^shjT}Xb z@#0MZzRxOa>b!T`1Ftj+K&vaGp@CD72y!s+tt|u{K=xuFHN}2p`n|ZJAO}ZB>X?k$ zgsT95bMUeuSC;{hi;IJJlg8`(x^AR8ckgEO<>f_*X?z{K+zT7X* z&Z)C?4IE@|TZx#NngQY-kYn6mSlF29jE`TOiO)Toxsqg4cXq0Gb`0dT8YY8JkE1VQ zyN1ig$Lc((Go9Pu52(b3vT6zlj6;&)AP{w6@_5e1rrviE5ZcGwIj@3L{(M3iD(_F_ zUF2B1!e3#mwDWh?v+;C|k#|B#L7o<(aPX6uQ#$x%Z~v?1Z*eFU7fpNRZMGDE27$DZ zgWELjU%~Ki_D^$6Z-B@GAb?jew|UL8<%s!oHtZOfu!Ykfg)XS-Pqj_2*&H8*?e&$1 zxw|_a0QH5$A*A#1{AyOy^oEyI4>44+yf-kTNG?*!-e~w+p+`g6EG|bm*ieR0eaj#o zt^;+ZEI{@K(dwXC)Br`spd=NI=Hx0`Us>fULWuAj6cf_l^?WS;#LS$8mAQ6p8Cy~2 zwk?%qSlD``Al~j0EujXqs|%}v+X8>f$x-Q(ASAz`4jpcW_mJ>`0dPPsT$=PZ&=7Hc zoo%A~a-$Ym2!D3z&44L_P7$ol5$WaU*TxmB~5qvl@&tyv^BD(qYB?*z!Vf3zF(kI#_AS$j0|}9MpZJunp{h6-lx9 z%_6~`Tq_l)(K5-r#YG+Sl_ydV1^GBY;zJ65v`4l<-hoJLYNev(Io!FlAVM|%BK0~o zL?Oo(3kjbH)Y8eB%NsxzT>@ICJ+tI}jjD|C+y5!$Izv*4A8K3`HUi(cA+n``A&rfy zrn6eQLq?KNv$)%&05&1$mB@{#x8eek;?@db&*TS9l@2mQgj0rQhf<=VzHZ;4nwgpM z!{&*LhleBTdp6BJ!L@`t>*29mK$>k>Rgiz0B_FdJ*DRT+qM(?aZ={b*duppNc&JMjvu@>Ff}7sK~e){*5}|8iGrzCRK?#D6V1MpFHEmtfwfSa z|5|`=2V4#Xg{d5Bo{T9(g zNnOO0?x$gAE@x94QyX4@NJQ$p!vhenJos)@Dx7V6W%iu-0xW!LYHFA24T*pM{tJ-L zeiXXDweYwDD%M*(xt?n=88o{yyv@&Hl%Mcw=3CHcjTn`UUp!S1bDkw8ap7rmYb>Nk zUT8qkjMtaM=>{*LSW+L|v}9Jn2{wID&i)Qjo3JD;xJVsFpG}qAQ#$y`dpZqx%&K!k zPqHRMR(fWQ7gK-z^0`Az7L_)o`wM(9!WCZtD?EqtUR^J;taAUJ9c?2AzUz%Gj&|z2z(hmvp5FotlWt4B?ubDy;ptkR6g2wNWOTsk zS}h$CkQ4Is@Alp)ubBBEQbSG%vL2Il>HzasufVY=v8(9ja>+@7UGiM|?e>GlM-a96 z&~n#nK$MUYsJ))iga^j>)yB)3obJ9Ib&DgRIXlTH_Qr2S!90)-gV*f59{|;Jwsa=1;FbNI+?Fe1c>j$2Hn+9_ep^qDh3vo4j zUPlC^1Qqc53Z6qji8EW_-$s;?=*QNk(1{z>^)-lu)86&dIY3u)clSU!pYMdg3Q~zL zSy>_CVf&0>{}%F+#{M)3poVoB1!*ww-mRtvMq;G`N@*=~UNSfEN%P0@M}dd_X9r;? z6Gxu8EncsFOst(vL$*b3h=cT6ciK}3l|j`cNczAce)Ya_w`3V)PZoW z^_qJ=j(o&NV~0b#VUc(rw`v~`3Fut}-S_4vOHu|-@pao10#mTpXtDCLDl0STYQN_S z8TqdKCjKGME+GfCVlJ9;i}?M*)W#yo=puRdgqwrk?p~6pi;UU0vQ+2p3 z{AIO1Z@_5S4`=K^kRb&ED6veZiu6g#k6te!zGNc+n}UN-p8~sBJpCDq<5)09d#ElD zER5Xvyj*YH5(5;2pxvTl<38{*vRjS16cqf_!RrdC6FOb4r*q(a2nhfdZ0Wj7W{(^P z0N~|^(lHlTUbyxePzF(PI2;~n=-M)TB~ntCzl|tphr!;v2W}(R_cB{~EY$<6+K_K= zfYvA=d_|5D)EPDHW1q_)Iuj&ya`2;ntkKuY$_PMr8GwmW+WqYSYBvkr+G=Zy@Yy}w zxuzU49g~%n+CX}AU(|QuEnW<0*MBXKzmQrMN*m}Y&dYK_NWJ_m?2#EG(HZKf1 z{(A}-2plyj!9v2;!yz9MevM3Zl`CM7R-(H4_lNwnwYzvjHwN0;1~$8YqijW8EETiF zi;KNMx%fm_;dZfKtVOtN4Oxo7%@lJ_aZ@myFEOv}^F6pngK+QAX22LPK!JSwmNHLF zhSXP71bTT@g$4Zd)4j3E4d%$59k|;AY-;G&M<{f!1z%N{m0in`@{lg9D7dlx01fv(npJV|5YkBk0iRbZBZS&5m&FFZ;5jAX+ z3N*pmy^&d9UZ0o{f?9s!X*m9|*u9xm-lT?jiE5no{gM8J5Oq&5|6A4I`wx1Ea}$i> zxqCTAYJ8dfh1oa^tHY)De;<^TGW)TE@P0M!*Disy-Zz3-v}mm2Sp*^4Mjhw;TbmDv zvZv)?M59k&^Zf``8MY44Pi?K-93XU{>IOEXy+qF@&rKQqu<$zPh$@tHM;|S8n z2bE<@#l^62pbU~_#yTj=o)-35b(#C+)m+1K>z`g<4hJWQIPh$qehygK>{?ryFdSMT z-U|!$bDUjpX{_~^;!2Rvnmk&wv1wda8?82CBb1j@jqqR~_TZOue~sp~t{Q!Wf27YJ z9l~X`-)M114zepK0%F8kILtvt`YMsFyLrOQ}X7tZlWw>vuaLx54**JS5_Z#1_T6D5Yl;XQe~*9IMi%w-skc6xEr6^A4-k|(SQI2E<*JZpRF2J z#DP(v!>c~sNHw8$sPm^PUn=_HMdo7weq)gnxGw)ET0rFfv;YeoKqA4hx;^TMwpFl? zG$O-SN6NkdhAm^(E00X)x)%YC1mwRaloUbQRyRUsSp-%VvNm<};Z=+|8E$ zt>dTa8j1utBBo7vrO7Q*7+CmWD&+ftjU-$Mzl}1)`v8MaV7WUNj31071t{4BfKp8{ zui=U9MaDX*j+~g!u3WmnMwsq(;h({+6hBBxr$XtVL9JsVmpiF=^?BDpd8g zFmeM(QL<#}i+Hof*z1(TD@C&miqMNS9()*GH~W`@oV?KbM3i}SA4_SKn`$(Df`aC|qW{Xh&o3^H-H!DZx*Goa{*CGzTlVrf zrMJpenEin&&{9u;d)S|(rEQlHhhTXV4i?ZDsmbo6=FJ+7OTV7dw0Z?^XI2cDkT0rA zHl`TND*gj$7^#7C`}CF-IJ%!U$Ie!{-NAf{HP%09d}=6s(LG}2@sN}bPytzGY9z|= z^^`QPW%L&_)$QAyK1}+euuKi~mXbd#usN*X+t~k$yZ;h7tq;CM&!IIcr8g=galjG| z3h>O%!-3mIcX^)b+_1RCZt&nDNgS^{xy}r?YgH%b{i^nxRpEASIlXqaaY(px_VsLE z`DClM`Q%r5sC$L^7~pjceqK^MIyBVX)6=uR|HXaTsp7XBF(D#sC-vH&) zjbz*Uw0|`N8L5_8D2!nUMN4d>^RUKbt`c8M*^1a(_(=;3G}@AjcDd0XcrdTCkW#A5 ztwt44@=c-30?gsjjf~yO5;NuFWxz=o z&mr#anLF9^V#6%#pmsfMqx)-;(kTFx=lVroY3zV$-` zmlx-rX}`N$<*tpCCE?|K3YWR4kGRhxOp+fT4rzaXER$g}q*cS8SYSNDspeWFSV;fi z5~KqoI`4?r*nTD>uXF*Qco6cY=wQn$!&V>pX~aWfVJ}#bfR&NgVI|4IzN0Pwc8-jo zhov3sTA^Lu?SUP2;b2uZ-w8H;dI)e5OexV((xHKLR;c9`@-!~YDpOpZ8 zG{nT@m)~W+Z(H_8x4;4lth0+>hFJOXn_L~uepN%>47^0jXWe_7_7cNF%GhRdcuKgc zP`oUh&j1$IMF{MS^q|w`BhS+sWzLPD3my;sbWQ#~Pkd*w$@48Z*_ic%KiC1LF7k%ri~XeQXMT!Oujsjrvguz59WS1{`HTPMM3R!3DuP;&^N%U`%_hgle@dSk_~Eo zRO^X5;NP41yPG|J-!E>){F)eMVAC`2cqqHD2Uc}+a|;8ERWJ6ZwX?2e8CZD&-0{eDo)tO}HwfqvFVvjiWlA*EB15N6 z?2%OLEq0$j4~x3;{%38SSeR1rnrG3k{P&$gagn0sp(hy*KZm@(zk)byk}|9>tR^wc z))7r_TIJVCmVJwF^9tDB6*{NnFKhReqll;p)Yw*Q2bRU3`CQ00;!02*uR*cSCLo1fke zlYsQIiXkKs$#QwsEO?-a*Z9$fb-Dj!=YLrEzYkS-_wT_IlY!M~xo6JNjHJy02T-tZ zoO|{*Y;(aO>BVBNO;4pS&^k^nd$FY>xTP94*W^DLyuTGyS%QDS7WLNpc=M^eqMVZ0 z)=Uo91rYXi43CP6gfK3MIeLmb{@_`-tu>?4zODuvi<%l$Uq`5b)jL1xluq@pUAtz7 z1y|Q4^*B4WE()qmATNQK#s}5>;89%oY2sufsypN*!s4M&xb5w%Ao`#tYm3xaTdX%u zko>1r_=m2hnuHpH^vk~Od{e+_d%*21LuX^%_3K{3Ix~WC$*68(h`Zw|pi{b=U6~rK zH=HqdBUUv&+nHS!Z{8XiKN(oPa}=yC5?^dR`5UFAI6g8qCg-1qZ0GznqOi3g&>HhM z|KegwcpondX*czc95`BeGtN~X~e1x)WKj%k&YHl7Fb8cOJ8Tbamz_LppI4Z4uB&*$ZRFv|H(aYKt>fkI*`VkzDL{hjM+AlF;#;3= z*R zI%8ZzFkzSbRIv9${apeuG+_yQP=SJnnSvvC!EHr{+B4V9zjKhk{5Wa@hC>_$6d`KR zv?uE^hT^$i>mKauE0t}qRLG)+vGOze2QSd=hR4B$rgM0N&XdxOMx+eBc?GRwDUNk~ z>6o(v9aaG>UK)UMmf|Ym7YNcAFQYV|tnswO%kWHCcDL zzIae!z1{8R_PXCQJ_=&5`b2%PP2#EmGB|I_Ks7KA~MzP>#=GO~ob)Vp7^ z42A{fSh|rtJSWGSMwfT;anrx&BfIeGAe6K2r@Id;mp%IS%3_5eE-KtwPdePSKBZfa_ZGxguw%dCmU(9+-Q znr%9XIEYh^S+s|<*Fn~<`n(8Z+c>etg4kS&6Y&)M=C;7}rh{fUW$MMbJfq8$Gm%9;Qa_}c2 z97gKky2&WlrI*GxMm>B3Fe)e>2_f?uR#0xft3?|5OPlSFhkoC{%Fhm_2?+^yVN-;> zSSfc7Z=lE4-16VsiIBZK*~y@z*=5<#6WLIQqZJB;L>h1K2ky;%VC$YG>(TE#_w_CB z;pyHP1)T*RxVbg^_3NLfGSEv93}!&0=VGoU{TqrF;;ME9F3wo@JQD3n-~+XN5~Qz1 z%Nksd48t3dGW_JnUg5Xj#L{Jaevoa<3iEssPN#~v3Iy_QD=At(oa-7c?}t>Y$)|R$0pU3l1_fqdM6f|JZW$j_2{p_4bt1YBA=8(*@MxUYxaOn5So; ztE;1{3wDdFwq70@u;Y1l7_7rijZ*OP|GJk=(YiKUngWcaEZ*xa`~7FVKBIS{Lf6j@ z{KKBje$ts4A2SatpS%W#-rmWMAO3bZI^VL2R!o;>g))RtwMxi|2!@ar_bR@BSdiBcrAtCm67!@q&C8;j(&%c*9ft4w_FRLMJ0}$(~ZH_xjcx?*s zJ8v1B``rzl8KXkwvkhlZoR`cht6p0X;m$_*HQvOn54LJ5v4}i=R=^-|u80=ol1&E! zw=DsS0zisV!H90?WV#TFwm)qhKF~={`T$U%kT2yv`KBq@YM_%rSZO>*p&bSp}SwdzO*2Kt%&6Z@d53* zBR4n`*};Hs1XlDN&1)>?or!SAGm_-AI32k`cR8cMjIyG3n2S#m+#4v+C>D>*LU&7` zp+^eTuF$Vu)4W_iI}5z}G7Iq)e|&SO7Nb?5{nUa~1syO6b07PunhE4W=#5)xkG{yP zyakQ~R#0B@oMtAeh24+0&X7Afs%cLC+4Gy!o#CQ#skxF~e-r=epIfZA{xZPWpTFu9 zd)h%uS8>JdB`1UM^OjYT2k1&g?_Ih}5`BCaEj1=ijo#{?&Gp6g4Iz$BCL>va+nK{W zExZ#Ros^%#0kCR9lReYPw+e8v*Ss zo$cvEhJwal9*UcPh4jDWXld!PQEwvmB5d-Y}*z@OS(}THLR`9)p`g*C38Pe>k0ducJ zUNU|yhHF}IItT}*IcM0{(Zwmx{0gtBh-mn&{5E2IR6FWXo5^?-d@0XCJLwTBZ2IS?2Y^pu zdmh)-I=qkb`pnD=dtl z)BO}gk(HD*`PoO=#+p2{?*twHe4i>H>p32>2Y|sg zlfv>v<4-5nzE(>c#X02_6f7C+fU0CY9t95%t&>TMyeHGV<)XY!>CC&#k*#_3H^tn# z5wI@|IX)yjou&olkzUDFwb#fC5D?SP>ihZ-S|-{U?XvD?0!TS~Mi}wOVmZ5)fx0q5Ef*W^t^u*xOvN$5k~Xki#)w6;Nme)1#@< z>00dBn)YwncD;bCD*F~U@$=_&>emOWyX`BYUHPL={45D|e_SKIOERh~SGC5lAAZm( zN)Juvm?3t&9EhSf^naX&o^7S-eeHG$wVT*(Vs1Qpp{18skeq7DMLYIHYP9M3SgZs; z1dwGa%8CV@6*g#Tb=XM6n6&1T?DexA@skusIpc>UCuVvkuLYu=k`dqNy=kxJf)NfMrw>W^2r*;AQpoT~YzC_|bI zzrqj-r5{TQgi3132^)wj`R}q_Jjwr)onaL_`;tPMed-DL&~KB_bX7MorGH;jm@JgnIPpk^ODFHmH{HJ$9tl@INKwdrhmFVmJ@;+BE@x`n;S(9XeIJrOJGu%OhGrfFA}OA+CeDE3mz+Dm#gl8XSDEDT!e!^ffnb*uBvKWC`b^(nP}$RBSBRi^mC}d z`m!lHI(qXlZFosf4>JH;f0TAk$S;@+qL#;}0tw9NLaE217?-*;=-$0NFxFZgaB^pS z&U9Z_v0su&f`p@Fdx+~vE(1X_tx;XDkfYcD1)Xa03aJK76mii1W|`(b3(PMjO(t!k zaks^v0p%pcs7vbNu~DB}nywtGvSEgrJ{@Fa2pU%5j34f-Y=3)`_uavdPQI5Y+MAic zAn=b&7%ei)j)ai=`l{tu3sUE%1Mb38jqj@wjG*=1s3xzq$mBt^+11X|iHQLL?b52e zX;j?T?9<)Dui7U~FJ?uB*%~j0y~n&%1%=;v_HUsxo}*!Wt)PoH?DHWIQ}^`uTtB=f ztCiB7|4rC&PC~TgS*YFnp+&!j@tf-bT~oFT=R#pU-GW5YT^Jv|UzL1zJ`{$)eEj?P zHnMe2Qx#fr1F7?1`RS^CID{jxtSScpvJZ;Bnsv%U@?7ra7bjj)4&AIk2i>2n=h;&k zudJz=pLlD+NgrxqqWMPs?+3Vq7NF+TH_SpRj^ zjkK`iHq7I`T63o$}1{$Fbmn+fJE>guh5KU{0s)Vwv z_IV?~Xj&9J-e!B&$zc<+Ve2QwMGchWx+n3z<-oG##lMbM9M(Z{eOkPy8~0XLJS9gxGaD(W~YbIL!b|?7Wl2LRuCc~^0wz+@;E~UEYf=Jg0HK!%7Iv-ARm-oPYH;wvbiPIS_KgSGA}8u-gz=IYi)uff6>C}3m1s~ik9SX z3X&XpK;*b(jaCXVw``DwUg{E<+>6O;qs)_*hi$H1U$LnRIj^dXFfx8Z0O(jKtyjOe z9KsRo#)Ynd`wKwv@y->IB%9{r{r8>GLsYUo_`OfoHRjafWYkYB8VrF>&0HDG!7;DM zL$C1hg54!36H|>$4bc0Zw-ZxR;syXbwgJ}ndf3?!Abk3tjQmOwN#s#%RbOHd+kxtkX3r_6%$o+Tbgt%bG;F$vUuR`ZCF`L=#l5yTKr`2S|Gh$(I}!4 z3yI@vOaG~|fTn*W5FP4!W1sy9sviED_yZcwV(|!l@F(}A?%s>Td(B7L&WwzA)O1WC%lf3*5XIFk1pbKq7i#gb1BCWD7JDCE$5aXO+f?a8$M|uTqO>)HTnFJ zxA+fqv>m)awD*HGM(0y$1n z`uO%IS7S9W*62FhQ^8jhd7T-BemUyS{m;e4e3!VZTxDpg71_Rs0yi~zBR;O%rLf!9#Tri?J??+A{GDy^(;cxpO`a??Vm8p|1@+t-k&lD+yTS{x);i zVrb|ov|7vjZ~GM)SQMa4!YNfupkW9dR;MYVLJp!A!ZvmLi8IAn5Ygg=(AW2b6` z;6>ABk>*Xp-;SWFGNKByoh%>Hs-wn~H|qRdLf`X98Q!}G)X6IMZ#(6sQqO68-WBfe zBj4i5YzSRNXBGgkD)UDcPpZ&BHs>;nFNukn0V4123l(aGxji*vbF}!0yE3_5Q(Hsx zY|m^xNraRCAzYKw0ej6saUR(N6y{`P0U_J?7$(I>mJNqX)pG@@^{Uz51Tj}mQTd-)U{;-`c( zv>ZrbQXLeK(=QhTdbXAwv{IqaUyZ}r7G3sb62MGu|GR?U_9&Vyox=~4vgNq|1iVNJ zD)GEfwg)5sZx=x_=O;}zP4+Jm;1`qPaUUipv$7WxVvc(CE{Yg(ukY03AAs$q&Q-?& zDkr%Dxfxl2$kb13PYIR0=pdjrw)u zrZf1DF6mimLH)DEZWI=HlMFwpwr)9<$82=GN`csa(l^Mz700Tka=wC0fkO2^`Xm~y zc#Cg@#P9+2HMHUCP;Zii2KkA;gfqSTMG&x~0Tj~O(_`_RgQBoQGO+kKIjCFv{trjt zQUxt9-~F`O*T)AA+n)V?uo`x(7JWf&+G5_O|KlF^zoVrU&dp(q|Z5^ zxWW$aovqxoIie6oWmA!^GKj&p2luRvO#)Bb>yG@_ee17Nu{c%-dKxbh$Ssu>PppJj zML>}HjRIY~S^0A()!Km2w?sVqw+j60q?fY_{ezqP6+ghjSb?(oRD@o1H$T*qa7FRlJkC*jm44pkp zxM`LXw7uKZ|Kju}u$xKZd?mmOlH^W|h7)d(ugg^h?^FOb~sD22{Oet?jm{sfl8GEeZLZ!-)er z4F+j})xN2AD84*jh>eaY2iBP9VG=N%LAa*0jtKtt#_mMBoS7sC)B#%okCS*2uNuy` zrO3=5i)4y?w@Yv8`NBUI`ErB6{7JUdhz*e^d|>`f_uA^a*)ak7^_3OMOfr{{I($c= zA3d6t`HVDYVR$~F-9-XgHer*Uo#9%GrleQGKfvvAv;dld1f67tQppwy+YQI-B^LADEfE;FyP9NV!^cdfbKms5Z6CtE9z9L8?+u7o>Vgv}i zTvdaCV7x5S{F=^PnK|NtnIo*?Po9wP3Pk?DUVu9?v)@(u^55a3jW7@ylKtIcpr8$= z0lrf3*n$n0T=^a51x;z)#@EoluY_0Q^x}J=c9)DA1_bF}6@PiLEgV?}j}KxiN~M8t zl@LYmp@AQU>^rqgePmOU3S|XwyKQi7%PFv=!WzvZmBzDmiB*4|NY1aXtr+zzJxZ#0 z_M~{0@ico>cJicoZ_LuFgb)bKPH>Rd<_~@?bDd8GT$dPDpC8$Jwn~V_Z!O&{XRyOL z9=z{VcQoO0Q=HTr`Uy7xixnHY5kG%{r_w@h5|Hn~Y8tPp!4$NRM$;TW4n*&EDI`0H zfcXA(Al8ThmXDPKa%2;KCfdLSv)us!ubnMS(&!yRW`46$xm7g~H;LHW!l@qvH5`G( zUH<5*At?`C(p*tJjU4fih0)q^b7&4^XOb``j=%JeTfe4sFHi`wmW2Gmk5>cja2~ZI z%si#3gQC1jk>~G({FTtS3yxrk%ljz$3^evw!3py~_d3W3YD9|Uo5J5C-kNJ`Yl|0eoWi2fcz=o-sQM>IzjAY3o!?IN zGHz3g=$;^{C4Nf`-{Q3!O%1yXuk#OEEqGf_?icqTaSvA!3;SA~HbB!3#eAIDwf1DjuAeReuXR9m0i4eA-}hG1vS9RXTx$O%P16ryJmc$^&p`DwxmrYRBx ztHIdX$Iyov{h`ynHYcQu<&OkHy1j6Zi z_1*+iBIF$Pp^izaE+YE1v?)zEkP$4$qXGxzI!-ozzxp4|eEVk0?lR*Mqt4j=Zf#gP zyNabd-rQQrcXg@yM?7>dPV_Q1`Xs8Zv*0Jl@pIK(1d-U_v)FDyp!cQ7fnlm(wDYo} zsbWVlZ}W~+iST7seY|wU`c+NJqExT_?V;5UyD6hF59zppg`>%!-GlYhDbL)4YtG}T z{tB*y=RdfWL!}b=`?nE7ZY3p{z;wXr0fsfNYZ`^~F+hY9NGLr;G9=O%aWNc8*>2i= zTty_B_$aerz;+J4gs&gX79gmCtMBPqXlYu(0l@@+k0>s|sL(XV{^BA?ij zCCi5vQOjC+M#&xcZPSueL7ml**p&R!U<856;dEX=cTrcz9Vqt=%5=mAr@z*H2q>R$ zFUp<*=nX~J&8k1+Nu3N#Fpibp&YJzu{qi*-3`AE#3*zc27vHzHQ!FNj<QkeO*+|EnD{7*kF{*Qawuhf3+DwPFOz8_?Bl@F#Eh&GH z%}3uN(@E_vL7EmK|Jo^|LZVNXQN@T|6$*)y&z`Tl=xoL$?pDH0-w^x)#KMpHc__jd z*9aoBVin0Hx)Qo(>*M!C{&;!aPjf6E8lsq{rss3+h3I-^%%#5uNPquF)49hp{lEWz z^$YRC36X&?oe7y|!GZvdTYY=od>)Zio4m zpH^1pX{nikb93*b8~&+e`ZpwtYC?+DA7-Xn{z9|BWUm@P4BB8{JKkJh@ULrZl$Re8 zAzXBN16bXjI05qyviX0Up1)WMiYwDR!7wxkbw@T2%32U6v{Iow+xZE;Q7FyVlh;uT z1h~F7R&o-u1pRU$gPV!6U1nXiRcD2baef?EZf!N~Htn)z9v;~QpU&*xT@>|ZzqN2b zO=Wbg!urLcJfK1RI__kO6<|6l@KxDgDencgMg;xmh5$Kavy!~B{7vQ5JT7%0nwnsM zmS|%#vmxCE%c6?CK`@k37A>{f?Gb*JytVZls_ma)cMom{`;|$3#hqVtGnv56QKlqCYR=I%3|*wZf;-#MdpLYJ4ql>Wtvg z>g4`H^Sb3}yZg!JJ^J2x3+q?2Cfcv#sg-jE1GXPnPA@l@T>EWlDM)a_vK$qga^)CiWWB;3vNfSPt+VZ zC%wrJNFPnE?R_y%|I*|mqB|DW`ZxEzHGXq`Vm19FQOY#UyG1E`*~YWvR0A*iM@BKT>xbLlw74gd1OCq3`^tpXPn*)B-0RQKaAeNpEm7~Tf` zTfzZ!_zI=2XOthW%JVlmA&kpF<*aP8ym^Me8PdXFdNVTkTZqOb8vq^$K(L7N&i=Lx z3_8RsD=RPlM=2#QG$*WG;kUH#-`L6awBv6mWO!$jLJ7XMIs%j6Fv#5ZsG@F74g;=YRkaUF8kTA#>U2gJ>z9sa7E6!&=6UZqDG0F_UW&MlEgj_;c3C)Pe2X#$7{yYp z@J&??z(p^|()LTK==?&)fJxF&R~IJO_dSdV%K&Dnndt)<81wx6{20lkexeYYg!#_~i>soUlV~jx;IBU!dcSQ>-%*eu*ubm)wT9kQOlDWU!tmZpU?B|7r zBDk_qz%BoBbV9oqs}umW`%%8qd$MJe|E8ouI2iAx>iYr?(&wbAr{we?`TKW&iRktYlaEH&cdM&z-s9)r z=_BpHc3@9~bF&&&36YQoIrW^3K*Te~Gf|H4Pfm(~o}lI-6--`^?_KYjf#t zZ^;)DS+~r?aoQnh-eCqA4m$YFgN8C!s>5!~1{a(Suj% zYT~kX=@bt`HNTqw_!CeM>-m=W%RY*c#6q5QePPl9K_kd9t1Ng>$ zDRU*Z;+w>0Io|vo<|z!Us!P5WjZc3kBswbaHgzz-%x@LwE&)?g53`6}2|ElN{PE@+ z;AsBF^grdw_BHb;jO36@6_;*ep@eO+kSrE`kuc7p6kIsYuI+vz(|P2m+G>U-H3YFer(vZ}1pd%7%)b5!sAi z9)fZ||1*uX{o`85nUJn*=Squs-9oLoL#y-Ne1ORc3pAA7V0>8BC+3i_*Lw6F|QR3OAX(1Tp)&Ge#9)CT(E@eu&T|3N|<#|w;8%KcAo z$3EBjw?XF;L_J+%F2|rXA*g#Q>OZ;*ljVG>eUsR)SpdvxcX{44h*)B;N|Bz3E<&qi zG{hg$Qg~tPLjzD6J^i4?oWn^rlX|58DmMYtR#?c+&JKMl&tv=CL#Pt2jkP;pSO%hk zY;f}-&%+-qNlyX615X6*kcmtbI@XtI8I*;^&H_vg>w^}fNLo_)Lflr?rx)sVBEo*s{Xl#uM0 zV-CrPk1zHOzgj~@jS8;-{8~a%40`$1dn@e^D7N(fs4$9Z&P65=g9FLH;u%@a-B(9%v zG@yQble9h4-@nZ_9K2wCq+bHKeVx6*V*W|J_w>a*vlHGKW~lf-_QIDJZvgEo_1!SR ziWE}qer*}t`D&>58-p(iXecgM7RH|4*!oxfXg^rRYv)MjWTWJ|j7;#!rZv)M<=cr3 z2(hkIqAmH8)l|^cy6#2paO(Bwt((0^L-muMxtNZ4-E%@0Fp4RzfL(lqVGkG+#k>N6 z92l~m%U$NW_qyR1O3ybRp#_u+6oo25R~NNG!#5FUUV~cy&HpbVd=S$Uv8031d13eE{zVAt_R`yJ1#AoEM?HN5e>h@Drb8?VY2DD;(` zdZPh?zs?(eS5ZAS8xglB$;K(dY!w%!q$0GiH&E9+nmS7Ro~Egu3@S_h6mZ*CKZ(kG zWM$>Qb~qWhVD#P|3n5C(kzr^F0tof@@WhfxITd^a(Fl<(DA22<8=RXq%6={P@mtge z$7%2B>|UQpNwdF~1Hz^EUV7t;zUa2q#)%;vj{3&Mm>$y5(2z*9R1t>>4||U#31|b# z!bm>MFqO`7A+|(gG>&rlxyCsO0tBlo8wz=&Gh0}UT!=y6mT-!B%FXA{CCOv>7zNWJ z2C&%@e)u8X6vy%PcqV{(K#9UUb>bzw{QS-F#!KiLoqlE^PBa_>Bqk3vk68nLhf!_W zmZg<*Dn?y|iDwTF4Mf%(G;lpYXMHG-e(;YdC0){%5 zE4mA4ps6FgJX!z|vqrk8)9<&7Ja7dTX&*eT5MV!>v7j_1{dLUI?tI$=+#`ns&Tk1f ziL&+;@NK;rV2BkcO-gY=o0EuWJc8*(ikJtTX@J$K*n=c6ON~umpMw_x4_2ZVa z(?4>4E(GcAY}RzZjZjsV*A^b;Pvj9$;Dm&DIV=VhNq9^2q+ip&%AGwnG6v51TKui; zch=?tMLY&=l0>?n>e)0rsSIVOWU4n;)~@$Q%QOeg#)M6OhIgf}P9R>V^gK<;)12b* zr%sN$%JC6pC78~FLBnp9TIQNyoHx2?^k?*APbW`1FD@9+aZr|5ZI>vgN=gjq-cnYM z<^*ow7%9wOKb5nPJ4EYt|U~G2b;XBU@Sb+bbEAGUNCi&cD>4a{EhTtEb;SpPRR5_Oo z&QuOG2EWVW%9(4AIZt@NFCKYe7DRA#z*SGU0;~OV<~;(JvQtts89+e(1E_3@dmAck^qIkM3Z74pK6h_%>$kA56-3Ol zKVb|ZV`lbnbYhi9du{(Wl8^Axi|Rb#cC|a=QdW7;RN$;&^ZtgE%xV7VmT3<%BQ*se z7&@F;Gr*9jBMdeg*kqx5h;_-iGQ*3gi8^n^*YW6bb3sy#1*a2(Sb`T?B49mt;q+uP zbJ=GcSm5`A9_$LL?9IGy+M1II-e1C%(1O2WB+AbU0hkK*1%H5B7I=P6`~Kxh%HV>w zdqFM&1wrDF`9#}TTd})@Utn zBUR|h4jKL{gNsAk5rnUvDSY z{<{`Z=Uy(O}T3gFEp*DeIhVE;8W%VfkcWE1WC(QY7pG55Qe0XGILF>V@2V63E3CnwAwZj^T>y5rD)SOdu=W+Y;u6AO5f_p~ zcj*7PY>=Nne>#%ZRBJ31ryy5RuTz|s`CABofd5C3d6I=BlPz>Frw@sFEFl)sqV#?t z8Io9RQ3>$k4nG-K)KQEA1pvsMX-I4V2@?VHSV$Q zfI65<<~}C_xoEAIbS~mpPg392&ko*(`!8b=XW799m+fGLbT?()xUgx>;F3%&&qtxa zn9mMa+M7jMSX-xNBqyh*$IR4BEN&ehHqyAWpL^k>A03EJrpPWiIBNZF+ zf~0c+u+_k#4H5pG>_`wo10z6iDfyB)&8(7|y~$$%a4l>w6w|C?|ytRO)FBel98l(7KLNk4H*6V(+dC@kx9p>~IM z`WYw2$ton@dok%ty(1>=k#G|XYyEK8)Q7=jCElmvwbY8$k$OMlry_C%52ff;zq0LK9|O=eyMCjY?gvT_5Dnx9%vt0@>-%Xq#sj0>^>QtvMzH}-Td_{B6#ih zzB*ttZixiE6VBdh`z4Yru>S1T*fi7`sLK*O=G^h>Wc+9(w z|8<}K>k(|)TJq{W{&&}Uzsna`%MCu*sa8~|%7&{2{P|&1!z}a`qbsJAll|G`5)UH0 zWpOci5l$@E4LbOyD<%KZOzM@;bE=bhCbzk|OVDmDk5%o?!QB$8)9Gj#_1)i_?hXEj zGqdjzSC50#BT*p!9RAyEY4IrNwRRw%wil_eBXhcuY^g{$W9E$^Jm`0nj}=gLCfNQZP^7LP<wTu# zht$KLlSd1pL^Fu@!X@>M>D{1R{G?LwiL97Zjwm`(ctzy*dMJ>tqRbek%z<;BmYaWS zpG*AjFIz|pFYe0ciBG`3qei;k4f0?~k)Ufi&}~Kj1wBjRDyyzvKD0{871vka`Q0sZ zMRj*?v0I-uId*bb5@_d*Th1*q?O6144v>^7gKy;srKP8rQuN5Pb8}+%{ys^gPL?Dks)|J56$$d$-CH$xP zAy+9xD6;)v06`x6P`BF#mFX^H_Z+gi(7Oqwuz@(R5k`WH>?uDOAj(b@SgpqX=tg0* z0anU^<^!YW)z#JGs|rl=Yw02cqyu|RHk=4ZXzvyPJ}K&s4}|Hsv57klXh}OM@VRql zfqg(gtFK~hJ3u}y2=9PLK)Hn#sdsV`O@KeiYdbK%)~{Is`-&lFtbL;We_~M71LjCX z2rAO8BsI^;y{@Q&t-a;)!18t*{5q?_rEH)F>Na?xZOj#LvXjA@#zyE(X=VQvWa#Hh zArhqMvb5y%tOT^~%6~LbJ)PM;M<4^D$pmOuD$A?$D>6PUE{zqIei>Lrdsb9W3cevz zYg9_Cg61yHAI7TgKzENSx4kh=MWbV*w6pBo{)_zg;=&j38FVAeCvLK1Zo*(0Jo*!7 zhv!3++)A`Dw#S{1J%XJv(o;gxY0yul4JydSfgl6Caf$lX`~2dlJF$2m#)B%ZB=m{C zk;oqZWN!ma@iG8y{M9%y$dvtM*OaI}0-X6K`VL`w!6VSB49F#xtWheqG#(u>@;Em1)h{JP! z?O`iC)>ylGg8eq2v3f_EI8}jsdn=N(;1`12m|sQ-DIA=k;td24 z*EVK()K7ZVcBVN__u};*()_mmj`Z1im6uQM9Sr9Hea@@8BE8X{-aYhR>ad zej&Xv@USPogQG+D3Cw?cDb?OSK>@c*FD{|2RL+VKLn^ZpQD8S0Ak5@dKRL;K zsba>TGi$U?g*I>pQJm=6JX-G%>@9!hfoM1($G8VBD3?ssRMnQB zmks(ibpjZ0uH}Y6cyU6Z(0D;7Gl&OR)9xbrm(pDp-IN$+j$yXvx>BQKOTaSDnn#>` zN?*t6Xv9k{uo4>D#-w4&HEp%m%E6MQJg$7V`)=CJ$xTJzLmehw2!g1e&PXkDm}JG5 zm#bnv%BMVgS`iM~Bb;N4A9aHLSuA&W5&K=Y@|e5@Y4am-^SU^)|g^8R#VX0E%W`Q)H< zR;TcW`?qx}HR%lEb+!=ri*<9*L1~ANj}OOLW^hg)g4A;b{8G9*TBYQgLV_VIk-O}j zTo*?Arwk$JtriO!$<_t{^vlb;KSyweLl|%@TBvj3PTbmtU>sZM9k4+}H;gbot_;jk z&0V|x1@=O(~jq}C2CaLj3tY`EkCNXyUH zy_XTHZGdGVMj77F6UP*&^h#_J0LA>m$Nm5$KTvO&6lt@pzp!$D*oJ6fl8-x!{yeZY zsH{TxNG-f?e9M7U-u3rsk@n>X2&ESQEOKkq0Kc`W%ECmuxp|pc_Nq%kO&9jx>2>n2FQ>Kj zX0e zb}$SMODH{{m6T{qZiarHf69UaZvzMj>SZu!w?VE4@-&UvUTo*^*r)u_pZ`2;R0J46 z&b`)p{g;X1=~mUv!zIcm=1Diu>#w{zI8n^)z-k|Hvs2VnE)^@bv|5``Hn95CKU{YG z`0ISi@8)1Su;B6=aA3FW=I7<>;VEUV;O}v2#Vv2;car%1w$4+B`7)L5Kn|{*P4&}G z^i9L;nu9JW{BfWJ>GNRoL1Xa5Vx@#g%!nYzA@T9lN^9!~YmWNCZ1C=IugYdW>*VoY z{Xj>RF;-Th1|Qt0!%tB9J0cw$Xrpenl*FF zWgye6XMb_?FKtRlw+?8#`hbo~nh%=^oVcoN1e?-!dKjjttgBt9!GD>GE3t~19oao< z*+ei|{;vmYb-yELf4`PX=S}cRz8W{;9ykOHB_Ue-FSo%xeqDI+_C8TQl`mF7Q4pQQ z9Fog)YvFY^6nKRnR-W~}1%l>y`+RB279vobr(9M)ykysml>Ro`;HclzpWD5<~6mbH$bScQ3-#}+fG?$ncKj^$%acv_s?ld-Ek+tloj($i9q69bZ?ld;; zt{gJjAkKtz;gFs=SeWvAWPyLU@<;V5X5zHqy!aLI=!ydJ+= zg*eCfce*u@8QhjuDy=)t6AQ_98YGSTst}wmh%o8oWL3T~TsGO6b3>p00N}2drs+m+bdQk@j+D{9Zq|klB!Z+BY(9(fM3CZrHyT zygtJG?@n>4?-~vEfe9wgov6*A8UppXb!B#Crx9NnXIKD_dT(m7lxGXr#&d+87Rw9L z1anc5JK?v%)3p)37yVEE#OtFC2rS8Z`5!KTK%zCpyd0pcCrEx_;wP7?>gvW_>?4j{ zA3jnTqBu40-3@S#zX6kNOW0f4R;Krcy4Pf3g#KyALCLEGNCG6Z)THi1Ar}Q zTY+I4D%I2*l%>2X+Ozvg7o(4X$mD;teBE;lE8b;wlJs8p;`uZjPKZpk1l}kyeR)4v z7p5DeWrYDfS-J zM_sPQoP|J8*$D2ek%`gNdr$H02IlgIiaUw_V~tW8@e}uTF#hg%MX+#gWmVO{;={v# zfvuknu||nlti99IbUuA_X!PO}wbZ$U8{qN9mzqolDR-Az+os9ath2l6M)o7VDW zDZLBVBIkNCn*lI}rmgl+q{)df1!`Ta?c$cJTrPvEtnO5ljpRs z;QsLEt+4L*C3i^o)76H41gP*&GzD({eRrJGw>JrBTi3>Y|K*o7oP3uFT%X?L2=-eI zdlj@$ayoG8JC_a+tz}Rgh&=24A?xFu)5X}6h~N`_9-g|n7Y#SeLR#GEEB_hr=NH^u z8=pLFo#Xg&vZ~m8@$3;jBY0;dD=ce@Vb0(Km@)vr1T2pEL!NOq{9B1ORj={c@Bcn* z9n5F*V(I6)WTsyZLu&>^B3Ec-V<@$LptG|)KjY|6eDFX0lc}x<)04&E)83OI!PCz8 zOur@N$>TL(7Mv_ZWZ^QP$_q@;#%edFdxmK>d;R)BJ4?MZ56Bktah*h=WbohLXPURi zoA>d}yLju9ep8B?$IeKUUD$U94lRR=y8PHrJkUWQ}K@EmlxZk!nKqc_KJJQDfA{~}I5Jh;R1gn(P@DkDRkav+R_?@EsTB+j+o z&;}a+(?h!vc;(d8>H*Oow-y~Md=J~DnDDNm(<4d?FhT;7si^K56whRVd~zWoZQ5jb z!mSgA`uM22(vLL~xd38Z7$1p@fcUvHctAzyA)6qfC;VR_)+bX-GQo32^gzFBuLn-| zt&gIsX>~Q#io}`Ek_%-L<#LRadmTAp%p4%L7zInq)Q;FI-@%QWJGpgkWpeEw&KgWL z-b8y*Vyaxbhm^!~pV2C#tn7Ze+%SsSVAlX5eylluwpo*d^7+yivWD{FKQYY~N+%|u zaSp30GGRiFrq78NFqgCBUOy&PRsz;qrNlzrxKCL5{}rNuerDhf<-dir8)UfN>c?Tsh}+8Xk2H+Fxc0wHc&VzXCTf6W)sI@=8Rj3}Y;D;sY$KT4S9FvSTB!tn?Mm z=Q1&bz*ctgWXD#(O)O+nNoc|vDYfpo+z=;-c`m7Hf$<;}CIAp>2Q+Q_ZOk#iMy#Ra zYhli^q)T}TOWpx`Bt}jM3T_XAF(0`oh%r?syuDAAHI&GO+d;DsV9Wae()lI0OPIcW z%R-mQz&z>06o5*v`{FMYz{)BB0((AEgxEy_?N=@og46a#ZDbC&Z9`M($*hgZ-HpfBCm4kEdB~x_3)(P7z^hj8&_<9mykwv3jsM?d*+OD-qpRz=0`3zP zU8#nP{J7inMT)@5!!IIgKR{84k%b7OKYJ(LND+-H|1$CTF{+C0`k$>(s15S>&3-1* zH_8E$SYb#RE0mruFX+3an_XCNB_w`SG*TF24h?rL{B`?N0*s&mPRWa!jWk?JbLGjM zU9a&jyF>Dcs5jsjVH|gw_HgIORPyHb`vKjBeE0k<**9kR(y*{livFT{{Cqn?_r}7} z#s)^MR~F`a#T}2UA2){x|03U_H*K!cf9B2I=E!)$bRF31xsI^4h4L1GG-$29GR-;? zy8;!7P6dEFh*+8pPp^#b4&xHn$C#HC1E1^Sx-aOoH!goXY7~?2aR{inkgyg~fN)Ph zgRW}F%?JoWu}KzG^Arml?Q{xYM<%+-cmbxkhA_wl^x|y})uSATpyx|}3ck0_#AXJc zgmIJv9WS5mHUovC|M6HQM@b;O=C6-3q@~V{onOUo?dX-@$<*R~;DzKx?_xF;I2@T3 zp7J(-So>_>q2y$%r8SHe3M}*;Q{7J$Y-XT{u z>2ULIz2NCLBL_-`+Vj1CH`N2kybEc{`1uv<(*^f`8b>qfcX=jjkG431w@CD$-EBn~ zt7d=2d;Jj<>%E^q6}~TX)St|JUuC-!C_tk&nb}wAKJ|J=z4JFE_;Amc9|4W46}=VZ|dh6@i5C8C5x6L=Rw5no%l(9F?yZGY`gOddyAA8ou( zGJVe^&SZyvB@gj)EJiUU*hdK+)Gt_@SwAu|^sc``oJPrX_cOt4(wv`*LD9d?uziYy zpg5TX7zv!9U;a}nEl^vgm_7(-ndrst7Xm?nU<4tJmNNvQy-4_ofN5}V^FNBMR+<+T zzt9jVJZnqZ%86AEI@n6418Fu~kyL7`uONP_t$?coymLr>UoNTz{@D>lRWvLR!nW{t5itY`FFePU@FqZ+BG7tiJ09)>Qt;$G!_pjSYav zV_{cB`*har2w)rnJ*#I_?W_sTDzBQPS34~t*kVcreor1ez*uH~grG2&!&_gTVFn2A z<4!u}mm1x8{6Y}IV89U3YSZVuoOWf42S4#@@d@>o1*zOT1v6?B+Q@v3l?0bUIaLq8 zg8UaMl}nTtVB|Pb$y9ddBzT)YCM=iD5dYI`x!lgAsJB{te-^^{;8LxE0@yAzikf72 z)gE`VgY4{TJYh_DKmdn4xI3g!86#Wh1P&!$kdhaBoHa0jxeX%55xIusY~c_lO3Ix` zw=pu;N?%S#()*+{oZR-cRZU-bqY(ak)64^Mb^f#AUVy=9qVdXXapm=8pZxNIe(Ehg z@;jF&{MzNC#qr(=CJ-SUKWYRTgSa;^a{Ft2pgwSl1>o>^nO@w;WbY7hW&1SfZz`YY zIi{?ft{>CqM3tpp!1zHP6J>=TM#5iv<7*6^E8es{P>|320GUbC8yHlMfCxu=kY^D6 zh5_`t#tg_~6#*|Y10ij5+T(9XCeJ=ltC~|;v_L90#L_Bx;#*%Ig=B(lNLBW6 zNm?4ju_;`#gu%JSlu~f6W5LhKjs|}=0a%7%(p=j|{mb!~`wlnT9E;B75RnU^LeMSd zy}^QZO6|T%W)CpkLU$qc(#k2Lc}_KuUtxLg{H-o&UuLpB^td}CdLM=QVS|8oOZMKq z3bi}>w$3Hh9rns?Y&p;3F4z+*A5+X3PDK*#m@62hDKTH3jUScMHC%Yq-`Q1ml-nEZ zbJ}{WjrGA#hynzpP%p~gCvud{{g2Il2P>l-C03-=lpEBb-)44WR{s$YQ6fb{HlB#T zG8w8~0S+ zjgi+6K4m_B#js#|As_q5^S)r<%F#BTX+%3r>rbMo^{Nc}L73WA!sAe(8Dj6%_}%N) zw|v)DJpAa1@2!8#T!MdxY1wjLFJTk#oBGpwhL5$e_~)hun1bM1-?sEELbE3&`RH)H zdjjy8(JkJ>)2>E89jd4>jxac_+Fj5=8mt5`#j|#!B6_dzK4+J{_Jvduyqvs{@nR_| zub`olf}aJEp|A>{tvx@r%(=}vC#e1VAkTtf%bMql8$8W>x$Z%m?wP^UO1Q1oFy@S- zJud5mjrT#DiopO>XH!w_wA&i#HUGT1SwljWYF3oaOj9B~$F&GES>iyT7EAgS*k9_Z zvP|VOrm&}x0-Amf*`D)uy z0#*pC5~>OdiL%-TTDG4m@&K&Ec=M+@lZwtx z4W5Ql0P3B^o!1-880WC;NmvXQ%14zd|;woubYTrxekUwL$l$R?L6ZSs7U4q z&~T@*#V4bFDh>Dr3Lw{}1}p%BpOmvgpNTs(DV&9mAVG*N3>g&%=hQ^>dT|o2`>Nif4$tS?V^|a< z^sBsv0ji=*0F+zd`!U|Tu&{#a*_vJnX@S31;)!voFhTROP5V{E=RU>(`cT%^Gp=$3 z0T=-?+Egu-TOg^_%i1+^KyE_n;tI5csJkQ{`%WeNzPLJ&wgkj(ke2PrZ4n)I8JTOV zYpb*xZ_CS9!a3W1@ZJS;KC~flw$aWo!4`@K7BQn0kis%ahLF2OIPxtg6|x*SbYJdt zuS5N0CR(P+cfXNK{LN&om-uT&)YQ8i9d-fa)&%`UupHpF&L8OcRE&7FAftlJxTo%S zI>x0RH1mqb8bJXb>Q`1W5Ju$ty!CX;;SB$SL*Sz3W_9Y}Y9D2w2^KfrVvdHKVJ0S2 zew2xIf(?2iBrSZ&-)2%Kr z=zKutq>k3y{rA!hlg=LhSGiXuaHBN>Lbk$@KS%sRo)P+yG%Vz>E8ZrsvU6d?!}a-ZH&B%3FPzS#s5|Hz%15%Y4oKk-9vzWLB|<+)He95-s-M2 zhW*k6&zFztTLszO5K!Ow8@5|Tzd&TkCa&+&nj6aN0Yn6fQf{ zg4;xU%8G9$_k4L&|AkaZb#jI0fngMXwaj7f7#6q0s5I8=T72my$Z~6#o9B?u;4|FCZ2t(?}cMJ16 z%Ybv0h+z8Vcw6?2fHeDo#o`M!qig%71wvp1nP7O`@2+|q)C+hF$c~XVY2P3@m#nl| zB%=H8M8W2X+6HD=`;@EN214M2<5$OryT0}5%Zgv{vE+6@*p*-lh&fztJ#8w@BXAeUHW&%Hlw^7(YGmlqne&K=SuK-a0{K{&lg~jLJr|Q{N z%o79XC$rW^5sPvh1jqO1U9abgbs*YEr9=a}z(+&e0}AUu5j0w@@8(X=_e5{b?_*Fq zxmGhNpko-|4p4j3$4~bJk59(PDaLx(#ITbYKNbJkZN*Az`!wz4nZqmC9@ z%a)Ue=_SX&fFx)-MlmQHLd+40LWQ>Wf7Ay*;pRACrRe5-uyepQD}er5 zML*scY&A6JfqZ23Xq+#GqP}sbPwsR+_;~W9Hy98|1Rg{*Z}M5&bJIraQkf>o;{1*1 zdOC#Cih=(qJK0n53j#BGoejG6>86t>+Eo=d%pS^>Icc|0&6m@sZSw)IZQ-%r0Os_4 z^Zxklh}foo{j8ZMKl3k(S#(~qUscrr`-7AmKqx>YU#0ii?q0*@zb4}@6j&DBqKsx~ z1?IdG`2Fv|xcq2PT(H@DllQsMIWE$9g3#+6(fdyZDkiQH4fuX~(cFvO2Msrb&b56V zSiH5snFqE*N!Yol^;&96h#|qDf~uQ87jNd%g6YqiCnLa&bcQXc9bM&XOO>)X0Zd+9 zA5h~KYAAWc+`@$tLa*{jWLSi-GHdas-(K2;&+^MS@9X6w}zfDkJR^?55Tkx z4Jy>(r%e{{F6BgD+ZP6(d7+MFn1SDqH`X0JJIMm0Dc9xLPySyPz*Wvcn(h12#>Uu^ zGj_<{zyc>RjWuVz4*K^JGO)O{LrR5;XgN&`I;HU1Wy1|uy_jKkF4609)N?Q*mCW0A zXJGI{#j5Z?_YE}s6~X2ni`&wzbEtw8x9ZK4Lppu3xkS3C%&^k9<U8a`pCq@k^;nC54!r#d8oY>cDN?u^1t(or$bk9Szsji zvm{>*Kbl~mmfAahd?^bK9@%)N4zT1i_ope8`w&9oTHA{ZKHO7(O?bQ^0|*x4lwyL_ z17j_K+|7bNcQ`i}5#q%BTL8H4Xk6&NW1c5RX5tIor~i`gsFF#9L062-6fteTj)5z(gaG>FUTCjx3q(-0CC`uO@}16f*-11FP(ZrdHm*WBDzkBagJh(~KH8h*fIa(+NBYBOpeQ!i3)5g9eZP+Q5rUx`hdfKTSpMT!WX>#-a+t%P1Z024d!=> znOiFt_~^ZRg$AD9*_@$^YjfLyR8T_TQ0co41D&gu)m3XW|7B8l!Y}L7rS~1}su(b8 zM2SaCHp|TEKL(euS+W@>+1Nq~fImxyLN5G7EozP!(JV5Cn$_i?W+Xx|Ni!atG5BsDspg$j< zCji7d)qfyHdK&ZU^65$E;Ek;YFV|8Qm`ic`&!_B2@&|C(=!+yCFReTEGCH7uW$ElmiPC`D zrFjz#BOkw|^a9 zbtdH+U)#^de#L_z;Q(4#L#?-{i~y>DzP;^-&ViC1zxJFY9sPp75$t3vY9;y;a{+Vd)(pn<_TEM%UQ(8kaQ({;dm!t=pr%a-%mRi z{|PSTFtN4C9EM1X;`c|HIa(OO%#e)I^;R# zDhU{4FEV9&TS<{fvINMBqknbfZ@dglfmpcm_&BY0-Er`Lz-eONs7uO|XvFYD){_bZ1g%cNl- zq6bAOw|FAK4y^)05ug{Q(oFi5ExBub!kMy5=Z6%ntj(<~{`xfdnn*3UJi>;xP5~Xf z;BC`Mg1)MEZM?kH*v?>i~ zN4_z1A$hSgXjSiC4T(IRodhcWlAwPpn=&VV5{IwGAH8FZg}M^^6F5Nr%l zK30;ev+X@HE1ik3NV9=B8h=QL5iel<{EFN$>9 z>Ze61U?{pMsB*lM>fW?IrhhsKWWRY%{~t|f{tor~_TjOVQDR7p$i5RpVk}uEMka(J zOSU9w>`T@tCd5!NmMkekVffhhJtJg$Vi~PZR3WZQ6w*B0|TTl-Q6^T4% z(uLN@?X>B20PTEW4lTqcbs|GLesa$m`{GR3SM{Y9H4;}8!xN*-mFYIc_}OO; zJJjv_TroLbZd#e)!CRSWq3*sRUmeAvgOXL!Y@D6%pfYETGHtzO@-uX0;hivDs4!-j zTTCmoDBb`K!RF&5*N=o}Fa5mmo|%n- z>DEiocg}FxkCUN%sGTd4BwNpmXq*!li?fvJtgvYcw@WDjR-CLX4vplXTYgiDe< zJp1O{r^q;`kzRdw1HPNKSL3pGpiDTJg!uEDXlqNWY+omaOOQ}9

    g<+U`I&zuH8`j|@ZM zoJlefGn=o{^zJ6k;pukMbzhe#fsg4_KxsXJVQu%($g)786fz6>HV;yI?>Rf`VW(95 ze0^oufYUj(*bDIv3Zw!-`@ihGPw3Ux*1nRoF~4P$O`V$H)ca8gS0X_=kr*5d(r#K5 zHcLv}nQqI=Nx_WOX#M9cL^4yYu{x6n*ZsP*4D2VO_ayFbp6A*eA@;5^eRh2E@RjS!UcFG~IvyYx~MOsPRSIJb;gR!%Gz zHwrkQ3{-yB*?N9MQK3wGBbw$lHK7&y7s?2Ne;@ng(iOKf7Tz)O@2q&%GP0k35?!C> z73Q}2;%K$4B=Km|tqm5`NVjj@KROr#r^Wyvmt1oG%x4gI^AgE0pB49KF5O}OAFs9> z?6WJAFqPUI_G{I-W6$wuPL29+Tr;{p{u8! zyEz^$Jd=7;y2yt!<$s~H0SVx}&C)N&tViUIl1|D4EbJU)#J>jG8&^X3N>wg#k*kX* zBeuDUs*aX%A%OmL_MqEr?*q_n=}VR4Rczf_2a?*BZRettqv*)h>F~XNM=hV3_UA4= z)ZpdI?%${@0a}^4+99&f7d$kcLUjM&DMZi(N`m>3f$M3OS**FKs;Rj$+x1n|{^0T7 zC0@{1mZRGrZBIvREYKtA!;{{QZTs))D0~;;7ufbWay5hg%;^1iBLcHPzqi6*3j*@1 ztJs5e`R4GxWVjo?GL7=ElwzxioouL3ny0@2`fGh)%_0Vd$xj_e3%e5h*@cx!Nj-p^ zq9a=;igM5Xgjd1|i`2KU#W;U0({0|#-q34PtPx;0)YRN*%wb~;UM88iU652cl|MH+ zI<6JDT$6i-Cw;M)y-SyW*<@~rxJCls7bX0dY;3&}ds#q14>cAP1w=PtPf~W65{pg&*=g4{K`5-YA_6p-o*+>HQSyRyt=4`!aF; z#SU7=NX9vPljXE8uxMl!TJ`}2MJK@{L5Gu*Gm(UOTwv?|_QLEm1@)l#-V7($@d zt*a&mQ1#;aDy?k=?z#VnAukrw#+}bDJ@euQ)~C)IV~)h zIEe0%e|ds=^_|V@g1JJ^-Gg{%#xl zi9q!;W$S2XW8TUEbBnr%z{6)D?Ty7XKq}Rt z{>jWv4CS1iGf+rX_io>5J^1qcY|+VR0Pvw`cD(i{+df|Z^c+AJjVKL|X)8~+5}%cZ zZR~ID0INy*v*@FlchR;>a`cw4pFc-p*~@5E&xZyAl%4S#!qf``92az&TGS4S<%imz zs+0Sef`7g;1P!>Yz8ek~Y2B0FEqkBNzKG#;!?PLAa+FV9`}KREj*2|~+-0to5O%u9 z^vypImfaXU2K12B!N_^iR#vw$kv=(i^<+hEqMOdq&(mM`=k#8PT$z|i%5O)S%u?&# zMEtC{5pJ=-h%6yQzeLhUp3Mp4tHhOU&11l=Uw-M{xFR*;U?oRWC~|!b$=`M?I;hQ>v!Dkq~!+xThojD2?#WaZTtPl z)s@ZFwT;R5)?$Tze4h|Jv!75jD9{?X5d%e{+e7~3xMZWAOjz|8-r)H_xSI|748)KA zWVqP9KzH@$`3^cEiBu<}OB&0H80kiqT?3{r@#c1nC)zKeeffFXp%4zBu&F!9pr|uKzJfn^9^5L;(V8xJRoqKt zQi{sY?B~J|2n-Mdva5jN^BSKaCkkoA1w8~*V*YWzTYLrREOAqOpi#0d)>hjr@*M}K zY=39)AaX-c`eQW(Z%)d9m6l;4FL#8YSFxU!X=u5QT`JXKM8%@Fw)K(#d(LIZlR|U% zWNExmKSqW=o2Z^PT-kZxu> zdfDaIVhxssLjW1L|0!HM-J&MYlxz);p@xC|fG(8t*}Fg$FRWT$ zc8~jqYBPizX|Ao!N==8*a^(A)V|QwUG{#ZoW5+XHC17x#J{{)$hIfj}sQ($60L$b( z0fD#-e+#r9%~pas3v?R^2we$?bCTCbiD@bJ>7OM=T!=bj|+gIxF(<^?7(c zGCn@f314IStT)_LnziAxn+x9OReII<7wHQ<&;679wR6C=8#k;%7KT{JLSOEf8C}!| zTn-D_q?^#E!{>$XJ-yV<1jUZSU66B7;V3huTs0GW0P%;4ysud!i^R2Td3JvV8iy^2 zG|^664E>=+z@H2iG3Q2cq!O}+!nHZN-kw=0bg%vItG8woEMJ(d*}w9C;834w47b5k zC;(igxxxU_1?htM2!gfeT($e%jFNrG{UNQ*&0o~PRg0Efn#F67=2|r#?&-qhe9Lk! zKuas&fe@p@^{%~e?boIZ%(H887P6_f4h|nnDnDXL(h}9uesOOvJ77+5;^6VZ!Z=X= z$Tv(n`nQ#PX6F&h>BERfCp`8&SGJ^4eSP)!rGTKIos-deTs^=mg}{~8T~?4( zN`>;Doa;hP#yW?uUjU-DZ;TcK_ndO|&xLllrW?cR#gp8q?=gBYVNG@3Q{ON=dji33 z1lf&dg@kZz#RLmVswxSNt*)g2-IX3W;4lRE9YU0ZS%N`~c z_HTigvj$Qv2q66M#UVDeGAe6FRbCYOFpCU$;Eab-S><`bzNS@^rWa;JH>Pzl`^ zbE&Y#mwMUcD)c^q&t<*&3DgE#QY;%^S#Uc+xRn30z@R?2Kj-z21jhEGsWJw$6I_^+)k1vTs}104$qeu!LQ?QakRG?_#Ol-z_?|adL2fy%aEOXOVinB(!DW_lS& zOs%i==ulKl?8iv91?P0H$)1a0(3kG7G%bpT5iCxTt5hzWi4A!JsOtrZ1VTl@oGU%2 zMlxPZ#?@YJ`6ic09894<8Mc_?f*-uEUQj)`e8Sv%EbwNkGYq*zxaFQ%U^KCRiQ!4y zUF`DD=-9<#(2{=&h0kSIsHU*OzG&EUgjP z;IdRex)`hWogY&z=j`<5N_RDq0iVk)=cwn&e%iVHXhvv4r9PAda7)I?@L(rAu{cwS zUF3la3#9=WUs9cC=EgyIjUg>{$7klaGzp?rEHfdU8ow@I|Q- z%QjsxemG=|zB2+=Q{En>H;Pgm%FjX@TN|zCZxZLiwfi-4N=MW~e?uke<%{>i<2g%< zmDz#?VqML-@WdMY1|nV`u8Z4fu5W5M7eBMw5p9>1W!tw9fR?`g3#TlAHZQLej%t4Z zxbYVXxFzJ{flx7!2Q_GSQk8M!f6^u)_p83#I0l+~^5;g-KTwERJz@a?|Fagd-()R? zJ>F}C?0*}utE;hUdA5?6rS>8l$qwse17g(EddHu71Vgsw(nwR~9q)d)`BG(6x|KuLN`)|KXZY=M=rp5~CKy%~!8!h85G%{Gg8Y`*@>4ZHHHyEJ+yaLM#B zZL+SZmq#Y){52zje8@`=WQ8*`0tQELG3#-+Kc7CFVGbFIe#3pD;;Lk_d~Bu><~_jp z-1xf^cJOFA?phC@F7}*_P6F}`uHHiQD-o{YJuRS!FPkY+rdA*JLlL4 z*2}=660nmpiSAz}4uD(Wb;sig#nz*Jx5(|&xzpdRHNzgIU&`DbMjE~MAXq^~h_~P; zjgs-`{JQCgrK7_G4k0a2YZJ%+Xx>^BI_k)U#2s}^AJ0X%&|vBi;tP3bMbl*0X?8weST#05`{2#4vG+GRwHwq&ee> zlqvsXgB~%Q{l)I-r!1^`EG)7A8?S*X=A|Y1&ib;FO8NU$GEu^(^7E|E6Hgv~(Ky)c zopo*fT*)m0Mp+JOo>SF=5Im>;f1XRiP<60_k+{4nDDnw@**0jv$8&Nx_h>q^5e&XW zm>CeH_eQ_)L$;yx?3xRI^C!ckj6Cow-(;~D(VxS5;3Zia_&o5*PJD-}_6!RTudHY- zBRG8Fh0lsARyw>uNJhO>rsPmAjP;$57QSU$NBoOlfaaOT$o3awlf?)Z(+dbE^(tFy z*8c8QHG2M%ch-BG^LTgD{o=VZOdoCWuY%s(Exwl^%#A-qhMn}B{I_|*2Zp)`=A&kk zS*l#`sz_mq%qbRDmgBy+N*Y&OuSlfU)E1wQG8Ztk&1(EGBJQe%AU!Oa70<)lx}Bhr z8|M5tW6jUIQ6`W{vj{Gfv<%Q^G`YS~j1PaUIP$aoyO$8LddMad5L?DfU})5Td*Mns z_*rCeU$TX&tO}1_!W3LpOa0%N z{moh434`oO;-=j~{=xlu-}hCtFlH+qw6?z-#U(jHskyR)qe7 zBq+|ej365yu5kgFZ7fDqNsCEWN(ojNRTH@aZoQY{3m&Rhg0|U;e$Q&w>9qR0?R;5j z3EP3X7-fp;>%+X3|Nb^OY5|N^;_^jO+;E>wqEaDq80bc8zsAeB*e+GdKV?Ec#MTTG zVOsH>-FMf3^m?k^x9R|8>q6YYEM3xcn@+3ZiffI4YA%wJHWneE+x863W=YM|yb^ zjra|2A(;*dYNY0y%jCx_|HuovI8C}B`!0&{hKer!nVJ$%69 z`jQectjWkNXKw1zF8S`O1Yv~jC33!WB_-gc*~~jDo}c8kIX+jE51zC0CG1D_MKtnM zbfFh=7H2lDV%Wn{f-SMMWT3yEu?2ovVO^Wd-rD7ui_mwJ^Ne4+S5hg|5aPL2?f5*e z$^{Qz=2wMY*+Jkp+=y5M69v8ro_<&AIf`^aGn21CP)K>w)#dDj*?R09wkU{*JTskI z)A4o?&O~J;vvaWLA^xLoAOomjZlGw|=>_-7B!#$TpJ8;ypJ;D+yATGC5x?tliE21f4DPtiEYtX;;vxs}JJJu45&8;m1xYw(2>? z?{DG0%3n{s3_gjQ;o3_+I?miXl@2%6NPJ)}_Q5mLwD%8{8}d%ISoV6sJpr%_@=+k% znsTl1oNO$Hc289Xkjy35oS)3EvQD>kI@DlGX`iTBek9>u20;Wez)ez;Xb1@=!Y&21rhhyGAa%Ars0eO`n@dEUS+C?~ z8(UgiTbr7~=D)D#tH8otT>KwDCVI}@QwBilFbL=Pl`z%oVcF(0KL)V3Sy~)2#X;u# zwetL*U1r_vt$jUMnYRbt>bA7l9Rz71T$NS2YC;rGpoFo6jVzRY=qvP05qHjhSOAM@ z52Jyw4CHOl|58={SWlNOjaV3HRbngUFA&+m(j9dA1Cv`Lc^Zz}15F9mXd9)u;)4#_?dZd@iAPe=&ZDtgZu3 zT+w;Fzo!`KZl0ELlRW-nI@skg^2gNoaGzraN%3+XLF;kZj%e3bfwK3t7YB)@2$sqS zA@q3A^!`lU(V90#jyL4#1!XJI_#Jk3x^}R5r+j?ga?Zv4TS1qth|T^7+Z58i;=g~l zK_YEAKfeo{?V;%uL(h#jr9>jAG8VZoJ9G88XFhuUPmQ|! z6U2=6U*C3Mf(Q!b@|XZc?s8jK++o%6dR^bITZsFq+Yrb#;U{F9)x3?y>sMQ0w8k~4 z^RI0BEk=w?CtUZp77nI|Q<5a_lRba7h;d&+%SbrG|82Hk!dt|@iyZp2%Xpo$+u4B- zc5q;6uM@oMr2JYiM<6$;=YWMpCwya|(LKr3bmd1wPNBO^Dn%VXG%?X9r{=8;s?e+C zT2DDkxq4xE(A`@*eNQ9JbGCx+pTQr3>d6X z6poSk0#UBPuPWQg-g(KzLgwCxY9k_2ieCls8EcCx`MC5S)JJ z;Vu3mPr_kz^yt>*&JW5DEAEIp3&cOMnCPy42FrlOnZXT1 z90-=KH4F11B8+Gw8>>Le^KQhg9HuDW+Rq!h%$SE5_uHr4@gh^OUTYX`YW*@k@2As) zM01QDRKcM+c&@KtWNr61(9GZd`)0~>676mv&6gCjv1e?=s>Jv;?2nAA9^5R-by68U zjAX}|5t$(m@)0CaHiAW;G!8+6i{44K9Q~F(EDS?qNe1>~7JW%)?pJrhgLx;`rtc<*&j*mtdVa5oQX!Pn~vu?Rj!&&1S=f-Pv!v(P{xqb#VVW>d<~7 z9N*denJ<6O?`N|~vUq#fevlBg%O5QYf?9O$zWd!iy09o4-=dW<)y40IU+o1M;b^csts32pzy9y{MrL?%0m{SA9%Uu3<}a>5;o#ZLZ8OPBQ)V zuqVJpfnoNO^Sa0J?(N7~A^X-xH^b-*zwsJwrI#|!qToI+xr!$wXP{z-Q*Hl7#7`kz zJx6L2so$x4n?qeG-FbxN2cD@;0nIzj0|~heTYb@C9N;r|^fO|rHv0q>?126fTZ8W} zks7M7=8OoZ@fn@S|LJq60)tY58h<$p;LZVBf`h!>Qn}i9939&pZN+bt*>SNMUd`Xq zIW9lin`PN~bLFu>_YiOwO-y9gB*E5y8rB_`dp}+pO6dX7IJcgW1NjDj(k?_g~S*uED;T9@j4`I3<*I+!G~J*cwH{g|(Axjf3fb zRnG#Ukc%S06&Y$5N*SWWlQD=89}L)8a!gN)u?@uLx4Bi ztPeShBDl)be+J>#Qvw+#lJH-J#YCl?)7ch{H8lkVqPSpMlLy~@fK(WJD z?7Rg5EqQf=t_UH>+te5s|594WM|_U_M$e60)#8EuwE%7Rdy}6}3L^#1Bs69l7eOEr zmiCl(jr=pyy4C*kCAwhC2%L{jMwWKIBV%fK48{P;i~RXH_dD zC1vkj6kYZ~4l06ce{g~!fCR%yO9Bv?Cyd3J+q|PDjU7o7aJ?lnRn4Uf6#??D{F)(W zZUf)yI|{4-v;}=a(O^T7)K}YWf&v2KAn|$Ed>9x6HxB|w*+L)BK;D7)3g_qKI4+!` z{SQu21j(9SZ3WK^GM9%Pe=S0 zDP14zL#OurH)eG%2A3ebbmm@(u)cx0eZ7y2Nfp2X893kKo_jI9zjjYqGi>EwuoeU8 z=MW-ZG1@Dnp?f#nf)w89?EE<@s_G5)46Kn~FS_yOjlhMS(8rw*Y`A-*fFlYxlea2M z)6cso>4RdHC|*!2bTizW17I~Sllk4!_WV@Nhq^7F_Q}RhkTm#ac_6|S9 zdWRpgM6r;*%bT!7o8PP>Nf*r_c-&$h7ZPf0H%~_X%MtR*ovxvVLOw{v>FTfbm$$BS zL~f{UF(h#th9LRH*Svc;O4}E-OYxHODn%>RZg1Y(k=C@!S>5d`G`&&!@Yq6Kv zw|SL<-2Dk?Qj8e=FkG9SapEwd?c>t)LCf?~yYxt}M}xK3vd7WZ4i%}b(XzE3*kNw} z8`zp)5UAeQEeTsUhs}SCw45F4Rc2y^ATkc-_QmdOT>FD_Cp&GYvBY2N#=N;8bqth?pqgD@6MaaY&u zz`#Y3&iwq@GFXHAB687*ppSVj9G{oLx{{q*X`_%XRU{R)flLC9%K03ZjMDP*8%6#d z>MmOSTxg$m&r_ZqN4xV*cff^&go5hA=pBBqG?${x zAWJ)MbO6VJ1@SJSTOfFvVls)5k)VBfFrdx?ksfHr(mP`W_6@F}!Y_)kGg zM5g-E(+#{C-hApCHz%YyFs*`@C6&O1(wAmv=f`#;ikHso;aO3ToTMK7^U=|Bkhhnu z{;~Omu+< z6Sc*QvunFw#_iql&|n*dh8gx?&wykJ^JE2{>u8%-ydoUUTg>KB?v`nlmK1ANFMozhxJ4QA*s)6;q%$fu#Y0?(kG zrfq@k13VkW3On07oe1!BN%ceg;m5-BC(hGzD$b)m6#SL#>#zK~o?rnaARWwlP!S*< zHn+WP($3UTZ`F5xWVGyVRI1krH&|4JVmFOk#yG<_Yc60@wAg4Y=DSdk4wtlWXRD}5 zQuf;$mT)Rf#>AP)601=#kTm1O2R$167MSD8SM>K^LlrXw50Th)I$j;GI@D4W(hC2S z5llbih}fmP=qXBRX*ondN8a;FEl35?#f%v_ zumT*X?e9ImitkfbF1$@6h>`F6l@m0b^QEw{i$^^c++Piy3VcHjvG=!v?4L8^p^xhteboP zw_bicd0h73JO{8ax@f(|6Nh{S?kd2dxX&_P+1?L6UJyF$P-8i~Wh9~hwf2-tU-V3u zrqJ=<+il9$Hb#}V%xrm|Jy|`S`}i=Yjyg5|<1$GXcY@>I3sy( zmev|zyQ-QJVoUE2*T@12h1@ou3a?CuHd^*E+3_(gC~_wVBtN_fmL>=w;%sqv^s{rX z!wIB`GYf$y5R;dm-^(KOLp$;jt#faAJeciCpoh_WHj z_)F-IJK+4G*%$c+p?GGq?+&XjR}~Fb`|80Xjt_Lc7GDXw-xD_SZ8Sgwd%img<{P2> zI?beu8QkCeD(=|ZjH2ymTB{UWy!p*BNEEqoxj7a}sT5%_VD>k4YzcW8V@ls~RQG`H8qTwN^ODgOt2ru**f1&tsRzt}6Rq z+_bCOj{p7sgLt0beYdr(ZW<$jvzDKamLEv(&-)w{G?=Ykg`GMbXOxcj%8apCWSGHo z8W*N4EcQK&<$nom)x#=FPRtbGll6aVx$L7-yjZC7C#X`P`~62*G9RQh;f4sllqGQF zmgQ&*mh|1BJm_cVv%PQz$e*2qK+80P4rl|oGlO4rYGWW4ATT**LAWu_Y~n+0m^f#Y z2#y?vwvn?V!B^YW4V4OT@Pf(0cNx`zS%t5Y>)(wz(U1bQmciqqe#mEW-=&ySTkRHE(NE(8$Gp=UXo zcgm#w;~=XJwTV>@u=_;TXeX8Py|o5#e=^9q*%loN7JdSq58@I=W>ke(QG2zR5;&V( zQZjMvV*M&vrl96kh7%{$#iR!}N`cHo>*{OyP{qJr7hLN=`PHo+is&?%N()RWG>Wy1 z1{Er$4iX&in<FSl=x5|5unaA(`NK_Hg)5;ngef3^-X5ctn?a_P~+*7EmhAQRu#?VZz1y%D-%BCxcu_vIWxjzL4q9g{QxT&9J&&IFaQ9 zg*llJVf@#z#kpkRD8Rchv}Gtj(3UvO-(^MEm;K%*Lf9DZaZ(ZopCVZ#H$dl8=t(7vyS&@5o=4c<3B>6N>T6u zw@awi#YI`tC%r#-5t!NU#M0yR$YZ*K1F{GD6Q}nizFA9MU8a9MK;z(9`QyVxwMc8r z(b?D+w?hwmc2=h9AI%OOvV6TNh$BaX1lPB%y$#whQucn)*kBH83;OHW#FYt6YSw_- z;9qMAO-cE?-$UyvDpDo+^mkXJf)pJZe?Rd~eb4<21%s~d2{<#u7CBCi?ETAsvEqdC zn%=XHbMk!L;>BN};)cS89qyljw3ErIuD9d@!Pv>*)y^Y-|NQhVR@bi7jsRtF3Pz|U z<_)$Sy#{oB^vBUmCu8YtvY0UpMf&5V@D6_$ukM0#cDg9>-L7AqzpO0ATs-P4!`E61 zKL3N+CPS9kjlF+Evpo|T#a@fGXYy79wC3?_`+RO5s*2LQLO+gz-|#}ul5OnN+_}4b z8}IzKNwaa&Jchq}Z>h}Im4qm%LBpS4L(&jYl=C9`+y;U6hUVY(yza@da#BOwOjt7h zq}jk8sfaPX?TUke>sUoisEdm|_QaKS9^KfdSIvL0JbAp{+hV6UZOg}=s8mTb%s00m z1(hwIdJFDzPd>=YVKw|)6Z8H%*xn9p5y#ALoLJU=gookTIXD&@9rzL(&qg_MNhqzF z^+}$JCX*c1M#EJd=hatraVjPWoZ=bQE}DUy!5le` z_BNI#{$4>r{w^-w^u3|ouaN7=XRvQ3C*IPsL+HZH)DT86)~kRjwrp~_q2iwSDilOP zh1qER&zQ=}v=OMahrJ%uJ$1@fofv!+R!_~vR}iUN$Z;!%&1l1g>EBQ+?=2L`|*kIwWNXh zgyrR&@Yl3GE|hmEYra#3^|b<66oJb)ZV3IbpynMxl$j@C+(+flVwRF9d5>Kzuci2M+0NI|E zR@c%NU{_|#8S8UT-$qlOYUch>s%?#!duVAj_(li&eiNEQp0C?PHdswP!?_g^i(TW=$vJWk?9kLyjMNL4q4{Og*4K zUi}#hd)MvJ*wENmRdbmyH!YA~-)L!OCt@|zd-kHpzYX^=L~+1ThNn4$QVW9)H0Qa?f<(uEi~V;^1}P)x;EzQv;;NH>!a zGc@4ske!)XyU{WoNJ%90ssd7kO&6!c8uecp7JC8m(jwFK3Ng@}8}bC1#OF!?8!*3y zW}lyc9@zyyi{d0%U^@7s{_~WG`fh!d)fp!m_k@Y8F#}?)3*BTF^h|2~=81eT-v*-ED0x98^@rtHT*7kiL%G&vx<%0P1U?z3XPqk!_y`mX*vYvw)0t={L(n&T%T$ zeNi?3E`F`Im(}GP+%xAAi2%~Le;M!H@ev8$84|^*FReFAS~H7w#+mb2&+@rYC&&vU z^qne|OB0{W<>6v*J?IHqmtJ{s9}CCIRpv(2P^IiU7QA2h*18QUu8QYLk{_reEZkKs z&w5m0EeTYv65Nq1ZaRbT$n8xq4(p#2g?{q+nsvj?)f|QUC4Ju*EcKTM2Bf)K#D_gE z{e2N5hb7iR8QiuyjyiyQrlmAJ(aNx=r>M^w^?hQ3)fW|MaA;3tlSztgUw6pSzQ+~ig^84~+-3gb3y>DSbhl`f7 zot3XR-e?{39+1Cm`=aNaCc^U+9W^6V>Ee7~M3fs{6cXYf$jGRqW za|m0$M0qIaL;n|`ak>+jst@4Zy9HiD&5A`}JuT!Zwf zHtfTstVb;tQAJ_6eT0HvjwRhNlq4>mR?}756%&X-ysg%hK7d3TP(4$`9lxW07NI0F1fMrATZIav7(`u&)@1r z=tA#Lb0YY*U9u)L)kzt0I=Ez%KWWY&6*&4?E^<@cOEnAx6g zUc1WFo|x`^bOUf$@cAiEra z5A1_;1`CM<=1g-P{uh91;?_3R%7FzgH4HS>|C2t&tW-eo zn{Vk4{Rn0Uy%j-Z+n$Ukuu+q4_y#rA^$o3|qIe0HV=9Gj-K7OY+{T*7O`=sXy@en1 z5u21VEKCZ_`M2Cho?^isSsnF3NfH_*9iLbMpWO==!9B18{yz4A2}QAhK$Xy=e-IaW zMiIsibzaeSI97(W6DACKGNSsNi>>0aD(vZwgO53nE0;vzO*gEw}%%j>i&ogR}Z*df^TAb7@No@JL;vli0Cee?_d^?N!r23(SRqx z5pJGJvV%OmTq_+fZj$W}MHLZC?ee$!oX#O5AMO0zC(YNj9WI0K+t1XJ^s0z?kv|S- zo7??!%4}CjNEf!d?`vXUTL+Ijo>3YviRv-ejFL4;uZNS(CK}vC&=xZI3M6{>TGtY10MFb;;1pYTxOZhw?IBV6xZ^?d?_ewFiqD+~pELu^b~ZjtW~ zQYD`|d8ocQ8D+>?o)yD|;Y`SX69kRiOUNZIX|P@8L|<^9e8`VmTU^9&_aw}rn2p`H zdZ%v4oFm!Ni8G}Nr)B0!z>s{V<4}Id*%-VLEae!O;d*RZJ%60&Gg-%jLWiS4$C=8V zd=E2ubm6#P6I=YSw|n8e4H<(p6Z^Kq6-{bmdf6Rw%*tPnwt%&$n)@2s_GCBM?p%0d zYXwzxD?saH`%O>_ir5ZUgt~MvMna*U zf&>07E|qs1g)Wn}YEvEm{o++{Yy{TvK6o8Duwr^8?*jAF9YL4(iF(k>fjL|I(7X-W zAPef&mW9v$iY7=9>NJG!6$sxYma^VQ%V1bVzlS|RfXQQ2(*RG@OQ-BY)~@>hed&a* z5tpngb>FwVQLcS>UJx2@#MLu3p=dh15I!WtPD?1L(m2zV`mLI#z3JMIbQW|>9iB*u@!jIsxJeR<$xRR}Y z*093D7D|@(C*#bYz>2fh`%+6RZ4`L@qc}+)`UMHD44jK;A=D7`M_69*qPS`GXup;l z-iD^sL3z-TVb!ND)Z+_dwr?ZWSV4cbq!WR#rLy!R77GfBQgB}p+i}@~^D+lEFZ_A_ zXMspMi?+Ern(fQB_5g{Q6?dF>hA+QSKbR;fzer2)!aLa8V++0{Bvw*fx3qWz`S7PFT%7B7ntMd6IbpAO^NU}J15}bBC8n>zgVS3eEXViRx z!I%o=r+H~jHVaIY7-(rp4T-AoPr7+h_)pZGl-~NPEvC54S^zczs*0P&nT^k9k&34= zHd88h;tD+vqV*y{Vhx4MLkMi{SGrfpi{Y-xfB~F>Ka{gT{`s#mbS&3mOC9+Ua(b|LN&l>5LVv3h8v_r1cBgX)7xfDbK}?koPX@q@{+?lP|a zVWx`7V&O?a3(Sa0AiFW?EV+K@qzKH=cTyVC?)RFBUf_{^3C@5u;f{SeV`+Jkp^l6| zRa<}>gLKW#zlNcckSy_^^CZ%<4c;53lCZbMWou;0DYrY=CGcBYYm%T;LDGdJXbIgY zg6S1(0p8SI8>qsQI()MDsijI`kfCjkwRoL6bc$9wM$Z)xI#X5ci7D885O_FGw96k_ zJ!)yn%F3FYoOF8>RIO?<0`{TMyV;5f-F~lJTe?zaIdmF<%*`ykfO~AiX_m~UGBIKH2gUgjNia-kW2nP@u%F4T5r~cTA-?xVC}W3VS^kLwYq5G z!%3l5qWr$%(RiCRLH&Kk-5;zl2Ad&gT%T#84WY915cx za~L`0lnI%T2|1@>G3R6WJwLzO?fVay9bV7F^|-G4#gNp|!)N0qfobD8t*fsg7q8IY7x7~k5QDE=mnp7p{U$v}KS1&`=yHWC~h`z|jL)z!VB+(Pnr=eA{bboTg@{jF_XzP`!!+0YVhv@KX^)(1+ zV#t+JzEsUxf55BnQ@WZ6WGT1FrhP~sOcKx8&EQBz6-J~fH3@{VxOYt|;P$sb5hI$MP zIeXRCl;6?>2}5J30&x`e>h0*3pOkvy#p08qI;zZ5^^##w40Uc8S7Gt13kw%u+bEwzB7T zg0IWspnS5>hlhtB-_C_0Jkr?FJ~@UN;GToVsDgufTsz zL@(T2WG9!S;9OhKQdWFxOJtua1I~gtO*`vy2KmE;zr)`qeWGF7uLV`K7Tzfh?79L; zXnR?j$p^6~52pwy*mOYM%}Vic%t<|%)41X&f-}|&8w-hrAa7Zwqa~*F&PaY|q3kSn zV{I~uWr{PC7QzC8g1*%uIF3JlYy@y5vY^9+88&@KegV@vUNoQ~Nz_zVuMgPlUL5rr z`~i;@foUJ@_RaMi^HaW(C&i<)zDKWh_`C`77P)N#li z9NC;1@?#WCQ5dHlx2MazD0lM=3G>@nx_8tClD+qS{%<4G_<-en@FNZFi*Nlj=+f$3 zalNtw_Rz_r)Rpif*p%&=iE`0>rodKJ`ld)60Zk5<5yw3ZEF&&*?ori-ox0&0Ev%T# z>}*jW~X*8e#R?)n6i4~nK5x4hv{-1n$g3gj6vws>7*>GVwewMd)E$oJI& zl+8*91kQc{!u*}VX=P0n*8Ze}VDHYo^{0cfm9jm7t*WdU?cUnhfa+eal}~i$O5jk* zJJKnbDCw;Ht2t=9j*V1bf1)OOE`U<Y2d#;h6y(~h-!7<(vc zF0}Fa2(HMjJY?$e_&M%lEF@;m-C-`4bmvsb1Iu)q^jGQY@Mm29qBB?b|N8fS{%Kjs zn30IpJ(Jlqy!UzgzL1Xy&I)|*m)Q&;kf{f(y{*pA3j7hbd;m;#!13efnu5jA$SP9Z z6RsLV8EIrJwJukxU8D`?QM#x;_DgeUVFN{8?{Lm2*kMGiDnv&1!7)xebKz!E7m~bG z5khB$JB`1ofiqzMx1{O3_>>+Z(RF-}*<oT=Ty;*Oz|C6}~aw-%a+aopi->;Uk;$&KOW{(d=Fq#3_BbTpR@I&@750B)GZu0p{+mW6w*z=8uuX1ee$DTg3;>>0Fe7}ywJP(`LN9Yi2h~i z)%-MAT%{Da^quJx!hpOvp;xy#Jc9}LX$oJ3I$>LCb?$+yX%Q2W>v+QVLq|53f9u;5 zS-rHJqhE5s?_T0XUZsXlX)oVVLWbg^@`kIZHzXR@oA(=;rpQjX4KsHBRL(|qC z*=rz?O;7JkGZ0=lg|)Euwqubs4Rv+?s{^~UdF{F9^?7)RK^(dXa9psZO1YO$Q2AsI zWw5fSaU0aU*w|e8a7UcTdfhgjjTZxb@U`l$qCo$(9XdSsk>#_31?P(YKM5ftTJyiI zKe7ZAl{a^yYngvG~5M1 z5}1%b5vQ0$aAB-@B8wpr58yplynC+nqzY-*M<46~KZZ%hT#t-Q^S|`+Gg)W;voy~j zR-X41H?U!b{SWRHIluFrh zdPI1*ID0$D)t~Mi1fWZF$i!*P>yy6iQ2`Xr$L(f?m!wSx!;1$)s1nA^jhuOJr4pBx zmNabvKj8l2D5-zd-^Ma4WbD>+J{$X?-kt#MYn&V$0`73buwb7owAGMh@p%2w)S+|5 zRGbSQB|+IQDr;i3ya0?d{?OIC@&*tk)t9-lZ{DA8$2qo1i9;p*e=LPmr&~~y6b)cl z7p9d5um=FlmvuhrJbPaMyrXxZsh~pkw~2`TrSYbN)&XwqP`AOz$)%7g&3JfeS&4## z`uIgxF=K8QAlJ_o-)lYyG5>*Z!F*J5Q+}frv9j{FF0jd0rza6ahjCqX3hsuH>1t_OaD#ztz3Uo0 zr;ro9`)~K8QRnl%`^$VK!6sfr#g3h&+KJa@Zm`wP)SS6+|FAG{XtF2lb}w?fSC28u z$~c+)FsQttE$W~6{ZPTN?l8?wAta_T@YFdDt`l5$$xvhNb8$p~&%jlnDa@B|L6G8N zKXp_Odtcf=SS|fPhlslJT*z z$c_1D$NbE#@7?#CCB3O#Ue_I`ws zhIi9C)yOI6plN$XYE+#>s;_+Qt|ktR_`c!UU3sD%?xZgr57V0hMNID+Z$b6GGlJ1= zHW@ceW>rHdKY|Z;R@+ft&3n&7kLWr(@vQ-LkLqEwJ@)5r3oe-l`l>T1vY~eziu_gJ z#;~iorEvqmkR!#@2{0AO5&_J|ii*#bl_qTVHrTk9`;8e=-61j$S~{H|NGbZ_$n?7@ zJ(uJ6Zl3HN{l;=V-O_S+eYbIvq4I-M|M~?`BV*2El=rNvY|yu-{$fv2IPVKrOM-y| zPk6SG|G!^zNu^f5aB`X3EthB_knb8(nJnL3e(M-I>Rv{-!eh3_Vh(bS+?#=POW%4t zZ2D}nDZIUV@lLg{|3w7g<&0>O=8y!Fz}Cm@58y$b;eHEi#A!cOJBP#8)I&q4^Zmft z|G74^HPuK>3fK5pS&fe7tz!;ADBT>v@#4|*k>BlaY6}K!>c1KwE=! zl2^V4=zN^|2q1 z8+|8z*y_Y^@VM9^Kh4!#_QEMcqfYFb$|95msYIG+&clU4xP)6tSptHTxz;;<4VSD< z2oT!I?>)0hUF~oF*Oq{?%19@i2QfARsLh2dk9sbFiHZyjkXaD3swNN!b@%z|EttTg ze~Uvs*5!7IGbaBRwVQ&cU!^W?%{OnU3CSjuWyMA5rlCL(uX$pIfaDI zW(C!c8`Qk_9{D-P=ZPH-7Ksyqaf!j(PzhGnz*jaWIorj91W<|H^mHYcrJ#T~HsCrt zK^g)=zZ1fS-iG29y&i1;=U5((k_j3w0)@AxvS?1s?dBGFPa#F~(dJ5H`tBDD#QFko zI=uE6*qcypPv&U7>*++0Q7rmXIRsT=dl%pOvFnaAzEsH$g<;bN?34sYel%IA zkS+qoCCNsv{(9182;owSXZ5YPRh{-lqmTa*%+eB|4aBR5mjb#~^E!?4Kzr8l3#TCO zz1X<^V0c`21)C4O-v|OWz~n6~RxbepF8VtI53{11a|)#25#aJ!-(XG#<|&4clkS=i zZvvUR)L#$&#fd<13%0ax2+yI}dEWuNaCEu|#O*!oRu%xH6mW|QX7>%sJJ)7w;9n6=vZu< zEfM#)9)R0N@^&_AF*cN<#B;{|tXMUb%*1V2`uN(`VZ+g340~=y{MU1MHh&5e1oaM- zx4ku2>VOE;{qR1R%Q?^~`gSutXY^K6z^=2swa)#eO|#}}FTYcnp@R7@Eza}gPA;)W zjEhWRQ1eYn^~OK_B}yvDfRs$mKVK}uuCYYv@A_Q@6hF|$_;5&u=CCvHLi>Oy_ix2W z$KDp}ZNSdL`qssNW#TbNla^U{8J7(pBXO|CSDx>?{Ye)_ zHSwq5`#}q!-i<#h!jWgSpcC)adDxlVt1HPRvZa5Qv^9Q?+220vmh>-AgLC%%{%lTT z#PY9&7iCQ=S@#Y$N0tUbgT@L3>0P@0mTM^TUU8*|IJz}#yK694Rv!@oyXH1%V#0-k zJ3*O{?~A(A=UgFZ!|xhzD1WeCn9D7=A{ok8zYl$gRk&8vO2QLeFWaI2;=YF)@vjOI zEFVg<>3{$BIt~zRe!E@-)p9n)&#l^|(k*};;hT9?^{icj?sZJg@=^*1huJ-b2s<&2 zqMCOB@?P(k8bf3yrdaYg2V@FN5L$&Bw<#VmjQNq}`H>riGADjnH21OjO0s>K|5dl% zG#%?#^R<#V$JC)~`w-?}b6Xsrh>BR5?`rkWi=K^3`W_C|0(lY|zthD2NYHUEFYybow-r``25g&@+A$v-%J1X1B+))74JKlF z1w2jP5k36(GH>-NRG{sVI6OL8NWqxf=i6$(c_BE=wkDUnLT~+=qk)_p3;IOc*U0kZ zXBNtlgxs&HE_$GJa{N)-ax6flgx7rK#RtxQyQ?gLU)6=1cu5xyN=tl7ua=T{BPd9n zU+Bs&E0QwCTZLD|w%F!1G%XJdz%PNpZsPO&G0)nu3#CJOMx2>}fF(*Dm6bzDn7l43 zY1%f=41>V(Ko6Y#USFJC=(d z_+hQ`JP_bil!u3@AbzmxjQpgksjhiHqEqkohY0O!&#h$oP6FhrzR9UGaJ(&jG%Lh@ z_*7w0*N96T7la^h^1edZv-b7nzB}@p6jnW0V-Cg5v;Hkq(s*DY=*>0B9(nP(DEX?< zu&Fn*1^wzU{o?UgS0&7O%uU`fU3yK4Y&Wy9bTx;r9;PRvSE$QF#L8P7(ssrRN&SJiY-^=o@ z5hKVWaiI>V2`_QD9%$1{JIMjWPF*M$?g2bAN!FI&+P@HFZDl>!k(&X)g?}JFL{0!g zQjXS`;58cVW7pk&I%i_#mltx`{i9)=5NNnV^_V>oPf&XIY226J`(3<@z5!2@u?jEj8=PeDoi!isaB(4H5Kt$6-M^azY>K|JI7v|l1S^q{jjcs~@ zX&%}7g`d&*94kOm<0Mq3=KKYr{sW!6S)7oh6Wo;u5P&ar`8SUul#`&)qCi;2@QzmMmF3c zL%fwBZ#BHx)dlKlIUy2X)DjRU)3(Tzk>Z?~-PPZahtq3|dpZC5k2YD4I%3-2zQU(M zR(TtMXd1b>m>wM?)izI3iKYs&*THcj-adun*?qLQb&c)i#*MX}Q&$h3!_PnX_}~Tv z@6TgIfHN*gBv|Ap*WaiAX=(@+!5z_s52s%#j2W@+%M{Z=2w<2YcOSH4L~PyNwmzEH zd1|nb#T}=cpe0HbU{9b@!yl`8ggQ?#t)ZT@*{H{?(-;Ne%jkg#s-b6bbw331+q_u? zt{Dpv@IhhhV3db9xph%FrdC!jR0~Ic7G;Fn@Ow+Uj(Si$vuWg4`RQ=O(hAIq+j-U7 z`A5y4E|k$d;S>+=*IIfjAR4sb9?7G^>leL`) z|6;t{XlKOp-yL=MXM)y?;ofcl-_ToN5X-J_B-YOF{W* z>$`X5-(07ZR0%QBOZ<7cN=P9SH%!!MWQ04ZO)h$0a3MF*obSE-9;34-9&|0J4Y19`=2qGXh5+$ts8r~;O*^gNn{i8bgdXnMcG>u1X0xAz zw<+w{1Xu}-QnPQSJ70~frvi+WbJzl1M|Jou#ZecHffe!q%_23D?T zqmFn==7fX2K!%NS_EivEM(RRDIREZZBgCtEZwNN&r6xg6JIL7oP>TH$=}~$#LcgaO z{tw5!w$rst(>{7Q><~j5PeJ?2fBT8`&T=Psx@4|{FXm$)?>RiGw0Lhj8jLiy>-u`I zT-};Ds>W}vbL?E~Z#xkY=U5)`Z$zdFN39FSj55T=1O=^nmTmyWYchJaS7lI>ruROp zipn&Fj1^LaB4@t|JV7gB^`>;t!D`a3&*?rL{ZZ=2gueJ+v2j0x=;PfMX52qu#Pp7- zb34@z?k4H%7wa|LP7mai#ijUFR*)3tPwkC=u83CetEssb*vbTj>$ZL!luT^^vi0!z z&!5*#*jmwKOUoN3NT?|r8`2}IYT1RBtgw}C?JyF#^;aS1@M>{-P-IqC){V@8%JWE! z`I)BGJ#TPyKG^6P#u{hJ{UJEIHf^Ge(@@y{wu)#pl4>F(oYCN-)Mxe3jmae5EzkdGub*mlbY9pbq zYRU%_#lNfK#mqnO&aH*S{s~KhBN4WdF1xJ~g6yU#6Dong0yJ z1A;aVH|c`(;x}~q?DH-SMx#phH%^Y!!m7VpS^ID#J&%68Nv2CB;IP_;)iRuODzMunQ6*Wu)W( zyJy}>DJ2;^YhGzP>G@jOaI~lhhV1=SEQmq{DaDydD!6!s z{oO#(py%ZNyjjE8>O}2msb0+W3{Re88im*H|51=DT<1S`({pSgD0bUiO3GCaP8saT zirmh4VV$o`fOlUWPz?>mhE34LwQAVZm79M?7A#}8^ESP&^G9JGZ@R8g`o4|ow(Z`!&V?y325 zruTA6u#FN=nJ&PG!#<+1$~mxeR1b;=0vGPU&UyvUMog|yHoZYPR(J;amEVQHjZapx z0Fxd!0{S@9UFv{=IX=ZO8Efx-fwcAgyfpEqWaq4=%wCg&r6oYJO9iynJ%;FtF=t%l z-QVALLMUJD7J=nkaKuU^(VBGlg_Ev>rgG>@5t^*-gw5#$UGES0<8bBnYm_?Rj1kgc z*cuPu^zv`wEo_DnvzmS74)>#@0@kJQ50YIRXYXFhl=OKf%G zFJlQnvG{IBtZGaiOmqc33(}xO(y}VZ8e^GGBnx<0F)2_Y5o04m(~Nz3k}2~f3sWWw zW?mO|KD8S`4{9i)2(49j?;v{rfk*9kVuQoujQ0wcNeVyO%#s zRIC=ldgq4h^pB_N^Eeq2`@0cbFh&$`?wU3XaW#I3P|YI^m_V5%Uc&R~i$C^?`p>h+ zJx&!WFDnObF|vR4{zljG@(l{ql{xIP6sewyl|Gjz6*M736dZqou95ZTf^9!x8jpNB zXM-?wf-7f+K$=v_E*7tbMQ#1%XK3QS3JgN#-&|1Nh~;)JeGJosfmpU)o|pHJS5+FC zjsrg`%RKD$~neika)-CaMnOijN!Llw1G z^j9qiuABJ}`uqkyV(;G6Ak(S^0N=u*6*wZaP_is?VK z7-(7JCqgmAn>-I+$lZ?E`@P_1hG-G*xMVB@v{Vzw`!>>e+IjP)P0sag>FGI z*F)~#Uz(aina#X#INYdmZ|Gfm%F2v+%J&cr;r|+i=Z@wfC!TT!zI( zJfhc4#Qg`pVc+aHXJ1&;teQ}636OSOPtk{!%F1cbN)+_qidHisu=Ja!3LAz}(k)Cp zX@5Nw6WczH`^pfzi#k zjz?b8HW_%NT+)MU%FYYHh&<$%Cl6PxjvCE`a45k7R1YL52z9bSKX*;K+Z;|rGJ+el@N5zr6XW~$KJU6+7`h`5 z&g=#@S0zqETDrpQsIJ9>0(}J&`|a_dpyuD(;Uy$=)jE20J!Mn3CC8 z6+C+;Xv$_hvvL@}-{hpj9uLR~L_}MadkD7FLsMvbPb)9jatP;)%S3N(QF!m(3WPC3 z<4{pMJ6(>RsyT(;#l@bl&kCn*Z*hV^BIogj$cDVUo?lvx&L0xB`s|HpjyQT=Mo|rTw4%C+`A8J328d}&vm#nIrhgz`-HT@ zelj+#tgI)a_Lqv~qP@~6>A{e9D4vhcj;Zw_I$%yv#5*e19b9hqQzcoF$C9}%(#2N} zM<%o-WMQWh=ATPmJDeVF4wzjU&R$xwZ$5OWk>X97`LXq=|9C{|8D?Jh@WbwF(QExn z4dFK8OO(Yutj&J}M|V>Ml=`#7`2oB>YB$YGgomnlR*6;;$m`PPfk==_!5aTs42pZiu23z4n>jnL3NlmZK%zsf1UoD*YiVd}b733-Q)P8@wEpIK9=&q{*V01Z)ylPI!=#H> zEQcg`o>gU|%e+YSjdnfVVS;S_n~Ou8*Myx@wAR+6rekm0*enFIhCfTURI+oJ(bI*s z5)|Dl4W4l&zOc@yDnU_E$P&^^xWugtcS?g4d*}1jcvjBQC9}a&UW|uNQ4zF-)d}DZ z6f{o6>6-9&`VWS9{L~p7xvP36!<8R5eejqw-C`mV#zg#roz3*8eyv=iC~4itT+Ze@ zHH+?%hcpFS!ORd$aOGsJ1V>9i_fGtX?iQ%3udl4F1s0$g0NX&9>(j`9_7!0>y%?c9K~SwhH&iD=y-8ddYX}e^bZc z;NUFz%<8ntvc2|0kXzUk6mHy~*r$$??>eZo{Z|@){afK+eOY}|*=7pbA>HzIfj_sf zkT5^vb(`=k-oh^9;dWV>3FVF0d3NS9f}&v{rA;Iu4-ild&sg#p%zAM#<@CA1T)fYc zp?Y8IE~mXrN>$)#ioOjq=XnT9@3X{8^ULTVg%?~+rBAUq;caAj{m)#2ATe=)L`9-v zUzL;z4mJ=jVAMZ2UU*8ZEBrlV*|*`i4ViEd484R}1f(>Vluk)ab{Gu@X9xEGw%tGwd3ox3lJY5y``np_ z(|6T75rD%rtVH}GKm(>iF2jg%%IYdx+a2#f7MCD!RHgv&&E5aZW<-+|o^O{KnF_PB z5n{f_x6YrJUsQ~Joj-0h`geIr`a^2UH7b>Q>}0B$gpEU@l;}%lI>|zGDyM#{txiFM zhq;)pdIDTe7q>^fWv)0OGAxz)cnN`?KNiV*S^L{Z8-g*>v+-l1m*KfoTa#C;Ksb3g zt#R)lYP;)ja(}N}Gvc40at;zF?IcKlQ`na|J~3irYrDT_9kaVjD-Y7RfV*2hsII2| zBy7X`s5NFsrgI%toP|AMPPDJ;t~-q#_x)C%s)C`@?}}mcImY2%(n8n!vw#pO zgL^7#%i~&6-PpMQcO*21Ns3kye={HhFZoEoZOFcRV*;494t!s`c`aQr;I2Q&jhQ<5&8$AN+Wn z#h=V}7^0L^#AXQDxt_qM9lYrsvuzEMMPtH2q%^A6y$h|Xws$0F7n*ktCimlywm1(L z?j1gtJDRaRT#4CL0h}nlL-6^UNlD%WNb%->ue>3P3%_yl1_(`cBw9MwI8OAbaj2|H&RMsqF18@^nQBP-YFGnq0Z-im2+r(o2&;1)t~6( zp7womV1j1s1WN)MciAs`b7qcJ_`c$(jz{R;g6xI!ujb|^TA98`nania(s$xHj(qoT z{*H6WrI&8uBdRJzl^pRO)2nAx`IA#%7L#n6l*`Utn&%2@oaL@X;cIMwpUFr6; z?8%iH&8m?v$oS6{|CmYteG$Dq&xPwaLBXYz)eLIq*#WJk){HFyB(D@0An1#OI(G`c zOLB3mnl*SN6i=MH`cYY;Z{3adSmds9oaxW;m^jU^>;GH~v}l>D*S!2-7}YZzb#S;I z!_NE|P^$$M5ifN@)rc^4 z-LKWA{m2!sTAY*{wmO>hBB$YB6C*}WCV>9e&+}!$y43&&GY8k@DjqJ)>`W2d3#*K4 z5@2%;O*Ko2h(B~h{rvfJDpQ77*0eF;hl+(?;5|8Y-^SXIPM&M3sWCaGK)z$JP*OM(6dSyN6AcW$~yMD9wNg^8St~;uvHj(w=eO(#q13zf|os-kb?U zf^u4+t1EuZgPvSCtbbbdn2n__rXVTkX#Q)2sxhB`S{MV@BD{b14M+2~-2FWw7?_om zl^#hp@Ae7*imcwgv;B|qY9wrHxo@%qu0#iaJ9(W(K{2z%HE$I+Z_$tDhlgK)Gtg3V z8SjUSJw%5X&fNMXO1U9ou1+!);3rE|-P=$f4bMT-ttM=)!jZp8IftLlSIwojYG&O@8ab>g z99&r48(r%jc$1=qMq0kY?R?ueGCbgwgtIfhotMr-T`W#iSgfuXl|A*SCtiI1EHoC~rUrz_dBCRQ zxp?7J!_pT47OvM63)Z)rpoB$AOHGXpGo9Jf!|g1^{EY8ma9LfhjXP+C)iYyjL&5Y# z!r&(;VKzJl4hgyt2EWTocqt(e0%$BLur`qE`lTZp4F5MEzcmR5IrhNg%i<`Y;OP2ko-Hpe;^m#0~krBF&p*P(JMQ=RvPo@snf9^%<42XpAZI(#FD| z=W7fsUIdZac?$9Hew@kcJ{mk$HPJB7ynNW!-rgr#t1m#@wcVWk5|Sj3eWL5vnqR_& zqyC)s+Zk)#w1qxrY?5?rBqwo`dghjQfrRKs!6VPSF=l`c^v9*HK@ceejHd8D<06Gm^ZD%?GtNaSU zT7oti6RG6q@4FOhuopOEgKJ8Pipr|f#?8Qh73{xWkhg>rfF~!A+R3`V|MI$xRbG3$ zYD#e>*53Y@FsF;T`ESIzSV)_`$wM{?f}uGc&Mo?$9#L`2kDRl#d<^V`lBN~!GQ{8U zh~|?FVV8-B*^ zG(E1w3k9rcy{E3P9t$CF4F%ixSPfv{ziot$BXQu;`ZuH=P;Y!fv81#K&~v->$FT4} zZ}G_SGPIR()?6Jr!=hXIf66U0W^T77pwa%KDhm0f&VZ(r_aH`3GN>{|E8$%`!C&_hLYu4-#?wfq6t=@X}my&SJ27((d1e$zAI5tRxk|{;bv) z{l@6Q`?U@ah9|dCPY=r-Z)QTbyUyNnt*MPZ)8xbmFhB>k0!+ya@rrR;)Vl4Ybv?)I zWv|leIEuen775N}$j|&8`&i^u99;L7@rbOslsm@`_QN0cp}*A+w&NZ8G@2_aoh$Y? zXxbV%eOcz2$7A+lj^?h&eU23gqB{O&I}KyPe7tGJ&x+Cx{3FZ99`@ar1lVMZ#)GY0 z1&#gvzDHLM>MzpPNAAe0sS6zZqX7iQi;PExJ!UeCo7kk?Fl7x&Wmix{elQYY_%))K zKhN+@eFoMT_CTTFYtL%e&K=Eu6I(jYkw#exD~6s{DVx0Nz8=y*+7DvPhvhCtxcGR6 z|NI&Kp9^We!#=p57SoTcsk`zAK^x4!t}k%VB9=9#bc z-Rp}UnjsKo&T6!Qx$Hntb^!zwc9w*8dyv)iKUOq8cDiNh`nmwn%$n9GoN!VFh;zgs zKq1CbUTy0NUZ9_V@Fc(?&GnTM%wW2&3BgzWIb3}rRxG`)2YC>j;rP2`DP$Cku#Gy6 z;O4V>*?fd!32Q}ZVAOM) zU~bx#6_^5lZC1$RA}*fyO<)#(D(~Y6PAPo5-{UvackEEG+8K^&Wl}#Z4+YB%M!dU1 zlPf7N9d8PxjfYN_7N3WSekVw<{;Rj*F4KG20v#H_p>rsrIh zV0_-smVX_PB0Wfzmq=_}nHZ{+AUMa-v0kP1O%4}aFO9cBPn)z!MXcQHYM}m~7XTRc zfqR^uS#jL?PUbP{sr`f1o&0n$e{PzAwkd6PL7#v8{Z-i&QTPM6>D_X+w?M|hP_b80 zE~a|PUZtuuxTy4h@7TF=({XStZAQu@jo1B~$3g9*Dv;#P|4%Z@$~*&Di`jvAx2UM} z8!JN;Cqi}ak)Gtem%Z|cjn+6!w{%s@>V-)da~qjglSr<3VTjecgOQ z^fwa#c;eD6C^jY@HW^J0oq{eTI{}XWIid~x>3hjYCy<}2|d^T|bV>0AL67c*k zYJc}$4%Ys*;8`Jc27exOdfIPphS;;cJSnsO@9∓buE4rzY?su|GI}h5QnI{Kj5u z=@{Jk16X!%(U?AxpXi3c2o=4V$tO89e_#VCK)O*mT71KI(GE=i_Wsm4k7rrQT%i>eH3owcu)T@rl3(M&Pwb0mC0UgoTU8|cbbVXsmqNXIOvGua-Oi(} z$sZt$`AQc&uVMs`(%4|hP9wrI5s|6|)hF#y=xwT>1fiM|-pT?J&CHlvGOt{1?0Zn` z(ylEUAJSnUO)fnoQlAyr5@|UsbLEQv8B>YV(EhzO`9j6Ftw+0(F%`jH7gEkKk^==I zAWR+wmK-gu18c%ZtHObldr^L~ODdE9^EpXZHjXFm#b?98AjLJwC{@U=VQXe2&^_bD z3w%G2Y?<<`WTdZnyT0lxwPY$p=;2rHf(1|=1m1v~d&jSOJ81jxfOWRt-%6&sl1`S z@v2C6uUl{Ts9F--w^jp`WKB8hc#4BaNdn013E@+cS?r*Y7A$b7O6-hGERXK(1!=p) z*}7!1nrhWZJ7OR>xH-ZRSE5XPSyUt-i9tNF=yoU`7*A# z6%?t(&|CMxAzBMgjs{_vpx@8I@YHcLnxA4o%jq`A7m6O;TwJ{ECKMxhtfH1O*%-`s zy5_5VsgFX#;}%xrz0kBE?UNWQD_1KwQ5cH2uIQQ>$#`IdK$4~2{ZtzU`IM=yJ8>e_ zRAAOC;`NOHMC{!|QMt^(=c{+_g)-`{yg0m_JyC4a_rG|OTH|Vxh7(IN-cT~l)Z7UW zCi9-j6)yGme$Y~4UsL9saMB|NI z5KPD4e+zKg0FTYlTFk)}dL|*DYQzxs;c5w|ylGLr8{Uzp@cFaf>~WX5QqUaw!pPIK zwi>T!z~=_ZQOIe!)?8H6NCb^!*<>*~KYZ2!f4uj@Ca=i%56d8I*R)vN`)8=w8Y^=Z z)h5+z0iFIneY>0*o?+&8iTWzcM0@w5$l1=MiV_|PvUphfW{ zWhB)5o8zNKO`S+usnPBG+fAz;nP2nE8u*Ml6Q&BhmB%b053caL=pq1~6-kL8^0>%y z<(7F}{Z3i7+q}P$jpn`do_?IcNXZIZAJO+-x-=hoj7t>H&ZU>|cD-x?%Q(vyb@{Xt z{&kHWyj#ql8tkKzb=8`_>0IaMbjx5gbTayvO0s#kz&QiJ+wZAVq#kF`i!Sz5mMs<) zA@U6A{qJQH|1DI#2xVyRY(8%8PW$Z_!&uw+Wouo#M-CqYgWIHA3INEu^^@ zZ+a=7Z{8GcCN+MJ-kq7Rn$+Cw9%HWdy-U%>b9+1Uzn`b-?EkAOOrm$xjFRD&dEbsc6w|$P6>ePba1ZuQva>u< zRvhudzSILRj}@#B_vb$$5k%C)1v*8n2t z3ETb6MavALNF3AsB)9}&YB>9tDclWz3RBYhSR?#y z)dy#sb}Z7O2$^?7(X(E9~)bs{y>M3byG~=))!WFNFIF*@%JWocjLc~0|FU3O5 zP4+(vzdf8_MSk%j{f!j2VB#`yjpLfZpT;%Rps{n|e=<)YKOrEPrbR~M>TxIp6SlEP zyqXqpQ=SrYv>mO(H$n+YVcH^>TEB_e8DgCa3kZnTbCsyF)2RJWD?g14yLU=Yq%UA- zv#P7)8#(9TPts68px+KTHD<3W=WyeNPw|@bzy40)7qcG%-!cB<3y`{@!GM#Qa1O!R zdjPx8{k}iqY5y(nYi8HtI8Dc3NL6=aSgB<;4b;`hb76jtzjDHVdP}vn|o37pyK+7Vzg^7lmz932`h!~6I$(kwwgi z58?Cr&)_v};Hh%8VTSB|eqr(JQ^lkr$)bs1p)qKyB$V8A(nQ+31kSA2_~ATsy2aVr zKF4)rbL};J23#Pz#LP`j?cQOq(Be*_-}<0HM;xv3H#g?xs?{=FckoymW`)3QXd~M3R;({=W93iplADH*=_kig1Tw$E z&5k#1_2vm_gUJuipWk>T2G6Z29n=>n9jiIc<&3{}?OIPIJCmK=#hj?szfI+h>zn2G zNh7{Nld0YP1zvbG5?51HC0qP@t6_5AVZ3IxOBNH03Y-A-$mC} z>E{vX-^Ll8{rn4fyyFrT7E~vaY{N44u^Ip>?^-ZdjMDg6{ewcqqox-H&n*#4K z#Vbs4T(SLOCDjo-JN?&UwtyHhP)tDx9^cIe=%4x`Zs~_lkvpJ=s~N0y|5gqUy6!{- zhg{JH7k*EJSy>=Kiox4P9RXO)eTeK}Hmybzg~Pe#8aNyA0o~-Qx6* zrCEcxY-bD)zkDk)uFQ<$0N(Cud}n_=LNrba<8l8c1?!HtDl9B_tLi%1(fPM+B$vvV ztm{zylUY_AY(L!YWX+?7ZxK9+5rK_-o-9+o9km7CSYK^$U_``ctZznAvQoCF!|!vg z;(UMSs`#EqOC)LMeT6E`Wr5wV>m0 zVk7UGw!}^S%fJt>4bn^Tws?yGDI`xB9zNU^)`-A$ksPq|&V z!FH&$lXzV5QLV3hHplp)s2m115h<*RY3^lbMt!^FyaCaNPQRD6?lG_*x<9|mE%4^TU=p*kb`MwqRoEtjW*{9_@8I)!zcxk?V^^wzkl0(??W&;ZU&zE$M|k88yu)yO;ZLp?>M zNQ~*QbZJlj*KkfIL>vNoIt~qW35_7`qZi%9>?J5sHe)E+qTDFEODE6;k%3 z;cYKtDQiQfkP$LMhLT1m#!~j>cYl7z@$K(wIObXI>$+aodCF%dkB`4a4#%o$Iyn(C zUVB|XRaIT?H69Y>8y%Z}1t$(M|AoK1;mNEtJ}m2!En&2ZK~dhG%|>2i2w3Dpkny8{ zV3|{AgY*>5Y)_)!1}*>UDjzhnleffk&D&tMg3gMVJwgDSFZyXfnUciQ zsH&aQ=L*F(mg>RD(|67m3=9LGNEP){Z+()bz!ulf6|h2CO|64Qr=IrQX}Smf znL92dBEmTTm^c#NqIRySySqPKL2I)kW{HD*8zq)-!zxE&z%j#rp)`*=Qj<7J8a}tZbP4nG zLqTL2VSGa4;=r}vWa4k4@oar*&Pqx|NXD$Nc64BL^h&Q!lt)O2ipkZXax=9!h|t~N z)n%B?5T#T%Z_bZB6zPEF`{YyYg?Ws<$D7Z60u)tLTjovfH}!x`0;pCRj0bY8oJ4m+5O#_x zVEHC++R0~98+(}Lnth`9!QX*McgFN>^(?;gU{?|Gs%EOcS434bucC|omv5Iut>!u9 z8p>WDHpEEs;t`K8f$Gy~0!5W7)CkD#*cp=Y0nAIQ?l;c~7=k!zVv|0RmuqLEkcrtR z?~)BPs_={1O=T0y^77>5(*~iBpLz|NmXLZI?G%O;@{ezC42wjqjHD0Mm{TjuXV-g* z8r^M^CU(iIZ~3h9A4>DW@js0PQh-*W#BessSN^tF!l%ZNf${di*vH7|mz2pDUe;V3{`+6z1wHKBI>m*AO9y{T zyuaa9-sp{u$Bm>faA`O?Ant(uh@ zpKRb^B#VP}Zm9J7zZJYJZEoc31>bd2;`;@T)9Z)DZBmV#Ke>{~8G*Li1UF3V`OG>K zm2Y*F(Pp{qVu2I`{6Ocw={qgq%e^X=IVsCjL5(fPeSCVuL9}PBEGHP9uG!1+==tQ< zPKyTVcckCjX9OS{cpsiDGk^U8`iS|7N|a050gV2jvh6UyZ}XP1>MX*tOWeb!7APJ+ z_TbFBHTxDc9z%-{@FP@J*0)b>T13QVPFX7S70F%Y5raQp>2=1x zM`SRfagMfkAw1TIjM0b0MR56US_#URF87(L4DAzLn_YY3p8YR8Dy-#;7FQG2cp;^u zV<`N0v%&+X*3;Tw$C!=v?o5&Gg$o(4OD-4icgiGuzV>9bb<}&{8kMn}oV+~s^a43- z%)_l>cJl>#`uzIrUm%(g1qUhwV`KNKWYD3ZIRMpSH9K1Dc-POFh|om$+Xns%Sh z{wUW45w&-J7OAu?J@efk*XOdMvdgfK+1_3ihceP;@(#$qSA4h26Q`%TRj^Caj#I?V zqzokY^mI-Sb#`_x_V9yxuCuGFE4aze;3`El?tG@9>^(lMP>c%!ab{=x(|8siix?+w z-JIB>TDGl#U@~=LPUPDfb9X_c%A!1^ZG&#Vbtu+45P|YW4&IHzY%W{Xv*1H=Q1en+P<3*l|LuP}@hH3R) ziHLd2VSs{YtgoCsp?_ug6hjQskvYDR!vg_dfUp=}t~l&Y9Bnkgqty+k7Qb>Z^Ei;_ zFpmz8J`&?0&IXAkvAu^^Y_$cS*!Ys)&T638AivO?$GmFfVwU@hxV1MvYmA*4U+~|9 z)!JS{)p%sl$9fLkOcxkx`XI zU&W19rLf(uRAW^4V6Dy)#PU|-b-|`r<#E~(ET!Ik-XRkkIpvC#Wk;%G4Uy{=L-*|4M`so7fjkHneAc<5~RZJQIv;3c|*4=_zX@bWP zOa=*_^mRny-ad~b>HC|Os`!PqM6S*OK*R22{6i<`Ja%+!oEg3sL;o^VUwKQ6B*y(t z97U=TC8)9pgUsG+L-)$Pkb^!BhA|jCG7zScWm-!^O*K|=YJkj;cK^&N{2k z4)OTYF{s3jm<1KBsEunL@mLDlY6`;N|3o;Od)jF6mL`2{d@kZhWRezb%q#O3(mvBp zpT9d)KQ{{LrtRm}e4k`?Coh2VH>x^(FVBgd8rEhNvqrfSeayL%TJrEiqg zjoKY4*mhiK_0oVaV)#n}dJA-EclB3y^%gWVG;-#OnH%~>U=enQ?*A4PZ{EG-OeTp$ zLQn0`$s~pX7~rp()J1LfCQ{LxW7&nv-paxr#1B)iU$2C}O~S}qGUXK5+Cir?gr_$+ z*yRKb{PX40gCXvjS1}lhlA#Wl$uI{JvqUPu;Jje)b9IaA(3=p=B9wS{)+?G-QP-6+ zDGBz;mJ4v>BzqE?j6R-(=`n{K;i@@xg6{&E{mp!1BiKL&h4JMmBs_|S9mI$MRjdfNKev^#dP5+cqOO;6$&K#y*Ckb@ zGq~8}3b&uvTFXBb)kk5;84gMdX7o2f|82_i_}AIw3$@KQH|AsRqn{zlt7eEy+jjtUvwV)^PNOJK?V12BlJuRS|H=@srFEb1urq zIoC@tC1cbf#OKck0Fc10>3?pt+u32Y`c$T}X~p>A&ex16TiLxwzchxD`1$!eZ#P$h z?rZi%=YL@6pXtU1L6Dmq{uv_-MOHh&BbMQ0{Gk8#WLZ$26XB*uUtb@y*Z{4@fTiLB z5M3avOkDTu-rGm|rp7Clgo%X}_2G9(@0bgFbvlaA@fezAxG@;!-LO+qAydOh0OU5~ z5G@UjMKWuSCETJZh32;scDhkXE2?>q_9#gqc}+OuT0*dRxl6J|v^&s`*s4c3JQ@>g zte6zbO};ITpBc?Gqpi*@V3pqsCf+*=$C{nhH`^yfxe|HQ9MRtgc@wZEhw+QPi5RYs z;NaQ;^c12A(6ugkd4vyP*%1tmi#Ny5+PpITcm1jw>w%eHq`$@WBaE$~@~Ibcb^Rt| zU`!qq)%WHz?Fv<~gPQoywX)K1K%%b(>2Pf^#p4kH7jV5V?|>eASUyWcNQr8hbC6LZ zlyV{6&rLl)Ny5aHRC@8{>LI7E!6_N+SO4fe>kAGay7ZW9Y?VBGL{Busv*9N0KcwUM zWjsQ_lJ`0k027Po z)6ibmxT0@gI1`j3VMy>(oya3mp4GcA17oS8QMV>PLBLH0km3mx-lWf-Zqo1H$t=@B zI!?|cg@)+!3&El$=6GM*A^PU;z_L03B*ReZS)dyanOaQ*VG@1^w)3jZ1c^c9MDmZB z+#&#wir1YiJvT4Uuyiv@&MbS7wJ$K$;-a5Zg?=9$|cj79F&AHYxDxV+i%&6$kb{JSa zXYfd=o7Zd@;AyU3=OsK%mTV1svj?-E=g*%{<#U;bxgY{ht;twj6c>hvo&C{ARIFlX znLM>m)&2+JxrMqyEH!@-En)bu1%#ySbjl%u8pmI%O+KW z2I6-<6RpR^zK&_!9s?*6B}&~v;r6`obx*Aw%BKCf@SPW4qmi0^;6je$e)hc4y*hI^ zd8k{J*PbJp(^a+U+fgyuL1iT~*Z>o5IYl>JMysUj(HOOYc%Xa*Y-&);jTkxxxM{Xn2>tUJ2SUi(i zjzo$LHkKxOLsQL`qv&CefEMeR-9+tYfNGGb3xyNWL=468rKzmpVOb&{u0jP|Nan7Z z!VO*l%wH*DJy59a+N1MYZ~a~cymHPpK&ahaA-ip?)C;^A7cMsOKk?iSp?Z1-zu%p_ z8s$R}bePNahcRw)fF2HE51DHv0sR3aqbh=A!n~BVz_U*c*|Dv5a;f%tLV3-NqjH=b zG>v?tPrs|RH$;J1@D*kIXNmUqTG51!Z8a|TtSS^|4tn-$y@}krO)+4Vql>jmACxXo zs8-1AVTvgbg1QAkP6FbJbzsR9Jxj|`@!^!O2u5LshFO}?0U=smv+Dao0|WOff?eLq z%_=aqGVfBlF$rN19OTrv$?-_rPF=Nj%+6o%eKELqdj`U?RRx)JT?7O79Z4=#}!| znV>@rseb!nldwWBj}ShSH~Ayc#ozR{Dp=RkB*+{_*zLKqlI*GuN1m8b*9%X7QSRN@ z*}2m~U20}E)_Xa_M(#K`37eq!DLc2$(()-Py{D(=yNV-0ved@r)Y2uLthc1WBcTli4;9I!|}aaYPRO~Km0UT0!?K;h_05Oh8|d;n#Z z`OCIsK>0X-QRlxOGc(h-)Q_*oM@<}Y$zo*H3!3Hr;$&2mGRvwGNp&(y=sg(N@mA&F zD3?;I?y4mIdB!1As^hEvpz%jN$1Rq?zUKRd&w+Fmlc(T9bkho@zQK+rJ}2}WB%&+N zz>dU!z8g0^m;hF4Bugu=%eOK)=bQbiL7msZrYubc|AJctJry;QtNvm3V+>r}D+L}(<6x>x#;u;{ zF-JKL)>59Ke~fFa0#^%Wwu%G0&q1aT8>e{^AQuE>!va@+KkWnEoYDF4y3oZRlDu1> z-{6Rvn>X%OQd3iNB3w1<@vm)aNXAkJQ4ZQ6@+cZ9vM6I+(-M@eT&_vNilP+B5X5LX zz~iJZD~T4Y>=qmIK8r_0G?RF6d~9(^I2;ZILtGf?zu(8f1h2gOByMK%rC}PMqZ8pQ z#WgINK|AJFQW94)7ks*)k1eia@{6EH6c^9MED5XVx6M0i=?_bmWn(92)`$T|F&Aa; z!j6PQsSAXDYi5)ph|;XC`bZf1@6z+Cyk_e+dVRF4DlKAm_+u9PcK%-0L?t;&2_)zs zOFyR+MlHa>K!b%Q;$Q!dEMqcW?{z^y4{;)3bTV2KV(+07J|!*BZ*4_3(LcEbOx|rc zbTH5#uZP-0gLST`oWTHhX{4=}+j7>&TbV}~PoH9dG9%FM1qr5e4gUkBZ<=G z$L2I|53)?c>rbQxVeQ+%?{7UgbQu~-wvXU zU4X|TgR!(c08j3a*(g8%{^Y|pR-S~O51cT(1?#PT;?@iG$m?Bk8wmo|}W%*1RH)SL%%e<0(HxZe`_E$zLc!I?4yH;<_eJ1k(P@&B+eMZ2T^vZ&rcs zEH|WR+SFP|kQvv5Qu^_q9lyWKIHYx@y=<=DvITM4b!L(+#8|gbOYLY(iQ?vMzd_1L%0pJEK5)Sj3wfK&?29yi+#WY?aQ~$Dd)Y zS9n698)^R$j(y*ousZ!b&FH1gDa-UOM`Atd%n|mL&>dgr<EK1mqDsCorvx{%jfukNW7xuB0Y;%^gG zi4Ys>97?h0!HnKxBHxcqEuJTfw zhQx~g1*#`w0siGDk+hFD(l3f0cm#@7`sI18MNRYDgr`NvQ$#=X%8lE^<^!~6#U3Bh zd7vajsemdqwdko1s!I-g2Eh@Gc-?2qypIuHaqCL?zqS7Kiv+!(g~!DBwAgWHnv;1A z?wcRSd{kSeH`%XmEi3Tg2&BB07LAa3iTi);z}B}+D&ev6V;40mKs64dgeCEa-Ab8z zvJVk6ZZh57;&0nnBlTVG>zjyTwaA&c4H}xg1ez$GeIoC)w`SwxJ3373Ol}G|GmHDX zKT7m2eT%r_)6lWYjhCJJq|Ph~p&CF?93}xStWP-YS|^66d+hswD*O~CA|{GINRV?o zB~5UYkm*VP`R6B~y%hC-ylo=OY)n=B--KT>xBs7iSaftSW2Le%SqJV!lVLPN$)x&d zvdHchW4Qc!iSjfTPxB3+1Of}#quFTkD^VeHG#@YJhF!+sBCtvc{h4@&7DHnVD5Z=6JMdIrAUzH)sl8ZZiF68xridK4`x+dqI0+lNGrdG1zsh z&aTfbK=n;vqz8J9z-^(vv-zywutARNhdZyk*BNLk}!Lw3w365+J4vjjT8sHuJrPe#~EU3D{~x$iJWwS=I- zsvyxK@P-7Q^AHidm zlunrMb3#A641b@DS|}{L<93d*)T2;t!k$hrCSguurL zud#5E#;QFq4n-;IhaS0rK}{a_sXmD=LS0<)(4D;)xd(En-SA46$gvMEc1KlAam zjI;4Yk#<*-VY)KP$E#qv%hRna@2!oEPnorVo9!(dMF8($&Z)~TRk7linbYP<@>%HC zJ+2yq#Xc#t3gOvHj2&<-Ap0->xi~ z9Y4w#YtJFlWbZ*5x8cec26;33)hMe3w zeuU4RyGZ($I1@D!AxW&YzJ#d=!aqXTd7IsH^dC$f7e`~>p*vA}@C$CMd|q5#eeNZk z41ui^$`v`%8L7^Ong7H9$?qw!IxJsZH7J*eTp#ngsS-6zZ;9I6SQ@yeSkPBqOo3L6 z*ziZ0z13P1WO65^h%>hTr+^NC*8j$ZkB zKghdfeE#^KkQPA`si2z*{N-+acEW9%7DnfynU%k9?ZbpG{+VV)PjL&6M=<+a5))Nc z6ckJ+!nY>3w$`4ut*yJ(WtuA*4JeyMc@Vre=l{&&ie=v?0TO8te|gtWA!047sJ`gUeYJ)1DMHN5W658N7rcKkr%6lUN>2qgwMB+<6b^UlBDv5EO>%$Ds@6?%HEkg(97`A_!8k7MG*W8v>`VUT?2CC+`w36}(} z>kIVTy)q$S&GNyEnax9b&ln>*v|E#xIuQg%)o}iFOY?1O;}Ts&SUB^% zEYarFQ>xkn&LlG6@Hz4p1*IYbC#UspmkH{9Dc9;-HVCqLWnx?FZ);6FzE2<@^9uB-k>Jg}isMfPOMHj$pVbPAyLxj}@IQgc@MPA< zVb@!e>45p7?$O=sITkz<8xJ)%=&6BVrB{xo0wU%$_A5+F^_>inGSXP(%th6Zl|a3V zu;)8Z=+~&Oo6q*XNDH!c(|cr&0_W+mvL(zHldF84iV7xawN)pmZ$et-jD}W`ghGc| zTRtT}>d8uy+%fBjJ!?akocSjYV!~!!>c$M{m+8T+>#71E1YwU$JW!XJYYjbO&rESDC7m& zX#s0^8oK+iU$BVqdqc}4t)nAns9x|_bb~kjJ@OY%Y&JRnV4Tz~Srsnv%k!Q^IvolRB47=ppSth(8KBfGnmc`Mtq z>;dOvX?HR)>EhuNS$sHxK@nPL0dt9$&(SJltoP_HU8OY+F>*3gSRi;Y>QTNNkk~Ax-{@__w%p9|PNXc*zO{UIM0l}QXwSv9y|BMB{2N{DSf0pjNE{ppJY~4iX22cV!x7T*CZF(OY>skgx-#FC zLbEdVy?z~c5&t>xtcHd*H@(k|^e;T1<%T!2aemBS$pCgXsvGLyuzlS|OUr)1Jg!zGf)?v2&CF`t$ZFKIgKc0uS#3w#&r2q5n!;1abeqUi3XYDILQc*tLO}N z{am0F(!xpO(QEw|-1zy$z;PlKoC+%nGCYpSAm$JQE%R(un6Z zLZzQoCg317R*6A`u49{tXoDd$%ny1GcVQ*W zfaYHG@iz7Rxlfikjb5AI=k8Qa;c;+W2#hHTgmjK=J{)(f44OEJk&vw3y$2W4p6MG^ z@X&?jzi%nF z9&;Y8pL=2+r6TyWjHSlwHD<+>SCIdZ?#H#Wv)x1+YuO$b*_vT-I`e=za~uc)e=ieu z8r)se5y*Dat2$?R7$e!K=RDe;lyHVqS7swtR`8ctTmbbpyz}$t^=zV^7LhfYo^F}m z|23?dFrP7C&4Et*EE=a6JJT|ii>2h%8J%oTdMNDpC9v|JJnn1oIoy9N!K4=Kwb zozMQZ2&NdIo$(mTr>Ei8d$-`pksEYcWdgfU1rCaI+z46P-BSLJT`#AF3%Is*~ zEJ<@2BZ^PBnQL~Z(h+}R$kyKes!_vr6WQrpU3^0R#6qWl&Yx?S!5Z&>WrlATD4f(W zJ2tq|oKQ1zE0g%Pzxd;Ut(B=w*b$CBZDAA^6;x;EL(4e`=HqFNr5C0i2mCJ#|9jto zR9b=q3R0%YJ?-fa6=M5ot{jx-nq{8tppRT>9LejeXFka&?Uy%rV^awzL)k9o5+ST{ zOG@NgSBbGi(4bTMvq@0z*k*R7_Z2kzF&`m+^H`B?uWfX3jdnLhD$iJD9;d4|zj@=( zmU0mx2)NL~pnV@)@QCDnRNI*}umONa-rM~{J9ghDK>BFi8S9~cqvBw+ zQA;8%r%bHp6;~ESFP;bAQg+k=nIo>hzH~r&d}O?i7F_n!@J`-o>o&j8bkWf8;QpZO zMg5y&vU@~tnj6 zXXn4P8HKh`>x{6LQj79wPoG~!kIi>xpSC3kZ~rZ6ld#Fn&9_rHdO^D6`nYEF*00~c zL1t-mBnxZAX|St(*=OLEm4E*4^*_l{sGJo%?;(>OBY0nNpG*a6-?OM7YJ8%r^T#&k4WS=1FvlT z@qB9oviUhynLZ6SnLtZE5v0Fxqu}DR1^TI9%NfaEMak&9lNQSx;|&x0*lIWDe|bkm zG!^0;j6OKl(A8MPj3m*d#~0H^UdTWAv9n|Pa>TWvfu@u6Q<;sG*MJr;3R=K~7VxXZ zF3z8M|4Cg^Zf&w69`>WiNZm=p9`dg2M21Kk3l8pt{GSpfj}<9sZdjesA<}dMgO6p$ z!J>Gc2W)L(msl+CjBE%x|M>D0I`UaDXZs`0`4-E;k6DOVR^Kn`y(rT5Lc~Ob-@1QI z5yv~LhB5CSOg87kQPs44mDkMp7L6(BhksK(?(@t}FgJoP4e;^4Alx@}DZOT8K@*TA z`ellF5?l$61U4j$O=gojfb$|ZP4XIfcoxY0XCus(A5zlxgA53Pfz z6iYds{;M?|$TtRH8sR=(b+t6J`%pJbk3E_jB| znyG9;w0ND#HV92sVjZ6lg$C99=+(4CpRJ8(3WS)%bhKa`ISoH*H%Xl17ZLO_e8vW(nbR~j1k3j07wsBnp5O;s~M zVT7P-qpB=YGx(;FjQ&wUKs);=7_c%)b~^jioaT}Oq1a?f>#n(HE8+IKkQ3{@3eJUP zOWY5tpIfoYKjvH!K)Fru^R+XSC00CO$7L|~I_6@*RHtFw`|0xeYzg-?Q8?lCL*qwi zzY{e=8~L9UnL_g?x#PmN3qH=11K#nb-b!v}f1Bl^dT zs5&g;VxdM>(_fhMt)qJ$I%E-a{WNtfYIEVc8s^qaLRtQ5lpCR{n}7}7nY?D2W>#G1 zoO{|-K%8w&`H}#my2@uG`ctx?j;2XjS-BkV`Nw*wiRjH!_3FAzduMt6F7nkY1pQ9EPgV+rE5G(CRcEbo zm2RS{re*^~lj&1aOy)7@O6>Qx-Qk$wmEMu~qRDUCyNSCD(!`ec=&I}`q+L&2GiK$- z(ooQ227_Cq){6uhSQmYR1;dT*e;L?QoidQ#*!Ff08zeGY6CSqSePefNqw%)}hmN*M z$A6IvBrDq|>%mPs+x*~*-Utl}edH3B=C&DJaD=#e_lkM%oqS)Z8`dxRee80<<2C=> zSI_y@-Ep71bD9Ii9G|&tk1;ng%#CEkK5|S#Nf%F1L%GJLtpxM_f|UPpDMWAKdx(|{ z$@t{*(vs^$>a*8A`I_6a<<;!5Q4LyTcvx`QD-9oar`Z- z1V{pHW+dQDRx>K~qZ+tdrOkop?!cd5aH|xW39daSa?vrdVtJPZ23N;{1%3FFOsW;x zXk|LBuwjG>>OpFB$Cpa!$vPuN&&)6f$R+M7A8-658pD(;ye3doTTfME)m`WAtL1Xp%cAIBG?c9Vth}p zAN=gWTXojj;{Z=8n*hsZV%5cp5^gnIN4x1}9GMlyz(L^HO``LKRn5f71$E zLOE*|^!{(>;-yOs=SuFoe$=c5pl##C&~Hxear0B1=WK6KQ9(_)T`rhk z-HaddZ)v@dk)M}WXRFe6KcKKKY&z=b|78L4f8w#D6)J3N5{9ypR{6H}6F~nXiNcr) z5G72~ROG1>VaszD__Ni9?a=-{&5T=-Uov&_6wv2 zd1=V5`|KpfEI*Cee%kS>y1Sw~IoCzH$N9|fC{iW!PSZ%}G4sc4N(f?*DiIcAc-kI?3+G(7=}oNMg1j?hzjoIqcKhsif2H3! zyZfWOdUdkxT zn>K<0{yVSAJWd7WAJH2#>#hiKw&BChi=U#$-^hKi{4Oce(ufn&T@kx*rqNC|Pohgi z;N;H3codiDE1Cck#yqW-msT_NH^SfWIqNmXj(V8^#f4kwK`-J}tGX**`wLZ`Ap{W5 zI1{dj5o@Sw4E#l~eu*Cs9-GSn&ae#;St;;8Jn47Oz6xdx)!y^@=UVvUghh^@Hsv9^ zOUaas&PI*tCf&Ozv=A5Ir3@E-+K)i`A0ynF_W)sFUA@s|LVuM9s)(9hCMSwFcW28NoEI zm<=u+1ox(?sRPY@^&wJAyXAg|kjiOL`X#s_xs>`srhe=o=1YX-^fdB)lG5!?&~^ZB z=ObZkY=9fl{ZX#xM=q(NTl?&X77mQ*6M-T_v0C%OK-_(zb=W5$#!0i69B z-@E~zQqcDceq2^@bXg7c$ov6pVRRUm7lJMI^@P`jEdJzs%XaYNV)y1j z;6+=F^D93ircVi!=Y6-wRE-_Rr14pu%aJw=j|$og5~%aRz1!jA!4X?U+M9RlR#tu; z;xU#z#WX+WObDV`IiDBv_VEV1qv2Ji`?EAG>Tng>xc}m{T$D(T}7RR@6i$XXw<>h#TnOP59+0D-88xq0Y%u4_d78V3$ zyACUB5M91C9P?;h|8-3Mz5UL#y;I!7)YRJk3?Y9XHo})8=4v$*Gpn{7*>zB|2^Ez;PH=;(2*grYo4ckM?<@5^(SnUwm5m?!&j$SHqjS7fV+}-F=Fui=}uqj%~sI0netMOw` z(`L}vKa+_ww&k^{Xcwc4`NakTlTnY|R#%yhLJu?}R_7WJSbMu~7vxiiJlU}SLV8 zqaznSVA;5F2!R*3)C|GrtNK(;T^{Qphb%6|Ejpcz30g0cxddXWHP2U}_b!KH5htJ* zdwdrKMwJ~=q=|-8sM~LCZa6z}eB4yDmm95$N9MBg&aQ0xL@gv%x2kDs-Td^_V(g*z z&NH(IJhiktZtTz_9RxB^#m92`(M<+#Rmk=z72}B+NP9g~rU;E;I9>Y;!b(-wJiKa8 zbf3uAen}&ohIIdO-f}Mk%#AAs7>G8as+AJMkGqJ}P)ak1AQoP7FIz4);i>04-1Cnu0&s}<` z+=d-cCvZu%L57(TkfLOVsskZCL!4{OyYF5s*drCyr|>S29={G_|JcD380pUVelvf(AK^&Me$2wA5hX_WRx^c zm64|Z(klPu{j=5Niv&e-Sk@7qdXGwhL@h&nwiL`x^qk=^0+t)EhRdfP!>tny*R9Uy z|JmL?M|qh)Wd3_|^QM72EbRQUZiUL#5gHUV^e4o;6w@Zn zGAmUYa{je#H|(zVX>C+r&*N8nD199NXt|!1fV6LKtM?4ZUE<+#bNj&T&Ghq&j_$AD z)a;>$27){9w8>S74TqEML~?~hrrpE+Be!-oS?8jcj7|58{Q*55o{extbl@m42eE~xYvf%K=>s4jvO8?&o9}C9DT%rLC!%By&`o3u z30F`U-|s0Gd~$^gY_uZ0Gm4*mn!WS-83taGV{WGU%TFuk^yX`>7mulMU%s4JsBuoM zXW4%uXf!KocwbVtf4zf8GVH8_wRWdG;4$RZSD~7o2Mv zUy=7Pu97cvTYiogyTmL1p!wM_iM#dR9C%V+155ca%Zt+Hvwqjy&1lJ1Y0}i29@iip z_q^$KKpZ?*U7!_pIBuD0<$;h10Ulhb-j_wvz3J8;ZU`N4j(u^eO9xt(YoOqgaFBJ@ zBpdP8%uSKlAUpS>%9G1+h?sO(c%)MK37>K8?ZI835j#`P7E2u&j^zY_T38pw)2@hu z_K2b{5ev>m07I9av!~TBx*D@GL)~!Tg-qUZ*kf7AhNk2CFGoTyBucmKjF*VMtC5N4 z4rx$93YGgjeT@tm=h#2D95wz=tgq+A7wZqwqpGR&n?>iGxiGhD&l((aMi(tgd_c!T zXt!cRD*u7UQif?j6d7R9`KO7$G)XFmKR4)TD1uX@b-TBtHW9?2`yyjpH8sOrK6Gq_ z);M$aXKoL$l4>@pf-*cNBp|A8Ohwbg-lp{g)5u*2Stw6ih= zrS~UymCgn!wl6*rNx1^)UXOIm z>rG~Nc$u=u=KJ{DgimIVB&>5MkAHn``#8vB3(4ZoVxcfa#9xCFJL7zMDgHv zYaKsw{(G(@-gIgv_wt~!Q!r25c{4sMr`j5W0E2so*F^8p(|{FvlxH+}PL&Ius*wT0 z>K9Ris;m!wTOew}hGUMetjv1{`NBZ2D&TxI|EJa2z^H7Aj7K9c@{7&7Wn*;&SR3-a z13-p7=GxY3KSBTIfJ;+0x#vqe_3O0TxTlt-Ii3DZH|bF7p*>u1k-vp5DqT*tT&SSn zxS^~{j@P*yui&vVxy|T{haCxvl(&-~93LDT2RkRrofT!>Z)m~PJ+Y>y!i1^!YFDkD zk}_z^o#uDC(2Z?v=hUsQyZi%(frau9m)rhTt}bVEK-hNL4NTh9RL9_yIN`G@mx8@! z3^1M#>Vxiu#FLG+29bh-0{7A~rQMMWB3Mdxu`b-l%s!m!%aglF<(L5F*cNw_Yr#`V zeVFI4Y>SyM-|_D6|JIcp2zn6CSIxv7M8hyZIKYTQ1P_wvYLXX_E$&uO_OP(+A1-`2 zpD9k*XlD;t3;csHUqz( z+EWwh>u-MKNnPuB1ERyn9{1|wvTKvpjpKi9BSK$|deguv^Eqwpskq_gtTSK&ZDrf? z?^n*db$*2cH}}GfQRUu$b6ysF!t8+E`19AVeX2eQnNWx75zb*6)h$4FD4Efhtf`@K z?yU7yBN6SW4f-bQs#N`)FjkDX^=Gx)D4N0Q~t~q!ue2mrhEY zQ?(nXKO8_$60!K_gGEzHM=WG@lg!nRI0+fxKdyIN2x(YtP+4tg2=o+f|&utXP!Fzjpz z!|uPpqL&sb?iKPIXmMW1Jg6Z=dds@xGtj3QHrgu)d;WeAc2QNsn)M%(pli7e?ACSG z@)MEEDVmoH+Cp^&lHaL_up7Ypp1Ea_sOVEfzT8z?M(&XH_3LN;U4_B&5bClR_ui?s zmIdln+<>OYhu6$-hAs5&M#o;aTyb;-X-XBx<+QvHBhZk*k8};yCda zFDU0mdbK?r@f;PA`ASVar-PK?{%Rz3Wl*w<(6t_S6VQ^?*)@$@+4hq3-& zcBbbi;5U{bLSiDCF2)|Vzt&YvbFoJM)kzuh8r@zf%m3GACf1EnQ;X1Tq zk%=u}2_w(Vv#*SX=%p1?)mb)McZd8(R-?w0`5(&5h*Pa4ufH$4EqU)Euz`oS&V*OCq~=79YoelQ4Um*%5Y5YE_B-42H^(J{ z;@70RG0ps_i(l}{!mnS}iu8uz52hcGvoE1SWuZB!ZHu9ZHssC@s~RVLxA;BN24R?t}R`K&X&^J{C* zD;^ZG*kD@rx__1gXY3>Yc|B2d;^gJarlY|H5~XS2eV8Pn@W3-o+~6bn!@UJEF|I&c z(-76v)OKm$kI&98Rt1fp`!eww?iIrB{F0?kyng*?PiOPTLASnq5a9VXJ}x3spwDR{ zrfRUz0dkaUGc&V8{-~Ww|R!u2$C{x0OOp-}C(7&&y*Ul5v+2vh+}BuKW;EM!F6D$wP=-`uHR6 zM{^ep^~yX&63Qtif$>|>Q-DoJV%k+ftY1J^*C|oaR6q`2A;VqXK7Q_sSClPQI1TL& zzi<#FDqULg&(VVg+MH4>K(OuHz?uPT_T_jH=?hjC9Lbcc=7X$@^x3K??tCq0XQ?v_ zUQokiR?FwO0q5kGwe5xNk%thzvAPJzYbwCK+|-J|#$fkidt91_cXkAvG6NTyuOe=I zW)su5Tk2byk;FHuZ;%e-qdO~Vt(Ty!+{H%thqcgNu^SbK%h!kjWxe@3OZ&&3Z4^eX z{PwtJlg;g1nHa9gI(4e6FJEWW`+=*CcE}$G&+V!Cs@65eMNt8B-QCrvMU(jXQ5jjc z!V@Lztm|9O|E7H+bFZJ*OXFi`v_one7iRk{>wNaIF)}^Vck3M%a<=;-|2XYdMXhrp zcgmcmY>vQ-V=@9WrocnnG0)X5vy1JM<4QYv^gC3nQ+Mz~JO9<~P!_l`B(c0&xp8xiDsSZTd+zJA7 z#$^mNa+)uT@wM%RH=PrCVqHx1cW(|F+h0ZcNet+YUPmCYcXaugs{T(>m@xPU!afMB zvt1pet$wfkl8wtgcOkb=o^mx`%jD_(3%MQ@$he5{ zP)>=7y$`xAP`fcSFygi5H?=VCNP(8((Sul9#gCH6ZzwChskd_$o;c=5GHr%!;5!|E;C%f#y8^J5_}DU1ayMG*4-)ME&Q zCxI9gk{9BRjw2UzHgyZNDKD(|jxK=QFA&W>m;=}9Bq%rCtjZnr4t(eE**!k~GVDhL z>w;OMeI@Z)-O%-+s+(x6fWYBhX4GctR_*TQvRc%iQ@Wq4SChF(@b{CauA(Ln^DcmWXt`BYD=G9P|Rzmsw zWYOfKM+5Hp5e-_l$;@~2_MR1im0nv54~7DpN!9Y*55_gw^~NbFR~uT?Mnpm)gMxA? zV$j!|O^;*KGBg#EAaPm!FtNXY^Hk;s*^lv5h7V{cxZs`dyQvih(89p$QdI|@M-qAY z>+SzNs0du#oOzI4Qp9}Pq?E4}wKKOFI`lg~oQvRHDw5pQX#cVJC*$(Vtd-yWv3qx$z3~pMX<%8{#A!bWNBWU^M1g5wbI7_u&<{ zL^3`}ZH$ocZ*y|o&CrC;YfCBf0$ISuGLq9cuC1XiU$ZK?`$H1mRi5R&fft93!R%MD$FHyo|i zAtEh^F=fh76akO^1+CxyqNkyBwPMY+9uNLD&kCkYC*iJFx{NI0j@NUpa&&fEC#=+N zA4ZuDo!~QMY9e06v0kC9xk8N3E1Eg<~LoL#f2a z@DKN{>5J%W{wiwSZfp$;3DGc52kD0~%9A9^n7M|OvC#kNSg&0qUVuZ0cYrTO&Rw;L zbju-AmRDKnAKC~piKscuV_^LjXYbh#0x~S(06zMM$FUk29tcp@2ej?~U)ULX=Fz$i z46xo$184r9m{a-gZ?dEPkt|AFO&!L!A7qF7`9#&qxWhNlORBYTtqTP zU4oG;2yfuhE1wC*4J~G0IuIv%3D~kqPWhXVOgnc9sXz0$YarU^gZx1Vu^otp0l`ug zDs@!gi%jy-z4+fQ^(35}gH%j%HLPH}WiNct=1B7kJ9}j#!4I(amGiJmu67oQ_^9Eq zvqA;Qdm(Vl^FUJd$J2acoLnQ{n^T5%M}ag~LoWE&mLFpBIzTJX@BEXz1PhUbKw*NC zA6mQsL^h|yjOp9fLrrI@mbu$y8lE<^6t&AC>PvQBw{fJHgaVYy&ke5guVl1x^v6bY zw>j=;hza@}))_LO4D`=Phhn;|z>7aO6(;xmNBRe=8G}YZRr7#0bv0_ zL9E}$@)8OpA2bGr=bAHvBLWu4jqlzeE^DlAD<2+FNZ^$t@EsQ9g?QknRFfx3qOJ-; z6{;{DTvxT0B;B(3F*;7lrQ)KNRx#nWhY>K{U4jwc{Qddk70s>HM~dGh9h5&7*cC0# zRwT`SbaV{p^aKRYbRv=}%QwO$bl=%~V(r9<9Sa{^&{x$j!>tW3?46Sg|J6cYd;4fe1v) zMBW*b048x;L#;c#%I1R`*N299^w=k&Ki;^4evIA^iAEo#Kj$sr(VJA{y(FU*EE#@_ ze9;sCN%Two z<3*#JF0B*BgpgfaESZ!AY`T^Ob!Xb-%FR_6Mb^4XKyJn*j-o&PB3GFr5bQx7kjSn zFMAZ?cySWusuV2X9BsJ_(|g~~I1D`4f8o5oJkd`7{sEZp<(lE25!xpXB# zvf%CHHbk9Q6>*Q0Q6FvM9?jt|JaUtnzq2sD14_vdq9BiibOI~}357>bd`IBRr^$CK z^q1^sH(Yd9t)vO(<@##;exDqZO~n7~-Sd8^KHNy70|>+;jK6eT6otGOu_CDB;Sf(p zn2vNwp}In5;@k6#F#curZV%G(A*7ICf0>OVU~JkSgk-<%F6-XQad`WVhaVm-;r!M? zX@=VwIUeeck~NVg2aGfwo)*T^&QGf2K1dP%mt;=D*=4#ADl02__(Spl-&W2p=TJMM zA7OtSRzN#?DdFVfd^o=!Oaj?~(uWzD}T zB@hmZ#spq~Oq2(ViMhw@H_24z;P*s;Cf088;0a7ZfJDY#)*2nb416Bo zO>NMDMIP7?Z+`2~+*l*Qt7ZW3W_EVt*PVzM$&81lP! zEfQ!}0_A$ETR2?Z!D4W8p160N>XIT*<*)S^PMzv?tI_Ivw7+p%LO9enn4D#k!yYl;{<;UI+-8`k zIS-Ep%)?7IN5;0cTX>XL^?k~PF&)28U;5jbBpQ-=36^}pKb>IV>6KFg)U05ywqELC z%Ivt9B=vA0jq?9m0P(mMAC_+Ta_4e?|JuNSOT7$2ADX0fV|={F?{l@OiCByp9ms+F z8BXgBd}wfk2_xY!$h(P!_8R6JP?_?H)`Zf8DS(en%8n~;etuaV4CD- z6Z*w}EZZD>(NR2*XsNu9_|Ri%A4UG`bk?{Nmlqyv?Szew+*>UADI_gl%7;-g6>?4l zF;3S*ewM#sJl76>QL#JMb9S$A#E@o1ud1BK9FmYN(n%Cr)K>kHX=nmBd1`Q2zgr_N zTJUFuqhh8*1xWA5Eqaa%xqn%bZG{qd z;p}ZylMk>0e!`G_&tGX0P8x=%<77anLB{zHx6_5BJD^|@>wGWynvp*eRxlQ;)%QH8 zKhWj*(8!eG#^#~;H|t||lDV~m_H7%g=CH!ydvc|y;8y#}62HXU*=ogyT)P~z$+s-d z$*WS;1AKIJ!z`e%YI?c@$u{`<4k9Y|5Ihno{7V9F#I_EZ1bzyx0upg5O6Q&n|G2HPaMU^h%y0P>#{1|=IP4syZ zywLV+k|99afdxNa=D09!DDYm#0mfc-+kVeOuGSaphsyEyJyl?svRqQMH<3cb096Yfjwe|aLiSe!z9yM*BmL0)RxH4c9UB{4A=r6JUs4agsw@pX^)pb!%Hvh?m%$ZP z^caf5l}YZT_4H&({FON(A6+}z$3BND^~iyWzN<_OKGR!$?{@=S3pz11RqVwAH>sCt zqYp}MQr#a5UQwQQ#4(g^#Jw*Y6X4ru(JiO3unr1&V)}#D`1dCy6ifWHG;NzhH@@7M zZ=NO{E1KbkSWazi12bCSaYo3KgvKq_c4Ypvhvm%Rv((5xHPb6#g{a!I0t7W(CPo9E zL&>0y$d{`hzLy)p)_*}V8Y01^ORl4k_VXTO*d=(V(l_P%AvqZ#Cz?*d&V43x321gZ z;Et{=rJ)DCes+Tj%;KaR@1Y@gI^~Y zvd17bUw3PxDsuF+m~#F2?|m97ZEtCC;a|>q8OUJI&pt$_nCp)cve>`&cgwZD;T|gkU_=`Zi z^aRTf3xK#?Uw{$XyF#+i|RCSFQnX$anbYnV2;q2 zt9$UDchFeuV(U?E=VQ(30flm7OzKdkK@`Vry_fi?8_5)^Vkrz!4yEIh~__JP2i z(1!f@_mAv1wx<0d?bPgaS=sblwC_XZz3^B_wc_!vv19vz)Ted%*P$3?qhDRRoBbT! zT}7qLhJsTG-^a)D$>j2*Nrf+!oSMisYs+oO*O84ajtsUypTx^Zhy?sY@}V@91i$El zydj?GHMhp`b%ZeS@p-wwx1J}xF=>kpGWYDX6N2c0gsP^1LHmT)0V&JhLgNuuV6Hu= z;ZtFj-m#@@`p6nQbEf5p=L`T$t|IU;9CRXn>6F}s2Q|ZS(K#iL1Fv^y3$$%T^BF?J zIQTCo^x#p?$SP20-cW@<7oI|uAIdcZv9EbO z`@dSRQj)h(rO~MviTe5aE5gbqZ+=Iq+&2K`0+4Kl9tnFHp31s-syWS6R6|{ zv(BE4y;WnU&EG!RHLeF`b3?vI*?Y!L_@@UtqR#9_6^<2us#NS@u(np~BA)98T^2Bq zY9N-EyU3n1!DoCtM!KE;$-qMn>$VvovbO)_W1^gWpo+`wT9^5=C^lNMJZeugKFSmCf>aXrj`;b#)S9bX7-(}U_QP+3%^%~+= z+m$WoD7<|isUIOsnYuie#m3y)*+*4Ea31Sg;}sM!rI zoOtduF4NWYwVe;(Iqo$N30ibXAXj5D$p?!-E&7R^QK;}lsMKrGDZfMzRYIbBl+W2? z?J}pQ{Vj2nY>cT!xy4ZLZ20CMmSkn^5bo&6x9wSS8j&f2zsLHsmKzkcTekZ(c~WgW zscHSwuY(=OFJpCLapvo58f9xdXHWAsD zy>{U})f#1_Js%=bR-)9?jkuAy7fA>}^Xm`N7Z)Fl+({2RByWQYm6Vqq+hi`kWN+Np zs`V1ayAU~lw%{MYI;*|j_DrV!P%1v(1%xZ{eHxG$CIjnAJ9pMW-h_`2d5KW#wN<&t zcq6$B!8FnhS?SP7O>i9Q%${o)tXXWhVwXt_km(3HMR-AQXiy@M;E-1VJD;AO5_>HJ z)fHdIDX=3NZExRn%KV}aa~$%c$G7N8UUeM5Zi6cRF8K!;N2RI=^|2Gh=@m5q#4}$` zbG7MZf)O1O&`N~kMi3Z22%4^RG^xacdqeheJ-++0&VExg6t$PPLqwwp37zCGP=)5h zU9b)b%njRXlzyWFZDP6pB?<70$F);%AF&xkKa@-X;lT3dTG^VvSU4Ov6a89*>YWqr zILQ57K24e%7NOoI`BYW*l^%rnBjK}JW?n22S5$^Cqs~nGYR$S182XRgt4gFwY$7kN zoRj>5(AV9VdgMX=pBDP>^3wD2fMyGu9I38*l~X zle2j@fHrb(^NLzuO+ckW4? zVm$R}jQDIJcA+A6o_ro~&eA#%d?mjeu~4yfv@P3T$NoT`=qlfTu`iRoM3d}1k?OM6 zfZcp}l3*-^M8+X_+0t?r)Gw2_KCgnb76X+(ojy@vvke0-o%QlpWYy0mxzyNyO&@ot z(AoL*NcZn>pL|U1F&?$~H6T$q=Q`I}!_JTRw=yYk^A-&fPd1tR;a<9NVInt7xkr|H8on!nfn2`U%j4 zxIyLKq4gm&$$sF!1= z##1QYBW`}wzb_%Xv#0X!w?`8QBpilw&+2-*;3qrNSMp^bOZ1w}@S*2#;w&`Hi>&<- zmr;8$cXKn=c_8as`a2Igv#pU^EhkCEZQ;HI7gIh#DLEsQyR|X~HXDz;Vg_2b zUpqUIzZ!`@d%H9!21or7`{?g(eXxr+o@=P2&iQNTCuVUem3JY&g9-)ILWim$u4>f! zcAXhBl+#-tv6Sj9*#TF|>iKWIZ3B4X>7?!k-e^B@4R@w`XGA#-jJp}->yodD(cPg0nY<4YG!AlXYI%tcZ@xWnCWO>pD=wU-^S#T+rZsuLy z7epRC$AOLhUJ9ju|Hb)VlLMjce65YGo=4A2{)?=O3J$|3KP&NQ9F<7v5)pR&e77Cd z7!}0EyzBu`nG7oRfKW>Nx3_0_Rq|eWiQ~RYuA4D=c>xV9NyG&^yEzkjVKZ3Eu|h4W zcGSU(gsV4>-I=OMl`m)<)u9;6hwc0u9vTmS%Hx2H>m3+GG}kxq8gQDeKZJmPaHz_O z=R;|J_{!RlQ)L($H7wl5YGd|K56yY9}m!ae$d7j`3@ek z0gqvM*D;2hMx+Uv?)pm+<9mw##S{J6C!~Zh_=K3{NJL4B zqd=tuq3JIwSi`>{f`Wu}8=K7u9yAZ(*TZOwYVW)3a@vJ+j!o->!0 zjM(V|vKe=C=pkw;_}YKI^sA*cY2tzn1yximtZnalTRb9siHufKZ>kgIDVVyi$){9f z|EDD{BU+@8v%mYk_dl;c=BW ztv%ZXKlkQ7%|2qIcc?B^vITIfgD&R_Nljz!;*-$;w82^nmCYcc0At6rKh*REA;*3D z_XbyuGnV1H-QOc{-E8ack4KZvePS8uqxb64e*SleSY2!Py)|rYF8(^2k_w)by^VFF z%Bo2~_&`bTlhB2GgQhX zpqc2eVh$MaLb*%{{g1TFG^x%G`6LuTpazg|AD{&?tnSzeOhUE15JaChK_|}S_y;?? zfiX>Y$H>ljL^F^dpQGz1gkBhnZ}0|gJO*!ZNrhMex)bxM?&}xA_`?wp63NiAC32gt2^isZH>^XujD64{8Lqw6Ug$c{1zXh1Hrq9i4o0*215KMsU{F z>9()FQW~WwW;RX@hk0^JGO%`Du-+p>C6Y?{Q9Hs$!vg~Yx;vXgOm#ja{Kx$U7;<-s zty?!3>LXiKHB<4$6 z?q?y|3q2&X!(R`VuQ#3m6;6oG^M)3m%mrnlF|0s_A`iWiro=u8DIvXsr>#FDgXszC z8Cyf&PUX%On2G#(x(L=1LrNo7Q>n2QgSK>-kWf=qqKgD*@&mkc*aVX!RKQS}uL$C5 z@whN+xmqYnS{n3;%80-tg(UIleE0TP)xikvwm>UL*|9V34$&pj8*}#yq^T5(M2i@H zLP*9v@w+LKap3{YK2(z0pe6nXqd+%IkS7>KhvXHLIJ2WV@EEST3YP65M~qv&xf@Ta zp42G$r~$SnWzAe;W7b!Y5A1hrKjuz?2boSSmuI7lcnLys(K&w7C`YG?E3(BC5kd9# zXLYxxrkP!-I=iby0{ObH4&=qKiS+dl4$I-K_&;(GW<7Uru5*KN8MM?ElSXoIk** z7h$Rr!7wjkWfgrX7(9~8*WAK7pTSUoV?u-?DTM6&OF3erWXtY5SP#V3k4sZdLwN%=D1Po@@Jp@|=1vs=!zn}GT-G&B^ooE0@J()pnID25apzVRaohcYr* z`Y|&T+R6&bT3p;QYqWh?2t$+OZ;DVQ<0nRQuUGB-P2K5~+~$Hvx8WKmP+pO~02fB0 zv;slOFTkT%|U;n+^yo!`<~oRP)8O!zGZ|- zb;LswG>k=x*u+qFYS&Zr1*BAgp{0pZiC=fQE@TZz^py)Z7mJqT@kPP?a#Tyj z`FM-I<0}T}Wb;#yZwn9X=M5We6~O{45q<33d`Kpa z*Tp8&p&S15&t_=e8Mi{)gt0KJ#~%|RJ!D5@-4&EGRxAonG)G&0NGudDHKBe1Qm2FH zqlT^(2gd@C#0SPNK`}IZ;gHd<28Md0eU;LvVFotC@USD#hvoYs4pZmO3v}QPM3Y=d z7!`W4btzYjPpot{vh^Smj*&ZuJ^(>=r0FNa{ep=9;X0_(SW@19>jd|!YI z#IL2mecm2Zh|R#M49e+YQSOQzY0_AvysUtvjxVE9t*n5vmrY3D-UbeoL4?xSm98vr z`EGx4O?GcPYXO{*@s^MP_2;{PuD9N-QllSZY^bNKH#UY0lHd4=Q%F72-F7{QBvh?g z#5Yb);eVkLTMrLze(I7;X%E(LDhV;_=yf}H;}O)#lnO_OU|uVB-vfm(v0vx!zlJx1 zQ{hg;hXE4!ZrfUiEG3&KCg1GmnbRuwx7UEJY#l|f^@hAq>`ihxRwyBr7p zhkkMyywUtwHA?PRrd6+E5~)-;Oz)=C>ujL{5>5hhhqV`PdVIbdMfw06%m&%2pU>{h zO73%?``?DF?bKPP%IjAce4PoO@QJ!3hu{!>(;B~;em)_%kc%mL=9oU@mV*%eU7Dbf z3?#-_8F|}?kUj@;C|ybaK%_?q<{s-B5DFM#PIfqaXE(VMt$~0|5To4fLM&xIgLl_k z8$L;u?Jy8aMWN}*Zy1^}*)AZ{{$ih)yD_VTHW;Afj|2zlYFD6Do!P}h_%YGx3@Pv+ zY_e7C@)N>{V9l6Xslw8cfSpYru4>t+m5gKUPo1&5$VTmCBlm^3B05YdMj&R(Ka~5Y zQqt&EHv*qvX%eC(4rPOJmd5pgBf?D;V?k-xU7xu$tZpx?_4>5_U2)nK*xio$2SR9j z1a$wi_qi|+uI?%HK3Uhqtg;dC=+Pd~ZVma zV(rB;=iaM0(^Kf>i3Nw=ovapk!m5GX$nRwIo~*Q{q)ewaP`ed2)B0UdB~asHARW0=Bm|5>?fz1_MvH zG_=&$-ybdGM82dd%qOKMm3ZI5n)@Ot#Y8o)E3oB$;ckQ|U5xF(R9ajNVlzEx_Pa}S zVR{M3&&=Q!vV?Z%%hHWppVl8lHM5K6T)?dS9WL==rW#HtE);P^W+nY8t7?5V*6;lP zT7d1%+{ShfFfn=v5e?5PWuMJc%Iy8&`|YOF^qGN;aQn(kHg`BIU!P;+I2R((*aNN0qtFrQFPe$5GWKi?kc^rPV`$O zpFVJYcGxz_xEOB6H072jzX4t)D=b}uqb-_l`2isuqv2kj=L4K9d0I`)!(RhmC4PvX zXb)q52*cbVZmbU@yvP9;I=-!GQ&c(16l+rTy~U4$6et4O5(E|}z&41+N>O_6+FYN0 z+9j~2#YZQJpgR!FL5%Erk2#MV6bJ{JZR<5#a{hHuh7iDrHRV(J-M@9qF*yHZv5c%Q zBNk3kly`++@-J{VLwU_9bbv`Xtp?;MT{;$rK0QTE3mG^~$aZhOBT9fn5T(nn#{p^# zAPaG~N$2!d<_6~7&*lkZkq347;KrZ(OTWL+6Xg3$|F^cgrDiSSU~C-C_jWMmO#`(U zATF-iL}*GB!%;Cbxz6`u`Lq-i!ZW8ff;-oHHEMIC72GMn*QHl&t4jX`Ml4A!tvk7` zm7=GMr@lY$8#Oc@7SNXVU|sXQaDSBBmAbpRyWyE&Vp01NJQ8*PO~lr?4J-XGNDPL& z*&1r4<|RG#B}hP0J7=}LmmFFC;5Hf4QX?IQh$}cnFlA1apCnwf@gQd4HsCAO@UHd1P6mmD)Z=fn!cs)+bHgv0 zWD{u%g(y$T+ULDli8tJ7Xmlr3PyP*~1WJ|X#)}HZ7qDZl+YC4=X~0--&4{Q?STyQV z0dRF&Vjl&7InB#Y;X&7_U?v1a42+EdH+@v|{fL4C;XZEW5cR$sh`*A*15NQtjCx;# z$BMDN0a0=eNIymsr+b}7My_S@@Q&p#FO{9%mkZI zR<#b{0jAynB}2cx`rX=WKy|(GfArq|+B1gLH>>sne!DXNYW}}A_UN>!n5zS%aQ(29 zy{C{t!tCap{ngN#dN)Gnubh&jm{518@TGfTa`Yg6$Y%_uB&i)5uH)n_sYQ&AP*Y~` zFz>yc_}feyvjju!;_n3nFgE_q$J(TGymbR~U!G z5p!j1AhZo3#!$Zi5Luh!f5G#F)#{k6G4dTiV7!BWxG0Jd?|K|yj_MH)LK5=W-(z zB2e>rm&Z3w5IC^+H8*dq$A`^>Eg1mp2ejyl7Yjk7En|$~9@v)^wR9|MulrzwB0@E= zH}=<-GnuY6A&gDJ(2`800uK)oi!1Ep!CeKXl8^&PDIP4W0M&7anCWnzeUSa#_POYX;h#@3vJt{agChz& z-$m(+$z6QwS(qgM#ju z(87PeW0hf(SWwwRr6ODjF9zj0-XqRrC?pjg-xSc@`CC@iva>XOg|YY2PcntX-wuyi z8*3WP7o07M7og>laPtEt@`+^wq3erE_Uo(5lf8HKA!=oTOzYj1)ZNbOK%@Tbn}ZkN z?YT9#G`8j@KgCvD>sdGVW|)^2DHIFv@J$_am6hd{r;MGF$N4fg;V3ppY0=1%KIw=! zNvsaZc^=R+twKjMiQ*U|w(iXWA@%7l1|5^LU*DRI2fEs!?2J(vIMB-!XUl$~R+giU zZWNFdtSvLKM{FFus;amLziPxoVsVhywu*2+@yo9|?l#{Y8Po`x1#xUrJfbl|U)HzP zQ^eQ`>UAJ=`Jhs8$@I(#J-1d06ezWB6ZAcbXm;urV*0Nsbv5`>ro9`@f3ndoQ;`EI>y} z+SR~!9~vX!`Po$d2XL2l7p^jT3Z+PY;bMCkcZQx{?V2of)Z=ZN4sB-Op9bYkr#)IH zTD-cw&r~F~5ZYUeVu$!XMv0qWmUJLKL|-sFDJ9}su*MG!cvOd$6BR8V0tN=F0jBB^ z*Gn)v#iLo3dx+?L(1bMD2XzLHim*~ja5{4xC5N@Mv*}`@JP+CD{>B6``ki)G1Slk8 z4R=~PRs;hu4R8!`5Y^$+y7^~rZlBNvo71w%C}sMlbJP8H<A>2y!1!Lt%~$Ju z(dprWd}uV|$$#F675h(J7MZe>Q^D$)HXEZsLV~e8%G$YnZ*;Af z3k;ZY7!_y~#m*B8bGAM{S+0*&$_n7UMVKi*BQ1nIDFaO9#I(YoqacgHB$2(nI6QfI zw>N6rNhjoO@=alai2jmu9xX_xTME_~?s9C?xnBu2IeZaJUfY2@`YySono3d- zd=en2Zyl>}P*yz^X&~7Y(9?0 z?>~EY;+dXAIJp#6^7rEXn<>n>5W3`v0UVaDZg{t1p)tkJNUVUANmUs!MhRm^RfivE z$(lfJk=@SP*a6#D1-s-`EPTTkw0v}Xm~$P=RpvOwI#c2JU}NR+5=&}~MK>i4GxOYF zC~#x`G%B^U=zI!#A0O~%e}i&1MoO6|Xg+x9gsbkU1E_zlJR}UUFoW)3NNnc98vA`AA=&OPM^k0l~wyiq4-nbQ#XN_F(J}LX{ zUS-pI*)&x*sON!TgkE%~zaYLlB^xYWf`C>!Yf**Y5i5u@Fb26`xY3)s$2QU5EV2S$ zBfl;Eo2@C3tQbs-w*1PKffk7f%iurX3)H>O0IO<5(X&qnA&%p*h%#z1>8>_gLw*0p zqdl(t52c>b%pm}e06n5*kW~e+S@ zer-=WqPb=4-_l%si3i>9f7+N6smM(rt}KZq*o-P3P1^PrKn>F7l-xm<6AsHKTPGkv zWI~PmvaT={d44QUo&xQNuepM2g(Y?nz~dFn@rm9v`@`)UcbiqX!5aAoZ1T)cp^CXL zx)o$&j8T-VD^=D{S~*~x?&x!Yge#CKAXzjxR0s;fv!`&09>!#{PIdY5b=eI@qWcb%Wjt##p}E;g2psN@z%KVp)!O6YY<=wQ`)tt)Wdv4 z+K47SRsbz`n;efQ17qh=FgkgSm|XV#Lg#0GR8K_#ldQ1&ce^gJI);b#DG0?n@s+|A z$r#`z#$XGuvrUHBcenKPj&oNg1w_l@4(>zsGGCI)%SP^;L9C;Hg?Nkha5to5mF)xQ zkOBp)@nb&*qE|R{Q5y_3TrctcaDXZKv;0jTp2P6XdE6CEz6Hf^{wW*ZDbw97irOCE zuG8IplwUCtQ!J(N5b=oHe;Gwe!}H-HK`W~A{b*nE2y3eQ4k}95rh?y;dA;Q z&$MeaW8|f8>9j+5tUl~IZSg=p?l&z+Y`9zE>_6yrfz@!AT8&LGv_xpHXYGvt%iUep z-JMa37`LJ$rqKp53E49t=4cfxg%p!iz!94S2t%Qh1_v|_KSe*tW0!bS6j#!LknLUg z--%01Rj8#gy01onM=(C}^O*rsI=}Lnj2DFOqpi)2t$2)hO6l3w&AGb~8Ci82dlNJ= zGlV|DP8o|V_dkl)4PP^}6A@cgyLwJI240x_X>T#E8*`*8GI+YYESDZHbzp5_eS8a% zQ>{{y8E98q0XT|TXLskSc2>Cg{|x%9tga8v`ZW>pyEEQWd^(XENHad+kzwL?aAWhU zo|VuV0DX)4FHb9EWh-i_#v^a+d-J(L9%nu&pi-57ktQUl3w&kc|7O%|Y~UE&0Ro&| z9&n+=0A`QhZ0Ylo(&)@M?S1Z#$pK4}?5&n8c{Z7(qMjc$lAzvO0tzi0tG0f&UE{ji zc`3RGcR3#i!T>pNzdR!u1FR0ee!&3)0x73NE*fg-+oJp13QKyDjVb7+D#oUd{^$3p z)Wd(wu_496-XG(x}8j`R>mZf1mSc=SBb;`$5n0^@o-%4oY#(AW>0C zsJL3bsfJ-!pk4qKOrjE?&`;iVq7JZb5z!bw49uNh$lSh5WUI1g`zuqc3r^-@5443? z4FSr&NYQsYHW}QrN0UfjoTFY+!B6Cqk^f*l@zDPSPT&dXxktIBe$DptcEa5;0;GQD zV>C3}iod^6FU`TH&PrG4JuZW*dV`~Eh`H6T8t7Zm#$fh-Yk`OISgAc;g= zXp2L!LhaB{T6!LkWgW%MDTy)=+uP&2<&~az{!)^qkQKj9@6$M_+2~zupKG3|cY!0n z`fc^)1sz%%!?JLi`Bza7aj_&>QC^4!UL(V!+?9y>ByUnTOeUKb?Fl?A1Ii4_2niU|_QXR&NC~ zCkK!`>3Jms{u@g(7lK{f? z9KUM7I|`Y;9IPo7vtFrmMe^iiQ@#;0>C?9o4-RKN+Q2yPk(0*S5&S9xDJ{i^gcRZq z@JUm~_M3|pSs!ptmL)1GE33eq-wOMmH!RDg~}H)O1FiJwmMW? z?~xVyatNRJgM*kPBJgWhgH0ni3wav{De>bk` zWI6l}+H$LJ(#<~{Au5>DVD~i{3?-yz-q)J*aHzTtR++xp?A?EzKF@VoQ}x8Q`u#hlp77g~FsAKLKE$Mr-6c#>#rdN!H@}Ct5*p*c zwSAY@A~+Er)AX_OMT(u-^J&$qd!w@!(<9)x?xqdEK3^*vvY#)MhfMg_8&e1*RA+gl z>uv-+J;QajxrlJvw4Nqcc8U8^3=j5qbWI~;UvCL|1C;`IfPq5!b>A07%GVnLd{inC z#o(H1TookJ#^T{8MR}ht-qlS3%7V` z^~lRiqKK@3+PP-915Ux!)zwX^>Vz-7Q0Va!ub|nPv@|y_C_N`(a#3NiJ%xXNCXM@} z7C8?F?eVlccD2HMLjzC|Tof065wP=G7fj9=|3}lAheP$h|Nqcbhm>Q9QOXRFku(zt zWgAOOV;fBxQJAC>g(SN)AtuBWG00xF-dU3^$tW@^A!I2rNwQ@f%kTC1Uf0iG{iExe zxsG$r>%O1Q$3wj@NqcU0E7C7w$MIdU@RN?iN;?q z*;IWKzso(s%b^&o6rF$dOgvP%HRK!rdFDEqz#VarQb`@ozbxgTmg0K-ocH={^VXyN zspLxxR_U*UIqa6p4MTJi$=tY{d*E4XX*maQ1aIlymutAS{(L<~f29}nt(r1|*Bd)q zl8@h3*3L$mlTfdZSsfNUp~5-CnHm+R?%TIX0dN$OAHH!w&QW(}Yn(q3wfV@y`dsV^@dCh<^xnDh>%g{kc@y2miYtX!*QhA~3Ipq!qK{S#N3|{kB z9FKaC@HYmsJg|!4zk&_I2YY?|F0#`O4S=APMEJ&Y;0eule%iLU&PonL5}ql;@t^_~ zh1oVg+ay|3ax6WrK$$U2Xf9B}8Khq=|HLj^^R%<0_GCOBPV!H_ua{=^>BRe6aCbm4 zZ~Rt0o-025d}Bs#eK=$F`*IL5tW-G`9EGQ`wRH`NVC2zNd653nL6sgIx}FqTlD40X z9sYj(+f*zFOOQxAu>>xi6qcMZ$^HZEZjKtzW%LS5+$D=8pGo`g!=W`*=YXl;DB`rg zCYAv}Mv}EhUX>J<3zhi{4u(hL(vppud z1Ks~!EjGu>@8f7o{HZ%Bp9iK(JzTC zJq!HIiT>uS5*4iR>9W}u7m8iOd3G|nR~rC*@qsPEe6bdCXrJHUNnD-ioW=p_g^-rx z9cE^*VTaCvAnhX#RA4s#t(L?Vn+1s~d~7yL-iim1krt#+X!Q>D9Id!Jr#_Fx3FQv@ zV{?YRcU|OuP23unT55?E;!M06m=aCgn^fq^Bs9lEFjBld`|67`Xb&UU>iqE}qU^%f z;v-mU+>mTtt5&5)j5N1nGcHZk(vxaY}(!8dp1f z_|CCC3zX8XE7kpzF5#gI9qY7<`y_}(GgcXTsY({Od)S+fC*au5GmoNuq-s6gUFTn3 z+D*LV7joXg6t@O|Y{3An(5c}#;ILJ0eKB-nisv6P^W!cduf*N>XZV$D_3I*#!*oZw zZeqbNzM8rNnjR;odpxZJjAZORo)@1CKgo4+@6j=B0t{?-#3H|G_gUAm=#i*PX~A;~laqj+S5~ziq<2Vq zL(b}2H{I@0`gpN_U(;iHtkYp$0m&ja^BX0}{_r>Ns^?cXjGO-3KGdsr)XDGYu6U96 zSDsyXmZL&-O?XV+q7Y7CJ9oIBt3UH#ryU9oZ*1BFM&Dwqpa~qNmv)B*uB#KGywYh{stR3r zzPV8`{~-lmjh2mobKEGNWHIQMgK_d1-fWgE5lx>Z{4_a1!eo3SC+;Aq$xZa&(U#4fuk)lu{z*+uCc7KO_tshHk7^(Im|=T+#fTi-kd-Y_Yq zGa4d^drL~xG8U{FPjEKpma83D9hgpn%!GbQ9C0sBpy0YH96L2Atpx?KadAFl2e-aH zT}WlVC^-N(UMVwWlsoRf`xXh90{F}Sh);on2LCpUAV~tXvp&!J-EF;OKgVa1V;}Cu z=Q}gRjPY-iE6T82-1eAG&rJodmj@r_Lh<{gk(}Yl+Vn=&>9#Jd`=;*6Zv>wD$; zBD|FtW{uJmpu&qn+vY~I3~Wv_Uo`M*8rJR~s(%ejllJsAT|KS*{(OB977eUyZW~Kr z{yd_;KHFv2T|LrSCM_5Ibx|Rc9H(;^CC(Iki(;JOH*wF`lY7>N6bk1HxkF>AAO22A5P3gq4Xa4LhxQFp%72L~Y z4&m1RhbV-|KD3{8*_?Qt6t$S{gfg&yZpVCaye1zpL>UdWAe(tLYayDcSSDgD_7+ii z^Rh?l?<<7G`*5|N7tD^2<7|c1 z8G_DBANWUa63z$k6s6Zb9+HZ2J9vzUyX)XOH+Y!iLau(nz^g>NR6C5hC^9~xfwkHQ zP9DxurjQVfx(rQHkKquQkaa64h((l-%5&D~yGmhFZItAEOrDPlxJ90b&h7hJGBulgsrY}p zwA)##z{>1YydSrXG1EK>@(h31(nJUS`^zKS1MUb|;t0gFIZiTS+waSKzvgKrG*1|7 z`R<}ObhSHt1})Ec>VAxAZu1CDB>q?N$i@`cWeT+1w#-j>OXe_nZZbvh?bA~N1_41q z4hN;t5W_I~5fT*S{mrk_?tJk4(zF&JtEQ(HT&W!JLe0ZJvWtLoI7Y~FV=`mS9Y`)CM$OgjVcV6z3gNK!1Vq%^7xsjpSwkRju*11zj zuFeGKG8uRA`?Dp&fszwVY>hl9+|1$`L_D&wZ*Ebzi4OXTh0%k1{wk_y?V zP1aH>oYx?pYzW==g0hB#qs`-Po(8KJK`f6fOrz$`g`{wTMy*?YVilTS_D`l5ZNlIO zUBZv1R(!gMj^IUZ$FgUeeY%wIadV`xd>wb1ycn9A=^CZM^+g5096L1; zdD^MRU8j5Iz4fO0Ht|$V^)sjh4z2Ebw*o_dW7UV#I|Xq04WXfnKblWM)}6A^#JA|~ z!ufjbTT@Aen;Y>c{pTlj?{mKnc%G-uyVQd=?mgbTB=MupNul?+UB&a#=U1Oh^i3`Z z5wG94apTegTb=m6#&2qD&V=ODFciExbHdIp$$nzkQDnWV&@TDF8&viO`xyKUK&*?& zdUvP~PApXgbd^(yi9m?DN;ijvuooWwS82a{V7n3NSqaZRm9o=FU%1hSbbs4k7h_~> zt4Q_-bfTO%I(t>=;R{7*A6*rCrhIDp!M5AT6)<-qdyBQ|@QUIdSPMdu0OIj-7-wwR z>!No8&C3p_Q3nPGYFB^VjlZIKHfXN>ENnw<7YIvj?>liqTL`nzWQNtwzvUwmxT$3uyQVBTsTYo z-F;!6T&^uv7(S;6(Kzk8ZFPG<^(LT7u)3SonXxJh#?N~eZQpb_DS{efqPk2nD;_@qFV zFp#De=60QE%-JNR3(*s7}!KWQh{S>NRggOdB!*zwn?C0ETviuFqw+_wAA> z($&`1KBiX^{YJ(@42xjnchn5@E1j^E#LDcf zcMXWv^9!X9Mc#BTGAGn7kF{rNuYPJ+&A!$U+`ogaZ;5o4>^4A&PRUWsU~$GhRy5u- z?X0TZz(>E}YitXke}go4fUK236v&W~^4%|;tcu%BT7wOtQ^mm6rG}%IUD@GMkQ1%;#ntiQ z{P>Jacod?y;O{O@B(v1X@B1f?qMMvAwGuC7SI7I(?yx9iSb<4E#fu9=@0v7n|IDm6 zYDbEtFuC>fh{8TJ_ClJjj$V2mZb-iL^d@MS-S)2`=&k`|81Db^+tebG1A590Llyxn z%1)C96RZF89`)w1R_f;m#lp4ejzb1;4AHWa)i%C76^?XKErd?uijSs-Bu7)I)OK`d z;%zZ&#%a(9k?aEu{6}|NF$1Mf`|?hpx60Mc`F|RyJQ#*a`hYQD#kU72+y!M%x&I{y zw@k^^R z+PFO0rFgd^WB{~F-=pHazXY7_P$~wtgi0^24f%KJk7V(v;3$uNF;gSvax%VSHz%3( zxwltl{b#l)UJ;i^eBW8txwa1AxCL5&7Qqe1@iaJwdkj^~y}H@G%cC%B3v#8HUs6+D zFT=61dNmbDeYkAx^}>Oi__qbid6Iw6=6GRSf$GuJ`GC61segH38mVO&GwM<`w9`bu zDJ9QbWoM9b+w9Muw`8|+zRt{uK~FC4C|myX`?t#CSWy`i7P{J!F)-9H#s5A((UTD} zE0kSc)M|Ha@NQJ?oX|c%o{{37^&ksE!TaL`0K;F~buiGq9Fa8?5kN-(eW>|FfyxOw z@`i$goToq8M*?k>ucOhd$I;uB?qY9A&kBlaJG?x8vSVo7qjdy(cO#q$!rOU}^HgqS zwIo9qBeOx$-bN4v()r#v>xZsfj^y3GqMkuovtsrQy^M=RBq`c5=Zh$$ zzl$~bleU8xX{zh}x|g*p!_8Z@m`Slu}1 zaIUr?G`W0d>1&1o1kAWz6W{P61VyG7oK8q_DVj*}Nf)2ynm@~74eAfwDJmd{?E%Go^$k$5qt_bCdg86An+bFDidMeV!;mgt?RrDY}4Zit4w zy(KW=w$aSe?5-3s6&c45zhmaq!=HSzb?jmvRy6LE)uMx0-Q_aC$pnHJuRvC zk4P!}DcTH?6kD7F)_%`7#}sBx+^-nouXbj4mSvB0_PWrX&i{jG>Xh{edHURS8#55n2+-TQndZX1t6bPx4H>Nd8g1)x z+3PUO%0+{=i7gzqH-9a}PI7ZL%Ozz*rJDX_aX@Pa$(!j+l`^r3i1)^mgw2H>w_mjA zbb?zl6_TyVk0n{^Z_M;>2<=mnas9F-5?SDm2_546WN*Sa6AxFoS3B&YM}#~r?6cHq zmNYUW2shUG!TO2ciDc|89@*w;iMx-ZIUIo`B$Xg zLCaolCy_!f$oe?)WpVBO`}bP0-S%q6WWuefItA86>KMPKX44dLS2^4r<`7ZXe z={7a20ftjlEC!aes1drp7w1(8AR21v>2Z&KMavV-tO6?8yWNBuxnD=J+Xv?FS5&IB zmQ2m{U97N|F1Qs0bOg%Jh$3^#vZ4QGTV?nlhBd1v>(LGJuXhOcD!KFjZfzj765)q_ z`}gdnkV2QvuYMm|ZMPD8%U_d{5T|SO!MGe2(+8F5=PBEgRj|KU$dz~Ec&#!vyIXN)5ANk!k8-NZAhQp`DLv>~ZCxA>HozrVka4}W$v z65v|mz=^8ccQUxve?wB@0t+Fvm0~2ZEaEga$BQjYMNfGrbzRA3wKl(YmL1y2ni>~8LUB%I zTUi`L7zu(R#7wW%9Z_2O#Ri~q63l_IkP{g)+{bv!@TlSs)K};QueHyYOe#xr?A<0k z`8Pst5{0A^cDwmS>Pp{LQQ-xhqhcA%vJNL3VtU~dAnEBo87{V!2a z#INEmZOIexXL~x?CvKZzaW|mbtcceKFmI@-R2uRPk-TT2Hj4eBB*K!U zLNi0%IjvuAM{+`zs!{ah$0T3HhxV#cCRAlb_4YU?qB57E&MWE;sOtZlUdg23a(&dK zK|WV#-&8Oeat_1)UrH7vn+O-nuM3t@P7Dt8!=aR;I)?jvkn?cQHr zOs)w}C;~4CH_rE0MK;~GDae0OP~Zh(Ta~?6H7B;Co~g9b9IM)I+n!e0jClo(qOT*^+R4P+XpT$wl6pINS{Wc^}0IorTD?6Q;1j9(9#O1%N z|Nh))2)z|g+2vkYQ|A*>;h=(5lt3UB=53g;FolezxeH;t$F9~Lh!#{JE58`rMTavf zQg8ym5Dz;%6Gk_Fw3=IXz*Y2L0|ZxHbvv;LmQC1jbF+W+>*_xW7prp-Iumqdun^Ap znj`g8K#Fj#GM2WQ6qtBoqJ1WytSRtzb$g z{QXzaCcJTcG|{3H$mAFwe)~IiL^vBGJJ!NN`Bn9J4m*wQ!aNteww*2u{coQBqq(`c zP4wI!zd%J6A#WlD5E8*lthCXrUeVFQENhES2S-O@SWy|j$egbzH&1Zwa80jB5 ztP!n%DG3M~wcav~bxN>;!O)`lCp()t8n$%7gZ2om*a~yB1Q9xb5dc{E<4+OlHXRqM z{1)@wc)>#l6z_=ITe;GhBgwYr-8F{0dBGx?MIefj)kHyC{FU#VJS9G>xXAmB$A8b z{4dH8dS*+n5Z35A>w8e|S2xpKEc&QNqF?2}S3yKOn@TIUIQvxI6sGifRWx zOk8_D6f!l}v0vApC&q!FoNqfZ>?a4TTK*g0$&@C?2Wyk!xk0*drBxs<2XVk{b|K;3 zu!>%I^c%uyi-`o*XNOo3Jtqc$0a5J;&94gXDHm4re&{M`E`kj>Qir;fEl=Fs5UroviJ^Ck_6s%oab3$Q#cd& z2mT-0`C3uJXY?kCC>#zaU`EK{^ZD8H9R8CEwbsK+PWO3iTT*5JeqM1!thW>;rTwD4 z6%sx&LeHM}tQlcCGr~k4M~S(_-@Optj6^yo|AVkkm>iaipb72bIe{=7uTl_(6J@7% zt(ZScpsX)Vm!DB}VdC=UuVm*igp{#ai%C3QLd;Ji`1`FgL$uB{^||$5OUYi}jfRPm z1;6_BnxEd^0=s7H%l*JV^Hjb%Ip|BLG46gx++J3DT zG>=d?p%eB|!x98Wsd>pxM7Fp4)&6q!%<@&eLbsS@`HV~Dk>H5ugDuy*_Wb$L)a}M* zJ7;Iczk}0nN?uJ(>g5!1=(Ic0Jbfvy+Z}SEo@T4-rqtFN!c`tE=;n;j1@FqI{q+Y} zI{L?aIGT=;7zb4;)7{0sq?z$?XW2ZU@S5zrS=aZJ=uD(${tg%`t<+^8wKqfR9ZI@S z(mjAR!zQ*9P;?CAC4ScxPGqG}8&G~@dB_>$hEH$m^eiU_t4wg6Y27=$NFWU6w$iU!9LEbZN1 zS=pSn=vN!t*1GH*`gQNZl-ynrD|$Rr(pQEOR=Aoq9m{ES!4#?bm= zhQm;8752#5nNz+;3TrY`J0@NLXRGFk3D5$$>JzY_zZ$n;Ytv<-y}KefAV8%}{`rsc zZU=mLyt))InfQ(?TD+frgn{Icw{B&`2R-055!EmAWZw$ydyT%2-6Dt1rA(u3qi&18 z*}NYW$orrnq!t9TyqL6}y_Nm>z;dSFH+6HcKXIh<_=nv1kTvTQ0P{{1Y1|wQ=YKfM zU;kU8{ikQ*h;%Fex{uER)|+GqHG927*$9d2WQbWp)}-oqG(Fs`dm)fG4l0e`;X_f2mji z^*HAncxGX;Km88q*4$(E+CE9lco|H+{RYpvGk$W=rjN@`@0JLf_Qwg^kg=S7$?QB_ z$AuBC(O(kKu*~RIr++I=(srTKH4RBFL7_g!3Q5s3ot+AtGv+S_WrO((D|QVlJBgPL zOJQq|$);CY4eIgrRn4c_1Z&<`@mfX)T%6e-rZ~bcKq4I%8ym~Gm(fxyPd;z4-pOn|M|$l{8JM` z&dD2&pIV3ygZ00Z1)#UMTi8gl9yq-IRg>;@`l-0#mr4uTqd{$=*>ru$@8zqN=hS-I zMlZhT)6+ZnTc_C!#>M>TvO8aV`T)JwCtcW3ITGGJg3oAg2$&xQFk|lu3dM`;gqjPu zXu5};=zuqEe`;lAl_O5tiMgHHe>Q9wzn$vn)%g5c$$s5tM5@d+TEGBLR%lG#CRUrz z`k7l^r55Qa6|>p&Qk{blgc#(ipmPUbP2Nl$a=~Sr*hraV7LW5SRgN&}oti96YgAd~ zWCUPQWikf_2ZJ~GLtsIw8vRCFj<}B@2!n@0Yabt=2e<0iR@bHFfe50n$Jw4E&60*1 z_igvOL^$II9oQK|L;4PE$8!yVC$&JE>VLuRI?=M_AAi>zsgGC*`H_J{Yw9CtpF8=P zFmo6PAS7C+n|p0&Qm)_{dd~wtTy5@n>d|X>CB#rsQTllQeF71kMO1MM)~gu{->pk4 z#)kDwc}mUs(@ui`?Rq{Sypt34^z`yrl_S>FBgC)2aK?vFYZc2%42Bp9C!>pva+wa_ z27eEz%VV0r5Go2-5P&a){p4p!{6B^u(a!A1CsU&3&5h>l#XTe?J|WMm;7(g zRZ&xQ8A@p_Z_x@Il;CjvNQVoV$V9@N(XFKvfISrlS38KdS7)hOSz0!%{@#gYd3pIS z3qsQ%%7l(YerWB8i;Lr+nGY(|?tDW_CxF}Y$-?^ypLa>r9ioZ_FCE<&YgnIJ=WpEf zDNnK6eE0Qlp}cp=#&CjMKLiIw$F3m^mC zj76jT=pRQzM`9+bhAa~`Z_1ht{!n4@3q%)VB6BcuwW#$UBU!wWfuy)#U|eoxoRw*R{cb$A zthY${r1a&k^X%}!~Bg;yGejyhK9%ckF~8R@iTzSFSe_FdjJuO$dSqi0f3DE3oimmT>s>vNhZ?BFOj$_ zPNL3L$5YJiVXRGVJFWbP0n6)NjhhWK&5PHr4OX=86^wUrVpulCyPTq|FI-#eZW`eu zg1n;1SFh3qq6!MS?Rl5an9aNl{OPa{QpR%7I1{~(t@#Q4Es?0#Uq#!NztPT~c2(Q; zH+`=dRH5=Pf$bA6WcUuyjK)0kk?@LcTB^;i>bnD#j%C+`sh2>!b#ZZ#{V98XW%Umk zZq$C>dgaJ@a%WBj2ia+oS+O^gAfb$4In|LZCs2)mFEcvo>S)Kl_jBaa6$?o9!lyrr zsqMRcvBy75=QH}N*iNL|gYgWhod zDY&s3f_`0&20a0v7n06`VynK~ezcK{1%zQ#bWgNLQ2K5QB*Eu$%ZP`^f3;& zpN=03^$O;v3sFy1%s2XH*s_E!+&B8cI6H+g6cB`5hWsQmDPVXX0T{t0zpvEvgLf?H z!9d1?|2d)voHAWVBIP!F8G0x#TSR9Pp@P9MYNMay!bq zeI575JBakzX97F>cEZ>N+n&n7YV>E%hDE&`v>SB~eILu3RGJ47e;F|eAYkkDX)BnP z=!Kqy1*no7H2c#wltei8U7c5y7%oO!>1WYNoDw3Fi`#SzpUw&S&F|1#{+B4K9|q1& z1csy-_N~SO6eg+{1h%4W4J(E3w}v5O8hJsy&8}2Sqw^2%CdfDcM{B=R<(BW({@q&2 zWT-MAB}J!k$bKUsoAv!p)*V*y1z== zf&xz=5v&KZR8A7#fg1{5gts5~&OX$I)Q0}Y`SAOddp|jb$Cftvq_I7>NX|6(i%Z38 z$TxVX@_u&!;rvfKWzzVkPXyvqxd7Z|Gp85HXX%yvgYwrywb1S|p`I|a^VI2F3&(_6yliyvb9%I=Wv#b$86qW>X@=8ksYmS0o*K87xnD$S4 zYNp<1VNfWs+#C?lZ>u&F!mF_t3r=-w^NRfb{#d2N+4h&KEjhE5U6BO-;vz+O_5F!M zMr1}QW#`7~Txdu@5D~eid4jYPKrqKY`h{=PjU9|^$)Ch;hi=Ej%#}=?uM5zP?F`av zL0>*r=RdcFUhAO7?dT|b8HM~QdPwoM#0oab4CiOJk1Z_R)XQiduB<7R^wumSTm-)f zV%jG+6MnL7O)L9bhWBLO_!apLZHBSoF7SF72X)Jdp+=IqG+Q%8IDH(f@}MW8gDp`q zN9=iJE>poGATNm9jKH|Vo8DYH`0xii5@ARN_qYzbQ>irb_|Qo@oLf?kdt6x3j3$pmrQvHz@lshy(2`pud&mWrtX zd;&4YwE$>5xlij_;j3MFGhq2RwJ|fbF_s^C?8aon26!z3u60#o2)1<{rDG)hCon|B z1tk_XzP!9y9Kv_%gZH$T=bvwU^E)piD9?DpASwDJTa%tuoTdoC;fwg&=i8oO!w_e( z8S~ukk>D_Rqe*|Y^XZ;3%A+GY0o-lqk61)OJnn8JKaez@u|A&RZMd;|X#IHM7Uj0v zO=w#)!pA8hGZ}#>%)Rt?+GX9Bbiw4(4{O|L68<>=7cI! z(@ruaZ~}Ju@$bx8!k3G8x4hqFE7=U94K5^5(3Rah7?;jyv=%y%1bF#ddSmkMn4{*HU(f z{jOcak+9*5ZOwvVx7KG}9h1Nt76T!@OFeo%aO!5wLHeJrp7UV9P*YRm`AbQ?E^zVh z!g{QaXYnQ^*}TVhC%rW=zf_f9(vgAZ;2BTnqYz=NHZNmuRZR0|ei)`t&tn_a0FueK z=={0m9QUI=o&IjezSIpY@u}pGkMqQ66p*G9zgAd8f6o>@r}}$kF=VOVvEQ-@ExTX$Ua^IKG7n7dP1of@}UTCR=DUb_fb($1!j+U~{O z6k**f%qYLxgdK*$T--C*l}Z(0-mGyPT5L%@qIg03yozGR)@O*2VmFQYP9)@$X_Co! znr-RZC>WdOi#29`Y%7!o(2__1dt3T%ijRJy6&u{6UmMzRu9!(M-R+i^Uaq-C{+4&p zE|+*>SaPkeiOtW-z-~33al}ty`ti%#gQ!eFZ7erj0q*Xq>@3)>38xJ#AHA8rx_AmbW`gQAo5s)Zuk zfX>r>dt;fnD~Jngf_Z_Vsr&DHhkw(buv0Go<6bT%7xkQA)a}%T|C_INi6Tz>V=D&jYBb z+eGys!eDLS(e2q?;GC;*>!<~tw3q1g?`Pezbm(-`Fq;CFGs^!1h29ZO>~^)GWhb@K z^eoMALQ3JH%MzkkE-&Wlzhq!=dCKK-Tf9CTNMj{bEX>SYmd)?b=a;+hxa&ftxiIhF zgn{mfeDAQJyfKm|DPsZ&G7R+pF%l4oHy2VwjPE%yF~Zo`ChG!mW5C!){CNeXtrj6} z9zBbsowSVPJ6N7H51mau-0r)bXg0Vt0%0EE(wJsUFLaA!7VC4sp7@YhO<@4`QjgR5_ z+tTlP9IeaziQWSfK3Y7P2aDeV3_ILhMznrUl`B;1vCq=9Tdo$RF+KU3bjhOoL$!4; zuml>4QC`7P=c&@aXm1rbRRBt3jt<|xeLFsRbNTF-ZhF%>n^8MO-{f)M| zsRF}CK!i?)x$1tE0X-T<9`N-8%yR&3XoBmq=JhzyZN`pHP5U5 zrmg*5*s>3yzhMwKNo}so#$z$yBx*5|e3z1JZG64omr9k%=2x0Gj@MV=4kr1y{|Q|Z z-5CG(kEw2oPia?a?VaiE{onVs4!*Un%<*$|AqqJpf{7eJ1`D_|5tlM;aUu~eCV)wE z!Nlak`&}`37r;&?yhXkj6wGl%cVSi|z}27s{spyBc8fcrPl`x%s_d0-iCZf>rbY8@R`R#=3lDo@Z|BXx zOFIDmUW6C)>s8)m#B@Ys?9t{oFVnk(-jqyuyS?UXZKvmL7img9^4CZoh=nUG604-k z3WTx8b@im~iW6^5*peCX(sp)(CrD9Co>q#A7$__DtGH08!*yy7h?Rc^t9 z`Cwbf*QtrCkq^AfXi3!Sp{ZgYMUjX2BU7%lkt|akh zll7O;80kZz7PehG-~0jsJGp!i(XE#QH;A^-Oo>9@Z(DJqQXTh>7U zwYWW`VdK43h_{xk9{-QJdoinYiVp%E1u8WqlPi@aZpcVJNK_2%0uSNDZlp5^=w6A_ z%hFL!blq&#p=&-mv6NOBxvgn4NhmtXX{e%+A5=~WcQI2IQtUe&Qg+Vck-K}*5mR#^iE@C}Z_A!HcYM_M zD_Kw}N4d3RH|Djds19 zqATZ?bN&LgdFMh>!|E*Htyw_Ut=p)=&k%V4ZLr8}^^(17jb*H&+8@Ltn^5*8rkG(jJurH zWh!m*80xzkE37CdS2YjvcfjGh1qre{E{HLSa?0c9BWB^j{Rc1l@M`15CG6XO*H38M z1sq0aBR*@}PU1xS9Wz;wYDGz-1#LBj20W`c>a=#GXEZ$_CHkKL8%7XRo$c7jeg4!=X}ElYMG zvY;p&qZ;j+%^-=u*Xx+mum~1&K}Y6!yixwuf{j%Wv^i^MVx!^Mc@s!Y zlf}d0yI)P(bF|$AuH#`r)PQrt)T>yp0#g&*$%Gt_vx@UK4sYU02!HtK7lOk-w!G$f ztxUD7TN`4XViJlcZ)m#rtF;}@-Dix@MZ(Iu7lNfx$Kf}n1?8s=C3DRm?K4*nAGq1S zs5|;C)NBufE8uo;o$EKGudn|+bqn+)EtOoVbx*7@$u4Q4J)qjbcf<@0-mvwxwLMo^3QqcnkdA<)?)uKFCb*Gp8bZuQqCLf>nxvIABo}Fp&Uu zti&B_oRZgVkNp~QUdvs1zcX4`ENFfSBAJftZ)M)y2y)DugE&aV^*wx@bwGajk^6@-oJ?D+pPos zscC=t;6s#@$jEDyTe!Jmi`PecF;aOK(?%^B4%cWOOQfY+gl%qmsw^QIw|naon8>}m z>2&Pu-vwvQv||${K9B?%V~iZ$%d*&=kIQ|l-HwR6SF3BF|)nt`)e(^mfI9# zc#K`(^{$kBpkfG^I_~amDe?S)N5UnT=xneWmGUXvqaaED_w#pY@quhfMugMXFYWmm zA+08eY38S0*tgp5{eWpG28&(-jKDQ~xnuGDKIyHv`H_(npYL%$96L>%Pf6`mk`#c7 zEPiOgZ?$g1MjpP%7D{2BhjR7~Ev(=+HmvZBb5=ii#Soj#Ao%^x8Eo%6}VVRbhpMX2!o)S=frrcufe+22!S)pyjH(D3v zGsxP~A;Zo&fBU+1+=@?*XzbY3cosFiO(qvn>+Kro0 zAMJZI0Ql|`Y1v4ffd^C&Z+}0(qp945$h8^Z!TmWiW8+?&HtO(gaA1ta)uOY{{wjI? zyi;RaIH*M}-qKgmCJBkLNX{e(#nmAxUw2wt(t7_nOBocHH_BC`tr_UdSDtVdYq~w4 zU5j7}IBwvyX@H6>{d#qQh$5wW$yN~d3jSr+G}N4c9|ETOa@`QW(X+|~1|R&PJQ6%K z-*kz&y@`QbVLdCT`ucTX9iMSX*{$#E_zfurHe_aX989>qWHa;vPy13IxlXjqySz|t z3->Cy|CpR_h^AQjf%;vQsKRZ63v+ZC1%2^#9P*p0o%_=@(L<%>UA`F{oM=qQy%72p zM2vxlq6|dAknj5ZvQUW=-vid-d9AU6dATO4 ztfj@*=8-&trjumcuCBe@yYhYMSF(*@*kGG<_GDrrgL;A-^CD2BLx= zJo54^uILUJJOPe0TLOy18nTvkB(llZZwtNPE(^J#Pt;qTfCUg2Vua13$kLJmWu}aT zX@A}XA+y!~S-EeCJ74vEHpb!y8*{PTGV9mROTOjy?QUfS1=`X^J+!SD;}iSyyKj$l zCWica_?h)NM6+v~oJEwt~>=1hey*4Q6lJjo{nZ#!ntt+iD){B_OS z>HdO4(_S~@o=xvJ%!p*1iwE}2D&kh0B04kga!eLt`1IgU!-`-)V01=Z?X@;QXAoup7;@c#Pr1*u*W?tS=sAd-PRaPI1*ME=<7O3JneQ z@~R*3T&dL7)ms^xKQQ#{3jf^o??neER8E%RMb?zWoypqgRi%7s7cT#1r&{p3&tR8s zXlApd`0^IE4D0?%6Pp{3{F@HiE@#-(5%NmcJdlTT`N~ZSP9+ zUR;7?pPv~=PLswU3OtvJEDOAQ0;C1l4-VLxHUunFNL~LXFIEB94^8P7Ciid6ZKM^gE4f*MxI0GZ0V!bj zOFQl+C{g+S+_y*}QGSzm^`8bsdoS**%nY@$`f14s!=5TMF+)dBS9@OE@UkT5>E++f zvZ7R46)-b64*76$KT~2!&)#3iD%RwzY#|QKv%N)EmWS*7GLHLanbM@F7)BZXquJ{q z`jnkf?GY8FJ*u$CE*EFZMZej_UrqDNQjQ)$z=6JZYJokg+5xO|80@VSw~viYU@JHK zzKiOZ#C$M*_2$NZ5%I@^S5`Z%LW1Xiic7qMEkD2fD$P2a@nrXxciK(K|Bt3KkB0hv z|NmghC^1SI5;MpW*|V=>%Vde7$l8P^`!e<|#!?2wL|GF?*-Ew|dqxtJs*!yYus=k;d>n&B}DLh%tmWl7?FtfnrEnBNS3ey zz+l)7uPkZ@p;~Y#CFgZCjd(SB6=}TVz!b|-&fRV!q@7k{%}wf<%Jyz%Gf?4>=g_0& zSf)A61kFIt5Z-M!`}YwoDB_ev?=XBhbXLsZHt@2#QdIPH`SCQc4#x9a^4P?Mr6m*F6 zx4$_Ed_ggCDlIDN>YC%rfL`OF))W;^fQ#bfQ?M4?j!_4As$wc9XIEDjeL0kLQ1ENm zKE3Eo^*I%Qe;QLjEt9LjP$s2|%rm>PbFk@Pe{7?@H&8_TonQ56wb3c|-sGVc4GO*ZuRt||h&m5C@v z_@!Dxvii!RR6Kd<*u#Gokpzp$`cZLcG#@LwGq(ZShwx-5lyutpztpd)NR^`s&GDds z@{(r?r9>v!iMB3h{=MHN+K0PTw@hmHXKlpcvR5*T7U_{3lmnIH_F|BH2@Gu&^80G4 zhnTPd{9+N4x69ZJr&WMpo+lwqE`uzgdzGW`huXCp6(prg`6i<2kM!VtU5JWCTSD9H zppBL>RVrlVU_0u7o~p6NDx?py!1z%PuJt({lH~IGHS@IxXJ)q8EG)nb@ZI~zFS)3iewwuzj{JG*$G1n!QTX?hT)WcFoMsu z#3W92CecR42|tX$z}6^g!^kE>Q>$`4{4}UCNxr{%W1CeMRm)%~SR43(fXK+Y+hFk~ zrBM7eU9?C3VsCi!zd62(E|YkSq}wSpfS!U0QgGu~x5a~s)w@rHiTgulvI22T$IVW$ z#6WaEO#U6M)Pq4-!Ns_GB;WyY%j2j@@Yzq|fES1j*bg&921L>e*$r+Ba1fu$a&L2P z!>bgt^ZD~VgHp=|!}ulX zK@*5IeHGu_kR?1}=~MkTonevjsmNR&0fc&yjPw5Rih*DS07th`?rnD0`Tl zDEg{I=do?=ZB5RLXLY`-xaX!DGRhuhUcc`SM@PeDxE=fEOb3D1cqK{xaXN$1)w!5x zSxRbqj?%dRA-)$s5jVxdL-QqVbU5WSH8uJ}Z0TDGdSkWe3nD3nNH|H(y*$?I){=Ck zG_RZS={t}bQi2{ZKZ04$aQ{R|SGHR8u~sxBx~q!8%>sciyOqxoFZyDT#~{uo6yJ>p z&5?-s%6tmWikq=q>3PTPx8s5Kk$0B4pukW)XX??S;}PBd$9^y8(eK%^;iHXp$G@D% z3ioA>`i~@uXQHo;2NwRcvf^&MYu7HwatquY+kAexLn+y8y|^-zE?uD9%089VJdh%UQqi)radp ze2F+i;MFyhj8X$BmE#;@)Ki8Qrzd~#WV;iZSnwxNl zx1myBXlym@0}Cs0C|zo$(W`zO!pa|yxwKdi!&C@0vQS~y+KM=Hd_K}$_TDw)CDP6j7;<1gQ#C1wOe36>>QJJwkE;4pJYjLHRV#`)c3&2 z-9Au6uG-L_yDhwEfck|eY8`?sl7P5cMvq`MhLW5R~(<+-F0rvE_%b4AUK@sQFfY{$B2tZ zS34kLco09neGs5_ZQagY@|hvwakR2$PserrPox}>bXTmv1;_+xj9jGy%qj1Vj&h8mZfC(TDgSx zHMS+j13{XG_xX<#pUP2AW!cr!-!%vO1P z;hitSwEEHZiwl=|OvmrpR2D%wxMB`Yxbi17f`19>uxL3@@qmq2S$5^I3QMx*sGfz1 z=oz=mZu*iVKRx-ooDmd@Pa_@ze+9P~_QRX$#-fA|&5^N?z;iR{Y|z(IkCCte5jhGR zT_`R@x}4$91%vTNZY{~fKHyyud(G}VR2!=$3AB}s6C?)t#E;u-jx(v zNsNU4b=(#9j?La|Srad>zhD&fqwWn`aUY_>bh6HnE@JlN*!PE^yC8VjCU{z3ABmWL zepliwMJw{$rDA5TB3}~;4pk$>-Nf>$ysfJe)uR~IyD`sh+T>XPu}YSSsFvif?TE3U ziI_9-&Xe14;j2$#b)fu0Q-v;=QdwBdfUV@WV5>ps-Ff6ikH#_M;s#&#!uyEgfpaL! zXP$7w16f%LT-1WwLpeJkfnlzFAl2*7_pezH;RY*INl{|t*0)0DKRA6APiza58XXU;JTTB{`;vUl~%t867HFc;u>PQLhj!*de@HOw?H7W*a}FUhfx3jy>m)W*41IW* zqxIE;$b;;DQWc&m3Se*s2=5?(>}XR-qH^oB#=>v3v!rmPy!rrym`Ln5ah8LZr-ce@ zI3q#|6CB_37NYdwLRexo2eyZ6!OW(`N4=DZPX^b%tOue#!-TO?==saM zfZU0qJh5!Be>4JIQ0!F;ZiT6`5Tt!G?#g%DEw`Xe^AKB1{j2{WK) zV+mt82d^z*R3i>&76DjV=5S3$a5%N!K|{IE%JibqGHU^>qf&6R@&e^YRNO9W?VB=R z{>+|dc(4D3P{Wf>GI2wh4DUz%GQP;!*yQB#(e45VD+=nuui{iA!2yQVaX%W~(CbQN zA*r0(;99nlo6B#XlRxL{_uf`$$~Are@V73G6?w2t>r^Mf^>R>RKRcOS<&^#O(`@J_#xC6dx`Ss|COV>OnSrkwaM8rTq=i)v0l zx6QdIziiKR`3~0^X8R(Tx%fO^$;QBrqajo0k}jfON|kj73Mw$QL{UWQxNJZKKLN!V z{^dI6O7^#07CTs<0e2iO!`JMY<>78`(dDwTi>oL~ZGHo);i^EBUVv{mVL; z^96cgC^Jw+o=e(|Y+M&xtOGMV3|$tM!y+_glXVZbH@6qcpU_arhI;-4{ANm~R%dnL zKGN_lHos5f9)u~Ij7V_u5WZ|~7Q$YcYwi9EYB_5A@gP3uA^f;W4L;xH48aM`YCnvE z#L5P=3PC$$`Qx9StWr}uL6{;YSj;D%wWU{jvQZ)?S#_h4KW%v{o()m51|M9>?ITln zy@KY|jAcQ%k$@Du1VWtA*$rrTZf3+8xeK?z295LbY zV>}6wh~uiET2TliXKpyAyjp8_h_eC~oaJIG3GCZ;DcCW5NJdMDKjU4b)Z;98p1D{b zpW7Ak&fMJGbgGtgAglY7QOn+rn>NE`vZwNV7C9{VL)qfu-ro7b&E@6sAnl#0>i(AZ ziJD=n4r+HqMm9=X_6Pg5_g`OdQOZ4y`dS+5AH@lOHa%Y+2eF&{kC`>2Ot_fz)9@bz zn?rkH&UD*7=})Tx1oB|)9C&=?M`5UNJq}_1I4&RL6f^TodG=g-gQu+M5TAQ;#(=Ft zO6*j-utx0=#U}qh|5iTtnl$u3l@xeP#3ZNQ3UScZy?8+J;&Y^aIUXW}WuicZi;9X! zPDCcCB`3j&m?&o}ku0l3abm9>KumW;de?sZ^dV;kT;^_Z-$j>4!9Gd$*sw~ufeN|d z5}Tm~w?9zFQ<^L25}JHiI{8g$V3o#uI2<&N(`@k_PkPCPmK;brzv#U*QOfhdg&(Xf zjPVx656+`Q!6_%f*q?zG$PG~?i>xj9U2sEzz%$Sx3wj0@9kQ>Jo?RJY zQhs6b%rfR=@y)c)xGWv8k&@F-qb}5}uu_73RlfKt+R`oJg~I*tyncrpi)$m)vYRo&*klwqsD}Tt;Ik4zyJPT+E6q; z4T(-LB3P&pS+M1T@y2<*qHp*^wHrLLM<1lSu~B@qUYtNR?=4CuAY`M64Z*#MnJMYlsl~c_sIX7r!C4rWU+<(c&=>EEM@C=c4ga`9ebqyp*(c z!pOb6IuJoAIG>top3xKcGZJ1|OA4wF8lc^jxSZ5(LsM=hO^pQniAHh19X_9Uo!elj z;e92$j|IPE@u_!~5}c)?2#Ggfi$K2c3gl&FPlFfIhmy5>@7&td{g9i(SJ1NT!WbI_ zG$*N{l$I1?aW-NSb1|u-fNtBuUqEs)iT8bOB08+BOkMbC8x|TG9>gH8gb|RUJDo{E zjxCX%$tPppEsug;3Ak4m7EX_NM27mQ0YDG=V^dfxS0F`>GAj;-vle}EGGg2emdH^2 zT)EzJrx-@FAmypWg9~2=!kb1kqE_z){SxF*$FR|)oMKL&HhT2q5={SprY$>-kNaTC zVu?wm^;8!Yikw*aJ5gk#m?B)Tw4mO<@>i)puZ2N7qJntdNY`73h+U(oo!BaGS?Js5 z5L5W0>0h><72N|O?92i_FlU=VV59ZT0fVqB*_(j~!{WinmZa(1m`6wunf2wrfrhmi z=iGMEJkE(Vk&W72I~zlgLw)!nI&xQTC1HY@^m)NUtrPy$d4DQ)#l&rWjKPp`h#cRF z7y+9@ghygW3hnXD+XLFdvw@9mFrk>-Dnnij?4lGbj)enDGL>h|skN44_1(E#TIe%1pcYxYfQ#A$gVon0` zcWHnB@UL%Vz}n*0@8SHY)!pIAoE*pfrOcL`zFX&Idi}@9uHftSr+9#`**$lF4-nH;`7x9aReKf5B;N`X8e{61XmRA1Q%dPj5Gy?;{ws(M-SAAnxk z9=j5MUE*>vkdX_|lv~-#r!YlZz7QuGy&3ZgKWY@*=y*xA5fHRM)!^;5iI`#21X<0z znGO}`(n{{RJJN{o#2JySG_5j(cOj~3YIeec?9c0? z&^y=p5m;Q73TsyB+GSVl74&s?|FEM(w#)RdG_Utk$?dX_|17(nIRPrGPa4|x-$bbz zxUXwF!E8+W5TtuS^`zb8eo4#0(*lwhj(W=S(#W=9ir!eCYZ4i^E+rW6AQ{I6{eH?` zftU;bc^g*)1%vX@x^a&o=o!lVgIYCB?f*5rszum_E`ojVKSMzFt} zVTP*5#n}ng4V8-v9*^bn%t}nh*O0Ac+h5M?sieb-Gcz;s<51`Cig@lg!))0Tg|a!lqSLZ)bhQ-FU;ch83%ET%#BE!N zBv90#s{!)6fShGvbr$k>PH;@zz1uqy zn;g0~Q!2h?p061Z9K64u^fr*u&b-YNwc1i^Kl|-pTM~__Xk@M>-88YO&6Zw zaVoP>Of{}QsD0mIXi*_{7xJEX#Tal)mXVglpFu< zU4LgcApC!pmTF_Z8WTIAF-<<|z`h5I|1;oufyOX0d|`!A?Pjm{yn# z;Vi7PNML6ZvpIJh?QUff@=T`m@@$H-f zZswkv9^slxQt81_vssYyc=;B7j60Y%POoOg3xRVa^;ihOUY2aBjc zrdC&ajglV@ohC#GpGSUIx`6e-2Q1~B?6{4qczCMtwbvMs(%-y8Z*&=YsA9%D`_ty@ zNca_PHSNPeBf;cCX81~df<``^*jV|7PC1{QCbhi?F~PMO@Ec6a2HKY-qli8zWIHY| z1foAyD+GrNd-g`wZ!@nT*~?1N2m_0&Y`8IUDW-6+Q6^72>afpG>tU*mP6#{`cD7#Q1P7$Fq#QVuYk<6vIO*^1W!$2MiRNUvu7COCWj`NNZNO3K#_tP`Z{qBs60W8911sH}JH@bJ(6-Nq5G z`tud{Y^)Dt?HufL9djfrD)a0d9CDhECK{7)fuC&e!uD%pEii1j#l6GB=F0PwUHY&x z>^G0hMA*^6%1ru#_Q5`n5DY0)m2XY?|dUd>R2$Wg3 z`ie#weQ&GRUh4(>xGZrEwCHy@#h8cq`i`|w;DVfB?Is<~J zd72TWvnt)|k@KoFu$$t*stPuJ8`$`kb&ACjWP;LU~y%)WD z4xyLVG4XtF8w`I0`JVxY;)^8cCGJ(3ukm9SE!c>%PR?2PBF4~eswF+0pDM4tp@ho= zD-)i2-Rwe)gIhFQswYkEIFmjiH$T@RhHW*9<%@&@<^G#wC0j`dl82evs;b_b9+d9@ zzsG21EcVC@gPk=HzHC#yHQc!C0ak2lEjT`MM$*)~cxdO)xYicNi6qR}XtA>t+`N;-He?%SAOLydUr_X@w4Y&@v*M@<9RPl71C?IzUrvST+K(mb+%G}-`7NOW5KJ-GzdV1MCWJWg zJNn8f48ta5i$m$#TX(2P-;%`c%S3A!L77+~_XuBoMd0HT|8X~7=z!kt5;sj#F;*x( zB^tm#=nBkMfgxJXBL4g;`-8&` z0r=-M6})YbXOHU1cG-S_N4pR`L0T^87YOR+6^z${wHF8?kNQu}96T9AskB`~BbA`-K#d zZ+_8UvTS85gzN<2e3y7}DPGK=u_-c`9XRTH*2dk(%X5kmV1)XIEqDMtWf?RwDNQ zKW33F*)kc0Kg(v*PVcuhf*dq4qwpr05X;}#ECv=OP!NPJn0|nU=oM3z==IMsDE+je zX%&#MnI?U&PdV0?Mb0%Taqx8_;>IXqJFjHm=gMI~jW zmY6H1!nLn*;(W`$-Bup-(7IuG{v?02=dgdDoS}04Fe$xZInjw!WwF)Agn1)p=wtEh zY@0~G0)SyQ%>l3yKiFh0^>oL6bFE%ZaF%}|V(b?hIuJDO_i@cwF_jrE1Y)U%5}kRi znXWH5+XMs!2k{37g5i$tg8`;##e{*~07E&i(o(5wkXFCirG#crbt0TX@SD?Bc)tFs zRCX4WHmdnDpsZ+|V3HjCaQmBe&n^(jDrK9mf;>`zc#)E&B*Zz7hWMT7*rLJDVZrZR zKSsu-q@+p|n%>xqxN~cE@qQ1YGiDIMWu)-%$0G`)4=6_rJP}30}|FD8@{z< zlR<+sd-i5G-a#=#pK69 z!-sFo&z-kAtM((V}3~nz{CFXTr_T(ekYPI$y#YzjYv#O_y_) z8!~RFrLc51a67GnW0q14ZDFkMz8A!3Y+5Pi(>4!bj)0DU@gPidp$_w}4S0r!e%7TY&CB_;@* z@a(29_$W7!tqQrNKB%;OOaCVRti&ekGwf6E@SXc%BR67%+mbUPh9THAWccCIh*Zy5 zDPN zI}9d=3aGLZnuqCfa&pqg&vD&_sHkd%(H5%7o|J;>R*WY9ThU~`qv^^0%OdTn`doMl zOj^9%^p2z_^7GQ2b{oWT`>~XcsYfwG^9vd)2^=~+1_kw;w2-ZT|6Y>#f$iO+=1rNJ zS=w%R3ao$-K9P?ns_`Cmftv=p|0x5#+?9GEiotQ5wP$n{r zr8srYKjwS5(&SQ|_EBg5WW>tu!h&y>2U7o49~IhW&x3kBDwagWS0 zD|=y+w6`*smWDAG@=u1XGz~7^!w2Y# zYig=KYS(c;`1ijrWbvPzpoml?hRTil!aGewqFn)ca?N=|4Ox^lpe5Rz~KX zxvjkXWA(>(PE#u^JDV;741lU0cTmyJdbq>m??Bj;Yi=+*E?UZTPrtSgaX+CIM z_u?%~5*}%u^)j(c z%Jcs4-Q@| zhGL(HuBx!pXeDFgf5Dbd_dT`l_uOc=O*)6e>l3V6^-^f&F#Cmu;uQ$U&qOkTN;yfL8F^{>#@DW#zsTcxPXd)h?Xq+q; zF2X&}wHBSxWK``(Ys{uXEn?-%J6h!qWfk0^BCRD~i2+?_lAS z0vG|-P)8s2s1CWr`ig{xzM`Y;uR15VY_{6Ix7(+ z*lsG}GWv4qB4|~f;`t4zUAwcL48c$5OIA0Rv-1!3Z$+;i{f^pSmvM{~PA+TEA}X9@ zBmcY|3-{>*=!;iZ)1bQgvZrGjj`B;k@7GDG_itnt4{c zoAogyw6^(~k#8=HyJlEg$JmwMUv_T^38&%4@+E`AP>omdKEMp7={Uo~$giaT3bo)KxN9Is*jU!zi$DVK?zMH& zDk~B~uHR*2rZkHA(dEw~H~v`+OVXtXkpJaHp~6tGg1IYYDrUfT_Z{UrhN}&ibqd27 zJ3s*|iwB2J6}5e$mQE(f0(>6ILxZuAetB^1KKyL?@mGGE9k z=hv5G&8=(ZGg+6eSd2K@bUgTX7~428GVZlL|D&Tyd?8ox_yOZ>%hq!p6RdvB3A6is z!J_x_TpBz6RttvPoWt2)5YUdaE5Z%ecF6whnp@7^mT8U{QNCmdk6lUlJyPw~ax^Yj zWYR#!Yi-0DK36hztH|Xp1_{^YvGfH+)AU>34(6ii#x@R)ll+`ry8%N(72M@tsM&P< z@TRgdfDc{~`Ye8slz+5Na}1x@wkJNdT1V%0a-T4UF(VK%m5M|#W$ah26&A{|{ z+>6~*mQr2~Z~GC~tIC43#29{HqnSuN6J<-(`6AL^EoF=ZJ^QCur*c4G9>a?z-tBu) zbpqlzY~?UF#4Ek~J9sMQZM`yF7acOpIXVjaeNVok6r1&>*EN={VZl_k{zlBL8*Z?7%P!R%|#cIG1!Vio0=cXNoE&^!YB;5w-a&Qh#ML14ez zmKAts?Je$&+6ouXpuxq^-of6CXT4)}XKOr+{fAezFyg!?M;D8JaP|0u!k@BE5MGMy z0vV@DLmDPJ+00P*Vjc~F3_J*+&4oDUL>=yr2_6nQo{DX!$}3Y~-MPw9>)wazSJdcu>oF2!EMiAq-IkG5(naZ^Jd5wGCw339O0DT7t+ zYGq-M_dk(7-s8SO_?Lgs+2W9!`{*WIwRZfGv2g|9#OJ_;wgQ5U{c zx)ATs4SzDzej+X~5fEayED;>^;mJP41^lAsPK*XJWc*q`Kk+ndMZDy1N9ylJ#Z>V_WNR9@v-OT=<{h=Tk2dxiB*Z&pK82}gY09$K;`dl@A zjtRl|gfjFtO%tIY$~J!~i;?!=BqfLtEvB~FYpi3{ht^lo*=-E@5o#`8KicP3UFmu3 zOwueHPx$=kWYp%BS5o>=I0bUUM3-nv1(=ggzj)NY317peYWQdJ8`TnoE+IOVNk~V+ zG@Y9u{(6cCprkr37HCNAfK8exZn5bk>KpA0_U4A`{j57;WvulpFif&_p%mD()_=U> z5FWJBmn+ocotqyxO%39JNABN4=-gk^JtTYF}^joxHfZdHaBW( zDa2~9FHS=eoWLDbS-pVY7S8Av%U7Wv%Y?K`$>eE82ng3m1AVZ_HGulzbZ(iXxlC|2 zZEtlan8!P?^{GzR_w_Y24A`>3mB;if%)$u?2L&sQ>9cA6YPn|F-^~Z6|8U~Jm)D8H_taH5oGtmlLx1j?&Z9{jingsPX<{< zh;XaZyLvutYxNXaM!*D|i;~wS48T0dl&a*JEApt0T*^m~Yu}mMo4bei`?b>KzdrKK z7OMw^*|^7UBV!2b1$0;ew&<=__DPJYo9CFTO$OQ6f;6_AaoRd#R+il+!+ZNq#U>b$ z@N-s=+!X!u_HZ!)Z`FmkRW|5V-}FIcWpB$z1<1ZXz8^0ge6fw^4=9&c&FQq>lv1Z$zYt4%vF1at1k`5}O7G?@338zBzxw z_uY|QnW#<4{gDzu1H{Cqi1STR>wEYcw>Vd{?Y_AI)yjmbyJ?0?*Fm1Ve15Nro0XL> zrL+O4v>M0TVQZg&na4oY#yhC9=%%50$r-Gv!%V7x<{m%^1V{XD&A;5=MN4jU#%46| zaw6o$V^l-bQDjCj@iaDPT z?oA1GKs}T85sp3~q4KsAOI!^uk4@;pg7ZVmJ};+XN||9#9hz(oUcd%}VJLP#xO|c9 zOvE2dMci*R6MeJ(H*B9NW}<=oCYDoBa~Hg5jc#S$%I;O_KS{6{-j4lYKe-a9-u^4N z^s(G^bkjNlv?51qm%*Cy-*;UIg+8G~in`mu?V${LTsGxS7vgP77j^c%6b4{h>xUY+ z{*4B)Oowj-Ac{}FIAzx&9IRn*O89xZy27gQX-RClMWz}bq-}NAH;*TKv9&z5i zJO%Q`lP@C1R5EVOSOB{r%qkLJb>ZXK3caCw-ENb`?VeV*RI!rG z7xnGG%Xg%KKNH05LH&c-zt*Jt4ktrW@9^2i9Ni5qjFayRZwy^M$Fz@ACa@pWDJ9Kc+dgP0|BC zJ!b|)z=;ruZkkBXhz8gGySG1IE;dN__$j@(OB_-jh8A?CYRlTH7jx+xE%qP%DHIc| zHI*cMs}>@(e*DMeLlK>wxz`*Gu|NxINAhFK>01lcZkX)G?Y|G)_5Q)p@acJUz=R$` zf&y!Ip6|L#h7TmXyPYRu+@O7v$fkcaYc?eBLTY2;)a+*M`b*rHkYrA+_D&n8p(^G^ zy}{E#&$picQ0Qnb0@OL?%gBSxnbic??m=WM7aE?d`S86soxIv+1TVjm<4?1{p$tuL zrgv?X)jMpDs>;M6(yNSxil&e|1)kYhP_x-TUL9FjSia*1Ru1G0G2PW}<{$V8 z>i;?=CVdJ&_!W2W&ZR!LpM0yn2gl`sL}#s#4@ai_t_B)_2((r)R->{U2E!T-Xw zZakRENftv8;BMjaATCIqUcGLHnO^$sgM{j_k2N2Ivp;AhHB9M2iH~6q{T;5pN&fh; z*|;bX68EgP_cKNHVH62UAC-D0n#FmZiYTV z^K*3VhWnP6Dw-xq;fFp&Fouj?C-YYEBpg`7o{GNL66gv@9{S4Hi{LTw>!T_%$!^)- z%D9N)X093cTC8&>x`nhEY*F(M?Y;y=X#g|s3W(X#AQav67~?!1aL_{wOeAt$;xa<2IoPm>Me|z{39kP-FvdZlr6W{b#V3hSpyqxc&pcSIYajgZJ&9S zwNl{B#Zm+v#3|HGd@eU`yq=(N)i=8J*a|kW^$cb}1O@f)gBuQwmU^X$EW}4ffsSx& zH3ExhPyEzN4G^L3AO;kh0Jk#J=EZD|+tJw3VSZjqOK8Z!VQPP#09{u^^|!III7XGi zEu6!n3Nng@PLHurSjze-85Nnwr*-w=7O`pQ6j<>=VEt{WB9h?(xVMNr1;agE*xr|$tf?dC)#)fmR4b1(NKN`Irt_av5p{E4|}dA~TUI73W~3*i0%5@0Mv z_l<~YPLOe$?FvT%mYqxIv$z46(sY@aX1FTf%CzQ%wR&htJ|5t6OXj_KYmjwiyfA^& zp(T8CBfBJM!|(3vII^+WQ@^{ z0XvGhRb?He1DBv6DV3hOu$76H{9ac^2g>wDu}KCGeUp6tIMy@6t!sKBRNJxgcrj^! zR^kT565u=o2zpcMcU^RY1DixcrD-wy#3}ou`QNdF-SS-Ag~2NPdtTye?f2<=@El=c z_&Z~v^36igpN&txC?0?L43|A*qnvG$EXSmeelkcwxWxaSs7Mk^71%G+W~{v%+y9dv zrIg+K$sc#gDB;?05U3wCY;r|$qe{yKr5{NB4&kgw5fUl=mAE|mDeqp?c72p)Hn;7m zHde?~EF(2?du(#T&hf@qYca7$SKmtk+1~=yn}o0Tnv@%|5VcG6oD?=`Y|fP5Wq_pv zWp9TNn%2%#tYWW9X3W-YY^_O_< z?Uf;ue+U*AZWMP;6l3o4;Sx19i|imx8-4CDHtsc9H-6W*J#J~QK#-d!?b_;}!7?Fp z35rctQ`nK2=t6jN_~zcTtJDHPX|M6f&AC&bf7z-#e$(4PpwKpHA|Rl|4M~*$Yj?GJ zDOdxTu%+J8l}r`fmUEL%LSlx%umNn_D4H%doC6f{YN^?rhrscG%L3T^X<=ivo@$Y2 zjlH7%>ryf)2@m8Y%*=1~g&2P1{1;p& z$gy|G?rj5R1qMaT1vT4R&EGv~$m`^%#u#w{=e9z5Rwjg=_<)H!3rZf~#>BBGXz^LZ z=07gti#h$G5Qm(+T$^d>NqY(`urVTo)?_)6inxOi=FZWBAa$^v_$CKVi~_2{AM%jw zo{G2XBNM2l?rK+pVZ9Vx(jt1@(>;q6luvV7aa4lwn6ZCbTnTm?7K(Z zOA-hW*Ij7ZgcXqAaK%qw#4BZQc06%=@x;={;mT%bXI!l{P9eAVZX#)*>W|tBlce{G z6caaUohKv_2uiMxf%4*i39g9AAkPF;jp3P?TQnMD@g)F{?yW6;RUfVc-r+t~6tw-< z;iI>yastMKur_UH|K+<%NqxCe0FDIkAc(urHr16v)AX7BeJMjn!7>dQ4$zg@uHFs* zXa@owFwarZovB=gzzKE>XluyuCQG{rLA;u>NJ9yIyb2hT zl$A-M?q#_qJ|TO`7Cd+2(fE9|=s%`^`(xhru<8Ymh=^X5x7n`OJ5nPz3ia&qdbJ}S zX;K%?e?{q|uM7PeSuhUM;0B57t!1gpDOR)gMMN78ve&G4|~=wFcKI}PK?x6-=$M>|nR!nFM#u|}|h#oObJ z{{4u9-eJe1nJ(>&M<&%^uaKyaR~#Z#TwN!%=6JA{DX0;;Gs}}N3`0WSPJWv33Q|_S z1-=RKIXb+nR6;~TvgZ=HN>iTIy4F39LoAY?$%9oZdX`2%iWxitpsm%2_Z|D_RKp@G zeQv#OMZ#IE=WI0cvb@Rdu}vEX9iki=`c%XibQFY461SaA{BYR#0>O?}n6pGtRlI)+ zyohwyBDNImER$Z^Y&@pYBzT_XJ^u@Zq_3(g8P@3ENi0lUOJ$QG@S;=MDGC{__k4)_q zIKCaGAn0~^#ke#+EJSBox!gUw>iMU!WmqvP7;N65&i;7^9>y?#{9tXazw|TX3^&mA z1GO-ax16%i?Px(vdtvWzIyIj#57ZtCj(yqWKwX74($Ej}7#||syrh^r ze7>>n7FK*WmQ$;URH1yQqIbGW(80m6Y3Fa_CvokgnRNX%T7NzklP+@BGIDE|N1HJc z^+G1okUrb}HTEjvU{@wm>xIcs_NIrDFv45uj^JJG`xVQG?KE`xFg+6SzWjdHIn;-o z{tC;nWwLmQfyGa&LB-@LX5o7kxh5E*4_?EsO|Bq9n*bY-x)9HF=H^VuM` z_n$9wwi(mD2yPID(jK{0TSs{~|A~>edRCa`R}-0;{^m!6)JgZ;A8MZ=&iXJz2om}n z4otmymMLs(C>1xiq!3u!@kzeepM;Od$w^VfpPK#dTp zbd}7~TYAH8Hj#m$CxmiLX~g$+^zvFQs9V!^8$u!1<3y>i||7l;ZW^=0P>wrf5&c<$i(*Wd8cfeP~ z_7HFJ5IwsqRiMsv`O|veX(Eg=@eu|=i$6Wh^1aqHgUmQEyTbyn>Dxi1N%bcE$C^*Z zjn!ehqTxy>9uFw~Z?9aVS@bZwB3MZxxeERYURZ5LW<%W;y*tl%^#v@|p^1r4mLts( z^!P)c@-->drESpreZmz-lxq$;%2RS}9Ji#zndJEQeU$3?``<@}jR+WkHw*Kh%mZ|E z4Yc^#(?VAz+#96h=X2C;Dx}|5hO<-d^XNfVml^f3mVj+;F!mExFum&3bPI!e9CE4b zLB5O4Bq!PrrAiT3QO`d|)wluf^2Z>kLpR914wW?qR`=p1^FIaqNitedtAFAwV}}-JgJi&F ze8scMvQV`bPEZL{NFL|GOOj2cHTMnCoz2Z!_#=6;c+zrU^@yi+SvqHaIPiZY%Z426 zT__Hh1w+t!`|R0}G!evfsVbivIx*IgO9!?JvsoGa8}_Pf8!bv{P&BQUGC+KsLeLVX zebw@Jrz-00V6>(n4gyT5h!hWaFzcQCH(r(VRY_%!PlQDIS6hz~&(x9s!bFK{k%$jY zu(rtiT+km~I8`nZR=;Kl8v#TA+xbzbVOmV`q}~Jz&3_YgAAeRK#^+Xhv0J9}^7s8p zFweV*j}!m9H-YefZ|77A)U(L|x;v$PurUn-mrv2P&Y($DOcr@Dp)a^sC0Pzm&`Hek z-Cyl8Z)n*3+5wZXrcG)^Oeo>;8WWA%tq4YS{sB*0=g2N73u_G{{{7Q(+h3r%QAR|J z-&T4fXxP`d7VUE`a{1s%?gRAwEKy^>kdR%ss4X6=K_$~9Io`8tgzGU}C=*`yrdT;2 z%2%N=?|S1b=?p*~Vboota_h1~;Am@nGBR+YTK~RhoJm7vre*L760$zxA^+l=+qD%v z>JVJll zAg^^9a3s_q&j5BWjUD5RUXvfjoEq0*(}nqdt?(tv3C2{3w*Qz)Im%X*I1U$1gdn47 z>v8LO3g9em@*lG0`9$(lRN_Jd<3&oBaGQv6k(`?88LS=ji6yzVs&6h`1FfSP6|~F2 zl_-mO|5;5TPzxDt@@^*V|Iu{r;Y`2(A0I7EDRU^(0ds0AX_K5!%_+-qB7_`5$eElE zX(8skB*)}bjycO&n2@P3ALLLDb4YR+IsfkOAHV*qtE($B@7?$7^?W`ae;O}11`t0$Y zF~q+bd_kLcmmy^bweR%wtZ#05>pvrOcuN`LvHOaw?z1(juwhKlS{J=|_=;Xtfg5ua zLg>>w3Ar%$kY${+BK1uW8(hH7o2_D1p5&2Yr=I0TbA}44efWH8_%sMs+lb|RQ@4Yq zjpZ}8AyBm4pfpe2b<38J=a_RZ1fUmOD#cvVHP}^C9Iz~qHejMPG1}N^ay3Kd!I?Y# zmbX@RY~+6BVR7)E@L#Z?^Q;Mz@})Jk^ZWZY`X^PZO~f;Ol{9)CiEH-FEb!XkS7(oR zem0f&R?M08Q}|QdQ6~2&clAfJ(TGoy=-2{02o`7ch@ACsu_Ms8v8?suCRcay zBzCm^71`}cTcRz*>1+E5qWhKnnls3unoBd>w`3M>!Ln{My?sSe3h_IlmfjEjH&NdD zZ*!(<_)1?=!+Yg}-^pDz=)4SV@cC+mg9rn0jGfkd6_|QdjAsNk373&2es^3cz)xA` z9(TU6275zU!)5-^N=vs^|6NI~LD;P{dw9p-#>T-6 zozZu%oTy!7yD`7Ar!at^(;9~tm*(v!y!)TD&V^e8zlhFY9P~aKTBwaFs6Ht`(BKv6 zcmsjJ1Xr89#0RQsT@d-t&Np~nrZfIO3sCk9Li(zUTfnf*DD?Y3@MVOw>U}5b3v%(= zgry2-S695yMuw3H{NX<5khf(uIkt4_%)}(nOi-9=&vS#_U%$<_JNjOgV+tG!>60he zDmJKQzVu(U!x|?IMq<5m@h{+i_N;w?Zqc>++iKaQH5-=VGUDTM)efv#*b=c)wJ&Q3 z@K5ndhyQkW&)dvq%JTsTcrN2Bqt4A@v#5}46Q!a09RB^d^t-30w%CvQj?8sq`dx!d z;*zx-OMz`fh)~quEMI`R=|EhY z9~6FRXF6+2n0@bM-7K$9xoqkY;`!vq@3aGtBp%)LSJzvrCc!N5AmnKEXkyAZGB~AI z+HI-^{C896>RCJ%BZheUjrTV}oeX8f-L>ZTkbH4_eB8kS`LDLvA-RXaU^w}hajT~Z z!vyI~#(+Xv5OQLee-r?rs8l$t?Y}aFUM4MVyw0ug#So?1!XeXZ(l=O> z)sAFCyyXsWn?~kC1)&fU1eH%r$Q|KOWn+3nW`+oY&v8&^JE8c_S|W2+oe%kFk7jlU zRzWksVbr*j7gSU7CU-muW*16pGb-TEJR&L+(@sH1K;YElcfXJbCk49`qE=j=0gt8x zJ|Av&TE~JzTNOgqM}s4d?|8GyF7qZ0`B z=KQhUTKPjy8jlMUIO1S&O1H(=#V+h-S$#o0MGU(v+eX1RJ5+ex(nU2|r&bFG9gQxr z?%B(fA;r-^o`x6GIa-qD=7NfDj@e4274Q?TK<;3 zZ}_B&`S9ty`V8GBUpO?p;?3sav%TvNn$=*wF0UM9+lgK|kv|`Pgq!PYQ@Vb7%hk}F zZ0i$<-)mh|NrQ`<2YcHfSUMBv^!sw`o#S{E)Z^lnUdf*Co5RKTgz$y@5lyJFvT|Nq zB^K=-t7~)Bj_E~Z7!8~|Qik$KBHbKVtY{;qS=LePk+xYpv`08cfLltcnv;-QeyoCU zFzuD$zq?xEnl^U-LJ+q(%S=pVm_Rsu^G&P-!iIt_R9pP{Ofz0eT3S7Y1EPB_rge}1 zuz7ply9QBA?B2c2TSK!qwJ+fv>3}7VK3*H2I#SXxr0>5O`t=apT?f@Tp$`;7rOcZDS`u;j)zn!2?f&ZjqhHZHvSY2olg@{5ZWY5u02i0)(hBw$E@o0aNXHvKz? zdsE|@wlom(_c&4}as7k5q>g+xm4JS>4O4+8YIBNqYVwC}0{G!8$vc&RLwZ`Z)m$8C zJ8Y5fzAyd$^=rxLAbo1z)hFP|_8&!JqV{ZsoS6gK*5$#~VvbML05qqw7}QEqL<{}W z*kwx20hJH4hK2cpsOnF4`4wK#_K8iJ19kbyVx{ zZq>{AziC~i9X}zU^uz?q@P&kl>2MHL2X#f0w^t`k9rzUgg>lGjs=l6wChnSCu#2#a zUAjr_TwE7!(C5Djb>C#dmBdEC%^a$$bVh#11@bq+nQ@&cRTzhM130O$LBf!pR4Wpz zsLuF#XCq~OoGR=E8P@43!9ftlRr{R6u_0xENP*T^>l`~=NH6ryn)vZUASy|CXSh7% zI5Obh!cW&a5RC}TwjaGMvPB7p+rs{BTvzVj*q`g;aeXWwk?_htNpyK7&BKx#oVOg) zMSt2zWtZxL#pSE+{p6E(k2OmL(%X%(*j|+Kc%%e z^UvC;T^Nzfguh+B-!6-kA-2hCCcw~pITz5v5?ZbM?d+~n<2=_N@Fb%}^X{eH7?Y}j zgZ?n?Vj%@#?Qlusvpm1bUnHiNbW=$N7e$NE=M;KF6oh4Zn6KBm9E-~JPqASWgi-ai z5q5+Ej<9e2iS*alfIL^{Qfz1MBjTFLZ!3~hDI&))P12=G{&yVXn`S}*I{X6)ulsuX zhpZ;A{9R4R&&IlYNC@)bcrCxep}_SG*sXENu}4${A)yq96J7B~sF1nzixRhgFP7B%2t9#ji9iWyZFiZXd{4qU;nMhgy9!Da%y zZhX2R6a}-zk4EjRHfF&k&X>iMv>|GAW=QQ2DI=p1hDojljP9S9zc?=KW|xM_@BVeq zV3z!ySao9iPjl$e;l!SA@$mbbO8;aus;r>FBlnj-$+*smb^hJ$Uw-=;ErcaXa!|&0 zf{ZT}&#bw7JdvvHh7ggYn3Ga*nH(ChTwxv8sRpB)jIX}1PXn#{LB9VXNewNH4IkG8 zoMr@xsa8?}tWBCQYmH<{t(cPc>0gLXU58_jktIx!9>?!(_29gEYK_)~HM2-HY4)sX`R7^CqYbxc`2uzX^qm`*-g z3*BF}{gBS6A(uFwNA3hwAOcgUqxZ@!9sI=yH$Rlq(k+tm;6Ekrq?h^7L?jXkR&1@o zyZr}^zIh4nwbL6eu=vQ(x*p{GE;OYt-1RuTV;ES#l>uY$A25&l7-$sXlY#~xc9dTOhP9E7Y?H&+^ z{I>!;h8MZahb>IC`#hI|%`?P6%QJp&W>QutZy~asWn8L8`#VCj1|1GRN#P)NU~adw zc40M;L@e$6GdMn}(<#$|RpYD7)#S$ukuChdqJoEoRY*bUp!rKglx%P6G4v^Z%A1H8 zvHrM7Rgy=AiKNakj#-=-Pt3#<>1(}%$y^%mYWQ&8+f)nZ$0UzX8GVhuO0pKG?Uzag zFpBq}5aFNNM3-nE#&KC zsbdfhw)|=Au0mhLt(EQWTfEw+xx1$o=|OUt)jGxG`J|)G!lNOybCX+I3hUFiuU-JV zDdbofRxP|G(icXJA65bj#9QC~xSYab^sD8{U3R`W_C-d@!0MVVA zu@S{7E(2+MWH@U&0*+iQUC>qb6a3+)vhG-y-fT7#KbNtl1;UCZt7&B`!_(oX+V?Q{ z=x!TNVerUY7t>4fRybowLP9kb#rhVuAIH)5AjkyVf78Xb&#@ZNz|{@0aTjSSf^Kef zsj;k%CP6t9*%9UJH96=1r@4-XgWfAFPEO{c{P$QY^l;O399VP=v>Zq)V_-Yei3lb| zy;s;h3nw%D=rB%XyK6>JWY%;L&X9p z*N|_KiyU>%v(|63J$KIL5LjbM=Qo_{+_t*m?V8ykZ)>jfJ(jz+TgHS8+W!_gT+#b5 zEeiUyK9$Sy6U*@V)l;Tc_0%Pj`GU`2xJ7AMtw!Thz?^F3K1*+B)=K$2}t>9`(eBXyik= z>>jm->Fw@gGm^}=VNco|hwj#jvGX5n(Er>z=C< z6Y{f)2XNQ9n7tc7CZj&Zx@BD~Im>PXFfXWDy3j*UED6H>|T5nQ8h$ z%;>iuRU^e9S z=s@2;A=|&6dl|!8Mjz*q5y=c-9mJ!UCb1f^QUc&Rxo3H)ScqqTt2CypI9fsZVlf;@ zi;Y9e72?}hYtt9KDY7wEO{TjQHPR9ZNy5CBKhHeYhk-0I?C0;_+7~wTl=tX6o}-dF z%4{0ZDRy(Z1B$@tJzpyBL9z!8!|m6oW3cRq)xQ2a|cr};&OfoYlmBzAZ~??DOn zhbpU&*(r()7wtIZW36ZyhNVN}HTti|<9!Ydj!%wh64YUg0I63?3pME~t#e;b)X>>t z#0U0CO_b1Utxu|GLTUPDSGoFE;s-Z(HXMu$A6Qy6fJtR!2VdC2vq+h6IMl&0O;myj z8wW{*hu@?ixSF;nyAc9Jnu&(#-;kh(X73A%IEd7bugWba*;GA;4ni;_i zv$5CP>1S?&M}71 z=0998TeV0lpqf!ScXqlkY^1fKqLLa!4)&q>&9fr2_RZAF$E{OA3OWv{0zu+PSjevuK*{P;SZ$!1G|OLftxdOdR$Gu66(tV&JcG4A zguZ%Xy}(LoJK=orbvZseD5%zKQcl^xW!N}!BH)rx9MZ|9sAE!oZ-1u>EZ6;xK#}G? zokt*CzE0e@YUit7p1^JMP({C2 z;FA&y?CB|wA8o@R_VIK5ps`Zyt*?f2I4t~K2KN{OkEZ;GxWRUej>Ge+{#a$V!|ogg ziRRyIc%NS8{J$&%vjHA;iHw7BgvS~m{oM{dDt>UZ)WM$J6mmcb4E3xOAnxzhwJx(X zn`GSW7VodL)^9uzzgmfyVf5>a)TCOeRd|J5d`EJ=#}j0ll7XeW5Uuj8oO5F<%p6Hr z5x<}x@LT+EH?piioV93ouJ2XV=+VGnI^%QF57UsXx{06|MF}^1nuQb6w506$L*L@Y z6JMX%hqXg+s=FjkjNaHACVOF(0D-{7g7k+mI+f8~MfZJP{Sf*j6jU>@IbC;ISw&EA zu)qJXo4S+voEwCy=R9T4fa0Lc0Lq7E4T)ONRQ~t#y;1@ExGnZL9t+6|srtpNUY&X^ zOF1w^Axnmi``b{Ktr)lqAX{{c@!AKW8=4N6l7Ib|v953rZ*0Vh02aWzS8`CodN2cx z^!eHF4dh8=d^aH9z|F+YjXi?EkU&bqw_!e^{9{V#$7Kl4F~z}Q+y#&I8$k3`iT#_l z{Y)m~w^Zv!T{CL*sM+2Y+uNbrzKAd@LUvs8$1#L+=|qOxZcA}|x5p3xB|iHk@X3Fd zYST}%;FR|EH^lmU*&91TvajZAUef96X@jGYdmXMV zCQ1rFUfF##E34)Wud*{*@>tkyDe8qQ;tVzAm2O^MRfLcNxXtex`N(DJp9~&1b-+?A zMtnQ;&sB*HxUKSYO``)|>u*l}kG7uv0n6WX^wZV%4Vg(4yz^2+rC(mAn{OifJareo zKKXp&%?nohWVbyQf*LCt-EA!s=y~gIt#anWGEyB!SI9!0g9EIqd*aM7xHbo~0Oouw zstg+3CE z;K|?o?YzzY-)HP4mqHl>N57B#GN+z=&H0H4e6A#916dH)6L7&sm?!`Qiph0>oEMiG zz+J{L;P2vpeoYfI5yGIF%Yu#obP@+rc)(sYXw!W zfx0=rqQY6%dn3Ek z!#)l24D?q1A}I!L{f}XRy5ju9v!-YL(^vw}*&InxZd<~YV5_%+GvlNv~}*aA^NL+&-J;T>+7-(Kk?9j>#YyNSHcW#f;(wJzOSU?QIJD_1E^1Pi zQlG$VtH9RGZXK>AL1l6${Tz}sG`NFj%@;;^QS%W7IFi2G#9ifyy3B6{&Y&pW!MlMx zbD-aEZ)7Cvoay6G{KB6Dg^ZaK1gLl&9I7)4!kGE$qnQ6i#y2<^a3wSqL2+nSUG~x$ zzO8s%kH!NpAw+9S9)=76a?1B~M{DC_`X>!UyBN$Keat77*1OfzaG3buV0+f-aqBA}R z?ne-ao#_?v^78W4GPmBhpN(qGN*}cPS6P;xX`EQ|9?GR|gnL<&x>6rrxlzEAboDi$ zNI6xFWqgFk4%Ur~=w(}Q;GV;cjF@p|@kFb3SqQf}mRD{dD`WLc|go z`2Vaz9cZI3o~ghL2+!dgV(9~P)~8t74upuI2B{?fto(e+Wg<^ge)TfH``?i5dP9QF zTr?O!Z%v-)5k77{>puv3R9@8OgG8&XU!y0e|K@^%Lyt_jt6;NzZV%!nHN)*pH#N$6 z?vPk>arQ;aa`8B}EO!lFbrkY;7?w^t<&>#~jmwQwvLYGc@OHpjjL5tJ%eP+WEBZdB z-wUJQFkwW(CiN7BAtQP*rfF=Iz0c{%la_|y`p}InuykY9(7Nqd{rbxq5Y7c_b6{>E zV0OUe_bYc`y=hq)&Cge)vAT*>apmlrl8jYJVUBk@suHNM8~OtAS4JgZ$P zAVz&A`>pLaFRVOiW<_3NzidnL*=lysdl0g{QpKZ}tsE*&{Jf#iRUP=_rp_}C*Yqd7 z_QGt)`T|Fc`Z6P^(c)5km#ibH45PTb?AECw3f)X3Bm1)>jXfEi=c#m4xGdy$)^)@%nhAbz4RSLP4Zcb~!^G zZGUAZ7|2nyvkTrRC!RDL1!Cxz%0kzeo^xvCg>u zs(a9J$aczidwZKUTHsP8W=m517{qDtJ>Vk6!0w|L6_HGEYK+73sX|DqB+8@G?!tj= zJM~HLO!7(VyR%(?JVw|%>}#TtOV(mBzaHQ;rTQu(BO9x#s;2hmkGv>f=r^G6QR@?~ zda#epjY8bVGz_oJg3q9;S5qNXpyhpUSY{JQcVl+KZ)hm}TQ~vUZt3GWE8^l*KuoM@ zCrjXW%cRF15^Ta+mJLWV?^Iz_ME($%$dbQEyvKxbRyvOlJ3WJst@s)lXrGyHC>szL zFBlilhKZ=KI*w6x-rNm&7oWcJq%JU{A5THh*>WG2GLiGR(IRYCr3criy9!*=%0N5* z_wUCQCdBC~F-_R9=~veuv;;7M3-aKgT3Pu8!KDgZqt_4TSDBfYgN*tJ* z+GnalQuTXN*{zNHi<)5695P7?=$=Mp*w9^-sA?&*3-8H#Jphrs6%2onl z6>#wItocc@)vlHz>gRhB-Cp0)T6yyE$|+N7U)@L@t2HU9iX~?@ zce_1ufk^hTFr=b$UB*u$3%7{xStrddgjZ3Kspsz{)ueDn=&w&6vs$$vc@Vro7uN&Q z##V?RgNbMrEdo(ZOJ2J9aw}rGb!UFO5HPWVcO?fZcTGmRXKZR7HL~1_W+mV!qaPQWH{fC#|nY!dP`0d=uxAHp*Nwt2lD1F4MOgCw$8-Ux?|!IB<}^oevzy zr75SJFH!2nPC|yZk2!#Z>)~kj;b!x;_+FVT-*VYvLrb=x^E2M(fFXCz?p#wH&4W@f zw9oC(Ng~nMRO1Cwj9L`$2OmUUU+y>r*6$JAXX)~(xMw}YCcV1<&jM7vbsUp+o4k#_ z{E!2}Tceb@WIbeOy2}mA$GPKxJ3B0qoAX#A4yl6tr*)He^W8&TG~Ij`{grD*7+pw& zJi^O}z9Aj-F)$3J0^(S0K9Sc2ov##uzCvX6bGZCDgW&W#5?rhquy$+T1aKkpk-11< zgLQ!ed8BIa_Fw&TT{AP{*JBs~KJS)0Dr9M=kqQH+N>ArNF`(|U2R{=T@bwrMHxpm1 zE(jyW){wt-+1z4v8RIILow#@5rj<5o*sPFva&TsO4-D^WqRlW@{VN^LT394`C{opwJMsY8`ADPL6xg2z3$FA5#>U3R z+h(GHLw;HHCa88)iDioc1*}bJ@p1#$*MP|h7p{VAQ>0f-6D7vHU1C|mRV!_Fz(MBd zrJXFIl>CUa6Mq=q~l@_}ILjWqno%_;QD1)^ePs)YtW>V)vZ69FJ8jE*bJy^FuE%6n<^ zv&;z;EZvy=VdF>je7*%b%$zAjKNrD8raSAkG1Cv&*MHJUK#-~9;yAjP(C1F@^{~Y`72~j zf}x9E>mdlF_$Z$N=Wr~A5nxMNY*eCjBG|uOJ6F|lm|(Z_B+&Sr-FU6eAX|sN(J*Gy zt$cN?EZaClc?+G75X={bUVk2i%z^qjy&(PcR&XkPNhW_|SKeI+J)AncCqQ=RFs!5* z^cEaJk)7v9YGdoloC950UfNAYMD9gS%yjHs&kEgMPoMXbEv|L6R0uuX-IKO6WvIU5xgwI6`940fGVM762a_<&01>CZLpA+T+i^hO{%7|L zgrFVffmh+}g2L0x6`}}PoRDxL!QdQjo!s{5MouRa29kC14O4=CxK~H&4@cvk1pBh6Bxnl2pI>OnR6`J z6Tu?>d^^R9&-Sml481O0C(sEYnz1%LI`bB`rcFC>_PObPhPJ}3BEB^7tcBLkGSfWPRGi(0*+7}z}Qh7s8!k>38t@6*h z;E=h^iX`SZj-i8J(mw(~0}w0%dMjgTcpF^MaPIuLC~Ti6n^pBKbQdDSH|%RgnJgUv z@_V6&4xwfvjO#!N4jSv`U;=7s8N9z1Kfkd9j!hsM2U-(gQ)*`l@?G5?^^J`>XbTGq zBoRgl-{>pu^SG#WGaF0ktz2j{PEYjO*`6Y= zo)0((kD9@*1C&p3z1E04Zkkz}U)@wBqOY>4zW#S)4yy0%=Wc7OjFw##p`*Ve6c?YGEyHb%`uU!)BU$jKQ$7GK3Jy@S;G$(|Btj1d074Ay zO=^U-wxJGJ&a>L`Da&KI86Ga)c#n%LxYsm_zp{E`9-L65t#u34{_vv-hSIc6s`NBQ z=dZtgJSG}}AvG)qCZhQ>svqIlCSJ3NCf2nX%p~$uTw?tE0sp9`#$k*I6ifRRN%9d55&>HQ~cJ9g7yPSFT zsRJW1T_r__f4j>$+Mj((<<$PLEiTdqTQ*Q-<__Kz7l};Rw!EVind6HrATo7SKZ>c; zW(6BeQRV=vnN^!8(v3DuMLcUe?r%akfwxQTOCUCxwIFw zYc$X(5zQMmpWvU+loxeUnI=paI!L--6?y-^cB(toK%?d+c#`kP#KEkjvX5yneoi-e z(KJ@~%1*VH-|Oq1aIFC`el#*0g!CR93_r-yy_`P;Hp`3NcobGtx7#*FYxPGA4}WJu z6T45aB+aObmnVa8o*+q6`dE+Zt4zCxBpNv59Z5{n7UIkzlDt=;bc?}iopi#LV$T}O z%rp)8bWror*Jx}}WhKI~(C`;zJZA0R-+B{cLT}HV^&NV4RyJ@VWFP&T;TJy_!*1Es zI#vRHzMnAyMkO!f)&gqI*XUxG41|c)Qna1^C(9XoOYE%!cTCAUkBtuxw_C?uYwZlO z;tE$Ew3uBpMj`2+tihkr)D!D;xWavD_w4*1JGEg9YI@&d0NWpe8t@WTW5Yg|shNv_ z!&z{m@th&Pl4>vDw^2G4xye=}PG%BEgaJF^r(s`1kLF;y5!d;9_06mx$36d+tr~e=&VA z>Erh)CTcw zHJHx%V-DW9G$mQ(@?KA4YVX_gH5@nzWDp6^o?b8xhi;lC8ny?M5Xog1NEQAmXHAvP zJe##?ox0!Zt8G^jpy2IkA0)dxOk`UA85~If40*H7#*<=8APe_&RV>5I*`9r zO944rdpG})3^G-!s-Y~>dVe8OIaTa3wreVM$H;=8Cq}l*Z~Nauu;0e~t_eS2kHmj= zco6iK;U_nY%BK%xt@<|354ramXm9&&_s#7uEnO*qAXr66!(3a}24dc#;5e!#$X~=M z@Bf10*f}729Q^Ii`4~^Cc=ucv0-di>9u--WkXd6a$kfLiT*+9q0qD!{ z_~2I#qn+{?+R1jC^~pe6Z?>lp1H9JzB~`_z58=23xQ2{Q&S{a@n=n1GA<%dunK%eV zhhdpJkDmzZ$?rkMwmaYnc)}*kh7AdQB~Spb=0&&T+}jaMV3QTBiLIa*+xd7L3X47@ z%@NODk)O(n?Wmtx>3eH_?Oc1Lp;wxbQJ~XSe4vU7Z=XchbHBZ<{^Y6{hJA;u+n%mn zl0lhfCVdWSYiv5-beY7|F7DTBg8z2^GI3$d(vvTIfLu*|V!<93A896W22oOV@YRqa z!vnje4daTC9igR|w#!!0+%>pPvWkd91=`vS!#pl#-XvTh72ML<-*7wfZ#FHL?kjT! zuj@M((xW1OVWK`B$^$`BW}EfGQtZy!`W+o?qx1XbKABy8sTRheVmV8bql@8LgCgEXIOc}tO& zcF|a4qq%^pe6lGx1S{SbD}acFgK~W|QJ)NfYoO5RmvBSpTX+s8eT~Dlk=8H8qn+R2 zr2EdixnXUj2#J8eK@6rD@9f_|1O?7nra;psP5iY>YO*M+-)!rp@Cb{ft{etEJph4AXM~RgOktSr`iM4)g z?2E2+POlVOS14cJU0O=Q(iqKT&#F=VUOqnG5$QUWN6eeU{D+ta;%Fhn4D_?#a;69( zaP>Jn4BlS9Y(_~X3+BIzWfjM)mznm;51{()8k3DkJ(1HHBN_vAFK$CNru#R7*U>~tO&b(maYQbO6C^XQrG%f-y*EhF5wVxh(uvi$n-VNsXfFX7igEhL+ z80fdZHSPv3>Oo4Oj3vhKAidnO*+Z#m_i#AiV^&-hQD0@TtBS|Lfxg;$bSvuT&$UFd z-D|CyjO&dpzEro`@yN(X!GXR?tFZI}t%S#awWAAUu^Pu;(RP61cJEleLOwSW2eoTA)mP?X?YN5pcll(?wW9U)B`1W&ZLUa`E<_Mp>h$}%9>k>}Zj#u&mxNwK zGWzA*>*+6n@vLh|Cegk*98C6kplIljuu48T;|7?nv8t0i66wLxc`)i;$X7;%?9k4oi{mzT#CDBHEwh=bB6CkSE=uS+W zE&lzoyh^?ExI!N!2N7HVr9@e^g~6V23*p{hIYox!wYHnB*x)#90eQaaHTlNpg!Q^wF# z6v|Jzh4+!W#42KU^J=f>(ptI=3mQrBb7!(;3o}gpn>*UixbNI=Q(@vlE1zodVMVr~ zMUi>iy1imV6Yh`OlO~4T$HU){ml_V;{|ltI{@cH7w!HErmn_!%YisLTt{Mz`HdF%N zydA!==#9YLhEP9R|E?Q<2@m?NTM*Lt7ByC;hrKPrD*_%)$me}AmuZa_%?{!3#iVJT zy@cBkKeIw=1H;MUoE_<#lcJF^Ctj6}RfOIIw}}?==SR#?;;63|CFBKXaZqA2J8^nZ zFw%fiHT8=;F%z0G*`ls$8wgAjIj+4Y);=?SjcH3zGloR~M z#dCla6CXUqzr33pA0k<7uQNFDV}fpXoQR+ojh1{qRqBK1Kuz**aa9J(jo{IJmHXF) zM;GNBr0zc|HN=B8-$JLQ1V#IFBvHRzmL&>n!#0D_?%`@zSKd;JDEX{e$|^MR6)jSF zGdVedGa*A{wL8R}hQr%~W0uQ!Z8~EtQlHz-$QUik|2E$G%Dy^6b`@^bTk!e?0nbWl z;2%k6c(z!Pbp9AZN@5f74b$BopZh@Ea$PK5sU+nNnX?_i`B?fsI)B?0p-E!R;kNw* z;2hWHW2*Y+Ka|HbP2<>tl^=+q?50BYz;MJ+&S|i=S>I`>Bl}<{+s@y^*LOAJ4r}dr zRiWOLA;GfQ7bqo(0$=E^6$C_GgCYs1M-3=rQFl zFW0gDYDz<+!?(FiGYrmwu!kJIxbimki^GQb+Q#Maj-T%SK4+UwVL5v-NN~ynXdRdc z{yo8|(yt3a0w#NU2G;Dtjs7ugUh4OE{l(I5rR>dE;#w-FU8B%76UH42Bjdgx89Xuqvs34XhP1ujWaSH*0(3G*$!*`0S$f8zvqf{p;s%uEIre8!(eNVH6)_W|sHd%#W+D z#ZYgd$Jz$Fg@3^bc!219?wP!sU=n*pcpViP?hcIJQW6;j6|k`Aj5zGV9h z#JMz|OoZE(dbK#7zkSQO%B=kP?7>&B9;4STwaZ7F*@yAV=@-aWQt2Ml`~|g zw#vYgNvsbr0ru*roM+O?9)O(P$e9@!%39L`6&M;ZE5jk(e2%lh0UU>KRe?dxxEw7x|y*tRj?!E}IaKwb{`?y=7I!^!~jT=d{|@NCW3y-kjN?I#>cj1AmM4 z^fxXX0f1M#&N`Tb-||N0i1oFsHf=*5$rZ@Y@XoBfH^5zd(m3p?4tb@{VT-Y_gQXe9m|80#F@!w$#eS4cdvg4NX zDF{%wGZwwm`t4uw++$d8PaQEr>!w!tedYNFFJ}i4MsDuZ9sQX)JnXw}yQ!Cz;ky!s zJx!Gu8*sdXG(%c2DGib!)kU zkvgkEbiC^J=Hhem{?>dzYhVWRu*K9K;^SRZ4kO^1Ei*aq?lT&wR{{5fr>tJPL3l*1 zNLcf!TpI3kmyJ^P0K(R6c@cxkhlUjaP`{b;`@Acjr1u+4@I%ng(cwM%9g`ijy;Ku} zW#$aGCTZk8*9RfAs-E!I^y5O_mi>s_#sgg~yWn@r$8xG&?k``Q`+~TGjzO9^T)s4L zg1;%dWgN7NYUj{U{8A zDFEydM~e~KnAkuV9QWQwJjeU79y(v)dcBp>@m!zrxV?j?UZ(v;gNy$frw->Gln)m7 z2C_oe*Vw0;LP{Ca!Ek~VbFz9(X4qHNsk-LrBy6G}9RD)ue@!$4ZX^^hE1<@E!;D?^ zdVXq&FvX1WD4ZMD76#Hh>fs)E7*ie*^3(B>1Ql}&Vge>I=`#24-MdG)QW|NEf!*FT zz{KGKb~j&3<<_`XnU|-WVyPFqx=f0L8IGklEvAVXQX6+l zY)Gd&0N5DD+MWp*A}6V;Fj@fdFMG(Q!FZkachA@9l1;tVqslvfT z%^>)&I-3z&FD~U`!yhEfNcWX}np$+{EP0G%?FaEDngcYg%pPchW ztKS*f|9(-8YwenB?ZaCTCo_n2O-Ou z1C?TVG7G?01Cw<)J~M+UOSuCwlgNRS@`&j7zT(irJi*k>;O^t0CmKXjIpQGU>_!IY z_5tbpw|o4b=|7?vN^ix?ee(Bh4V@)i)YH_S_LJjeCiH-TqEt3(J1Y{5dVQtqNEI6! zRq%|2w<~EeeSN@G@aBM*y zDw+}S9OHf9?(csK;~x}+im|yUm;Z384qG62UHp3apHs z+LyirRBQ5Gt|P1PulhJ)o}@n35j9x#3i{UhQZ00mwgE1}qngH{w)sfLp1M2d`Aw?- zD+BwFJF!Z<3-$avs39R7%$8>=l$4cQKQ@=L`+R~xT&7G{!vv82QIDkVYwu$rUu0Gq zb=ePq#Zk<@Dm!GYYt3W|KtiUbh9eIay_3QnUV9rG;-JaI57Vlo9)IcMk85}%t*6Z; zdY>n#v;|%#|E1pe1QRu6Rnd;}w2wXAu5)>9@yR95PoOp{p3j_tVgUKMIjpxgd8psQqS6* z%;My#V!0=U*Fw5&HQh@_rYT(^tw(=5cwhr|Ivotc$2oC9B8!f}DB1dCW>|{3;A)UU6m}ynv zR2DklAGhY3$x*?+xADdo$VpXY`c6mnS1Z9l==tZnPn^>JkEb(_hO+QjvYE$-eJmEM-KQWEmvkww66KG+_!EA%rZ2EQ7I+-S_?ZqM{;t5dStR z($|fjn!P(&P%vRsD3Moq<%uM=fL22^UNJ(RMNu3YSUAAEw-Z`9KrJRY?1+GnQHcIn%9?i!X_KEwQ4*hivJJ*U!|Ga>d z1x~7L?N;U&zMKr-=Q-%hQC`!p3=av}+g_iVYAwhPHzOX-*<2WwWBF{`fF5vzm6t)IS}f|WP6Z(WfXev&yfrChXHciDjaAHcN#KQD=(~q z9wnIcC0qsAPsTMIp*+UxByw?a(NZZGj3wgGYZlsKI_Rut`olgZrg#`KUZN<WdKf&)xIJE&rJ`T;DJ8Z|MRsHbOe8&598IDhpVqWV z$R#qH?|+-7eqmTOU9T?ne$06}y4~)1A<4*ra2);bdCu33j5KRZYpvWs^Us}emRz{wjetlA;-7QM*z$VOhed2l)sgaCsAN4I99W$G znD8o3GCnWECen>M1Q86M>KJkN%Br)00X8_7EM2C?N!prk!c`bdObz`l@kNKV1^L<$ zL4_%^45_ZMz%iC;SNbCl8W7E*(TGoy1ohAo+|zzjyzy`?QVp1I<-y(6h6a+_kk{xJ z?v##JknsvT7{2mqby(_-ZH<6z5c0R5-adU> ztb<_vxlR}Pa*97^5~~`4nkIOif4NFg5WL`YnbKREwZGXcX{{H@#0XP2@v*NXPw7P^ zk}9O$rNsLNKO`FJ-XOx1wfll!+*HM9jozhPR6S6+#aOqymohTz>i(>5KmXQS7DF-O zY>``$wu3{<>DJor8_h`S%#(vWRI||y%$pm2ag$ZJz&rnh4AB!u!ss@RR|PoZG=6>j zQbO)`4;B1`j6$j+BQbP~VQ@&OaV21)yueFr8I*OOCSB!I`{84Oh=Bj~b}mhT=8GOm z^7osxDs)xoG1I*T&`X#}%|`Rffuj4fatHjcd5jHd^!(;jegT1#vFcPO%hR>-JDqOF zg;Ws=bT+DQ_0H0ubl*i(as(W}KjO{db_JiA5xu%uX0b+ z6iTw{C_87~?9>rIjQ@}E68>zKAt_7?oaWLXE!Oy2)W)}Z$@96`6T1&)-S<~{titqD z&0Sp}oq<|7r!syOvW*)Jj%CXsIG0AlzP)fe9v%&(ONh!pUju6)1<2U=>Pxp#(+klN zoX&t^2vdH)*V7(_BQZxrB=9#hWN3pyeJgWH7aFVYVhIes+!x4z1>LIX`(+$mTq#N{-fVh3t=? zS39R=c(T2W{v!V3UQbZpaq;3216>^?-^rtJWZ6RAIPsL;4O8yqHXo@pr@Y$Xvl{Xm z)>Zmy?Ul(~NFgl^NdrmVf11@S=Ng%`6CG$rzzQy7;1E*DuESG-Z0K{u7MRQ-8B<0V zis*kRt{EW&nzF@3>DDB_-Cp)CMQyPh5*k^M{6zXBYaANm$W@DZqZ5y41al4%`0?3QyaA`x5aL z-2r%j^VQ4eqNHN@BEB;hMky3}?YkrPY$BMs04GwlL2$0Qomm8M3e+nyO zQYn|M4!29)vMFkgYHkbg@eYo{m`g0a>@Un;1p3wtXIB&tC*+cF_hH=!V8PgWqIyDBtk^T2}O)vVoLR zi>GwAEguzB+5^hmEe?fUae~ct_+Z(~VORO=R z2u82ei8u@t0UrZH?%pE(EPEm4Pg)IS17^}%JB{j)4S<1Wtml6_t|gZH?biShI}ja<}(4g8IIYiQ{i^fNKeDLSQBZP=}Ut)0b7>fm^DgM(Ms zgAzFBb{d_{2sg}{Z;ZLdsqy+Y)t^bwhFc-ztLVySr}QKTANk>5 zoO)R*JBBXw%tI`1Npj$!kCeP|T9^RmPA<>~(#Da=QMo`PGpd&_O^hr-vqI`iFF?Q0 z2r=BL<$p=bkk>oVGi&-37lN~*pGT7-9u6pPbMq8eHGG826@!+#M4?-`XK(MGjd1GkoRQEm~1cJd5Hq zucOMxZBL~%T0Rb6&b)j{_d;9sDg{LkV{Lh>DuGx|q)(zaVQX7(^9FX*Ajmq7VtNQ| zSabo!i|gq=CNfW+CKWYm!;_jUygOgU_U~Rh&Nfoxs*J)Cs`@R44RzTf<+Z3{SXB=* zyFW|TR^rjHF0&(pd9Q*Wk9tKvKlM!^7T`MHCPc!lIqbO8BG%?V^c#j3skv+#KX+6m z^|MccRwYepu)4IIYBpi68~abx8&a2pV?kntL_-t#3u-;IOTk5Piu@(@hkgbaE4tt$ zsQ7c8mdK$QOW%xz8aF-!Cwi^G!V9JTLw9d;BC$(3AO@Zbo-*erD#S>}Kvt;1LH!SXZHm1T7r*#Qy&N$ij%Vp(syHxuwgs z?5^5j{jp++4k$$EFoddU&^J4ehrOsK17`r=yct#6PtRW<*3g3E;I6kl4{L{Y(f$n< zCXBnqz6B;=OR?I$>IiKY6>kclZ`lauExD=t4Uv<^GyWtU_HCb|#FSusU;}c3>6>P7NP~_38 zT4sAsFt!oA_7JGBQhy%Jru}igktJ$rc81lH9R$PhMqp3nOXYjc7HJ&!42w5sXJLh2 zSDyr_u?=OrsZWR9LCPPGgf()1e-+cm^tIo|<$aSx!&HsB1W*zdpRgEaqaL2XYqQ zL9efnFc~Y5D6Sq=7+5b7yGfU5`3@HT{_#4tq;87(Nce3P`JPB-@*(=#9}+`2RgsPup(+C;CI2jqdp4uL|l2oZbu7 zp5QOM7votWL-wa1zxLFh`usCiOhb#esjhx|;Gntb8Ku8(V{Prj(87z(c+69HL-||@ z4_XGFN%-bhm^KWN^#Fe`l`UTrj6E}H`*prN6gx5~*PK9p* z#fp_NKEgkm|5Qs=IfixWpU-hZ?C72$4#^_^I z9*hoXcj~Q*dZP;45J;5-4DOqq)D!6a$Iaz+7vT@_kkM(DuN4GuOZVE`ZkU>SGmR~0 zdt){^e*BS{%Wu+wUGd|jB!9-(7K(6{XiF2L%6EB#gAnuve=<_ zwi6ITZ56YsTt)IodZH+s|4A85ERLgt^2E_JUh%_mZN?l=F7gU_%xNlKNRj_pRX>*7b>QNJRU`0H*N)jl#y0nu z=GK=nf@mM+g2fROJm&7nBgBd~Vv<@GBR}+yv&5vrl!j47o)8V}4bf=t%LqZ6Im+9U z^1LTwoxS4WWAMx7oUaw#c0C*5=kc)kTPYxEty%%L-DJZk@5dPZ?#am(VdPQ4O7$B=lX^yIl=fuv|)*Zc@BQ8RA-`+w`;Ow?!GNJIGr7~Hb0pB1<)S--MybD zto(1oD;`g>K81@AGSq{yBu{Z^urvEuI2Wr3VN3ss`8h0kR{w7@@A<0Ij50c@I(b>F zbSm+PJ$o40d~2Ky-7zJ#{r!i&DR-j(P?9@1x8(x457qqv(M;RS0 z77UkHRt!2=9Lc!n4r}zb{V+Suf|nHKZ>W7{eT)+iT(8=>zx^t;5SLN_htkTM#!1D- zSzatXabrLVn+lKbEp(Pz|3Uy?0De4ltV5zXm5Mz7s(WX|VRdt*WXP4)B~W_zW@P!? z4(c(c&^8W@!0WJ5-Zo#xeKYIez2$R?5&CXh_(~q}on@2j5N!)qmF(wrO)u&p1O16> z@BZ#|_EgtU>=+ zenjmPN)vg+9gXbsljBVcwny=xxB$YZ#WWr^)_txQw!Tm++`)-XdS6uZqNkq0hd{?5 zTbJf%k6H|Wqvp<7w4VT0fTn|3E1aHiOGl?)o%xa;{^-fm%cCx(yf_%0ij?nvSh}j@ z-w%dAa}#;X8Q381Uc_)d5 zTbS-+w+e2Hx41Q^BgI{jXh@Z&p!K0BBfo6;ZlPr>l*o~2^6txor|HSlpc40Ua%E$5 zI#4t^WOwtFTI&4zg)bK{F%lhBcXPV~YDYwey!f)t3Y-mOoOi^uP+qs-2{G!WKYs74 zAxH1)qu4ml&6Q!OW*HIQFr|!+CD@x5l|>7<@;TFX~5mb2(0KASwNUgk>M)y;tv= z;xJM)&^+@E3>*E?In_E9BHPqJzO=GCSXrRUG+q)64;lQ?8QYaL(Y&gSH>4_vB2>rK zXI>sdm)z~BFS0?HSVY55rMfES0c7~ft6~J(h?`t4&JTDF#;teb%wk0upr23kE_b^^qS!W-@t zq4Aumac_yC0|{COF^i^sl86;w9+Ai!)0Rwkwm%d3KMKGeEXk>wSMc zq(l`@J*pltTXG1vA*R!I|I*)8=-CD45a(W=PPyJ@^QC+S(iL~pz| zg%|&t5iFRy%88vP4ZF$R&A6q!Wq3>=a-dz_QH=nzg43U(ma4ddg0hanS!$~BF`Psm zUQ8z-?puq8{4Y0Ikj5JeW3qA`fgkQO;Nv zcdsKbCw6%4BjZQP_?~GIDttQ4%|YSQE+rb46h_COgdJtLupTTd5>F$oD@NQ7PXp%@ zi$)ygnNSR;@Qu0pLjU#N3%4@z2Os%&A7zls7dIzSEdimSXR!f3L5e8$QF7p!$TJCA zfmwNSoxKIO4weNERPf_dQ}!uSu4Bf!={3&j+t#udQ0jzg+2n3;bhPC*{;%;}QTu)U zv~g0wSD)w8`W6N6kRtP7A@(fRo}Gn?B4-o6*rQj?M}Pe~w{n%Mg#U!U??_SBsUc>l zMW1F?_;%Zc)xq7(NuSC=y$hA$+tUYpAx?9$0f`)4xBPvBo9;VQeE9G|h{&OpyVGhb zmCk?mtc9idenU93=}yDQE344FZA<1|4-f<~j+x2GPr;sSr%bhK_Er_X?7rBUn#x#c z)1!`O)XVlu+`EYUzTDkiR@8W~{6Flk(KD^w^`H^oJsztNz&3GnbBm4YUSBs!Y3l8XVs7Y zJm(y$=yWC*(}I{lMG$#;BBka?^qs7vSX0|~+mqd!6Q@A{;A{qb&Uqu_vu2?R9O6O4 zP+=`+_@!m=ETgoV)-bNlH_t_wtFNR+Lodd~l3!pPGFw5XzJti)K?MyC3?f;n3%YU0 zfP>3i7U5{|oCo@(rtqlY2zoL~yKpPPGyTSetLLfrj|r%i6zMvcLPmB9Ji=GJ(DoxT z#20p(DaKDFT+(BtpFwv*<#?KRZ?TJ+fFYGP zH|OTNV%ghRIMBKf5{dqd)Dk)zKdRuE_bqIBRb^|V)n7Q-G|SmBl>Ktcf?LC&tLf0Y zV*h0zeFFp&$3hS(>HhQfAt)$z7VYPvZ@2jcl*==0YdRq;cTm+*NrN}zu! z(Xl4^6w~i}*0!W*Zf@_TlwZRr`YHM|^kyx$KL1dX9+hkQ`sX;K^yw`RdH!cHc_zh%)SUpdeBjT+aA?WWzvbtk%)frkwb_YtEz&YHTg{*8ymiz?>?**ca%+4RGP83 zL(iDCljT2o`)`skLJcOij`QXefH7^bxBFQ%LKuZ3jJnIxmjm9EWHA`z#-Q3?k659h zAzQ;Bm<3OijxcPA^XeZQ)hsBee?m!X3T|Kfvga}Sq-dln- z(wSV?Un66V#>P}K=zaWllIJ57Bp1T`ElyQx$OP@&WjiVUgrTyoReoXa5DgH0B6yOG zHB(dqckPt;U2D!v19Jy{=3}p!g5z*aIn5xyx4w{gH+5WlIZ(7@ev5xiUU zE^wjL-}}j+cwG?_#!Cn5V+T7UZXF8X*_N>&d(rE;&Sgy#6H?{F+TajR1%U)_@&8dr z1|OA`xyLpe0mWwp{DvuT@Tcj(y;@cXk|LHD%?&v1>_z zF_LMtzhHd6vvU+=KwTBfP99N5{;qTs{A(H(>`Sgy31{wGSTH~)eCXdXH`&mEtNN=` zudGhQ<|b<=M#cj(fU3p9%9|SwHSl#@iR&@io zy%qUi8NI~U-iTY1SM|n+v(rj>Rrii5$v}a8+G-JEHkflNf@`B+V08ivAwZszV#yNu zL@-&edNerFvwpdxlJnCV_j?+rhAkrPo9M)o%EiAMqQAk6HhkuZ?=ftgkb$;IDK}ND zTeYMbJn}@eS{nYVULI9LfD1{r!R&p(NLkTL4KQdw8LK~nhrwL~V(i&TC19}lp|atz zu~_)8rh&Nh==oA8BFUN^t${Mbecl!APgYFa?x1uNimu6eL)!;2ocEa z0cEP87N|$pN8SCep`|~|PbqbHp`*V^#l7J;q9z!nHTo=mcXr}SY-L(4O+1<0~PWxJ&%&=jXn{K!o^u*#d3b!KaRE~ap?`^ zM?v1YQZ)B>;1&RBF)XTwU)npDu2Krhj8?u2W|KnJr(TigfYKbPd}*2mGCuN;8p2uw zm{uVIP&7?hgYGWn_wRT?tG8D2=i-dp^S)I`JZ3*ts)V(!D)0Xvp9^|B5q6+*FnF*w z9llXqkwkk43r9wP&~7v`K`VLkLKThIg$3bUavbeLvmp%Eus~I=7xVO9A1z(e77R5z zd2H4A|8oJ_hg(@~Cl5tH`G*6M7<+=DS3tmw`kQmx+K!2lOj?>!S5)F=0f?%nV^Zdt z&Ux$d)KsUy+a9^C5tw76I0Tx&ZG;CA1)KXO585TMsmAT{{<8OZ78zjSKvuXO#vSV9 zca@d1b*B0+Di?W@xe*gc=>erfH0u0M)QI2SqsH)BbF_waJ^OZ+SNa;5g<<1-X=d?~ zvRYh(>Yhk%Bv7iLGEoD{_X#<3iU?J!!se~+52O%}4T7|R7`^_k1NX$z9*0#2;l$A? zx}X&&VIcmW=C_5lzSY+hm38VaX{9Aq-1|4QDWmhWundYw3(CEOmRTsi#M3dg$BL5@ zNLZa$3sMz#Ak?^ed%S0mT+&6aNTCl$2z9O2xL5aUYikEu{?I>b>qFbH0E8vqtxYdU zv7@Gq#eR{?xw#Wld%^(>Qbt!kpm`P$O>rQ(ZxrCjiSIX~1zw(VlKc_MVS5f)>$|tM zd>d9Jln*U59_)k3Ol$Y@@@sw#=pMaK?n>DJ(S zXDkXilphU`OLQF3^z`&AZ<4dRv{*Ef!l@(?TlWnKq5h1x`Fn>B`|lNG?*flX7<0sb zX9oaKO>{X41ru#vU6)!^p0seI|7I9OYciLiL%|Z}+qvb*)@2 zFqb~TTt3~AoUGkoaW$h;{5&|yR|c=moa?f;FrlR-C*yd20r2}|ru#J$V$|Rxn%Ln_ zI0Am06R#ol!;I_mXj4<*@k3Y!yyqQam9%N+eGv66T8J)HO~dHgJ(#N?9WM>ntx)Q5x`VFw=$oiu^}K z2&=+!cbP@*fJYMpd!aq3y{aFJij+D;d!2hUYzUkh)6+aiPREh0!N7qv0vn@wFn1M| z%lsWy{;{z!czyfotF83~3j!>xq0l9jlYmZDjYEmr8wtz{vUi|yYxCW?vjJ7Zk3@6Z z{%i0v2>)5owZ6#xhAM|TkH)igB(8gJ%| zO!B^5{|Q-6g$W8cvx`(QM|RvPbjZehlthPGobl4&qng1-?G=W)olJ)fibK449AW}C zo;hZXz%50om0P@X>@|J2eFYTtxBsTY;5ehpG;5Q%si58-Cp%=u#gcB|h-B$wqHL%i z#&>}M{M`m<@ddPqnZ7#>VYSj$DW=0!nLWD4o*-8!@p{;}3W=M$k_6Aso#*zL){>G` zgrF?}@Oi+(w*kiFC?goy7XX>9ilC-;JALKlio7Y#+;9lYYH|3tu&x((`D)s2w!`T8 zo&Dd(5-}F#gSzXj#LPw{U zse|pE(_$KJsdINKOW_tcx3@QWJ;-FiFMEH!(!FtOahMU#f6IX^Ycb~H!d0o}vbQ94 zWGQDL(kPBaGwJQh=vI|$re&G4)B?$6Zew@eRvzWnpHWmqOA?5e)G(1$!9=o#0h6Wh5PL1-~+AEbMCUbu`@(1>6hCB^~*18{z_(PHA9;_@Z zp5e;PFzLD?SzaZ0b+J?`2A(JBt4=mDzDyV)bBg>;MXf$=((Z=__{>Bdg&M=w^XWlI zo8cPL>g*%M>@Hdtt)}?u=K!TNJ<(*Kq9N~vvX9%zq#Jx0`U%+%*J6%{=XFyRzKCl= zDS<33Kgf!|u5sTfOK~xX?gJ&lbzS6gr`(uNsacsE=Mj2ldB53(w?e5(2QziVm642E zX8cZkJh*-OUM6ae`k%$kEbbo(UjgR4gZb5imGA>A%53-hpJn$F4GbhBEqWV6S7nn; zi#p}#>%ip}zPUX0pTt1%RJ?nWiG_$*=-$edL#6U{g+8+#xMsMt{}`*PHeboIGO^Sw0oVyD*?M zOKS~uozywxnbMFYD58upRI?C#SQwjX-CkVND|`0w8xG|dq^*pZ zIT&F(JfVJX`pF+njd$g;uYn>4XT`AO5=5dUz zMu|71s{3ERVzR052MyLQxt#WT;(66~f#Rtvx%Vu3vgD<4jq62eHlhE~HRqJN;wyeo zg(B72`v+5XLm|}kkeDv$t$~!Sjx4N;q`VdD_%X&9IxUO}F)V6otlL^_<#@77jK@0P z6n|IK*VfjyH?sGzk`2C1O}9kr`8NcSM^*KJL#<(OzT(X!Ru~Ho7a!*pqb0Mtm`9>2 z7Se?~Q0I^Cc;jDl7`TLng)NqxP$mgvp9@z~Yl(SX+9~ynbAB6C{C)Mq-}`?seHZG% zkApmyAR!ocC)7XSeV5o_Oqtvn*HW=bALU|trnj3CU&g46>#NPQjD;ZOY!m$vmjpIW zQi0h66+(zuWZdl(M?mIpq*q8}>lcVmV-=*S$h48s(Q4llkR))2+Fd@{Y~21${tT;X z>e~*We;2+Hp^JwimlwDHF3tSM*aq9$`Q7;tNr~FwOZEioIdZRA^my+}UK~E|(&D1v z^`LY3?`C6Tm%`Qy!h=ErS|lU82LQ+W7^vN_jdm#Ei1{hL$Hcfk8)rP*wIgnHUo4eG z_nYe77^unU^poc^#R+C+j{W+z2(HUz#8bv*IJG#C;nj!(Z@8LwAS9r20bvx0hA=H} z?Qf_Eeo7rRnf>|?P6JkOQJBWCy0{WJMVtuv=R7YSLjU*Gd%A=v3X}jM_-a=hI$ObWDVNLfQB_Woy$M*UdfgX7uu*~R zF)Hq^iS+QbkM(u4cfR1A>QmTGqV0$}X@?n^Ojym;N4S|)5Q86WAksk$ zjuFgfz`rdlqETNeG1T$3wf|g-?_Fsclilm!QGvChVPFPqEf5SBR=9uyoyl|d7Vg_9 zR2fmgv8g1kA=l_I-n$zcRQMPkAL+4;8^WNJK4^P7s?}W zu7!5h-7u^W1V^yBIbG&Ri1Ja`)Fq={QU2$(pJVU*`kZ8j##CS|m`@~ViD19CZf!Bg z$Pngqpl3)xh>r(%NCaF>uD1Zc%Xec22!j0WpC?`ri5qvQ4Bl94lLLR-e&@BzmA3NA z*F#(I_uXoA&$P=&e2q=AUzttjAgmATpT~#nP98$3vzJM%Oy+vgj6NfCSYBUg+^%2X z&X>^KPuA5vN92rf9X{DEoFn)mLx~lpGxq z28DQIy~kAU!lyzDwJ_~)9LIt-glmy(d0o9sJIshCIy<(SW!Rez*9Zv{o?v8KzKY!% z&P3+ay9kJp5l3M(RyhDxL$I&{R02|gq0SDoUPeGL>whnW5nNa?O4=mY4!nurYzo=h zUR!(KLlt{48C~t5m`V7OTgw>bJ%juQC?_otamVW{-RU(h*VgwqK%cegVMAk4x~qwx zfPi!ENHef@VI_6rmEwgg$IP#X?QXXEUwNBkdiQN>*Q{N7P?NsJx`nq#Rd{gl8IdG& zqdH0OqTTJ-QBw$5-R@+B9b`0Zj_o(o@4d_PZC?H$ z(Vkxx#e`MG5!kPXZ@}AQ2NU7DYrVI!!#8(xrvLKq163EmYy(fTW-eGx+eHG3EYVfw<05E zBHz)??7YIm%Y1lpqcFl6LaG*H`USm{wdWD)sZT$`xR8K^Xb24s?0U8YB#X->==mvt zion^pBuA>$S^J_)Vpc)Zu0CMI}-e(@G@AfIA`#2*_C>Z=AXXIk_3j)i^d9Puo3Vk zY-|VgsM2WzCKi9E%8KrGXlC8Sdi36rWJOwA$Pql*k<%}vsL_(tUzZje%659K_Ku;~ zHbx#yKN|2QVZ=3_*2cnc3z(SNKA*a9;fs8$6Ppbw6dXYam6nASVzx_qEBUTq^Y!_S z1mhJGelxBna&ysV=MN=;@|y# z`2q3dSL&3fQEk5`dT-85xRDbu4i%qLflv8h=d(F8^Zi=0 zSXyWP&gzzrVn(MU1}|u}|5N7D`L*3YB+T}pqY8*59!ynssaUz+opuD@4muKh$a{wf zZN>NA(evx9B#7O>!81E{(EQGEHBbTNHjpvmR%=!o;^8{{Pt<3#Q2)>l-b;3)Ri#AJ zJ{e;Nt&0Yx59EZeq}Mc%$xR`TXwd zH~}4jWpYE|E-~k?6oDjYggO z5(VWIC&Mpb8&Y|`OYivgwy7RLmrJ@2nvpCJ*&CyQe7t%ZJs-|@yg8Pg`*Yme{UcOF z#L<^*cuCLv+qt_oK7t|$$(S2#*Oe8YqJQ|_CfX197mCH8VpCh@Bu9FloMQ#*io+-c zM=d4^1G6HPquHXlsVJ(vXbYGatk7QBr%hG3&D}}QOMc6N_T}b`#J^s%!YBQ#ek^5n z?;o5*YlB!`zXI((B8L$SiA+m5$6As@$fgVk(M$oaDmy6w&{4U($Vii@u1+=VyXZ3F zS7|Z?@KPtg5RTJDB0k+8kkLmZVH%ri9R=If`EgF^MPeX^zu_MacDP&J9u?*#gr4Ef zjqU9siH@2=wKX6adi6gT67VQ~WKML?0A1a^g}M5>?-}P?WmcS`%zx62G%g5`!NyD<8nMrlGpA5e`p1eM~byV+C?&vkF&}T97`%2-1 zW=6RG`zAU5m-oNZ=87}U@I00Zsx~_gc3t`w$1hjS-OJdvc0ZWg>-$alP1!d(byf`) z(}G*dT(C=QsOQsl{fZhe_B&OcaR`a9fgmapoAk{FKmOyK-W8PYU}sRBLZwgO&hPGo55-W{*dbQXTN)3`ZaZMmR!&GeBDkr#GZ2guU`)G z@_ep4jbo2wHI1C|Uf#_G{Hdk)14U)UN*%cz%@j#0lI4yr2Fs#>v^5xXlKidpeghZjJ{FOd0%#VYljjye-J+`?tlW@hE&ghnLKH=EiVm@Z6jr^@z57FfZLM z(|39y+$9dciUuBlB)1cveXzSb|40V)sNY50e(CPTYPoDvmuJrsLy$ypk|y@V@9a=s zBj6tmBTlmW>naC_UN_GDtAQ47X_Y5++ADlLriM{cP^@pLtJP)bJ4RNFhd!SMXG#Eo z6FmDZF>wQEuZrV4R#gsGRdTr}9J{ifY3J&-=NB>D-256wY|8-%&X;CoZr&KULj`1) zK@&jMcDc%z=+0OS+Zi4^D<~Mg-Z#)tk0v<=+LQ>~5@n29sf6veD2507%Vp^y^N_iX z41g)gtjq=3_BL?e-W9FCKba>LB*|B8aqph5B{$%TBe`I(iv{mPL1L?u5X*qc)~`7eq! zwSE`UK&tW)G(jbLG*HjjCN2T2{a_oUT06TEY6pTo#l9x!S}>Whi!HYr z7m5NNX8m5{Dl8ZS3n5VvdJgcXwZL9B!l@TEhcOzMBeW09lOhPAHOyPl@Ca3xtCQAt_C^-=M$W1NDZrr5TqzngB~0H@rph?A(6$z8V&ENQgMqv3@Ip}T z%k~P1-`&&+H52!ql4a|I2%&alaj{}@#gHqL`PcRKQN}I7Oy$rZar+wc%hgiYxYj@W zBMtt>?RG7eWv4-~4=2NSvP&S79JuONIf9KV^>-cMbFIP@TyTt^dU2c+?LiTV#C&dZ zWWk|sX$>zN!H!4W3IL4%Pe-TEPCt_8=fuWFsaf>lld5!{V%nv){&v#gW;>a#nA`;~Mfa5B9N%jSF=|vN#ABiq zv~(c7E~=k$e#13dKlQ z#JN{~T3rYkNQdz78;(uXbjfiFXC#^(R%et{Qx#mQD5+++_>UpWfBGI)UVi#!;I!KP z(&AY=ua*71MOw<$r?>x&HV8a+C}h8P`b*+7VEc68*qtayq}NkY z==DW|D3{n=z%6&?qj4d+M^@a*KeScucBt$&gBag~vbzwZ^`SCMDzoJ^$d;zOZ2+&^ zJ~QOgy0G7FNp$sV4KmGpKef44E{(n zmr@~wBx2CtVjz$K%nip15s0#{rtLZ@hPs>@Xue>U2m&1ndiC z<#8px0ygYuseWL1Jr5yDO|l%ZYgnE0Q?Dg5%SlqXCvs)x7Fpt|6i-Fp^1Nx2APRCt z4<-Q|36s?M;0#Gl>n1w0+Q@O9+)?o@_>87G>P_lm6ov(Um`kn&v%11^#h^1M1^G+d z+$$yYEAHsjRbPEjb}ueTrXxRDoIR&(PDVcuMsc0D8>vDizd<1)s%k8*pd)CH%jgBY zZNvVIw|4;hI40UZN9+hH`C#{6xNmUqy%fzXN0K!4KW{4PdKv-nr;4`ytwOKzCGf;Y zSJsF@JDB{$2b`@JHFj~v*q zAH~@8t9lL=!?(cuTBS#kI)-wumVS1-N9G@m_w@SvB|>;HQ3O}<2`oxPB99darbT<7 z_zM2HflSztK)@oClapl3k=xr#-O147a$2BOUjox6IJogDFBq&O%XEey3BCCvl3Mx6 zm^?isZ*r6{=E{|01S4}>O$rwI_!R4#+S3v6C-T}Mbu1DKt09HX5uI>iIn>ng9Ph`* zVZjX_KYrBhtzt~Rm%v1ZTDa?LgL7-s$GXP*ml!AIYjPJj+3i0`n^PB;XFR}7_;H=LmEH^ed$$))$Si2`g%~ExhA#!cU063KEpV+ltydgfk!TLzOcbx1I`LNVT-EQdSDv1bDmd5wE`E<%5ra ztGRdJ-55+zTYCOPF4I7>;0o>CktntFzw|y)sux#W^&RktCRI-4PE1T_H&Z+u9hu{l z--|Q@Bckpx_l5WTFrf$V3a_EK?Vmq9pPx*j(e#|3PZb&qcX%OmhTDr4g@jSJ^=`C$ z-5|eCm1m5E{wMM@T4&hzc|dWsC|)Rp;}0HFIMY1+MMo%N`P*w$=5$ozg-!*YoN^RS zkQIzG_yTn$FRZ32zM;q4USl5zXC(7cETw z!6uy|Njg*+By%4bCp!{ca^IXfB{E5(GLLd;9ZKjQ0y<)K6qcP0t*eW$9%JTq|1=Hu zuQeaN#EAt#{0FNG#T^|BTfa3OonTof6BCzgdp!3kT>i^TGud2%%=;`U3w-Qw>>2-`<`JQc9Db_V@EcoiEao{eN5l zoW($5fpq%^Lx34j$*`A*ydZ=W+LY08NS+-4=%1y{-?qNNq5j9ANYqg%%74^UPcq^I z|4FtSi;Lh~E+BYzVPVmW#)%;GwmHq0%w|v(Vug^(%Kx3lI#oY;n6arM^INH7RZJ{# zkQFuY)ySK6UPqTLVau7&cQhl#QGg2&6n`eU&^ake0iDu=oLJHB8DG#>U=bO*GKrblKyS@ z;~inp?wrZ{x-t*E#HPyTr2`Xf^7^Of^Ubl^Dj!1vgFw2HIQ2T@V1EJJj9a%_H$t+e zw`@HxM1PHc!$V#b*i2eEH^c$4L#*`Do*wyl-VMqF$0}LZfwKOK_U!iDTvZ<)tYK}n zs`}xHhm{T_KdckI3V=YAI_`CVaHg)yQ=PGXcS|y`D!x*L-X?@@uU+tc;24-bZEBhV z=#^V59akJGXZIIrQ+>X}>#!sAN8>3?6nx@TOpZ1-`n1g+6Ob4z7wka@-Op-YF?C;3FY)jZ)0`*FvGdk1R` z))py_uEVDEH={Pn+29&@&y22S3hFN^fh(KC?oIUc%Ux34#lJmfNTumPl41#08KdNE z{b_&yo5*fZ`RndJggY^DXDxJ~28o`wPX9+aqUtLKjlD5)Jm!i2KA<9j`ERvUabJ-8 zfpxjLlvb&?>)5}g;NRNbCUdalo^wh|Ky&x|`G&un-Rdq?-m*F`Y8GVa+XuVxO%hLS zpc}fE-V!!n!NDTzDr>yV+Y)#~nd{bg5yf8tJVHxCl2n$+RG1Muz@%Nn>L8iM@sRL5 zn^s!`Q~9sd{ppf&BM;Q@Ra^-s#t?*DMgdx#1%CAnne%n~5EQ@=J0E(*_QS)hX|szw zzg|m-=LKfDl)l7RjIlsOZnHLgIo^Bv>}R}Tii7DuwPyv-M>*iQL2FqIaKxxjE1|z# z6MU%|Iu^_TTs`{cur0Q#KXky08o?oi{{R;dj|jqAI_VMPBH}~5%!%53!eLlAbSw%& z3#Cf7i{Xr~N)fK)(SXa_|v2k9T&Sz&g1!wu;?c1<6DCh)4+K^5UFM z1yOpVlM#LZS}hKhrRRR5n(H4v6;3p1jmlLo?W6qO4+$<7^UAw}gj9WkYfl^hn+Nz` zw_Vfg_csd!wLetdt$+BCV3ajwyg}KK0CrU6u$2!BLuHJ=t93~$zngQ{9VXDTc<%>wEXUb%47CWaBSFPcgccVf<{rxYpMw!FDc%Y z%eq!sIvwPK)SJZ^lig?IwU-+AF}tTuoJFVLOi)nymu2NEDJlAD_T{VbMTzWCyCJP} z;bUPAI>Y)iDPxyV7u`e+K>^xmoi{%^TYi3*9hR{~7FMPwMVRAY6gcdTyQSwDJ`@9_ zps?*(CRuqyC&R5TKtDBYpFa*Ydxd44jgN&foMHNOlX@BJFRZAw6}5j;vxa-53l|%K zDf$s%v}y6zENHlvI^|i-Uc&bVyxzR!9a*Zf-*s5lvJl;2tXM2ZEqgmweQ(XsLYQPz@VkysCPSJYBQ`QU+j}zxmiV!fS5SdJUdEs z8UGyC*UWoXAa=Fyax_3SmzHt>q$#7x2QjUqbI{jiaveakflrf@+4tz+iFX8&MMrx3 zQ%VtLKFPI{s>wz;wK_@kH2t$&)` z&@=I4W0TDiF4dVb_ND@2&m# zGtf!w&HAj|xAI@!yw~g3uhmTQ7d6dnj3D(a>VRB7B(9K?A-B1(t|k_CoUGR&;vobS z9w&VvFjE^L9Et>i2pAXJO*CHM62ftT2~pODI1WiQQEg8B?Ka!g)&qpr7&AnX^pQUd zXK%kBo^XmRUhkh13`JD&Pp{LiZoA+-&Xb0u)JV!7!C_|j3ixs6ml3vWx^VLUP^v(5pRjnNd!5&8H&hp(46AfkA;LdhdYo8>MXzMUzlORYtZ@$+n z5p{B$rvZvVTOPSt?zdHyL0JNj{5jLTr5@>ZT=;BqO_raZU@yyVh6jeiFmmgoCk6KN z5bF*a`>rmGk2wUm?RD?1iuu`c{w&xqitcqd^Tfq2PQ`_Yy3cK&N7qk)56|i~-3Q{| zY}_;HPOVP1@9XR*BF%h;8_7?re3ZcKBySPqgX&#%avwZDp;k{g@pAR*;HqnSDV(HY zA;i23e-nv-FtV@=MD2vBi27eH)cmnD{1H=+TXO+MH0*D}2<@=V9he7zYHC&UFoG7wyGa810xep4e4%_l9LuAkG(zK{)yXRsvZ->d-Yx5YwF^*Z~zL z%ewX4g&<9W9=>XBK5ilaipF${+o7S=uV3>bm6mt>>(iY*7#aH0P95nY?q3_M^xmeZ zteDO4Nf*CbkmE+iJ*~F~S$+xnp8*p=_9LaOI851jZXBXLNsEhWa`qIk%uADaQ5$ow zN~qj$g=sARLZ8}R;Dt8!kC_Bt}vz^8AIeJ!}S-LJP3>l z4eP5)N(-7ecMrtm=I7^?=v614ue4Zxn*XsINq%!h9oz+J=M{te#7H{MiYmDQ9C!zY z-a1EQz)9w-twXoHBb%=uh1~hnyZ^D+NSU)N8Hqaq?GQJ5t8{DyE|Y$$YNSGIB5~;o z1zy3vt}6k@SB6nEW>0%lG=8=Y6KrrK-rwsb;akg;jPZk z+W=a!uPzPEmkmCq2A_Tl278qCM#T5nz|9grp+1O)n{ zfp{ebVn09XLhsdxpor*Nm&(He((Vwfg5TJov$nqRaA%k}#~0EbWzfjfojncHw-wj=O1OY@GX87+@kC^p(jws^VD0$Y`9*6upwHT-= zaXRMa&hpGb%j!@w{IhzNvn-xZKCQ4l&?~{m*nAH!lt6PcERnMz{pFr=$M1M&}jf#D_SKig>r7Nw@kG=Si=>*gA z=8y*(qS82+(c)pF7p<+kjeDHQKgZ^|C=NOJO91c#uk$;{r$|-sX=rX%%#qSH%<2EP zk@|0L{_hQ4gd-6Nl_ZX=Ge_IqpHj8WJS>~4coFK%Xc)^0_bf~bY(7#bqyI@IbJON# zhkD_-Vi73O%qd&GcTUW3XG&0n1@GnIwwW^#uV-K=Qj+r;mT6&n*6y&wr2n2DTn|^4 zKJ?S(!A6m_p_GwG4u*t)oIC!5%N$pKKes(744ax*m}sB)x4htA?Fi);FJg`r zDj|(SZMP#Ia3%Ad75oYl6v2TEs@*Z!$b`;2@Lce?eKHdPYmeaMiWT<2JjjozZxS{8 zF$zAJdK|skhw{yCmE}$7lwc4cHv@K=)zrO>OX#7MS;O%P9UwVoU4j|AI^f^U3H#+F zxPR5wf<9GJ&#TE9^M#OtL?K_+)lae>H-=esY`5)YT;9vZYzgfBk*){ zE!6WYsrG%%UTQx;i$(236^sssO?Y3FiA|=JD-l;_^(b(`HBbtYR4L%#pcCKXPIb5Z zx$-Bzb6PRg@b=b^qVe5$atM7UT;B}FhbktFnthAAf8in-2GHj+_1y6NkfO-<+t*wg zCr*)HXf5!(VVFjoBqI-#V?N&-fBekA!~x%BEaAH#AVr#p-!?K$`lMOQ9QeWzA6t*^ z&5*M)c;W9MSKOU*?f|&fU>KAoD?3x)Kp4tGIByXim97BTFKOBeU|OcntSFq&OwW6C zAzH1eYMLU5r_~xVYm|r+5tN|68S3YA!G`ZXT-{z6uV)Qo&@|+=7~!wn5~u11W}bew z=Yh9`wMRmb9Rt^`kdVQpu2YW}!n! zc6*lRoGzV8xW14P_z=sA{Gi0cb&>rW&|)k)9?hQ#3=3-nPK5Ftki@0jt3M1$!g%Pb zCVz4kCgoGk+WX@Fv%eY}8xRl>)^_@GN4X5Z-Bi zs1nn0%Eb1@t+O1_UeIMB$|I1s`HDEp2jGQgiS#R(Gg(HASLzD=>hK*9JUV<>AgAo` zgfEeg==D%~p0n=S>|CiN4`8X6R#bbRXo+$s3Dz($K;|X*?8s3Rq_4c9_$K#_83B75;?X)0Xi}2FSM=9#Ct$B#Z+%8O<`-?>M;`A20Y%Q_hsK74cw@Db zxEJegN`i@8Ha)#cE9=u1WWJ>n7jAtRs%QBJ1f;l06iv28XO#SM$C%fCmHoRleku{^ z^>qWnCzBP(;5BVmipNm;xD*l4R1^;3!@;)OIR2pBw~?6J18hg#S((eddSWdH7h`@> zkPygzxF^JJeh*d<#HUIJBQ`d>WOE(ha_=k1^0o)p{_ERYzC7mkfMLsya?4EV)-rji z!dpIc0J%56so_P@Z1Zngx*;)q4Q`CuC#Spd26HbKRV{dvc@)sHfw9p2hbx-S2gLMb z4CC`A97(e*Wu9WIcv0YHJ_brp3a+;#YjK&2C}9 z69AjA7JSa_T~(%;M4Njnmv9g zXL3h?Z?=3Dc%Hv*r-|)Dy#y%Hc#!xV2Lh!|k94`|CEaiD9mi81T#%tcVak;?73QCc zeVkFiI>NiRJd^S+{CmsT4c7k#$kD4>D7n7isKCHE(y&e3mg3+XH{DRhMgI5 z)vQCw;I|%zZv5M|upNHv@R%jxTQBfHh}%Z@%NU0);<~*tfVKWIvS~X0nNkf>xi=!h z)-&?;E47c7Yjrywr`K8Ps-=AYxs1pEs!W9DUj_<^J4k?dYu_HaJ>6n>`m}HJ+Q3p! zUWs?9V$nbnri}iSf@S8ejyfipI~{H=0b{dvI7p-gJP+{yUwqE6ZSyC%UW!dd?`?yW zf}b{cT)~XRc?3Z#$pmHe(B+%45v<;CyFmNiiSew9={UVJXlK2RceRY0@JNr5c3lI z`w_{z*QGzDJJy*T^_DrJW0l^<0WVPEEceVs{FCB)^{j{#U_@~zBc|~^yH=FzWMo|7 zTiH#WI3p$T`(~l8vk?!l-#}Qwp&=Zs+ndZ(8ryiBFsDP;$^$etH&)jQ6 z6!S6JPa zk^!e>DIs|!K5jqI*4m**2LBa{P{3Q1AuMWpkyc9^xL!LlIns{k_YPrZ)g};bPztDy zzI7KTB1kX5VRx`ji?NsjhE{X!@i{rBYGk;2U+udqQQ_ejiNi5_;~aWAMMHY0ds7eR z{;K8p{_e5H0G?%rGv&hYn)4<6uPgc^c>!SNeobAR2cqlEo0y2VpnwfY-_QYR{iwP4 zc-X{O)w*i3M&@F}pE{fAfh?Q-JdlZa2q?0kz0=aH4fg&f4nP0bzqb=$J&}KdRSq&f zLNhO}P`0LYtWHm4!N%gdWB&E!{>_k(e@iStaI zWk#2Ck9Z>sj2`Z}f&4^a6bZk&`UR%0ya~*M;^D&u>4E}2?$y@YQBi+&Vz+e| z3GMC`bs%SUs(GyT*Oh8VfC-@uf~{0bqK))it1QKtSoBns0qNgPO?ABp<05`{O+qN6 z$NfKc z1;Pu4^H!bxdh&zrxxv5RmvO%Gz`kLD0?Q{D>YGZiCK(Q%!0w;4{;WkYGcLjeI=?TljD&nhtB%|M1A( zbu5UHT=Nf^vh!-s) ztdr7CetR}>RUM(hs3WXY>RG3cu=qjz=zR?o8XFPx0P|oj7Cirzs+RarK}&yG(jMqfLG^|Vlz zObu%Y^A~NT4zRn&V|R02>%DHXXVOg{KJJw3tEi92Udu&LSj$L%Jd)~J7JE!Cb z*VCb^xn3hL5G_%gLb56*(iOxkcQTlvzvsIbS!BF;Z8iJY6B+c9yFu9p*_wbZ^8|@e7(5DSNfbi)>E?K{vKv zJd+SWDu@_=u6M;f(aF>(0q#>}`63}997dAg146@^iJK?^b+>m!p1j3!{=fA-6ZEC8 zU)7m{3f6fB{@MMp+uN@b5r@wfshrDQf$yiwdHi?%cgb_U6tQFPS7_K1xfzxBjb_>}>u1_yf4bXWeEORbEqLIN;w#Zg0;% z9zFpfKdnuWajysI88Q~dMFJ)UhPX%FpRJ{E9G`eWMpk3zGrQU~UC zWvD0$8s$3Kb6S*gu zfO>&nkn}d9Pw#Ay0SwFd5zq4(3UWoM#&R|?bKt(;eX2@n+3_rq1bha1xIow)o7)`f zP1fzR;-)Zdt4<{@NFalc(SGu1CtuOxCq$C_SSag@rWJ6~wDa;N+S$!Sh^n<2JKYAy z#`2-wQ>Asur(RvJeTWmH5INVV4Wr@g{az6vA@N8gf>|Q0>XrG^xoqfmQT;-blniEa z^e{xr%J7M$Ozh^>ARg|g{6$m7X2x%xL{ar4mglVZwhecGHV0I$bCJ52GwJt& z0Ellj+B-MoBhd^+VqIdlzzauj=$4Esk&UwDMP#AeTrVmm5|T8e_Ct`8)XoyWTIyw5 zz70UC?rnY8YhjPF*}(4`s5yE=8xm*iRQ33r{OZt*m%Yf?smMYx8;m)+frT-vti`6v zzA;id(MP}!uJ&%g;gn(lU#mc-Gl&&a@AGy7FKuJMgw#A|?|W+Ow=-{3pq}QK-%VTN z&5aS60QRcsH>Q2y8{7nKEr@bHYG$$M=6fF-3S#Zg>X*N@Ev+&=L?EyvccZy?Bi$U( zQ{7rSAx)u#l7(OeIun<26!Z<`fZGyi34x9~EH(@y@fQzZ0aP!ie{7~OB|4>o0_giNVD7JN0{`isL z2iz=-`AWzgaVSa^f(J}RdoCLQpM?Yj;**UBLX?SYX(h+g0(9YX!7*vU)&nNS^zA(?-5M5E&5tqR0Bd^Qz}8wgigyQ{JjZuFpQF|5tbSZChVIh)El3$OG&a{I$<@a*0$r~yZShG)xq?MwPJ=!-=cNi z?%$oA9l-3`17BkI`W>dfDM6(#r4=fDufH@L>h>eT=7*Cp%qqROGW$2=SGGDq4&aC!|$1`wS}L*!Qi~KEc+L0XZd@f(lWVvsv;~?sIdMnYz9;n z`l{HDnL>DO*uFDcM&xTsy1Swh8Txf3t;ei`>%n%j7I@wR%t zgI#Aj)b@HsHDLb9auHDD00zH8K?kidHv{QQq8^rS#H$tyNgUBt|Ejv z^78nDJC*}OCa`)?Nzx-KA4oPxJADQg6g^Y1!W6dTg08>oMq%)t3#ufDF+x~)0lSEj za-FNVKZ+y2sFo0x?C}r!g0RX(hI3RqF#9nKoAkX!V+4Rl+QZL~jsEf}Kl>iLUzUQo z*Q2uk^p6Pt3T-nRT#d@u*f^m6B07_?ci?*7Fks5kt+p7v=<8Rv#x&h?>c~LE9?{EL z%PWHIH@yexg5Bn@%aTo73B50FM!K6QHTF39uX5IU_7l`p()Ki|55NR_mNj&d_%4 zU_*c^?8JuVhsXh8y#At7Cc4ro9g?(Mh#7tBrc1o_bH&5Pg{SC$Grfy1f z@mYMbRlNe$9PM5E>zXDa)eO1e@I1z`GLshKRe@bge5?kxng)^&sBowtJrs+8B)Ked zg+uSuXWQ`eym@%A_W@7b|{%twcmz z+=cHIW^fzQ!h$G71_Bm~p)2Y_V+1caY0<%)OOV!nE7H|`NR>NpsI29k1*;UMfbPg!Y^s!DQ&ZEDltIKYRpZw3S}uH4BII`P*4(!N zkjjn;YX<4EY4I62iYYyR@HmyeV(QZ9tI`3DvbqG=DzIDW zPD2a+{D~N|!@s*0>`pm25|SC1N9~4$f4SwFT{7ILGj?iay_Dnff+{aXp1B@c`w|@Y zsJ62-Ff*CsGJ@GM>aYXY%#wFEPHH%t-a!;mJ$_fnBZ?q=3VhaA)b^XcYOEFhpGFeQ z8MSiC)|jbgvd^e#2V_iO0G<`>_;2}fY>S&iMCOX7E&j5bTWdsYVQ%zthIdNyqtNr$ zRO`Oe&Q*@K)lVo!w7qOTYTZCOsH3C9+bn=7UKxpUq&o8z$rI(QGFn?(IhUitLPIve z80hD_>C(_~T5jIA@!ihNC^pF2=;`Ub3l}QS(?zlvU6r4}pcdpUjUi^@y-H*l%F$sp z>SX_lO22v@*z1ov5h?p26XO$=3z>u8VEZ;^W-rrnX;&j+LPI;zjm}3a>*m3u!1XUiIhWxDc2TXeru4?{Dr4gAy4Ew&Jrz!!WDFfGT&}L|xQ!Qa4fQ#jBl8~`< zy%ozcdrQ7Zf`141J+M|Sgpa3q<%YnFeN|h;gm@Q?EhSq@ftv9QgbS=ugGgZYUB^le z5)E@=J#h>s;AkuGLb4*^IR09cb=S81PZ4*Ddz>LF0SiXJS2#JKJ&ci-X{@ZL5YYQj zb$&UT{V`Gd7}{@R5hFeMM9|EPd1Jf}y!{nEnNAN6It$_i+sQ~jeiQ;Sm7BV_0XOvPf%oCeSJ!p{cwX>4mrfv6~uj{ zBt=Y1z`kBVKZJP>WvW&;0Q?o6K{;YG*Yxj?t19T8uluAqp56c4UyM?#X_Zdh1AP}m zd5hqPkeL=B;XcJCUAD_9RN^9^*pGHTCmzZYGVz=m`t9%JR|Z0)t*z1Whv=4gD_A|N z-t~<5t5>h8CwzzrogRaqoiZJA`T;nJdSP(nhOUHFi3a1#_n$u(7vK1%Ak%Qle)?o* zr`~H{KN$h2i_IT#&nxtG%8FI9DBkHH=6ezx4JFE@GaF|kq19Ec>jY06+g@p=tO+~H z-)EftA}nC?Vvd&CTc>lFC;eB+Q|883sNF`ov!Go{6f%xj7ee{M6Idf~eFzi5!xz2z z^YqmxXHBlB!0qu0e7qA!+0AWg$&x@rcqYx=a?~Dx9)7>eP^4gGXV#+5!|rt@Uz50p z88N5xwF87dgf)?qf`Yy|1;<&ICO~xA*S^X`O1B@%f+syq+YN}_PPMX&-TS_;>j$W@ zjuj$|0FD&kF4;5I-$8OK+*uce3 z0ksE*1=emgr06%d=;kvUu%1~L*tEt6A)=6{-%8N1oe&K9Rs z8tQr|@l0&~05^=zWyDJgJ#2iXRi2#G=1rEUM4L@){<>z#CoZ5!czb&ggUhjcv z&_TUnVq#*M%!iH%UpYA%N+mE5kZK$70l;{vScRO|OU{tvMBr-me{KH*>-@*Bw`Qh$ zdI-I*L4fXuKHrI{+}8NUfXS$}5r9rS5fA`gPcgS{NszoL3-dRQ%SR4ec6AM8R#fBh zWztmBnFo}Db;^_XNuP}v)cjz$H8+?az5KnIv)>8$B0o&-w2Q^Q1Tki3 z2Qyz%QoZuYBcC+8L1?%!tf9F|mU`U}2Z`4Y_|1sCJZz`9rD9!AfXCIm?TZSG4pn^w z?yLZ17{U}@sIbG=yN)$f!gsG}+T#+mJ=i!vfO3OM;T!jlB5%1cetpul zyTQLSA|94zuiFXw=C?ZhoQ#^}gs|k{wG%q$3ScOMm+xu)Zz(Ia^(+NNqByZ;GD!#r zw-7IXXhcGu;SDaF?%aX4M?HytvwAf^ogXWg2I1x_h7pobppS11M{A)df^vE=>^VK$ zU*;>^0bi?AzO5^pc|Sq7K~4-pYH@skg24IYH$RxdnYSSCx<9A#+fvZ&Hzh&{V*OgK zuJ#k7=?5Y1cA2I&R6F{kWR&FL#Qfd)+2(NrGwSTjh0g%twu_Dx@McoETNijf?;(w2vEpEBd~>Uh*E z2-42$5%Q@B57ev@BR{Qsq{bXl0!1dc#&#rKqn8!JDSXU?HeR?^t&?k`V9AXtB5%Rwwx-J~=}XKXTNb$v2=eK&t^ zGam*0z!V+Sd?Ug~iWpbV|3Li98kIDKp`QNWxk?g(fgiG8*jDAh!*k)#_F^;Kf2%>Y zhS#LCRBrHlIh~vZ?;Qn>aK|;tM9Ft=VH%^@-jOx;Xu^#+Tny`D4v?@L|nJokPy7S_BQ zq%XC;-iRqFQyTW}D`&56c0U2PhV1?YU67Z&@tfgziZUH#uQV#GHp%X1Ozd zc>?Tw>uLVooOK;jC-vT(vWS24MX$H|_D(TgxV#tW@k^?9$Y{8Q*m7YZ{2+1dyh(7P zBm{=EM0!#@xYJXn^c6q*^oYyDupM|C(Lx9c1vxP+R@*Q`eK4p?nf?~Ih}uA47-tO4 z(Rbl?c8#?SX@E-z0*cO6nd>>K1$z40pRJ zk1MscL!LnqK|^8j_Dxk~v@qTC8TJ0vF1yo)y9@a-d)vd$K?^!k_ttA5UK5J_*ZqNz z>^khHeH8z0-7sozNip9N-<`$?dhbJ~RRgOp=m+IAt+lH&tEx^|m&%&LiAj7?JvK-G z#7i@(m3j-L{U;~Gr;`hnd$+=Wg9~>v^r<_^z0UDHO&dv{zo^=~{5cn6_QW&~2f@y$ zcRBXaA;7WLHs)7(i;?}F()!Zzk}n}y@AKyOWzT9CWqQ=#$B)I(j4~B8apEpQmW+_0 z>70J0#kFXhn0sk8iZ$Ey(B)l;KngIG$ajH+=X(2H1oEvPmJ9ONRjpW(f$B=a^nS?n z9$}4GSY^2KAGr&p_1EeaVQf?Q2X71ld~`6Ks_C8n)arM zUCu5q-}QH(&I~H1de@G8Tpx%CaQ&O-3H9i$WqtkB4a0O8kVOV-6{T$~e>YW?m-%Fu z_%{vS6MT8v=-e9+_Nb0?wc zUZ@-bA(^y3sA~*ss``)?g*Ug!#2RyWW?j&x@M5T8BDq;cGH^WQz2C(*ur zCE^KpLe3-2;Ic5Vq3@d_KFE2dJQB)_cET?KaT8B+K`l#Sg}6s0yss{V;L^S){9%-BN42#`ehrM6@&10LM5%Z@=)l^gNsmXuMvB!1s6a3TI z;=t(LzcJ1E{g0MQ zt@RXJka^5HxIlY7{`ENVKb0#^*Zoc~)sW`67Y#lQIj1=M9f5O^j|nh?gZ{NWjL3l8 z<0&V*HjK255IjJWGto)?Sv#`YO?RKad2(M)Nl+nKZZ_XA(%vETt?)iPUlDA&jl);K ziU5S-2SM5ogbOa3KdaAE`w5qU+5G$rNZHDj3mguN4!<+v$=qj+epmK(pxN;7`JA#6 za%K$#DPCD>9MqfB6vRB->7LsT^)zFb*f{6sUnXZMd4YX+?5<913cEoyS>|lO*U11T zYZjz4l$L++7T-LXORERF5AQzuQ1U_TvI5RF?tr%zFUuZ5(ik`UJO4;)A$X zf_Y*w%$+Itz_9T6avi4R2hnm0HJ1Y?At`#ID0xd5k>B_~sy2v$l-DGq8Sr?4QG}UK zTa^+@z~cZGV9;@JLzAJqAb|k_tXMM`^H1}7dryfEj4{wWb*!B#^gytl;hU4u7-e&WGSJ|6KM#y|mUkN` zLrxe|XoSj8)(_x4NE@Al`k0%AsQiRBG6b(C1IlYJgE)L5h;dW*BvY1A9^25@sU{HKI3HPlGHrbJbu+S@Q(1u-NogxfXUa9 zmmUp$h*>+x_Tz4QGPJiDwzsj{r?awove-oYcwca=E-*@tjpe-l7rXZx(2%g_vqyH8 zmzTD4!1S0Swz8?qKd8xv^0I+~KoCO$Si;aI(xm&?nftDmXn7;O9J5FLfTR_maSM8Y z$p!5hTv}UO7?Y0qFI&{pGitu6EiL%#_&(Ly1I$peV=|F@=fV@NcZudBbJ%L@ZXOYy?++7Tgq>pJj}Z=pbplpCB}#K!(q zsT|~t?=1t1F39KDq53*K9PE!kFZiyGl;$toYOYb~#T5ggl1rc^Ch4K4OXgjzTZo>T zDhT-mdE*W~I4t&ZqhARP(Dd$ig78*O?8?^AIkTYThc*(#Ub8f~{uDmTrDsSTootwazb@(?g+gX-31j1pIXgj?Q|mQ=gtJ6@VDYOEIyuMh%Wj%!f{1 z5iAa&aX>KL^xK(@C6TuWn&xf#?`ZSMnP3=7(OJSJRP|?rjw#q*+jrmx2pw}=_l}-1 zfpaD47CHNJTx>)lTvCF}XlH!=uBu~uYjl-g`%pfqRJ;}LBZxZt2Kd7 z2=;qA7o@N7Vi93bH(&KZX_b#N4uey=3n7w`k8tMiazjwiq%@ZE+wbv~a(wOg8_J}y z9nNF$BCTwV!(8s<&ovhZHE%{A;38eA%>7KpzS1@PpGp#QIE#RmSCBh#xA{kN9ca zm9^KkqG#r#FN}6k+jfQ?59&^gj{_FRew?HIqsE`%UmfiBp|<`tbN>BE-TU!k@{p^J zPpiS@$6ohg%nq7#>>Verzr<105vtJEc-W*cS=WnFATmAE{m7=o@V=kM;CZV-D7KCX zPtFa2cexyNb8|Tzxkj<25=`K|IB8rhSBMmQzVaQtQIm;UxiQhvJ7{N}N8QQB? zbRYYj%BLnH(UrB&X(5?Ukd!5ato#*;vnZ3rJe%O47^yQx0CSsCBa!EN!qdQ&)`zB`)mzv_Mi47CoUK^bXC)zUV)`jnM#RK>EHFW% zp!lpQnfRCB_DK&t#Xf7QWGxt^@YC;%;LWR_Y{6wh?ccxhNdglt-&gy{{v;RNQ?is# zxT3y*Y_6cjJmC(tvonSbVHBj57_e^*Wmuz$+gfFFB#niex{pk`ATB2!mkwI^>_c@> zC&mM|JgB&9^onX{U&fak+Q<6{=68@4WywMQxx>!=-nAg%=3oaRA!!j`crYjtVJ$0~ zAX?YEj@=~r8%l6~e-)&;fi#|*A94||!Fx{QhM{rsrE zb!EL#HG2!vu^?(2@pOn4nd9(`_OZd|e)T&=X>J9%F3p^N-N$Ei+;JdIa+mt4!p{Rb zsQIpNynt*!&MoRbqsVtlX8wX|WF) zhF>DiqE`$o@!J6L2JS5few;zsz7I)Tj1L1cC}N(pfl{m|6e2=kP=jkN#lu*^%$}f@ zmoFuH(9PDP4Semh4RP@FdPnBA%0L1nxPwyvO5T&|<3|#Jfs2i;J<}O)P6?_V|2vI5 z;8R)o+aCSsxd%*2+XDX#oa2N^R0=jDyO_#y+(FH^aJIiLdfJP1aPcD7 z*fQ_?{~bswIM{yawcB&7$?mhGJ>PCbU#&#<7GA$39hDR$QA+*P2O_(r!nps+eh*e> z+spqE*#gHOP4qi;D);<#33d%X zGZ;0b+b?<$l_Hsz`++S$;v_zwh!B9gQv|^4^ev>+aAz4%U2E&2o5wwpmt*gMYmA2K zi>k5$>DiSTPlIy1E+MtAYJg7 z-4B;#DN#~CBNO4j6WglFrcRU72$_&65)Z6$h^kKXTg((9fd*X&8bX4|m|+@%{t`(x6Lv?5y@Uhj=^}U^NV---nKGoHUYpAtc8D3G z&>}FP2(rVpki3z8#%=n|FiC^$jf~pvr~#J4tglm2zkgAs!A(~PpG_~{|L2Lz0PXpC zB#L~3CDwlO9ogOG03Vmjd(nv|fRC*0Rqr6BQkI-F2752y?8`NrM8H(MTK(tG1=ei< z8k)Y*@$O&@89u9j)G{@ZN9^m#bBH^9M$l59><_a!{m~O;!Ays~Bkd-=o|1`e9MF?~ z){}fw>B|3Q0aB&0X2+d8$@f2*fn`esEZYJh%(#|>YQGs7%ZpX+6*A^W5uA?~PPi}D4>M1pQ#Id`wD`s zcg_itLG&Q%u^%qCn8OjXm;Ws;OM{1N-%!K>u3{tcU*{8DGKDSC1;0>i%2f^HpDu?w z14E;CGt}A~b1QF+<<{B<7chcaT@>IUWdTA)RJgOm^1iHsFMrPoO3^O7Jn+q@mM%HLpa@rI(>g`=vJFhfp zownqYjiC3~uFnm~!cb73*ONB*+UDcd5-SN1VF_CT-g~2QDoUb9gqUn$b--BUOjZe> ztiIJ?q7m}V-T$(0OD5E)fR|O20l;#V-_auuYF;m@XFU;ptCWI*wU=7l-$l~je$9n* zdueu2y>mt#DdGuGV?;$cdp}Auz?)Xnq@>33hAVK66_5pS=wsXM&ce~K2`-pGPyE4l ziM^ff6kwrlEv5Be)qtdjhzicTTyXZOY)y?Gwy^|(22zN(_i@;rPbX0#TwjhofWHC8 zqlU_m6NxqNXEl-tPWFT(pKK)sn1{FDtv?7N6_^==5Ovuw1|gWV6lKtN(Tvl2Fb_D0 zBG=bW1G<7JDWL3=ct+?MT=Jh7!^Pn-+%3A4?m?RxyGkdtmO+Xa3ogiud2Nuw0CNJ5R6m3*#y;I++(8G55gc4~MS& z9`c0+S)x<6$Z&&~SvWUipUT9TG}BkDlWw%<@wTQY6qF@_aA(a9sI$i8~0J~ z@rnVG{E9h<*I?*+v$ienL)&rYX>W3dpWm;iq|6UZyUbbGFsSw}7>>(?sg~U#A=m^6 zbwqV#(Wz$irkF)6hJlthvu2GFMB6tJ+@&HONhnQ5%!SQD{r7*F5$wCvCqp@2)p{zY zejexQ>c46`ti>=nen{vI;^?fI7K4f?7#siQUwb<5e5h)9%|?phUSA_;0Xy?J^|`F& z1f#+4_3qZCcM&$3UL%OvnDq~Pb&i!=1+%nx>RKt!Y@PpgF`^U17XHsBY&5@8%sT&c z#Ol^e(A*P|6B}?D#fsbyhkK^CqE4T;<-TT+W7TPn9rtTEGa15!POIge&cGp|C?p445Na$X{`g+;8xVgBwy0wI_Ssq`V`<-nQ9MN_n1$QZf z`zdusTx)jcM(fVE{_?L8a*+Gl@Qy5X&xG$i*7;v2zJhP0>|Ud&f#vIVW9-T>w1~|v zuTcT_&&v*WRYBASRwTrIGL?4FOx)~?^J9oq!mrK2((zxKhrsFAba-8mPELcH2D%CT ztn;AZ5ch3ZP7qI2%9Ko(91pGntQQV?N^E%`N@|p5`|bv<1%5eNX`6h;Fc9S5;3kx6 zEi+i#$c@9>pn0l;H6!vr2HMqbMd{cbvDhVV7|CM}MZ)zWxQxC;f{{}~SCkMvaa^4I zWOvy^C`(qmrtYyjt=2sFg6-lRf^!l#F-l*O;i0>bIyPR#Ni0)VDjL-MnGh#KyK@+7 zn*=w122Z!SN;!u$0)#j(CkDKt9{dV~u7`KZ&@;AYvP)9uk`nz!wzHKi#Nv4F?jBzk zJj&IM082|BXsYtnvclngqwMTJPNSNo?3)q%JPl%$^`q``auVFL-tkXZq%S`yaD?fQ zV(R*cRx9bl%5Q2aqcvbnDM9BwBU~kak4-Tc;lJfU#Sz91onx*N?eDsbUiXtH51s zzO>-K;{qL5v`jv3r+tq<_X`C>$oQ(5emSahlW1pOIvDiI1&`h?=mc+-;NuC{dWKiV zWmJj>0s;wj6(%1*_Y^$u{d6+=mX* z|EX*YjOV$#IsghUOR1=2=z6!(nBO{9-ZCk4zbAtDl&m{lxZWN?d9j{{e6PpZwnaJF ziB6niW`#-N(#kc#1da*Eq0A`Ngag7A)H3#dB2^&T_n1kbWWpTJyX2m-1;(9&Tv!E) zI#awIEzfk)Ml%pZSmLe}x1;$z6t`a7(u=)64wnxNZe*w#=rG}AcZHTN6U7um%B zL~QXJG91(4IEFoNRn?42ls*KI9QXSE*u4nOHh z$v+*v40yFerTPD^WZi^(OweUn$+>y{TpHtH1WQ8u9#8aO)@5Z`@2)2xe z)RMz`BhmtKi}%NAhv-$kls6*|(YWf-@YjEw2HeTZI{Ev^n(I36qPowKd9?kw&{Sg_ zUS!>rNkH|vR`XkT2~>UyF-iFt)|5lJ{0U9QoSLSY7A5IX9?PXaioyM&Xe6CR8(@Gy z(*XQ`I~`Duk{}5Lhk)bzn{B8UMFxm~=|j!&ih@>FDU&}u!664-WmOvG@RDjpOewBp zu~=|qwbBD!F0j}z6vNZv9B43@7#l1*)R)HMjV8*&*5Wqq>Wk47kK~{}@Z$|}m{NKe z0Jl*DoooI5xj4wn{rwi4cI9p`hla zd*F}h`72D)+#N7cQ~Y!B@+Z_u{Cu?Spb~teVFJYMKFu97MI(A@(OueMw65EE z{hMz63h@B+nCVTI%=z;h%zeN6XydX2^Dq7x>1$6sjH$wns9eVjKCh4h2&cAaNgh0T zIZ+b~(({m!Ga1Ke8Cj(|lzU_EWs8m>>`O%GqpDZAyass5f)f}?@b>JIRP@%D88~OK zoOpH*e^zh&0A%KllfR0RyBjUz>#3`%#V@?(hwDy51fqAq zB>=mLghO72_BGDm%UU^id zp*tk`5?TGMhhG|bEC?6ohVuVu7jZypi<3S4x9W=KikNpBku3^G3Vx`(=pj=zbRm<= zvpZWaQlHvW%zl=v+xpiHFV^C6^F6d%pd|hWZ-#DWyu9J6%XMH*EMjyE5{a~+RbxJe z?=9`I_m)L>c_LwQ1WqF%2RHRUyn@QdRBU!1Kp5Oe6d@FkH3Y6zg4e~&R*gG~*ludBylZT9PtTV+)Eu|-Lksf&{_PTp$VEz>)(jISUnlnpj+iSp zdxGJg`$OC+69tGQJ#l!EqxEH?b!7~fu?YoEsMKe80*(J~t##J3lNk-?Bz^R#y^5(` zxSMXy{RHMT-Jb6=E|)3K;eqi?l}OL`spW%n`DHqk(O^)FI#vEn?*20$4vr4fyzeGl zGWjl@eX5w#r*%D#9>WeuCef;CPc};WgR-eoc^tYUF0Tj7Ivdzl#RpI0nyIi`cgR4E zdva?|yH^|X21(IH52cMt2wKI6$3Xe1u#5@<;~$L2UMr+>(pBuFg^|gbrm|*fcLu z$NsN+1R*z~0o*L?*(%6F-=49HeIjPfFWdrH0ad*f()DG=h_g9G`H`?Z9TD+}8fd;q zyNYw5P}41o11$`k74pa-9WTVGR!fvOhMp8G{<3H0WCxCp?>u-5x{T9BMD(g{!n9#` ze{y9QN*rl=!u>*`M#4nWHzG#g0Hc4?0C$8qwx%`YRA6=>EWzuD9F##)e>X)m$`cpTIUcNsSD0q8~$E#d9F;hTfq59z1}G$iE5^i0C14@7|(Cg1W8Eys;s|No{g2bVtrU;qS0=G@(6Wdt~ANQ|* z^+s4QKAvmZIjQT_jEY1##$pQ@`kuRs-6t`+%WpEevowN_V#R^lDQdSWwWntQNXvjQ z$S#UnA#`RUT;$FJD4+T{(W;rMfsJ2ITW!!z=x>9&Au(lFSZ!XSKi%UJC82s{Ht!@WQlnK5smP zU|}`4;mC{cU|Qlkyx*w{ABDuZO$c9Izv!Q2syh4$P}hd4(;@UDY01*kZlU`!Z$Af# zLl;Vkkg+TO^xufbnYd$Saz@EM%$dSD zHR6$+yQ%tya1P~|+O-Lw{0@a`+3bjXAXYW7FQ$S=z23+hDVwK|FNG4_lz9}vy-KkO)DPXD4z*R3NC>;cf}Beoze5x=>glHDbrXn3YW8b+w$-J;<-zS zT9;`)NHN3l&EM%hWs)RHVUYpX8JwWQx(p9l!6S*NF1t4-K* zQYzk`{F-~My)UTo8V+I(3QSi{(yo@3J{EJyi33Lxm1#zW!a!pvE5+27-!$cs??B)s zsF^yy4uIB5Mtm)oPaZ*}cAubr$(AZA>f{@$kT#38u(%{j_qtmwBq6P0cOIY}NN05I zHP>G(l$E%NO7LY%F<{47dqum8?}N5CCyRj_qA4Ue*o^;?uhJrwzoWz+-|IYu`ys*UAMeC?0%^4e;!;UOf&LH@6>(u6OXu? z&6vOIFh!jYKS+seE&{OyPxL<#vs3GSO=D*IW`?}_5w8x*LJzCke}~wgli=3 zaEx}RlmsH8`hfER1QMZ(e3dS_WV8G8-7mz4ogc7c$7?QT;I(gJWKWp}HjHNeRd9jO z2A++!e0Wf%CQvJDE(#~G+5YashnSa2JBuoSl{0FQKU6C23(Bm6laB&@;zPT+kAWF; z*Vk9zaQP9%Lfadx=JHP5W#f%3j17z?zA~K#h9+ITe7${jR_E{f{}+dkqQd$JZDI+(cc|Y9Gi&J+->wSaJ61YJxBLeDMheT$ zLZ279<4u#|ZM$yvN?!r*-|-LmX4cj%e7YfTQn(DbHdi?DF`j zUv_@Hww7L0Vgn^d$e(Mm;`#QapT3J>$cjq)v40-cj;hLfXNGbbi(Ir~PR~`!<2z=* zKGRzWNz&uZiH2_*y@sVX|E->)2@>1AXgyX2R}5Y*)orgzkTt?q9Nz)A+R2=J;#gK` zk2S=+AZmJ`8x7$i#STDXZP@nle0a1m@Pb{}wbnw9xiZnlBLx#;r~80P+6KZ!Ie^yI zaQoo%tkCV1N|0%EKb~AmhnQj!$ei(gTAtU<2vjQIm+?lZ7J3UE#JeahPpv(+w>Ih& z%=v15e6sLDhMkQTg|CGc2hd9u(xpE581;WL=)8E9tnR_$%7qLy?d^6!Zfsm#gaj1G%YkQ_tj|3&CNf`dds+q|=~f3-K~ z6653QPCc7u+DtYzIF}diGG|rjQf!0%K;=k@WwC>BzE>pJa<0$+{3)#O{KuT1WMYn%bpHph66CKY zd=+h{9y}G_^sdo;s7Cr~=Ud+zX@*OBgU`^61M1$=z1`n?TjAEr$)=3Sv!`J*HQx*# zuXJ-mg!Z^&#{(Xm9{GWf2;b9l$B2q(BqDX}^WBy=1Foe!(K>*YwAmUK?(6j}t4_U4 z*$RX{=Yc#F$60C=3!uOGsk!`2HKr;ZDWOi8@E;2~i581QM}~68JPDf-Lu-&-(tj5% z8rx6`MfD+vL0_tu4Du*?bZl&Ib8yeGY3v~xaoP0Hw6GzBuDB_^pM=OAr}>L$eL%(a zwvUH;*48SUdUpQHekEPpw6y?mqKoYgL7p9Qeqn(o%Ka+w`Y!m(*~=TwqC_%9uK6JJ z6h4+q=KV>Nh>^-05<+N4E^qceV=aP{mO?^%tM(z0YR7>Y+ zXrk3&tY&Ruu9&?v`hZ{RGnDV#f0Sp6wFVE0vksD|#50`AhD)p%el&Xqn4WJr>% z&5%DB$>wjaZ@M_`A{>yPf_TL2LCjzD_XRxB;9FIj%2lr0XHI;)Ev%1pFu3BWVboVR zr;=wHQ*+w3XUpS}1H46(6lP*;h z4|r!~MdXPNP1x=*;uiSdXK;97DlTgq$KCVa z_i0vzi^rlzsefl`g*2}|Qw=GWb2pvJUR)TiZN=WL9S$i!nKM@>NB`wN^>e%8Y;lcy z|G%g_NN0K^sIg|?3g#W$-kN#%N#Vih)(3J*+!E*j)Fs3R1*5c^z5b1CjW{=-CGj}% zfai`Db)9kgR5VUBVqa* z_w-3eZ3w*l5=Ae@f(}mfF4FO-sg=79ggbQz2Nf2&Dqh2K7{n+>iHCT-7unnmP>-Z) zZ2U5Vt`G9Soana$XNTR*5*AOzcoj+NVN47hxHH%{Zrqq#OE=wYWh~`UX}sX`WJ0LC zDJ_@-i%*9lc{&vJW7slV|3rJ0fQRgmj9#BP_+&v74m7G9)!X?9Iu(~`noHG!q)u-w z)bKY*okAA=8#g12#6Hr(UO`CB{m##*I?IUkkt97a6-R!Av7D5rT}j*;*9=a>I)@Oa zCZzd<#V&J^sNRxvF9VGl-$!t|qLJs(2&zt^3W-@a;s>tiz|Igq!1ySw%45boa9oc= z>(A(6bjUKSjh902JpzTHgj1@0f9@*#uoT7No5!?dKAwH5R}nj}@q6~kSD(U-{)=^A zp5))k$vjaj?#3wT)a8WQe%23r)M5EAZR}gsom%<0y*0`X{C8Y9ayq|>E%S*h!>gx% z7w+|G&dTR2;CX_J#W`B@1L*v0y~p0$ruTJUz+#dk5_(kvm)kXk{I@XVftBfEY}b#4 zZY(H|nUgNYo2B#x3e6S$uFLcp^}X1({Bi9tusOyRD`z!a8~kspo~KpC3w?NZp(}63|Awx1vq<D62!KXk{?6LICGYlcst46ETX&u|;dDDF7BL?Y(59kP|z)U zG*FY9c=in$UR8IdVM>`yrWBE-P;C>}w7psjL>lFL%h8$vO9d`vMXtiZ*Dyqyqhr)RLnhRuDwg&gpir-u=DNXOh1 zzFp;Q84bRCr%3#Xxd%Ywz7)`dTObS4%C|FFCi?9z+~_;Rr}ycqSzH`hI`gOKsiddZ ze}~2(u7hPr^E($|2PD8UqlF!HVXNt?UT`l0Lwa=)Fc?$6c#)SP7D-2CdbQk%;gwIv z=V>4fF86^sZ#2vVuo^x}UPnUv!^9_t6Cfw*b^Nu0z90ZL3Y@dEwmCBK7kui%{;sq} zi-K3g$lh?%4%^EL5jh&Yvx{;J@e1tsJFhk4)s$7`jYE*3(?fUgK&u|5(xdh`6q9Eq z>+F28GxN!P&1YG6pG-qPqqnwlUviJix`qV=ynX*plG>@h6m8;p4Pzu+(jWy(iXa8l zb0Tp}l(Ezi3Rffw0l4QBiI}JS{5m%W^~{dD`*-DW!)hn}>ys0`XwwR(K^qLe`M&=B z`%#acNcM!naXr-pGh6=1I4_#i1VWcC7#VXN&-Lzo9j%>9590XytysAaE5iccuW{Y$ zAwD%lCkqizp8kUH>93yRU2Se%u_1aQ4gcb$O zM+a1crid|19bnG2Xx^V5ec8OPMv|*!>W}aJEf@>```5%xHn;0`jn$2%@Q_4~BQjMx zv+L`V>czka(VFvyDRdPI-1xmdSKhQ3&Ede!@pr0zi7OBO5t#WfJZd(E->mI#fZAH9 zF=S%pqs_vLBMSl((3|iV2O(bb8^@8jQ1S*`R$fk$;V_KzOA@i}E(&Dt3>(HguT?H+ z?Y$L^eIFhY16vmNV~wKwxQMjf7j&;G=72?iwYxpcVR(=`Jmd>(>uGrhx^glWb)oF^nK{9z~`)3G^ zUQ|+59e$2qbHNWYALj3WV=!J$h&NKInda&yhVPsS>NofOxIe2vRUgZ(6RiH&@T>1d zqhw#nBYMljt;rX3abwzm>aX7oy3XMu(!c>zux(#A1ruyj;1;)8n6i!}n&Oh`n;A0?0;u3!-culXG_okc^uTeV{H z1J}{~Bro-UNHTHR0qoWb&2PuKBV%B->IEzXmHels6)GDjuHTAw5JpEq&GkH@pt9A& zRAScE-fL=VeD}?xwxEw!LV;TXui|z7`dNDp2zLNhTjC(6CLupLQFzH_VlPahv=mt0 zp}r(azd<)6yILl$MWr1D25?Y`FG@4Z=u6P-J@?FC=kEi#FO3a1OY^k?v`eWXZ)D%B zRGuz`CwEp{PWvtWoL5^n=8IZefVxPfA<8|r;xoNd{SwlpShifIT8Vj3_l||K-jkEW z2WiE!pw*P1gZ+v9xGPm66cA51PZh3{w386F)G$+LRZGR+;|( z4%<^XFcetu%;149;Y8~ApYzW?sh>{OS*BY>;v#yQJ*uVfj}u4l*!&XIwhykU(PxN{ zX=Z4Azt~k-!+bZ6xXfkDUL3hVl#aSHzm;$MSo(tSQPAL7^R^=MOMPYb??-cr zNe28AgVx4@ghl1}KX@D&G)t=80kY*PS8pd7bu9M@;Bi)to+~Z4ZMgG$XzrV;4k)O6 z!q=fn{9OjG!Zma>c`EQHO?3&s-18gJ>4?N}G6A1vmMHa214s%NZavRaTwmO2pLu8! zd#sMa`t0j!!k@hORc+}ZJI+)r3ZTP>U$}`{YpxrdM?}G#`cm`{su`Qjs#jfpr=+4J z&?+k(W+uvH2+;n`I>Egy6&dHKd3;;vj}h>ZX89STUcFklo#`KHN7ak*3x2-~3@jp< zeu$)o5*a&d4<#di*9XzV-FaNsFrjKStg1gYW9COBf6d){9~#d75x&*4x4{#>z2iR? z7QFWJQgoO<1z`{SvA@;~0L!%Oe?GEFysv>r_HTB!18?tiWlPcbnNjDjVA zc$vPdplnGp+5SD)v?05<-9t_)XmuD!_c|ce%TgjV&n|b_EE`@wjr~9xwzgc#T!EBw38J*9%a=D-&%lfBVY z=~d<fA|ysZa3VM&6x^Rl{JXk6+1;&v&BBBZ=Oi++Lm;acU}a-|@}XE14CdWP zC=#V3t|{b(=ays8U2X%qXI__>F4-P9nN?)H4S{%>RUt;v4GIqqSI>;i{s8TZ5z~F# z5RJRGKBG_zAn^1CRvI<+`ouOio(>Ma`o)H~-*xR55Y-&Dvm5&!-f*uo$U<5FoFQ)d z>;A(q5^2gT%J*(A;9&2qgzwtDV7Y($>aKZ8zurGHUs|vQ!gJ$3q#pb3>kiqvJ*$!g zz>5Hg7cVCNt$Ja_^CtxWvD#sIw3Ni$nrrQiG| zDwxB_2KVK@#lo_aZX>SM`BWp8V=0k#M)?r^rb|4&L9MBar5@lpB#OoR+6K;1OoMD` zl|UVr)LSQ0{I%a$+-4f2ns9Y+NT>4|m)GlthRcC&_@uAoITa z^VFN+fDaUIBx1E7-3Z=`7oXk*0{OP_mYsk!&Dhmk!qw7cQ}9)D@FX`NK8 zMWvioxw3O~pNS{>_P~+WvAvP8#=y1JkNy3kd)v+_UI^X~p!?NOVOencP8%5s(On{; z3PW8u${~rM59uT5FqRCppc*Ru8arawisn zn7%vAo=`c2k%;I_KXs?yN`Qn$JwoRPoF|3|o)x|9+F%-c_MzPQs$4K0&AWJlD6M#>+EQn5z_)Su;xS4nL}Ru7xKmm>M{j@qt%Om5 z9m+NMyE}_%LpiF@j<)yVWPK*))q5-~PS4QQdvN3mX&+1@kC9D5Ldly0=sOw5@#ArE zKAB#0E<}W*Ts$#m@oji4ue~llrfFlFs~ETmg<%s$!U-}JKZ`l0kWw# z*leBwHE4Wt#b|Gg%FfoBc-~`^3Vu=ik(h0NnQJ zR40q)d&@j~NtwM9DqXB!jcjJdwE}Tjm=23O--q6p6|dhfdZ8v8+aT3Y?P9y#tqh*z zQDz^vR>;Qh$?mndoxa8YYT`_x{CZvqibMqO2RM@b#90t2^^a3VHRX$3kDaxxu-_H~ zc#Rg;XJ;|`F}Sqnf?6{T@nS;65Kpin$3=X&b%uPi)UqeN0~HU5kVGSs6X*lX04UQd z3Zpb|oqnQJF6}frw?i(4%ivo!|Aa95F6GJ-c|0VUYL+r351}I;D>|i5e|?-!<;CBo z=TXt*s<7d^N~2qGEFU+@ctc5%-uc9O8%=KfA$*4dP^<|Az9|CPdSxS4zukL!j93hc z$e&zx@pR#e3ODt08{a26ZP-8ujlYxqM@|OLmg8f{Ia^Z$-xJF3m6dPR>_^{p(+Ffq zP9Co>o1k4N#pD^xA%3bP>|pcdgKY+{L~x?1rvK}L7&>o|2uNqtgM68-vW1~Or;&gq z?5l|?sfEnU1bj^UNGQRwSv5z|`EI3cBG{^giAdZm9k3a6D~OGA>c|+Fh*UT(CEd##3 z!)W1#tL}$VJA%N~R_b(MO6c0O=KFB=;!Om5J(OyE%Zq@`UFw34yaUnSAVGlJQW}=rZo|F$Bi9!(J$Q)&g>|@_3zRL9g};7hy%FQcU3q_XRcVRudbgE)kB_*O`+&1i<>vf! z)_KM}&ExkWtpIi3=d!kqdjWeayIs>lk}#dUr0FS1H5GV19NoS(H$1lhMmI)?hjEO< z(<4P5k%t9yJ`g%*+qbsDgt&}mOH)&h4iGS`IuDeyzRNV9^`R6}+Gj6pq;9OCxJ)D# z`B|`)Yj#Kp8O=qYCBmJ+m6%9u>dL_d2|MQ~_EbnG)84Fqts8H5h((A&)woerauR!e zW!EeHglLP3(ThrX13{7@^n>_;9~5TXx^{Lh8Ge4-1x@H-B;Q)95s0@XiIiCdr&6Q5 zbT8q){Uz0BizDqRxZ4y*d~C&aeKRJtm;SA;aCq@+=8%if;k4qwYx!yv94Xhev!GRj zp=wK_~pR#wd}r} zX2Nq4IOUV=W3;%NRc}xq4XDW;c0VGJ-E|nw0lKp|ET@>po;-)Cm0*ra-fWjIdtz&+ z&(?`xW-)=Kxic3vzVlLKnatk}sJcwkL-?0uG%#+E{%0}t))y5KK}{h0_=Au*1dM=a zy{HCx##gpf)Na7vpMzNpYktz&*xn8gWKw;T%sXxFtznc?eEcF~Xq}rF$oH8myBi14oaB)*%{rd>ey?z_>3K z=Sr#_b{G17-c_U>tWNN60RV3AuUF>tz;r1RiQq&yfc_e!jUu=?{)uGOxP`CJ_CR?< zsiLFd*Xc5J>#^@LaR&P(pr7(w$^j^eQ{ZP0pF%Q;;Xa|~RrW#Mu21w<{stJ1hr}G~ z6XZZ7A7fh88s_{eal7FDr++Q3Y^ip7nq(tD!UQ@!(}Tq+Vw|)}>bjxo+I^$^ZPe*2 zLusxF{|OmMt&Du z=wb%AMNd163UR zY<%_Sys&miXs8YU2G$6gsF~BxE4lhs<{az$oqb||Mol_V6O0N^1MvHs;1KUpIazSU zlL?Xrju4}Q_RNuXVNQ^QqrYE@b_rRV>QD67T%Q~wA2w}# zV&$*$_+{}RGyPIU1Sc~v(>c!6eNc5N6f&5T?vaQwIOlF;!f#c~U@^uYvdcQ+_;>$+ z_gKGNw=2*K5V<}wDafr&qh5p%xDTm$}R+)597rRzt! zAh9MLPywydJbQKYBa(4V)k-wq%lh5`FgRJw8X8Q@S9LKj5YI<^_&83~g7yobBOu~6 z!r5PEX4dwa&~sp=69G;!Ji!0W$mfy`4-va6q>cKd5ws}#&Rg54}1DWHy{G*@^aF4W5@5Wi``=Am<@C8~*9w%QI@!1B{!5%-oWZj6)ctJ12oLOo+B45UUP<6P1K27EUgeS4F5bhGk$p!k2Zr1mc02t-d^!;bF^Zl{g|ss{Xu6Ckn-VxGdXykp5O|EB zkFB9&N_i#II_wQQbszJZTkEZPN^gX7a`R)6Y`aAA{iO?3CTb`k`f|LdDW?F z_UK8zjcMK-FI8mLgEJBx;)5NL5hj3`thu$g01{pfQT6L>7`rNQDkoG_XQ>Z@%T-|w z;q%x2Auq45OLlV|Yog-(0=?cyvs8{kucZ0NFustj!MKgY5pF-TY*nF>RI7HPd6v+e z_}h^_kvM(NnQLr+e@d@!-yLTxnpT;c`yo|jx^MK{M5H`Z#V*CA()J;$t73faf7sC- zrQ=F^G9@@T0`RG2__C$*qhyr3NBB30*)Avr#)1-i{p3yqD?6w(1Fd z(iF(z(mw_4h*Oc5kof{~r$gp1r95`(yLrzVi&mq&8c4S{ebz5mjMDnD=2}`Rk4ECL zk{v?(v_3$kmc@NPq*Q9@CUhr6X|K zhTNm3mr4_}87n4X7;^N~fonkdA{BwVUMUs5T^Emf;w)kj$?$s$Ekie3WI%F*A zKEX-yZ?-v@u#9eR4mMe`92@(rG7_TeJZL@$P6HPipE(;~HkxV_+{7h+lYb7iqAud? z=MUmLKKuUfmit_`OjP5$HVhv41f5%@mh~f}X-Ou86&z^ z+?*P|S5#q@BB-qp&(|Cv9A)h^YDIaesMeEbd3DfFP=E?Ya)BoC-Fj6WI3wW_!rp|6 zi)@er_PedH2>2LT>4j0STE>tBSb_Tm2J&iuwjvQy1WwbX_|klsTX!g`8Q0JOOTb;C zR@~32Wtic$WHY?xKJ452vY~dsp%b75>%uP6reJjg96!u~j2VZ8^|3j>CbmQcKL!#& zFlTpoDcsoQN%qs`VEp6WsAI9%v#ZC*FP~YJr)NtGzEZAL7K?OA=R)@$)OYdZ_yDFm zI2C6g0{!PPGOn;l?(r*=-&Y?Ycq^E^6bS^y1fi84EMe$jH^O9jtAj*wGBvQ$%C7P4 zrlX~qce45+-#L`ld+${3K1%hPS)K1I{}{F`Kgt6-p6W147@j`Y^T1MS;BgZPdd@X z9NGyhclI3;MNZtaZCV)(T$&;^L(lZ~^IB75dCP9N$+Tsgk9=hg7fd|xmdvxhr?m5# ztGV6felrIGC4l~G=p>g6N4{UOEIy!n{l*b)Z70sQ|9ET$Yw(8xB*5{;mNcs&F|LAN{W$95eU<$Xa}$mO%%%~_zyV& z@Phx4l<4=8sRrqiO1diE^BRP&2?3YeuOyYp5(_y6H`*h(pm1VChRN z?X_|tmU_vk1hanDb)3?N!#8IOnl^sMy&qA8( zj?vnM*{S{omzm#AJ8Q~g*B<^fGvY%X0kd$3fFeB|x;eMMZM+1hpLMSm z*boh55&L3Rve(vsx;ANUKsa%0&!wGjPR~A-6fug5Jnofe_(PoNipuT{*T&v~iwitQ z5og;J&JX;pC_(Xwaq0pE9WjPC5+R1fo-WLhlnM+A2-(>@e*9IsiA`6(3fh9K})96#|6*8EfppBWqK+c;wo!Td6EBS zfXQk@<$%KiI%1SCeQ|TP{*qufDv|f^xD=_NW=-R(uVTW(>L?$P#=W0$ve6DnatC1% zo`a?Re!;f<`}6LjHXAy!Tx==(oz2XT?U_$qLgo257qvy)7i`zUtPE&Fq1+k)Wcwiw zw>-_T5H0ut434_%(HCQ`pI6I$bTfw9yB_d&HBPo?V9wgWc|LrzU~kP+1wik?zv=7j z>|8%0V`PMfSQXY|qh$jp3BSU3Hs=!kMbWw%f3rLKj-=kv){|5v@h4kUt~S@&WPK+N z3@Nl9mU+LoauKZ%iS17Q!q^QkH8?V%i+YSZo7X4&%qM~Or}ezwh0MnwjV}53ZP5*M zn{OqPoJ;fDS+31)ls}5^!XzT*v)1Rjr#w|ojazE|;qMy{Ntvb#m3Eh;z<9}1dEDAk zK98ZJVn`Igx47VONc+lf*v@tbJUIff_5QhO6ao*fGUUfNNroJ=vTs&baFSL`;t-Q@ zT^Y3^$}taPxX4y+`y7X!A40=;)2ZfQw=W0x9TF3A#?f_#ad>;mUlz!CgKuIW`D>vh zy#%h>ne#nEe3CJthXjHK)n=7|bLi zTaaWLYZtZ)$SCnOVlT^<;6u>`1uiHpfY@;okHek1r8N2VCIff}ZEYI=GH!&I7I&(h zQDKb&a+zmy^&4dJc%!1)bMIiUvXZbN(R`QrYXx32cJD)cy}U@Fe^>pRPJ*q+W_H)J zblb+dovpDQr8du|VA^z=X;C}}uRX;vy|nEzmk~XPd>w)N$Rc;8=(R)YQjU`pSssWC?9d^zysrUW5i49JDeZE{7axz9v6D{Cm$tv8rK3xv~^rQ>|W}d&N_yV z&HhT)A_IyNQ0P744kUMJAHf=05S9+hWac$y6BAjL8>+~v|V z7ZT|NUF<9V0tk%^ zMF`RSmL-$?u7jNDAbbGUlB`(&Dh`#hO{bzKW_NdcZ^`CS#3VUx5>ikt71H@$6prh7 z85yvK`Jb8@9LUp-dHea%r4EjIb%Le^D^5V5(vtcn@C{O4|B7mDj#s%{|;!4LV3B4H#XhQG3TQ$TMJa4C#6 zw*DB0@646N4}3uFlOV&euGVtecv^>C<}*FC&$pus!2b!8KZ%=L+LY0t z>4osEdwV>H@u^LHCqcyck00-)4iQUyMo}38s!?!T5?5JuLUW(9mdc;eeb5(cwIj-3 zc+VTL5D_>e`DNmdf^;N=zCUvP*QCO=(RyQzz+^8a<30r=SPMgv{M#RQ_1f~sjdi=d zNuW4N9p9S;AUbgUh@M#KpHm+B41y8S(b1=_8$BP}^}Lxf*|g2t3;R!0187vh8K|<- zeJnE}x|PLwQUVEU&j4(otnK$ZL|!@=lD_lR_vGN91K1uY)x2yUA)2Jb4KT7TyMKGC z9oa!hydDxmh{uTYrFETXRGF?byYc+UbmTFm_&#;n9hGi__=y-y9PeEvXDT)mwUpV>JTs%XiOsI654Fc9*;56k6{t$Ut&bayAdp9BlAWYD@VulUHryoA!;riXI+TJE*GG|2 zoRD|~!b9mK(jkRJ{R~H%oY3ij_VJGQZ&G}msvZEH2@>#q>;C&f+hg3leGKH*qaZ8_pz|zSU=NQMEx65GDQI^yX66 z2Iw$K!sTK@pD0;}Tb!>?ft2<~NxIU&QL9>7EVAz3lt9(7%zHgGktDDmW5nm0~e0f^mr6d0=Y&OE6Nb=WuDaTug4jV_M6O1!T&2m%%83I&6Yg}C+W$#YT7jb2z4tJz1|i?+7cX8^lx48m&8|WV(eLN#?w{xar~i*}V1^;nb9fGzIz%Cgz@TL_h510zQO!3 zHCSpGJc|6lRlIsk{1>IQ=R6cE;Y~jgSoo|LOp5tb^2=T@1a1V{dNNCKvlL4YtsR<*Xd?ZCzSowF|_#pFdP~!vG#?~4zgzoHz4Ud5#>zn`U=-lI( zZvQ_%QuoN6k(d%jj=5#Hosz>G%A6=v6sT#018w@JKBC&P?6rD&GFSJoLHFW1B@N%65U{x{L zU12?bcA0q0755sEdWZ8H7KihB%OWB?7O@Nhrb6~T)??l_Qpi9ixs)flnin=4%~G#}K>p`)YI zqjYc(yG2?CW`=$@|4nuvbL7y^ctlmeTiLFA5V`+}^A2OJa9izp5Lbdiib>8&LqED^B1KeON zulnC%2A`mzu{m!+DB^46SfI_2BWdz*8$6{N1jD3@D~eKs>Y6LHUs>vI#%taGsV7te zx^P_5aS<_@vY|%&d_Q0Jl9%nyk!ScvC|0Lf%%L!TW6;!#5YOewB zXh68SFyQ-&n^X+nbvx_!XJO$^?&S*C+Fo=>QJSf11_FzR=>om805~Iyh=|5lm1R-Y z)y@<3VThu{gT1}ITYuIBsV_g#_2I2BxE{UkD*sWmA|SCcv<}8v4lkyIH;J7Xvcy`h z^&APt_N#s(R!j-qKR7hh;aWZ6rAD2vmmSLIs{uP#&UbXzOrRe@QWBcvLd`6>m34=|7B*u^9w^48ATU(-O#Jc9XrO^}4A&1-Ep`l|NM?ktBq_n#0t7r!si!EH4Cox-{`d0h_ z_LGy7C!y@2g>Sj*N_iE-CGF^uQ#D^Pae%6CH>*069YmEq!b>sF2@tS)1!Q2iE6|u| zpMrl3krJQO_2Jiu=!BDQy&9tIAGBKRhWbYCSi2krgp=KXYJ6IUrkaI`_lwWIRP_R_ z^nutLWJwgim?>PSvs5079nmuDQ3+lFZO~D50th6dmD-TRL<`VXMiS`%In8xOTV-J6v zEX0Y>f5O2%SbcvuIn>poS?6q{Vt`yVwp^tLf(J&f>^JwTS3aa7traj3FN~m--G_lA zUzidZg`U3=4*~DK4_R=*p%E~n4XwDt6FEax{~YZgi}k*IPHBqR56LiEF||o+0V|TK zM)|ex7h^3A5JHl{nZQ(cob&~JvCQPJYKwoQaJgM-CGml+y1F?=t|HX*r`wA5Q`F!3 zFKZ+ceMF%37{c|^7MehvB!bG8D=DEbC7Uc7|Dv_YGK z7iqH3YiX00AN<3wkpZB6185XrUy+0yLs)=~hsg57*k;l0s)b#Lo9Q%NGJ^b*9}ck7 zTkxWTY6xxXW=$0Uab`^>A_|xJ{shW^^C_S@koeJ`km8>*dPBhx<@4!wWD1VmzyML` zv;@bwxO41u^_kfSA_!{!QHn&=7XQoIy*laco^#QT}s{6cD$xk zci~to<0NAD?VL9c0Q0>1+L?;@M#WKq;0G8)^v%06D0s@Z(=U*MHl@{-0*=3kbr2Gs^X5`d`FV)b0E8|o4B=`vjE8Q3rvrffk)|CE3h7rP|3_bTWj%{( zd<;7twHd2_C!f3h8B++OD}$!PFr#yf`ME{_lSR~gMZEBI1+1g$U@;E1=%Ix>b#^D( z5o|KVD8(0$&_PyXG9xt?OoMjTh`6coB=}g+JAfGu=jt z*c2kIpU}%w1Eh$rGoJ-p{qH*xkwk9ONJKb8($;!Ofki-)kTqNRjG3n6Z1aD5N4VWgK?y%!tXGt(wSjP69rFtJ=v(v*0TkOq-LfALBg^=)Chg%!^k@LIzt6JF?=s;gt-w+!c z7w7kOG34Wyfb@pGcArQJ)J4`5IWe)Lf+f@lb)td-tD84LRrryQLQ%b~JwB(*k^^QH zEf`-8k2_wcaaM*&6{5naVo2$XAVCBQXAJqonJcP75-5Jd@Ak(C@~Ep^KcFUChob$< zWABi>veV^m7iO#Ls#UiUY$mDmUH;*bwe?tso}L+s%1>OJixk#M2qnn`r{1bp70N_B z4uhcLewWWwRb=nqS9?mxB?jR0VMKhwenznn2s|lvM2T6Kd6gks_jKWp;+#1oZSVrH z2g)>!4FwlDi>G`AeIemX;fnO-&Cs?FmeFp#H;x1OX>}uqu8j>(dqx*@JQH{_rzdQ) zw$mWX*32n8xVfw(e_lf8903x0#D#7Q+Q}CUfyDZ&7Z(8?p*GjG`aa9Mve0xr9Sm*6 z4e@6!_KFpFrv`UCYV_en0nM)$JDeXYs=HDCP4AfrQir!@)o)Cwc`kw_HJcIYn5iN& zTIqgmz3;>xBIbn~Bn}bQZS27^;oD9jL?j-pkFdT)8Nxf^MCEGQ($=1+cGwO3e-3}o zq??VI4w86DaD1`X>(|}+l$wb=bM?9tLM8*d$VT*O=O|d$k9EckX(|cVebiz|hr{uy z6IoI|cS~C+W8k&il9vly&zCTLdn$HI{^`eRBxRavFmcP$Q9nasSJV}fa1OX z`$xgQ=I|G_oD)SZV`18&()OtVTnSQ|)QHF%4*v+bVISXXKDY+Q+jzpAnlmg04d5eQ zsyL8t>h$SNjYjS@OORm^y~sj!VE8POQp^6kXnjdK&#qqK9}m*NNLVfrbVJJ*N0BK^ z@ET2Rc~y%~v&I7CSS*NVvtP;0p-HbSjaf`^b*YYp62Kvij6V^ls4y@c&(981q?Ub_ zu0W$87Cg>d)f_m9nis1~!`HgT5KTM^Z1-fO>^P$?JBmF?0#;w47zLyMmNtVOf=mYl z4TRV}Ldv?IL0%~n+?viG&Fj0v{kF6mVFyR+nGYsqS+=Pk;ZI4I7P^T$^RJoaIX$3k z;K*AOD{V>j-he$rD3b>EV*A?L+watFy7ycbsdQ0>`g65spao-P>ek*_%;(rI8<$={ zzG-gYajC~Tli;`+g{Ws-h6p>vlkjBf3zvTq_y^%I_#>dB{|j{I1I>v-Zfm~t6}7SL z=ugi}KyH>|Y;NQ)^c@jC$u; zghTucXm)VB9Z znW2wSMSwO*EAGZmH1c; z9NF6tD5FW00PA5n>vokJcOf<2{QJ8>nvR&BDg$_8iU7tLs+PaEplJk0-zo0_Q(SHa zGP)!$eA7KiQ0}DXAdG9`uS;gon%CUribGJ^`ijhP!!8>8s&WsinA-=skGf{W^ha)X z%!lEy71xFhukk_Je}0GK>F-7Fxh=g~31NoYUk}$YWfUsmZFVB}D-UOYlXm=mwH0z_iRKOQy*7Zjn-(Hz^LGN<%~! z@|)RkN+~eCYHd#uiLY4N>WpG{(o|XfN4RrbCNBB7B(c6KK0j>Zr(xuL#anvjJFnum zvB(N^0A99q_w{9Dt>&_p+7h!+KYt;IU#q{0*`LSG z)&9kg##s!H@)aP!dErH*uSh$qY4Cax-UYZc#Zu<+#Xs|5R9Li0bleoin-`-C!%H1? zW8u$B-l|ArvN+jrawhh=3hF2%n<5r2MMoNO8f92fWr$=92gLirB}*y}74F}av{@j9 zM2V63u;6Q(j=$Sr(*MEH?wi@!Mzxe?hg%XPLX^{-SoF~7X{NqG6v%ucKFjjTC%u$q zXyLCzbPT6xJL4Q&N`{^NSB^gNGAWGP-G!Hckx7wjXll4waor-*aDRNc##q-z)KCT3a z7f#SN67(=gQhI{Ufl{$Up5a=eHd1xdCn$+tO7-Aaz{X|}2lnRZwB7TROCeM?-E7$h zwlVG>DE(wBX3i8hVteX>zS`51Z5hXdBO`SZ^mE;4Bc`%OrOH&Hi+TO=jWRvHS;ZqB zX{CRB=VO|6a?I)f_3TtNJDf+Ibl_k!|M3;6AD8QQ0-@N7e26|-P$RF5Q8c;&h<#1| zg1U;CoTxVw&X^n)+Btnr5G|LwVQ(Q@P4nNEbV82dPfFy2jlcgjLL5)_U(E5a<~LL$ zo+xAc>mYWXBDk~Ti$Rp-tBmrQR@tT6SPgGnk31-oFZcOE|8L24_}$a3Wwn-_4Ulu{ z1THWZb5PM4V#e<%-iKIAUVfpGq2Ye4_mO+=0dJ>?HG#jIQ$$h;VEmEz>@xRPkrHa! z`Rx^?2UeEx{jbY17#OXt{-4xbDY;jJlXFRVjy(w(=LQvet`)HsJ8SJzj%i6NvIB?eJm=YRO_oK4u^Uyii$?Zpalpnwo~+M`^^vC%z?u_{(L6&+}QSyr~E zP4go3uv$Tu{3@U;eGW2PQ7Gca*zKD5CbF})KJufV?i9KZUnXxNE7|tnop4PN0=GJK zq;Y&@6GFFkyvmUj=~PU>r_IP!u9cPb7>;34NC{gW=HRNo=F@@`3U>AtWsPvQdao-M zf0-KF2)H};oPLP;oO+|zwxC2Sg)&$^`$X4xR->PL6Q=310g$smhDvJy&C zu3+Ube6A^IFVE_(Gj^Djk+qfy7fr~XCRpjvG%yO$LxFjb6J^TyBqV5e?)E)MPcZ?dAgC-` zSF0KGG4o1CEmDGTjw6pUG^iqJboKO6>{A@pm;*j>lc^Xzy<%==RsrHIg?nGY^|%Ro zJ2NzJQHQ(T>wVwa_fVa6@Pccux227OHN_t$!g;I)0kD=ctaPe*bv^e4GZOe1dWkNJvy;B4o3-xAr|3^gM1A|X*-C)wn+edYVYALJSs)SKn@UZt z9`UHNCEK_|9T{-Rd-v|eYk@QueYDu?iFgUglmX`jyKU^H`4^%wJ_wB1$Hk3+w3+Jr z6RQ8TZU?DPXD&44@@Cn7rJkl`8ZX3@&DAUP5$D}|S&gr-kQfIuJPyA5HXcEBFN8pk zOKe5F$fM4VO&59wGO&e|N66jR?eO50_^RiT8|Ak?O(k~fCowau<6geLD>)RVElmcl z-W|tyt;%xW)5o}x&b?2x!q?}gUp#d$&vO2i)4_lEBk)iwuYY*>dUovI%uw?2)sY4Z z0yG)62dd7ov42ahzi-+9hq~R>cXH*@i*L5f90tygCYW{SL|hna<9+oGXn=A8Jyg`W z`T%#^!?AnKy!dyGwq_~Epv5X9u#s-qUk=hzNbebWH4gq4V}E15s8-a@`ZiDF=~wF# z4^k{9J>KzzPj@#YAnt(8( zta4O4LPeTgVcLOoBhjpS5MSGCKiIvK+Ye;EA1zcc z>~=Q&v?k>j5rb#~oUx8Stk6#>>YV~txi!AZe+$0SZ} za-vAd_l2EZD4mFb4vO5E`#6?z8?wxI1n5DRiv6Bj5`w}`eBz3IZt zLK{V_7D|_19arsSb%k0W^pF5d_rwu53_27zE;mS76a7e*NVQeiDU|M&alG>VCRX-S z9K!rRpq$R1B|y#`O#L)~@c~~gb(BYk;^+F-G?-5s z*Xe)nJJ$Np_UFO)f30t^p`iiMCU`4s738$Rs>(+zr@!)66W~`ZBjJOrG7J`6YyJ9iL+ zRn4;a{%0*|Ua9YyQM%_AeH<%O;34cEC6=0u>l@u!iUqmhh)K|g*Vd`4qejs>PhxJs z^*CGMmfXDTMdahBF{X$kv>>SU_ILpEU8#hDXEE}~i>t2P!O}%pQV-D&;%u({4>%A$ zrkc(g3DueJ3N}$Rn)|ALC9fqY^UWagM;yBK6VfdQG`zhvn}b$=`D&l138Ct`6ZS5N zk&`=g-3Mvnu!5T2H8>zhnA>{Cpa(*LO(k3h8r%l;`l2eg{yb0#9zV)f-`woJP`s## zm4PXZijg>tdS<%!=E5CKdtH^W#>L<6zpu#7Li+|DqB~M2n#0RU-04?9Yh`oXrz;pw(Uup+95Zovcyw1`&SWWDiImO_8h;X!#NEj|9(+K(T4G9!Pt*EM*k0g2m>=)>4UR%CpBZ_mQA zmkInYQ;HuA&oT8%wg&_MN}EMR*V2(@SEeWyjGEy8=G76^8%6hj!d)lrG zccq}EF!12ql8zybPNA{oci2*7LGKzV1P5{kLIlNL%|?VG!wlCK0GDVY*S) zxDHzrxDpixL#Yg%<7Kbd@KB9MYc5i1lYO`|(5mKxdmdz8evInH>3LW8=i9D$r=wPl}YytCewGB{sjTZy9f%{s^>pmErB z{k)i4GQ`0`PDzRnTvxGr^tNZURv_?__f%n{&M}=G$T*k5LJc?ccCovRWQMq@H@6jM zQkK~IxJBgJxZ0$R%@IWBR}LPcmBtG1F^pxTM&&GvwHzlg{{0@y&eqK>UWlmG@9SBz zAF(wrotH2eg-}>yhY4Jd&zHA{8)bvbJzKHy{e#s_hGK#?CXI;V05)87UU66Gdxr`d zQ(4f|SL3c5;%j40MddIldHUQ8rC8Z=@SBmv-Z(0VhZn!-%G#L^yQXxKa^2?Nd2|nX zi+(y>{a58{fyJSr;ae^DvZVT1tW}v*#1pz1>S!R{!TeGi2e0OwPqQ6z5gdt8{k~W{ zpMVLCQcZb_z>K|{2)*mUWkUT%-7%>>C%a^As#NCyv{7-adHD~wvsFJlBi?BlE8=jr z0o2kJdADC-+Ghw=T9K^HrJ3)X3iq=srsdezwBaatvD|rx&hc<6zYJU6r_K#B4c_KW zfx!+ga{93LqU@L?KJiB|ehns)jZoOjS{%xGa$xO;8!l$#yb&h+f*BVrv=a&fs?YWAi?xH|(uQ?fEBMGXHC~kG(sEqmAN+?U6IA9bX_FF-(f_5UXz% zWyz;U_q#sbdiR=(P=oMoxrohtnvz@03G<;^yUX;0j!Nsczvgj;Xdbjdsw^sKjP6c; zF5koPxTT?`9hx@Oc0ViOZ@)tM%T&xr7mlEk>RVhcJ4cn5pTD~_SklioR&yq1|3@6B z9(joPlr6l6HU9lUwjyt$-a+rs+^Z zubiD%fBd@8&+m^Al*+{ge=X1VV|HcWeWBb9(Fav_kg^2mZI!$Z$Oay6v>d*W1NUw1 z?0<>HAT2nae(S)APAe(VQ^ z^0HSL4yKmw!sV)VuUmqKX{Cl2TPPRc&wJyiv`_|#);2cjJ%%%Q`(Z$r1IKEaH9HH< z6uD!GVhQcfJ6AUr)jX|_7!(;mUo{_c^5XbR<^&jCLzq6?nm0AAo7;=itk+l=*-dZWx?z!;ds-^qN z+>E9D&i2*k8z06zD=UY$c;3rd$F_@zg%Bju^8l^~Wc$5QjfoR=Wo5Ow<|PGm#*RM@ zOG1DT>X;v(>B3}b^eC@lnbXfCKQk?T=k@AsaN6JY z>2Gw0%QwcC?CpnwlMV-0A|nF>1MB>u#{eY#iFP!K+@OLKcjG4jpYr?H@?0wwUq|t* zKO=+U{k#c4rIlup`(2kCvL-ymDfP1i`)|2m&u*49uRMJlG5|==40UI)r$NWOUObq+ zcOXT4c~lT>gq1Ovg8E1Cn*Z`)oZ)-p3088CKEiqI6U8YB;8&GPouTp#F2WyhWUqRa zyq|@O0W16gO^XbeX=5PMlQq_GQ{mHm zm=uKTR*dNg)8hoivvRgDtLbnZe#3tg80wkGBr>1)pO?8Tn(bW_wf?pJZ%p^=6@54+ zZpJsbk%Bhu2Jo!n z@v5b5znUH)8=B9=K2Ut3XlYdJZu(n-q=-_%PvUfRDx7GNKH@pf0xurn(APkBbld9poG@y8 zAb`ShLQYGhrh2z-#kP-ook6cgVd9MIry-*Z4-pad7v<$0cLKm5cw^CKbHpY*U@y-khRw9HfEe>V)TqVG(bEO^@!hd@QUmpnFLTF6q$lx z2Nj#6XkXeRvSCt58W)PhE6~)L(HOE(_W8Kc%l8V`M||tzP$4U|Lm7^;How7VWA22O zP|VlhevJ+eVrCd?mYC~iANd&lX$r_&C}8-bhJaE(*Lo9kFlY- K!E20T^#1|xuC7J^ literal 0 HcmV?d00001 diff --git a/docs/assets/images/multires2.png b/docs/assets/images/multires2.png new file mode 100644 index 0000000000000000000000000000000000000000..31f3c8531867f529cf15886b1b9f1f725c151bb1 GIT binary patch literal 559179 zcmXt+5o-BI<)h&G`FaQP6GRW z0|0ygy$4z*AycZYdasd_k#oT-Djla=x&FhL(7%-h<*lPs6rcs_A0MgpK6=D+PlX|+ zxe7k#D+Gnu4>AWSw$=2gB$+%E(xLdM|DR@YymoM4;1E316t2_}+O(bGd=mcVeZ%3* z*ek`$ZI#Y#m80mh!i#tU;i>lIGkHs?>b z9&YxXH7RT+1dvvvo9To?eVFs{by1=ej8Q~1$;Rk6SS)UUVRV@c<2htvxC)&T1 zxwAJT@DayjSe73&LFv<1gJ&%l${Q;R!?NBTC>b^GFE6L=vfC`PJ@b<_{3x4YM7=^} znzLN1ysc-mLf1gA>C2z-94SUoZ8i|tZJ=hOPou>mMgD1*lk80BLi@n3*-p_1$(ax z#itK~f++y})cht{$O2Nwwje6G1}M=Dl;C3ofCbNVFNdPTkM@?gFXxz2Qf)heh>00~ zaL1SgotJzV*n54u#HhW?^Uw;T)`;B*wZs$~Zv9fS^T@x-*^o_aqxYSX?6tHf>C(>I z9pvG;I_Ikmi{1??Yqu&*A-(LF*VuBe{`R3~vWdO%XMb(9tUzAm{wQs-)46luS&>Gb z?7(BwF}Dvp+QJqrl1a9dg{lU9uN^^KT#j?O&p595=8y zEf9zMPdS~KB}KP}q6@niAofL|*d6Thdkx0(_dMg>kbtI;{SE)p#QblnOgj z)KP0^U7lfC@oq$x?0^&bZSTL6p^9_+&gdy7Rd0vDd+<`ShY}ZKF#-P&)tM%VdI{w|LW3`1u;d6^8@2s&kBz9`GAP_BuH ziEvW>bSjV9sM%b{xj}(*@K(gVci)vt=1+(F%Eed6pRd)2Zk?S>4a}b%*b2By*|w|m zq@*2NLBwl5)z(jbO3mtT>^#ji+|np`{8H1Ci#of?=3+l-csO9~n!hv$Gq%&CSari?7*PKUnclH8own zb_2P(aAc=!ctN;a@9aGP*Lpb_y=PdU5!%$!Fljxhtj_Z*jxYQ8JbvE7A<>wAcqD(C zuE(cYKPyS%F`@g9eH~OWy5schr1w#2Il>6@aeVw46oK_>oOPGyoRkd@^{MyY6|f+- zYQvfv5A#4%o0v>wO>M(P`}~FdjK|Y~weaoEBoGH9J_p1A|*YrR198Q@;?9P?U_H_9C0up@%CmSc3jF~EC8YwTH=8e*fxFV zvIQ<-)+~^w6WO$po`4E?d^xF%Pfkn7oN8gw{UDv}x^Jd&zBkx7-yRv^$7gyi0r0YM zF6?x-*tuUIv(`#jFok9DyDxVVfEi(tp3%GLk_LOq?ukL7`(b_qAUq@C+X1@+njF@i zBI#$HdN*tNg^#KjvO}M))Yn9MZwB!Q!k-b+QRwu!Hqoyr+1h&2k9*`0g$-zVNQOBh z{6{?HIB*b_?$0{Rr8zP$LB|!HCmYdZVzebottdkxcKgTt(Lri7QK92}u`1I2t@DJJ z)#)NrM`y>liJRW1+h1dJ?3gKwaN5A<*HEv`2A(BBTq?l);{X8I9qeFg%I*MmFz(;= z5gmM{{#GCfEMRIhQ2S1p&LK~wvev9g%05q-lKH2{z3}#1)D}R}(VqZW4hAVVEzpGE zaQ|*U-7^&Zl#9G|{4HdZJt?B&d!brrhD5eVd>__K0T?GBtu{ie{H>uF1Wvhc&fXjy zhA4Ln3~ZmA8_4|JD^r4*@RD?@3%X1517T`M5qHaqPZMvU4g7$a+~Q#HEv{)j#Y|W# zDX}}kjm#45o*)KcSI<%=rg}pu3Uq!{6}7w2m0ozUpWb;sDKh9N#uXgsc`zG1Kiyp2 zt%Q$JQ}{6uQb|ZCE+44By7`P-+KP;B=NC`hmlahXKb5zuK6*zX;Y$FPmdn06Qg&4ME zrT1yhwcZZON!oTOR?{$}H7-^K`+SSS^nrI-&CC>nhpjOR%J^s6&!7EinF~;Ulj-rx zz1`rE&keJKFi-TuT7AP5gR=BvzZ#Pgj(>e<27sevNXLlcVcVC${7*a(XtIpma0AdD z&1mrm#9wdZ&GEU5vedE0g1X>vZ+Wmtv|%LwE-Q~}L{oD|^VAwm_W>94g!V`vyD$!s zEE5$F($?C#LE{Aq!8#SMgnuB>JSX`vQ+I68zubMV;a1;LH%Tej6yoKstSD0pzD|QQ zJ1W>vLerI%^P!iJZ^NIbidhOzK5NL6&PrjUHZu7HbK@S{IDp=S_|Iwrbt@7V=w;;wXR>h5TIOJOEe4?fiWn9JNT`43+0_o^vTi+|aw(u! z2vF29^Y1G8HPm$di<=SGgX<2Uo)mFxPq$a_P@sFL*ef4y>3U7o5%a0oUexO~Ay@hF zlCKFh>AQ-OPfGZP68q(jPv#VIWc7j22wY=j#op+-v~632fl{#QghganSdpZOX|I~J z^nhsP>2qlm+2fGC7h{&x)YIg%evlxrljG7m^v<^M@qc&}Q6)xybxeDN$z7mITsq;J zE->c5Zt&ccRrq#$Blx9RMMn*;xgm7UPD1emZ`A&x-&=Zq5ES@Y(5l1)Ota?qiWy;R zYyEvi=S_P^jRaNam@vg4EAs85+W!$`3x%_u$XZ2^vopY^d_zL{Z zY?E*Cib7NQFsyI=+Uy)6$?GpFe4kVtzv<(C z=~`9ihV2ClCcS=9`w8q1;fLuNi1pMnkF(pe+@!*j+a=(@_(v6zFZn(_r?561ocwc4 z?Axet&rC}&;ztpIx{wk7wl9P!^@!?ILg)EkXN}XPxprL`yEY$vJ8o>)(tB=Z&Sp$p zdSHKLY;dE(({veck^yp;=%%*!z;sdHL{mrrD62Ig#c2ONxBJXpV6od`L}Pc&hj-Kp zQk>(o)C~hZE0&r~BF$h(Mga5I>$6s{Zg3#i_XnVRZbm)6T!KSg73nI$9dnWY>M^wj zjf+-uX~G1tHeX8-GUBL|eJoTe@4{CTSn@6|@~ zC9@8BRbA`N&)%yS8ot_y*dL7#?mT){G4YP+bS5z7Ny!~e4vN~TBO5-P41NVE!!@FQ zwqwcq7I$zZ+htZVe9;LKFxcmNtT!<@Vf{ZP5iO_B8lJeCsfO;mM3%JHwf~#jw6x^B z17y)&XsO(IW!B0)9y=P6$M&KjK}FvO3Y0;#R=T7AyJ48-_*RJZ@4!0!G8X_!>~GHZ zFO2>-xxNl#=}YfNGmyw5+YzTkZ%$7LCF;tJ0knY*XWJ1}CDi=xSRF70rMo2F4&5BI zxhJA=c|1pEV@YpfwS;8I@cpuQ4;Dn{V#j&Uh?nmhTY|RdW zdDO$jv%FTqQRZ?5p|+{vyt zi>IZ9XBpw;8tm^D#SWJas$!SI8fR_T8RJFzbSElp1J&N#dRr4z^KdR?BM5v?+!I%0 z$TP$J@3h^k@!M1Cg|HMeV+d;tB|kNd1uLQYbYpxMI?j?_Q+xx05 zNnJw^dsTd+~kZ$ zPVE1C6!PTO%l{M}*UgrVloF34vJ6V=(g}+K{V29!w!yd_!kQc>;|g)~@6M`X`Pd7e z@Y${1-8Uw;@Iej^b+;OcVY3G_Mc*QV20fTAb)<)O$R_V%bUdz)wj1fRY=?;Iso*OSkRMLu@4qND9TuT zP?lPF=WH^>EtzNEP};hsx&{}yeK8wWcQJ)kP~J3*lJ~!qf97%0}+)9pQ%**!|Jg zq7{aQC$spKiQrDDkEMVbs^YiLz|;-{OWN!8j#))cRp;*W7YoUj3g*iBDuq!Ok-I%_yv_Ym~)_P{@n52u!nN^+3Mu8f?q`mG6PDpb5lx|1zBbL+hfL{#?X?qJb!lyZJ@nAq+y&xGMU1mgs4oz&-l7*?U{Px z)VK0(4n<~Du}62rkf^;TZmO8xmrsPO3L%T3AFk;`WDudxPhEl!7mG z5^Zea+|(4g=l)1=W)0Y3Skz7e_c!QWl1|uVZoKipg!i1!HMTs#3c3%jwR|X-n4m_s ziH+im_tS2@Zw`lw%c3h1nKU8_*#j4UzR(ftONY1Q1zR4}inqVB%TSDUcmaWU+WYve zA8E6e;1(eIG5;mf;q{-)lRy3%DQI6kbcQV%M(y_Ehs!~K!skz$#(+Ivmj5#L&>^un z`NX1&H9AtPF@oh9GQ*+t-a4AF<9bXy>3JJdIaXwA(O>OYaB}?8Y zAHRVA6sFq8=4>yA4Cg|(HxX*WC{71D8nKG_)D9UtdHHdtI;~bXIqr+^Q)G=i2MFvA zaL|XaF+vbdu303MulAkq;13?^h31*D^qd}&+DNg-N^`%MqoN9Ja)G5fOp1#0tT zHD`Bs!eOLmrZyO2BmCC5e0CjZ`&T{sIdgd*j&EP>`+%%;?Js{y>?@Kk*j;)D>_8k< z42Tr*o5r&8v5Zj-C&)CUwHc?;+mPdGzsdLt%zSwXz7rQ?^xvb;D8X0+1e`2ZW^cin zs+$8@JVs2W6ZlIUm-cL`+V$xt4#)yk<$wRI{s`>B;WCAmp{6Os%KfmBphBkjI7kYF z$~|M@J4e2d-ogvCtik8BL^^Fc!5j!4!bcqgqS1tMmLxC4%HTim#Kq8S?5mA1k0Zi} z_=CHoRYh&FWWZBcx}%nuuiAuLoXp&GxG#BS==6}+c%ZSNVLtLuE$)r6a=vt$+-;Ut z>c0`n8c{FUD^MZoT!9L~PI}#9Pcwhv&*=9#;{f%>U?Q}*Ux|t`#_{gQd-UJd-`|>0 z$$wCkKDwGbQKc~#nFtBp7@F=O^m}wzSx<}Jxoa(czx_R~+uc)S>traisgbpjW1`aL z=x9RSrIEvUfRFKV#aROf1jLOGFjMkBBz$B&%1CeGd5X@+FcrH-A|F4KKa%f?j%q2Ho#O0c6O-a^b_v#NA%^5`j45QV`3W1i4}Io%~=#u1hd zUG%yZ)JRjw>_I|$y6RAQ+iRUQNI8o*3`ya;_(bx*GQ%*P4b7E%u7WB_T_ba!N^BUwoTkECstd8v6w^{gQy1zS*G)g1lg z-cWwA+vsO_QPNDHT1mYT-go9v_VCk0r0Fv>-EAYuKY7YFIi(%A*PcWgGU!>?2?+Kr~U=e)SHPjvq`c5=|^p_NN*L1B7sUZ42Em1`Eu?eJ)3P zXbmBy2Vvi@?NO!5md&{cd@+VOAj=3R>lIZB;|gH5jM@qBcHhIT*;I{-dq_EpBbC*7 zbd59W3G9^&9t?NK-b2};b|>FZRo`jPG}JhbP~@_0jXM9ioP;%Cczx|r#xHPj(f5yO zB&j?NWmSt!tRtL${6=3ooAlwtxWYSZ5Znyrn)E$F#@f>IaoTdfYazW9R;pr;k-;(! zf*;`60=k1-US|ez9j>@5i1HVYQcGw7RkZU83Vh-NRji>pw+E5$eiixnM+U0rrt}d- z6Q_oREx`W_lO%M;74w{2e|j}yYmCj3gt|~J*hg@fb!dStyWX|K*cb+N+wW@gy(mc6 zQq$a85T3~Y;h~}x-1>9TPng(sAcQ}?R{}2Vnw6=8ynbZkl6)-=*j3k`VKnY0ujD}3 z4T%gK`XE8??yMxhhXPRo92fyb)OTS@#W_#9e#?$X&@2KcZdDRN0CAUSIZYIB(E?(> z8ayS5e=B!#%7KJ8N~G*)V7P~B=?@xjc5?_uJ#r$`<+37 zOmTm;N*v-l8(5GLMDv_8y$j$CXVURhahCQq|E7D!uVM;>*B`_7VX)bM%F zH6^|dig>fq>!OITbpIMyCE>5Vb`lmW&&$KZWBlOigZDFFEA0DjNS&#s{tp=6!QMpP5IsxDI zAZ1k?nDc&7m>Q-TZe%eCcD8%&Ux0iCl1SM|*(h6+g$pCriNwfaq4ROtd0G5dUn+oD z$zB^cwNGoI^LQmUKAskuTb|Z4x{8~yjV2E@judttonS4sz)m{NIg%hs3Gh!@yvvCn zljWm9kXxB9Uh#`uN32h2%5j)<-4QG|XH9W0XI7+R5I_qW$;MuWSk6(+{z ztE_ar0+hMDyfAGcyGu(i9%-EAM{nDnS9Ah=jS2e|6k3a7-#Bs>ic*WVj9S=WmSYGw?vnC^fPC6Ql5quhsnW4QWRturk96ZkrSfDId!o#E4eZ z{kY9Iv%A1@*Y98@nMvd1XsLG)YvznZE|WCQ;l-2i`QJa@Ph(5vWvz$l?C?#PfPyk# zH6avFhw{wt->X5br?jWZX6bzU6^gNYp|z??O0$!5^j4#;_yW>{0}eZ(3OCt&m}ji0 zxcCriL}{#?kJ=xvL_%-^Dl)rSl-nzN!7+$OTeGd($GEs+g2pK!ntU`$K9;DXk#7vE zns52N-hy??e+Ja%#bg>k(=RVi%lxAah!Nz%TNtqnxM+XYsjg|hO25tn4tqmtbB5Bf z`Q&!5RLFXZMB;i1r%9$H!=y*UN)o(rnmx7eylZEs*&il05|}+G_i3z15emfI13PGD z*+s~!irt1cd_?`1ND%{K^pQ7xbL|dSRrxRJ?HOO|#inPMV@c`hL}=YB5ab5Hj$$j) z|MG131*tWB&Ce*cyUWEiQu|Q&#&XZ%Zwt#$FmWXMHrNu&-AB~_ z6WRqX&gj=J8T=L4yF8d}T4G>$YFe^Fc6=)gFF3*3HCr?lO#GE=XlO(XDKf^IpVG!H z+BrLumgnZCy*nm10*VldoT(c|_070`vHJk+ogxW#hdRftYc`Vfw>}wXmArw!eG2Uf z(*&Cu^P@y>$4EdQHl_F|v2oc;G*#Qt*=MGOW+|nZXJ)3+OV~Y7?W0Pvn#dm(&Kp%s ze2p`*@CR4K-%F&U)Qn-Yzz$VmsI&og$z6a9W4tTqBqv5*oH1gAxw5BDTx0E!2qpM( zp&$;w4!HC|-G63YJc66)mliu!NRSz3OSTBy#G3f-;6{#Q zsNm35>4zA4DPDnC@bO5D9Nry^fLneZ@OvY)8Pq6hg5|M9mDlcYla`wOjX=*dL(?R) z`+a2590zL=H?nZb`Ovz8m1cPpU<$x$LN6_}Gg<(7kH_%jyz45_A6?YC++UsCx*2vl z8w|l~fgIr}AOnIvthx4QuD-CTDZ)X7s22@cWqOJGba9-o!W+5&X8SaK_bN7OmZ&$q zo}C&T>`=m25=Kzb5j=c1w+~A1PY5d3fxixDA&0kJK=TF6TNdd>|NOr zxG~k^y>+p~rlIyb`YMYj^bm_N-`PT)C~`n>Bc8&7yu2H#6S*RK1*9BV$;VcygecmP z^#5l8meUyGji6xWSOyq(pAz>CcIOm3EYtz%srE_7u%Htx?esGv#|Z8Ue|H@4MuOEi z3wmqQY-hKxvGZ`2sb$sz_~5nHIEWgM_4=-R0;D?z*lof22tr9c#o>V6K81<#qsBQL zJd*9vlrd(oM@k$w;(Pd6@PgmP#lY#tZY2~(8W`V^Ta}^%#_-AYhWQY3md^`PC^}JY zsF|3GudC|3z#q(P4khR34>6cabzFtDJ-c6-w6D`RaJ{T4-?u&gBa$suKtQ;{j|+00 zm7vss>oh%^`T1e(MyZ@B8|ss@?S9Mab)*rs5npay%aEg^e*DV#@}q21)8^QCt(`yp z1kAU@qVJEIJ8IIi#W75Vq%f%#Zy8CmaIb$?LdJp``5K z%cYU%y|ZKTvTQ$jX{k3qx5^rB=`Lf>l`ShF`XSbrp}Mx^9jQ6%ov~Awv9_dzJH=CB z)Dy(!*4A*^a)|OEgC0aMgBd3AyNUT`BB4HHcaIOgaw^Rf6x5JZ^aO!~U#u@=$|Hc! zDUR(Gxl-oBNZjzuXb}@2KLl^#J~EY?=a2dV_Cy~CcUl18{i5ZUoAYP)x_(%?-k=fr zrd>fOy-G2X&2pZIZJviSL3?)R>Sk4K>HC)Rswyid+>A{7%QFT(?Kbg_t(T|43*Z3M z>mJ40FF>6b2>+Dm3J~`2O_pn#n5lJp7`tFVKt!!YY0qemZwIb!leTMfx{-6JNp!Dj zYc}#^-?d=n^z_u-a$_X8&>lUV%@7&gP%wlAo+CWMEixDL|QmvGd}5`!MVdJneBAgB0Y$!s+6BjRA748N%@QH}Lr&{~ z_2GOK4$QU0S2q=|+RndQM3L4z74Fne4N+^dr|TEyIUv|uAFJy}M}JUHMz{8X%ZI!( zmpvM1Jv~I?s0%{xUakR?P5b&G?Sbge+KA1A+?hqfaeyL+3znLMmMyL)?FhkD!!H6Z z$1WBE9IyX}Vv4Wx?g(vbj0TM@T>%jysfBar>r(bx*_~~Ny(HTLo~B@DA^ z*xc$o@3-aI-mVG=6Y0Ae!vz&TjaLQ+{;EY!y5Zu}jcm-e=b|oCFV-|7&sImPqxZI2 zz3;#!(@oq}3d``K6U*(HnOC7|Uuq#*H(kWA;NH8(R86y+cJ5}%*e|yjwd#0oqJtY6 zspd~tx*|UxH2Y^0!>p3pRHZRc^nWM_Ng~DlAZ!TXAU8FyaWvg|Jo#@0e@wQ-I+4t+ zwMyz`8p;PGhA8+RXX~Zep%aUKN48j+`MEojPCIvVJCF9SB-(Gc#sLYOorLW3q)o@P zf;W;Z6h|EkS<%5Q8sohK`JMIEZ}ZhBNnIuV@> zc{?I@_s1&OD(>9zU3GvIuN_TRoTn2A%d&cP`fkZUr#v1W?yb#Dx{)${lc@|O^O4q@ z<$`SoZE6RW*FDYJFa2%)T%!bav!kJPy;hdDt)>!+L^0QC9o*$^JK?5}y0#-oDxDWm zT=Wdry2cSNKr~nO3jMPd^X;u0Gg{`Bb_P-l*kE_1+T0x&OXTj*Yj%qF$KZ4dq)Y31 z;_f@vY=?Ybk{v|L0=0}_i^n#S|Jl4Y_j~J{Y(SiyZftC9KwopOF&h_s%5p-M-j4d$ zE1eDBYS|iJL6i~x9-j8gR=hYsX5DefFe8oRpZ-a=Jv#}GzT!1lLmTSqHkGdihBMqq zDvQql0l2q-6x@<8y%nJ))?d4y>&^2dc49mXX}auclPXXwMEL*&OA_}AY9@whJrpyn zb%W&D>8otcO|2u!W?5nfYP(rcAnj`Lkz^cRT!YbCBjR{(C;C$3VuV;s5PBPaqdkij}03D3Hz@vzF0C}&}@IVP**Pwu!df4${^nPpf4(%nx+9|15 z-&KchxK2QCuZNh zUDfob|2C&}b#;+O!bvFqsE`1CFqvxpFj9Nx1(}32Z4blQx=y+&w11(EahmyW#y$h# z=}dU>IRKtfM%!m9#(qoZid!h3aKK-)0NlqkguZ#IFVk&DQSZyG0Hk#PFzJ?^DQ9ey zC{k=+VHB)bh5~lgX8>5g2rz;LQIMh><9`*A>QuErb_OUX?9+BAw&^+Mz-q!bk4-l| zczael>E|sQ*+K^tr!TRGNy85XzM*SgWs?r$xN~14Ba`Bbk(#QSnx{OXfcFM8eKf@H zc<-LZr(><(9*61|N2i?!ar3PK$FMBn{)mfX>5h<{9WDMk)j?^iru{#=Pe*oX&OZpw zz{)@I*mn5rCXIAHF>X}m)>X_i9wAc)7a^=}Ef@DO^$}iegyKZk|0#DLY~aG$S&@VF zJTF)X(Bc=M++;SL63)%J%|i`EW#w0#$&(&IYu&wG-X*h^t;Z*u2g&{{Pi7CfJOn0O z>%)-9G`Z-F*+a{Gn|H{GD(j@;hfN>H66YdMhp?LmWRgNDv1=@eByZLN{6HY~%<9hX zFX2nbY$-SXH7HDQ9yHClD0a+y1dc1nD~x!CYgIoa=)8OWLgOO(G9=uYygWyk@Um%* z+8nTh)W*m-;TLdYL;WGjg_1XzQnLp=oWq?j7czZ9hk})G)F!gI?Nia$>_jP{4~xg% zp+$7;$HOX;o3ex-F+2bo04W?R%8d~+cq@f3s4>n>+!!uQ&F}p6Jt8!V6yy89K1=(~ zeX;93)#WhvAs1DNazCW!d3fis<>j8?C8n-+?_X;pQ)Q*o(CmUGGIm|DIvm5QQuwa|cG{v?x^6t6F6@rmDsp{%=>$JTU^7fjNi8Kj z#a9y*H=+LWIX3MP%SWp&zj@D!HI7D!@$(Uf)4cP?%Vme#=NJr(@e^|&JnNTsqj=V_ zT%o?mU~K?ZuwbP_MRLtg%DXvyf3A5|Oz73tYj8guFhR^T1%&!X5p96dq-DIuk-L8Y|oyb{Ol#GkmRvrrs{pv4*CEIZ599; zH;zbtLu>}$ydq>+9ZV(ej*u&AKcWjt_+Vn1tLWLaau`AGF`?IkS*PZHh_ay&+mQ!Y zz-PAlra}`b)j7#mb|c7=)WSwvR%R+zhwS)H&k!R2SpEDjdDLZqtI(%$)QzerZnR!P zb^y*&lX-BkCg7{6OPyUlGcy;_(rW2F^9*e$l2o-7ta`OP;79(cgA>18^Lg;Kb^<{at1cxn}Lu4gk|ROLV)5r zZ~pw8V`ZI%5bD3aTUIrp4H3<)=HB%p#4bN|SKPa*`H*mT|HnS10bT=Sqde{S z^<9C?{@Of$E0&~#p~n+Qq^a;AGESFG+9qUw;lrr0yN;5+bDd$-MSp74zToE!+&_r{ z<%;H;+Q1UD5jCqrtc*O~r5JndfeSo?MR3G{G+Y&ZFh+_#CPqI_0J^`Sc>mzx6#zFG z+(Di#j*DD;&wH_>5FJVy-l`L+HO5lr6npr-0yB}WXf6B$Eo#`^2Uf!pP$&#r z@6+__9Y`Az^n%!|zQ_U)72Ncy;E6BTo;_WOdiTBP(+Z6Z=;a5t{P`xkkFxku*MIw? z4qaa>&drm}?);jvC@!(GoD>36<%Dq|kFx&pSt%C-%xq2A3NE4<>Z-v;F##cw2#xTyk^^~AN~;k(%ZRBCRUZ?&nb&sfh+v_c%rf^=XN7t&N;xZ4eK|l*2gQi>2ifh>i-iXz}!m?w?a zN1?k9Pe)ghD{O{T6xDf>Pia_UtT!-u)9SWa>qCumdRgQvl=eLR@<`+CFPlbmz@=A} z>9#!4Kux`|{Z>c;F(IAkFwZ>Xl$RB1%vxd$(*sz4{*T!m^AieZ%rM$gX5~ly@M~yl ziX0BitN&I;5Ub%6y_xq^ljSM;mC=B&MKMpu<(7(qZFHRt11tHJ;1ABmE5BE1_7i;F zP6j_tY2hK6XCK7yZ(Cc;akJ`48c{LhKL%C+=xlw50?-{IpFdni@M!+Zs)$VL=fad^ zz}=b4Y)lx6-f_~PY6x9Fu6K)iRaR9VSCT@tu1ukxJiBy98~NZ0aq+16KHeB4W!>@b zGXDWExwenspo zbah<}Lb>>3@x`MqiU~z6f{GSH?7mIaQ+%kw@&GG^$}#Fb@6N!AF-&W$Ab=Xop9mU* z-G!px#Jt9_-uwz=zA*vg@az^9ACSe2abOKv>;BU@=!ql7Gx6TVUulw@5}ixO9I2#T z7e;6mwmz#)ri>B2YdsM>%f~1IDE*B9RT5kqMTn#QyRIfx4iCV=AScdT&JI%HK{>^j zg3xFbV-7+xZ-}jO!woBGf%b)Gk=KqYuE2)fHAC(c)O~`)t?s~_;_Ia*ULCanMho z5H&^8$xj&%$l&wplCq_;kh>Avy%8ON7#z-Yxc6f4{1Yn=FSob1w{2&TziQ50J9+Rb zS6L?;Mz1_+X|I{`kb`v5y!N?5OVWFnu#NLj7T$aw1J}SYhKH zLM7_>t8z`be{kT4k0Rl&8XXr*m~OIE?jx9w0ptO$z6S325$)I$tKY8|a~u8#wB++_ zWIq5?X%*NV+`$zzcjt5|r(^aooH*Ngc&xVlEUUC;K~*}jTueq-;7@2x^3R3+zdR-S z_YVH9_(lI>q87sOIARW8NEo3OJ%I97eL_M*WR8>|&#@_!s*kXsCwX)s* zy9F^I7#wakcKZ2+Z4dX4P9D2Hg^iVubRI4B6G%L7%xxn#&-QnA?COV-E_`;zr@gPo z$CXNmzC3LeoE*RL8y=NYB5?^)-)Cs+ zN{~wqy?8bQdmFSg=5!mU)*c@G^v|?F6+-U;UvmE-f|KnS9Zw47A2 zQL)z5#mxV^C8%ajd?Vz`$+l}puhvsz&U$u=GzF)g|@n|Z$}jT4=b`Dzj>{s zvW!@yNrU~4-Be+b2Y&5Vn_HV5hjZb;=9qM?&UEC)RrR`xGvDUk+Sak!PfMwr(~^5T zRNm5n@J_1rm3QY{z8-KRWII3pi;6q{J_-Z?P_Jg8STYcqcuv*G79!LmGMdRC?-{^Q`y54yn6U=@lm7#%f0nHCTL2mvy8Q!}IA z9B#=!t^LBRoqq`CpKKVMY{RZMxV_$ueKJ{(gmb#r*ntFjUP|1+?Rr+Q4IW%9^4ssX zSGDy~Ik~N&+u02@E|*5fhR*uyl6sYSx3;3MauRa9#@XWbd7MVm<=A0jdBCuG*#2#8 zK9B@`Q{YQlZ5Wj*6!0Iqjm&$oSF9>MJZvBni|Y1l@Es2$QL+m8X7jP?7;z;Ta9n$? z335DcsC=CD8FrF;T&plexIy)8ugxn_fc`-ia%0HsPN*V>FvT^XN1ZnH?ofa%_y7O_ z7eRo@HLPJo37-P`skI=`%c-db&wN@C|Mv5`8~m%>c4&6bJRCLuHkbCd&{VNT9vRlK zRF(7DNk8(=Zk=is#@ALoQvY z6nx_!&ZO>`#UbsZUK!!@Iz4}FbO=d)^52{mwf7rM)Eja~xw!sSK8oAC3aV^W!%qmj zmnBb;nor=40DJ9g_?ggHP|dKU8QG&%sl(qS^GXI#2u?bku8tOWy*CtHJ3Q3_>wQiv z`ZaDb&GUCl0X9~P%%Dr4(*}i6^J#u^ai?m_pl5#8PJnuwZPbwoxw*L#(!j-VmD8S! zh5qzDRXbS2vES)%?)Gdnsp3t-4JM}f2%_m*ZzY=GkrebO=uJ_%qQkMgV1`X{6*RoK z*Xf@1clXa32l+P9!QPj}BT=uEw9y551xj`=i|1VAej=D-(FANpzFd2F*j4QwtNE)D zNcVLP;C#NeHtAl~E)Qnp6VOZZ>wecj19&+3AB=LCsQBN9m>Y_u_IR)W@J-`ZkO~k$ z4Kg#uA*zT%6hJ#hTpdsGZph3=fEeD01+iM#5kV&-lwh%u@yi|zf-Nbc(;P2%!1SYf zM5E4|cq212Exr|UE_AHj-dmAF(YvCwr77%#Nu9-z7&7?Ah_Y*yXE{^!MPqAER9P-! z<33N|&*A(Y!Ne=j$)AI|JFHJzCSMvrZO;X*Ng!5NmX~^o*@w5@XObwn`Xex6x0lV_ zT)H*?7klR%ra(1(sm&Uj1;c5-F8WTPoywzLpfA#SF;*q4Ks^5IB)4kljjxqVhXf5r z?(OP&J{8h?2zeYHX9|~UobC^BLNoI_Ga85}j1*`@@BLxNvph{BjrrwsGClZ~Y!0yh zeiW8&KfpQ|Xm&55y4Gs~UXUG{A#AcU7BpM$33`c2%g@j6KUn^=*K5#OVcKd{)gziU zMIBpZUQt?^EMqU4CR8xOHb z>be-7+?Bfh9`om-%lGLR)Sb5LQ+fu`z0q0==!X))UKI!4tapJiKk@hN@{t)7w0upT z%~a4;&l9d4zC_9i6KA8ZAB_Rc25vneHBwP0=~vz^>RqWAQQ}qXg`K9DE0Ul`Ja6Zg z`rUbvbZH8Fmj8L<9Z0-nALNnrxA&;r6z?J!3o@>iWGK1)4?u-trr>eIUR5`W-rV~? z?lZ*@Ggw1~OV$r)$D7Rtg!D|NsRj1uZeCgK;nwrGNc>ye%GuU&M1u)TWjlE^XK8w2 zDQM_gX~t>SZQ_R0@Y2$H1T4cc}rzLvA>;0XtZ7 zV=HaE74^^67SGnWF29Nen@>w?_YF@1_p_66Dlv^YeVc-58Fl;+rz zF=Hw{{2z|i*At(m3F$Qw%239!wC4t*CQY-JIu3;}5vwQ>T%^O}` z!ln(}`{7y{c2H(*gU>AzVLdj{ic12R@^Zo}(O5A5n7DRA{MA3V%zkrv*fuiiwdLB4 z*d5l74}f9YKz@(_iVqLw4@fFhi#U=SOp17#sZ(d=HBc)*JQi4j&N8ME=mHtp(bj-J z^8bSln7L1zVYBdIBsCK}3>$v_oIDpUt*C$qb+@sx%F8dL*pB1NlVT0FZPo?qfS-3h zDg{u_QD7y@K7J=xBxOq%XdLe=@Omjc+Gf=Lt)eSNmDBK3zw8by2StoozsUozRsu+i#bF5mnNuQh z?EoonEbLh@<_kw-s*~52mBV3`lVy^ulA6Ozk7cAisY{h{6VzE zV@~#MP{#YK^AYFCD!TFQHo+ZM5t|jZv-8vK!G~Lma|N<)(b1_%UzFW3taVdtO$>5fs0{vHd3s`qd+Yn$S!uIw2ow0xXl<(?XVqb z^ao^*N^r}R84sVA^CbL=i%R_u8j=8>_F&yOP)+PEbxjwd{Nc5ssxRPhuP8zGyCTj; z#U1;vZf%dGajC;X9evDu*?ur3nB#fZE|M=+F|qC5WZ0Xpi(A8@39(~A`O8;n$7%ki zlP5YQ)=uvCtM0Gx)1%#DmEap0X>+Yb-y8|R;gXDsAwOJ!_Gy)Pk8w0m&rlr z)Wi7pc6&Ao+c8O@C8w(z5O4Gcvl)=SSWVk@XYVJ+?^nh^t280!va;b5GdHOv#FVH3 zC4YUKYuWt9A^YuoIoEaQe1|kZ7DiMwtHq6LMDO}}AO3(>Ou>8%bWoiKU9=Tr^ne&< zIfP(>x1<)npYOfx<;l6|`!BIE2`yd}!ULxe7Q5EZl~s9eMk1m07W+)8tVu|B1c@6k ztn>)-A%jM1p^X+OfEE>Id`7wB^JBu)H}7N3I8PDBQad?Zy3!l-qP6(ErLxM)>!(~w zPxZv+_V$(F$>vp$Iz!2%(1o5I`Mx1dUa`5Eo2B2{{8^qt z-^TyA4}j2s?gKwi4RZihzk=*mncW=I@p|uq8gyuwAKaLMZW?eF;|_W3zbaaK$?HwA zqhFGHyQ!p0+BUN|9K3zMObhjd_JQk$1*rLVzFcx6Uh)Z8zzHT}y<|31ILBv@<~PCF z`p_)S1yHd7W4et(;(rN09F=FMr@b>(Tf+~1E)AsD1ORkjnbae9a+x$bz*j-ym}5r- zaj5a~@5trZ;l;w?e8;7Mx8lw)r?cp7D<1$K<)>VH=UK0`K$oI}al@<)+fCujf?=l& zqk){p3#SNfUH;n^pM&JM)T94NfUFYu^pw%H4WHZVOl@GF-O zUzM@={`y-S8-^Yi=l$a8eLqjo#Ldm%tVxk;t80CD(`H<5Pi-i~+ z5XDO7ki$|Ao6{UKA&X=_P9ujL=8#izzOU~Ow|@ZFu3gvr^*lUYkhl-1m&zWbD-2zb z5)$G}KL*One0ka9VoOFvm9OUOt@;ChN@u)<$$je@OQerh!|Rom74G9w3AcgMxfgkS z#{EKOD8s9aMJ6ql`m+399kaa2?Tq)QthEP0+6W zz{_oVlp>;H9hgsqrh9r)guZ*E`>?YiuS0H_$bNxH{*=2>3*!mDzCT;hbkNGBvs-o) z5fd}^)BR2s2^QIbW`LMOg=nzO_Giv?c9H&o2vj|0lfD>*GH881R zmMnxM^Vgr9xaVkY-P3!x;y@n1L@BfGPOqw(brDPKTIkx54|hCjKbkssNRRz{pcwmi zWBa>Aftw`2P4y=W+@akp&N-!j4P-j{vboHc0~C<1%O`cR! zRPR(LNSBmJRyBTE@9!pcEzYXMOy&&!)hKBoQnOAr#j33S>rlq$RwpB$8?d((Hq5>H zkHYSTZ=G=ny*{E`z>k8{$Tb($y84(_^&pU}D?42q2bMyx{X5xM)EW18J8Ym}S~~)>#_p_(7#<#P&GwqEg}f;uGu1se zd`~Cjr-#8hw21HT{`OFH#}f!|ZHe&+Upv`0gHoCX6vq#?kn7)odSo7v*RVC-E!QkW`W8eC@5E&)hj4z^=i-~9fhLa`-n|!xly+1P0ls<=cLXs zyTsV<33Lz+KfSQFR}z1AgMTyf5#%v6`p9XupJ)VWL6}f-Zmaf2)}RB(er2*J>TVK& z_<|tI?->6q{+RxG%MlgQ=d{bbAb7?X=Ldw69L9rD*6LkU$s4OA>^f+oIo8qV*#2@J zCzYcmYL4gqpJj^UxY!muzx}Zr^o$qjTgg{wDEUsCyb>n??fZ)INU;_Z@^f7u(Li3k zg6cS^Ng=)pB7uiX8~6+?gxqNT>0NVz|7WlRCA@jvp6_k5in!}HH~FZ8!!khLNq@KB zJ6=__w>@#dYCg1l>zVOGNYOF+Uw*1bdKbc!BA)U(U^)Xn+`YC&>t>I>h3TJ{L?Kn z;|1k7@HHR}LYas?+Vv1k##&epodGE&OUho*y(w3iYOEzzl9>n^>-K`SK~B)!x!$fp!6{O_Nh&e$#D zx%&?IveI$J`VzD3Xk6zAa1au8wCkd>j2<(rqFhs-K%7kA`X&pd<#e;}M^lQ2F0tX^ z4Gt%f95k={SD~l)frGwv$uFmWYn|u(UiGLvO*jyDEtp`r=yMSz8lOBRbV3V_8?(Pl zv~{!lv_7bgTFtci`**wP-%^#*B-Nq#>+uVP+u}|$Z0w-uoyi{cG)RIrq*CEs?{DUg zUbAPab)`E_7j(?kZ`5v18#IE}mqmgl$}_(}CRC407=W;&>sK$_^@$3OS>0ceXWrm~ zd)yW-EAV9r-l(Qjv1%HQ{%WC`3>+$64dj0mrE=|@i02niM$%yX zV4B?^8EF49_qt{{T?GOqQtMvR9WYyG=&$=nY#)sVAN�iP~BBy5sTv?e$A!pJb)h zY~>YxEC^Oc!8F+_IzBq6(Tn}FG(4c@5Zf`&DODUgO(G*}OpoOi;%!&8|Cp2z2x6BE z(68)rtjTsmTv}1?Xz#+8O3AX@^wT(DX^6h-Nl>5d4P_+gC#p9)V!6g2TuXNnNvu`y-Qx6I& zgk2~$GBQQwz7?mdZgfm{Zoj;K_oK?2FZ*ssW{DSa>K**mGWymABd*`y{2}gXdA|of zS?QOdjIq>?{hND&U#4qWP>qLUoJ`8_8~r#`))C#m9P;wKC@+^D6hVsJ9eBr0pGIsl zHCD?XGC8=kCBXVg{B2OLVp0wGmjxK+%GbKwJ!U6lzE@#k``R_S8Fx;sQzKw~w#qWpF$EJV{r3nC_OG_hRxiyxoKw)(1-EJDWmHjWAzI(FHuiSSuXR!RB$4yESFD13Xp_T$gmMX&L8?+Fvcmm;9yW+XA zG5k55$Pva>EYpiiyRorWI@>L0*`wjQ&h-i34FW;p{d0ZwcfE*0%a_%mEU``cRliha zUgC30yFpa0G|sYYbLBzB*Nq}C!siaM`hN}aY<3?7=RA#e!UkF45wMR{^;%=sv|@X` zP8)U&Zbhhz9@1B%k8GNEH9#w=LynFLf>~LvaS+`6)YRf{4^IAm+HZ8w+WJ(mHo8I; z|HFYYx*Sqf9w-h)LJe})5XWmQnej0JP|o+C$sbS9>yl3GZ&k$J_j0dZ7gy@$mT-nE z1$lZJO+*~|K=O_jVh>ZgTpAj5+IaZFjq1NHyNq0#)9n*M`{z=UUJYLCam#xMZ5usP z-F#8fnFo{em2QGWKypG^H57w zRJ_F5emLGR7kVefBI)@-@wtPogK*|DA1A1l{35;;p6tq>JRB`ixDwVdv3Iy_fN;3y zARNHoI^w-53KrJ`d>@LO75fXW7Gai{!GFRhQd0~90|RTv-FgWY zgdm&wkC52ayrET+s*fk>3a@Jj=25Q(7u3o`S)$S};OXV*@-5y75OqRfXn-YBw)siz z!G@hG=^;52sr3wT#(0Kbg*l5ttC^yPfH`;K91kb-rKkD3XY~isRgd;(t75lT58H{I z=G{pBwrAg057dqhbdJ(>4mJqXadVx$O?tmr;hB7}#7ub=O_xWONY_i21x=FFCU!f% z$C`Zd#P0_j{hm;t+vepZaS28YcUyohp#{eKBl6)xtW4iomnI-@4wYPe?0aTT4>dTk zPg86Dw?8nd6Rh7KTvOj9>UjUY)$PSn*hwG}#K(C<_A2P6@S{hep^=f1VPV#&3&^At z5U6(CR~8xm{d;%5Me2E+fpfNy2C;f*bv#Yo5@tVFu9{(qd(qG7y3}|B2lL_MduDFF z3f%rp(f=Zft*TboHzd-P}(eDo&_l0 z-Cs-#xt-pCM^&ZAeJ&Q}I=vJc9^IaJYw8J9YoTmHxygT0xcCm46Gu^|cOIHiMthqN zZH`JwCg4q(=AFT?DoI#^Bpjv(Aw9(YTbn5@HIencN3CbqQ(t=p~S^-@y-LlMT3N`qaQYd3E zbYsM)f=tRaD{5(P&1<&(mTGAUg~mZT9JQmBn(Cy%p$*(p>OB;~c~v`Cxd^DYD+C$u zd=Ae3z8JV-AS_!8PU2{(>RE+@1CFf(bx`$8=MuiI>9sQ?kr>Y!o*J$a!dU+_lr8%` zGx;x4TX=b?cdn|w#L>aww_#9V1T5jba)Q%s*_Ex`P}D5uV>P`JUuFOO`r>wd=yK)2)6*c5*uHj|XGJN)ku|>dq|5;O^deyLYrhGPi`R9EYePsTAxbVOR$Rq` zZn*x8h?epR4GfH!o5TXAGXB={Jn;uq>Yz6!IwB$>5Z3uwxoBuvR7{jpd*(4zA8Me% z2SK*$y}Kg*G|x+JG8zVc3~fJrekCR_FiE142G)Z@%z!6oUU@gt8g++SE53~cM5@qc zg&tk-Kv((4L7S%a!Nh0hR6_?%(^XQ<%)ck+YinL#r}q|Z6umO(KA)QD%NRZBJZAea zIQqZkf*?@}=_SnqiA~IyR60f1@Hr`cS1vts)>m_7doSA}8W=A?5(&>O1(QH*x`gS4B%S2w<2pC0L}Ps3n2smJ@>nFx3FX_y2Apm=Qq?Z@4z3kHXD z0#TtSMe>A{vi)t(6f`u@b03&c2wFxdJ1*A=VoZ$?`uE>gJR7ZcXZCZSSdRZ3==!3O zN?qo1Ry1QbA!SgWh@Su1Y`c1SBg>?5gsF^}3BlR;PSfs5M_7XQ4(+n$+OI!(M<=^J!#Np_X6wgk7KVda?yP^4D z)G;37iFVe8XS*a#DednMn5Q!I|I~ZODV2BEmyRHk;WVbyoD=FUH6~oUX$E(kP6`#z zi;0C9@vo;@=AQ5JNKfrlOPT$l@hBujW>gS`y5ATrtv&~2JH(r0wMXnc7rWo)HYaI8+u&re=Ocp$30m70MrC`H+Un zP{pGJ`ft+#@pI?YDqCSEXsS8A&HIjr?qu|{$nmnCl;I_5(^IXmj%-VIZU(KqYPsXz zle?s{nob%81_^Mif?= z=}!TC5tJo*jyr+J1@ite6XU456oFW3nD9;~_6IBErMh=c(MNar8r7oGQUote&9!haP(2TP>jJCZcX9nt zE8wC{$~~b0)dstY^a2}q4Xp3z2c112;G4SLe3kmzBPUeR^t+jPBGD4o$)7(&HYG6q#-xM+BT65_*AZN2GF33T z-~v*X`R~S(1h|hak6P8jdGFpmN57uS$EM3 zg)jYvRSd^NxQGkUJ3H}QROfeGW9TyPr~Ie*UA5V2LG4&@OKlIRUTK`%+o)Hw}b1dDed3S_G7g<%A21`aq9(Lz7kE+@U&*GU1S$lg? z+Y=bpLb{?_*=&UN+g^`Um3PtWpGpeCvCw*ExlGk-WkK}{_mpeaRvcW0&>ED85kHYf z@_ANW^{G=gg;VpDj>l_tc7AtkeBegCxX~3%D)+qI7_sY?P7)bT2(r41dOJt|56%;g zB>Is*j#|kdlUS!0TEdW?o#~Kycm42i^{{ns;_$D`yO`a7 z8|D)l8mhxZvORBp2<4cbd|o52H&gzZ&K}#K5DIqPK6;FKYjvCrE1vsqJjc|t{)6r4 zN`Wj-{J0Ghk?HtRHTT4@Dm{vy({X3fCRyQV{a3qsT6ZaPblh*zqsjKCX(}+ga?>k5 zR-~%xK_lh@{Qbki!-Y09z!t()BQv>AtBBKGDRcMr%#rQwW{MIKl=PLY$d(bL?6c3u zp2NY~O0-B2A)FU$mH{>JCXvyv4EXgBJRBF!V4)zca^aIk0}J~r)F_i2h3~S3BrChJ z^QLa{0F%!u(C66QqA`!1NTSHoYcENq-6metuFGdRwbMYYHP*aXMDmpSb&czF4SCH&Axs4dwpG#XP{95!0N4P$Lw3wTy#~zyCl7S_z#FUI76#VF%c1c z%YT7mCJ`}%r#XjQAv6OG(4~K7FQv0BF6p;^iTwQ2PZ;8HO$ix9o3glzGKI_nD#{k4 zacx%w{WfY<`1C>R^PtZS4N=!#U&HK=Y5inGQt73Y;^xv+v-%;H(gP#vmxUs^D?B{A+ARWJv|SZaG7t{T~KZCj{y?KzHnB44X$QdXAr_#pk6LW!czxdWOgD zR=pcUi5VzMsPo1<9_|a}Z0$0~H#&UD*}dv|aa>S14lZHqeKp5?L(T^kFWd^@zNGG) zVPW<(4`$bipvE4JcSVeuo=r|W8ebQ8NcH5wz91X2I@Z*AaN%mFK> zOnDA}!i<{+iUbv0$$XWXiG?fJ4w9|p`JB-|bAN0zA5j#NcicGHmbP|TTR&hvq)u3( zGZymu9{BMj_zr#w(M`5rz2}gTZQDs&@b$BVcI}=~^04r7g7e*1y;=biu^~H+ zeHU)s;E}bi6)BeS+~)BJXbNg3jRJqdt#QVI|Mvb;M(}U8yo}2hUhb+2tFKS1fb2jd51Z+&FCk_Uh+%?Rq2U_QO}gn0N|Uow+N%Awo_8n+Ow zn)6+Pwz1P#>VxAJ(hofT-V>%(C?Xs1{ZxlG4<^rEBL)+?nz^wyQ{;sTSCQ1yjsJ9I zzNRvb2yxE##JrIfw2j;Gz7N>^`J=3r)m5!kp|T5K-a0+Nr?r7WH@V#f0vJ6ujM z|I71&>l3>pT<(^=LMaW~E3ZOBSsJ64gmQLVRA1kwO*@RdNF4!`hQZ@5Nx~j+SN%#z z`V^3co}%K%muB@$|2CBlyyHCw&m2DmcF;W-XQEN~5A`i3=X)nS;9koJ)^2&+SL^kt z85T~h_UC?*JJ7?Dm%TczV45GJ=8i`O-Br!3d3%C0*9dYt4*rK$zu@Me)*UsO%Kca7bJX^1FKWS>>SL4|+&5e|-3hKID^H6hRira|Lx>)Y-yGws@}m52NuHGloq$@ss3%? zL`YO(O8F_gbPyER7U7!dk{w7VY}0Hnv2%ft5vnnY zqVK+dD6Jbq3oPN;Pd@sUHu{?+f!-@5-6;!o=73~c zC|2#h1p4{ay0n%OX2UWiZCv$t^CE5^%E%FyqBquz4 zO3w4a&V$qq_{(}YBMhLGBYC6j`O0?aRbNq=krC^~O7F^ii*8Lw`7!t58FbyaM@zdy z^LEZN9k0S~s-tFToNp&t=t+CA*zUo3A5OW>R!5+J5VGQYvsiOWJDTR;C|V{kvo zVaHk>2m#S`@f+F=ubE5BtNb|SFV-THzOjAVkWA9jlK4t)Ge2L#bdHG0JUx(tFu4SF z4yn3-7p-ybyI{&y4@r|KWc+M2dhp41O!PHtzlJKcA11&b;!kO&G-OFHto47st7?|- zhpt9)#9iA2bIgpJRhYv$K|ifBO-U!S6+8|s%@=kjoxZ^Oktr4`r4q1n=Ljl(KIQ9Q z`QtS7RvQn(ph-pkHJ2e%Rnr5%@|qnK%IwDRbEsi@aoNU3lo#b)*dAdeugls~Cb5G0 zw{%<8OcE)Z00K34i3l3(CGNE}#56Zht}KS%aWjQ{lTXwN592K6+S`d7OeH2&kxP@D zoKMx5l1MbjG06{$>*QZKU)Bx}{ZT_+#aRI;4N!P~qR`l+gP*lNFG><(*C zbHL6h_wSEOLTrc3?WSA8UW=8b-HqL=O~Fl74IJ0(6x0TWcT@LP9d7&A6U^{Ra%3C6 z=9XMiqhqy+{RfgBSe_{Hr;lS=3=4HN;AVq>c-UGY7LPju)uRt*lrv2q^mesgUkQ0- zr*R_V2jCY$r5~s)0vrsM;@fL}IRND$^-LVauWHf*4N5YPiSIOTyyC~n zZj3l5Y8sDJpVU|HIX>*o6ZGc1$t@gcvjw9BJ6Rz!y%DwDU1~+s$7>lEU-FsJBahuh zeBSdgjp370(ySA4)GIe6bg@h+dsBQ@Hu{xlN^4DH+8ZaT`%2 zpj%*ntZ@#j4P^Au3No~6 z@mk4%6bF=T|e$$3wgz=sq&A$T9o9V-Ry8%t*YzWSrH>; zT#Maw?v}W(D!S|^K&tgqGenW9u71f5^nTt@TRW+phqno>X=vbh-jhsHrC~U@&+_c1 z`kqYSWarR^L+&hIQ=;4Xq%!E}ix)cn?JqT!z8MUTSBjn;Y;b?!Jl~F$F;;-xBG!t? z1Ob?^csLlUj|ZT0KU7j12pJDK`ER>EhQRTlCHn#E%8W|?H{Jo^0Tdmc54zCb?!VYB z(@M#*Wu|EV>QXJ^%k$gZu5>9M!eIB=8;HRXC;ikPC`;rChk5@0&jL6@J0yr;Tc1?_ z%x{(DerM?srxGbF-9mvsht^)4*yj6*H$d18m_AZA4k~Go$HlatyB5d5K=g9I5DD*< z>;3G}w^}hRXiK5)hGCZ-hE4O@;dTrND*CMA@pfFwn%ia3Whk;(&8F#U=bn+CfCz+3 ztHCQ?tABxuW_nv<$h?>|y7pmj})j|kOO&$(p&-5iJrT3x;BDtc!TPiKgrZ4S&5 zEv&AZ{#a)C?d|Uvjw}FR;ND0>{!&(CKzOIRNCN+yq=4SrIZIJ~c45PCppCG)6sEc6 zq||4Z=zNn~56Zlk`pn$Sh}gd{T%ug0Hm__FAfY%a*sjMVsY2*|dH(wK>-=m1Z^*tO zxnUXQJ(4HXe+gVpF88+_Xv6>>-pse^O41wWig!3m0Wfak7af>opdkDMm~>o%sVkz@ z?+$#DEikuAWf_WtDs|8My$T?Y&IY4qhE?tDeO5%73n5xjT3UWm1Jxp(%54um-+P-& z;6rNB*(R~j^N<_#cKC5tJ>WSZC9p85)!fOuvf~ROdk3v6hh_)__U-XB;HnNGr2IzJ zR|Rtni-#7r68+@a&IdFfmg}`0cN(aL0zo-5Ix^<}XGU3M5U5gh$h|pgv4Rs^4g2c=#NFGEpC~=A!x9 z30GFSzpEA#Rpr3J1#?HC1Jp*%iudRTd+&7i@m6xM?_~6wqV9Pmv+D<&18@PVS=J{D zT-QJ+-%}q=HZG=*r&wbsl`Y_Xadn7U@qTJ#9MVuU-&I+}lWwE1q|W@4AQ z-O$eV{+q_c>b65ug!0HRX8oVBK!-liCMUVUYquSI+T)?lCK_2*!E{m;jE%@DwZ+`e z(Tx2!Ta0PCrm1OHp+=248aj9IyC?Bko@b^16e4O(Lvx{$m?TSxR$*)wc)jS)bMJok&2jGZ4N zJqH8j+)GR(-JP2Q9=tM%dkqIF7gH2WBp=*=dqzPJq>o?o$T=YD>=GxU*N(OBM_#rM zSSMd)#`gg68UF!;f}jk8{44`^^2cPqQHBYH5t;O9L);awM1%0(R?>&Ij&d>3T)Bzj zk`PcIUA0mV7PcoQ_|UyN$lByl=r!?YGCQh5`VkfD(d~wxm@^p5J0=ZYCc+nZ$o2GO z6tTNewlW{_KXv4KY}n^}zCr`2rjI~{Jtg07wBD-?@gb+w3uqf`l$MSn&yL%)A zOVD^*%D>rPpmM-Y<1OA4b;=lxE{|xX&mEIMq~#-cC1`dvCc==%R+V0(WIudA(r1P` zcs5dJ{^Z{CH_QTNYr@L!ZOx{CUsy@6A6)V{Yf`{| zl_)H)ds+L{HB}y%E98^sQV$zX`=JzP)7sc5RuSB#s$x=|ARtTg04xrf*quGOM1sv< zL(8~r_wh5I!Ur8z_x7%t%NrMFFlviRCB8sULnPwE%c2-6;Q-Qu+a}szn^P9&u2-0tP;9Xk166gBuHIJaJ0QhehFoAn#Q@dQPl_ zjG6;tyGZkHYX2vlv%J4IjLXhM&11ty=8;!7c2pn+Ewb!bC;T6B8y`hL4+xe5l?U1X z)n_EePUR|rTkKXJa{-e$;H|b_g|MQsW8z&%eCB7p+FmvY+?{J@O9Svsgn5ek~uBC z{v$NOPG0&;m{b~n0S;-Y0@yS%r@x`m*5hFf<%>fVOz2IeFXv+Zv7PoM=MqHUsTj6H zsz!VZRh?UQsefIR=~X-+o!4m%1phY$wCwuQfC*}c#*-GddB*SvZ1C&iAS;V>Gh~ER zuD}#Mr)a}6diD-cIE4QDdozD@*=2t5a#g*C_Si{|k)Ice@sQ7QWpe?{a@IPH+A!3! zQ~KXn>>jDUw0`{UOHNQOjo{$<^QZJ^Id+>67Uk&~PzRXw&x+GOPkys4BWY=A0mErr z-)VM26>bu7%Dt(?2NM$E3LLi*4jR8{QPUvmU|X+QYFfSlSc1<0g&Hl%dzco)RC&^W zN~+f3B0udm6erpi^VwmlB6{mq?iHRj@2cZdljFtac3xHj8U`SV|GX$aJ;Wk6hGPE$ zdu;|gB60)P9Wr$BJw?Yc&|~kzEo4tB2SX%R`CFMccr3oMuWFz8=dE$hQe79W3r*Df zZ=z1L!p)DHPa9NPqA`bQdfi)uCIbs2s?ZZnkJS8X0B#G|GdHEQRGHS(VFLbNO$+c| zeM%tjnU57?XUlXB{!KR`)IFhXN?z`U?in)<{1w!2aS#q}a2?8SWrYd6Kl28PWy4x{ zkuvgea4Z~4?6-iBdj&bTG`&*%G>V}Stnv-3TjHF+N`R(NpX&r_^dXOzjYpm3DfZf9 ztBguyMi}Qser~SkR^HUH#^|-Pk?Vi$`3&LyqGF|`WJbkMj?Pg}z`=5OY($Lmus|rR z_-ICFcUfn5=;#qpaQM_9B6HDI4AeAewpcHm8kYNz_$%Vl;LqO^eQwT%9aG3=Fv;yXFAZeSl6&l zDdI>7!nL%X6Ra`Mug3|)KE5HY`+#I$&d>+jjT!|sKYA3zT-~maNjF8`^a6H}K>vtP z(kkVevvX}qKe%~mD~Zn-hQ`E{WCjVcV{0nu8txffyb@U9k8ipod>(H=-G@1KA3UyV zc_x!yJ;bU$KgS!+mGbk`#;PdZl& z$zq3&SD3olfrn33CoFWY+s=(V3V*e+u^n#_(E*)z35T?5^D!N0SHJ*L0~4-*1-vuaQvu z*5TIuaC@)fOa>+uYW8yT@L=yCCd*|h_32bWDbRHR(DWP^Sc8%LkOXeBnWD{!!r6np z@JwsNw|C;SmS_5jot?$SBeh!FD>{+uo1Nz#{X|@>F;1^7xdr+bW&ZB)N0hnQvk6;I z@#do@iKU$d<6qV8n{*;YCuU9KX}gHpGrJ(ooL<;0T7g5r0@kEDkc%tn0yLM~x5@e$GY z&QK`9$XHb7qC^DH4$`6_fK4IoY88%YomoK5=66c3$5ldV@jzKwSr3Zb=6FO?ya5s1 zz(5mBeEi(roR2+RJ$i(ma~8d1({o@3KxN()fR{sdsbQ2eNM)>X3!*h;FgY2U__@;B z+feyEL}QZ8fXA}pVoQtN6Zc2A0zYQ3-Q@a}-*3lJ_UOWy>GMyCTahS%o#5-M+gv7H zDt^}@0*{t9*(3W@QW@S_j07lVu1Y(0cZS+4UB;4@uM8`G7zUs)Gz^+DaZ!mz(0;w* z@cpGZ9t;FDVvPX|U#adPQ)#sdwqM^(8|&SM%L!wWcHswEG2xGVQ)u13e`-@S_8f z=2HgwnFVDX-c|I&rSFIPK*Sg@Ml<@JC;!<#n$+1*JNg~lctqDq+CZ2l*MBUn99_ma zPg3If!R1V=Ffq_4LJ?Hrb_8W8%Z?w{=mk-t8?)c9K?lx*|5~bsInUoEdJE%EFDs|92#(k7Nx&r$c7d(B5&%{qiM?$+>C=5&U=kMu^D@71}-EjXx& zUC_uv$dtP9$;jf)iV!JMBB&qXwFZAs7Z(ND zd6jXh@GK50EpU2~)Q(f4!*SVA+;a{l+Vg!P#G6=63G0b9=+oeWgtW*KN#UvKlDq&I zoZmGU%J$^J)f_Hh@5zZ}e07n6d|Y2w4&Zz53I75=d?lm-nq2gb4hwFwt5DX1ICm$7 zzTy%+o%AW3X=Rpf&BKiae|{dtdSgN}HsF2&G6=d1<3SX186~37PxRaXEm=K!@0UH8 zX#K`t)rXFeH+`0t7CG+lrohS@mlO_iVVB?(6rOElXX^8Cx4G5*_w9dGF#*i$GlRi( zb|ePsLSZP#*{?B_X&ZpQ!VvKxg)%hfu*!4|K6oI54JbK*bX^HteGiB=!8E%$bs>FR zJo7_lnEGt?B;q(hjqw@|Nr>;K(;=V_HEX<1c>Xv@>q5x-(y*t_-Z0Qv+q-T26e^hw zRM+!=j%f11v7zV=XIs=@a19Pp^W#-Glfztz4FuxLeHeP*$kL5;4CEU=17&9^V4YaV z&vdCcWn_jjC|aO{p;{92+A(QyN@J?{Vji z#nW^^R*tIdateo}Ox-nI{Fo_KnL&fy{UpKm21IURACk=6+? zVrXB{_IIu1(2Uulv83njhGa@Z3j8u-(3H9Qw;j&IZuzS4DwaC|?p+9YR;bFAYJ1|Z z=a$Kk%QS^pqMvb`rTB8zthyVw-p_tuWRW@(@!lV zb;McuUVUlhB-*hi*#o=-ss~h3Q?0}`v2a6$NqzJ(H{7mi;9TK|$ceiG;@2>529YMI z(7$FPBv$EJ-ren0CI?fV6bFyqWe#j?r1;*k1(4GA+`C~(epD{{EGB50X1e<5?Ogi8 zKPF*xPDn^R!t>`r)OI2J0PAUbsDsPl=P%v(Z>C*KM0iu5W*T zx#$C{qcZYQv~WV#1JCV0POI~Q&E=O%7KeSe##av~b@qEHBJTV}K_ffG%?Ay!|K1%5 z0l?17bj{V8D-a@rrwtBokstT%{AlOX{lz-?v2x_jZ_|+#U4trLsj|!b;OrlzzR^L! zpS14v(t3sq1ovoj0rro8g9p7t?GmJR1iYV6K)QfUzK!SZVK=Jd0sf4_tz;xabY-11W&LmtYN2eq`So3hi(UuEC4+UFI1J zAuG|v&b=cL?)zDzwTy{MPCUwHpkU{=Hr$C;Ze(_zwbr=SfBcW3arUe!#Dakz9X!`K zv^-H4I!7lpJY!-)Hs*iNL?(bV)wQ*?HRGUmuHB{Q!4EINJQ*XBz{mQ5MLWv{&%bN& z4d$G2IT;cMb6&g_@*D)A8i`BdAqG%g1B9ofZgwEQE{@wh+oD_D9e=8ETJ1EmTHZ*VKv9_;vGKIl{a6C|~HF3eq7TycQ zTfRAODd7Jk5SrKPAthgzttc$S_*Z&~Rc|&02JB_MSfxC$D_&OGzIF4}mDlIH6hXDn zHpl1{3e*D3{|5x0XZu9Y3jLKEP8UAGV4V>HRxYSziiYg%H4q8?SjjJth3!aZm`RE7 zd)Q7GC4H!d<2ny9c0Z?iXJ_tRqH_}H-(Wy={GI)-@7MJ$Ca4eX1DVU4mA*HWeq|i~ z>(m(;9)6myo@|#>-bd2|YAv*pq8BEwspALd({vvF75)M@bqU~+atjZTQM~o6kE#_; zR01UNEjqnV(+KhCVA1qcAqMR=Z3sPSq!lC};tGVVJ`LR&(cn@>0@`EKLmSn4g+&5k z+@WH7aVuv~GbLRmIlUuz9PwzHM(Qn!Slh1)B7ZC$r;ZP58sSz}#GK?VDR#0Bwwp;6 zs;csyHq)Se)ryJ?`&fPEUZ6hV2JVhr_Evp==*urvJ1WPIftvi2s|R@v1i<;Fa;qSB zFgwifSBPdwY5tIZ)HFLk!<4%9N@MlUQ1jt4^+NsU?d=CeC5xrW?Mjd*RwHQp`{o8D zP<0)^{NhwDuvpY|`*L%Zz#@f3U}s-=7>1cJBo}PJGn1$`KnpzhSPZ+Zl2-c zKUZVdsM`sE{WVzsIUJ5yJulmd5PZ)SNSLd!21$6HL?)eDq{=`73@I?FvQX436q=o{ zAOrW=nvzo22l$uQurkGSd=r>4ZwgQ^jNW5hL=X1ttVe3^^_yQmSThF}9?0PbjLhF2 z(sT}Gn)jk&mBz+Ni?k?v)CKnpgl#kmwiho3{~9rYi4N?0bCIpGueh?OuquP-CZ^T0*|KJl^Gqj<%) z@9sw=CD$Ks|MYc(G7+hjJcT&bvbW`(3aCbCE~qXL($`-&q$fG$kvb%?xU)Xe(_N9u z988?#?yv3G($wYcsG4$#wxE&vhpboO{+e~XL^w}-dR5P05f8`v`&Z6}hDf;+p+x<_ z-)vwg#V8Lr_zB9u%n_6snpkD$jMKNF2{iN^K_$|jIqV?rKfFU%XDR!- zO=Gzrnm&zNxIo1dCfxWW7?XX+x2XnSq}&gC=cTL@bjql$HURcNV?=ro3}0%p$WUIQ1Px0w~oM>y5o zzc?i1nN{5B*%GgA!Y_?^;hEF;QBGFGXDm!7Ub!{f$$+d2)fc9LrSR~$m2*mSfS$Hb zzU9JA%XY#mNn}G6z#J_a0sO#vqyQ2{(DuYHK?GZdm5C4SgYt3xyNnTGr)5DiV~_#l z2RsSk+QOFfi4o~@{sCD|5gTq4MP0!vU&8f`K=m7zFX>)SlUk)J+sXQo21kB|j^FLw z8Lp#TN;|z=uH3C9!lf^Ak-gu<3dg@Wdgtu!kub9H=-Bnx6u^82trC75j{r5s!%mr$ z)z^tT8eh=h%R#N9g#*6sYVh>2bi^?_kW#r}8yj)V^2Ed@3W6JOkMHE); z00oJ?fNQmwX>0T?zjEIh>9R|-^d0YU*2!8ZZDdPR1RthJa2U@vwNCS_ijNm*&}vBO z;K8(WNB*NfYQV2M1Jy@-D@mL2r+`7YkO8@ZH-3@1Y{um@^CICt zzkt!OGC#bPiC%!#vKc&I2^xy>S{5#bI!k=%=%@?lWS`8q0oC9uwNo{Tocm+bwCgPY z^zoIXyz%jIcoHMU9i5S}flU$o()Re{9pijV#{e~p_S>O@_f+jz1e9yzfb;#262 zmUkslETNi(B%qID{cGTljLl! zqbznl^EC4`$8$QdhrgpHj=V^EBMXm~0l7M-dFy-3UU&>eP4u_>6Qz}tyOPJX#xF^O zBjyQ4Pz)rsCj0p^v9uEtN5PTSsx2(;zQ=2)f}4Rr2X zN3|d9NkoM4RMO=iD!o83U2JoN=$v&051-2Q#L(jdsa+CCfI0DF7tj*;5^uP&RFcK7 zNA!6Y3S|k=BMYm`QBt$a6*DN|q%TQ0kWje+BlLyQ3xam4xtl*s014W+W}i$`shWaYrKQ!{lr442pOp z-3tyz2JUUoJWjWhC5rt4>EDLnAaD@dCKJ7yS|!fTrCng_#c?e!NfNtJjwq#h4f$+= z1);S{(B?ls;HSV6((3ryLy0dILD@Mny%g&(OKigf5hr?kSo~azH z!L!bQw>$+s%?|%DqRCNOd8rJjv|6p?&gP!ny{7MlLK#~6qG={2r5Pyn6{JRo*UN}` z(v_as+o~6&J|K?!-F_ntbM?76vaZSY-_$h;{pLPB-FZrWrQf6w2-o*2l@0!F-9_`= zF};@Bz7YUjuDmhaX2q>ORMejeG6nD5T2963+O?FYwq3M z#YH*A%IeIq#zz|fdm`t&mtq#{AYP0fA!=kPa5|aIpuPXPkRG`!PARvyND_+wq;6LI zlb&Pxy4T}$D}wmn*=f+%i-v|%YDb>R-vL|g>_Hr%j2LFezTVa{%>}okr3vva3+AFHv1o1v|#VQNBZ=;sRTjLFcSbz1WW>o-6$I_1X>kA|Y zik3nO5XBO5PlXoZY%o-Gg&{Ps)eveON(i{jpOETJ8}JeTRR59N!*n1JDO_mB3L80d z56q^R(k*iHSUeP`7ZDoDR_>au{|unQL>eRk)hb-rF%>QQrv;&!%p8CktA7COJ^2Y9CRsNac z(EDg7eV$e1^38@Z`Re8?if5-}i|@%T5T5XwdC1Q#0b=In((o0CW%EQpja?bAX5eE6 zn0d!UIc_xWeMYJ>r}GS{0~bi2LbO57z^Ks8D%!Idp0*f_}hA5rr&D!x5My3m{w|GPCf7g9~r!1?& zu_@vzfxgWf0JI#B4%K2=l$e8@X3QR)u;bFjA)eseFrf$La(+OHhp_PxIKZdf%Q?i^ zeXA3IWmmZyP%uFuou%O$|D4Y=<1GTJTkeDJ5+9 zKHB(gN_$dXDrvvGyhSMC)}?E8MnaLA!2{5SSE6b?^QT;L2UG@;Lo;0q3yz1?gOk4gfyQ2 z#5c_zHhp~@exU!;Txbz{&!A zc3{Gcvdb;5+>}~SjH%_r!Wo2lT!O9>Hxg<=M{pFT1$5uH97$6PSI)f*fgPq_^;LaO zi(uk5Xb3NYnx#z+(ebX$0wKGPaU0amE`C9eF8pUk;;>1-UR2Fo4h3N~we+mj($#Hn z;K}={LHB=b_4Z`+wckkX&@z%tbV?^FV{AT9Va|1U515J48*XO{t7CC6XKslqIs^xr zxVw?3v&YaJ5^u2n`ffKl%^~nAx(k*N5aw_LQ=_bpHIgTTI+#rt>dM<#NtNQ{Q=)}U z{r1Y&z85=aIQqI(5ihPC*)$Ef1EN@DM9jFs6egH_r}lAr|^}SiH7Ji z+;6JnknDZ}7REYDa7kXI5ZheiJ7!Uts0ZIX{5*7EVoT>c#+U&2+mLl5ND&H-XXIn!8kwCT6ncNP4~IFTa@3U^?gN3Uwo+Q&mNT&x8Sg- z;IKy%i+I2~U$lE_eA|@F&o&zM8EvYBgm@(AP(L9WM$6!FHm~>+>nTwEzC#+AiuBc@ zbCY3f^!fG2>c`sl=_Jw5pDQRsx&QN=5+f=cDWiA2x;q!OYtL0ER#0ze_u8uaE9XA3 zCy3|Dc}VD{4pR0m2rg0D^Gmw|D;sL3yF-)2)3rM@Yv{C12Vldo;EM}`Ng zq@~Lp9tV$w=ri~}!I0ceSGy?MwG~1sgI7KGh$s`vJA6_6jO~uGrWc_yJ>W0l+M6H0 zhKfxs_n-RiHJg%TMyg9ZQEv81`Zw;}rfQkI4aiYBj64jH1C!&Oh=#FmI*KrTXZR1M zX~oo~OU>Z{ksCh;F6(Eq*$Y4U?|w*fMf6^2<_y>v9gV=k-8mqY-SP~SmEGoV2%dPS#9QOaDFs@vw4aQK4y0}`a z26PgT_XJz!J;~M8pn2UlYZz_{+bL4lN??~Ao?lP%8)G|4kb<%n|42+{xy;=Mo4cSiMV352I#JG<9^02kTIY4i&EC z5A?PAiJ6CM^SsSlOZ(bJFZHji1f`LBs>()~-)((KhVbLYcrx6XAtoc>3W*7#sbG`< zEhSFk2}JLd5_g_qKYKCP;ZB=GiF}w8i}k^i~&@O;i7%;8mCgkG)l2c7!)}Py{0MI9A=bq^P9F zs-Z(^pj%<#C@VIIE-VTwCx00!EqRw!l+$-l5~lpAh2v+QA64(V?3IMj1SNe#^YH1? zdO^bHJZsX3tvpAI=SS-={|kJ<4wQIGe4?U8J2A$PSDX^KH#eYg7ca5N;9oHzlkCv4 zYM8U^Fx}$G2Udu;ZUc9xN(=}J)Mrz*Fg?Ywbx#4I|o9aWIZ&lkBj5|wgvva|bs z(CSjZ_Kh^Rt|9_jW&ZfSrZLsN?j=S zs8O-zuZ@-*ie%4JYn@D^$ zaL&xO{@kVgflby_)2mMd!R`kO>)Gq~&j0*C9JY{)^B@G51q5d!{TCe}5tleL{ zm_o^F=39x%GMCrJ*k0E(J=(E~{UR{M-iqwl2y<#MANWUz- zM`7IBi|pB^1SgQkyfFv}oZYF$pT5XC88wq}v9Z3fvr6rWwCNbUMfF)WM*Aqj9VT_| z({P8|&{zG3EWL@Zsr>E`edzfo(TgL^eAJow`NCVr+FpB>{CZ&Zb=c0ALT;|r$UfKI z_-`=d; z%4GEang?;)yT5<0uuFY49*iemu(>wv+%VzbL$A1g{m5xNr-_mmiQ|L096lv7#WHN* zR@&2-aDJs&q(ALdjPNw)-i$WyB$Z~9PpoZeJz%~#U{$9ugRE3-Cz=8n&3m^G{$1MZ z+h6)g@2!~#hU>zJ$`851#92A6QRxsJ#r|TC2__Hh$dtGn4`J zhsExU47b8nkd$$%Dd5yiD3`YFD90O+)Vc){DPHY{KH4PQSitZA*YpqvPvBY3c0!^cIZ-Ng4k&01% zh_P{_#lU-sP!@75wBXZDo!b}GQ>eC{R6-L`+#x_ONaE#mw>8?;fvk+ zm2!p_#=AR7Gm|%q+2q{eY+n1j|}&1Ij~5%s>Ybzy)3=H9OqM(j#0CfXPsqtkpD$EB#y`@(~advRZE9G$@VJ7T&G)h z=EIE;meh1xIR>E`=GrQpzw4=kfdk4y++>7)XQ&Dn)HlQ;(OK+}he++5G><{^xOm{W zbLSB1XN?8MPvi>8iXdYShfTkN#hEpngbf%cOFtuS>c6k|RH9PfO28+#QTzmc7(r!F zivt3g)Pt05`VkP!!qjoOZ%#^Bn5fqv`qA!E-mPAL@+^U4y4J2-vajy-MDUp-`WRts z0vy*BeD0@&zSwzItU5K~MU^AFi!M>ae%*_aAgrJ+HpxaG( z+C=+2WN4}0>2*4L-E%*p`9PcEd=L@6`G_e|sDPgX6JI|2v+nKAQ{nN-G6LY4`D9d8 z-EdoAn0Ej3)gb1AsjC7=JeyxNlMW}Lxa-K_kr)03Yh{~GeqG;hjV(JNgp|Q49T~8y zyH*FbRqSOO)KAWJ+G2u1DF8)29QgqdA45T=ATuRpm04ODvb5r|yU?qQ#NMF)+K}bl z+zb{joZ4w<25R?IyiDdpYLaQw7ePEwNHPH_U?#s70PQ_7vTg9trTrbpPK{CjN_*06 zeJJNn1jWI<+UAO%2xd8>Y0V8b5E)67F_(x#8PQACP9yZLqRx-G7@SiCX647zdKDKW zU{9TYmT4STGLu*{N4Ra@`)C^+u~#r`Ja`MXa1z$mAC}O(K~@YnhZ`z=K=f9Dy&Bl) zUEaPPwUUyp@nSM!(_`pspQBF1PU|@BTURJQ*4)7e@fm%D4Js}Y_j;2@3PLPh^}m>H zpPM5Vyz|Li;?3j$i8wK#z3J1(SX~c41ing(fBs&K+WI-Q=X>yXWj4;-g~-tyLW}Z!TP{`ggFMa*3jIAq_7Lle6K%u$$%UDqZa{eI?C>T-*KUNn}v9J&5s5jWU#!7l{_M?=K z^*aCI6c$&dh{% zEgw`L3Y^@UF?Bf$*f)D0MqkIF!WQZ2BRYDL37MyJyT4#&Jt!vcBMJ16e&8v?`r6t4K`e=Akvo?ax` zLh+cO55aUN9HqJ;-&`b7l_y1M2~+Ic?@^fNL{$A%V{0T<3y>tPth{7@itT6f8p}-A zxZ3A&C33>9aYLvdw)865QkBmH7if*e|hn%@zDl+Aa8bbblk7l;UZ%4Y^%D>h7c!|frxuD>%`2E6=kl-Ck`EqcR^%Fnl z`m)F1?*xez+DS1numr95QNkizG4IIg+;3DpfWH{Y`y_sUV1MS}doR2jft?e-Y_EiK z&XTDf-ECKl3f-Yi#J9I|f-<)u;HdTHV)OO}=*a{Qs1*mssnC&;+ZO7E=3nu&)uNIt zv|02l*DK{&&li^tFQfZ;Ej0jz?atrz`pm1>^9 zG9D6~d$C?oVyiWzxwIsapYUlQQvF#zjP2AFJ^l_{qE25~06y8m%N6fO=Wr+8!)}Z% zdRHURLdtpMziZ)!=C=8>Xca2>$_K&qXrnXx4tFez-9OKb-V%wJTOc0%b=>2P-g4Z_ z*dv+`f8Co=g0UZkNPa`O;`Ja}Ot>`tn^keO>197EaTDh9^W0@HM;6>npaq%gBvd_i6?dk~iq*DV-d?sWza3Q8_ywPO&PP zoH*$WJ#`^+7w{bmhCF=L<*&dYZ_{e36b}B4M9*KDI+)oWHEb9z!d)SK@Nd!<<1@yz zJDfQt+)fO>rgkEb3YHXZw~jx=a2*EnWC@5kyKLcL(W}H|iK}l!Ykk0D1}sPy9&O5E zCv9)02ML@8Vh(P@1m%U3ohxGOx=OQHrvwO=N0$>KQ&W<)UUdKWJ&LWbx(z6{oW-yc zR-#g$Q0_PhtTGZPkS^{0NKty8?2xD=0mtHwMNlS)6eXMi!lJEBLhIti?XD}Q937qu zA8kYFCD<}Qys{;ELLTuy9hW4TA3+>zbc2RyduTsPMw!fBg^3&T6@_N+s#1MIOj{yY zgycblYt08b!b`c(Lbfna-dhibr{ix~sK>$}1~hF0t~M+@j&Fmij71tuwwK7^EwuBA z2QP{?J<}Dm`_|GOy>`|QGj zPpgUf-FFtjA0D#|3EI{wettdoV?e`v(5nj?VHrZ&lADtsn^=!>pWa}XcxhXnDEXWp z`3X~T9Ue@#aytQYPCEj<{wDO1{S4u$b0_MKg4OMOBLtQ(plXz?YI{AREC}Xm0tybK zA{5^S(Q83yUJSdV5rjxsw-MHt5G6O6#BmwGrJzU^D%xvE^*8|_^-4;B-etS~U3vLA zK1`5}{JRFqb1M-f>~+Ybuoq$m4q;4W1ymMEm5-;xBsn1l2`co(U|~km{2PT*l$jRs zIhih!pK3DuR$+Cd!eM`7q**I!~x}O;2rzT@uTYJ$*==k8` z`oF#XOZ$t_`%?$)(YFjIx^1_LFYWQUuFbCK3rnS8GIMeqsD9%SDCpFrm;_6U_;-JX zJQEri9yL1ty+ovg#C%$LJIm#h>?#DVkBsa8?Pi`pbIKfqUt| zg){&UORhTJ03I3l-r2Dc?o@l+@UTVBK%N9`&$XW2jZoow`b-+an2 zFXXvO8;Fh+ahE^K_9Q8i3nC5uY$T19fcUIO*ioX+^eV;BzM;4aZ|NcI?YWgZtYoQ~ zK|IG5(s)tJ*;d^K|>!`w+~R3`{Lj=2sN zg9vZpW#AHq8}vu`O27ASLWGZ~uCJs_?P}pUTEF4j+s8G0%s#jK6yHhxXd#09LpcLI zV?OgZJd^ zrKG2#qS}607VK^}wcOoT-S~?wZ4T@8`_z_%lPMDbb1PA+{6XjqNV2cOaBu#giE2E5_x^{yK2Q9Ev1T2*$g;>q>g3-ZiFxB|Pl0k<=Y^s6?a zVO-l8A>#p1;Jquq0?(08=>1{yEC{9vdo>QVcw`$+@anHtct{R&(V>#QJmJp{{evk?rk`3grG|5u&P|D74+HUw+s(}(1hluN9^Lvc6w4Pko5T_ti^7+Wt} z8#%-#%{&fxl*0=P0uD>Q#h<{2GfPVxrWz5h=Rz%qCmTi|oU@#3WY}Z%1P-%H!uZO5 zTi7)OM@V6Hppy|yF?|?23>4(?>*>d(sIqQftuJMp;;UCjBi~o%rCJ#q>N(*S2;|wV zhY{6jGIpZboKHF9Nv536=IKctE5BD}X%iZ=3IcqN3Pm^ir_cyO<{XX@W^tLpJD{$+*E-Agjc&l;9<$3mR? z`W$Mj{_OEKMJz5Y4G#dal;K z{1ZR^I3{*d-Yzt+6x0Qya{4Z>~CfB!mwmzExda zopI#~{l0$Xt)Sss=31B?M-=2 zHT7G)2TrZ3T(d}YB1$(*+l()6?7r-2BuvtRZhCW=7`#w+I@Qw^M(yWlyPBWX>J)$E zgZ0^*rcl4oxx@OO!loNXZ1dGV1suB+|MCV7o@!y^%5@sX&N^u$?zGL*-wqo@9c+X71 zIMbooZ)uNrY9~K;w{?cZq+Lwni~jJ$?E%TE^xzmMdu9ksd-&BS#;@PB?{r1Kd?j$ne58AhSfDsqY6Xz z9%wn>%F+IqVOaQ(YNxgy%AuW0=RHl7an_);#CAbG;a!5{+@4c_mk#lnk_3(o(p}WO z${vcUYe|S&8#n`ch)z53w^A)cP2S&9NtA@W4&c$f&lbABVresMXzpZycB7bOTZm9W z!N%>G>Aa1x+-tZGe#O{>0Lz6Rq@RsK?O@;h9o?bcVk*o$I}9pt5*qL3`V zn3oNQZ|n%fnnhj}k-Q@8Mz}gG0hYGFM4|erZbH<)*>7ih4A0b<`u2VDT6OT4PsomF zeDC61dMGn568gwT;ZSb(9becXwn*l4Lql=G0?=O1! z-d!Z-3tVTMXXs^08)eZJ0-#7K)gyCnP-jv+%u_SrOtv= zI`k3PSzBDxo6(ny?EH$S2Cb}ujJT+9TZW(|m(rZ1prlTCP-8>GG37=?&g~#I@ne@l zS(K406~IhAE8Sb8JUOZs+A#j>1{KBVnYR#iO#3&J!OOeJi%akD{2MD|V((yY^hB4-B^a zgZ}}?f_jy>;^&yq)7dlgk3X1_x+VLNOU7OGXLf6S`BxXytag3n=XPuB-&MwS znYq$P+U^Oo$aX5^_92f*(D`ND)nO|xx|g=_KVU` z3ldz1u1B43sz-2ZfrTo4f%ezM{GLrscLsMg+Klp)WJPC%aL{7UTbhfy)rNeCyQ+%! z2YjJ#szGq55Q710v!b(43iY^X3O|Jz0BzY)^ImQA`c~J--1b*n_Zo1*hN==S$1v-= zS3%0So8^VDl|WUo$vVHirD>;r)(cGgz@J1a_n}aSg|zBIKfTiN(Xpf96P%|SrzXaB zwyOK0cZV*?rq$3lA|}R1HYMKMjwbbVW$-pXfuBo1S}1Ms(q9n6M#TnHe*9<(@V|Pn zn!!>XA^W>FrE;Z_AKMUzVqfD5Jj(8J|hvwtD%2P9Fo20`l!)vIbB97naH_^Hl*J=1w*+4}iKt8$;mM zq^zMip``8ia)PF0Zq3th>q0nm@^ayt|9_00M${2zStT`0;BcIBy_qf-A0;wqrN?pq zuTb;WkC_p$GZvnky}rLzJay2@$vfH999_pz$pL-rEC6M5=H}y;xM6(HZ{x>uHD1rR zzZY}6xO!Qkw?0$Jl{EN-b4Dfi!lRW;Wojk}Q*Ix4OC$>yr7Z7`4rNe$rZk6`A%|SS zur+_CKWt=?j9wGYzah)5W3MQ!gn^g;=i6=l&Xg4B4cZ_SV=Ur}&7h~D&4=oS9>W-} zb3Ms$ku%Te>F4#hyhMfF*w3FcI;cO^%T z$H}fwvau5DrExA)BozTPLCGqK?IjAc3K)bfD;`x4S5Z<`?q#xkSDkAXc9UD#zlCa~ z+)J~Dd7MkCQg>F72>!{?=-0~< zZT+^KxJ{}#W_&_D<{_!}1DzcjPVo^tV`#1(H1xHq%oscK?-Sr8LbO=K>V)ZaA;3&>s{ zHouN@)t77q#5H~yG*y-RGSkV%7?uEU-B_TnGdYL4?(2wr0Gi9<l6=uQMAJ zQpy$~MLG$|YkRyGzl_C~yaKJWMdZf68oA#Va(o62+MJVl(k3LjVUx}U&EyYAfivbN zn)lf3$^m2eSCLJ*ppgip2ZZiibJef3TFJih!a*n6R-k9wzuuk}ebDeCNoAyJmb*w<4T(uwLsP!kd)VC`U^YG{slJoKw^#KUV;XMaK7ST`BV zYCiZIsB*45JiuMU@k_UhAs*3h_(Ot{p0O_&o6WH#cgS`CZm^s3(s>qtBChfZ=Yv9ykl(qEO}++x4*h0 zNJ+=UejAS`WW9`Dy_c=k*u-<^kj)9 zGFaeGwFvKLoiKb3$F;%PTZHj(SJg~E$zl(OpFG0%SQ%2MUNwm4`01%aBqa_+<_M+v zHNBMs&o@mRqY5aZ?QRYNZg+<9{^}XWBnuR7L-JIwDN}8d{ky&1;ZiM|_+zbKRO3EC zUA#;>IWRCP+@(hDc6HZo!>LA=jvlk_I1*N#p$37xCRWlV6C{?PY+m@}VU4Ls%iGs} ziWuv5z6-$^xz(f$mL>W(eW7r`Ujr;b$o)kOn58|<>{o2w{hhnNoqs)Qb3Xry;+6dQ z1vA$5{XZ}Er+J&B4_b-%UXUQi=5*mx0$Yr%Gh8wODgE|c_GoDR$I5Mu=+%SBO-e1P z9EK#BIojR0b%LSq)gx?Gg3MgoiCjH zyezwz?wxeDLKq&xcR zwII4Td!(OnA?YG~51C(FDsLH+tmI9;)mvXtZcWvLk<~%7s~{7KXIa|nanr;77!YVD z8-z`@`;+-yJezp1)*Xg_+j38W3y7p#sI5 zE?#su2@I#~?QytHd_Hv$rR-?ly*ixu)a9f7hw;Tx{{?tIt(cTR_9ImgssT|i&ddKQ-; z`TNAr8r#xg`>utppP{az43T%Oi;P7WZ21PV9S8uJF-=DItx6lEK8U;nW1yD? zQIVT}$rvjfOlt2}m!Y|uon1uqelrB*7zr1%QV zlc}Sd7q|BRZup2{u>1+{)$gIj49%y@lIFH%XDz(uDM#5SJ>8t)o~JEuy8dWbRCs>b z^+6W4|81l)sXNUoc@?6hLNHq?c?XnTf{<4?qy>_;A5>7Z?5``;C(W95Kiq93zLzmKa7qF!#^cq<93HrrY6V)_8F+)B(jt83J-n?}WdGIFCL z*H%WUPW``YnDvQoUJrFko=YuDFFg$b*PgUlmTfpMegGbK_2F}5KFr+ytC~=wTu)It z9n9S`EWMRy{Hmf?k8%9k*w;gRGWMhy!l{0U3w!^v+lh}BV{Scp8Vjlk7EpyhM7~K7 zJJrk|y9CGPN#F$Cobg`d>MFUBHZQ32RS!u6ktHjU#Fv8gWw=`{IgWR1nQu@&o7y~K zZGLcn=mUvQueD)@2}mgrSF|#3taK!A!{I!8sY`6$QMBnSL|-wRikNE*5rkk#WY}>g zn_kV(ucjSh$W-JiQNcr#xjOG3swU=mtS8c@Vx>x@c7^EQP7NoUPV=xZqlK((q(_k;l1;a$AyMA(qdD zaIC#wi`mEt;QRDtKPQEU={L&?0)dDKf`LouU*&&HN4b)3;bHAo#iD0M167dF%L#mv zFqguDpmd8t;xbq#g77oCI#oiEm)^h)-P7A^nOK0bYAWw5UL)l_rmthcH#H(MR z2MkIpkX?Fik!7%)?R)X9DA`_+Xm%!1lHKFZFsUrf?W|YobZUTqcvN>?4E&~kj300m z5uTyCl-zGQF-19hUqr8bj&GF_iuCd-Egz25@-6)JK>b+z&%YBIKK9xKGfag;t}U}+ z53k_Gg@mjT%^J$AUgYYGPEKCb)|O3tGsU!Th|2t6hcA2a!U2G0eOP}UB9)Nh5ZHUG z#G`tMSEgr6Ex#<&UkB`sMHP>?5=7lIdI+Ey?pmGi=s48+lFui#OQ>|<;g|oezCm-% zsU`|bQQrpBe+Q3a+ZsYxP9|mR(0p_vAtZAe{j5z%AEv+v&@<#OD%}PW@#Y=H=!}A{ z^=yqHrEQS^)|^%q3oE>(m~&wTK-SJRMaI}e{rD>qPsC-y{}5u~z&2+A0cm)zIqir%_eE?353}#? zM{I)Buad?2QIMmdVx%3toDuyCxeMY-9%>QK-8=72D9c`54JcGS%6>Ew%tFgFG&D9g zH;b!BdxR>~)iprW!nY2|OWN8mQoeEMa*dAtWV>0+_ZUIZx(LvmCknrWu}B@_KE6IR zc0>)IDLqIy6Ya{}9lxuh7djz}w6s(dyrvIld_hnslndf`K0PA=%&UaCgaDs1y0KO< z;k-wdT;aW>(c$|#IcIUoxTKl;yYmcQz%>ED20i78F|oTIgUk@#@>Aa_ArS`;eO>## zK|z_=it+Ud2#D}vj;%9CK%#fWom$%7zx)??36 zs%k18wLI?|wO5MzF|Ivslm#VhYE8_{Kh(~=L;RuyVIt7))*P{i#u~$y8*9mI zd?kq%(C-nKa{Gi`VQ(aORwHfHs!F`x1zB1$uiPTb5h}fWj>TSmm@ea&{7F1!RHY)- zV)Clj=Q-zOs*%Xe=fYCBerdA?;<30;d8VYUl7y{rKAz)w0DE3+KYFOf?j2nJ9Y)q> zL=Ab@v_9SokLRRqw>m9Nx7vkF*2$MHEaz9`My{_j=kjMpNACuzoy22qXSDaMu2v6K zS09yiYZ%st8J(6bq>rJFG?PzgaUyYVl%D68mdazgv?8U`{Am?kv8gVu3P`By7fr{E zatMTZU*6STwy;1lQx_)NVS3ZfUD$Op0u<`WN6j&h zR#Vv-vPk%x;;DL~PnQD8sNaVKXtQypEO_PQP?^_BQR!p6zr_Regdt)Y_boqIs_iuJ7)f|&lpG21v zpZW9+)U$xG=u@g>Vp$Ls@dFv?q;BU=t)MA_?)%ju1%MQYk(FB$tY}a9fi1_$mLNIw-;vmE{VAyjMy6}Cj=t-A_ydC?rT z_UlY81g8E$L)dl98lvL{dI&3d?Tb;17k+MXLIIrxFyMEZlODfLJ=cBY)Z}-W1kqm? zw|`Uz*KW37+BI*!bTwH({{RfiWilH>m-U5Bm56;pDZiu>=e8v;H3olM4EB`e<>j42 z?{8_GawjRk+1zL7POfBvqF{h`P>$m4RVZOTYWr8yRAJa%4QMwNkb5=IWkzGe8rc* z^lE)3?%zFO=qzGL`#2gYgI^JMN+?syoR;7gTeFpI-QL)rjQsf0f-QzK-W&6{nnxdT zSf7p$@Cn=&L66?*@Qq$&GM{oDFb`HPfrQiw4-w9UL7Jv6DrEASs{|zI&V5&e5YC)h z7qV5`yf^E+4_>stW^J=bIr+eQcQ|@SDEgoKrC!^2e$+5sC5KWKSywnD!O6yoW(~0T5{LAO+ z+Z7J)>KznTf@_6}Z7hcg0i$p0&$(H$dA$#zS;u*twlp6xyz|r}D<}e#029$nZ^0rH zETTGPD5aulcV%G2QONRd3^UNe40ic-Hd#R*>%_!yW?C3?6@rkb#Co5Q2C%oYK9hrt zgP_lfGISV`i*E~4ADZFM2U)7&^;1O|kk+7^5kFGU{#IA?5K6D4&q6ajzb`E0)I!4R zF80FXP_a06-|QF{7;$LqsvGIfd2EfkxGtm;oI2nC22Mq@_P`>qr@H59ZnU3&p#A*E z>cinzl-OzdEcg->%;J`uR6w=^=U$W37mlaOK3SLqh~9nr0`Jeu$eMHu_0lS91tDgt zX?hV%-vA!-(EB@}##wZu5`lwRj8pGEZg|YV+UCdP)c%Pni+d-%zin@1=Cv_hibjLYVjUi#zw znRiaovjfG=JAuk~3e0g3boiqhas#D-yq*-j_4)dx{et^P3iO=mw1#;=Y z(c;%4%G>uuidWat(isKoICG{#8A^TY^)zC_XN={}^LyK~oa|YvLQSA2gK0Y8IcD}U zCLEeeZUMH+SS?#-N8c{?5;a(qQI;>tJ8E|h2*$P^e#o?Q>Z1W(z#~FY zrA7S|i?z7;h2hFt)OgXfzZTMLcd#DDB!!^n0FA5|d&5}q+*8Oj7@+*!-){w^nKpC_ z;vOkD>mCU9x>Dg7wU!ip1U(M2QUdGEQ&TMuK@1R@(;uhX2bL!Hc8oo!pom{xh}R&g zL0Y?oBOiM4q7FcYZ)&1;2y5|_I6F)@AIl#zJwt9MEiRVMyhq)pqFJq>s-oN2}ULEh6H8iE0EU*tIq6IZ?eTJg;z8qn9SyywhksuDp1F{|2({?dkrOLz8`|h0#3%Z46_tiEDgGp-+WhJwU_DGtr z@w+SHy6$C%`$tNi&psr}_0i0lS2wh8=MQLke)-q}vvW@yfFW5Y3j-^^fW)Jw?Sf^gW1fi;bNCZHIA2NWgIE0(z&@RD6az*Hb;;S2u)&db5_o>B82$ zr!GBO{?S!E8n`^edy#wY=c;1V)c7CHyq~<`0&`Ctb?gPUodS+a78J(9xsZ*UUONHF z_f|(6J>{Dt?(kauzs_O-%*k`?J`DfLJavErJ)8XD+b06Yn)rQENv6fe2R| zAE})*jXCs9YI<+1@F?2~@X7IgLLlACf~;;76(qiS=v|P{l)ycugFQR;eR+uloEW_G zbIV%xU4aXh4S<%Z2yk$X9o*LYD%Y2S4yIj~aor?sh|X_YfKYHJoD>#EE_FFUtsK-! z)NkFk9g)xW{AhpArU-wwG|@?4sXnUiRKjb8qfoyl>m#&rk{|}|Tt?!`e~-Fm>|vP( z%Ogj8M_kATWMN`(y0mhP5_kRth2t#Q$`t-kzf;ojvH6$G8^#eVE5l#FY6yXq(Q(SI zstif)xz*Lx;D!Ldu*%xnT5&G^FA~(Dt^(_{5}!8!YgdOl>dlQ5&_idN`A#*0E1G_o zFZIKqs%abw7k9&Go}e+NuquW`K))k;xm*wksm+azHuQ>kho8N`QSAGH!`1=e{$(|| zL0EuFZg0_?xwPcr|3)B)8zif~+>4`xiqseXuLT$#g?27%yQuYT9v&w=D;>yu+M2z2 ziu>PQ%AC|(szu4G-`hze#qPI({P-9LTjPkuQ*#S}(~KF~U!O|36`ej?@9xm7qKph7 zeI;2pes@v3Y{SYgtB)T@8wA><5~HRN;w#2@7kD6%ONE}Fn4_VGS$tM%!929Ip{5$`0u(P! zr%IvJrvdJh;kj}X0(ZV8db2BBC0FvQVmSt*ja346 zNg*hkzC@x6?9m+!LQ)W_)7oxiJ!|y)V&LzR|N0oIRphi`+Xz3u844p#nKr1<0kdOX z`uB5gk$947J(N24OWN^-$wP+ykm_RaQ~z?(`ecTs2j#q#HZXud^j^daVk*)qd33RV zYBg=Hpzf5`4UADZ@&@IAN9J`1EmVVeow%9$QWr*2v(;`yTG*cFTaqZio=ZA(yk=w( zahfl%!a>Kd^L%35OFIS@22$BaOe?~2DiXWVpAoaTa9-S@{N>2#gRJw@fBt}??9_hy zrTyPC8P}D8%k+QIs*D%=Tf9vN@w|46&p+^kK)6Hw6?$U`Bxg(jt^5LM^1O^r3{CU2 zmvLqY4;wnyw8!%Kt4o(I=wrI-kDx2M`H^k$aK2=+wyEVwN+h{EBfr%7RfSU9q$ce3 zG`H^C0`cch%n7J`O$OaYrqf>;bmGcdowlk8Vg}@7JMA6wF&D|G<(2jJic=$afSdv< zRaR)izxe;%h{}djJMpXtMq~Wka?P-J02n1SpU zM;NjyRf`Iwc;%&P!$_5|ncmiW%_FS!9ewQQ3c%;NzB13xfrAu4FaPADX5N6j0@d|{ z3sCrFELd=c!`Pq~&E}Mz^Eq&iL)cq1KO+KYM(=PI&H^BJphPb978St)t$tgOub`w! zOn@Zp4QhpUNb)`XhKX!p+)+pjT;I4b)qj!$hHzy%Zq`$8-AP^YmvDcvc7@okZ!`taJSYe7)_J8uC*7{{L0e2Oi3TK6&AKMp`@<6vjlIl zma*44D8Oo`DrO*%5N7}!mc>34!+^%c@84EeN>b8lL7F*+s}-ilioA18)-v5qRP+&Y zE1uIAaQvb(q3rCZI%cRe^)>?!yo6k0+Un1>Kla^O7KvPe{Q*=|N4?Mc&-E(MWORZo zCiOL%E4%(R;;E!Wf`tqmX*lr5=Olqh=w+lR;3*oJ$-f@lYy1o=F#64A-B-F|sRw)X z@6TwlW8?>NLowbNXX7PXm^!GNkfG?vC>3*lF9$>cbCEV@)8!eD5ZFA}-Jwv%EvZ^{ zjTmz3|Iu{r;Y|MjA0HM|VoEH;Mnr_knH&~kg+>VFn4C{JA9I*POo~yTkmJZ<ArNCvXz7eIMhlmD+%r_9SyarAY>U*V}*K~*!6Vf9?pkiGJBP*E8tLk-JT<6x?o3Vp9LLgY6L-JPCyglJ=HWq-y#>SJJuBAapYI( z2NTlvLec91@^6iq5mgVH6WH_mdG)LkFnmg%6SRD|PJyyGZ#XJN7 zI89o1DhdNAefp#cFTy=5Je>r5_NlQk;ARVbd!`e#DUh9wV>p`2lW|A~m>r41!w^JBiizDp{q!7JQNEl{1N(on+<_I#Roa3{~F57lmxFOhtWoF z7?t4_WjJCTN$8<^@5`M$_iwMO>2PpsLlAD)w0Fs=0=dSt!3-brtb=Br^<@3<>+4S< z4&{@XQDr}@B_|d7T@^Nj_-W-$7Ud;C9|Y=X^qz7O*`qx@9%0aKweR)2n7qBD&b87W zx_TfCNT0c;pVB59hb`PMy{9;!N3%je+=w6dUFvOpbg9>P(N;XAhFMm##pyYw9MM@L zb9+5s#(I7qS2e1g!y->3?wQ_*JjBD*9!m2v=Em07pD0yZiunpLCvk5GRoZdUJ8XcL zoLM3U_^Pv6Q4-Fx(Jl@W=}Y^>38HcHgm4nvb{?2AyS7PhZ&v}!dQ(&miOdp<5L+8# z_yFp>J%xU?TyMedT;s+v0WP@s=TKTsJj802WXjmP1CC+g)t+f_$x(G-*Vlo6l6aJ3 z_UV%Z^9zMqs|#Yn5yni1cgN-z)ALw#2xSD!Bcc`5wMWx zLdz|1qJ!XAHQ78FM|0^!bEb1~gZG4V-ZF!| z@?-KZO*}h$+pQ;E3?u#AyfQ{{68Pt(&}vn#<^@d?z7MhoGxp0T`zQJY=IPsouQ8`V zz95(fE#<$}gAOZwgNpb-GUkr;-p!?h+{@_z3uwM>Y_7(!jv0J&eIE2}<8XIV1t-FR zIhSZCcsB8<$<5f<#6z-q(s(8jqymb;qZOFd-W4wdI8yv(4h)qCO)Ez$dK{+=^kAdo z_h+GGogb3!gOIUB@ti^8`s?twJcU=wjqw5LA*39;9HT;&adj0qPcc0(b1sG^!1k_N zVC=q_$=kg9M1TZi7HjD9eV{_5qINJuZecsQ#U6)5RWwD>mz7gQ!VmvqrWAApBM(|v zcWv{FnV~s3f{B>#tDB?QVq0YmG92mNE`YWx;E7N|4fGref>;P{7Ag{&%^n#?H#gRm z*3aASb_pN41|Q4-mWrN??w#(*nf=U2t(laOH*AC3D-MmLT!q>KbD>cWQ{-iF4R86L zH#Q*WKx3CrLr{h}o=O75z_%{oa|?n2`Q-p1p^%i077`NF3_ZN#=F1ov4LdrHXt;+G z78C@x(GGHuYa9Lam%{GOSSSXz9X6TBCG1AXPyv9mF??aastLcwCi+u;0kf+*YFG|8 zx{_4*5|(lKc?2cWxUrG^miBu({Nx7M_XoXw>_~DRr2rHm{s+tRIj6)AYcl&@~N!L zR&d5SpakFJ&Xqkfw}gleFa&*_tuW+zQsz6P&iK2mpifX$khN^9A}`{zT*+%SCkZk{ zn-={}U?zGsw1Y`ftN?$mvY6vAzv|!RMJTp%2!^73#JmyV;4XYyjhmX9@+0fzt`yx$ zE8%moDT?9&?%ug4Zn!v@RN46V#1Z!|kPFTJxzG*1GMr2d~jdH2? zNO>xZ9>+EHbY}txj*EK6cF)7>S~M)qLg5s*?#~7fh@96q>y*=`Xu9>T&QD<+JDIXj z{xu~)F)!x{Mu#j&x?{nS@+aAsM2ay0bL z3-zCu<`xU5jsD09ZnAYSF%J%|vx6WGvB;nf9WXQjb+uQbWOr=PU$;i7$--z%Vbb`U zq$u7%?1t9e@hW92jD_Ac=x<(o$TODL&~m){KUSxt7c3nT=G@FOcB;M5-QVZL1kQ@cB z`~y3wRIkZMs|y_fngsQe!GcO+;Z$>}-)hxn|1y?hkRmNxB=Li4Fd`@ zo^b(iwue8&y?4d>TL{>UC|>@m+9iho`=N7@xc9tQK0}x)x;pr3#lc>w-8`L5+!X<$ z*weGmNq4U<``Jk@hch`ZZTb9qOOaXmwYM-eInWk%s4cli&i0XT8WO3a1~#|a`q)>- zLA4?e|E}5Rg-_Yb0V6ycFOuS6G)<#p~?O;cxq|kU$E*6CPja{YW%&nuTir zr)_K5hlz%x(iI*OBp>HI%{@OY>=~}ZcO3|$Ihjqx>u6PaXJrE;D)tVD=PY_@69Z&ss*lKp* z$WjKn;P2>Rqz7V{U#a17QCyDs_y}5V@CguUGtg`oQEWbbW-Na~HP2QX4JyIl;T)sc z=5M@MTZM}5urK;+8K-;u$W2Yv7z>Q~#txV~7rt@muE4LSBVEpl_!}zJ`HlH!gR7>N z+EgWDkh1-o0Fdup{Mwbj4H=nb<~T5S&fR`h1eZz4F)bn55akJ#!q^x-eT?N*8;f&h zv%hw39Bdg1JZA+8;OB*Rv&YY<6uyv0UyOkul7fSRylvb0_kI;=7^(ru zUpBLYnSHN_^|*5&rcY4OXs9^&q6-O0)j>Z)=1(kJoxwueXkHfdlobDIE(AF4_Y42+ z!##iO`&BlZ+2zjn(}i8I;r_5$LD1Jw9GlK}1z?2*MG(wIFN5^iSQmiY*??~7Z=fQ{B-7!Pl<3gc_A~kB ztlEzX=$wiA6H&x+ME?#HEt&+9TlpU)4vzgEQ{8{U zSzphFdJP>C=7^R1C2d(ckk@{^?-5ut#=p~?``T>WNG&gN`wNXr=w9l(?EOD~VeYBK zn;?5g%qbX%^7D-QB@mmADE2xl91?vKB1Kr8Z1=%UOir4ahT;6D;~@UiY?Mn{Pme3| zPQo&HwRV3$Wh_r0Po`<^hq$<~siwrRY6IioC?EpcWgxGOv2A1h?C9udvi0F$lDuqM z+H;0N5uODyu`2?w0CXXpkppLr_S|bI)Re8TjK>ykvBzs$w&)ieIYS_-yY-M2jR8iih(taOU{+Yvw z2;Yt|i&XZQI8L?i*1b&nFsDaG*{&Q=W@rQArdMmRALo4+1R~cqPyRW3U#$i%0{bG+ z*exFZ1O0?tQ69EGGTX0~X-XP+XI(|tljatAZGd0`y}k>{kLytDVzEQd!4<|8jEXXY zIH6d;g6=;EA)Y1tU}A&27b{qpku@km!41(h&gQCYP<o0orGet^sL+ouWv#0+it}*9K$|(YkiE^gP*?XlH;FW*}Elv zt+!-!`4&cDAy}0FRe`{xU0V%vZ<;@p#9YC=!%HXsNon2zimN)tFhdS^5VszdE9SS9 zL+1=Gw~pF5;!4(NKbhn6Y1vD7;rJBz^AQHY@pq}5`(3ubkfhI?G8Wm^|Bfl!8a9%m zjQ%Ih(-W7@Cbr&p!<>0(x%H&ZmLTAz=%hQcrM}vBUVJd3M%v@0cWo|lxk+N`L!^g~ z#<;W$Ea=PQIz^$a@Q38GEXR*lt6s~>ZX{bGCb}rvC!YNlOj}zu877<3G^8Z;Z~6Fx z)`DUQJ1Q@k1ImB`ELCN0g)3xK_Qm)i;l_wk`R--6|sD<;f z%}2Ix9y`BP3{_GMJKR?GUS9ULyYqN*3Ur_ERsoF-w+jMN0ACngqZbRf?1iai3oZ%2 zHF*rY!K;6T1%7;>9sTEnrTLSOIVgKLxw|yO?s(rAbFXMUi)nWuVtenXn@cD%9^Mvu zG~d$`Kcuwwk$M%H0y=}KeE@h(Ig{JJ?YI=q{ zL{KFW>2~RYVfx)zn?7v!#ZSN+Q^8S1$gVj^b-5f3QV@)2v7a$yF;p|w0El059Dz}S?@&GFQrLE>s7nZ1zb<3;7^(22AUEM!%uRIf&U2=voWiD%I_p;k1US8gRp zJO8XNRDCulj=G=%nRjvFT8Y~KJ@8b1C4N!@T03Yhb(Xhp={T;`&&4-NX|a2A_OPEq!+gKySPvJo(W-B8a(?5f{D7 zVZ#>BIv#KkdFv|>qI|qNn2|l|qsEqP9eMo4CA6&*iil?BbwyM?Xf46pRG)!JqQ0rU z!;8OWW+U81E5Mk*xg?ZZXXI(9M1`Qr%=H8Wm|{(22Q=ofWi=r9=DdxMU2_!U@87>m zyCJRjT@kq?mt6UQXrzmA?SD$S* z-U3hm>E8!&KN*)GDvEt(y8ri!d+W;9KBo$fn~e1n(&xtNLPnOi7=@glUi)hec#t&) z&VaDaR=+-kimojNJmIJ}EyNqegE%x~lZ)E->FxW2c_$wFhE|qtZ_eGhJInxUcr|U$3nreUTJO)3=%R6WvUG%>zs0%->y)kwA2&$qWHU6`!ZMfGS|35e@Hz^ar~&;?$}Xb;gueBQ5=v87}iNYo1F`*d2O6BvQMCo z?icA4ea@eljo#G=IU+VjO#4$;gdhA%Z4Ap@$+e68s*;7SQqGp!G#Q{|0sa}~T;r4F z#;MeFZ(9q$ocr{u>5#?WUAM?@9D-H&Q->AK6hXN+rvTnXj^=dbV;b#B!N6>^Pa3&( z3O>QpH--X|>E5}4u_^;8>#h${+-s~kx|>a(N#7ojDQWF|H%u3s#D;q+<+ZQxX9Ek1 zW4(u#re)PaS~oORiREfWqpNKP{b?%^0ZRW-T>Og^5xd*O2@n$svhz_X8L5_M64cNr ztPvuY`@k1l^{{D^OY1NK(l^@!#ddQ#P|CuAbPiEqllj`_>t|?`d^heyG*g6zRD2OU3 zlbTbbF~G;Ls-9R5Qa1bF{#7aX!OVuJr|RJN2kSq&c)>-lj&ms@$#=i z*36hRLcItQM16&gC~1+bOe_S@AKm^t_cQ(X`>*o7kS7VyN11r@qinmQbdg~C{FYDK zQ3-8u&t1 zKg-MOH2ir#V>t59%zkHR;9jN!lHBl}Ri#2GYF}q#eq!~M12goy^%cLv&2`bSzek+i z2Hdh5?e`-#*J-@k(fL0<>G;l)11m0cJ&HowRF4|Ar$F=}xP+UZw52$3>P(Dx)LuzC za67OXi6TB@1!gE~A`6*i`WC1Co#;TA1MpQ-cj5q6 z_tNr;k&HMXJ?O7H`<{~-goyT%5dnGSX;*Z4_P4Bk`7^BcpunGEbp~KJ0_bUG2$Oa+ za$L>hlEHp!r|Y9j`MB$p+&bcRHK8^KNnO}-4-5(#63>6-JoZn%*aA2+zniKMSlNV& zE@T*X##aGvde3}>epZ5jow2Q^jn{HPis1EBdGx@*07HZ;Hd?Ot;u+@EOiORX47E=T z`)-ten^5UzJ_#!lKw$B1Z_R+qE!Q~R<)Szkb$66BIL?Sfvuk%W@wp&Q7exi%49P<#>ngfh?$rPbd?(Xo5%Cj#|-t=D0(kJ%9L(x zP-cfei<~z^5SdJ$N#JgEz4X&JEK7Ymz?Z{lk*M@1|J-`a!aXlEFm&g(>O!EZ)A&C? zuQ=J->SB_2&)F{^Ld~vH5Zmf)DXAkFvcD^JjWBrDH!R%aFES5vwRkC@=}6~fJhOsJ zSTlfA3H3eNiR%f)+qNm_BttgLul=gn-$AygyNTW1x4LOGl4))f-+93+HFay#C(S3v zPk~dLMjOcUs7MxhSVc1|z0U8`U*Zpn{q0L1wB%|!nxbxRzp{(^&oVTtRPVosV-xCv zX%TrY=Eq-3^JHbSx;mAjCD4D$%gbvm$RfJ+7KTv4OE)I8ehK(^84@6K);1tXgrI{l zdv$yV_Hu62%U9+_@p6nkl%W&xch1W4azNAIVozPm{jI{++z&>!=5AY-lnxgqrUiG~ z;D&lU_sKRsUP@*D&*jlD)eiyB?(*vw$OB8O*4Cr-kOzQ}OtY=7xlTFvn)j~{K|xXT zYzP3McAuY!vp87-7Kn9rhb-c{{5RQIJKBKGiZSQdbpJ^ji_5G^(+3rSG*)%>3EGuz zy_bA$^PxYikFuwKbyiQeO&P>r3R#}NJ$o$C|HP@XChNe~$~+3j?4n@QV>0bES4GMwB zP;jJHHSg`5bLYj|>0l-aQUcWP&YP0-ucw`JNZ*;*JSz@ex%?*%?Q;jo4Y|`q>)aU& z)>F}^$XBuKK&f<#`{G$v>)xhvo6kAWKRE>O`PjblSV$V#23ON0fq4HmF=nJt67No3 zObBl~w|^M0&B%MYJDhjq-de`J%~tf=X0>H6PV3-zMWfHfid_HYuZwp#|6dCrajJva z11U~biGI<*i@HB@Vb)f(IFJ*?c1g~f#Y4k5##`>Lv0~cl)6m1ip1H2p3QL*Wm};ep zKwHnDjUx4(=V>xQ4GrpsfRc&X;tW%6jkPHFV>eP9g!1BWvNg{n!v+{ol-Khpvynh^ z0k)=G?<#PJxYd)NqIT%P=MN`cQ6$EHn3^bC~Ds>>IqG` z{TKgE-X-A^V7)9Z^|^i5^69qlara5t=<3No<#vGYlxWGxE@BL*g_Uv#x{SZwlwJHh zI|zb4r0QAmxzMg;_a~qG#J&?ca}Xn}YpqU@)(3-%Nj3cNcig^U9f))(R_+n5#sZ0o zAj?I6XTrWeciIW{A78MVdh^7jw-4$5rAxvDH}~QWuk-4l??(vJBqC+SR9X>&xwaNynPVs2ap@y<~&*~ zkvQ#f4GdzQ2^ETdUzRN*Tbyo~ULOwvx(aSW@i%{5(olKTDMCGfjOPY115)P7ul|4% zQe^Qm<)d-qM3TNz>T0+pr>wc&AU!CtYdx&Bf!CBwFY$guRx7Rde$=Hx|6J4ES}tP~ ziV**a_^RTVaSFWcUsQDdTf-j92ZBf>%!UpT&!DGhD1K)VtM zLy+sBna8cn7QyL%0a&bQ*(=+yF_mG~yXNN0f{?hcK!9Nd{f+#&F9;gP`E%gkVWg<- zrLo6#Ictt9cZ&1`AoooNddxr6Shctv6 zY(2`IdlCgyfVEY@+uO63^(kbB57+tQ+n&B}@0M7P=#_g6nQqx0awo|MAZ>`6?cqC1 zoA=z#a_fTq28PkoVS8Bvhpo#;>cN_(oUhJA;eDGp?u#N+%vv?{GfNERHitVpC;iz-?EmP^E0)yYI|cf z0*6SDCym)er3sg@{6v)2PhiS<6m=!}kAwo+m||?%XQlk?N`^nABP;`<8{0v{SrIQ5 zL0}YiM8K1_pOwSwRJp~^F~Z(T0uTf(=PonouaL=bWfdBbgx0rVEJn>?yUSlJZ0dT< zbZY`Rne9_gaq^%Q^kMcmd21UE#1B?j7c352L< z-vgAmn1w;n(Rv+@3+3`>R0_V5V^;lu1ks6Qalpw{F86y!SmShy#6y>t!uU|@%>S+r z8Mxs@APxW%n|zN?1*Gx|4xY&yPtno=R8N)@B zN5orc!T}k!QiEet6N_ny!(VM2s0(!? z#*9GkC&P8J;2jd;V6<4TJlprZHa>6o^pbwWF+8a zXb5IS+2h<46Tbr+Oku5KcePx1A`=*o)LN@+(T3gx#mRYEHf4QW3Q&V~G?l|+L*H_- zbp^C`LRdf%11ue+H`?eVf0<+vEVoljl?U-M?QnlYO8=@D7Pzm<`)W527Zw(h{7dSq z{*5yaF9yVRSfZ>vU@p$)RxU`f(3iB(!Lv7K#{WG!!+zdciuP`GE>y2 zJ7y36L^O^4Eqn?mh!<=0vbXS}{n!1BM;?|}a-3MQswKB|Wq&Gh8|o#QCfV60r2j>;m` zv-0T~UA&aa#v7W(p&AvYm`J` zc~tGle4U9_^ZF18h!;*+571=!s_I0JJC2a=#9{rGqQ5{|0~ld~U&v!}cjWZZJrW#z zj6F{!kAKPMu4exFJEr!qR8JiH2_Wq4?!2nDZ3<d9tnUr>7+OE-o9m^$6%K(p zq9uwVT5XjB`&IRg`%7I4dt*jk%t$=vm#k}9yO9S~1siMEvRjRP>JP&>{pO z{B$dGb?-IQivwlg5zqYzeDKTX4L?TXKa=5zIJtS8RT)y(A>E(?8UO|r)dyvrUvSt6 zoDtH4qIB#1K_as`)ROp}0v0H$D0RddT|f+^IADPzRH$;gyX&{3k{Dh@x3UIjx*&-7 zs^)SnA5djAcF%S=ExJc;9^PjMd{Eb&TAO!-a`WswS65oLwgpyOcD4_MBWN2V4++ID zn13rNHbicb%u}HacX~!+J1lVa6IXA~K=h4oOZI*V2#eS}-1u#L(BS}cL=lGKIt>ht zX8O7{w@Ne480Qa@hEuQev+%IS_>-*DG!UP*NN`9}mzkt^vTLj zmv>_&0GErSGE{W8M}?1_hVeGD#AADd8_y-A^oW&)DVvT#egOfWUkA_b_Z>7R;(SXB z>b|-*-Y>>LJ&394;G5vHSXM+o6UWIr{&9Q;%&$EMO9^5u*{aG_E)4YAs(F*l!0DIZgEmj^?yCRseGjgZnI(Cja zxFYB|FOu)_Vq;9xF{h(PtZyd496GGgz`X1Da51A2XyUL#`arMqah9${IwiN3_VaSSAv`kJ*Dyxux7GWRwUumwlEKUUU z@EibMzS6eZn9Gi;N1fvZJJ8=h#>M;H`@8o9Da^_0Y@U<%mh4d9`1I%U77)5cS0JVo zp1%bX1>PVY6O5KI&+W|~K$9$qb#)0=e}3~HMhg-Y6l5}Be1*@2{3fLiAbd8w9*`va zK~a$4o$Vp%MsPsbrL^IauaxI$@pmh>PCH@YJf;eyuR|I}!`*4Zwjaah)@J1Tdb{Fo zSBwA@E0yOr&TKvkW4aW!J7dTbP+x=peft$>6oYPJT$nOoj6|9QOo5xqlb$wV^#JzhXVRio* zxmfqu3MR&M-=HcKmIDm^_l}yX47p++CWxd{FN|*gR4%E=wS`1#Y#qMcq-R?~KZ_{7 zioSNr1&m{kIRGlOVpb?HLmCF1x-p3TF0Bm;R6&VU|&SG|(yJzcDCgEhz^7!A8#yOEZt1J&1AV8fsD z!Yh$=qLGgHLh4r*9WnPLxdK4Wd?9p9;S)_dIl_rBWYjn+yxmwS+9tf>xvHbv3LN13 zE;tPO498?=rwjsaQ>}Hf$p~)WS{`|vIUhQy08H{G9!btl-Bz|!``MgR8u;>6;1~cn z^=lJ$FGI3IVfGjFvye&L9S{)^=^m%bCTWk$Nra#eJDX56IT?A!AoJDmq9^J8RYbJ^ zhijyxH`UCXKp2}R{nau3Ls-n|*r#u7m#?ufgYc$amKpxM=iPJGBh&nPRf}*aw!Xr5 z|H4{r1&T6^`2dzcgRE!g=Z{p*%9Y6@k;%%5yW70!1pHM(7u=P*hnGHVeG?J~cg=eR z9j6CWH2ujjGtNxMJplpfKiiRM{wtMR8r79oK?QYH<>eKxxKgBDAdYunMIaF3-hVVa zhN2q%Ui!9&ClA*8YJr!ip6y?p8Jq2gZgLSO+^-%Yb>2Ky+YJhgfM3=N)SNr*R1VLBHRN}@G zmpF~)zynRTtRN_6A&up>BYl1fKe+MXUgp-GyClLMe-Y8Q_2&G2MMZ~V0K7lIC9^CL zU0jR(-Y*WALHz{htgJJ?%pJw)G=}>{1x0CEU8~dDn|u!^`JNY%w z#$pDI{JLY-PjFAuXFXvtU?X+Hhc)Vss*SXGp!r|7e>gpek@#@G_#~iVIm>D&n4+)B zCZ|J%Q9?>H04k6i$^a9HVh#C~>R}m? zrex%d<2AJ|O7=V(gBFSl3549B#@vbLB%syRoz(DGhk{FJpZG%nvM?u)f)RAEe(JbGY4Pe*58WM`B*6OtAnyRX7jXtEl15bPuR3CxhK@<~f(C5)| zqF8R+OA@bIJ}Cy`M!z}|0_dsNfI8OyV8n)&aem$*>Gzkh%}h&MHeMavl{!YE-Q+6Q z0gov0RBZWZYTEO+$J0PkC}Z(sC9vPPpr>)#D*MttdrYUOh>m^esesfu4LzI$-MRvkGTNSxdovog2H9^q$+1|6zd zvTM)Sg5EbAu{55CG{9!guvT2tJh(D<%9VJ^+QVu5(j)>5@Qtj{NR&h$LteI`*3{aA z0Hi{{kpK|?J6#|h-HX7;2#S_G`ol0O9X{i9cD6-Px;}EaBc_8vqLMEOmhNP4jMhYiFGe~MF;G?roDi|p!E%( zo)9?d%8IU^3B+nN5SBo_PrOi|@?3Q0fuJ7G`5D1z`~M|C`}mN?zKv$X@6;MKyf(QQ zGwH326T#+Vtb48d#&^DU9>1m4jCp>NyP0J4TviicJ+?@+$UT_5D1y}+BuI_gMlLrD z#rpHcbN`Uxbi(wANVNh>Fb=jj2}l>c^Z~$wfm7u21Edfi0^w!7e45b?qUx{ z-afoDYkUs;a@8Mk70cbJYoPk^^^d?JqM}8WMT(1wFd%KtjT*t%jWKI~sB1lc3Ik0r zHDH75f491Ik${s&0p^UFsK&+{f(9(m`QQ`yhf)~l*FzwUSGayXYDsA7+chwim? zs{})NfR3HCx`*>~@k)6Df)Mbp?LGSUzQnH{%>MR$;+N%ok#XbG;z9etF+g1CBm&Pi z%CF@cRbP?|Bc=Ol9VU|3@xq=HQTqD)66ggAisHb+W|h9Zz{CRdq}yV4x(3>;@JD#C zt=z)a#e%w#H-1r@hs9-A_1|^>$CCf@oWHT8z&2Z;`F2=OT@mesak9}K_VVfMd>}9p z_@&Z)qx#fy91@IJ6M6RuSl($MJRC5Tk*#su&Hx!suAZvGR*CGePU6OX1xdwxfpFhZH*74wO8Gg} zx$PNLkoqxvbud++F~fLN?fjQxd%UZZeG8(GjM%f!#b-{b8}|;qapwfXB`Vde1%Q^xKPwEdR8(%(Ag{umz9%jA`c z3_6(^Qf}XS4&CTHO01YeE1t7vy96RTLXf^xHHfw1sQ@wx3)f%n@Q~#sx4eHWinZo0 z^XEiik+Bdp8Za2UUYc43%;6QCf7F{@K)C?Z162^Wg}$595xgZ}?{o=|!zUO6c19y= z<8ZI~=~iD!r4pba9YG5?v6D^RDWT@(IRDwo)y96#Kn#zUgSf7Nq;oyh`iq|k*0WTa zz`?xiXM!I5lZlqBI4inK9_dRw2-matkt#>FI#VBr4?Qw|<$&WZ#Q9NFXfTH~068{b zWyHP_A)8!SUY>4@|LkC$EGML^6AOyw1jnp~AFEB)_jcPf+S*pTWMrI=&E-{mUt;8? ztZxQ}g1sJ8ci+GwQTH#FO3OtX#L0>?G<=w~aIx#`80j|K8(e%rrzm8m2? zpww!tyeXPscrMtHR?$1 z)8BQ=G=K)X;#bWlW^GuYsPB6{kC4IciuUXmJ{lCZ`xwN~Ix0P(18Lur?Z?^e&oh4R z?5$9?8Kt*OUpEb6ei@C%f6HENIUv>z7mfW5QBq$FY|;Xv1=Y2Z)N@yE2_OIav-G2J z;osEUoI3$$^^JD)eu7;+W3RSS>JIXgH%WDXVcui~s7s{=-saisll z#sR!~&ilI0YSfZH8J9Zc5O5e2sUdXhaZJXB!%Vn~s=5S6f$0-T0yNxfQ+TFZZ2Y1J~Z-=T>xuZt5 z+TV-LTKm7l1>#~F_WvF(xyu*gW9pCvHdb%oJjhQ-)K5_ys#o+AxO7OOmt|Q{3=i6v zQ5F9jS7V=g_QQMXesgBp@>UpKfd0zTa*751K>3`Lv@TqNgm&o7($mbnLuCcHDtCED zdKfN=w+=>?8-c`ZM;w%Ojp_&h8r|bSqThh{@^Dm*;&`}l{7Y!eU^;gPB}X%SW6LtH zHR7ojr{Tj3FrW#=J##eos`84tl`*kS%Zsq!b5^GN_VNv%V*SjXVa;rhc7w8VMp$J< zM>KO(5Yhw9%rhHhPIoD!cFE0P!`3LOY{BP|+V4);fZ)Cm!0Il<64D_A)lrln81Y=j zgO>|hn%hsddKi6uJ#%x*bNyQYEIvl5UnEa6eEsqwxNdQ7;OViYUDS4&<>?mZ*Bop| zaEPvi1VJEMy|HL;CurJzjBCaC}6m_3(`NOJeKObJpsvB#0*~_xOKL!wd7avc)VAMW9 z>SwwGU9buJ7tqW@!P6aW@5)EYe~cHqUFoZ>y#D#M*_|9e3=h9EiIn;SwKi%SI;I|Z zd}t+zye8HAn#wQeN`N8orrO#NGEUN~l96!dT2gdb5MO|G>HB?5x%JKr) z)!!*n^OC4fZbGTSpX4{R&d;VVwa8~49 zyQans_5N3Tj!JnZF8N070@KgCfyCVDgHGYcWA>TVZ_4GYy*#~wnt){usRmM1kF&x5Y=N=Nb~St*N#>MJ$2Ns>1lPD)as>Z;D?RQ*2B0G%&$#H z0Hp0_(SMvVzn*&w|7t(^v&WdoemVGWVQpbM=-x=G()LtqILryaU3v6hkFK=1n)GS% z=%M&R|HzjvS*=_X@9F_yV`)BQh&)xX`K0aZD=BAUgAxSGU^N@k*QwgL;FJSJbBA!D z%N6>E6qdJ}oH3yweQWZmS z&OlIZYh4U<`k30txxJH82s0`1;|VWv8P1+9YJHMvMjrZ5*G3Y1?9;YR_2}*nx8heUx2~F>?b&@CaNUL?WksuS{MgHgP|cmP0HRpW5b6C}Q_ViD zRnDp00nL-jwojcr{Le$*^q1xulj9}mWK|#H1)xoS(^QCcB?=ILCp*QW;&CVIvjZF? zdZ(vnuk6Pg`>>}cuE8$1JVL{wf+E#Xf@XK#DPBUnV*?nP`P^{*vRf~&a5%A0qDw_y zkWdRUG!6JK$05$xoDp!Nv&u?PolZ3uB&)B5v;lKsDu^C@k%GS6Th^eI{AsK6yMPBS z^dPs9mLldPC_R{vy*6xLV!uGo|^ ze%Wy7G67%DR_Mps(Fp3X$kLb8`Tj(vrN%;Pxig&ho(=n=q2zAhq$`Da@;=HJ!)s)w zhuLgS(|n1hrF`kBb2(YmIE7Jlxt?3U?yd=Ln%^<;{qXYNbj@0L`~>%zooj2{`B{n703z{t*FyL+OoZzp0p8V29YsxXH;lX}Wt+F3BWMBW!cTGNb1* zq^s~77vl77od&v3es-M5hQDKGQYkR44bk3Qxs3`@m0ykQD{KKLlsGh zRXhVZdzs^um_aX)R)={WtxC(Jq6I*gKZGz+mCH+jh7*Ii;6ihmnph?hw@5~W2XAS! zJqC;aI)AtMH&pf=+wU%I#y7mxtAT(wu5th~#GvNfqgIyKGLmm(;KaMf^0^Nm*e2-6 z!8jm#p;q?-N!Bv$5xZ+kOBzXCmDy|BP{iZDxs1{)*gu6;$xqBj18W{wdBxA*i;m(V z(WkEb*+1Oyd3tnsQuDv3J&?8`rzPi(R2dS^!T_zcuxc}ub&Ss@V8Ulg$Y{3kKoWZYi%im0# zJ~J zi3#0X3n6`DlqdapeeM(FyaNc<&u~sBM8nU;1RE<}JuT|;P*4wCP*MfZVpRZNYpZl$ zvN=0MqG0^Bf{~n#o8WooKy&>9AZ6sVUfY9+qXqW8v4LY4;t`HSKFw_n@Mq1<&!K9i zyMU=5@r{a6Jr$nj2EYvyl7u?Jl-fdEEDGiv|y{jO8O+xtLGnEUo&j_m{KjgS6s%uvYB znBteRf|WQMtA`S9^_&;|E!LwwW@9i;L~6;k_M5!+pWc+{!w!{GQnc4do%Y}9;tnkj zWQc+K*-hT{rcAogBh7f4Q3)DJA>z`q9?CaCgE4e#KjvcO=c5vj9EYRmWp#HS-BXbnR_@ zDA3s#iFGXZFZ}IcTuIBTI!pEO@ljG5tteMh*Rr&Bb_fb+A|06^8A!3Ak1wQ2 z82<N1Pr=*Y2oYh1i*fN)?VGWRN>a=5K>FF347ZY1ycmOmMfmrF zfwz;AFYmd`Nr^vy&U&S6Xwf|`?xOJBFO_X&zQo9?e8R!>)xO^OpAIfXS_$FtaaY7f zLtFPYf96y+H6yy)I`cnD@3humU;_`u!d264yL#H1+dA>sIcIF#YLQJ%R@0R_e^|>{7fv7bsH1wYOJsL??s`0+h>;3MYoF;-ipn-CqGDZg%gx55E*(%K% zOOemO-l&1!hCMAa_8tFr9yDoj?cKV7iFDPtceX@KOlQtM7U)uvn(F7@G{3&n$M~lx zYVqXf>$$ZD{Qk0$Ev>Cd%(&X?5D3jL;q>+J$Mb#GD)?Pzlc$PtYpe<8QepPKwK+;p zsh^P{v9Uj-oc|06f~`7oVy&K;9hA1=JV>?y4u6cPmx#>!aUioc%6|K$QSf5{e#`V$YcRweXKK z=F{zsm3`(1n6E0RtFIHUc)*>E5J>5`8|~GeVQYI*nN<1iz3V2;z+wO5>#ngJS_hg`#I? zdJhStlas%^fnDLTvHAe+tjkCjikzEXR##gmAw1M*0Nn&LzZ{Cpn;3owhBe@D{{DVv zv5sXKZ~?=ge@`fVpPpkv&S^<-y8U5@dVgXG2NIS-`Vd93+IoZrBPu?D#aO!R7R0bM zqLrsQy6++?h@IJ^#lGXFTc1$m!9PTvr$85GFeTIh zd7a4ZKL<~&MLs}4ZH}2Lr`3;KSBDNbmlsc=??fL0A*aLqhf`EC|7?e>lV9z zQqUvGh!=$v5d zIIg*ELb)a5HfYk6=omYo>b!Y6=B>Uq&s)^FTkOgx@V7%L9eS?9hZf6K!Rgi;`94yL z(Ia!4oCLt2-tCCd)GSQ- zSyd8eV~>aI1^L4s|0I*oiSG?iKV@uu^s!S7D=V0aJz3^1DRFYzRN$+_*-8AViCW!O zP3^;vM&9Ebnw_-(P7F#ebv)IPpIzb>7x8Z4!8?A}yY)#bHQoj1+TMnnR@l}y4c69V zMJpBE)QnOrk%uk9#dDRy#$l^9O`DWdH^_YMoitayYD|+i53wEZoc2EI9pOrnC?JVs z6Q3aO*k^xis?KnSn~AD@0uYgky{1>u8`IMY=u+pl{ErCEN;o|8lc+vJmqnl2Ghkh< zeI=8bh$#5G8c?hi_eYDE)^)toDR{giN^*Q$e&rIAfHis5igv-{%Ogc9mT)vU^zwxi zOL`MasnlwDRC~v}ZXe78y^l6sD))xA#EIV#`80LIcQQkkl8%Cxpx@PmAehlHm}v6D z?z@%}&1xpoS0&R$^`IUrQv>^gzntGx9LEpAz!h8L@@LHXdGQrc|gx&a!43{7| zAlQPjwN=@7N90}P){@^;fF5dgf}u^_bApyj%`*edibkuZu{91r)q*3Z88^E|Gpc60h;dTAu z@bKz&7sRbZ2qRcPK?1kacG=1fE&T>WQ8!X#co^3RO6-cbl*lGh*fD3J*qccP{?y;j zTwaK!BBMkp;jO6^my<=8W+i&4CJ5r;-ayhW zx=nMBUUC`-hi~n_w9}W~m`4Yn>-uImIL)92=4(cuW3*{dsx1FXJo9Z(4JZgXRhP;# z#Gu}ON(4y>Co@6bD4FIcU`drju@!ax4fk1#U4PI+)yt*<-}c#_o*uzeT{}3blbZjR zmktu9c3sc2MuXl9_ri7_Di&%VY&OfX&B~&0cQ+G8S3OP5=uXgc=%@ScQBhH0VNr1* zF^>5c^}t$p{oj|VgfV!SOXKH(=9KjF7mbEKgc=#TmLU)w1q`+T_9!IcuRI#)E%11t zndILIfm$y%-G+EDQZ#9wRgr&N*%jv@WtXVLR~ht~4vdAk`XZ?pK%T~`P#HLM-%Hz> zCWm0Ni-t3ScC?t~p)Wlq#>lpP_PC7O%VDd3FgoZ`*94_d$kqPp8fO{wET`yNrsA{^ zx?Ay&2Kc*r74BkLsFzoSSA^=2hBsMy$X%sqmU3^nl0#Iv7sk-?oS5Q;7Ea_+NSY^o z`Pwvkf{Q1_iJW@E(yXs~1@=90{K&FN(PScVpa~I>eWhnlisD5|Upx)SW<#+V5)sdD zA7J`Dh>jneb=vX_Tbf$x|D7()i2`YxV7v1~;*giWTU$4t|5Ga2s0i593 zfILrx6P&xs>!XM1!->y^1D*&3`k7!?Q+NB>mz2(kQ^GFgkQC7!7aO~`Pb<-A*xhLb z_71+Y#_i3W$2*P7AbTg&d+dh_55DGHmA$xNT}^s?_7s!m@jRPf(wOPjc`!C;QJ zu0=*LBO8pE4ZBg&d?tnzg^Gn4Lhw|sMXX1%C|VJkzC1AzhPab_!`FiIylHSTjgmBW zp5X%~k`?UX&*!OS(Hzhw2;hWz-PHkGR${CWSU9%vo_74^UFqX#UslkMN7^^lzLzxo zk)<2D{VUu}=!488-2iVO8fgvY5A4At}I6 zlno47-}t!!EMljYy*Z6)n>2blqG_uU%x?};jmD?C0t#e@u_2eDJp3AFF6b*1k_MaV zYNj@#GOQF**7F_zi>r4@Rg+p)Hi&hZcMu9ILU>q9aAWB`&&Av zTS^w)v3rZ#+rvvs5_+z6zJ)OA(W6%$=*N)MJ~x<=(eAStf_DF}gM;X9Wb&C`qh+6- zt8gxg9lvXRNr>*z7SmaQNL(WFTMA)+Q3P45ptoSSX7^M|W=6_7G6NW0L3BewSd}=mpNOwkAG?)CD(BE&Td*KU5RBROc?qT&t^L;!w#$tbu}`y`5vhbZ_k??Tzi^lYC|lyHJnko`Za2; zSCiKBib=zFwuon4ZWkP%5V)UkL(ETS0BHYOUyZm;VG>Ex|15nwQO$#lL@E6I7WpaJ zHSlzPX6{6V_-}*S;MF|Um&!`pYQK{XxYK+%6kEtPocOq6#Y!17w4yM^dRpl^%U@H6 z!Mmb`9W`i0)9UcQH0%U9?X{B&TlIY?7{cIsCr@1T&cHdXa+61I6I?O%wWeSBE zmBZtq<{@9)bN5R=NtDV5?MMjiN{HkmPAv}m7wo8Ac7t^t{5fN4Q%9 z@$E|j(3hwPOR#R)zw0iHYIvSA1ba~*P9^Rk+bj$|6>-Qpv|ue05Auxk~U zK75VQXNH@Gu>I>i7J`P^4KH!fFY0wm(WNfo+A_1pr~Y}Jo{ZF~y73KfdQS7U#IHV& z-!^C@Lw^rJ065I5oA0>HWjE=AM09RO(7L@iu67gzBODQ@!TW_GTU zMM!+~d01nIEVDEf7i_)x7Ybxqo|l19p`%$!iduK?U(W|cpz>j z_Ft8hr3dNV?pGzG_v~==%XtNKUQU$uNaJoQ6VqZ1y6me@rXqVXZqpN1N3idjGhaWxHuC+PjzE2Efy2RR~#y^LCkTd#w=})tj_6CVxKtKgR zh9^S%(_GDiI@g1H+Ipjbzbltt#)n%lH#DG~fHJve_QMb!F@$bRP2qNUM7Yl33J2J= z@X$_tb6jNP9=R~^@tb#7_nC+DJvl2J98`g;aq7lHAk+!BTRQ9U4cJ>M5KX0t zFun4cT0;{$A=sX`3=c#@l}joS5{#oK5fBN=bm!Z1U`p@oc?gK(i*!GZ@r_0J-V!eg zDh_^qk+6lM{b%pvTwfjnP?v3a=tW_qKH|ZW;K|<2>Vl?v%qZz)(>;UWe>pk_R3=tu zrzPO7o_oIrYtF5zDtawfwZPTteNwLFkk~VD**u@x1&Rk?yzuw}5SAwdOe&~Kn%w{e z=k&$qdv#V=W}xASRWVoX;v>Z{Lpou;x?L248`|S-yWFx& z#A$8rI@~$rII>9f#wnBC^^o5)$Q{={ygxKlIk%5gM&DpHmJU1ZO<9XuV@mnCK9EzD zaJqXM6dg@|a0`GJiS{Yn`WUl@C+nqk)E8EoHm0TSUr$OosT6e)f#0{hMLFTkc*TY zDlWll#YC5)Gn@XBMthe?mo6lCjH2E;I7eHU(SaASz}$?{Jbp}5^AIpZ9#oawvUajPYNfj|! zc!byc921BqXDkAAH5d>fzbZY{REmiP{>coUq3!oJ6Qh1fc?PrF$&lpbih_%jn#m7w zSSGaMo4TxMd`*s6*rh9Fv}Vt?oMA3IX{>Z&ns&I2})&(RJ8(av=z3pyu@bEo6- zF44ymfamC-!~h03dJ~TFPd9pwbxxn3-ZU9YIH*cM$Z}0OI9Qa`2NHFTe#Su5!Jjp( zq_)3@u&HDg$S*LGReCy0>wbn8@*d{Y^}+6wkeeQ zQPXNem5Jpo8behd-i=Hb;1`g4V1^2UPr&*HmIr_=5~Da=;4a^IK(_d;^HiT z&xC|`ftYuDjg^)B-=2Th_s4Y(J^q&>>z}kLURhZ=8lF1>T5)%IZ(qq=5TpMq(b_*) z`V$@JF|JWnZkp2~H@N&e`m4#6UI<^Js->?lHX`vol7{uqdJ6F{R}}iC2x34nSYP;4 z76H;ruJ8e|p&Lgl#|JE}M%Dy@1oWYI+YO-B+VQTAE@Nh=pQfy0>JEf=yWe$n4K}S% zHi8jcrY7db0Pa2@JSsTv{)T%y2&Ko?z4M0`gnQx?_Db8mJRVFKP>C-DQ>_ zAw8~9@1^})*vxZ3`FXfz^~o;zZGAzdRBw!>)aGj1c{PuFX%jvb81OH;p@^Q=o@cio z2K_VXm7xR`7|V>`aXhA;`YEK1kGB*BNwH zV{3NP9Si@^(L3A@4q!IYyRAf!Sw&3~Bt^j@dpI);B!r6J?M#3gY#gqghQn2e-&J@R zlXl70EPN@=%G+|BdILmFGiF`jJPdVRFVFt-tABa>As=c~b1u3~XJv#N;Q#lc6`yrY zBJ&OYwm4toE|T@X)<(uhNV%emA_Te`xj3dN8j!NiFT`-?kbFMfgpuHY49;8sJ=UDt z$S(>Z*%=f5UEK& zEfH#)_gL8wj18fzhU4&XCr1wuu;caSStHyr4PtxZRv@;zc(AZyP?d95n2L^BD=yM< zsZS4#qj#p@a9y%3icN|Ft}(v8+WeD?GAyvlZ<@cinM@D8Mv71WIP{!QcDs92R*nD( zuIl)}#oqe=&R6&sPfm-_A)c{#88wgOuh(6E8@8(UG^v+EPY&hu_9f6AAG)UcM^a1R;8Hq)$g+vK-Jm!p1{zy51++v`_< zJaeKW?!s4Gz zR)%+$mdHznPWhg88o$^)IXQr=L;Y}2AB-cNAqpJy>Fur0>K7o>t{s{>IwI)nbi#J) z%rb8Cs3K-Jy`vY9b_H+j_kE)1N}61$0<(SC^Scg^xDR7GG3*{VWfk;-*fYQ!FIf`* zjW^VgYV&@tb1fE7>rmRe`IX1aC32bu*}}h1r7dIzJjvQM4I2}Cnydy%7P>>uMbg4D z&pIG^gUFiVmtminjf#CPhS_i%s0&yy5l-4DaS_@jF6jEY5dQ$e1dph`^tB-k&Mv3v zHklo%w7L{ZkW{j(q9eAX#Fo*jd(Y1Umk|0kAvE&6!GF0~o>#7)w4DOs(sib}o{p~Q z_|295@hb2O*{cXL?)w{Y7EP}dh4&Dk)#9KGG6c81f_qL#Rb;m&E-(=FWjwLDNakKJ z73}e?@`J}W5i~;-i-3A+7B_}y^AV^g1`*#!trfLBbN9oECu%kEn5X>ck~6)UdjoFg zTXAKPqzNBts!{W7=-ND>H}r^CxMN)PC!Z9S4J;fy(0jE$kK4uCtg-Yyi%cO%xZdu? zE8_Bsq0`y>e7DL%Z6=?W5Z>_*=j!(LzJP|tgxo9vCV~C8b2O~k)P3&)+7Qxyda4FM zzZwYDg~QO6Y!zUt10C&q&PV4&t+DI`g^b3I=J=vBiYTQz

    36`CzH}-+|C(X7m`JPUf&JnDGOb7f_5;p(sJI)HfOHux7EtK0(56ieTL7Xqk}>l$EKFAbY%0#(KRsk2)iU2I@fy zZhg85?^HrBSv?pk^>dCp#@EQ86lHS)TzgCqM!alLqR=F7=Ai3<< z8XLZO56md~@q^HUn|9I3u*>O0(_Ny83jfHViC3Jz84%mDY$o;ZPwf2d1vWHWWPk>< zlEWI&s+yAM=<)11E5s0x!Y}`&Q2P5-^ukx-W^zc8=R^q)hnNd^Sa+A=}UbMuN zY9!yYImXm;=&EqH(3~sGNtDqO?&lZaerr%kQ`6Cg6UbBqM9kmhsq=qU<>70Auh|9Y!ayVv&jYT!UO$e0ea;onZvv&EKvbuje-KFpvLa;fxPi$-UfoU{Ln~u zWNdi6Q~kHHhT`I)Vt_uZFYKvwiQ3oKr(~83T=jx&WKlu(aoc-8MM`=ONsc2WC7{4mMfh0Fnf?HjcKt8*2071mq$YYX_F|&c7FUak9%SO-+S|!) z=K<3x!#^95O@zk%ox;HIj-t}L(q3A+NMAIYC^#mFcux0@nSrz}2nX(3q)YgHJ0f;pK-#n`E9^sVka=bIylb*azHv&A3N4d&_ypES2kMf8H zk=XU7{UTAXWoq+a8Bi4>u=P^Hhd{x)1^1JKldZ4z6HzT#LrZnTM8`%3AtnJ3pc-&9 zZJbA67@dwr60o;dtr_a@0wA^(hL#Y#J^s#CY}DqFLEDT6P%~%1j-K-n0ndH^0VI0( zo=bwd0eT0HaMt5u6$UCauNcWldH5K65qx_-6ORr?J>9ybaGfMmh7U<=`eao?%CBu1 z#})iJ*g5#se}gJk2@(BaOlWN+Nl~%+a2t5Vs88cvA-$K7y0hj|l`Vu~=?a*K>D}7j z-Z9m!!MGhlaBD%H{6 z5xw(^4lj1}ufP}}tV!q_AgQzuQt3An?Z?ywA16gnfKhK0$)r1vrJ`+#xGh6o6i|(m zdCKr^9$C#bT!$A%8QS=vFQ8npip0N$7z(dPwwN0_sm;R9NaQ_a_kbV-HE0C9K@F^( zMRgVnk^lBg^0q&S)%yC^;Vlh<6JId=g8al*fs(?*->G!*&&uXC$E3zkXKIZAYA1P> zQ4h6g83;v9$utZ#1rsk2*&kVX6D^QfND^=_n zV8=-euEzj3sA|vDJWOl3*vSE0cw2(=bJx;4ywA>()T>(>pV)@S$Jbyke)xRYS^S-+ zPx|aHoH7L=&FfVJ(PRCtp7tRPh}7*^YL+Ez^#*2(k%4O8$x*{e$#b39gzt0~jhm>( zt)LK1pkpd7FW117GCPc$-S}5p7gEi+lg8foWk_sbdieM2{D1(KmMz<<<=87;K)OAV z?Q=&sQIWke2{fr6{Gz;Q^dSTLohhXzOjEGH0P)@&8kk_#)>i(GaX z8{VOw*6s#)_pTw#UMQ2*E!Jkp%1W(eWu{|gu~M_?R5y)X}K zfAG7zvIUj(Lx6vpht9R{gP7tif{j=+wy@&hljT(Cg9!oJiTH4?n7qaUb1P* ze&jqgo%qic6l31foH%pCOo1zC-YILb`RL$Jt4*ct6NSyq<1#!xzHL0q6zR(sNxRAL z3x_9h45A~tGf|QN;sE#%B(4crMMx_5w%nv6Eu0RQJb>VYKv%FO!fyE-#Gc4$akF5=!LtI$oL!NwJ|p}= zsuTnKB0wHk*8`wA{OXQRJF-=-en;&A+I1Zkv%+^b1#3WIHdXf|sV6hPVVSQ#wMQb> zN-bNv@zq#DkvY0K(+}D^XewZx>PKFU1S4N5nWQKv5ZzIELubocWQNqzrQPOx0WtT5 zWX&L!bHDhZ=$Q$d!dv8c2}K|LVVWx%(%lTaEwHyE_?x#$c#;;n@yu5;m&LHbTRb5o z6yP{?KLY_+b1zn%Q%1zx9c58Y2IDg6vc#;Wa~xl;_?DMrtWDKuP2MmMq%_c*6`R-c zV`>)wF)V&TVNm0}@mNEw-c%!#~_rG{>3Fw691RFF)ubQ?@tX&jhilTY>%y_R-*V2xD*_ zIZ3Fb_?orSO~(s|8vOgJMyNq7vbtY6rJFvBeEut7Tip@;FE{j!jE`FC1!7Wenk{PPPtzB6G2gl=3ndhl^Nr2h1@yFd3eN;t?c_Zg$xKRwt>QkW6(`+lkV<;gdxQA+1x69a$t^N)o%nc{f|&V+&$cz0x|92YMQ@z~ zhx=y^Z)#UCLKIuwl|Gslv`$^_T#T+QU0GUQ&B&K;rBD3qrL6oJbS&{|zsQhSX~R=B zsIj-MsdL;fuM@wsP`e#o{1G8<(c0;hw_Px;Ah$!z8I636zfMZnoTBOMFT4CrX9wln zW!-G~{x`gK^#Q>)tCbWu*?;m-$6|p>yjG6o5g$BnUf8 zikeZ`+IR1~YE(8r`88i?#5%6TlljEo*W%D{lFuN^`@F=%sc#t*3)}s4Ky5n^>6b~h zbuzE&`w0P^rSY%K?L%Swf-8#G{ zKC3bcK`t^Z^Pl+{q*fxopf=D{j1TCXg?Y@7@6rl89`x+(0pth9By0DgRq_V-KgGX) z9d`lISu?!20z0(4or@`zrN=jLOV$MVPpI*GlHV8w39GG1dx9a1P<=+>&^16}6hvaM z)=x%VH)ViA7(rBQm!gVm;(N$I&Nn5A;b<>;7cYVdr36xu42;mMSXJsVfs{zYjutqM z-}jEaS$MKs*Z>iSJAN|xL1*P^j;i~Ya>%-rk=eGs$nD}ZEC)R0w`W`N{#m!_ncLls zxLqlf#QO>~nt5wz{|FGJ(;6)35=^OO1j6XUmz5@n%V3aj3kZ~ox$)th?i}pQ zE#`B{^S6J4+OnCG86dq-F!!at(dDPRBt#XS)EwJ3TU1o!ugW{1Ue$uDsjR``6F)Ow zguyDD3NNz#X$_{NLi6bO3lDKy4AK?B82#XH_-YNW816t_mRVgrh#SU6PXRTr$!7l= zrEg=-9A}4=nB#ib`H-)aNw%=Vj}9vT?<)14&E#Z;0b(MGl2P`qgyx;spY`Y7In!#{ z)!pbgV)<^b#+t?#U{Z=@H>$)r%><=`84Z3rZ_GSABZ(3E3dn7|ji?*TI7f|Vlby3e zTMnL1row#Da)@cO#Iu*5YFWJTjkc-5FC|}Z+Uo}v$X5^GA z;{jXNKeW#-_q4fJ z+!KHBZ(t(Sl=%(Am{h>bgLZ_2#Z4G%j@osieb}ti7wbV0eszzI15pnw`v)m;jG@g( zwLtTf#N-QtU16=0^fO>nZwRbP(Srp7)SML4+4bHdE`UY&Bh(b7Q8&2Qnzg9tC2t<@ z+zM|eI67zaVL3`F;_)58MXjSm_B?j8nLzpyg-kfs&WQ7!f%(S0^(2VCX-_x}FZNkO zUfU1v^v$H2YlZ>>Z@-`X#?@fYK3!5;oBy>dqL5Z^Fb%|cCR(2+%V4cXh8sw2lMDb< z!POyClj?GxLPKAt$?fQ7{~0oZ3Di0JEZ8~ElhYv480gygg1%+_< z>Da47gNPvj%PV#5Ys|l5TYyrWJ-vVH)oVR#ilW3B8jJK#QwJQb=HOsc52E-AJ=D}u zOlpT7|9sdujqQoYi4<=eX6*l6ZU%M(n{A$Wvz(P)!VH`1onWFCkBfDk; z$tB^GX--F5J$hpy3ch*{D9;6k#=e!5x)wh1YksNcxa~Cl;Gk(*ZcF#Ue-T6+8Q@2I z`O{No{m3)!c%+LUza>B`K}?iw2#6T`nh85A#Fa6`tGY86wYysBoy^KFW5BG;w@X!$ zbKE*Oiq$CGNj)APAMcO-sddMq8CiEgaOMF>T?&!q_cVAm2j13P{rIB7q%@43POr@X zOyOeWt&EUAvIgtg#=;r?jkA7b#&)K)HLhrTc*xrXEuKtX5ANDUTEbDRb|G-Q0}$bY zsQIO#$I$D0uDDvdhOJFqsdIugXV|XaL)_}_p}b4?!abJMviU|1f#G~J)9olR2l z%?A3PRGlNYV%8IY+E&tYFzzua63zI`8;2^#*wWtSZ>tWu<9}F=cumrpGiclok2QAz zRx7t)3`FB;c^*M)5d+c{j851>Y zauf}HSHIpce17SYI@MzKh^lkcw?*?R+~$dUSX)^yv!Cn zP%1U#WaD!sSZ+Zq^UfFbwHH5~PH>u~Z$+6-)PL@*x=vid0+BKk(ks`0nZ|Dq^-Mb@ z(V$zf7*UJ4fD%GvH!fXiBo<;iq-8}_14`Oiml&Aem|*&CxT^JoG6i6sXoYoQu$eS$ z205<42-Z5|y8d8L7;|1&<8~>KM@jF?DLZ5p5K78#aKSm$mdX@#ysh-))QT34%qD7Z zA$T~1lFgDIW)3%@8L4_c(k?yGuk^Fp49!fEAS4*I_e#b6h$E)=^C=O<(6OHZ%x^e_ z)KXzWd-MEV>Upo})@K;1b9L9c$}s1^R-Zf9dQN{D33~H8bw$U;MKxlF^O^x(5ysZ? zVL|yV*Uqbqy`Zl*y~EVQD#EJ%xS}r`WQjf9txpjNzgbf%6&>X~32&TLr)_psVLH0I zNn3SwKx&9t*!C(8vsD~y<8bkfSULt8+wAPi&+tNa2xCh|3O&RzypPW_5&qM02WgPC zNoIIM{9XkVnJHbXdY=#Ds>N;vkyP=W#d7JTq_NK)Tl17<9IsJwqBm~^C$wWWFN~UH zBDhj7TW+n5a_-6hXao1}Qcm7#4X9JRMR{FumKzMY^%?`F<*2o5=>%qG*$Uf|+J6Cl z8&c_?I|h70MpR}l3g7RXxiVf*xj|92xWUINE$m(J zh**Kai~%bJ|JIq5ls-#W!?#1^#4u9(`-ignKeor5)@8CavN~rUD7pa0XEjA!7}=#u zTfSznW%ad=aZL4Chw>Zmn(@LI=#PyP;advCqm5>HdAUkT8D2%`x0E^|I9p;$=X5A= zrnNE=Iiy>x9M-PG10WawX$l?*O-%hcNN49&Yk{I0lb<>Rr-*6ItKf?i8Ozf@UJ1&@ zD<&0foeO`Wqjo8p<3o>GUHxKWTS|Uy)NauT@f}lsOIvWKLn+IboCxiA9mR~2$GU=S ze<_`Uz!c`E1bf*^k3R5E6PGNPzM!A*R;Sz9l3sZ<-+R33C;r$E zr>>;|4Ck#gQe^h9o0hMw$pua`stk(b1>xw-| zS0G&(8T*JR@g(Fo$lu{(CYjId93D$r6<;^3zz9crpu-+0@jU-T1!Pf;E=LPqn9bqV z|E_KwOw>B}jKIn`QS+&(F*yTj7GX~I7OUMyS+E;;%iqAG!XsQ}ASymax5cx-)ld zbxJ*5rwSfFe5Z=MT-ZFst#1uU5>|tt*vZvblT$CvUcANpH2Z%r62BSXE}eN`yv3hK z2wKMt;KZ0k-h7K`5UFT6PdYvTlu$<#zFvO#T5Ry|+mPNER^S+!l=wo#^}hlQPB;asv)Ov~+|oM*R3-8Q<5^1As8A-ex4ik3NIqsT^8nMl)4AK7ys z=ToXM`%v=;fORDNO>OsR(F_c|2LxNh8ZEO?ikEIBDbTw(&%a;{G86}i-%8oFg@g*E zT%7;Y@l50~MK@^nF;tW@(c1FL<)p;0UJo_(n}m?v`cLaC`%|GBVPxBMq>1meYo>pp ztO*K=${nA=TOoA7+xr(gA>^~?$Phrss>Gf$v{k6kgq|7j(Y z`ucjQ$Fi9Wx>pyATpA{U0>9p%+A}s|hne%jE&dz^Pq(^nJUcJElo3^M-+u<|ChBoAy44XFhm=gyFG;^H-|SVjNP(d^ z$(p9`=C#a1_&;ST=I7_nIQ7CZfO}Ge!$f#n;Y#M?-yfY|3PEzQ+(tXSnpI^F@kkoM zdG;GY*UDtMNHFtBFki00R2VzPmNYfr7o;YJalYqF4!iMt8Lw`tW<5NXvh^;GS}RktXnqN85O?{q#M%?Tx9z|xKhiL! zG>KeWUA@M=)#`tEtXsU>I+GnHEor(dky9#rmZNZ0!Y&IDxYXdnJdoGF^GG{`dQYJj z2G6eYX3^&RE2#IH5E~gBb@_#uck6TjQ{SkccEe2c>3R@hTB;hmJL1y)4(rTDl%NuT z7qDcoIWwNv0X;b8Qvm7NO+@MFsQu{dh*rMx59fX6VBka-^dlf5Vy>h4rF@Q<@GV2? z8_WA{GG`1QbxaEWAOu&{BQFFgciL;Di(C^Q*7eDS13%-RV+ zuwv361LrB3j3v@)CsS%ws!=NHmd;ufpnta7{BpN8*KbC}WDEdaYK`QG*_$HiQsO4r zcWI!c;|ckA39#TrfUS+SR@3_NoVo|#KWK%jmbcf@!E(QS8mH=OhlT)d`sf>?m8F&T z=~0G5gFGWc#a_@?FLV%5iB@f|YW4inv1|ssbo;*2moZMzOsgkGjay^JDc=~976?6` z))n*B&=nOVxAW{$RWm^7bikSn)VPaZX0z=Iqv2ZdpnqHP-FNHrf_a`xlqp#p93PQz zGeZ*^me~MumGDl8Az-#cxkTR4Y?sw4`k3-a`FZJH8Ea4e;xX&oX<+v$p`>evD(B8lZ$I6fOKW@fuzI-In&O&1ArLf3BoZ3^Nf7rlPVes?9@7+p8 zf&Q$Id10lr#&eR1u(UNz>p|r;oBzuKh%13?EiGp5Ihiwmcz_R}0|e+>dZ}L^y358! zjg9pwQfI!BzTRC)pKTRG0W3e9=(Wp{sKmLkw~Qe6^C-r%JRRxsLQm!iYnPZUO|n1g zr3a8j%0qO8+0%PP!NRCMsFsMht(3I>?yRGSl$Qw>C{UfLSc)b_q=r|J{n0p7^1chAYWPX=;>-WR!QR_Qr1V1!4S8VUU0#?)glUq#>D7ARMj`TaesA4XjmKZLQ_Zq#*WYOpeimi@ zCRlpA{k|6Fc978=&wrYguczF8dr6wF@`Z1W+gI(3WplKz0kWyW(w5%&szsh5T>WzslZ$~>!0w}yeR>e27 zOdWY!$ilA0i&$pR-M~oOsh<2}hsifKMO4*nI`Q zE55)zZ|@D#yZPBo36oHs>ium$!gu>HM?47`h@4ca_ctF0=%I=1jkES?C}z^*b&8Yo zy?%{6JvCa#pgOhABO;ij@u)DwlKJT^>@GtRGi5dq4oBpA7KmAlE0C}e;H==v7R!Zi zOo5%fW`l{nQ2@hZI|i1V{YVLhf-3AujqyW29)1;nj(Q;+`Q~4Eb3kDM^dnTQ?AGmd zXJ7L4^xYwYa`?gCflErA`0!^7LvYE-{Yguy*2(pgb|N8rwK;p1%~rE)|IQqF0X znINtewmGiKfF_CKNqI`i@Wu$9>#4omjQ$mDP1(}?1 zw9-7;ATOXDt3`0OkVySxRHc!J!by0W3)q50nc>)@Ea@9hUZfKO`X3eHWy{DbJ0l zP4(*e$%-D+&hiNx3!d5KIRgR}b@jD>N#Buv744o8^;`BpNW30lqdY{@-g zyEt9#7B1lAQ#c&%RdlVUsm2Tp_N@z%l&s2_kQuYFo2ZhMJY8}*rq7*hNoIrzvsYY? z4|@0M@w>QPXY2#>b+JqyJ4MTT3Q;-?e;T;QYw64G?UC`}I}80o7LC+oj@KBVP<}q4 zb$AT0Os1!4tKrJIOfN)5hq6m=lZ${ir^r)V#&VhS1L_8PQg{lpxH`=?-QA%DJ_I>S z>*T$u|20^w+{baIfDD_-V$2L7PPZzX{!uas<^t6KY56&yiScaX8QWfbZ7+G_bZEjVti zH--!j)mOL-t>EnCeV<5g zqs!91X>cdgFlX1|*GD6)o?qHjx{^s$4WziE1qF*%tabpsGQqK`>adKUl!>=>Ia$7{ zuOX0Gfr(iAv7`NwKzVrT+7w~@>Xs0g#+o04dh%Jh_sfm)_?lm`ZlM^OitJX_BFLEMN_@T8ZrXhFLd~f5R5RuUJ2V70534?hVswSHq2@u9KQ% z5x59jBkets*rd|ZuYdP72s@-tPtTz)Rq4T$Nr+VAR~Ouxr!nwcT9ogsPcxUTVeq}Y zMaq3W0N3`(n_Y{)o6ti60WY;!^EPHA($`v zEU4mJ{dYY1qedlK8kgSm<8OG_jFLsI7!3>&691@#3p)Y))6CGFgM}mVFo&Ku#9lgU zySd4`)zklGdso3C!41)d8XJD#luvIH{K3$I9dbgnJj|!(-Y%>F8a^gGItNQXx3`a6 zPxo|AKJ{p7bZh_kLzkH zA^LP<`w?V~h|`mqlB1Jd)j$Es>gccycY>2n)X}hetCn_m(PB!J?^(kX!#*KSvVY|5czM|?y@JLcfCJ@TO&R7 zSXb;)=1-uU+csJ$2%4rV8=V#yYZVjEvgJ6-A9{4IXNB`p#`2U3EPrF3Vaun ztcAZlYK%Rdjp%L5r^y%JjQ>@4*t?q$`RLKRmo8j0nf^1f7P!W;(XU7&s5I2qBF_tG zLtv}bhB6ybwqjD4-+93+RF{*>LXULMboV|oBmOTU)}2QEuI`BG?>Sn^X=O$wf3x*< zf=@8bMJ2R5$&MMEOX2I2w+kBdOv>~_GxzVH}e?Sj_t1qsuYISS2@tP zceeW{0Fn6NS^_k=Ct>X*KOy?%gWL1}78Y_NCf=5m6!X~{Li$II1^NCZZ04+8V9rVT z=@-1+&z*4eZ`=yV7G?x??=P+FZ}t0}1*>_XY-z{!-yaEMpp?VE4(n+oq_jSdxCv)w zYD!-pVIwFsC`hfa!JZyA(~6Yg_okhJnnxojLtD;*Np<$T@8>&uIE1l^R-S7H};+$aF?ThOAX8p0EmJ!i9`^#&F!&LHuy&Ken{f5^ffsTE> ziQ~Qj?DU)ngHV00KSMtk=B*Hypo^sffrggF+QSi%gdcFy=60xC5g#s$#MUf-V|x_l;WKmASXlOYk%fNGy1Qg^rQVB8^y$|g zv*+pe?q+A-WM;0XLE~tHAEuZWIgk&X>@d_Uw6IS{e-&`SRYA0Ao$@KpivBa?NTGf% z8jt>0)IB{545bORTnZQV3=sXtP?$B4qz^6}xowO>RXsBRrQa}Y2ml~uO;^f*6pz?f z{iN!kYlU4QC#yfkUVEJh781b%1iH1F?e<4s9@q(nZ2tZk*fCq1%N@M>H?>S<99gv( zdIA0l#PgEA7li;OY?#d>@u+TiXvceX9gXGf@!o&K!h>CF0W-}OYmXQJ2v!0vw*&c>YMALDRzY3($NKCuaTOjmBsB~gx`@Qz~d3~T8m^fVO*QNS~ zVaIEx=y6|L>dQ>_Aowtlm5sCz^77H@0rThwkX5qxr;+q6Yx|VfTV^eTj=5#~NnS%V zja00CS8-~1B$tcN%N%b1NYz;F5ddsWG{plkVvp2LR{f9nnJ3354;eG|S(WyROeZIc zH+B=ivZ(9i_+Vmr(!2S4?NoMem`-?@(wAcG<4fbURn_XrPc!5h00{IReuCU&U!ZXA zvS)l+Q_$J@k#uv}M)JG#m_6=|70*Qp=2a9&SBYK*qQI+nnuE$uI%IL0kG`K-qlXz5-}9z z)o+)B4Z~aiv%LMFBkXZ_!1e9|3uEA>P`8ou7P@V~tAm{!Q;X8IK@ zlH7b8eF{py9|MABl+sbj@#YC8fB@y;l;Moz`Lv^RIKOh>Kie6gwA6p(jLz#@+#6QZ zIaw%qvY9@?@Uj+MvJO^dy^#;0M!K1`_A8MftPXPYXdiQluLZZgLJk&gpOe89S9k?t z0vaf}qs2OfP9tyMz6}usWWMUjIH?DC;QP;vp~p80DNa#}TE!qm%>WNNf4#oeM;sY8 z#lfNvj{Um)wp=hFmiO5FXSV7gGl1mbVOzZ_xk$ZEpvDOSx8lJBl1nPmm z$-dvCrU@s;zFLABuz(=o?cGz3aqJHM!!%z1n-Ttqq&dfFO$R!ode0WG%`i3+m-?xm^Kqv_i2U_1xrteB=mL z2sfy5w<{eQmzP)#)gl^(^?*uuo&doI6F{D}3}0E37X?Ugx*>PL5SRycIPvv01a-k{ zO#0cuH0;$&&*t%`cs%T-OlJ^Z%Ckde4XnS-(zWQRK@L6_j6f z2Tbk6Y?4IB1byy`+44hW;8Oe*TguWiXqAH6#F!6rzmjYpfWWl*)6B?1tN94 zS{E8@a03>Cmmc2M1OZ`)t&h5|O;dobbwVXgxM%AS!0SHBODXK{&mu%u4EC-{iFTGo56owPv*CF4ZOC0A9i|Cez@wv^UdFo+G3x4W!idV zdah5rNv}od02G{gHfm>pPxJKHsvEh9aD(|fu$q<~1Y`H77|BiVxfKQd={_m!{>vhM z{Yg~#W2N(FD{vldK4vx9@-=}#?R7MH(T5MBi5==4v%agA{i5Xf5NJo&-$Dk%s3#;^ z|J=hqHhw7s@8)x&0?3%u8ZeJXR;fzx6?D1HgS2Cc? zG<-i$7j?=Huj*F)E9a)|i2{d)1B=gk=3K{c5=3%kk>=FEhr2t`H1ep`se5yNHlA>? zu2FqCr(FlSUZN9mxGu*W2Qq3^sfi3sroL6XMMQlj`1sNvXVW22p-OHua|0@W8Jk#`_*!xw)S7%Gy=~_A)KK#2%^UY-H?5a*AK*nBG z6*Gsr6^^7qZs*#Phrw*@z7%rPB_K9a-6M0{v>>=3F7}4pa?u-nPKeVrb1IY50BM?A zi8^g$3jT1XzNKT~EofG}J) zdH_YaX9A8T6XIPvVZA_jTUcN<-W-j52hny_QgsDmxfCjPOrT}h({=9}%UBTPE#Q7k zBW&7DOn>UPbOgr_hIh}a^TL~naEIK9o|R>>i^SI>++{!_b7dMHibWVF<6)_OWz6~jglqFO1yhPd)Y z7)gtpedjDM_?~^SXQt7_FZ+d}3c=voEEQ?|d0K7X-u?C8huUcq@+*YRRjqzwnV3Tw z;7zx~ZB~Cb#7U$6q#L7_)kkg0Q?J418Fp_Ej-0dI0WCql46k_V!I8n>@}iG4J4bCz zpmwpNvw2N5SyNM6dkGt1iaUL&6kZ1`SVrzQtep+XCYq94j?0+QTl?ES$QL%Heudgh zCua+NJ=tcoe(9gmek2fEGl1!|m6ebAWS@E6EfsjfN4_F7Ma zZdwq|q!4#w->CUt$LueR(L5uwj)X=_9`=2`$ZC*T&rk)ON$M2%v!7u~`g$6cIc{zp z&ih5kjoA@UmanHL+b6kw$GvEa|Dhs?^H-Mom8|#jixVd z($l*zo%Vj<3eJQ69cK4+(R6qjkX`{Y{J25Qu)373FqEt;X2=J#F;QryuBtXJ2S;F7 zdi~E`=7+GMKf+%ZSsbVC{JvZNlIxy|Sj^h-K^9^CPsIM8!K^;t&=AaznU?QyXPsORs0!ZGz z&T4O>dWEl!OSzXfV7|x+S&3sd4P1C|Wn9zz7L%|e7W-j7q`Xn(7V@+LvWNcG!j`GloX+75SuYyrpNN*2a&j3jwSK537gnbj&_d zr&-q$uHpHZq8^{2Zgm2Vaxh^5zz_vzPb#|;@PnWTv~+R~3^85ZP3VR;fJ3FfRkXCU z_<8_O=8V5l+jN^X{s#{*9!GotA_K#+)<4XR{v}4D!Gn{54d3hS{A|Tm%|**n8`$9i zfB)AyzDSs7nGXLT1E1R#2_sh+hLlrh%=p$v-zX;%<5s>1u0-pB#lLC@31yOgSOl?RXB$vfHoubjDr_4!=p6M zr|W~0zMeOh^(ky;)It&%(}!ba{^dVo4q9U(10xuNG*9;Vl~yJq&cn7dgsA{B$ox-B z^k_-3Ylrt_>*Vmq#GKX^3mXh?WdvW=xqJPFNT)0Isu7$E3Wit+zxmd3N`F3^4+YSY zkzf7Cj4=g$sE&5hdtU?~)^`MK@^jic<7gwaipTV~W-n}WOUlPE6Y_TG=F)nZ_TWtW z4GFPNz73$>o#!-_G_I!>x8`6{AQK;R8NJ`7vG^c~xu5s6p72V*43g72B%x(-004~t z4?iUd(AQQF&np=8v-0Y6_UeYRUov2@vLaYS+^&>zf0pDPh)uFn9HpsW`powezApIA zPwq6#wCRjtRClAY3xO5bGHrWljHbS-t@FlMPP$doYyg~^=VM#_;m=CGaV+u zqQ?UQ&=8O)D9>|1hL`fjvN-ybX4j)sjBUiaTTsbUDziS#aDzuD@4J^FBWZ$f5x z&lhu@QhOVvbgLDstf%646P$?-_nc5k9Z#^jm+Du2$z0&o=ZokeniOfHslKqL<}xkb z7=lJf50ygCa6(>{E$f4PoWQWrAR?UBd7xiA#h_&g&_!vEDA|NHsERJ=6OthGw1L3qc|)6vM+8WS-~)1-Uf%v7qfa1#R zjQg!u>!w#v*M(3SUKQsy+sJam<0_`$r(>?)TdvXMUtBc0Q~bd8R@j4O@*UzG%J~YF z`&KB7xWfdfC$zN;Yg*Cn^J^sH;L`1A;IhlQydm>TdA+6sr-Y^vn`V1dg_|`x<|Mt zlyGGT?R6yq7*76g?U>^}vD_D~+~vG_ytVWvumQm9uD(BoL!ev;IZACG-2t0*S3Hlr*Hz zjONHVfI_f|iir3W$-r+@!)kuDR85b@{B@&i(?tpX1??2YD?*o%fYtcO5}y*A&{N2R z3nB_BuTcJ93lK?o3F8XJKq?a3cwIv(>;2i?a3AHvVGl&J87!?8^5acx4n9zvMGL@lthi=1=?^YaG0;Lb=ZAN?zgt zXI8IX;15b@^PM~NC_M>Rz~l{tC1$fU_=$i&yi{~tqik0y*P*>tL?6mZd*T5w5A7Sq z7~b5AAc9$laM(bbUQg_u*3`yx$1cUxCga9!)Pw^=cxN{aVQe8|`72-B4ik#0=j>iC10vlN@YH3?P*LLySQ+I-j#n!3Rjgq?51s7EDv_Sdj^y8`Gjd&tLwr-;-Lk* zEU&-TsQrCX+`M|w4wr+C8{CBP%W{Y($gvS&5})+G3Jbu`2EJvXXL;B^exh`iH(s6Y z=q@i=)6o^ilCYI9@N5TOkp@dMes!PtdXeeGLzDkj>LOqRRi?evojHYW@is?kG4axxO zc)W!tQ14T!O>yOq9O!P=*kGKAtgxH;tqbC!xfrp|xku#DlIx2+)bLGndh{H?zn#24 z2!2kpPU2giY&psCxRazZth3WLdSO=m$qB(lH)8EwRqK>cULnKh`Dcw39q+1G_)UHv zGy4UnDWg*A7R-p|+gznu(;TKVf&&D8Avr=G*dK>Kk;!(ur`#f|$`O|w)XL|fLfCaE zE%Yveq>se|<udB> z1m@5H6siIRDA0@+lagkDMYO!>HCh}utXY|?Ox%#aKr)NRJi2rAz^gJF)mZyTMBJ(1 z0maaSC=5CT2b{HdZ5p4?uaNIrbW?qT*BI&Q#C zY{J!S4>^>TJJj7KYfjvC*B()(?BKWu^M6X-naUUA6DUF`fWX3%$YKw*G+zBJt;ooQ z7dJg3YAUQ89i1JI*AjK3R#s>GA}A_<0chHbYf=X7(<-);sv(=rZ=XDcYd<-3C)5>R z*PWiFbOdbXjsxj2_K(-+4zvEJqVPXCJUOJF94<}|zn3@QaoPK%2!7ff!6a0wr8X#z zj;10UUdUUP3nCIyCh~af!B136f-A?WPPtO5XLUaWgb?JC?}vr8G-}zuwbMz6xU0o@ z>V`Pa*HcHM742U877Ld3YV>rM9 zr6ZMK&;A^cBj0929RI8`Pu5Eg12lv?K$LA_LFJ5N0H|v5T~F-+NrMh_uabJ1p6KeN zkLvAIU)Hk|uI11~dKy`7LY6g|4elYX)s zb3AuAJ33cWSj?>;tvPYdK7zLUOA#nC!(z6nDOp#M-=`^euhhq^54&hb9j?8J*=giV z7bE=*n`zpVWl-BC&RKVAr&U4mWmEIfmY#QED=0*6*|M}v!`dX$K8;dD}~ z-_FkkcSpgF#;TuR{zg;2f%LF!%HkLE9Kj0NSXj8H?B}i(!j9%-QDa=t;GKGbK6U

    vq=bw%^D)z3*lz7SuOo@`dqx3JV^r-H{=(#td?ba8JD3nsNV^+U5z zsEW3X0VzJYiaCJK0eHd`6kN0;sbNJ6Q6|c)y?XD(MFCwdoS)_Nr4LX^F2`hM3^UPb z;!6EnV~++$g||Z7MeZ1T$+!%Z$w-^KBN5uPV4QeR&s4A&RTv%pJ(+y5mdw}-{#AQ{ zh^35FR>=(-COy4Mf^H&M`;2+vVAz0c8;s8fugX=T^MsxS-ImRv3v>9lE9~~Py@C*e)`l{; zqNnm*qj_4?oaTlN_yDS1$m4p3Hwa?ph<6GXhkBN+hl3O@SKy>x==@n(>4y}y+(OYY zBtZFPHn-!H0?sG%WDW!v_?XRwcnS%Xje&*PhDtEvswEjRC?aS>#iXO=!zD3DU)!;rf>Myjky7**oh7_`O}$;dyu3sQmB(w zp;=CbjG{$#^(lAsz=-#C;dDz2i@C^?se}GRMa5BUW69nhdT?oa8m~|dWA%UkqJ&<9++p&)qxu5a zLYI^6(dufMd4nGHLUTI#B}AK^4WwmO8rnzw{8w(sAo6=3@p1-ATphrtG+Cq$X}D=Fw>6LK$_S_ocY8wx4S5$jq1#Hl_%t|5dr zB^nl=YxO7G&Rr}^OeeV%XQrb~&O%FL4249o-R$hpr%BcZKShQ0#iPqVbhPd)D#ov0hlQvTB0u$LV2&qcu9M}0}%La_JlHi-r) z;2Z5r-LSS!uu@zB;*?3&m^yI@f4Q;q3-|efOM)yf8=eO!RIHIELoVhhSLT^YCcMNN zqhv^J@8KKrZb{~|P3BtpBa#L%OfIm6Hiad^{Bp~^a#_DV)P8`Mwr{CZtyvt`$Xm=8 zLI+jEZzk9J97x&5&PN9;Jn%ZNk2jamNqGACj$cb$Ll?8K{({X6g2;kP z!5WrQq0DF=*f2M2GF z3bb)DbkCdgf0+?UH`q-K$9ITYfeK>c;+J6?W*YR^OpEes4^)frI=UB9hnAy^_=;twqb{F}QP>dv$C*Pp3U1?@n!dH;ZlkK~?eyv*8@!uZ5qs z)>qZERO1_+CZg$-xoKVXfgx-5Ro2J77XdGfTa@N(^bz&0_>&Di&poY@qc6eAM?iX+ z@MF^V)#Fale^MAV%fVaIqfe;z`+JHpIg1x7Dz>RJ#R04FG)K@4p3lJYz)gw>Wd)*& z+1ZL8=S%1R{HP_4bj1fLNcR1R_A0u_I*}iMpw_q06-UGVh7!v%-Mr?4E! zY>!#_66PI~fND`=ul8Js@D$M8=DBx?-V^Q3no}|*9N+wH&&p#PEI!2c?g>F1VvLHe4P4om=%Cf&4 zoGa50B z1YY>mM$d}?Vp|xMn6cRRpyR^#9@J1}9S6-m7enXzm)YJq;I@Vcr`5^?!&;o)HUqP) z%_0q!JN`ND4mE@BKlNRa26256fKeAWi&+W9c6t4toh^C~=WFmf?_=hG4c6J9UOsi6 z_MpT0Q8je=_kICOxR1JPa50bvW*1jjKY>1nxxuawE^9cYVrwgnx-82l!OqkV)>)Eb zF{lW^RV2j%@fcwJZ=8sPuc6mrFT0pCE%2dwzfN9!N}x?P4JjukThO&bX2}dQl9`DZ zRu_4gU|75ptyc79TwCAWz90_+w0!<%&bh>hq$p2MOK@)Gd-=wBx3znkg^#8f_u?sc zMcfihyh;<5xar!@do-p@g$C*zoWkDQ#t>Z+h=l z%bhwq^w3B(4lRRPU0nf8=04Y10Ypv;3=l<;76+GyTUJ>1HUcTl*M)+2R#)o%QX6U( z(Ow~s-@Pr@*3^s$h}f9_5kEZ4P5-l=O1rDZ1id%r6|b=GnkG}KFIZOAGpoC%x3*V( zhon!jWG#pLYr{PI8~Nxz2Wj-3x!wN&?{YdXZ+m3~jZ}2BXQK!1H8&~~={M$~xhvNd zo_(2tc5nl3Nq}nuT+U+)bln)WQ<~bEAW3mn{RNkU8F6(XzB}M-&prT-Z!8`YH-KbM zeiZ@)T(yLefok9(^mdoJ#?kT4iL)~n%bU_CsUCT}k)3IrH1L7D!HYsY&zh{q$C4Q& zsLAK}5X>X{*ogIxiq1c^W?9OX{bhkVB_qGIVxyFcUYq=GucGYl7?;D@OUy3WBf2^} zYYQU=^u_-$OI+|_(Is?`xz_E!`>QL30KQ99lv=)dj%5Jq9m+ zBywXV+P(xAyurwYNVqZ~``FZ$zcg?8Ou+)aqWRlcl z1twyo&hOtvo+jlt)O-IXpBE{!!dT{11jS>OHvew^u_Ac4|S&UGJ3HE*SgbM~xmL@D%pO zgbm&>AqlZyuc;jjg1`e2f>wrWu-(T|QEvV*CER0MN0Zx=5e-UYNjH4MjXveih@=dd z@ox0mQ-ov^h@7Z0JQuaO0^D}h)j}!T51h^%lJ}zOvjB|{bqgPq{Mv^y@8@KTZ>5ldYv`+8d{d z2llE(W(Doej!wqnO}Hn}th0;h5D=d*_ZT;cv!+ie+V;f*M~U}=HXv*46U}_AaasE# zu+`(SM?Oraau8lo^{%*nQb40U1sds=c(|kYvBG3B)TegBft!>MK?3RDQ=#z=eOnJY zW`WZbGLUb~TG2!nVfcZ*v;0g8Uhx83ZphEKcH%z~} z+*1aiLarkz)>oT1cXV9lutWDjTPSrFxc2&F`5>ZqMO0G4e4HIR)wrw+DD|A?u9DOk zsTL|M3DAu7$|}an?Z=m%8T>_QpVNnaNMg^ZTn=o*3Qnk8u)Ku7S{E`wCcaGBtO?LK zqi`C=8LY^9N%IAa=Y7AyvWodL2u3p@I^h~&^PaZCt-4zkDUvi%s1@!Zsjc}Objyzu z(l$?MenBR`9ErGIILay53WTBY$+F&i!-;|sO55S}170q23;;{mVmG$E z&Djm4G(=L3yb7BAQb1Tl#Uyq0aO0;VBiM5Xh#^o^04AA=3R5DawvgxQqsA4>a`QHR zj88{*U55N0X&8aq96!(+QFR3Y)cfQrN|Jo5MB00r5ceEN}WgImjJv3`=_baug`j|MbUf z+r@0H_?y4klpodI-z{7G8KEo|pitxYEQ!1|xBp8`Sjbax^hNAVi&%qr0$1iO@axu4 zrSr$fU(>0W7g$LRCQB@f98BZ>T9?{&NfCuK&{y)vDhW^!-^g8p9jboextIxbz961w z5cbDycK|mM`e|wUjetQGDH;|ee32b$#>F0Q=bJ=2I?2+J{vfDdlTUEC&0@&@T;Aw@ zQe40*31}HqSb{&mLhwF#Op}h3a!puDGSiz^R$iq&9=#X0Szje>Jor-Z%a-3`BU6JU z{MCx`ARtm3SUM_534CmWu!)KS;t6rSuaiJ1=uh7^=N7-q>f+yEe6A2RgXGu&P6DU? z0tEO^B7KtAmv+f@dr_;kL8LdPs&Yn+gYsisR*qNloG1}=-?_s2GrfEqZncf8YxAxh zvk^Y=fS}ID3@gTG4Zfsq@`qq=XUqI=eaxH{Z~ms$pNb0kyD$it0gh+0WGr96$M~n` z4_qsm_y#>Gs1P2*Ol<}zJRg!Bl#Kc79V5%u0bA^p5 zHT8Z1(uAEJP(p1apl+IwzsSx&=6WLKn1mn&^IJtr(EDIMmQ(FD&7_w)K(A6kc978= ziwK{v3+aP$1IK_L<$3J$7t(GLQoPiw3hmScNL*{;!2$Utv^3k>lR1D9hd;;ix+MX{fxcYkdVlPT;Qsrb>B*yi+URC;SY73yhnbQd3 zR%0O(f|yl;Tap*mC_Du%T@^ z&hC74Iq1^ohuW;C$dr0!jt%X759B#RJMcL+b*R(p_xi)8Szj62`sCy!PzF%^yQ3ra zmG=kuh9yhPJk4iig5uCUeU6%7+2ZiS>snr!z}afDY=V84&{<>HA+W z-N4D6qf7?YgrR5HKF+&zgj`kUoR`TO^lnz~{_xe|A55`#5uHQ%Io6&&qz#xCGEoXb zdB_T_jznP8GcSHTt;_z|yTfnhREC)ky10&AG`%ELO757CmXxdeSMNfSiYR`PZi%ahLdmx+$5Iu-}}EK8uVZ%3zjFx z!K!tD4U2HJ)+&A-bC^AB7HC$kmtp2Dt`w(|cAN3*@P1qUL0@1H;Ze%i;Yt{_AU!BJ z4F*Yxp5qkKm(aUL(R!Q^y~gZ1*p$CKLo&bA;c_@G$*0jPYKQtSkl!6+t?eH>#@}fxA`)llyvy_*al75vfZ43=Js&Sc9AC-_JkV`)O=f@G`5c0;QI0mJ^9?M-24k%|fG+Ljug$jg_MAZ-vy zD^)p{$Rlc0SeUDr*o6x)fV|?+I{Rq9o)-a%ZB+=ri2$EUihaAwP;0MT{hf^DdGhaT z0Z$%bV-gVI8a!14EScLPcc?$sfgfup+wQ&XNJUEvaoq@ZFmg!c=6)B4d-vX2{BqQ# z3Vw8s$5R7GFzb7&KckMM%ue2pww)rrlp4VXm{U~!1Z2+{DyRqc0uJ@I+1ie3`?soS zuL=QK56OQ(eDUo-RpC`YKvF_hT!l&F*;jMv`9Zk|K}R0TP*PvGb}04g=leF^b;2}! z0~H9elC;KE>R)9ME-ooLGw)PUjzcmGWZJ@1pAW>Yc7@8Q+xgX)z;Ry^;p~r%g!1xW z05-6`=F;Ur`hVNo%{cv$+v@a#E;ZtU*J`|f2RU)6Q^1imv$k)|3VT*EBhXY zkb#QmIpH|o-u8En3Wb##R9z@4splmi(J`Lb+aj$@B}=9wB;UX84Sy0{rCyTOKk#9* ztDaE`hZ{-Vk4uE$gUZGpHr)9PO_3aZk3|4ZR&FMKTr)wb$U@b&+1`Jnbg5lo%)!eL zRI?q?;dJ%6q4hV)`KQlCqp%A_LXMtZuxEh^N>5|?l-gZq>W3SnnjNqC4QsUO)VHq4 z@QMYIctdv{&1s&cnpJw>Dr?M-mYKysaTAcAXNY;%8Ws?c@1em4e;;>Mb#59^p}Yus zy`o9?(~wm+rfHWd5roYz0mF{~pLV?l(bQnv*?vPeE$OdYlc{C1@2%`B>o$v)Yy4Cn zMh5@C7NBU!Ku(r@wDG@ZR%#bwq`!Qc4vvV3kbLGl^Q74?JuS_1a}Q9^q%QAwaUtC8 zpR(k$%1UFj+wMU7h>aVc!eR)se>JB}VIL$J2O|-YA6TAKfVYt$=3c5}z19hYKf z8(X#kh_%;j*af!v0d+Trny2>8tt&CR;z#|!k&?GxKT|aFR#6cMCpkJ9*Ywe>vEgTP z_AlrkRnWn#{Txe4F<%+K|0JBY8naD5nbqBGjM-%#$Lk&#pDgJf{n29Lbz;URMd+W} zS9y8;Q~QI25VFSB0}3B3#k5V7D}puhMSm?WdBz+}=pGK`)!d~IZ7fka>kRO&w0wq zVnJwdQii8J;C=&*aWLUut!8p?T)pZk2zXs>16x8NsNaywpq{~Q%x;!#^j!Zp7gUm7 z&lv3Q97xn}$VGGWMGuq@Wn~+lFHa$B5S79e%S9E?>{1mAjy#wxC>u|}v)7&@84Uw_ zYqx2*l%?xkLr4hUF0|+k6>~}ObX(osN*rj3tJb(GXZ&<*EUP{|xv8opq}6=Wz{kr^ zJX5rd`jXMt+vJ<2_4!-ZKz6>P8dYEMJTybLt7u<1suQG`e_Ds>1iG@Vj z=fXa}4lT__qx@PagTY7xfO_+m@b|pifch;5JKM!h|8`Yt2NO(4^kmZ&2uijo15mx! zHk0k|54@MR#3gLP(1IX0oQK0;O$~ztg-!HZx-=2*-bAL1JXkDh3uBU&`-W2(i&6BY zzLc8HMmlJnyX3&Jm_D$+vHxCF2sNx?+PR4z*2^xR?miJej3g}AMBHRYT?$+6`V}`f zH+Q{Tb2Rx7u<~d%7S%8R4WsWcsa@K-)0BKs(JwRgn%86U7xEh){o8u>%j=z(%^%a# z72K~Gn(luV7CsBxWdp8+TB&(s^i~m~u+dfV% zww>A;b~*0!Bcxv6nAeX92`IYM=dMy$7hzt_88s%}0WG-f{kDs6n=oj0^6~r7)qd)^6U8_Q@tnn0;e!?WGlVsB z8#dCIXjvS!%3UJ)wQ&AM>ni-3!);c+TQiJ}Y+J z>&E_FoB2XAiYJ4*N1lKR;e>bY`0vjBE#Sk?{-^Hx_qjP;^}}CkUF)lFsgYZ|FwDvJ z+n5@!0-1Dih7C6ijziRKju58iUZ(LLC^$PigP-#Ba)`fBr$a6ppdBF~wsT4QumHY` zv@eN}`(TytnXY&I+8~5YQ5L)qe$i`)FVWpbDp`>46*F=!KS1O6e*Ll*u?=_nh2Vzd zNK(@Cs*9gqYo{c9+P&Yia@d8w;AM4R`FRqy@u`O}z=Q9V{&XWSUBBlkI2x=2Icc6_8p%o+@A zj@n)OF+4HRIMKNMTk{U1&NkW8-rJm4u&BAR@spOn>n+)esB$S&dgI>mvKLmx*SN_7 z%%WkWC-gLk6PClA)8J#$61(0NPK*F2nDMQ)z)|Bh0{M)-XuPDULIAeDolHy-| z{=N+osNW5M6UNawK0C7klrS(9Xw!Noko1fv{!xJAB?s|U@o=9}3m5M?wglG{|+ zQ%SyG_M`-`9?O7$brR{N_5}JdOL+x++~)FRQ|dK>89(d8nOq4;V^#;n+hy;uu+u<- znEdcqtnBi^qnE$l0E6xnZEnQhqI@$MFg)Q-JsHqZ0Gp*>BK{JwHbV#hPH01Q_pMan)V7j342uTzmzj+%ll}Z9q8j zIA6W-6k0lt^6CRTr(OlOZO?$PLE>>4<1d}P^670m&N30o#lET{q&xP42m{vhdI4;Y zU&#-%wB@G{Rj%Zw^hK#!3S7{KzDjd^SMQGm+vi>~9clw1d!;!tkP8@=B%n~G8nd&z zD$}w8ZoqV6j-#6E!+8Bq=P;QUI=6q#zWLt(a_wQ8V^K-T-cmv?U}yzD4K6T@dmDWu z60;t2(&ycr1Tiv1Tu4t1F*Y^^u+XiAB5FW>?{tXMR=vZOH)V0R4p$DCES_0=U#x3q zNH3L&zO+|fF}k?0yREygYWMp`yfK|l#}BTA)&v&-L51Eb!WZ9^9FJJWY|zAGe$^ec z)Fo@%R@Jw+FenM8y|$K!*uqQ7TUP?8*ZicigxYY^lY4<^vmx!f&Q6kSIZN9S*9y%y z<+D(JYS#jLpZ$)!Dwg`Y`pMpgy!pg*uxD79;$nCN2Oq=I|7At~>JN z2|G3kDOVMIdjb1n{Ra@}{%7fNn7?P}@y6Cze0obE$KG04%+9dNs4f7>-#e!M7`baZ z=i&$?tT;sh>%Q)g!~GVj`!ka9VwTLClWASx@SZwZiP7i^XwsUC-v6UvxIqG#I*lof zt#eNfvMhBlCsWxJD`I(C zp(io6d(KAMA(AevO!G}pf@+uJc$CJt`UZsOD6?(R2hCX%dGV~7eC6oW@o#r!a?a!Y z4FbTuB5r~-*eQ|!+&wG#XH`=TDxthOR!O)3;&(kv2GV=`bOi!?{QP8`rAgiFN223% z-eQCe5=<1{u#1Q^NEVcYu)vHK2)xC5@H39=l6u4spkxzg)2>!6e}*5$2Kg#mk_hdz zY(k^q3e6T7z@H6QDK-bBMWH*tI*41AK(~&GIBgL7?R%GBVLfxI@S3M@n2wN{2~6G1 zOiAI{whj?0d~@T^(ytL3&5g9%=sBvpyW;Osj5naOe*!ERQi}sk*;VB27S@kYH*f-< za0bK?#fMxna}lH!wytVN?teaiGZT)>P?q#7Ks_9J2DmZzyc?rwscLEI>C~8$DWGy* zs<|y;Lgb*CxE4vX-j^H+(n}sYFd-oDFAN4|mzyY$gzxL!nY0yjqzmVvWQ&0AOz;vr zj9pKKi0!{vx3#@(duviq!o0E4&$;3Z3u|xI8%sh8*3CbHQAUmcX7uAKKWe|cHwB6{ zAds&a{X)*jWA1uHkSbVM_VtG?tGzud(HY{pbbqgF`^!@QY#>gQ8E(_X%E3o>KdT{+iL;^#X; z7Aic}&-RSHq`1DV-KU1_y%f4Z_Jiqnr^GUVl`tL9eP*L0m`V2m0F9RHKZg8qyzoQ_ z(%-C@jB)8nQy3r?qeF_QV#Jc70~MK30F-DsKC) z?<3Ry9_XDj*EfAP=VNa>E@fg^{M})4v*5drc>E=EXaYr&d6(+;k!Q=l8pm7&hsJI! zdUxh0SS0?pj~Y@Ts0jyL&^OJ(Ko&_<_btt-*c%$d8Z&0cNpHBXP<-o^#hx7lj(PP( zm0F$j`*lylt(R|7N9(4gTvfH@1)i0Ei|5cDS?!w?;j*%_ivBc?MkjyO@jEpR=iYtb z6#-}-D-ftvhZ3#N0X=A!d*L0msdWgIxrD5W^ zU;pezMu*P)84qZc{g_HU>)>UtieS6$T6j2LeYiHa0A1&o!-sEHXhz(NW+)dNA3!Zm zEVNPB*_ox#ck+|nxVIwC&b=Mo$}`B&osoF`Q*E3O;bPp@TxZ2EI1^h(xNlOj;r3{; zIX)mljLE3jWIT-0MBd_;lvoRhqthu4`qb^M=pbkQ1rJpl(<FmfWEjHVnU8M9E2gJ|xy*gSt zXpZ1I7L6^fI+dBQy~@ToSp2u|(cFfoIEtgReuhyeTEd1>BEy4%;)pGA>yOpA?vIr= zwl%dxFg6Ee5_VQPUbJmM$Uhp?&e+?GX+PX4&ir80M?e40BWoVQnQ5-?cEm7_df8%V zWM8#=zb;?Cyxw8jD9jQ7Uh=N68=;rFfok)DhZm{en7;e#aN zUS315WZi@DDfe2-v` z>jXJ(Jvk;p`|k-fTNYVK{49DER4kXYr9Z2?X53SvOMZC%q8R@m42DUh?ja<2^qHsS zn78iVFqVcfNhZQUI7B~p1cZ})bJNfOmaLhAaF_XxlMJ5a{AOQ*vgqqIeC?eAunRSY|D zD4t8xKhEwK`2r+8beM+G*U#U0-J25;b)C#hezNKrH`f|}!NKIGf)%!0Bd#P6Pk$(h5^&%7_- zW=%uMC^2k^^GJ#5)ec$1H{~A|o3sZkhqm%IO+hmFmR}oFML$Eka!b7@i;~miPp_Jo z81GAyh!kkO3KK}>Z_UcemrV73ZeBVB{uKV~Qow6yYT7YcF2hH7_T<0Dka+RioSebB zfz+$7(V)52dD(&*|8ZWuaTUtA)>UfcLD ze}sg<-L!wc>C9*m{wSKie#;?8>XG6p9-^goq^zfvS`r7%iPHkKc&;w-04$Wzm4fM# z9w@}U@PcXrx;Lze*RsbW7;o+C-z_&E{fk4_JNV)8@jENGEbc`7rTUB+`ozsp{B=2z z8Z^Weujn%+9EzB!$_r~|;A=>~Y6IM6X6gJA{y z5?|a1>(nw+WqD}ht2TT`>2wU^13y_XB{VSd)3NrZw%b@Q?@}VGTjE!Zhgdx<=WR~% zl_#bF_143iPlM2M-I8AYYty3#&1zPJzFIrE=a75%Y}v(E+A)Vms~ax;S)LFYeeF*3 zM%2D~7#?5I)YOb$R$*0s&yon!OBDyw07*n=MksP$$^!QG288dHcay)6ZjbI;fXtL#j997<&*@@Z5vQ)!C)9M=J|+U2A^`j;5CmTr@TWzyh;ywC-3g+{xND%<5`K>o$<+RaW+R$lOYkfw~oD5lCj6=^3`Y$7v+# zNg&qCt|w2tm@$MMg-oU)QnR;t#6#CoWzcwq^z*|IRQnasLAp9TdxmrN$zgE}X zxq#NA3&`E}y@;bBznXe^5!Yrz*+b}RI#BJTj(hqsd~<5?S@NpF0~dPzelz#szrp0@ zfws22dFqQ#FZ-u?uXtHEyIdH!c*jxG(Wu+@0^mh^!7UcIKHarI@z8v11$_2tj9Q!B z&B#;J*_|!!Tdz|KnA}}kznHL*{c7p7NPGNVKlB;?_~MKSuX>q!@#j@3*wOs&&xe7* zd;Jk8fe6NA|N5I3TR0zGg#&2Ea+u5((O#-j&&o6}(*d$3CQ_dBnktlF0!?3YBlJu) zQciWk&Cl`ygV2poso);Fykerrj2*}cCrM$7o>8Ew>FdXrK?>KOH# zD@a#=s4WgK0bH0wp!1{Tsi-L?U`OmXQ66LSE@oTo28nH^rluZ}wj^ zahb>?K6{^wh$yoVL7MrNL?6UgPnO{v2xn-P#`NR})oHW>NibW9735~SQsRKQ(GV=T zb0$zGix+)kHp+P<&%8U6W_X@_3SAy)8pdf4GcSBUS|3bm^1Mv~`p6svq3*eWUh)jAYHiPO!nORxH;Wvb}^miCwC zdrwM#IqMo{&DMv?e2M)SJGXWP&XNRM%iEi`tyG~?sWJMCl4oaxYwccg^ zSMT5op{WxN2QwK7o4a-0neH9(E?V4V#y$V;r*f*ohU%TOQ}ewZ5e?h@gI5RSit5Sux#1C)xXtI3wA*f>%6X85 zGA=fD|8Mi;IsCu808ufK(|?zjhr^Wf`fI601i~;YEMj?VxVAE3S0G{8NN2yM!9kz@ z)>|UGsFEoU=c6aT&*bB?89Z=Z5u<_Y*A`2!O{?rABF#K7xc2Q~MLQVABmk zu&}D}J6;jCrcqJxT);Q-U7EOL19WzJW_#~$@vB0um|#c|6Ql>@PypbGK@T-!5aQQl zJ-@~^g$Jw_o|7EKe5W%x0MZEk3WO?6GeV-)6~EMqi`Iq zBu`2Abbj6nHGl1BLM6_C=Y)j*_m6Bm_-Db|c68Z}oT<&|9(dZ@w-^wqpev5@l)(I1kII(<^e`4f^`}>|6;t4UrNtD0lAHWJhL_|cF*R5z zOrVm`Sqs<=kO?cD-5;$i#Azv8s2wMyb=UFp16_~_ju6O`Xdq!zu5>`|E)t^mrKO?p z6>wR~pWjOUf1a-joX-`|dA`(lhn*})V*;Q`+y@;5AO?em0VOxb&xrvTI3F+iuEPUy zoW&2-6U8c7gAm;$mpk>-@EvObVZ*y;*%sO&;L}~P!&hStDrs?v2vL#KP^_lgVr})T z>#yeR6CGdF*_c{TI{x^z<%YkUtXIg#NV;H^Ss!>3jU^4?@hpi+S$2k}1KITKtWT8X z!}DK6IS)I~;fac;&^Jejs=1b97n0&u!kn+lzL8lY?@qODJIERedfo(i&OT*xQz?Wr zt7q*`#ez&)30o~y=K`>n8j(ga$#7PX2MyQ5n&e7ng}~gTJme$;mVLCl5dqhwmC{bp zMR=n($HLr~m&YTdXKLP!wH_S2q8{A5GJJJ6CgL7M?PX(njjzHtQ71IZ@!|D$9^S02 z=PP>EN5r_IM+1pu8vW8^5C5=>Ced1@IXi$r#b(cL)G*G5xZd}2%CF7|2KLs9W6qdd zH#DihDV_rof}^Kf-1#{Wu(j%?fYz89Qo6wPKVeZdF4D>IxG((K5bOj&3)K=04UvSs zS9Iy!fs$vpRfRLlfgpOecz#j~_cvYl zU%2k?GPL5>cFyYj>sVWR@OEc*L9L=|?vDC-iZ4I(^hac`Qee0D_h&JW%GD4VXEibF zmhawFLZ{`e`9TO+9vK)2gTh`m)|V#6sG}2mP|Mi$;OtSTm)AD+U@z(^Hyewf0a%<( z8$jssvy`algRo46vGMU2O3~1){2(SGf#G^Yy{n~tS^a2d25Q-EV+R2kxrZL`O9O@4 zCpRRlF75C43>nQVNbz1DGQkM6RvDy;e}=~F1*=xz&tU+;n9WT`h)n4qFr3|;IdJW|P2SwW!|it- zT*s1R@1xRhrzpIC&g1a>qy*xYUn^92N~4!nWKq;fGW zdwpH1Cu!Yre2CCvd|dkFC(zRb;#1!OATEC5Cqy#n2+y^d^IXX9M(AOtrAl$pG#(5k z%J_+Dsqb+TO-O5D7zWy}6s#^4`I~$~f z!#yFaMf)Tl+LR0$qD}oTK$+pLV@6;P%CwFe+O+vkIN+vvOmOhOrG@pmVCWQef7?(N ze6854o(V3X&*Uh8PnA>Lc+V>8N2jE9i1rsofFu<3Jh=chiFXZvCs!fQ4*ChZ$;&4}YtSXmny=HR zu9P$2`FXDvn}4Hqw7yNeTzb8nE7S*Hp~mUiOQE{%dPNxZdersG&gCltvDPC7)?FsK z|3Sn0m;@z}JF7m8IcDL7{eODg?tbvh?+$|H>l9qbEA<{1y7dVY$aK>`E;@Lz@&SU| zs942hNQSk8u*U4(c`RT&+}GE)(dkQ2l49FO2qPlv3Gaj`BFukJM2`t|MoML`*KwFG z6zP=bor|2R6yvNFR;!k$RZL9{pC3`n>(r>mHnrI8wQ2~)08K{K?Ll5zg@+T{N8wtc=y`gnis5AQ_ORH|#RPtX zg=IDB!TjgU%uMbK0;D}=Lf`em6@iz+l6guoa;JPd-VsUmdcq5Fnvqsh%m{>tWQ|`eZAyMslVn6w}+NX8zOBLc@H5s_Nh9` z$9n4^k+6wVUW736?x$kA<{~rz*EH7B7e%A*mhF5&;OjTZ84nNOu_9MH-)~biY}GED zQTfC3f)|+thwi&G)Ry%>&x&WxLRjONe;?lY7OOA=tnikHQzbi3Ee!>iJJYa==yH}0 zyS^M03e^%kcU%u@AOsWbp6C4%yb6~pPZnndZ#Dc~{L6-UQY+Vd2{re1_k}$lBUa4~ ziGgvRP8oZN_lA}RjwPr13(ZcPmp&h=XlhYzT$RSL4;V~0$5RcW<8^48z z6}160({Dp)_`RHHgs`=Kpm>~YnaGn!ji&7-Jkm6I`Z&xGxD zHsJ>=Mmk}lXH6KrgFK{2?L2Qn9zL9$a5yTE*&em_$1wmG)o3T*%0S#fNQiU|Zf)I^ z^@L0h!OyCBNCZUya+80D{2(x7%c$RXl`c$`O+{6VaQ9$z>)$nT5J`)59s!YzSP|$b z5Z`{WMC5UIkjNxd)0u|8*47RW_7Hkx)R`|1Gp)*o5!WM-FbpUGyHA7idhBx$7lJ=( z_@+VIW6uvR0(HB!m3Sx_+Me%!y@ApfcJ?B5lqw*%%Q%8Wg~dAmTqR{~Uc6Ail;YV- za}>B^CvIjFg7Uu*EVCCd;u@mYx41J8|0HvxS32xyabseYYK>v1^rX}$1v3-23L>Oi zJ1C)ALR_{L!<10AE1}zcG1wkdT2nfbb~}JE1>F{w%o|=uxF)R6##-G?yp$M}FOm3% zZk_K*`TQz&V=lH)9J|5R3M49}xz)Bd7Ym&fuO**&7&lapPHicNBlAN_ZbFUgr`WTs(Jy_p@KC2e8bUk~9UDrAR$KQX z#!FR67M;(+5xj{b}?P#4#!)2Y);szxWSw7tHVc%V?m++iFfSHVKy||52K4 zxwZ{wR)ZVG5t_w$r70kgN*E>!(UwNG8Dg&Lg=Q%M)Ts4~hl>{@wj(B^Xa(a90Y_yz zdv&Ns5b`JD@8n@ed;BKJ*Iwg*5;J+QCw3^__qLA9T@-M`mDfvSj>|Xm`&l(4-_nU> zYstpw0X&@GYao&FpSQJv>@iS@+%)rZX$>v4HnB}TD@PF8{O7ACs=bqB)v3sFx>E!Y zYhn51z>$9zp=gRKq3!~}XP6$SwL)eA6=%jC)>?CQCceJ{@FXeN;1_rw;M}~hKDltY zPcqje%!-Jo%ljp;XJ&GOe4QCZEIXaucQ;&!HdX>z2Wjw7B2&4o&^qVdZQ z;2NG{nD_2`!Q}e-dZS_ss|K$!+WKf^)j6*VoWKqjdG^Y71k)50$la*@;Jv6d8S26e z>QxB&-&_IyJuWiV5Vr=90lkLrZ14TbF_X4Tt?0H5aA|I{`>J!e@_BCV*Ll7VgJB%` zbcGYl?r%@Cd=w~QRwgXpMUj#y4j0x%+&x;3!KEP5yrYDyBy!wl;1mZIJXvdlza+$S z+j;)$6Nr;3T28u4zW_zqB_Di&z3^OU&Ggh)Cxi}tAg0dUMg5wfcEaIF2&B11R}ENy z-s%d&DXSDQV9-=uW98O~tl?1t-uU}=`Pp=zlx<^#Z51Gkd7v-xZ zwod#A%aX#u!CQs2oF}Uu6;;0OoS4)QdCdGTXA6E4*@BP>J$(@Q0Frg})n1FF(6<$k zr)$=y*Lab$m+ul&;EV1vyhF_GYPJ zZGGv?^Lxqhz_;BZ!by`ByGm#xnqOCN^H`#S=m}ci8FV>>h`{OYVv~GNa{)8k4X}OW_lN)OMB^=<+%7!5xh@ zO*zmmi;dAbM&XYWVUK%*{`fafD|G^{`?A^ci)N$7`Lr%Z|fPs@BpzExF{DGW5zgK-io$=SF0)y zKSHlo6~;V*LwrN1o7W^?g2nLrSLBC96|#Io@{3b7gbciAKU`c>g4x=1jV=fZD4EpG z%s^`cQ$c@R>d#P(bG2uqU6mzQ7ZVCR_s>-kRN8_t}jzuB%G_>-q7qgatw(Y7#Uia4ba}9*UDfO zb+#uM)Pu!)L-nvAtjYhNKZR<<_+{d_f&Ht(d?TgbP6{b?sCT{R9?eFg(q?u>>%6?7 z+eAxPzG9Dh3MjeMYCEP2=7)V^>p%%e^jX3H+D6v`2SctnKYe~<$xmtdShdai@O7Pk zA0-*O2xdbA=i#uK(;(cyH(P z;r1xToo8Nj9INmHb?u!g<}M@9(!(w5Ow>~rc(lDKXaL`ZQ}VQ`7Zc$UZ*7FoejjSc z-UNa&bYL3miNtj&O8pda7d`>Z|6GQ5mR3$1ujM?F>HQw5m>1)lZA`M1NNqU*J)oFi zR80*_a-ac(dSj(;pAxH5C!I(Q! z;nF2P$8y^?x5jh6Q;XUo0#`!XSFS=BN+?QU!5bmn(-UbX8$|Z;gwE)n&Ofvb-wtO2 zl(Ni+&|nFU329c2d-^>$q{abq6Xo6uIKg@uaI-&^-W7}zVFf;X$2>76y0v>4tYc$d6%dRe68StsESEB|9|ztU+Dh2jV|W zA56hASTOM0W;eEvdEg%ZW8oI()4KXyk1~+;L&(;)A9BmqG&c;fZU;Yd1v%H0F1|Gp@xb7oPF9IOXN#_0mlF zrM{(2l!aRVoop7kLou$-B;mb7Ky<4%dZ*(v+u5^cZ8N!~Kf4GSIe24gIErjYFohhy z3xAZ^oL&5)4>}@gQ?3VjM}OTIJEVT$$%Cyuud@S?t=$IYM&SIc@;vEAuC3?AtJTiU zr5W$&DL2RnYg6;GY^_N%X)Eye+?*U{s)hbxfaDXqOgZTrS0kU)fD=yzbY%vv`kE(v z^Ky!$sqL~(>B_XNE}9cEz8lhQOz)UgSZg9UVFF9E?CQ)x>*=8%N1Ms*y8}nN1M4kc)gCmcKGFwObw8nOd&3DuP46l#D&`~xM(_mb z>{UP22vyFMV#fxTW>kC2#~hyC44eF0^xUI8okLl0cDZ3vN3*${Ui(72qgm>j1oB_2 zU!4OJcd<-xhnoNS##xLdw#ir?_TIWz_`G^IXk>Z31LxCM%MAAm2=Ma$b@N$Kq>5Qg z>qf`HL)VGscBc#VWsd0HvGVk}+XVq&VvrCKZ!v}fw30}gGc9c8MDh;6z7A(jgnt1$ zrY?8t(MxTH7e?3d=TbgvV>+UQyA(?>w>uGMaA+6{U_z-F54S%_xjUl*CMvV$Kh%bs z!C}-kC!4TYsb33y3PDI1!h=79RP0jSji~5d+g}Q8br5#fU4b+I>K%y7zw~$ z7b97LMSL(cNNR57fPGUp0`H55`du*t_5af-s}#hhR8w0niC$0ME*rQm8h_xX?usfd zpx~?Y0HA}b*0a*z@qyywMitUsPc?%^d)k4^z_IF9B9pEeyu;j4*|Y?n&+eNa@mwhd zHqya_W=3amBq`7;br8BRu)|sO;$!y`2Qs1q78w{7|8z5Y41v9Iw%lym*t^wXE{I>) zQ}Gih&X5z}WOmEY1L39xVe%-pSi*;g3e|XX3t4|CAx6sKMMk>d;B74yvcqY{`&uzY(FJO2oC2X`M@UtbFX`u< zx~I@zJ*Ozl>Po7Fpr=Xc2SpMu8tig7pTx6r-@+6eG<^UxO$NF9U8Jkib8AyXo#da> z1lI9Bc}=E6eJBckbhgn(tV^al|{uOWR z3JVK_{oh8i??bsYZgwPin=E6fVAm~6OEOaW?q88xf3B}Zh7u*~f#JE0os8O^SfFea ziyf6y<*G$aJ0P3_$2DVef_+ajQ|YWxu5y%hfwR0%4+{MKb3=b}Aff@dE>w7cxr^xX z8c=d-@fG!YSUbkF91(P>vblKeTAj*}AseE;z5yDQK*@5Bit)-9Oc*CXK5@CA;Gnf2 zwJxkN_*+KVI3rSGVkL!w8>*#J&f`ai7)uXAkrwXoYtS+=ZIjs^ZB%)CayA*QI>Stpt{(V$M#95=fDD&KBG7Y-&poeH!6dZ*4f z75=G71|{$m&dHbbWSgqN2EXfQpzu3K0>~}Bu$Xqkk2ozM^!VR+HdEl%(nc3$Ykq%! zdUiJ03YYT+IvTQH$U7Hsj`VUi-%Z5r6IO64BSch!C2QqZya1z|N!~kY_6Htl?tI zQ^X7aNP)TtK;*H}%&NYjg;!$B$B!~;%*>wH!E@>sSpeU7)Cj> z%i7Yzc)M_Lv846qRvPo03Z1Z9@L1>Ph^JF=R%#R19xE(XCIiP!b%DGV0L}#5e~7)I z_cEg6?sDrfY6LHky6V@6&5{zIPj)4!omPH>r@K_s3L+@S;5bVFCJQ|!d4p|!9S2t^d=Ugikl!rY*r*$j{qD6(&D<{gDJ=pB@5^pi(VB>dSUr-YOMYN z{1^kSZz_v^7k28lK1c#t#l$h@Lmu|3uP(-d7`KinskcR(=%4k3^`0PEV$HR*c120m>J$gapz|@o%hLxmhC_G6hycR zl%02VBDuvwk>X~WA0H9xLyE*f_7ZDrrqpSv{#qA%96hYY&hMXneS@ZKdY6Xl&J;IS z6$FJg%oL+KSD&)BKJV%1$-~)db_%cVDhGETh1|j=Pn?bymRtsJS&vj~vH}1P33rJi zpZ*KwYJ0*E!I~qm`(7sz7T*XbOB?Roko8b;|)OEHdlYBHW4Ug6_@x)WnD_@UH)3?7?r zh_oC2aG;lva8z_p$bH#|Sa{JEf>J4E_2$StR*U-GQcbU)6hniA;o`wSjhDxfZ)DD; zLk}*SQ*(ro06jQ}#%0N0%l%?fJ*kX`$^w~NnOq9e_G5c92}g{Cf5q(y+XW5rGZ4yb zanrW9c7GKDKK5nBY%?IxLOs3<(|SlM7+U8**F5=kmxCz{C5b33C=@&GVm&5zs?K$v zdhvvGai-3J)9|^+e6ahMO8w8dkBv7lTDJejyow9o9v$*JaGB0nrRGtNBlGH6J2-kJ zTFaHmLs8QptVEQ$MGjK(qeHEF&MR7#HJzfsyNC}VOkl~*?K(k+J< zZPMV>0T1cjvwx*Lw=VeFW3Wik`5nG68omsCt7t|@vML&o~6=pc6?T0zZox2!vY zU3SNj$Fi}Sr^R(mF6J#Q`Qg{nAvj7}*yt%V?=|p&%`eFS@TpuxKeXz5;zP|g$=Fi6TZLbJn$#1_$VgoU};CK*+~qn)z+pY@XO z|8A=qVJg*x4N>kN{@T0lEW(K{$+)M?dF=ka#o%ka4VHZ7qZ|-;(+`m85Kn^C^fRH#NyZ zlCkxv%ZBAuK9G{{8K&)~eYm8}UhVd>B9dT(K$bXwoy3{*GaZS#0C>TngfLpjm2odA z?0R7VzcpWMIbOpgtF%hb=;(N&o289s7Bm_EVzCrA@1Yttp$kq+EpDBl?x7wNDW~tS zLr*2>jfImy@L|{Ae8Dg?h?bNwE*%+3L4%+n3P0b*+Jk~kytQ+ard=j-jk+CunM2R_ z(jR7Vxij?b@A}7?;XwJ--`C3=q1_UtQOX=UXleM=tX3+F%!{6uik{gLCiq;xe*FqK zKJJ)2`0+)TiO29Z-^}hLLYG3@Y7@DaVvF+_mYQ-O}{JxTyR3nY*Mr~?;3BtnH z$btl(B!HFPQsW}b0ldX^1z~ss9g?R+R!)Bw3Jp}oHaoEbdd5#Z-@)JHl|yQ}57MqQ zXvwfM)iELSr*H0dz_za8yYH-#)-Up!AmDs!_`$!`RmH?M)r<$mn$-mjBm+y!v@Db% z;y98C=3mjAIUIGd7}S$##OAyOGL0nlyxUyF#9ZUnHb%={#Uhd%36RAp+*g^-*;$Ft zZK`ajuXl-ACJv?7>Fj3f*az60rCn6ew|~x*iAe=Lx!Vr!wEc2wkMeD~q^_egle8Iq z89pU_5xk={P0DehR6voHz0lJ|aDdk0STw!ewps56`2}p=HN8W!VtM_?dOS7`V*+Fe zz$b_C`aw$)!H3=yL@x0TKnXF#M1(3{RCrpCgbj&0tN-1MVbUdB0;krm>kN-A`7xkJ zi%!CpUyK(A6YAAPoaI1afmYm>g!w;QI)uO~^(oYj*AU^_JGfu71?9h#4aIbtjyl*9 zoc&aro12eDj&`BAR>Wj`_~uyq&T>M}8;nA2UF&dP?SS^d>~_M@HhEy+=8#HnOYr(1 z$`;u+0@4@RdP}gQsZ78|V7__j%r#73y2zbcfn=lft`o=8RbXF%@xYwEHd7s-joOhuagqYU?Y`t-SDjJ!ZCx66B5uC@u`JWi3+7^Bx=Y906PCec~$a27LVHm=%VwO zk9L`cgG+z>RY_3*FgzuYyGY+KNQ4EXH#rbSu+Xisjth3fkCJ62rknc~;ZC23ZiM61 zy)gV21F|6cuOC3Pgt7w)^TIO{NG1%~o)+6a$;}jM@Il4A1b4CDlB!GsI4$_q8L}nT z_Pl05qIjbG0<@{Y-iOypH3c0w6b8fsV-IZ>DqnGZ*B{xu-DqDKtgldz1tJ41&yi+|QCQA z2_#xi#BZ+9hoI@1XM&2*;}rk#|BMxSD{CzH3D5gf(%l8UOSreUCR;)t!kdV7dsDx! z7%HZ?X^1W_|Fulxf#rXrU4JDpwY?qT(i*m&%zb!A^;OvN>PN=!s7 z(t_$)dvDZ)l%rxrMQ#-o2ZwAvlt-Tds8 z4sA0$R78wwVt3|$$0}w&HLjiAS{|V{jg5}RY;APS`Ni*%9cKvsPxVRodIAR58b9f1 zJA0BZDdjpiiT576O@HI!f)hWzm4AfLXh-yHkT|-p_f=PStfeGUDjH&x#uuzY1OR zZLQTEE06Lf4{ROx*hn!TAc=Z9&3y=+BlicdE5fjKjH4;BYuBy?P-8c@metZ@S&HUx z2>1ND)Fhc{%1eprS6Y|tt4Ct?nva%75@t3wmOgXqh-4ZeBpI!Be<}U8#rpRG{QKok zT`bgjWyWgpMYSu%LKdOs&=pik42IV`Jb)6gX5aDh?6fCOs{c+hw%Hm2CZi6BY6z&< zcZ?gwm$!LGL1-@Qn7GJ>ve!wZ)Z;^)Lh6!j?Rm|0#~7;D<5c0Gvafk2N-sUK_{l)b#*nY*C6VY%9c(kEpP+*)E_+!;X-IKGHQ_epAZJ(pDojG3tZ7N^w#9xkj&M^mKT<{u^%p-V$PQ6%aSv{vNBhGlSN9F zm0M5R()ToaDdtSJ6d-3qhx16kr8f^oN}b_WLv)KK@<{o2tFLNC9b|k26|cTsbVMt3>LP~8zO>w`lP1jI z14O_n4)?Ds({5OLzac2;YvnpwyNuUuo-7GC5T&KXct2-{S|6~Q3~Ni0z@bqZfu8FIyLu85%v zI?_R8@-kZXnN*K>tyuhXt$_z{+zpKQmmJTiOG5U(f)EzC~TqIA!-~;C}HO6*ZH7-aQ{~IpOdzx7u5V|Xx+Q5E+#Mey=`V64gQ;- zpMzYfvYs>ek8Ld<8ykhJyFz`>n`bpcq`}Q8LczpnPoKbYbV;s*>C+Nf-KE9;(bY$T z%UfHg&g`s1I_T;2YSp|Hj-a^9ljH4SjDEF@OL@_JZ>}0J!$CuwMR8bR*&}}NQ+eCh zHM|@(cD>)RVT+5KyScuB6zR*?@$hczu+IYkHG}T0q7#Yctu^u@+ELRIOqkwUeYkDK zNm{V4648(kMxICh8h&`UKmg5a3YGxnwyjfI=0msg=L@nep#c@8Ni*Uv`b&Nt{_A%5 zc6#u}LHmAQgIJ5zsokN^pN%rbhE31=?@`UXlo_$lrKzJGM*`>@rY28&rRH!B{vRxp z(pMv=^T#0$(M-ODe0lnPOF2Oj58-)5`(X$7{UVj$+kabE=UzPAY+BV0Mh*-N@V$iQ zQ0wV+3G{{p;iSFQ%%ghWyoaw2-pbTY?nT6JPi;{@_U=_#IOml>s%&{olQ*JF={E@> z%ja%Z_=1GsOD1>C4ToyXXvwDeD2Z0nyI$=l9Q`4v zG1|jv^$}G2y`JmZqvI1-Qn%tJfAj<1{{KtKUG?3Zd*OOA>Y0>@b9MXbcAIt~&dBIu zAO2&Q@8rWo#VUMS$kx(A-CS_kHrdx}XX?OjLWX3^G@)7P#&X4^;>ovL_{e(m7m&7Js|!UOzP@&m46hZ85&2ChV+c zw(s?|!`ue0RfD&XD6s<7KY#9M;|+1sG24Hcimu16jrQN(rS37H<(6Z@YAa)T=^ppB zTP024J)%?m-nh=uaB;Q5;~c{@_AVT+(o5_!OKp<*xQ}nac2as3y z>TsMJ-?FF~7Zq0gL6rm(lXe^ui`}o`Un|bkZfa{hg*G#ECq=g2yRDB2MjK#JFnyUY zD)d2-q~@ikua~-5V%~a?9ZEEMWr`4Q#D4JLl#*l&JrWoc;ecOOt%v*RPz~>~J4lU5 z3wjATp!8mPU=2EDuQ2`INn;C0GD4)^q-y`~+&V((Us&zw>N1$z#0HrPqTyFWm@CBf zvG0Ta1_u#BbF{O=>V9L=YBavGD^W0P54G8~EW`lX!AN*=aID{I{ zuJNn80^B-A$g1a8)8J?Rlj%oD<{U@f92fLQb7B<*&{!rt6^fEPYYTrF>S`UmtN#ws z#=(mGL9x}cU~z;#w&zyh?qo+R;5M*#a&i_=GLT?8hJAz!uCbGQ0iip_ONV+@%pGwC zg>!lRtdgN&AS<0HrYz*9_N zrjn)=gE>m4c+zBXQ?KuuERn)R>S<#OnhP{mF7k` zfebaZ_ie6XgTagWJ2ku2kD8+(;f3jt#|q|v|Nd1%81f4gG<@q#**x7Lg+aN>NoPMI zsyba+)p`onA7idXk z+X|UP?X38ZG26-6*xHV~gBU6LjN9PYUF6G4WP9bW+z;>LFHvIHc)&A?DOv;A@R;U3 z>>8pN*SYup@_5wN>|7nqsLaUAB)2to>jPsC@&{(=V1shc*gv%(wQ$3E^kFel3}`$2b4cD=_quMoo>%YUFjVsL=VYGzJ#z8)CV$u&>z7v7B+=bvXQQl*k(G5( zg?wmiO@3`tm85=>q9?!m6Q?KK@mmKKeSLC$r9*`NJJ55fV8Nq_cY9vRx z{fOT^)wmqHHv4x%bF+PGkNOPTYXNA& zCw5)BZh2YjdR~)y^y=*(VTfCu z&bF@B!=3m4>t;*0J$C0anh%w0zx_P7nVqX@5AN35qH#+~PeaOW^qxVnU$!VuPhU;~ z0V`dJQ-F$+4*|W&!6}SF*euDxpIwGY)ZEvU`01YTuO9ua?KBH$%6X)wutNGaw)YQdxog2WK z1|-9kWSk==lDh)9r4~BXSjSDxUalM-7#wC54O~I>EvMWdjErs!5s_a6hY5FY$z68=#TkgyF($o)v5m?LH)<{A1In>!IPQA}=kzK!xAI{#(aO6?;`h z-m(pBQoE3GTB>KE&4|js^lBMG*$0xoOlu%|Y_D-Rfc}{S_9reLKed)uc zA&Nrd5tAVl`}iruJyDwpsAqK8-?frf_7rpSD2Nqi8wg}xdff%P^X6X2ueH0;O`dZj1<`1+-$MRx~ZrXNUuE$*BlIy%PFq`lELd8W>wAfPBPr) zRCyL0+#NfqngQrk(Q8ynJpXN?;|7_vTkUs)s)_yT8y_0#W2vM$HO{Oi_|yGBurCZ& z^`mqTyo^O1acpeNJVzS$oCq9&b{Z@z{hhvL22b)px4MOE!Tw-16W9aKJ3cWnM9Dg5 zOdWja+5zy^tlCcYX-Z6Q=5YDS@{#5HXD}fi&h5_ z#KNorAsMJtDy%SqNV4NhzAwpQ36&EpEl zXN2r(*V@h-iXvPyy&>V@7ah<(lO9@EY+X;;@q^tfp-l=J)az{V(Jh+qJc=LoBdc@c z$8yRM!&$F{(D3LI*>PV|X9t-I%kvbC1A(dr>GV&rjU>iY*Rt+yPeC^v48&nb!N9Mh zAkXBZ09DrX)oVRtD^WN&&jcy)07=EEuujYMXjhV+6D+ASfL22bY_P^BNpVZMBte3> zpqvkrIIwS-v69_4vUo+UTI6orc>E_H5)&F99vs}_q);JHyn0CuR&pO!FCKSJ5U`FM zuRZZjzWST!jZ^oe@Ww%Or+Lubt%Up?H@wU{kXtc{mRqqzE71WsGH^k=(doMg)>7YtDO?sfFf!7G^zue6V)f0{rLvsw#K#%pO}Gf{%2$EFY?< z?sDUo&r|@ObW<;y-YjOD0hh*CLR`iKl54Adq>T$IK~Hn3p!Zce=0X6eQqNR=C=~Y@ zB8LVe>D-{e-_~d(6~BJ(wsmAW+d2}5n<0-jM6+Gr05vLDC8YF}i4hJDv(vJ#s++I|pt(gx<19{&$c`geAB*R+~f zILu67p?!1hXR&JagI?Uq%I_y8XNB7?j`yz>BVFw(1oXE7esFLM(6|1K9@FNylT;U( zHr)c;F2YC9h`?W&x|YrMDdRJ{yX3kW@S_m4ykN0aO@{kBc^NJ^UL@0GBux4d28@Ur z3y1YOlnywkU9|wLz%n@bvon8gs}zL1tF<{g?QuRbq9s#ykzNEOk*D@3Q}JvzB~h=- zcc~D$lw5@W;3F;iF6WQRkk$dUCrT*F ztXtFbcSu6L+I+&MH*os!TvobSTv80d z4=E|Ks`plu4pS(T%LAEMV|V+?{uk4nm*lUg%oVFwkCG#+iBy@}OS|s{I(K#_#|U4L zhWMu>Ep2Ud6Bk@pESJ|CP&r4`aZRipY4b0gV*|Yt+E%hkpKyAh|%vY4iqLI^(@c zH9MBp3ljU-)Zt$UtAKJ!U-t)P(_^N8J@@ggzYC+Y$UYN5?V@qRSnXYiL4zsS?c2{_ zcwIOl7@dzfZ@iEz@!$hNh(+08>R5qTu0wg^{Qz?^oWc1nKbsuTq`=B`$NNkQJl6Aj z0Qt_t2fGi3J=$@1d_Z-XQt5WbbpqW1-Mz0q9AkP#i=kHa4gW^6zf0I1^(F*ABMj4` zS({$A$+sLECH3NYaUuQ58Za6B;%9Y4JuaK3!!AKas24Rnxqw>u%(#UDZaFC=`wK@w z@F)v;xs$Hpd8<806Pov* z)W&pPuZ(`DX-j#8l1(>z{1-?&LWe0KJ|Uo;)&LqH;>0UUeR?3awa)<@%^)B7aN} zA`Oaqef>mgfo?8+ahgXU5--@n2Ofbz-hqY9a&VZ^G_G3E?R~P^ilb-?`M2Z^f z&MO*&Kk@{fAk&UM&Cf|vuC@>zQ$J>_U8YnCB?$U``fM+R%8?bVeu^@yu*8{x;gM7N zAVUejH7!_}rfbQE&Zm?8HChADe5dT~-qAM7cf*O!<8qdlmunOd-APioZ)z@u9(caD zZ~V!yBtAqA7bxJDL*@p?EI2+sIwq!bT*2z+1dGqOx_(~|1){wb%Xfd{BpYh)1RSeDh0j4Qm*!=L?8U^i)l-O zb?yJmR8TrdIb0Q}X6P8~{z$! ztK#w0WqoXDP~oAlq9g`MESHLuHF|kZ$@o zus6dCPmugq?+P6QlHI&jNNF~ug&UGEGYH(r5A~n@-T(RX*V@wBez|Ml+vq?A?rgm2 zeBjdVTwfo6+*o0{{^dBr#kRpgusPLqNBnBg*>fIJ@lulS+)2{Kyod)|fOwxwF@gG_p+b^5IN(tq9b^fdNhGiQAR&}gs)8VcSUc`KIi&4T zblbREJF#Bj2YBX#Rq1HS`ODa3c+`NX6)|r0+P^amLCVcFomNCOewY6^v3GK0YaEOs zuPDnA zh`L4F$86m%&Hf`KPuCch9PnN}k4Qd0l&UeXmxTO9FlGxT+t>-BdF=1`G6FldNK?Bd zQ(Agjz7xAlibg8*9@$^1p`pgcL~En_!}KW)4W&}Ou1@msgeDtVUGWDO$_=xn;w+Y8 zZ0$~-+3!VeQe9nKPW<-PkpF)#fZoXdub8&{JQH<^2iL~VNJ^HRmXy>>EcIHfd8rX@ zB!3z90WzYCEmrMsQVV5XhLT1BgT1*>Uu6(Yyb1%i#uqD}z68DmzM7+ks=Na;c9fj) z8j-Ki^7M3k(O}Aq_Tz8|gOC_gi1b8^-+!oKo%S~cs#GazHR}a|IO(4h6rZp;I$yTw zf5yfTW{xN#pCxdhXj&q=)dXJsGNm`rNY^g$j&sF>UL$*flRQaQ20P8nuhE51JRfB$q%`7|6EL_oHpy^`(JJ37lW@(A-X|Km2YBj+05*uq$+Cb+sgkLc!ov+;xQ&!gp zWJ?j`uj1hTk0a--B;z;20=J%I=?@B725QF zyz^)Hc%srqmY1940|FXuc0_Rq?zq+45`?P0?t1|RKgj+pR}7zM8QKY!Et zR?7Zq9B#CBZq!$ghgs^Z{*o%6+xNo!s`0BMVKSz+2d5?s-h>`5^RPSiNZ@Nhu7Py= zb!-@T^M+*n--A8&O;?vsA_Han+qTJzVSY=LObKwgJ*&E2Fx{%mfYBbm#h5xU>0S^x z0Gf-s;&9e#6VnhaxMPmlBhII+IroK|_!X^gdFmE3=J}^9Iu=VtVRYVZpp7s7Y{`>T6=_ z!XK*8!yX{DhlmOT9mERX4#z;)SrtoeY?69}nf>>#tdjA+6rRAW0ToM6P*ilBkn$p_ z0(Z6co!G|Q%=7uY^)&1A!WAdE4f9XL9ix7$C8^H?V&iMJ4nmlw1q4P_4F%zq4=%xM z(K1N_mk{?LKb?CPuy|VAPMl)ZY_Tf!i|nJ~TOi4IzLY<3{$9Mzm*z8a-}Vd(c zDrGtslUfe{O&xBXkTeKk^3qC(_~AZ}ck*LS1)Z79uDH#*K)dIpPfh=$<4FtVPp7%N zp3+$F9i0oe@nG)lxJO6FQz*nM2--RUBi$yI?>yx!KI!cf5}XhmA3jHMa6;6J3Qy!O z((71^_4QCi&$cJ?*+L zcpe)=dpkz>MUFX+Y}AbTz8#iId;brP0xMqkBtwZ?Cq5?a?1&%tPvrAMlJ}ogy%@CZnO@Lxu0* z=2c4Rg-Lxa-HvcShsA?myD`X{0hZ@{B@ z4+rJW;CV!Z<+$<)+3Sx-fLq#gnC0Q$*u;Omd09mbN~Tzp4~1!nN2OK!*M|cTyHvrT zOYEsc+YOhgaPYJ87x?2&?bRz|tpD{8?MyH8_%n>tfVaZ$DBUmp?r$~5_*l+%cEI3` zi*uBtho!j}G$pRqcE!cTef{b(2K-@u-W%_&62pSmLW1K>5FCcMFI!y)$Cu-@#2%b` z9LbEIPPtKk%4q}kL)P3|$JX@E&BMVDsD6NaesgNP6!`DN$pR6=Wb@}So?j<5m{Dv$ zwu8x^R)hW8^^y6cIIcY2Hq{c06fKGt{T4tnD#I~r*TAzz?|R38-{M!2HGKcA=3^8P zEYV9mC|5Wy_XgP=EszAm`sAFik6V2|q{vk?)M(EVXI+H6g$ARwJn^p;h7jV$8Z>GoJzlGoTF|6F4&RybwuDIQy0Hz|NB=tgR7~hqqz>>+9n+ZS46D6Q<_7DJb>Z z*xkYtF#cmcSTH;%6w%Y$dk4voXo)}{>m(u2YOfhnwb-Y z{NEF3S{0w#m0?#?1PIwJEKO`m-3gQjK8Cd!(K;2s`fyeOrA8|&y%{4g)AuA2enr-M z8yGNu?}v0cdz-A(v-TPk(8-Iwq=~7iEaWjo&|OF}M!N?Xo>*iFu7#pO(|%*WK^PyL zU*+9h^KQWTsUzNE?Zmp|rLx+B@JvfmNwubmipwVhT^F}Ii*NYxoP8FmIJ6E+Q5S<- zARY*UyQ81*%u`JqPgV_Q`~<_TQAQxFzwtCBl6Hd8B&`IidjBjjE+j5g)d1*;nA?fA z9rJ#E&gThO5#;_#qBl(t_)wRfE^DB(WX&B|BmoIw=Tj!YR-gBFt@$!a+ z)nEuHh}J)R9dR-21#3flu&D*G<#hAZho?#0It^qfsF3hR$fcwoOKTYrQ^d{xG-?M^ z-HheE@J@ck7mJa2-Wg}{b6Uu1KSrrdLcHqpVq3X<3!s}t%Mx zVO6GgxZs_@4L1g-fMGJ{7gn2qj;XHI^{(l<_VB&U`jnKBkr5y&7Bdpzp9Gfo#oE_C z__DMznW8oXTHmP=mQLKBbI@V5pL>3;9oR;Vw-A5zRW#CB(b8=MkA%?i=0P6GxOkG2 z6u!SH3K$0bZ(Ql)07m(|)D{Ce@yZRe{Qb>#$J zxbj(`fA|?*^7MDa04HeW^l7z0>TSKE0H1mz{vyC8#qJ24ICyN8@RL$+derdu-T^>q zJoAA1UTW><+RxeTu$GIl?0;MG&zxA*0aa$aawY{+@yl*RM}w%KGQN=gwR?o0kIVL# zQ(7fG#^11k_B!|*wUc>cBJoq7su>m^A<|XNEb`_1S?w)+wAjFP=?#0Oy!Gk^87|2< z*I7$O!uGI6txD{lpFu=d`AJMFhb}cO2&h^6F(Pt#q<(yl-L>9$xP92BtD~61^(>7e zv@1h$QICt zD$o`4wIzI&>BJ+b3^1Km>tqb0uCpORGB^khGP3xWH0D~{zqJ2ze|v5?rtS2d4iE=O z)6>BJBR8)Y(Duy_ziEh&gI!iL{Lp>dv;HjJth=t2KAz@oh!n!hFE=mkma1-cYZz=V zqzLS_>@l){@NYettgoYW5~pk-3dbYGIWK*THdqxyrNOXLW{^~rM^eg$ARtR9KXr)R zj(A-xlUx@$;iTvZ`t~*4@MG`oI!A?5$(gc)sfa@_+pc~Yn977;Lw|-F7s#J+qT0dm zW3-j)%Z=5~UP$T^`B$;d{F+(?-jRK8*0e}>Km}f9#{KXJ{F?Gzh;#8x9OR2JU>7-y z-T*+u=GUfp*tIocEp)2m{D0JMPQXOlK*~`7X5}Oh_72{^NS*s*&L>UrBWuiy;qeh6 z>P3SYO}`7T`uukfXrkta0#&rq#&%vVW9}ACo<_J~4=+MGO*z>X-ta54sK}&nj-ZSS zva@H6Y6FA7{SJJSLhNXxMp29Z`&Vm~YL+8E6aYl6rR_O$6+EQ2#vOmW>Fur0BB-~p zD~J(=fu=fkEDmxuKQw^SSThW{K+IQyowa1Rq2;SEX7#zD4>29Cjf@uYh$;vGPu>|F zrG;hMF4bFBy1{BY8~dAlcAp)(;e~*GTZOxLJ6=L~7VoU~Pnn8V;DQuWi%s#oRl1MTNpeG9 zEac=l-^m)k0=%_=^bUYGVkt~1d}?$mV9nFv%IW1Gn!nn*dLdUXeK>~5tn@*Hi8MH_ zIP|?tf0aUp^q|W8WR%JYw*=g6(vQQcpj7GqFvIUKf4%Gf}cVSNgx;L{sp9x)OV;{cw_<&>F}X^#bBa;Cu}BKM@tFu&}kY)z!sJk#m6^ zJG8OR9UE6XGkTRK-q^LdHU|V4Hl8Q$dY3E>G!^4NXlSf&kQ3JH_kaO(B~#?G%h)+{ z^%5Gn1#7`yH*l#;;my|xOtO|Y_!Zsv_4QfLO9vx~yJem}+=9I4*E*yC%ccWsLwt+* z5!h9X5Z8$xw9}QT~xhz{-6crUs zD;{Nsz%KaHStBESrr!>jB~7qrX}sOhrN5%x@!DF^JLBGEVJ?HPUKlfeRq;|AF#)0( z?mrfu`U>}&3x1nndLegStJ}Et;P>BeO9$h`a~c{B$SA}cNXYdlWjRG9#ihY7V*Vw! z@Z@R1q>Ueo12e5tI}-+bN{6)u`|l4~SqGz%a;FF7?EWf7HBKnzBF-8kD8#P3+}@k} zb6fta)CJe@BC?k=MlNuQj3x2B1)w#ckFc?bcw?9_8kUQSnO`DPK}YiM2k-tKe|Fh^ zyj1uTxPPSQwk_18^rT~s5y()=Q>DmX@_SosOw8u?@JtNlmWRBg5#chIA-F5UOakhS zavE&GsUm&mJ5@h7_!-IcgNmjI3KaoQpnX z)5GQCuQ_k(XDSNUOtqdpiULc+{5#fDngY@kb208Xza+S% z74+@}G+7V>ZL`mCBah$N?Tloe_4%T{3}~u~Jd_m-RZHX;|K{{ zF<8A4yQ~X(hu(60f~Iv4L4rS}RK%L5lT;+`M&Ss-fs=`us=I4*>oX!lLI{A=HF2qE zi87QSJ;0|p=T0IY(r*+KA#r#PTOf79M50osZ;#e??H=4@c80I6Ei3@}LIGyN=Z%u= z?@lQQVU-6->fyquk4-|5@hO8hTfb5|9#jc&6Gv$Oyx2Q zs!yR(UQvs!!S?n{UlbpE~KTa8p-nyZ`Ya6^L82Ap1y47 zN$Ot@q0s#&J)+fTuNx#LG`U9Bw4#1Kw<@dj`B|c)9}~@HvUEm#q&@jLdKZk|ChfXj z@B}Tmlhn}_X&qTE&#whe*t@t4mg(z|ydLvjx@$A*&#$O* zJ`RuLm3(idzt_B|J%8pFPSxg#3;?TD>or^=w{?&|Prz8paGVNC9{c_FNO=9M!WAJj zujlNq-KGF_Oh!v!)hy?TjXhd1)4h0=>vE6s6%QbGr6ch`QK?bFKwGV(It|<{ZOjH{ zg;;?kX%vCK@+4Oh?3RfQkURcVZ7cb1@qdzcE-3=WnUs|%((n;1s?G#c-ZejV@IUqL zw$%GBbTB^>=vVY84rjJQAXJ=FepQ6xoNDjHF5t z`oo?U2^^`qBz_9D%FMc4(WNRTjH<|D#!z9LzdOV`Pr6k$bK?j8d^5VUtIsJ7#NH9l zjRMvHz3p*NZ0q^$pYi7D=^1y!NfZIJUU3Eqi}$i$Y>4lx3AS5 z+S=O0S;X-_UaUL)p#ACwPzX)KAhcZSmWTrv3}2kT0EOd#{Sl$S;c1x8!lKJ62(U32 z|Bc)|xZ7eqMuH{_EE${fn!dkRp>U;&{3DJBrl^Ml;t;?06i?W9Kmw%ydp#LCuf3zR>y^edU z-TKmx7LDhCpQd~elo(g**>`@n(+kAEXL z&m?ZCOl|FDN3qBas?=W-P*E3!fXpW2N{m^uT92W;4}%^%gfNnYnuC$GCXnGa2(QVk znGfR*BO*39Lhk5e6r>V594l!wivlC=eYIqqIW2LDY-nnm5%}rUtmOn?!AEao0jb6K zG>tJ0{Ab|({IZgiYNK6h!3(E-d)E4X8h$s&#L+&hOgESr?M)%xjN5DnUcf;>WzZ`x z()hujvV-vmMk0F;NbOV)mBw%U9tSAIQ&+eEFMxj3;lEqTC^IQuGg;_|nUV^JbM$Y+ zFCHR+E0Z@(3vo6c81BA?pF!O&JcW>8YUyff0^wG`hODC%?Lz3iqu#hQytugNMG*u- zRV;GN{aa?~QS5V1v0n%;KTV5B&T4wmkzP!OMI)o?zan>YYU@~M7jHR zyeQWd1F~+Osdp%14b<+$X;8x=BHFI|2Q&l(HU!vm)n``B2+wm0sh2DtO!FAT?9&3 z=3ETv2T(N}8WNm=eEvcnajqf*6+#R1Cpvu(>W1(d3Kau!X@#2dha6__$aP!uJQYnI z1XmZ=;?rFxXvj(^LI!4Ji0&M;88meTTx^6TGP8gNl#zB9rq<#ePjyK&ZTRerX#ST_oCmO za{Ww~Hd))?=A>dW(P&EW?RPF}etS0ogu50f{X04F$jEvi{i@b0-E-W>>HJhF&&;`; z5XEK!d7*@%_F$t^{#bv3{dv_c1O_EVH3r|ppUYWGB7~McPlV%O!q33jC@=;MKP!!f z_czVrZIX=)f@poMHRB0Uw7 zo5PHywL!`ycb)4EEoc*+;!EVKh)WijerV`u7Lu#}A{Ht|@_)?ksHtg!0LL2K_7ibqzmt5;!4B7PC(G$d zvIk}I7#x9R#;B6|7ett z;z^)oUNU719z=TtuTb!wIBRC-_-|9AixJRba4;gtM+*!LXvR1nqeXAx^GtfPH{Kfx z&scD?bDuDlmzI{?NlwL`37+>Q+zYQ(oAveevGxR39-Nbr>f@12j$NBA8IKF3OkURk z`mmp}b!c4K@?4Tx&n-tNhX;{YUArW*Olgjay}D0AF>Au+)mw_=$b6~TOczn11+ubsmY_9JUp@O#F7nP z6NK4W)GCsjvoF?4bd)^ptmYpZA1aP5$IFCt&qe8$SUlH1G2`>Edyl<<>fHV%ijk6y zn2aI4(T|RAb_Nn5j^7of?yV1~&Ra}1cegkAwYMCVWp`~INFMx<{7wnodN0sbB$6Je z7rhTCS)Sk(9?8Ttfx|xr2fGekaXUXVVY?r)RvsJ6H$}jn)RJB={#^Ujbucn?v&Q&F*PZS=4+5w$@mTn$-7Aqg-s=YPz!RuUM4F~Onn?QhHt-O>0^DM+yq2#u(O!U3@#DkCdpXE)Uz z8hLFD6ijphS|b%s@%dTe2=2yGvYfI~*%U(pgj3B=C0iDyJa^=R=d7=^X!h^oEJ4^j z?u*9OnH->5y;ZfWYpa_la^*Xm<4J3)NTZe2&8~n}MgpT63Z3ufG2<0_O-qGAUN34J z78)QqlxcA97s8+PBq14i!Hg8uHsNx7s2t#GoNQrLPu{s9DLpSe!fBKS=i&+j+@%@i z*62v;Y`k%R`2AaH*|==p9BZus{`Gs0F5f_{!piA|$R{&}D$#&~0T!*pPUYM}NLPV@ zR*Ry1jAQP<&wKgJ^zn--e~(D7!>#+9bdrLZ8%Dr@mW;d8Y6*s)eVQg(&q}G{x5Z~$ z@@H4*O3ybd9HYw5D|kJnzDNLqQXbbX4yGb2@ej|<_^O2{Dm-BYmUfjF+oDr0=BUc zunI~$Dq1?&1@)ri()M<9lt4y{!oa5r@vL)(AC>=Fj=_c29=-Lk_@7F;72!TS=8_}eH_#_gt-8KKq@v`5E;Pd&ENh8Joj}1 z#iuS4!BzPQX!6KH;vl;XBV^5+iZXDE^C%y5u(!&~W9dlkd8mk%xEQa>Rik8BGUOdk zBVkiY)pC)A0o`)ILHpUKXz`z>%TU`9smWHS}a{b z*YBFhgNe{v!h?A+)RoPAm+I2HQh)8X&P>#*S79frsnyIq}e{{p8v4HsB zT67#GlpIVg-@~O_04~tc3xQE$wXFiG}lvA^DbUdG|F|UN}r&1ib20jzaajfcQ zr|$03K;wxMY~AR;*Lfdd6#Csq?%*k8&Z<+FNBUJf7x&K7VnBc*_SoeQN~SYwQ-@`TdtU7a<3k6FnMw&aPdQ(4 zlK;US8WrV6u{2y7j#FpYn*1C7Q1)r_goIv9X7GxU8PdyDL0YLFgQ%|zqj?@eq^r4r z19QD(al9|MeKJ45?>+|xT8u4k=LLDH3G53e@s(n+IDC|Mr|mZhqdS{UrF0G`J7#Ms!qrMcma zjlt#d-rhyWzZ~xFX%H-@8A3=lx|Dj)kY+lA%v0g8HZ~N(s?ac%2r3lAxlkX!xi3z2 zbj)&2Gh2*O8^$z}f9*zeYvwuGQibj|_z>sS?&Z%vG5f6TU7U#oa8KrGkC3LK17`$G zeDT1}-;dYbjsU+m7-PhXLW@H3?ivC09Qy>-Sv*J?n8N8!RfMczZCkr4MW_Sn{MjmL z5Yo8n8ZCyFi?~#HQyZ>X^@5Ot4(e{E>qoiB_rH?lMrViW!$w+;dqa7jLA`Z!%*?ny z05zEM&yM|f*{-1c0^ff)i}X(sTMT;KX0HgntvBXkfyG%9T#puKI?EpzOw-l)_T$n7 zF*QqMNiqcG2xacoG=Q@cV0EN_%D`NXUApfIzLafkN-WR76#hXK1K`RhM^BN1=+*hA z8}bIO#!zQNG?M$QXFy|BPRhlN7d4kp0*su2#gbw^PA*ZeVkwA}SrrCdL&!k_ySs~TQqo8xSljZr7|1ixL^#DCw1Fi zJvW0qXRHGBNre#GTmbcLEka6`qtdJW7S8;oJgh$#R5SQe+q^PB zk3zzjJR&g9K!RQJb2BN^zBkzzpTRdD)3uy@WTO%yIw$K~Rz2;6ggS_2@dtO5SKnJD ze2Xj+QR<4I3C>D@y`}HhZd9{(OM{1x|BF)Dosm4;UT^FwweY5E2G*;pZ+YOTW}MQC zjDXQ45I2b{iT};Bn>G%@LYR~D-ls|V&kI|LgHrY;k@o( zOo(ifVMS*8Q$CLD0FBA+?vkv;zv=h4Yo`vDYUgj>bS_48pL|Tnp`U0}qGj7whG86F zwqSr;;cnQ|4qP1*R}EDX;)8=@;yN4^Q`Vu6;By2YIN}*z%IKIZ_O(!4QQ;#7I1MLV z0liz94-}Sg8R5;~m!QQq)Z$R)QDZS-{5+8zzyGgQ!a!du;osoc&F~`2F4wZMVhrbL zL3g*01bfj>f|yx+puHb_w8g)U&tWXHh1J;5fC@6}b8kCc_W=2=Tb2`)Zoa~Cs_6I} zCyb#!7{gF#xgwWO?{{QTERlks{%>yer?fQ>xg9QLg9M#Dm|8;L16sHY&9!PS)1sxU z^G>FI6upAX;bQJq`(P~auW>zMe)WSDHffIl(-V6S9_vWH1^e`r)G&Yv?v;N=P)?=o zwGd5gZquON-Fr<612wOJCJNFupo;iX-aX>g3*CZ8pQ8r`z3vg*lgQ`IlhGm>0}cL{ z?M$StP3!+OY*jTxdWV{=ELQBTmk1txGW zy5~AnTLi!+{%X7J`a5e0xWS`+G9G~*VWi<82nzO~MkB>jO7RWYr_E{bmrmnN$*uTC zLPoc+)O$DAPVI8Sg?bdfzv+LW5^xN_vMzGxOh#XU!;Y5cM$kcq(zuYjgyU4>q-i}& zHQ|`PrnmdC;&m=_Wz+1+e0gb1i)-Wk1%iEz!czJ7vOz6R6apXwi~CV$w7Ii@GkGJb zE_a2Sv85*>ou?meSCwCh!MyA)pz&J-QDH_gK|!y&+F2#%2rcogjvC=Maw7M;p`LyB zo)T6*Rb$Xe#)tutI7fSUD)fB}sozMXD(qP%^8_Je<~MMkIRX2T`~j*+vx@Z6DONS} zQGNn}<~RU;sdeUDKEPNn4%g6VUEjGwCXT2T4R!4Uf%M<(GtHJV_f~0q2wtI7vq%0# z5r@+cubr>doR*7vvG z!*e>4|E6_lTXr^w?+^b8usi+*;L}5|W?%Qy3OUhy9;gM{$t+7;>d>Gn1%vN`pAhGBFa(S>T4&^jcL}L>j@+;W5Ddrw5Cj-(e{YX!jE&{d`I%xFP$8*jaP4F> z&P)9+{3WV04KS?hq{z{`gO{f&f`%K8K2a0rO7P+4mI* zqNLOQK6rX0?KL+HqbNrl-_k!=Se;&77_DvW+HZ1f%vooRs&G3v*ztp)@p#;qIp0z7 zcHfqH5fShU!U>3I9xc{z+Bq!#GKAc@_pA4cq!6~eZVBa=Y*yvw{QHwvp2HaM1?q`D zSCxk3eCz%i;;hNOmmO_-PIQRZ0%=l3P|P^(Upi7GU**EMXjwt%e;>~&RfVcV$VuwX zpH2ezA+UrmzsEm{@%a6R)r~4Md88F-gz$;I@<@0QzXjxS!5U`1|hES8|?j?ek?efxaXZs&!8WRQ)M%*jUAGkSZwy?<&e zo?9_@7b>za{LJ>z76Yv|PG}@s|0%wtl%j6rHwgrXWM}wSH<#R%^`tsucAS)dq#Q|t zV5hclNf1unOFjN08~>Ci3mWJH{J~RobjT&MKdHC6qa9Bb^ybl~hgx91;*A2#f#4OCtG%Y0*H@$MebOXR4+Vdq!13#B`V@OV<_$h%W z*7jdd3aui9P^kgm>Ye~;Ln8qK4k~0gB{0~cO67Hd^b|3QniLR1^L$c*^PF6z4{)G|svzll(#x8(mRAQg@l6hsP%*{K7(=rKD%B9a}7Z zjPdAOnHxRo+05GO3oFbz1CL63WcUR$^oz(S67P?)Nawwzg@xXmB>)!CAnI=C5m`*% zsF$dbd}fXO-#h997sAh0sT%Q1fUwf|%yJ1^(|ce283C;zv8zM+J^CfLOnG zr2ahM`h58C;n?7l&}Rf=l)MU;6QOFhLtNWK78HG`GXX#kp6|T{Xb=(Y~WD5+4b*l{rDZ)i|r4GYd7yRrMf8;7sEOhQV75s z0UbmW`}LsDkn(GvV!c!U_U4uS>z0g<3{0H3Q#3NxC}{5D(AqjS)2G=R6x$Ax1?u3w z$53bkQ14F>MDCPEz4sh9tQ z&XYfT+97F_t&v5w`-SXJUd4R<*Y%AMRfOS=TWfHSlOPUhEh{bp2Ko|H1MDQ&)W_yy zEn3#GZB8l&ztZP;&f*pr_UHnPlfo&00s)=ZrGj{I*%dYYqLTFMeuG|=t4v^Nwimf_ zRAjedj0{FJ$CpK-YOIR}j#$lthuAQlJ)(^ZG8q#0 zj398ZQ|pioma*{V&3DHa4HiN$xrGpEE-OQrH#1hs!+Ff?1(Z|Bd}?Ji1Lfa(LlxG? zCG^$vQB~6W&#IO5iC*{Dt*w{AyvV=*UUhYKG3!`0rp7dru`N$K>8hQk%d!QtU)3x> z-ZBB+pg1@B_G@5^R_pj(?W+!Nzl5ABh!{G@|&fl`*M2+4f);dY~g z5t)RbZc*B?U zq9&~>yp1<^Qdo4jqy3!Q8OV!)9GMg@r`pR|5(_nVin=uqN5^jF{U1%|9?tat|Nqfs zq>Pm5z(!;xjB-BCSq_<`$svX%NlwXGT8I@fMTX>*a|k(%w=f}-WI_%ljTUoE&cEm9 zcU|AEuKud4E7|Myd_Erc`|akTUEXy{f3U81=nObdCi1Z4bfJcSw#1(zlugn8z7BTa zM?4AHSE$FLiU|lqAqA^JOecJ%-ztj!jdj3W;mVs5>0zJ2KLU!3Ih(mkc(r0l4{ z+sub&0GX?_a1Lfb|LRWs+qykIdBo04i0h?%>BI|9fY&TfQ&z!>IDY)qBoWDa0P5M9 zR#Y*Z094qhEbs`G4}R&+R5-D5?1D^a7yNK?b=mXYvG(?TJwJUTS28)_|Mazw@kr?I ztPYL@ns^)SO#$NGk8N`DD&Rcv%eRL71?RJ$i;V9#X`9o!J5msCy{rILRaFms2nY80 zn`b8sinDu09w@Sw7;kFoSI?NYcmOiHHxwTPfZFl~ygKS!aMR%2Te-JaBs;HO8T$Tx z7XX66LN7)TDohO2Il1OzD~mpL?zch^nt!@qo=7CH)%;NF2i}HnQVjnnIB|oD6ZZ>xXvwlHPK z2}cvisT<|erajevVo~|-1y#C(+AHvOpd)hArQDugx1)TxAs%ni!mJnu}Uv$nyQm&73|I*cWZp;(|-6gCf>YQ{yZFX=*U%G$4o!n zs)ND`0-NylPQjsfe_?-;4@O8dAErp^1BL8+a0dn%yj#R$)B~6eI4_Y9Q|HAj9bz!f zN1i>~S9c%5ed-c5v%(g4$+s*wnay9G4bJ5cuP6U_T|vf(pt)dR8MN7=(8~`4=L%+{NGh{OT{VL|5xM0f@nd0P zw{=4`YG7?g(|Xd=bgS+#@B@izL1d-#DduJpG3!FYkVhl2X}&OJ1j>+%=|~^<_jPl0 zlMB?B4XbID0k%affL!_=gOH666F$!x+ghk3RjaU)#Z7Gwg{zK)+9o>|^}mjCwat-<=( z@C3E75gT)VtEZntCSJekyPkJopi2a2b$nUJJ$2ikc60O)AAbjQs+FGRshCof$94JNL zLbb%Bc4kB|{|dd9_4?z|Vd4`F!FN~_V;q`lR=;n3>E5dK-UjH{*ZVk8z=NlOg7uVF zLv?pqc%CuI+XxSCQGSkF1M=YQ&CTWa*SZiasu>#n`On+_Jld`I9|dAmWAvhvUmcW} zG=xq&`dX4cG?>C1_+!s|%yYLJHQ3FkO_xh1(@_ULrQs|GC2{B@d1Ra4S*M|59y^MsOdEm-6g!WMaZf#%5%`{k zlfV)j^;1#6C^zxdY~vxJnn$0*S{*8hHF)OxgY6(D{+7A2Ay2q`XF%m3&cQxtQU5IZ z-Bb!n*lGi$UhM`&@*3yIV3&r278!@=S8eU>juO~7E>ub)!q(=f&b^qcB1Yu<7@WP4 z-4*jvYH!hHosu6zYm$@iP=?Z-{xl1yRln6`ykR_3y&xehcmdev%@~=5=ia)TDi&mp zb#@K~4IjcKP$Xx*sOy%P1Zh{(!Lr)!=%f6$uXR3YBGi?6&(yWO(wQ^#Xc2Wnp+s3g z-VzLBSv2S~rp8ud8BCrnfTSF-;&*1+O#(AA8B;oRhK`7dn!d2mMBa6yoRMzI6-0f> z6JlY_@JC0nu8)i2EwdCj;-acjsVkC`e}0GrH43y;?HOD-#M16uxA!-iN|o7T*vAjRK<6M z^{bnA-*?}M5RSR#Jgm2d5@N(|M zd%WZy;P|OEeV*FKlF$W?ixxfg%!728e07|zJr%=4e_acd2ax*2&QF3+vzG5_L?gVK z1pKMreZ81~iPon9fWs94c?7@1w57kObMn2Sns~e?;6V5!YEp{+@TU~YDY(a_;b z6Z<~)`|s?(+3i0kqM;m>v4i>U8a3~nPy{2VxsrG5vjaKX8#ykM^2+&5Be$A^6Fit!t=$H5;_cZ~;NNK%eByl4_lnP$plNY{XVum1 z8SCBUA48iGJ1;9+% zp;|YWOP7G+t#^MrCB>a;^YJ0^iXf=*U-f3KfV>EXK3WJa!jqF@wz#8>>GK~GLjgGC z&o3}WeLr_4RA*5Hi z8bQPc^bst?Ti5Q<@T!&vpnz9?Hy|Jj`R$vti<7e+nJ&O-*I2s9T**Lpu9+H!lH>gH>;W(o4?*V9{@! z`J{PW94CNrKWYO*L5bAbwkG&~@BQAq-c&)X8RMOsWLSPUcYYveYVrHEBzE_`TKvwm z?(TDY1(!oU$0Meohb*7fb4PHmyke$ zh`PKxSg2 z`RHR*%hQYS4|F0OACFPv}VnKF=`5=w4i@TucAUxLYp@Dcq-6%@if+ ztLN-DG``(t#`t}_x&_UwOFH!k`)>+-buKb^jA9@uk6wM@dwG15^54Ouu-GZMS3DOI zmr&@-u0HYjceR|!v<>*Sb(&n)yECRjQ8IrN@C0*8gmQ&1_e5IAMNU=}Sobpm0dQW{ zsQbpEd|_Z@BnXRzn_?9cE?wbaaX-y&)|qRp;DnZ6fbgNrrPYaO<3Yj3PZXSCk6IFD z#^E^HihdyX_ZCGeIg99Yms_vAHbVJqc9g(f_A~ml?JsQ4%FqW(LAN zGI-b%rDL|Aje?r4Dw(T`VmkWj1{%p|{Pce1z;-z534NLqwMuK>p)K72pG-5wtgNiv zm3{yMc>)5(5|}hG{gmmN=udKgZSyZf5f= zLbq8*bMn?G_H04Wp}KXH28Zt@h8fZ&CWzuk83-gJL8M7ik1EK=hjU;Caeo$kP!)TC zAtrgh`cm69)9$V7`;$KK;hr8iX^bu!^Q@UD1H}!`8nijBre>cIN;sc<(T15;wcxuq z-+Hp_cvA3Nd1uiuh9jF z`^h4yNnFk}t&ol1nK|1tdv_v2G&BA{=&7lL8w>KyeksQB-I`+nl-oj$jJh%VvY-O6(`uwz@#5gT#ePJPdbC;Ksm7V42;=H`EOV%~kJ2;3+Z!WecUB(|Z0)T8iS+_AC5CO7JlTZ8cfxmzY#wDN=%8}3x z-Jbm}B{6lk>Rn5VgX4Ik<54rNWSqdri{B6W^^wd`IZeiw99TEcbK!qe5qFpk>5{p# zgg4BMDL#~kjVa0vrXwSf8uWc(oOg0>VLgrcT$E)}>Fh+!Qt2~Bi^b$Yn^zo{L$!Vx z4cy)Fr*Y*ow`S^|I!H}p(R4M|+qp4|O+TjR83p)%Q0he@h_G}&Q!LIu!_UCK!W5_> z3^L+T6gx}VxlM62Oy11`PemI(;p+;|BEbWkt)96MKSMp_3cd)&f}JGeNv)&6%v)w- z1uek$x&+m`JhM>0qk@xm83QcePJv>Il(4xe z{@JkVu$`S5x;crQ3y;B6yuCdpV{KB7@fk#-Jn(lI_N8lmYvm&0G)Ifm1QzW}qs0Dv zt$&}+KZYxjUQ_&aZZ|R=deKUZ2g+z;Q*>`7L4e|F{s`xpbr8diV&cowL|&cTUtnG= z;t@C-Mt=%Vrg{~}Ry5(|(nZwYBtZ8zm$ihGAHI5llEx+u+)Hswcw~x>faw^TU%J_+ zw$9M!?h)gcKd|;aZW2VCqJo`^f9#HHw(k82u5@mBN23+S$6$(UtzADH_B5uglaf7~ z`h>sbvP(;Dk1`zk)z2mf3(?j^Z1}S;hREET6l8{?f(CCT3m2T1q*ExkiH)+*m5Csy z)@CPvI^}cQhRF22^Hxxpq>?*%4tud6xq9tp+AG$HBY6*T^sA<)pz(Z?T=}O85Vj{Q ze{Y2U-CQLdz^4s8;1vXYv7D$C?xz7L8BIdZ2si*$7N&ZU^JPm)6MJ32r1_cZFyrgS z?u4jI}NLcNWL7^sm!@er~#%x5@k4z})$&D;zM z-+m$F$Jrf+3Za1s{1wYymHBRO6|hWwX>0FF_@i$r$9=Q~QKfW#r^wwAj?Qk|Rd9878bVab9U-M&%bo6w@tu0M+*hdiC8Ne zzipRWaK+BaTsk>AB~T;F(aFidJ4=jmImpQjg-dYJiqg4SQ{SXnQqm2woPY8SldBnZ zKEr3q8^A7TJZFBP)9^l$B}syyr8&+y%_-EI#kHSBz(G0pf3f$LsJ-u>1dED@0M7)* zL@1KEmwrRsoB3buIeqv%PPj{ng>c_~i3rHtKu8k0HD~@?;=k%);(616Ky&IQq)qTCaJL3{H?I!#C z7~DS7a;y%2t;*rt!>P>qD@R5Vwq9v&-^x^RrSQC(CsH?^0%=~Ob>ff9E-(+Fpz?@Q z+)%YVdSe|MN~EX%DVTB8<349M7DWCm;PIVm>ppVx?89XpkS2x*oAH&DsL;7cL*S#- zt3OSGvu{1IE>BRRQ+D2bxKXDqTj2lRcY?>$z|R6*^hw317vb?i_C7p(GH4)#5rV(W zo<9ma0!D9JL^gjddsaDy5=&o^(GwH$SJ*+CtJt1g5J5?(UT#z8U>7}X^aM0h=jy!b z#(pg?D|P-X8!%6z=RuKb));I8xk__=fl{y^8vD^fH}HY*kDc{NgB0?-Xzy`juf^S8 zfA5anrI@k)xH~E(P&S7k}03C&QX=4js4$2baP6_I6 z$eDH|cMWy|_p&K^T>dt?t+528F3M^>?1W;lFqY$3-PYEYm?a;&AYGQg9HqR%`HB~> zJD;5|Tbp<+vvJ$h1CL9-9z4n;J-;pnY;icRq;RQ|{<5f+N>=7=W(kepxn|12e?Ccv>V zsOgY#=ZJ=qRE^TvnzuJ~~ruJ?n$+`_NIq+gxg6PfS$q3=&Fc;0Q{MC6!2Sy?q6c&pQ(**3^D=eOXK z&Sy6^Ry4R%lo@ji%!OKS6Vaj~Kr&Vp6bIRc)7P$DGrmSVS0L~YScxWb-BSeg6z>b& zhq*Y)gE;`+3e^#c038+8HARqa03mom3g7!15Z7AgL!S8*;n=@-?|QC0VoIUhZS4$( zZOx^L5yNLQW{hM+M9r_0$+c|DnOB0Kt6iQSBP0;fFAHj?@aCj86XSQ{#)QXH0z&Zn z%2$rF5%wrILc7}R+*^0@$pwy!X5;41ZYk1Kd9W{@g`UP=fx^cMwHxog#aFg$uT?&A z(MfDmv^o*J*EhLczh(b~$^Jc;+7&UmGdn1;LyX!~h`RUhUwiOvIZxXQS*)6K7ISSw z$47oF&R_F&QvbR&lBCO{SOI9(2iso~7Ezlpi2l9V(Yj)K%agWid5@V_GW`&JFPB&# zSOu&#Z!KGkRk|vZDo@PYCWwhXXZM*%L{!sicQ%N+hhwf4MVM}iwT|49@z}85TkVu+ zX^ryp+t^Tux-24WtoED1D~K_G9gt5kiN*;#E>5@tmO z1u!Ipo&cmH{eQ-G-Q6W?KI7oXy|wnRb%r&-1s-u#dn}q+H@~TqX%$lVjO~fH%Ph>e zt*~sSo@Gs2F~Z-C5aiO*)Fj4e!r^TRi4^t$K=aRRywBA#_xG5Ta@vgshFCn()3i7o zv0pnK{@?L7ewmERF?P}T^nIS!6?xARGo(vE7C3<6WtP;O@*{&Utx$5zIe0|b3#g4sJ zDq89Pl$BA<&<3i9J7_8WhOi8SpuWr6E8tDYO z(Tt{>P9FIEdY5AiAZ05-!#U25v53(+X%dvfzN!4AkrN015niPSyR9;$xSDD<5;T8H zg{G$4Tk{doj#!_tCMu&mpnPioy~QxqdmgH&h}}~M{v7i=PCjn1m;iG$N%87g*|Zo# zxJr<6xAGG)$eZC%r(u{RC##03nTkGQ5XcZsEgq7BOR%GlVbg2m?dJX=gfvkquWeR?O*Fwe)#Azm5Dq~s_Oj#@kr^*ptX9d z>F;CQ0e#ffLVu{uVhg(wuvi;anEon@^Chf638go>JyUxlJ>UuA~t4xC&SihQ#;RHB3yW1=MzTZMw-&0TLfahIh%jWM}4W8zqqOuC^Dn1Z^{6!?n+vi30h(4Zq0$k zV;*PW4vLlN6OW9I7ZSjd;_nfFgVAAl-oK%c5=ML#M3@Zowv$N{&RVE+ZfgAMAopu5 zrq}-T>0pToiSq3ETk3?ppDVie#j~=hUZN}2U)s|z@({FiwXMaCP_li}SHc~Rs=J;p zs_Y+Tm&w9V8~KQ}sr?aeYD%lW$uyV-o-mO{!2GpxtC^1X-Y3rOif`A{W8$M(N` zt@d?9`>W;+_TTQBE>TgIrEM1i7Lt0voWHQ_0|e42L9Ls(>PxG~(4+NUmA3=Nl&|3^ zGFtVT5uA1avma^`kL-+uql_>Ok<-7zI8ktH^GaVmfNS5|T}5+8!!P@s5#0y6b8cCc zV}FObyA@x!7fi>9dWaD$Zu59s;Gg-1s!+v16@!d{M6Wgepgw@fcob6%Vb=w=Tt6fT zU|+7yf>E_I)#bI^VG6+lk&EQ^w$Lzr2&cQoV}!B77PJy39OXk^=hBBkR^^YBxVdQn z^wp~mplC^inHP&+fFK8oPtUj`OvqI!!dQfqY4DZuT6j#r0`=ni)86GPIvu8B_hARy zArKKqiU-&T4hP}!9aB7n`A-e-{pGa-y}iI-`-~Mbx&FNOA|QYYxq;vJ%maX$M5#4- z;%1{^njG5X#OVHshcM);PIpNjQO8T5!ZNBJ4{u8kP|39POjV+%qrYR%kIMbJwlXK6 z|Hj#=MJw{YB7k$0lmN}4RH~cO&8#=}aDqfQNr?M;txbshyGuARf)I%@+HrH#K@R6H zjGe{3Q8SFGx?DoFKw)D75L|g5uVu2-r<>;*^Vq|2`n(cvRd8p>bNSSYQgiPxfByt@ zww0&P7_i7ty0vt5dzS^U)b|Ui-4slVb7f}X5iB!kIB4f}-|H@tYZ~r`wlRzx0Mmo# zi5-lF9Zmqk6dSA_+2cwyLOCt1(|tDdy&@FCEu#09!Dodr%(y(TuiFS`>1ob~imedj zdIyI@Pru}&Q>zeqxz!dW=RNZg$}vTQ85kKrIkk@opoS)zS1ClHU3AVlks zH2vnP+-Bq@b7Sc6P)P~oR7^Y_IP${Sssob7j=Tj}WGSMfxGM+V` zsXCz%x%Q*CGExdEL|$)y*L?L#>F=d!6U^rNMA-VT@^#Nd9~n|jor40fUOcIIp1SMWZbVW)A# zOYd{EBUuYKZWN(iBwvOCbX_|}*j*N8nQK6Pv%%J;XQA(cSJIfEn;%bJAlEigJ z$94ZB!Q{z9JDUsD;a3gbAt(msxiX^o#9(lH z)kIg`C^9l~_xDdjQzQ5b>moBzYq8o1H>|O?TLM~oq#^3N(e?CEO{}c;{kOt=@d(9=)Ajy|f&QGIaM*@4$wkgAQLCc%&GzaP5IROj0 z-D=fxqF5}fEArDc48jd0FMPQODf7c^Dh}S6bxRmUvX~4)AEEEIzVYQx=eC#P{2Ye(Cq+gKY^!6 z>Tb88`5NXDmRbc$Bs7YDgX1e*?$Itk3;T9BcRUyOe}mB?;JXzK9#O_u9m1}9vm32! zf;f(o>kRdE;~%1*do)nD#R|M$_`WrUhq5qO6lu!9Mx-r_qwR4X{~U&j7*;0;6J?9j zCIcI&H4H8Y4~sqmd$saJsYh&m!j-JfLfr#a)DociGj3ClNxpdD*!cRsT#9hDbGc&7 zOrV2R5q0I%W6Sklu82#}QG`4XBv}~b9tVDb580ZUUOb^=f|rDphDvFXM>}U}aTsve znQWOaM!1xV+95an{Hu?6$Cl;TDY1EC&glZQ?EJ6 zuQZbs-ON)V=bq|(cBBB1$|(dF3{KB%oNLtirw5yFI)tK_@u4hQlVEg_Fctxz9D&$4 zhK?s3d}WC4lnr~p-{D^Cpbt}QigLiAwl%?Tbs)K6e2_W&t zzgV0%pDX-Fu0(BZI$WDPu+`$LPW+D-Fe;$Yv*b?ro&g@7ZV=i`#7#45I46+N>#TOTp#jx>M<6PqH`Rx8*^&Y3Rqfz%vCO zR=y#!#M9gar~&35j<=n}0_^G=oUp#BqNSRD!Da3eKNJ!&aSgtYv}6r<^ux?B5$}i=$QwS+x$akrn z^@wa%m}VG0`-o9UNXS6#1(G=T`Bf=nsMPr^OK1@(xtf|^SppZhZ_2mbZ5`#$Vr2E} zZsBduwQl~tNVsrB%=Kp7S3gF5sjcx;H+z~lN&NYsk*-7hjm3$pni&*)p$gk>`219o zx-qL6SIuc0TnX5A*%jUE3E5i+s~1fy7PNx3Jp>LZaHL5~Tv@5V?Wn6BBBqZ-_?GnT zgbAu<{-QswU(kMct^B!t)2EfMTr<4x;jiE;LaQXk$IGUsb(R{LM+^E8Y2 zoYW0Ms>G1xWZ)c4)-i4Y1jW%0aJ5?Dp?P*q+1ayF~2-;eSd*{QDkW1rm6@ z_FZl2Xz2GJGrhx;5m9?ni~Q4nQmu9OBjN93+XCCwGA&8M03euSMFcQ)6Z<4Uy3~YR z&kzM}>knPty!O;3-EU3(X+3E@phIz7+ZaAtQOg95nUw$0i1D|qYffOlhMB0fV-7`3 zvQfP&M(VEVs}Ew+`DJ2GuBpMXdxoJ_ zcz#5QkIo1oDdv#_p1{E)TV#wt{jU1^aPk#P@Ul%;k;xF`f=sIwI-eqH%`6p6F&xnO z12QBC7D;MY>9umDO3XgG`G=YnO2a_lM*+dBTL*b~Jgd4QmO^%eD zz{`58;`m{9U+0ZKwLwS0!Qy1?A%qd+%24C+{qZkx)e?;`ZgN#Rg{k3vj*NNK)96Zu z`=Q8H6gM{YBPGZRmciQi6eKX%8BUkISaU;KngAF+gfG+oHGJq*!rcD&y0;ppb2ASk zliK~0CODa6Rpc~$AO4ux)zu{^uJdm-HEHduZp8A38?=dA3Fr=@jxl{BZgm@f`tQeyh`$4vrDG5U+w7(p-(@8);?uGzi~Uo`p?^>o`?Dcd9|3o(b2eXRhx6hYa46 zZ24b1MQx4o*C1eicJr1Bn1;{zH&9ZD4gM2ak&Aa|4%d|Hf-W4oQ1sg8_c*P*vrJ7h zY@Sx-d7gRh?%&!V!tiBQSHeIdkiieul+W+9s0tav^MbCR@y|Lx)wZdlPDzWPPGA=q zhs^~K2`={4`--IcYh*!vVbZu6Vi9Y7VKNTx;^=sl5~N7bZu4H&%JQ5LL+LNc`b~ z!*cP@_6C8gzI8XV6%a*q_m(*9(1zLzRi0{%p=)hoeV@wfK4>iXaHd|_gx zwX;^(-`}0RRh-zuL`*ayttUcY{L?;CqiYAr9T4je=Ta^l#oovYqVMO(7FdoW*g~XP z%Y+U;nF%#By+8&WOI^XxXZPg^7`}eYpqOXSe>z%s?&A6vX;@TD8`tS<5Q-*>bBhAU%B3fprn-PS~k=k=~S!o3<%*f_caPmZK z!vAFfJTw$!6rQfTYGgf`MsO`M#JnNU!EO-()!*9)&yQlVgPebwozG7Ak2E#Z$PE|n zK|*2rWE<$z&(-rG7RD>FI2hzzb2HWIG>GV9Nznl^55JC2=;&%@Qapx});Zc`C6-R* zf`WpW7z}s(btsoXv>q8{iq0&2%mqKAC@DfK$}PvQ6)15|8Y)6_dQL&5+VI&PPGf#_`1@%!ZWtdZB*OqR zJ}e3Ol49jKIJNVs4uO?_7vy_rRNQdB{NrWSRmzeX-c(vRB~9oD!2*RtpOWe5yb-QP zxk@Y_!kN<%9WXa;#WTv%YD7{D92GyI(XAf)#_J~03Hk}&&vTmO-v)ueqsOzdEXN^` zWjXLd&57LX9&X(l|GoVFSfA_>oPfdJ_Q>EGSe37S-1nhju}vRl`!gN>qfD@kha&`x zs$R;!JnkcZkO=}pP{d)P9GE3#C>c_eu%6rzovyhr>{@y)zy*zw8ek!WgqyL}p|AgMIN+iUQE@ z@Ms)<_@L7y!QxlqMmg}foNz2=|C(DVvb0q;?p2Bk+D?Fc4f2@`E}a=UB|502s~fhn zJ(o)C7az8)O}F-!CVepGU2eX&JS!NM*iiH9-#Q=Npg1)#+A z|H!3sf7qnOOSO%ikF6-_OKbP8 znfnvh6!k7-#TZWkcd&PU)3Qs^@HQiSECL1Oe~F2`se{8?ym4@xL_}@zax(;SM_y*| z5%U-%8riV%w>)cyrqKHD$6RWh1UOrSJFAsiJLg3HYcuKXy~t_5Nz3l@3~SO1{R0Yv zYf%Bk2vPRX@`LsNttdxS!SQKzV+D8t-S_UeWG?+&GaE}9u53MG@RO?PjUq!2lU@ch z)On@8-cpIbPFLp^`Uih-ybA@1#?UF7h~I@Rj?R*#(wW~qX$BUG#_3$hw9jo~-oP?* zSse94$u>miZn;X{8e`+motYcn#Nba%hr_Q_nfaF>vGF!ae+?#UA%}#K~4Y!K5c%ceVlcjV& zP<$dqxSTnFm^b(UY*}M(SNTzjbTXidVUyRmT%kw`)}lAYMj(cTqh>ofI#=kEASCbM z3L$d{zyMC|BVJaF#Q^9%8&d$cg}1348Wpe$5|ctwt{vZsv{10TbX3oxTAv=mZ?+DG zc2kaU^JU36xEhBKMDjil^JGXOKNSumR8wub5t zd??TjQtMY+0lKYM7eWf*#?e!WL&7MmSSP}j41Ml_S2T|afJ3|m@~HmIgAt2dQrr+d zN(c;;mXam=Wo5eeVG%qKMUrep9{nybXsMwX>c=1W?f(2Jf^~meK%v7EwKA=X>?_3W zGQkl=KOQ98tGCx%x17l0g!j-mxCx{z$j(l>4-5UTYgYfWmoP_*tYg9gthmY0){3mm(0NIM3R``m-@5f{Byqalcj85Vebl?KdQOwS#(m5^mLzoa z22n0%sxKVfF-yb9KsgTtA(t~ZciVXxjf^LF{70F=;vPP|0rgqJ`1wkO{*0*x9Q94O z(nAuiC#D7!dkg2RuF>efrs0ty{F@5yXmaRy*=Tq(5n5S#p#z4!K`SB)S;QPL(7hhd zCqw$NS~efU?s7d5bTbr(O+_NOFCFzL^iL?}v(b!No1G=@{itbwKpVOl#95$q2}iZ^StGctq=}ZJhK64Hen=TpM!@b={FwNj;3{f2{90}jBqE}4611x={=n$gW{Uc9QNL7sDxpN@4 z*I#);eE*ai*67j;4{oU!qSEg_@D)jcwQ zJpDnfQuR22`ti$6+7qyhua@kup%-$JQTUUR?h{>w;;r!2nYC5T8#5*^ydP$9_>~q(%9F2v;LK4uXNofX8|6c*Xl9re*N@?#@rO(7krSC1TFbx3~|82ykUoyn(LH*;!@z zjNwatn}beHfBBk3T}d4#PKNLFfiRiQUS~fid~2%{oYX~N*|@UD!8*dP)a;SQ(qhIp zX1itwKm;ptBhlrAgl?8q&20qiXuF~YNAT~u{%X+Rx2Stjpctfs#(u(1RSoZ4uW)Q& zR;VJrgD$lRS_rVmLieVoR9iRZ%Y$#zc9@T&cDth7NLmrg?%v**jG2hZ$l&$3;E9bX z`dIzm^SzBp5G(xy4pyzrYLgQViV4~f(Nd4GAagVsSwupr1?E-JZ(cGT81J zwyWJSrUF7cgo{WKVqQ2$x^tqo3OGDrpv7_CXRY8AbS**EK? zqFb)l0ALr<1^9@!f&hc;qV*0QO<|NO!(Cm_Cj1LErpt@OFY_Bwt_%b6_iW zBJv<^WFh@~ci!Zn%}`{a)%H(oQcziA$R+AI&%}A2cp-gRXr_oXAZ7_e{JAdmG_|m| z7&jh6l4ERp`sG1}8w(>*aEoh=?-AYvEE%6I*siDe%MszNoMtACY4aJ=i*_SVD~cHD z!$!_uCofR~72xgj^m&9Xc*q!12O7PQ zbe;WVMdC-XeL`;Oq$zMOg~sr~UaCA;&vxUM>>wQ)9g2v$+aQ-FOwNVD--n*S zhBXut5dtSaDm- z1EFsLXElGYD_kD_?lKfx^SE0-q4fyE!6kqzpkjw zwO)H-SEZFzzd}F5Nk=43=820^B@IaWw>~ojxh1uEB?m2ehgroY`weNkS*KK`T zT32>9=H?V4H$rH|Fs?+SjQ_3*Va;clOz{G4NIcvE2^aZ3cv_*tiPqSxWh9II!}mRC z+&q_pOA^=S*P&*&OiYYKvPYj*5y-A5-qz-_!7yHRdOr9z1{ei)6g@*W`m!{2H|DH; zCz_XLL|xuyKGO>f4E!g$_q*RmF_^RSY3*;Sb=2luQq(dlYWKNA4b+ zXsVwCH$?G00!xC!<7JE(V$Z=)8f7@Q{8TG$tZ9qWys{hU0RF+7yJNl}FWZc-TvaUm z!~N>&(S}672Is6SC!Bm?jhKf8Oblz9Afzqus7cG^V`IfM^*(INPm!q;wUlBelP`PP zqfiOX)uz_(-*a_xJ+&L?)9NgpRE;y?fY3n__C9C`k)jkDXY?r8pN&rrk_RSFUbrHi zzuT>-Lc1K<|&uPpU1|=}l3%xcgM6t;Dl&gkj>H-Gw@`p2mtGw6< zZ4$DV5+t*E$1fy<$V2>wNXTrI$n6jS&AOpo z=y;Y6mDE~&aQy@~f)F?XUJEi4yf7Ows`zW)jo*zjBw=Hz{UkR6DB}*!i4bCNe%vuF z9I-rRrbtI83#=$-pVe*NR#xSI5z*FEcRH|*N zkw(l2?1L;!MkOENncm*0Ih|S!ww|P(?w{XxwtStM>RRhXsa|8hMpi_hKks$@1Mk4R z?=a7{kb$PU&SnY1zVFZ;?ES9X+l=}ru~!rf+CBg*vOBLjIir?L{ zAx+85xUDhLzm>t~VNC}_|9o$YT)aJdEpM%s?VF|Wd~_q&xAm~lyQ@yOM^%i!1i!!l z*P-89&u*XwXY>2_>7teL@v-_zF35>LoUE*DB@33vqnA;84}!J*CwIOJvU=AvIZ@lY zaXHXvM>2o|V`LUL(;n0e4)%ryR5{YZcmIrjKVp@!?)ruPPVweGfVAg=#8nBRkkGhX zUndZFC|B$jvn4l8@e)qJYBv5i+P+Q=Xe+=WkkW?r_~8Fp@c^({{G^is=^u=4vk#sM z-{^BbdDt937S!g&z`tq3KZpE=yhlhu;q*oN6HzdZ@qeU zaGC!{)42yS{r_Klv}&ZhUA|0-jcAj!rI_4DViD#NqOg$U{&By?Tw>vqRYK%4axM4V zlT66E2(erums+fH%l-HI{PFAm>W}x{ulMVDp65JHCqc}m18~rUlN@!Bd6Rm>0YiQv_ zJ>NTUoSLu}Su;Wh7mg1@MN9j^aaSFQB+O;|SDY<4!%W0g55*y6VMHVOU~4gNB{-98 z@Yw$j`&}IPN~6`p2a8D8ztT&+GYt@0v_0|&9k`=Df)V=jX#zb=F^Lz3VtlmIqqeL~ z6K-e@1z3G+gfw2iR67noQh_b##6iXooMwhSzcINE!O%FkT!vZr>8#oFLg6Tc5dD&) zEb+5lDxL`WT`D!Pvhv`(y>%`DrWLZPIH=&_PH+wj&Wj(+*94=JPgG! zAViGAe}NT(SgxQ`Yl$Px`Uu3Mitkh>E=}r7)GzST&6{78V~7R} zz`1-KEOn0x5bA4dtr=X?W7lCNZ7PNfJ{bFOTgVcL=Dl!3{mv(G^wArvMoZ_`tNrz2 z1!rv^?S;Ud6F;ZuqQU#Lu+ST+bQmlwf3w!~v{NXgBl2Vq@*zfv-UAn~1B|O4;)P-I za0Zfj%7=)KwH>0(lPz^{Cz2uU1M)6Z&0->zlpdbC*8VEvmN(ai0xT5RL1+ANxE?H_ za>CL>i6Aa18-w>BN5^CzxNu=OrPBT`%9&)%VN|)QJeF<`orzsznI!!wdj`bctL3NO zfhK`x!<-9((zEANgn&~77P~g|ecd@UBxHSMcp_B1K4^7utT~J`bdu8vrp)Lkb|-%W z-}qC^d6===67Vr9{hgRt7ZVAeW?q4GVbeGP>#Um&aS*}HG)E)zU2(e6K2#!1xHrxc zp*$A>o194&Kb5Qf*qC(5_lo!O=Vi};X{Pz`*=#K9b+X$j*BUjKPv^p>XRi!TG{wU* z`sX@vp(2Qv9}-L)9GXMxFeHw>>gceWc&v(2{5!49t*xni&yB&EA04rq+PhoVe*Od_ z<@TC*AHU=8;@$OYq(@{Z$M3vY zL!U}2$2ik6AVAsI;7x?&GtO~v%<)Hg?$J@50NL>J`ZtpZM~DJXbbJ*If4?VMVq$y* zB!g@e>viDmJ1c;X+P*gbwX@y>L!q0YU0}ZNo1~Y&udC@GV1PN`d?^9K84&+y^cjF} zz8#Qqsfp%+8$YhAWHFlmoxDd@hX0_E4>9LQXVu?9 zpJwua{*k-DJ!Mn*0R2~V;o@x};+-_I#~v9+`lVw37$dvWj8Ti>0CMkZi)$wz4t)Ql zmMoNl7LK9Ndf?JLpldWj5M^`uf6*udlrkS)a`}y#>CgqPq=6yns~&FX+#J?L=;enS zTzi4r{*i%^MR!@rz_8eJ>s4GLj2A&WOBIIc{y=Zr2aa?-`dqG z=yHHnfa>8G9s@%ep3Z%|V)w-8FCH$J9edQ{_=$MnWTamRlNR*t>!P1#&)!BbF}OtEvsEph>-o14u5QAxH;2pWa?YC2bP;^8 zPwD$mt|uj#h6*!!n7)r{M=V5R^wPkit!|UnAt9Ww*Hv^5c0w@;sGW#0{t$18f(#;7 z4V_5NFUGHZMNYHANG10`zZm8cF2q~N0NsVO5W6JAU#94#ec(w(9j~gp2JW`NlBgS>jKszVq#;| zX%h>F%OGQMA;4-eh>iI8{joYT14Qv|HC%xSQQz2!#8hx@B9D74T#(*QJgsm)qu=#- z(4q{LHQu(p%AS}Ml%Cj+_rvnSp!B66@x(M!t!=n2Ootc8izqVZ25u%VCGY-~-r07` zji}bhCSD1Y;sYdqp09^jA-^txYdc znvp)&%rXT_+c z#p)0;Nkj?oJSd$HY@R>bfoV1m+*}>s-poitiWm^$4JR(2$j6Jx8bgchA)1AN&|INo_&10c+Edc=*B1C{xkW_rfde_jb zqH9Pfpz9`PuR%m<4Skr1fY58W2@{rvV-DHH;L-YiLVCAA8AvG2$l=@xF8cqy07LAt zOZ;D3`j@W4bb8NGNXlQGRdTOzP_JMpw*_1Z!kP3mt@rQ|y(je910qy2ejeB_Gz`J8 zI-ls8KO>K>Q54%R~|v2UCvB= zbWY;ql^gVG{x>Ez14X@;+*Ils5XWc#y%`HKs@rz9^4yWa%=0mRyj=-t+FOzB`yn6Jf6K->O*ED4 zN*lSQf}~hs5RSlke$^esx_ef9ItbJ^=ajR~vH%gt>ORp=`qprrm2GsndwpR0gufDh z2`+||NbV)_6LDw)_2phcEhgkg<&k;6qDg&eBYVL7DKCWzzV>__FC6g((a!_g(#{lR z;NWmRISeJ+|I$eK2g~z9!1bw1tE(a<+KxrjTW@?0$?XgaLEmhZr90DF4xkOJ=vHF_ z({FIIRO3+oj?{s)s&;gI#IRS8y4BNcwLsQTKsu~;s5^rwKuvQ$EEIz%svk2d@%w~p z7q6&8=qd$k3n0FV?uj?^NfC~Qjeq$fcK&PY63Yln5TC{&u-(4poSV%fG6?bHy~H=_ z*Tl|GtdaQ1$DCPW2d=i?-Cj-ZK0C*5J?MtZk^0r@_J~ClGvuK114B(!(67Try zBJScn>p4MOB?QsR>R>1CA5DWBA;aY`1`=I=DxB4^)=`< zSwY!^wclXN`r)&j_Q<8CBP+nv58Sg+?=C>G38{H|A7w{=FpS z6x1tY9C~#75EUk@gD`*r_Il&G^Miz%#`kmO7a(WaQsn<)YA5QD9rN}y9+4kQ8jmfg ze6RKYH}icgEHzi_f8^HY@HN$_O;z9*V=n}fupR=_5|PQ#oV-Cs#m=0(m~ zr~@es1Jq$WSkF&qkmomZPIMvqtxu-iI~(uV!d^f=1mkBka5^r2BolFYqZyNX#5IC~ zM(g`ztHXodmMnA1IN{UZn>*AV%EmN)%-X!C1!p$;EAdR0_g9T&4;dWM!}7qG^wYe0J_bVkEF)G~z9Cx4)r3(vY3ZkQ zA5(ZbP&nJ=EsAlyD#IxzIY05kaabK5&kP?t(*1k8JpzFM3)mWsceV*oFUyFCV_uiM z;Ndww^DWTdi}y8BO%5SLOH&E0vT>xf1|eSF`f(8fOT*~HWvF+cB(oI!ZK&MKTZuJM zyXmQZ2rrMmo_NP`Ho~UD8bM4Grj%on;KZEWd+Y88WeQ>^dm!|xBA!6X=2(MNlg6x=uiW9+d)|LcHsYXNjL`FnKTZ9+~$ev9iY2mm(fj0@hL4X`>(G-NRZbA+ZU zKs*{P0E6@S^-8!Qzm}H3q9GV-+k$#hV7qU{0j(kqwt)l!*#fIuQOfL*a3< z78RO`oKWLXC+Rh7O0!1(%x1v}SO{%yb(kPw1qBa1t5gDO7AvjDts9y0 z97QUsOH|KCi3+~b)n?e+l}DJqXILI?z)xv<=~6@@$mT_@4-O9{%yj%)U%Ala^mggy zVd5F<%Pt3n3EEMcJ*L`4R4S-3L!76hG!NAjbpT`b((x9I*RTgSB9H&xLwN{DdoVbq z&}~_6XTu?t#1cLh4_wmt zP?Jip!-rk&-+7tlXfC!8nGAaqv`dFEUvSj1g_h?Lcl^bi3q?&s$s{!o6ilu2VE(&K zJu0q4GdlLVy~1cTx$vT4cu8BZr>T~UpVXb)3J(%w|0rcxDsgtFGjo!G#w_! z$?`;mC)=4;R{a|3OoJH?5EcW~m4a;_kW2qFKDhWlNi|V!Zfcn#mRA27Hy!xaqONf+ zt@MrmF0$aan9Qeo&!jvI;9~0Vj+C+M7efE@f`K$Y5oU##w__=RjCq8dIUj??%RAymp~;xrkP;*cH%JTP)%B^OYR(61p8LmC9d zOntd>#ZYOly1f*Rbddq^VrLJ5+GiPhY4wdCrDjRKx_q{Zvo5xaLCuqUn6;QB`bX`T ze9A0Y9!T%`5QgF9?G1i%<#o&(q&sweSjKM$aYcp7*n^S4qty}+Mml^jGU?6&d5RZ7rHwiG(MZLAuVAi5{!mZ)qFyzB51aEDT7Y@zZ zJE!;SU;JXZt)lDFj12R|)n|=>iyc$)!N70uQ-JMLz%TM@_#e@Xh&E9A>;93VZAKbq zAAMCQ9bc``DwutME6GgcYxHKPC5VhmOC5Elje41a_D>nO41(@Ux-;b3;4Q?A@%Q$$ z8pO&W(sF3`7^1>xo57XAnHj>N004ApsnMd&IM248u++unFwITV$>+z;u>0-&QgmdH z3#%2Fn@X>5)|6xwneoHs9gy)=+~#UUaFp2c!srT!^9zA&%lo1lZBb3SSnAO1W1W}p1&*m zgf11NMuvyg@S|2c-wQ_gd8oHh(iILYa)?(MI@U1dUSw9$_phA^*}n(Wi$PhB((5!BQzGx*rbt2Z#&=Wgo&JV* z5B47?Vwm9FgXMK~@Hk28mh(F~m|1CFQ3O`+O>mM`Sf7A7s@8H3zVA3Sx0H}7b(kAq z?EUW4?$Yj`+$~@}C&B}4)ii$&m5F|dy$~c(jE@tYn(j`eE0mUs5eeS;4Olx!Q!co9 zL{jOYoA*`isMQtc@#}gQ0OM&g!Vq>086${#ZJ!n%6tEYOfA4X7#FesYY%gR{){T7u z-0Wa%)za^2bSClvErCymW@Wp`*5pl_%#LF+Z?HxJn>!H0HH~YBWD;@vU@z(Lxgk5H z7fY3#CL}L#f(YRMJ^yArzM~e6VID8{+4AooHx#qacDGktbSEXZ^qPh}&e> z+Qp_6@WSq;K37x_sCsPdb13E|#zD~yM7Gy?VsW!%M`lvB5~t|VN!Px;`c$)c$dxXB zzC$e!e%a;28GpDRVxJSW5MtSNg#3~!Ead;6u0m<=y5rp*?lhR)Cb-I`9bwYMNuby) zt&H95$82tf??2p))_orYdUQ!*)c26AKE$gd6bEy9m6CF)qRvimbIkQqdaBZEOorn1 z+xUZ0$6)uEYpzRbZf~nB@G04Tv})c%g5-+#RU+zpKmt zs6aYM^sP+ScJ@Q7#xc(tZW8Vg4248fnn#;m}e@0sRcKi2lR2pm14B>aBPjIHUzWNbmlZHXT5=Gz_7s zLh|0McL{l^<7)--G;tTF+J2r0#J#ogzt69FL%=N2(Y3v~_6&>)!>Wiv(HQ>+_GNHW!ib$2UvOL_l?zkg>WIo1OJQoa!X|hNlKiQEWCbq zVYITmw_1UW*c@Zo%;{}RWjz~it`H^q-9g15@T_`v1)X1nSE#9}MKT_}FZbE{5VGTi z%03kRBIskK84U*nIP8JxA*lBv*uo@-U;puMc<(4*6+6GP4@JepVNU4(#XnJ`Ti%1J zz1dEZmR6qvYHYdjPV-HHjbM$KtG&C}wImK~+JAp8y&DZw6{tuPjuDLsVqHqV1kD^! z0Lu<-+5jkC>%06c-YKmVuzjb9UO`t_E=qqpsT4%2ls0(5dX~7kCm$Xts1VhFyA@&M zpLFv@?ewHdMg9^+35Z;e3FcORJE$`sbDUZT)}v%TrV)EV&oFuB!@|vzRAQndH9j&J z5T?8uMk*rQ**{RDlGqVb2Prl-q6aj-#H}s7-0NNEUMJl&Mcg{#0=3s zH1>F4z*Xxw?VyrY*v`~Wtl&Hq-c?pPR4_EqHs%7;7jV+b zog3^U7!M)S{)`jMND1!W>`}CcB)(%xFKU>`JwjsOn^BWX12dxUkPEpduo*0oRsAdK z;OX`=eCX>+!8D*^1hp!P!g|z>18S2I=vkSg@jzvzqYHtwKXmf&!o$8jw5psUQ6P&a zqR=xq0aBvknw}$kmq9ZJ|PjBS^a;`tLa@e&=ey5Xfi+rM06AOV%wSt z-5F*iw|)WGjq*qGCO9TiT2cx=hmp0)EAmaNo{TvHQh($7=QQT-ozO)*dI#hed5|#x zXP4Jyj7zsrp+3F~xh`5Bl=!?q^77!p=xAX}dRHU}0Q}~*-_*qq84Rx|#>QJLBV`$) zFe5)SRg^q10 z9zGb13ISIQj@Pi{p8q}=rthAkKHnWJ6m3roD>UYgsDkW7xi9N;c-^e=wS>^T=Mz$aWi;w6y|=@7qn1|tFYkUo zKzdUw9cBNp>wVC==uwJ*5@CAf2EUck>_zalV&tU5e~j)-ZB0$=bX^lG?JbtL6e6%V z@AG?cszvEQ&-%g-*P6zoMTe9RTl^Wfu6xz~_h-#Oa}b(Y9CQh++7l8cw4)+@e0)Lz z7DPTgatPlfL!8_tXYDfiKeA%L}Yp+1r)u1q*&H2JDyiHg|WVEjMEl zK3&P)UDDp1kkWkNzq{x_DHfGAG&5Y^-TpBg(R`xsrb=$td~uuf#@DQ8KqFF#T7MXY z57_q8dYJ8M-n2B7fB;d`8DSa2j!i@C;PgMf5hbl1G#}>d`8b{*EB~}LeP2G4+y7vx z5g&NCb}(Mq0J#Ujo7kKGWuab3KL%%jKqD<==$=9BLD$D*80wQ1mY|1pIh193$87Y! z4qLbEqX4L!Grlq&u|4xJYK;TPcGqI*nN423ug+P3@6xSS&PLl<(D{)!`8JATc!sYe zJL0m~OxOnl5|l4Wp_M%4pW8!)p|d-CAC+RMlJWQ=IEwetPWO#UWo0IX7V`WmJ?@bJ zOy|f^y|=|GbFKJ&x&YUsES}T_^b|CiD8AH4f2DRo zLL>&zOp*uG)IAQfY)L|Bgs>0mzKfBB5z4A`SqsOk8=~J6mC=DIe_V-h6+R7cgz*O= z{|R57{JI@mFfEuHx%@5mc(!uEifi+^c0$zV1^`}mt**L;`Pa0zwl#(}*gk98HZYAn zdYl#FFbIAp+_B~;AD_=}XNMm)%z1l{w_fQ=(=qH$xCn5Wh=N4CyxMPx^O@wN+h)ed zbh4{YC(f9P>$q;LBTB+Zfo?)lN1Bk~5x(K=`QcfwX-Sl#)Ke$@d?+iQX&onXnLh;KM0be-BCiXjmaVQ?=h2e}s9}@DS=LXXDST z>wH4gs_Aa?!p(ry)qsIdZsOvom`dp;FK&e`YYufD3wJ@nqOl_f_c)Dw+MAM^`Y7#G zWU!{YvVaBRHt`i`wK*q_M5B(;aA|>NcP!#zIJ-Sm zVcw8Q?qd<+zBwJB7|&&|UBy0f!?}LUuAbau2vO((2f^RPcEFvog}*EWx>y0o>MsWU zyg5K9nvdOx2nk`(r)bx*uYuLtrS+AWL2wTejEH(+uk`Q$C|$-1b`k~9p`3CR1B{iJ zRUSWc@7&h>{PM<+(Xh3R70y^>_ugw#il!;4yW3HJQvt04a`|L;`F}Iu&)|Baqd?TJ zd0>xP1JtE1Ph6~I&RVx1H+=a+Li*60_qA&d4iUd+hDQljZz7R;i6Cls zKP?}VT+`qk`KLg7OigWlmh)_GY39}t!T@~yiZh;=qL|mS`6JPb*_Ja}$m8 zPp^}Hshz;;H#BdrM55(_wJVb2X5xbAF77B$B2myv&=P*(5Rx&|+xJ4fo7GK0Yn z*$N%R8T{euLhC>j!*LWSKf{?tFis!$s-M`I1uMh#+1VexM=b8|WfZz+dfniYWsXEj zMkGRC(+8RdZV=q;pHF%U+#x>zQW4HTLJoRat@t>I`kpRKJVyN#w8ssgu!tz|MZa6O zK6@3O(%FKZi76-0dlb#*nCMjl7Qv*k5S zD7Kiys=EKY@&P~AL(k2jou8xh2u)&6sI}QlQk6SgP`~w41 z&{RGj13o4=7WF39HtRi_w+Cl{_%Ty9{H#_5y^oPp)4*jZDG3#Yeq#NQj#|z$J3Rr? z;B+%=a;YL#E)EP1oRe|{Ml_yGel5BgiL(ZFX}n9`Vz%UrwY9A%(GYZNXCG*^kyI4B zKonzLp#H`Qd{Cde0OMs4x+YupU@L}>csLBaW%?>6$;hS6*o@ww+;UKb@iGYv%Of5Y zom2>n#E7pep9dqY3iO6Hod{W&#VbAV5W$VG03-8~fLI!}8bUqs2b5>CRMtpzn zBDM>m3oCNJ)vV&-+f;v0OPF@wEM2Ov8U+xG@}4zY7N$+^hdl*|kVt-AQ3hNZBhLq# zth7_0^fa=Uvn~~k;AV(_?m?XA%(N%OjL=QoJE+r9ZTvp^x00&n&I{!S4h|zXyAAAttO<9PVq7nsTVQ zZDMgP?w+EoyHL`99Wz9=8|nLh4*e*qoY?#qy*!Rpnhhwp&V$yc%fwXF4G_#(mjPfT zfS9Pfj``$YIgvg z;C}0eo#|-Uwc)y@99-t$J3^m1G};hGt5WW0FaA~ty#fkZxjXRJ$FBQbwJu!R05?p4Z<{>)wb%liHy zv}S#>XFp$IsUj$)2dYZ*1jx{Tcgr1bjoJlM729icU_hO)biE+ApJe4jbE0*qsa_iB zUkIRmon74kIUJX4VR#%wcZ9w4YUhlK!QLQs=UacmVLE)Sw0U3qiOSw;N%A0Jzh|elOlFNbgF$*b+>7(Qfu>jDv5D5d~LgHVa+(#+ zWiTuWN=H2(@j7*CT+O3>Ybv=(Ay*^hEz*P!miX?}c*PJWeIOl4S(cJD#PW?R_c|vI zvj;^V@44+CsBs0OGj_cM(*IKs8*6K>6}9>{&JyS_*O3XXZ*N z5zx2M3r0eBw7wg8gF4Vq@Hq$x14UJv-cd{cok_q_|ImA)MJ;NDlsbJz0KqHQbxX@1 zFGF1Q^nSbtc9Vj25lyENl7Rb;AcvTOKdF0gx^#t#dY$;~tMQ>j-^h7u9U*-n_}J9q z^;N?Zt0zD;D=2 z@<_s1qG8B(?yj#VTV4Q7EbCw0SRD#A#jtPHgD%nWD~OlunwsIcxy{I5T7Mk{ANGNq zc2Dajc)Y1%OXnR_2?Zf|Cva^r_r5BI2iUCUdWi0AxbRyl<$7}ov7^Frx~YG zj#Ercxkr!YE^i|(UMC*r&?K@|hkhWBQu)AUY86coXGe5P41;&&E}mtFmZO@L$oM}P z=9rk%(FUAwgcjA2Ho{exlcVaG9(JOlfbI(@+8MPeSRz71Kih&UFsE4dG(DBGB5!&W z9}`Ch!RFY2zy`Jg7U`BaiKL|TU`i13+2$SsiNF6&B4If9gQzo18EUcnAJ*N0V^k?KeJ1+4lOcBL`qF(@M9L;EQ$ zj(c`dkBu9x(V@b^xP7T_LLSi?vRQOwlfA%{PsJLDiswJg~w$GTb){&H?e?^kUlV2OIK6Up*8LM6%CiAfxeNzsk2uW>@OALIf>EmR< zb=fO+Y)B@bka`05$~uc4EjXS)_GQrd};<8LM0Kql+nWQ%*I`_FgdIjzC# zc1Cp*Abb_P)zL}+7+6!mVG7daamE9pEj2^L4B+p;+@~W!X`R%4m%DrwKZ@8v zn+u1~w;p$A)IpW3M`E$a$rVKlY1Hy`f)xV8hLx;u02E6MN<=SB@}^-W-O0$x^_ zNXEN+2p;A-&UlWiRGXs(3i{eS!Jhv@*t{__wR9SO(2?VZM{`_;X}m~9y+rH<)5iN^ct_XlK5=_XVZC6Rw`ryw-7Mo+JW0Xmk<^8}PaRW}0PGcD zaY|4Op_^ob2F>1gAIU^Ft{X!6)F%jM_|W=bD4>krQo%Ao8K>&AYY|KRs#&1<;z;(& zQ1BdvnN614>tbmb5)h$$!?QeSJZM`7YfcVuxPZMM!^d1E_|Z^BLt(6tyh71xPLr?X z((NZ+nb~XEMM9LfjZ}yi0oKIFD$Y`IC;p;f#6$$|oZ@R8tnWBa1{E4L4pGjd_uhG& zk0H_^BBDm-K$y3XzU@!~sKV?*w$xZTgmHzUJ8?FY@+CSS3@v|bntOUf?A0+wuX%6` zUo_t_$H!%ybD(e!j;5Ewut1R#NSmz2xCU5Q%>bmLMpIO-kYD8LYClJHB4Ta3c`3Ob z0An80_CXaYN3d4IcUevDAF&K056VL2f`MmKWJ{~RyXtUFFA-7HeW4gMhiGc5X=-Vmvy;LwcJlt3Al!e%<6cQzQxsnsQ9Re4{VvXt z)I$^eJKwFXMj+TWsG}{18#-~z4uV4WNC6Sz1>VgONm7O1BH*wNIQUmT9I`moOmg89Yx*Ql4$;*QPa9qGdL{Ou@4d=rlz1 zRJw8ZpbHfb0G&BlvKt;P*v8##Di!MB0Pf2=cEr%NvNL0|dEA zJvhFQ7N>`RJ?8@WJXk5#XWjocbzFM)TWEkfQu7g?kZ}14D=e~r8ayYY{~z#x2R5XR zl|z3HiwgdymhH82#+OxIgCGL;`s+~d7En$_V{hk>dyz*rE-Bm*lA(!_%=NKFp&!v* zRMfHgv6-2+v9-?U_KGQ~DF+xNtLrgsiu8LVpM4ZNMc45#62xoBFGMlaLNIZ@B5cB|~1~H=Iv?|bcSX$XC2#bb`5Z`x4gGiPH1q2lcv!vw7aFtvT!(IYVE)m8* ztykv=zSgBNa30u5!b=QjVQ1*Tg>=%6IDXiijL7@+$MM6O-Vk~)V5Kcn=Ed4h->J5y z#!>s$W|n@6)BN(8EtdE0pFdkC^S;gh1^1$!z?wUFH4mVnIZ4OTWscXMCYd1iqF1$` zUKo+eA3n!Ir-S>6j-Vcc-+Mc-HFRV7`|qAA=rk|b?){6O&fQ&a*HTl%TJ9BDRzl>p zZT-k920C9>`*xP8*3Plu-Pwh#{cGH_0iA^XIL`*Qq;zJ#>-seW(ebV>bR32w;%|4Z z^AM5DU#nAo$bNtfCySoWZ5E1we{GXi;ebZq-(%`Q?YldTQpJG{S?@TaGV-t0*=J@7 z_ba`A+#Gc3nKz_QN_?o@^7q?xs>E#?#C3@In|!L>nTY6NK&P&?*-I&c&TJU3`SYDW zv!R0vEU)pq2IBOpM57pP<+HZP-`gvJC-w+7o&@J^+*{Xosceh zR0#do7g<`Ggf9X$BLUl4NW0HoP_C3FSs@^vhN3cZ%svoaGl}MD`5XKu~=lwfHlrE4u!b;2!Wm^7?u#` z@V6_u*>!eDNN-jKR|uC(1_*NyD_-cOnk-Tz=0}rcH&~L>{#`?}_522-B$;#=MW9e0 z6%Bj6rg`Jf{O^M4^z^36sO7I0l1Iw9P2O!gHzkYuLtC31x<#Rw&ND8w4X<|T3wKeh z`yXk;O1(GhuAZ=hCBB$+v30o`9VAtxzt_KqVql3zA!>^3o_Tu@b0U%5?x8^;XAcg9 z1&PY_-?AQDDZi=#2>3oBHmb^CGA>d4Q2_qm0ZlJN@gcf#ObW8Topl_-e2PP+rwF&|`Rto)cAZw+%X2kDnrSX~&ZmroUF z_;ev^Rh3r*TQ{*~2`sqr3{&mR@Zm+GF;YhEbxSt31c|0Y6?JP`Ff*_@H8SFZEssyM zNA1pT*zs$bh%gbnP~Tlg^PF_+1QJu@JKBN@^D)(9yw4TVl5h|^AUzYqi> zh80SnS0I(L59*>9rqQbwA{*?+ZWL71jd`Wwr(&>j)gLqQv*B-$^YCbu_yb=(Au?!p z_As%1z$CCj41S6bi8R1sKroJNWPlRYL96o!EgPjk_T4(I;Hc;Jeyrr`Gea%mE3;F7 z?xDYyb3n-f2?%Eg$GkQ#L@g&cOaQ%Ryg4W+PvF`neE+hC0a)S>*0xK3c(Bz z(U8-|R#$Rq`F-J0B)~SfHXPlV+ntGO4GvoW^;-m;q`g@arIj+>nXp##iXitAuydkC z;WNz+Ycs>wB6oj|jARW1Zo&ZBkCibrO-SKZRtgHHwr~CEE3GU{L&|nMJ$pF+ZAG-3 z_?+0^{F1$Lebtw=_*nAX;(3{P(o@nKU&)B&=CMOic`sRkPge#i%fH2r_@xy3t}(G= zPCr*Lvf5Q!pcLb}q{hquT0S!2_5mg2sos3|!-%h54OgBGBc0?4(Z6=*zPIKmny@zC zh7Y(!E@t?77KQCo-UFdk##EjZ3D%2j6{ECk(YHn)Us>;2X z8}{$PPZ3s@kIz|Mo88=rd^a5vgxAvWDs58uDMK=J7-n2p`sE`{X^9HfM_5|%RlGfO zfOSlq?s!=tTJ{NpQI%IIUADtV zLyDYaWfdk(Qfqe~_XO)VP8;*tCh)A734lg$vxCZ(z}Gh^zy8%Ll^ z|Af||{fz6zBghMUBVG;EkM22@-d>Sw>VB3GBL?fe*SZ;J|l({r(BuiG@??EoBUgr%?obIe#+w+aQUCGV}r z((&#Qe&nB)qEb}sP^Pce5sM-nM&YSrrWg=>8rhm*f~c%v1r) zs?lsA#+jMg#wbzZR?ncNFY7LT>5LyKc5O~ve4B7fC2Qtp-58fK8DOzj`eLxK2vMRB zd$d>zWA-xj3*q*ejJ>U~EWMc}@YL8VP8j1RC&yr1JVY`CE8+(w zFTJ89AtoIejFt4P(Rl8^)ktdP2;01bQy%)LTEg>fe>2}O-SU1msLONXJ z_;F6m9*1Y3_4m296oMjg+Le&^7OO28#`^2r_=~mD`FviChNlR8dmERCzYb%qpJ64} zUkN-~OoOUz{yBcUEPW+3vtM;0axBoH!A5d(dXSyfJ(dDxn$bSEMK^g}ZI5)hd!G!_ zwC%f`_VwTS9=n@SyZecWHH%YIJ!edaJ~VR&t9il|o;#%C2;D9oOCvnw$Fb zr+@cPLzKnYfL;Xpli>F8-0*69C791hiOqCMcVvz$c%sMd(*j6nd8*UtqL1f-hwC2K zX~~HSgHX!WHDF@j?huR$4vhTWzB{)|L`1Alg;<=R3Nt{23h_-6AH8&yuM5-P5ydS? zWnCI#ea=qD2O{GWx=oV4Pi>V~-elfz!0G^o0$vvxwbFl?=i~Pg+e1!cwMoAdniH0e zn~PyIIXA8*xBI(qySijO=mA0+GP1@3W67WFiXoJ&0223CG<9IU zRa;YyffS*gV8l~QB`T!*`WANHn+{Y-UwZe>f`rI(Mr6;q zXENza>B$E;vHre|cFlCZORyInM?ly_fOMI}0o~VfaEiBP0U*?8J@PN26A2XBhg|uK zu%~|qK-Z_7!PA-tIcji(cLn_E*QpzZ@0phIrFk9^`*4{n;Qv zvB#j#IMQPnNCwinOs?qfXKBhMs{tg%Ss?n~)DHD#o7xXe37h-*Uua7?JcnUsZdA-< z%x3d-B4(U2TGnPRTPNwW7wV-`lIss>QH9@k>R`KJCS#uhVj(02$DBUHpyMF7Y(OMV z*i5*fG*~4KsD6g*TCAK7l5+EI9!)0ZzBRH&#=EwIhX);(_T|duG>7vTi!=8+aRSr& zn7Y7K76XZqW2yB}$@~_Q7Kgj9ddx(aS*`qfkw@2v+9^CXfphG=!NL^(j6I%FD0<-T z9e<~avBjX&tb*53eCI7Jtemg0HCr^ej`0hPlL*-nO+DFHJh zsaRQI8FBB)x1^+DXy$huI2Ckn%F(m?CBvTvm|za5HA8xcCBjLu$90F$TN{HMU{Yc? z8C7k?P1Sp5)o)Lgosw?2LRT&@zT9*raGKyswN7SOf80#NXU?sE{R#~FdQlo`>K72c z=zkdgEVMlF4S~jpwn{mmI_#a=9l=)F?99Q*z}s6}v39y{#*6^AWicm!28zoG zN;T7DNwVcyg*6CT|H+-Deojb(Dr>LS_UC)LPFHeOnzw&tP3$;)uL<(iYeM8(94hgv25e@eF!&+Ct>|KIm( z^wV?Mmeugp)r44bZvsrhoXPYhNFEAQ$yR>z68ETBt-Fv~TBkDoR-%uO2L^M_et4Ds zksnIJ8}{_QwR7)Bb|X2ZM2zVG^>i=RmI7*4@F~;t5%0-aBd2?dMg%(N9bW3Vs_%hO zz8pS)q(X7o7qLPy{w(XV`$J70&8h8c;-)#80nEsy71jR&&U(KRrpH4~5&f8A(Y_b= z%x*naW?EYvl(;`9jV?SB&aMZ%F=&I z$fCFX1aysh_BMbfi*kQs9Las`4D5}1yIsKf27)mKt3apK-8-E3Wi58e3(3sBXXdBE zwA&+rXWf6GMV;EPQ+yEphp-CFtmI1)JNji8v2oB_jV{UiLkP3@pA}&Di!bVQGDT=f zZB}|7_~&1|0X&_IVCgNZG2F9ZY2ew37Mv1>lq`Ek&b5y%juwd#pYwj+Z~w_d&8^~o z(7&gNSeNW|y6befF|aze*eIRu1x}`LZrH?Ktqflxe62IXpA{Xr=`dC&bpF-%YEOh5 zVC6Rh*jsb6Aj=8PwBhRg>gY}r`U4)VN@~_*_Q%j{dF3m#+c0pYIuk-ngo{)J_=xSX zJ1IUsdVW~QSa4HwT1M{7JLS1@k1XH$=BBC+!6jqtGbPBgju*Q)+8D_nO zq9g?a34`Fw+3xIoi9kgAMrEnVXs^HIGdA ze~*NL57|`BE@-wJASkm27W!8r8xD@FPUGjo10xM`wA4W*eKu&kMJ!4!3U*I}t9zYJQLpk$46)`WiDl;Si;r?L)jv+6CF_bX5txqk)a?54OJ-6I{=ljR+5C3@h!=vn+_j$cvujk8rWTQ*& zhEm+-x>DHOjqNYn3L&6(=Y~d2@g$UqVvfu|g4vh!$jMnU{LV4BE2kj##V^4C>=)!0 z6dq0${fghg#OAy{_M!HE@Y3>Hot!4HxNk3eZTs0w3~v1C$p~MTzj=%IC+3UMi^z<$ zw9B^VMEyB?|Cr5LLtEuNQ=?%gEx904y!AGGZ3^qc@VR85qXPRF5^Ik6r!oO=jVHzN`YSyYW*Ky6_!?b@v^dT4&@orfRc~p006Q!+ct;N* z41qc9#f9LXkuP^uJpFW4j(ovNBu^I7H!W%J&c0&e&QQ|;fTxp3m}aPZ#C9Y?mP&^< zGz80%EP6rC;^@x0p&cV;NA{fY=Ir%x;UIIGFu9}(W1o#Yk^Z2yTxTXP`l91IA^ngRfcbME0d8; z7yi?ZIfFb>E`HTcO4BMjPUWG;Fdl{0UmQayb$Q|t7 zV5)!*UOsa`_|q-3$5scAoZ6>CIk}vb96Qv3ZO5F4`f?n^B$O#{CR2O|;#G38uO02Y zqpZ?=F51B2;Y%?>8`7F1g&U{_0QdI<{NdB`sfB3v*?oOE3jltO5}>Q_6;+gzq;XZL z=NkgK<@EoCf7r0u?oYn%VGE6#A@vW4m?aM#W`izyQ8q$_6KEknCL!M}t3@ZeIWlr- z+L3S_L1lQJef5x%UOc{ly1qUeJ{zpJ5&#D@Hwpp4c1l01YFl)VSx&%x&b7>lf&sH& zU6A@s2u14Eqj#24kl039#(8K6Ewz8EE47`jBj8(OFBMsU7jJkSAn_t~a&jb760y6H zuG1zzGozFy{sNt=?uK%+kmp>r5`(h$gd?ZjV;AqTpd8a@av()OtPHawWQ z$K;A{&`+?-G=V^e`bS~!WS@}h2dB$rG5kvRTJpd;EK6KU>oFRSs^o>51%(^98l%;T zM^uA){2aU^3bP?Xo*qRljGFBmGx#K~?-d zkIvN>F)zw&C_{i;KH4ZbP(m@0hdhd(z|iC!b#)pkg6~F-Ccnu(6!CBc&4&Yr!AOCg z7o0@+&b?W`^0md>MhaIO(0y`tKkkitpX`ejCxzVCRkv8tFv8>$vd_XY5Yz$P?E)Hh z7#0c6Q7BZNJ-jyEbz^(9Wj1^+&8vQGO=*i4eogZ-HmWmhVX?Ig{KikE3xzb}k0=R} z6eI9?w1vUiu!YpYjpdkT5zvfweir{S<1hDw~S^AL$dWe-n8eqP-A0QhE91!aYBBD#%=-C$>G5F_0`+O4js1!7!!1M4}Hz^z!)8$9(TJttI=|<+5bN}G0%ujJ- za*{40DpJ_3_Kle4_n%AI&x^bVRz|G!VxRuJn&^9wZq2q4!{)-X$Op7UD2(HNOmEKg z>vp6#N0L>ypP&EDkPSamdiW+i3WgRcq7Nx*y~K-UKIuVcN+4B?e_LwBz;pZBdcJl=hM@F#$v>H(%#Z`g+&khUKfi%4-Anw>;=oh@M~Tkz=V!EEP_ zb~^eqQYaqcs^in($E3Qy$;Thr8r+E~6-q<=(eC4y29 zRL`mp>uJZA*T&a2HVoJp3$lfk?Jg5#=HUw#sGGJu1MBdEPTzwD{ikobQXEf^P0?c= zQOI=?s@b*dYt1JJGy)%+ z%Sb@AnS}-WB2jJ~_myz3=xjLVNU1_i|Fo;y|Ev-Yj0|hMFW%nHkC-JvZTyP8VSl!+&9Usk*nBAFm@&>gZ%4tVU2CfSQ`-^^9x7KLQg zu1Fj}$O0p(9o{H-OJaxOvOfM6P^^mSH|fip!-1IeLd)`Rw3sTdlJ${S*%D|14m2A6 z-7mkpB`gILF8OUaRmt;3p|=`%`FI3~l}boNIDST+qbmilI=8fTFE5WbT+yM0;^iTh z3%U|2%tFtTN(ZeBl3P1=G=D@k2$|?4G)lE46Yem~kvl|)?y9P4Q#`Nh`*(-(jzQH8 z)p013_eP2{N=lL~_3rjt(R+hrzI1; zO0)qw_Lc7aFIYRm8Z55mfZHYb$?*HV;A=81}7d@=BJsUpi&;-9xA5zVm=2aeZ z+WvNtcyzB)2>(n`0eC@&1F^g$?-Elr$Es_s^@X@b(x~i?luilw4o6yE1$c`t-}v7d zv^5-0C4FK3objiIz2R}11DD2cSM{H&!<0gZz$QD_N752Uf^(Ew7bIiV_1!Y=Ju2p*h9$cnJ?&C4y-%D**=FT9SaP?Yatmy zvs}da)`6C;|^as!1{Q75$!hox{<+?ZR>)2h<~9 zeam;>r~E4W<2j`$Z__+8ZInyI1FI(}4Uvnqr^)L09|rLa)Jo7{%Xb4et^x7he*Vwb`VE^1J{VfK zbFYt4OtB;!kT?kG(u8`zhYt%=8h8d6Z&`*1=0s_d^6D)aB$B3@o`f zY33*!9IS0XKf*vFwAEPO?N5yl=W;^vWd33o4%&SZCEPMQ6GV|NI?jJCK0i6Q!49^R zKeqE34dzI|%)kdwJFz2;-ZyDBCVouVD;NnOPLX{g%RZT#{hw_!vW(MZ8w+!!rPeGX z>}RV-X*O&)TNxZm(*&jEfrKG#wWnm~skF_@7al9O$hN%=P0tysOHI3Um~_eYXTy52 zM*^Lut+b&Pi{`^3VFatoAxIk9!_&;?gAu39GbQKV>>)Y4=`u%1mWiy5M^TWJH-Da> zIq+NxL6B2D6dI%fa(*;uW^3Qy;G?5=g|uipM3Tl^_0$q6NinoR z*3|ujGQ|o{D;@I<_4mI^tNRc>XLyqWcj2sQzvsyN;#)?(QZW`fHrlV>9BySMv3Mf-bn%^}RDUBg}9&8Gj4Dw$utd`&wAVb$2+4rmFPc_s&u! zoY{bW>zkpYZsqzjD=h~E{%Yu&n`^;vLNAa9`JY_N^d-(1yC<=W-Cq*hMPmnYX#`G$ zDCH3IyFE1tvP1AJ*0WE+?f%rdlfr`t@i?7)p&KQ8W9i_h-bfRy@&WtM#Olcdwk&)E z>IjbpiRfw9hsr9S;VS&`*%1C1KVxftc*eEYucElGW`q*D@wEkfNBrF%g~?D`y9gNj z5OeW;?{{zQ-! zRsldp>kD-}ij!A1TxMxhS971|*YD4|rjcmg|MKp+M{$mdAc)Sf*J$b=zq{aVDT+ib zQ;Dl$n6Y9{s?*W^wv;(cvZm4YA3#KDp6Wb5xCywy3q3|#tv5b|tZo@?F6P>K4N89+ zcMn+|2p(J=3Z-S{-{x=H-3Z6-YXl{31r>Mwgi+TfbwuPEe~$}U^;G!1bo`{XR5nJJ z!4;Odo*?p|2zeK}FJiRRXr^*KzZlMkX5Ov7a#YS9_32Ib6P=p=Sr~$$t=gq!o+QoG zC6#M^NFcz6mL}VCJp7oGIVkF7<|Wj(S;=4%ah7FbuOnBNSoM2-Yis6!YPo#|fSRPS zgIsCH&3Wb1OP#yi?!a5 zC`lzT%P-~2z7|r6obP(4uYbxtrB7du^f6*@4AZZepkSp2XS@G$$dN@O5GD?LFQH*( zS|S`IpN2Mpy{0)D18armpw}Oh3qJn$|8A|%2DC2?|JdG;`w;Te0Jz$49VmziL@T*B z*iQEk{ab%nBH5KDj)*^_LRbxBEO8B-Xmty${;)cG>|{<59j`yDg~Q?7Zb82$C&Lu7&LiVTE`39C zdK<$&T=A!UgP-B#UAyO+PD6u6DR<5zX?u@j%%oWKfG7gaFEm&(s8MjV^6J1(m7S#IjNUs=CHzfxU4a_%3ae><5aLAeRETX~n} zbIHVgdZft7{O34E21A;HjF4qG9Za&q(QzlU89Gh$sORvJ){cTM0I+?Ajk0kycdr*2XEZ!pohVOMvtie!*~qbJ48S&jjjPB>WMSX|O*FmE22{0l!e}3(7bmz&&KIB-=sikjAE<6~Ew@+y zc6P-i&Tfu+0q|1BMps#`WeUFJa!mLN=+V4eRaaXZ;_u_*U(;>xQKZEN(-}L7%YE_G znK*GPEt}z_KmyZIJa4}Xm<2_IC|1Y5yDt1bV}|rvxrS)+t^P&xY4hvqU|;gv{P*uO zcIT5QSy2}dXg5an-qGv+(dnuatnP72F^<@E=(9W^eEnxW9`urMVE0b;6`Btt=UwuV zoeST1W8h=^B)1gV=WND6n|UJ+GwE?u6(-H9ud-7Yj7A8`6N~gC@+1RANqZ0cEvO;; zifxU1itK`xgePyg5y2j1=#?E48>;jq&1U3IIL2Jgb?Jr2f5?kppIz?7}}awb|Y9$X0`R zP<(!9oI&vI#*z}~oAXy70;=YTgx=9{x-3Is{7kjoA-Ah@(?ML0|#aWw3N@H(mKu18EPt6kNn6x%8)nt1!3@9AJ}s;C%-1Y z;D5^d@dOj_oT(l{Q4hBIXr}3zBfmrvC3lVh>70?8miKG6#ZHopj*p+Sz%v z@2V(Qd1BnM(=E0^=wgFBbC%LDo6m!~2vJ-CnB!cobgfb}@DDx=7$D)n@-(K`KC;wr z=Emml^MFi^b^KX=Y-DO?=CW-?aX#o4nf71rNlY{p;b3rA#gYk!TjHqGu4RL0R7!C( z+(T7V73xw{KBVaO5o%>Zfhim8xU-gS8jaoYT=XHMarpggOZ|ibLU^o0IK!C};oNqj zsq1!v^T2HUi_#anZiK9=3U(y@m|d24WDTw~juLMb01vweJ%NB~QMc3x0k9;{s3v5! z`$)lYn6+j&s26Gph3EzQ3Mtv4;h6s7{bn%Y{w}-hc)Rq@r(g_I% z)m-9CB1RbkR%R1Z8;Z!}qH85~EAjgvk*Kxbjk8mgsr)Y)^?_Tjjdt_;>#rSsxL|G@ zzSU(n5d3#I#!dbyp+?E1A*$Q{@YT^H6h{-dnh+#t_Tqp7$qXKgwP`~plzgZQ2?nCZ z9>EY_-!`~rU>zLzg_x(0GGEhan}}$*)F-;Z-4kFX!!Qbs6g`cNf~8eOh$6}{FL9ZS?xyA0FeQtoOZkhemWi!m+0BEm^aaVATW0cN&(GYRz)*WcYpZ`2!;86qzO^40&+#r*PzGD5UWmaRo(Q?u+819Jx#GLz6_qbydvY>{Y zTYkN`g5DsENQg)970&?3GW}cQaD?cIZY{Pbf(F_FR47*_{nz)a{;zN;mu}StCn3&y z+_CNQp(Qf?r1O_JYq$6qg{o-?PYJvDATjEv(x~r*B69ELkQcC z$;#1Yn`&eRs*!Uj4i4a7*!Sy+Si;&!yipFVuDYfsguL{{Xmeune<~g7T${WcFqNQp z2#F#nzQg|+8W>)#xxW&9=q%nAo`pVVZ0h|$V7#?_Iud=C)(XM9x1M|Q%vw861=1G& zZO>lWIzasqilES&wHY=VLqQ*r%<}6+l&6skupJ1B_G|jw{}2H&&<7Q>HK!q0@Q-~D z&$=NfQbPRt0JadS4C>1^Svf*laJF$c@OONpbG2I1 zVblthbj@zFRP!Ai;R4Ofn{;;6W*?Pne|pfVFmFsZ=(vjeZ>0B;jEDR z{{HieQ!U|}BdILjjg7zHWvVF`12bS!4$2a02MrI5`y{Csm3Kdfm|)9{hzka>7hs z9PED0$z1~iB9lK0+It$cHu^tou|E83SVvu|d3!_-cl9|UzQ_J&CDVX+DuNO?#3A;3#-k`0Z(4(?IPl=M zAflYEq?g*65j7K2T$XcmgS1M-c(nMW#9l4B47lce#;%2%ND|s)_6+m^`RfUD4pwEf z&JKTpTOBA@ z+O;;dSnk0CkL#FROWs}ZP^r1UK9L*Fh;4-)_mi=q6C5QtyuS~#Y0ezsx-a1Ni&{ZY zK4UCV!L$4z3#<=Y9;`5jcJK|dM8wxZ3T4hnG=!2mcuH=4FYwtJtVbY_#nLjlG@H#luLQZN|g^r}V`V_pKr*yS185=s=1LUP@TlD>oT8mg7DOv|0iU zd+4Lpy9r2=6@l;!?p>`USF9l@U6*UN*k}x00#JtBhAVF9$h*BK@q@pgM;}+o+%;_CyJU*=K$fDs7i#B!D8$;>{*lQQjS7u$S6&R ztww_3@ujraIyzaGVA0y2B2fGj7&g)gGxkUndtf)@sg-kN5FhRe)snh|JdLpeG)2#A zV3>Qj^it~Th_LruO!{$<85aqKUg93c-r@+i! zTrIXZFr!Dnb5P91v31Q312>_X+g0ntM-w1VT3-YDpc*9ygSSC1+b_CvA-$N_tZM-u z@lmV`5PJLcsJiaHM8e@cVk3+dPEgOiUHlG(s_P|}+f{L*I)(Jl;J<3UKEo}mLgW2T zU=?!xYRl@M=><+Ac+cb>M>AA)aP4+W_(nL}eQTygi3*3iV8`gM1L9z}b5?&%-6;zy zR0#F0`O6{DNO*P%{8Ml5YK-Ld#nA0vV+;93$ee-mbRUzC*uk0qO@rt12EH%dobn1^ z(Kqw%x`c?POACAwH9FA3>J$-w2Jsa+oxIcy#QHQdRNf)HHS|RAMR;m#XkcI=C^CML zYhO_FmD3xPKA8i;*ofcpp*F`snYsc3iH8Y9Xz#v607;0cJMQ1S+YTt{(X2J1h7OKN zK$v;m6~w_6E=E8E5m>s2N1d7DtobOm_&AjGfF9|O_vT&}&^5KPxW{I~+t zU0)B23m1}|zvCB}3u+imCrB%Owj|{RWPL9To z8syTYBtmaY+*UBbUugS$@>+UOa}yK-mtiB_3X44?{#&UFu()szDhkFb-ws}<$>A{u z@z`F}Il6V#6g$%n@Dbo+*fIB%^By68p)j0s)T^YM^tJjP2P7&@=QT78t?^Ks=EJ%& z<$nz~p+!TOwEk|K4(OxcZi&6f7=xd((Y+e2Mrs(=lg!}u0ozx^=Y@ZZqZvVXdp z2~z#a;V38v_`~6Q1_A}oLfP27_6~q&pX=%w{Q0wg{kQPQ(KEL0ocE4}zYgarTKPAC zZU`uTqH!xiyWEqMW{r0ebeMa(IW=BckRT1sq`#KNd2`@nwB=AsWL}?$7RG~@<4RXt z-r1Jq_fA~upDo+-k8A|2|T$!$`P(2 zh-rFz)HPWSFAtk*nDyu7cxrJ#|HG|MNm_fIfn_*D2G<9QRPR(%cETYgkDK5!0 zP+)8$Vei2|3OktXuvdkd|EEnpi}Dl)i5{7d#ewiGB9QX!wwZuhLix1|cjTbwzV;rQ zynQ*<#u=;>L%iwMpkG|!$w(VjD~|Mdiu$}{Pwlt9llti;hG2N z_i&+;dvsmir2BH#D-7QJzZU?>WJJO2^^jSLH~<`G`vm!g`T2zTX(Sxgc*COdQsb4tGvtNuOM+kn z{ki*ftp=KnQmBbbvUKP{-)NY_XVm#wtXsq!#)3v@s6HNT^(!p~3~&M@RCad?Ih~-P za}0HEuKrN74vtawR}}UUOA^$LO8S)B?(4l<3qc=e2&jkzvUnPkkBuZI2uK}cNQC={lq3?E$H2XW}KJ$+AbsOu;Vk_FUp=fwe^hN1wxzaM5khBVoKxJ>mI2@E?`s9JM748*{QQ>#ZQ?D+W z4-fe?u_~9by`1V5w)tgSkb<(U3*KB~dDU01&u!^4pjHs&h@#`@Tz7}=u2XekVo4nC zXdMXxYTl$&zfRUTK-y08DBs#x_ySP7 zYZ938E8q+-)zD!>wG>+9q2|c-A*2f7@l!>?-MLQh>uWgjQm?RCU2v1+;)L!eHfz6{V_K-8gLjdt zqQjHwmM}+LvgEKgW}yG)=I@ppGaQbVqcY5elQ{No==3JvV?H!$P;X*`h$U>h;fW0N6Cg--d8SLx(n)Q*n z<#9EeU*wN)AI>GFt*trNJw*-R#%$4n%r0$93c>iSXfY;{;B69RMSELWR8-a-r6{G` zgnEP5ev$t~zA)5O5^=ly*#|QNB zrgQ!&IsL9XfDgJb0I&%Fm5=bmuxPTcdykw%X5o=(#$%MV2279z@`t;rXWH^SShUAa zrFTdXfbNh^bTACv+L++F-3VP8dy#AD&+@db!rO^HwVWTG2hIi8lpK19+3+SSHR!4h zUY<|4d6cPq1Feh~1^wLa`T3CScFr!B@9S3YdMI?>vAAZ*7y>k1*<8pb-Arr1nOs4IH1!|>(jt0b_an5XQCDeZwoZ%d}9~NBg{Vg zz;6@L__P)I;o*A+DP{`}3K0an8R!Zo!Eg%Tiw(zJxDcpLXUa0j{LObq(WVzx` zCF)o=iU9?oX2=G|c-(yd)1#{T?&B7puTs&U;8J3AYr$kR zVRtC|hkx0rG>e4%VhxQt$;p~x&Oy2@lO5CqKgX}h>GiByZyX5nN+aQ#WM7xb&b?5# zBVIdYFd%RmtA6@{Kps7tqGj*A_DFg>Z8#FrpaIvwqxUy^8NAIRu|Ob;f&TOnxzz9>aP==JSn})NXs`@7NjGBsXU~L5 zvHgft*z)?r?u25$w%(nV(4zddU`y21mwqYdl@DdtPWV$t!mhr|$*WBD%nWv+r`CM6 zN8_PS8SlttZ|DE8-hE`hPOR}?4=zi+H}=;rqUY? zEWxbEU6-7FfHTh1bA0swzA9z_mzch%z@qi^32xE z*8DssJ(}wds_J(S6t_DURu~qt|G|*Cl%c=W96CEmO9Yi5{Vso>(rfbdynGrK%SVXh zU3%cpXLt}-hoXjXP#h|AO4ow^?Wyx)*TQx&c$@pFSW*K{=1HixEi+Oa8+LG&U?TO& z@E=^o%DFHW0pZ}=T!`XjXS{>L{4GQm5GVOJ(dUsBM`Hrgt#17}K`}3(@DsF7XnH)069hT0sZ1y=1K+%7=Cj%>m8tPo@%2f|m zeL%N18#yx28R+#AIA~Rrl3LpulT@=WK8yQ3zC1#e zoF&nC)7{lpc_*8mTKl6xkETGGebLgp4nLw#8xC4q*whTO#z!PM(w^JT)z1% z_fqc89`NN5dA@BuK^IWqpe8ePEG}3i3tHo)B5LwG-`&cy$hA2(IdsNUN`?ZFvA~H5 zIVs9O4$l-@7I+bK%^R^hXlunDf7B>oX;{|(((%&8t6{`P^PALobPmI6aK-kRlnL$v zDtqYg+P}Ze1@0*o&j&!!i}a_RN;c_<$D_&zC0n?qgNulou6=n0JSsK+?w{ggzx5eX zFlpyGgy88!*7RMj*IFFmiIoLbm9Asb9mM~iRt)n^Pt0*wQd*{eWjIUB{0-R&&k5R} z`}N92R8Z{)y>^1_pP88l8;dO&nj=ksej|p+b$9Q}aZiOsT1BGqqQsu1;o%1RV1J)5 zfB)Tdh*Lno%7V6@c>-Z=+H33F1?#R9M?pxWxY%d?7UA&K#&%xnHOHy=ttsHtI7+iYP9yJpwUM&3fWo!P{fNPo%_MouiNjG zk$x5DKIlRkjv{nT+yfgw7@PZVd}-gS(LcWgq5tE^jpuxeMJhxP`(Kl`JW^J9xR#eaCxRDPfEg%`@7~>#PtvN=Z80o zuI>_^YhcRSd8C5H{_P^t6E0?jXe5!_UUt#LoY><^OboI>Eu~I(cAEFB(8zSMPpqE# zF1U?}VRCgspVG29F)`iA$5E$E>_Qsawa^@uAb*9}Q&2iPSXXlIxH%cPbSP->;TnJD zN<5%+fKKq_9f+f@DBX2#Grlma;>}L0Fegq|rsiK>2zfWz1}`cA(?UcC*FclId}jxw zySj23E4Muf2%fC6vd!Utli_PUT-~jSjI9e2TazW>hOs0X*v}ITBtXr2?hVV4&+rVs zPqJFkl7B!LIoJ{oa9&=8XjNz`>9F1bQb*W_M8ZqE>%FGp2(Sg5Z8^y=k|PAplAfSc z^G3BxRG(#79hB8lE-Quv$|sul$h7%d3mq&!3SM1D8nE%GCdD&i6d9ts#3Qnr&=;&{ z4F_wNq+mZ;ISq1OtG}At1y{^aJ{n{^?H&AK*9+=@h%OI{o#(a2p%1gE-eO2f9kx_eT+#dHeWx zBp$#NL(W1EC@r@;Q>@?uZlCNENu#uv_T9qj*~lz?{?E5cGcz-FD^E!v_HbPFtoJjt z1!{j>3*+6@=?PtY=967Z!&_2LO-x5dT6E^Owxk3xDY6*4upo4MYqP7XOZy9vCn(@y z-Y~Vh5msAL9*6#o?=i1S*|Vc>x{@xzurU1IY<9FLa?r`t~$*VesL=GXZ6<-@AX|7`up0pX#cY1Wr2YCe3p z0aSJWrF6#*tmcbXIo-MQ6ww@t5XmrnE4e$x8V?mkeY1Qna9T8IYf2u7WBjtRh4uBF z5Qzw(+{WRL^5Uq$f&L4qic4Id_q9KW=^0M6*0HOa@8<^OK*Ifjk89my6x^eu26C_) z>rwRm31O|VU9P23YR8GY*7iOoX?hX!jhp*(Dbo4nafp|;)AVodDVIIo%l^-*;L@>k zMRR*&a(g3VyClGC(9q!L=BPSg&fb7T1ZW7Y^al*~4}=t!JJS|Z4TUt{I|4BN0V+4~ zM%dDFKd*k4%8h^=DT*ycG_hFgJ`7kJzBOQWP)tp1uO?;gZ&&-~Ryu(&F}|6)(q8-i z>DKCv@EE8$W}ipGbIz*E^>J>ie1UDnhj5_U_ECoz@rcfL-|%fy)MLa-=ncDstL8Rc zel{dpYR*?eSm5^E^d7*Ol2uWSfcU$yHi03xh||HXj)NxeLGSl* zWKpDE9Bg*5tsvl07f?YfGejE?lM7rwcJ3U_y7r zB_cO{YHhi(g|)s@)y3&3@rFaU-*lZ$HwB(8OK8JiZm)%t3i4}Mtg>z@EPBLPs};55 zf%cb$f%CIznX47YsW)g}kdHn@)CE!oU%jhS7E+okD`Sz3eBTBzkd#f)U z&PkHmjj9S=2Q({#1E7$O>}n>Y6qE5l=83c5N4Sazj8Tw~9pO==w5Zb|E)InE_HQ*Cn@Mq#2Ojd*zO5^+x@@OAZ@&+8_Qo<*pG+0 zG$BFq+=Kod%?3Gnqu{l230EX1ZgBM}J{@(eZiV(P=&B_34Cv1zdR6I18jC%a zn(6B<9G{=}4hzdUd`v!Q>94S$0%@G)V?lzJz75aDK`$cEY#L$mPS1(4W8g-DBFG#z zm>Ofc%H31IV*5_|xMiHAN%GKwK`3q)Qx@k)YsPU*-h98->_ySi5TY=&UCN6O(~MeI zYFFr1$`QUabV5-H%m7%?q-_owJ45NubMm7cvAOQ)k&>Z308vfGy@;nme z(tO}DbRQft>n!w^>iq06VDpwhDDI}x7HTvi(0m5rAO(5PkZoEjIG!YB!YDhqy&G|p z*5cEF1OlY->XGk$$FNo1#|n-;^!c}Gl34Ll{Mo$v4GHBb+8$itWK9Q|r%Q*asseJd z2};w6YIzX<2?vcpbFgf>jcwh@X{@>rX^BjCh1t+H)L41%9cM9ial$2e z6(!OmbnefUBErEOnkWTEx01b;94r;#go%=^AlQ2}VA}Hj<;6D+rIk#k5NamY!HLQV zWcodFBDx-ndMU<-*XZ3{xOP->UN(=$@$%m#uZe!bd>~Zx)eFbwQJ`p7Wp-- z`=U2ew^?Retci`OtSI}l_%9<4L5a*EH8I>?j-zj8{A zli6O`nCD_z-t3ynvTlr9^-y;*gDfW1(jm%B>gx)U8+XZ@T>JIw*J_#D^HNDALuGn~ zgHh0GV@yf-mN@@s&5!*2n&Rp8WlUU)&nUqcVOKUz>$nZiL@|SsH923TfPV<@0ZAGM zuTz7cgSm7)R{y)bkPumhDm}ijmHL#VMmb@A26<&NQZluEI`zbT^@OR^Xz3qIsWD~Z zkryTgqv6^(C?Zlh_g< zVu3w5bQtvZIev6=W6@OvezS`2<_BH(jf1-Ayle>!u=C1Kx8Zz}=OH;R+a}%vCp-l% zGwFD1K{yo_xk4j&bOtIMDH0x0#gEkTk7E(>hbF>ULV$vAuy^pV+B52mT2bs%z=hN zQIWG&ZF%|jGy%k=E(PYj;01JxgI(wCqo0sthlJ0dw!>#xpX_Y$&XMhB6~Z#MzFBQnd1~;c}_%tujpusLgVoLc<4D}-!>W=P^}_i(jjjv@BAJ9mD~Y! zXCe_ON?93kzN0>DDMgx%Ir6mVTLRH;-x*}yE+W_*7gxkTz&}8%LEytlHqZ7+H2x^} zelc_h-G+JTkq^W572St}EIK@Wxold`{+8JHtNTb2Sj0!Jfxd^l3si+thR#_W zj9iHjRXOwz0_Sy|olSH>2yy)N8P2-}yxreFqoCyk`409CE~O8w#Ei8dhsj4HXm3k* z4-;m5&0cw4Q#~R`A!|g*M(!{P28p}7ZZrbBDxfkO5nQH(LCddn@YdL;AFB6uwDxHAFbi67~{U7XS zn6~G(B)GKUf^E<-dVc7jhH(|4ku%G?YuccCew)4A zT$Xt_&_C=C#I4`h{A0(}RiT}Mws5sH7kXFa)xNj9KY6Wd7wP9tP2uxUB9Uk7d%p+ zC*Yua_62QjWMn|WiVyH$)6$5<9-Oy306yE09&1OI*;S83&s>Ie;~c1< z?Crw)zEmov59u`?ij{S-HMxm@ zJFnGIAF#Y}eGOz^-!|dN8b$YD1e>*?K zsH-pd^`(@P1qJ`BDj6Y2cS7q%%zDUzc0*hY!rYO(()4)w(vb%ElE@Oa-QU9BUk4z{ z-Ol+v(GufOZm=%Iy?G^OB7l*78dTBxdun9{{bg2SL^@m#Sra5)&_PeMA`X;fI3Ou zQXdZsCFX;tRTJgPct<8n*_wqQxxWGXb#`W&l^m108kB7JpnDegJf z6}KXl+~#9Avr{)gi!-1mk^}QjkQ5J-5S3t@At8)dzjt2ltTz}&1V$L6%c{kdHGeOy z#X8W+;QzXZWbMwsO)sssE`!r-?XpRn&`8tb8cs@Tumibt<)!&SM8&)S2@)CnTy`R8 z-j`{EMw0{ARB2E)b{3R3g0sm~n$KJBlg41j@5=p+d)D`=3){s-Iu{(%+7ZUMQ>4k( zFqe@O{^gxbB~HQFQtE4GyV2p3E89B!K5blD+#K|U<~pV$`JfQ&o8xDhXFb%R?L^V2 zb-VF3!((Mvx#*N%#l@Kga!SMgIV(fcOh zAoRu(OwwZ%O(*dVsYkr2zjXAWi42>9IjT_`rlO#4W;y?w4F5&&W4f1Rtt9wJvx&M0 z5@Dksk$}x+*Dp49%0=I9E$0Dg1@wG1ZK%B#hV^bkfj}5dgI~~ ze(6`DZC0&6h1|^uSSiAoL&STe8Kb25Cgo>lf!BCT5t8G5oQe3E)|T)!0099_e5pgC zI``z&cNbQ+yTC6BYf7Kl?9pH^}6(r@Ef*3X|+g?6KRe;SvF6h`T+ zBEN4wWoi8|#dNC1pU$NVB^g*V@7OqVzm;|%f1_Y#zF*Zv`p9GO(75v_B>v}ebf$77 zQ{(re1mBD3BH42JacBo%z=3-6KILkW*Z;RS6e7wYsZ6@toPg$hKoxM|JwWZ@#Q>07 zZ36aAQGOClk(xYW5%-Aen@$gGcV9Th{hJ04Gwctgisk*uVz#skR+vPjpixT)7$(d! zTB?O|h%P9Y{_V9TMqIvDEAJ{vf7^D0_DB%SWC?__<1C7gC++zh62+Syv;=x-`UETf zmj~LZaIwe-dXi;T2rbtX-`7l^HV~Vag6eq(Ts(4600rU&iE*_ZP4N-Q+uvDXhmBItm>XEj1h39)u@-kr(iBweu5uyMB+0MF?k@fI zB%7m7G>bm@7--ll{j;(Eb$akkeSA7(VLhbL2K^4Wfl1vnZVT0NanBaVjC?itB--i+ z8_Lcf#&h+}yJb}+SQkjng2N;3B0C-4P+sWsl1#~g-2j|YNr z8`4%kBU%ebr>IA)&8!UMTnfG)Z5rPuLtoqeHog=NAz)?eJcRL_ymq5rbzycE&el!q zk=HKA0s6jtU?XMO)dqu3Jl+qyl5fexub;jgY%G<96Q4Y6nG%HZ9(o6^9K_yJU)jvl ze8;Ob-q4g-p+g>XKg~LG{5TJNEF^!3%^U|PH6L_l?Tzb0{-BR}RX2V5Yr|MD%kH~@ zMo4&=PcSOQbNh*3?fBiCn>U~4>@F0d?i0jf%m)>ijSdK`6!DJC87a(w(jgOKh&y0N zdN+gV7@{*aI~*E3}x zzzLw^+w@}+Vu&2&&$v&0n&eA!e*0G1l3>iDInGf6?b1R&d#a424*`Nq@f&wLZ-xzC zi@Rmw?z4fgQPEh|3VR?rA0HQm6gEos3&?PW*!Bg1jTlgEdH=)BQ9+*&Me0`{7+>^! zJ`&p@f|;R3t!rUPebyz^TBZPjwl0Y^{k?~e12ITjndihaPyk{e!BA|w31u|>2PxR= zqD#sk;irE#=?~RDiXUP}!95UFDid@VEmduE*|&Dd6kbzLkN5wpF06|&Khvqyz3-vW{o-`$x<>)&R3Eh9Fna(0Jr z?acy_+ioJTwbiVi;7|m9nsx+e@NkZtq*h($b|S-XQ}|*JqpZwE0k7wLUZ2$|5>!l@ z#1>{)QRhRsnbuY1SZ8Js;b+j-TeKWDB|fDeu-cgjfTW=azU_RGFQ@UH26vH@AajtX zVY$V{j+73JT<`zLd|f8$X4WzemVPH=2=1i5u}x25W6*tOZc#qG?t_@rYNtA(i;ub+ z#`D9vu|U+oM&>3t8r8><@~MzGfgZ#W6lWWAtT$n0u~tROo-9Kr;u9+A(hHeS1RP7p zL=zcfpa4|$JnbOqnb}tJy$%bDXcPIze}k<@{6UP0{AXiB5BAXp^txE!)@bjHPaQ); zLxZ;~*<76cbv+9nWiN+QIL)t%I7Edjj`+yO$Gx-BiL_$-5@wIes3sFrW!|53&ss%g zGlqWN8w8EwtaZ@Co!Ik!3+Ws`N=Vam}oi>Y)5%iTzyl+Cqkq&LDbh#HW za$hglkglEX)Ph~ZD)vAeI8|o_m6owM_IN|fn}(*QCSJ6cf;=Ea{Yu zg8Lz@NTf?7M(01TFZQ$-g7iL^8Azkc+L`L|+h0~>Q59vN$%H%ftU&6=0uLBUm2~cW zq3tzm{o}L&e$yAsjB?L@a7b!ut*@_d-ux*FR{55l*uW?}U4#*(9fG#ddW0VXu)Np}RrV}q9poup{}E4I}KU~KpS zwxY|M#%6u=z{=MELj!*4AApW0oflQvvVOxE8ds8hr#xc;^tJi{|^1!a-*#JBanVLB!s{(y52; z0FKo6ED6D1x@LGkBeZT&3eTRh(PXS;#pL8Ab$bY^^OYt!9V1nR)e;lGO*x2%*jtaR ztgH|RYdubx{hO4vtFhCEVMnf8&}9vgCDfB$X3WjCxmvBnY};GU8XygE*HF^AooNK5 z8klNFar6}az4sa1Yb0(n;q$xISd#_kV?5aepua35E%_{tAc+IeK2ebW% z<>Z{E?LWW&{@uHG67cI36ch$(0hz8B^n@2d6p@jn)UNfb07aGWy&o7Ds4f!gFijQU z?!YL5)OV-+-;Ir+i&d8}s*0_B7l!LI)|-3*!5G2bEL!K!2h3$nDEYa0AoJsH^Q8e^u?pA|w4; z#_swW#Ij5R9>w2B9DozpPCiUm3sb@aNZMdXSF}~ClXY4{k&a%+Un}1eRFLHxaeH1s zQ_TAZt~2J_eH-iR6VQf*rq{4WXQ2>;FCOT=oMxcq8ro|m(5DX8Q^(?b8Lke5gx>2?C5Sgerbshl zkES$vzU)MMMvA~6`FGS&|4zg}@7>2!nj+bk_V1=McD-S!>V_{r+{ObuES^%R=F%j} z>lqMuJ($@qkf&gE9vnIsYsAK0?5(|B1&}c51W@?(^@#m_#Z~9l3@4Y2(Z)H4rQJm@RUKMf z-}^XW@x^MppE8aA$;XHk_xzUmPxqyyR-D=$=u7(EcoO6RIZ4a#_<4F)^$?TNmoCBl zXBc9;^4&4|1}(uaVr?v>EHEg0Y9+aM{zl&q)yGtmHuB1(4eN0m`X()lOG-T7Gacp9 zt=cnP`V>!)q*JLxa#8OCdjqa=_xj0dtS;kByP(s(kVf#V-MxTUWLitT()`_A)!Vte zwx%odGwer9u5~r_Z%6p(1w#WaML|~t#COt|K|p)_0WeS)Yt_v^BupRH4TnErFuQhx z!ULB6&73*Z+B^}^5vsa2J`V2CE8Z`Kv2UQE=PaK4zk_d=FU6wB-hO^+Pb63d+(q>N z{I6j7@p?rcZeR@V3MH^U0H$!s?EU6=tjP8g#S=O|wv4=uxR6`&h57ymkijm!f5Z!$ zrWQTDysl?D@oKw{t=nlA^iNs~Jzk0QF)~pUl14@Oy@$VKKO0Sv2O^SJJf4WyiEkLg zmDSZn-DnN_Vo=&CC){~CaD%0XNMk((iGui^mVbY2h1&w zhpOJ|N@x_aw6tW@FD@>s8qD_-WDR@nAIMb;WcEHn(_w8w6MjrBm=nd}GJ-uaE+~;_ zer>ktD(o7%ZrsCS80})i`8ys1nu-YDLwG%c4l)~oq?I_q+7P4yF4Q|oc9e?0p^wNmnB&-< z^9l?()gB)4-?*;g?k2kxS$e58aH(~tVsCzbLt(Fp7(WearKnG@?WUST_A;kJ9r|uR z{@BnEvh=-!Ph{>##MV$w>icR6JXew?WISX}enPb`yH|FeUOnFk$3G3L^_ZuvV7bxp zS+)cVLVU+J!22k6bKiBWd^G~m`q>O}wXTj)p#DT5C+SSpED8_{$P||On?B35G~liJ zQIk5-I6hH+N3N^}$M*H_OoBoZ5yl-wRVK}I~fN_5&?!+g!41bnM{-dXGVOk+ooC5NKYHGb)5O|t+ z3RR7L!lQBAqq(Z&%Fu;#9B0V?+RS8dPBnu88Cb?Hru2I6vZr*}ui^^hu~n4P0+U`XKoubPU_J`!ZtoOuK&Ii zy72*#X4(|^_eqt*LgBP+yu)yw$3oK( zLDI4>OR?pAkrXwzD25mT|=n%%b|ei2pK^k5Q-aVqCgd zC+H8=d+E>krXu!tnDvz_ukF6t-a3ZQpP?j^0tK7yuP!fVg{&{A?`>J$+8Le-Tl=-V zHk>&RzPmG7flS32nqsap`*vy8T>ZTts37KsbMrHz;Abw~I|xQe=J>Fi#ft!9ca-l^ z<56NeG-7j@wd(9q>O{TZ-!J|1iQSYxy&hebvo1oqz0hQ(On~X?MX2L@pd_}s_Dn#X zTEN6>yF*I}_f7%Gx&T2@*8m26f6@}-9{B|ve;Ew zTmk?Hp@$H_Egb0kdTc3?7(eT4UAn+v+KejPY!d0h9wmeG^;iGebH6X8mTjB! zCBPd5IEz0oZ|{mYs2eIdEo^Ny6rGZPgVjBL?lqiYO=5%hJc@4ubAKtKE8oWn-HuZz zKS}xPSywXOFy9cIU0h5ga-qRyr+Q@aaM^j(8`l%qjb*GANt)g|#2M))LOK)O(9$4W z_y~&~sJfoPbs>|B!yf7}{tjMxe$f{NE3ZC*hZ_M#L{Givua0jU3uC?G6W{I!ZW!-Z zMQr}9YhB$LOAcNDQD)DK>jeM(y%6A6@ethuw`5`TX9nLwX(3eAs!&5KOJ78DnQ@e`P31By2Tk2WQs z;=5eG-W^&0J%L{EV{@aOE^fv_*nfO#p z3q7~E7Et4fJJ#l6;7YddqlG$?*#dky$J$}qzZ>$1J!*lf3mn>nYp_mfwS`2A4~3rr zT&g6w{B++UH5aZnf<9XvbuYuYTk=@DRWCBx#)eHbpPwD1Fiz@YuBoad#1LcnzuES! zz+hy!q58TO?)s866l3+IgnGss#I$G8lP<29r{e8i37tt zAtkj^^@w+wp!R3ghp?2qLbK6lq|@Q2iFAL3TlT{t9vK?g!fwcd5;QR-N>Bg5Wk*H}dJ=ukXL3u?2$!zgp0bd<4P1i^H@*y99M$NZ&XB zmqi?5o?v`(t}3rCpqe)b*g8@WbgE*MNzC1>ewdG>S9ygQHyO^pG%F}wKtoHaqH;oa z{wn_i2iEo?(18U$%aaOU zV#Ln8fiWfDM?PISimJAiGi8E|nmefn=AfmgKW1)`XJN!IaRw^7^+4=b)?;ii8)9NH z+Bh-!84M!=mnNcllQ>$#lG`p`MdS)b?EIBL&#E&M3hG;0yNFo9Jb~Bc#s3?4HI#GY24^SmQsDPhMN)`%Q!Wtv9d8leTBZ^+ z{-g|jrYRzGC^!f#rn_((>*`&Ar8 z(+L0fV+go#6(V-$AwP`w7mO`SIsp@`(Z#rB@B8R2+bP=$m3d>$-InJJKx2~WPD|*_ zN>HP|7H&`WYWX`N%y)H3XF?A0L4CYJB*LOyCK`^{dk?-L0qMGoV9HaUn++!nxL7YE zBlWE^s6?1)K>(Wmdb|U+Jm{ns;axrbq!WjEkD|! zYKZN87EZ=4|Bp#bF|OUL7sPl zeA@>K4PdTwxOZ{bb0^8|DHSqy%#8N9zmr0uml*k4D2x;;A1*HTipgZay3IHl(dEiL zubL;ARgd7?4)!z^|4!+wf+EpIpOd5W7KBLbtSv?t?G)S5))|TEfn0fHG&bJjIws%b zM-dQhze}sRehtTaz=>*4#`H0rDck}1-u!416&{BL8EI~u88g(LTfOCyv8VZ3wzVNITEOWbk56c5S`oq8L>AN zvDzubb~!sfk#hbJd?ckEQe)0`VV`k9-)_9?XOx^p1Kfg^d77VH;N6VkjTiF-mEva< zB~D!D58I(n$cKrbc*CgmdW=MvlCd+oqXfNkXSCmJ3>`m4^j6Bu6(z-kOs7D*cjJ_= zJayXN0*fa;!7q>XrANL9YPNAhNsGB;VNY;yqbEcXcU7_I(ARiHt@>g&=0W>uN_O_$ zj0Vns*KJ(O)b35F4CI_%3t{4PBOyRH-)+=eD;4*60t4VLyh3ubWUjXKg}^$03sVY$ z1kFVVNcL@81@Tjqa-u2&euR{*-md{n4yPAnxB<}!c8rWASYPuG2sn&Vf3o8Eaq?~; zWf=^#|EM*FTH*$pFxE!0&m}O0A^6gzp5YkMwhrZkKVP{)K5i zk)RuRKjr?;A$H|fUnUvu&UR46#LqVv>?E6i=~Abd@p>XIUN$lK>;3id3cQ(3A!z$? zhiU#OmZB^s?y5f@Qx$u2Q?9t+XBW1>T#k;tJU?;AS>CDVk^T3qoViCzo@KKBD)^v} zwUfbZRu05FlFd~K#WyQbGyA2Y#pvy1_26Zw11~HczTJ`Qk!IsgH)rCaU(_(jf=UE> z$^X86VEWvHgmW^2rq)-~kKqw62dOHC$7CsT1bm#6^KpDWWscU9pFsRY5LVMNsEjL% zh9?pKJTMU_Ury&`rSqHU>imoHD-x7c?bJhZwHbH3poi}5j18|IVJ&PXu#>(wH?jl4 z7;~#PhmZADc@c1R@2h{^TioB?e>V-c*TRvdRTDLYkKTCy5vTG`hx^;Bsez$%N4Twg z#vunPX&HNh`tfg&bnep?<)zwfsyLgMLon;#-MMG;Wxr z8IBE#hGVoR8yu~Z!LyW-1dH^^_6?X^op>rhL?fHKV3}YMkSuNHU3a8J!t+Yit?0K+ z0atkY_j_q0G}0aIbmgR3K@>up_W}0TL+}!2eurL-IFN}(v+|~dl*! zqrPfc@~3B9nZ@6>UEPI7dM~Ft8r&gpI8gmwGp?bjROD;EY+|;reC|DB51bTZn;JU% zDCJ)T%^|zcN7zr7uJaf>;(rB}eU{{*dhc`r+0ka$!T={eO<7!5D?5H)KYbNch1{b5 zj59{9y|S#!EU}E@@|uy6#wdxW1g^H&7O-ba!pDr+khLvNnkn`tn=9f)7}(j{r6u>S zpn;BK{cszO;{}XlATUia#Yf`o&RI^ZeW>O^AJ?9FqxlZeywZicod)~=EIFBuJc1Q$Gev2a`Qh~!HD$pg)_IS%Bk&1Dbu_Tf(N>v`}II8#+}0&tmWLg z$#qAGCv0h+M$#zi3xYJ^zq(ZMcnIO1YTmt%pAa1Rm$8r01vE@s`b$?~N!EPra1;;Y zNf!vF0#}7a<9{l>PTUW~sQAlTVl17A(5>$loO`%1@{vqCbHsCIXPJZWUgEr z3z&DGeOU)!Py@d21VndotAUvE4B^||+y}u*k`};*p}?o*O^7k<{6DiQD^IUL>at+2 z=f6rd1G77sPLvA=x4Y{!H$O%!D}3qyxw$zuk>IzSwG^HnR$FzX%?}NH!j~!7wln$D zVUfI8-6BaLJo;RUdBbv>1;MS%%d<9Yv@YQ~8fTcd9*$r{K@URIGMy{oQ9w9#rOH-5 zVxvR!rmb!0?#BF;@$%73gr7n8#T@RH^IM3QJ|i{~l7sOn*{-zyS&;Q%5AaQx`d;LX zo$zVBbT_shxH3ldg=9R`_R{ zCx+oHJQeZhZ6B*jMInrd__5xy(yc7aE^2IUxrXC8x7{MT{ZwFKai*ygc4euo68jE; zXCfuOKNM{^iUJ|`$fL2%SU-brx2qnZa(UCgw=DImjytK`<>6PZE0mmOfo_I(o4}kvl;&~L= zQIMk=s%%xZlZbm(9@UWoi;3kE1vC>zLorX`Q+|qXHv19$nSedT>5uqFoRD9gj)+*t^|^Fs3S0ujZC=c8m4h9E zf0l3jNTP)Gmme7^C z&Z;YAC@0`CNHv{nO2$7Kg5WGujL?Q1m$@v8mq#oKT!df64Iw`3AaL8LI#rt1TU=y3 zFaW0)d+skz?JOQ%(tL}vVe8*}JtM45VRAsU^NZa?)j7$EO*Lx=;FrnMlohznl&Gv^ z%5;3CuDdQwH;!LEIv;9@AGX>3%eUXWyI8KdMpeWI>q;L`-_jc;Z!1?8`ns)$ArjAJ+F&g>Z2TeNZ4kh1svdlRwUhy-*V_h^f`^AX#t$zYm+ z8DObnk7u5*n^mq*2pT|gzAkH19D;Hjd%eQhx z*~ZW(f#bAuNLew)vgBYVjD4B^!cbrIfA=o+A0nm_I;og^CqS((vzO!8`V-Q+-*$Cs zler#l44Vv$9njbgVa~F;Zgu^@;wg_BtiLvg?2onvFWj}McE8Nez`co#6xseeTQZuA zEpgIU4V0&9NOYd5hcU(UxD?wzZND&=tf|$wA}U)%;*PXGc~+@EWsrs?{P?^+f+GM6 z^}9$28toU)w4q;aTf6=KaXBg%A(_&hCIAG9r0TKne@6$DUJ_*`pAQaNbs+ks9Vl>J>IcNj z^_KE^-p$XVSUPkFAM(vsZv0@6&&k8|gN#Vb#xyOE(5qN<<5PmGFv^8}`rD^N?xo+J zsU%1hAi{hZ*BApMnKQeXf6f^$O8SyQU~Usn{4()drO;(EEzeLEg`16C)Hbj&xTmAEvP*!m<$tYb6|8scJgIVu7 zj$kPtZ79A+uX%RHCC1bY-EIZ>SFslx(R{ISpr-spzgvv~N;yUTflJ_T&5ehmJKq3@ zP!qWD+SS9B7Zd%f49LN073E$c;TwC&ULvjGYo+6h4dsbw9+Vvn3)F+fDTBqg=YX>a z6l&+@oNtU89=(ZSyg?MypDGAbF^~%V^Y^U6t*Mq4jpD8Ro3yZj<)?m3E-ycssvQAzt3LqWN#|pvDqGs2i!{0l&e91D zxlk+91JQaA*&@u_pKhI2PyNm^g23SUUw^WfGz&R|Gz<$`e>E5)R_s4WGk{O^kR{b9bT&E;MNe>%^X+camAp$hMcdSI7^6bx&TQd|=6 z_?^;=bkT|>sq}^ETDv|nS)06WV@gnj(9f`||0|w-{pjPZTN6P-u-y6nM~SY=Lwg^* zj4r4&W@cvgA|BT4ZT718SG6=uiuWl=q4Opja=3sQdb?DGq1~61A^>7Ue=~bW8DD6F zKb`aHr^(vyBkgIYP4+g%k|PIIjfDc2;PL)tr^@t2noI~X-6_h9@05&UJo+#jkR8bZ zl~!^mSf2xTUrqdu3Jl0TVWUJj!_MfXDl&o6jaoXN+Ix~;ii~JzQ4_JS7;yG1)>ZWE z2iPb*)W%y7E8G0O9+2%=ZCzfPh`>cuYQ0Y9WEXS)IHvUd^YjUf4BdNTHqL*Mfxf~psP4^f(0 zRbEU%6{z>mf#W_ED;a&ANC;LJmX^HoY`RRp2x^fG!_F!{&LgI*mwTRc@5ij6r5Kwp z?KlO|T<#fCboIVtEZ>OF`slEK#pMbW<^S0eV081qA5ngj>HdvfZtpNgTr`AM$lyNkx* z{j1z}c4t}a^x=}BklxiS@YO!&_B1MFYv!84HMiO3oC4fzUp}quF+JyKE=GV9hd@al z*Ls3>BqLAK@Z(>f5old)_RHI z`kKMtqoY?>S67%hB=|7#rmv|hx@Pa8=0@A_D$xHlPGx1$Y8PLo#vjWjInzWNS(zm& zcrKF1gfh|cY$4z?fGwg3DV@z_wgcqH{0z!U+=ubZiDtDzTW{Xy*i_Q%D%|+p$)->M z!m_EYMRz7i&{Y|q)-N&4Wml)$LI_2mI&{afu5P?zFDU%Avz#gA<<*ECu=GD%7Y+UQ z1P8J4dr zSW$nHyrQA=$)-7U^Y!3Gi4Q3ZGP4S0u2=L%a7ERJvE8C@&58VBdmV5l0{7=DfZ9~0 z71@xd#7xJzyi)}|6L^^tbuc)C{C&v#zf5jlt2;FxZ2WGHHVoR7xK-Xkvd|LD%Vy_J zEOH+^si+>l^$w(dvLDI+DO8j>QSxtxl3I>Nl~tLb`xKH=?Jz*V|vU}0YwASAu{|m!=4i3(}z1o zK%2|^)>az1BJP?yvB6wFPqII3tH!EO^l-{K}s!UnZfmMw_5bEp&M=6)ahHHd$No(Vq|{3HZBR=A@|eY zZ1virlN!VYB`6%Z-!E}SraxN|;eSR%hJmRT{awa$AD^(`S(5Js?=}whglEX>NlM2j z`Bd_>k1&GNwn;NZO>(!@&qP)2eKux6xj=V4eWtGqZsyAbOX?qdoGb07yP%RFJhj9$YNgZW0>`zE@ZH&Ge#?{94D{?D^ri;Dnf zcL3OZLqZmejhARSIk#@vg{^F;oGlri2>gxe5zt+_6#Az_bSF~jWZzCn&c0l50{q{K zAnN#^ra^+9kMDgvuy8uiT;xChbVehO(d0)9_rHN!MM0qTrY69Ki_Io`+@eXhnvMlIVDOMCxZG*Mbj>t4GT+FJWv+OP#lj?M;Fr>G{om1=62 z%G}Q3Zk!W3n|Un$FK|4N2l2&MCeAD&ow_=nn!3#e(-;mJ3X{z_ezi;&14T$0$Xqxq z{Hh%!aCP%X1!pU1O&wueB!9d=4Cz7oa&(XSpQE=&f<^2>V68nM$Wbb(oLU8fX!`Hw zm7{rg(+dJB553)9TMjsmYutQzbxAYm55_@;sv+E{5Wc&)zZ$V8I<@&jXL+)b zow<7QfLk%Q1Qk+RX#+w6gXhJlW~vM8NiRq4BVvMU?MC^bU|q!r35^uG5G?A(cNYUR zZv^@W`>6|$J8ggespMi9Z)&0|?f&b^=&C|?D@?nbCcP5m1NiGIux1XS0005a6t;k3j8Ts6?_f}O+Q*FqG z$W8Ky>65+!>j#kbG~iPrT3AvCS>N79BVr$5Q#oQhp}g$ADt zz({hL7h3e4kS}oESrFCOUJ%{;)}LwF)nQsvY*!7uf4g;|dLAbr>CbrDtjsLKruf2Q#X^>dag^k65!?UOnuKR47~5Mn<Iu)s!fy(liu@}I;(Rj+tGwk}Ui zNn)NfLi8XZ2(||F@-?Yx8XXXO1-<{}ss#`Ukrb}A$x|$it!e%;bKcY!>T47I!xqg} zH$C{0AH&+Ze?D3nQazdzzCRQvCQcJO<^B?kvc?9y|L6p&3I}K$LLDdg3}3*}5j&lm zIFz7-pw2X9l!#`wH5Ryvgs~eNKX$KX1!@M}ThBVYq#pFabA%`(gA{67YW(>oY-#c| zyR^o+3fP>B8;X8?Ik*(XgK~zV$h?2%Rx`mvBfG`(9`5)S#-=v;!QP(K;p(J{Y1vp} zqeXY7`M@&=ife*q@~RBg!kIjwXA+cv#&h5k{C<~L;|WXo@vbt(h70{8Ye-2KCSiUp zTFD4aB7^DRO6dLjZe@#&*aKu*xu;ia_%biQO#ZJe`TTT0Tlq}hr)Iin9cdv3nqfsq zA==jTgE3gf+4(Z+@>+mC`i2KU7c=eLqg`nVb((u@&8=H|qx*|X``^w^?KUs1ciaO>gj?#tTYvNTy4N*#1IBAd`taOZ zND1YC%}G%Lsi?zCE=uPzGB5#OmjLs^7u9*c*$6-;(|S`XJ%4m{!4sMW zj!1ycDol#&u8)K>D3Eq4h9n1agmNjb7$S)i>VP+UT&bvP3Q4!WoK8(Kc{y@iEBx<{H5lPrTBg8(VG8CD#UuH@YP&pCsJ%}LI#v4^%M9T| zRu3Y+iI2(?)7q=_uyY`6%0SQs*)Koal=&Xr=c&1t$|>~2f({I|d))O+NyXG9p* zo-*3&)Og1?K51}l?%j~r`9DIb?-bVEZ)e+{uWjCczbG&X7Jj~ z*h;Z0T%7u-qw-d5NkRE!#QrxR<`Ie5_2+~?OM3@`XT2fd0Fqtq={fn?zA(7>*Ox9; z!>Y=;tzW+u7J!sJg~WPU7#Vc+3h7Rd!uAs_3r<+3H?41POmLwJFI>Ie-$3 zx}{(#Y3WxF(saAu-XrxPRDA}H0rMRMH4v;g(VevT(!=A=phcj0mm&i>x&9Kmn1 zQvrCjXS&r_wce`TlC|S8f)nvyahFO;xY@R~_jw((rM2Vu4W#oLwiZ_`AH?;REc#3V zh3f7a8229CCIzbg_N-9I0Sryi@QB9dfR#_DL9)e<>4)O#9AToODUqhv2{WS=x5`FO zxf{grMiMG{u&BtoiX#lvyL1*n7NrnDO6ND<#7hsJRaG4(gtn4y1}pLq8i}6x1}8zN zsxFzU#U8&r>+)bM+VM2(<#BPyLZL4`6iu)aDvUMIkmUF4{v4TjTqnvx;1($)Ms_Bzj1w%3ro#ENO0w*E-BC&TGG!S8KZxGlRcV+`q1|``fE^r)=e$T25%)e8a5cN4b-d$DayQiS!c0 zRxa6WhNjd`kR@B(-OIP?z=SyeG zbsHX3%E+zo&7jsP_aYc0wnJMFC{koN;C@ETU?vd3H|}QhFb|ex=+3*H?01NW<0u#t ziTzfwx3&b7xV`sY0_di*64FfN2unOB$;<$?7S?*Ry8DXmXH|;fII)f559E#L+;XOV*jEM0Za?{TDRuh*{8)nAMAp5 zK)Ys^T0_<+J2x#8BgR)xi{GyG%qRrco~HWUs>$(cE@eLGJnCDu!W5ZIKIWC94;-GE z9i0^Fl0N>`CJjGLyWzssiQp&bQPA}NiJ1K-__b4kM!L}THPhUNN0$qa?->JKn3X5k z@{~_DvMAc~$9~v{d>o2>E0>W8Xnd1>AW7{k>v1= zcgSX6P1KlNiKe=sB7K?QJhTk~%Q@6wo!PpHq zhW~zY6=F{T$?T{^v?PTrNUJ1t`!|}~UKYi?@O>{1A-{UIADD4$;QzA#qJ~Sur18{j z_G6l}ZDn!5Vo>{J;aES@@b#(N3F59NQ_sP~LP-Z2l%ZCK?(U1V)vZMz;N5OdJ=lBq z^$mgU-x}%;>@cR$@sZ-=E+>OG97Xn`@%@#Ijh6K=5hjpat9s-Mib+OsK{50=ff8K^%KXsze7`ldDEI7cq|&i_KZn4^*{6A;DR_IXL_RB-97nq9tKX)8Zh*t_}DF_^tG@}YJ}SR>SX9#pcMYPt_Y z#Zc*f1Y}mfbJ#cvhLt2Z5oA!a0agCYO}JPTZDo2#<(>du07_MaaNvJ@?1-(n*%GG# zC%~`3NDzU`N$~GFKN{N*S+kqK0T*L5BM@~aU)3(V&!wuxgCF5CC!mcW>0uADFOoi} zgc%+cQ?Kry&N6;#k}(_at9ZyMt5Rq5s!(q+Z})+u|D)+lzL4zLRZ)3=%??ERk)phj5?&gZp6*>Lqi| zch32IuIv3?7wkaFER_-vY&!D>w>Cvyg3}8XBv6@r*(OU|ChQwRb)v3_fyt7I2VpJn zbjLmxqUqUoACI0_8hs8QAQ1GQ{*a|)L$e1_3f|SG^yHbJJWYS|1rGn-RyDbW>_HCD zdFR#FbOy==yUSN^*Xo4fgdy+h^*GE+t3FVOY&BLH+sTbjz|0kROz13y=}#AEV=|Ft zga{H5-S&Ir_j9ph(P8p#bWatpCHn7?&h_^2cyui|4FUYWd_o2Rr_!;4#l@5S>?^iz z?xRB+zgwdOSnQI2eLsC{j>PK!tkiMr>BVTyE>Od#kIv%c2=sTjS2Sv(47W1vO@^hY zZnTHYx(;U7;;FTzqDUew!8IpUP;zLYF$Z#$BGM1A8oAVH{V?vJ9didRN;n$MKxvS5 zHLyITOFp^x2zr_oiWdMOwkRc?1Sp06Tls-eF#1VdoVYDTnOmZLtmuR#|EW*%y~lZQ z!T*zjigaZ#OklAkeCYB?2F8XI&OP(|)G5r_lymb+6e=zn?I0EnT175C?! zNm-ELH^)+S(vzq}Nq+ppxM%u2GZ*b}7R!-NV@|AglCa5<9?zZ5%L2-}Pd-$5s2NtR zd|b0?sIBqaujEKWoTUxf03Fo?2-Z!g_OP$Bg1WJDxc{G@eT=wc%#EMq09JO3)?RZMA`w)2n!0aSHgsMGeM z#@2Va=e)|G@dk2|Iy<6G$sl>EjKE8TYJ=}$$7_1;_Z(U z=i%t!k{hyr1F>4DnknCzU$ORV%9=Nxg%y^7N^nFlmQO(WKee>yzfu@u_g!9ELF*rL zA^7d9Cj@7E+Q*8oPkzoIMEh>`3%!kh=f6GD^Yj$1-uGa2U-7SYxoz19WCgWQ^k1JI z+$e@v`b&p<*8?!D=WA6|4-XGEiiVkWIk;>f|J~$y;Q?0Ir-v&}bZi{{H@Dea9eqd+>^>1{w zyv7Pa!RH)^Ov)vPrnP*`NQ7tp6tC4#67^H-ZH{8G>)Umy+*kVBq+6k6*lh{`QUCEc zOn8^^38k)Q2&IgBqIRdye}6s~y)4mQ1L3`wBCN(uS7y>2N(j2gpEq#Lc5h;m;p@3MI&Hp7g*clLN@0fWWCDQzAg68~8Z zFQhlUnAeWWEgFVp$acT+XbxGsj{H!ZM*^vq1QeRtc~YhWPPKt3tXlQ{`+J?SIglU@RTNCi{B1fty5_G?&&wVMR8UANDadU zqxB(?fDSe;Mzc9goH07{Fog{_tA>&2tT~DP(G;L)a1!wa>A%@2B)pp{SEWK}eP3Mk zAbBNN_arWDXwJXv#rkZnRAt^Gi2wMs#1!sawSR7Y++FI%5G5;Cv>QcMGn`dJs6hQ~ zA3p=`xm6cQg>SK}g4O5tO4c<+ZVcf8%q3f-df%c56v*B*n{@906~^Ve$Zv8ViA@Kr5>PM{94h9P1#?BB7q_54uzun`Gj9}U zL~PhVUs^IVKMNCF5@mib8kP`q0s7@Kvsx|JbH$vtMLJYcaPaqK!dZ_aPC@ac^umF))*w&|b2fagZifdMD;h6VJ-GE&zpFz78A3HTwHRrXGfSI=T3c*rOL&2V zQFdkBR*&s5bWGy2ex?NROUqcWML5>ph-dWiOhgGw26xbWivRk;&k^fH&B3khX`h4b zgSQ*#SF@?dG5#(`6aTTC&hu)${~}J~CHG0&6`sP$GH65h zvZ*CB8My_krZG2q2TDL4$%M2CLL=x z^kUxkkMhY2_&!=29LSofl1&*?jS?!08%M*bk=CT2PE*85mRcXYPbsNl z5xntQf}tCt#f#AN%QM}MP^T%-!~@tDpq{5|jckF1T)thkmy$#h)%ZO;8Md?FY6YRa@y9m}4G%T^Jpt5$jc~|qT-Ia485)G>z=o3G!-Qa=3T*q{F$GBp@%!=r2^5WjqyoH@A`KpieX8AaSMwUHoR5n5S%;2H|-i0>`Q31 z#6#-#{Cp3WG)q%z7S0pt(=08FWRA88a}$&Hm|$X{VOI>0LTJ^rd6bp#-`&EE!JbiX zuQIdVxH1k%dO4t@IPT~i?EiOtjVsWSg1H`6dZj{YY48kWx@#O`-2P>5E~1Xje(qgb z|Im#6{{C!yx6N=ll~e4wqI=Mgkb;NTcNKW<)KHBm1Q$WWTfQ5&;zrX0X$wSTQXeiM=jo$)qVRcQjCI5K!+G*O7@ktHCPw=# zGGH8n%%q~#?cDz;=Q>Iy1}9KeFjj`3atnh7teii>oMcj z2g%+t?$~I-UU4lAKu_R% zjQUeX_tUQRV%{|UJ@U_e5&w5s9qS*BEiUL{?sD3sRqCrDdo`1Cc^Jm zb?4ox%pbgqPoOASB-BTNR)kQn#ppK1ZD_~rCi~nvfs<5M>Akstrp=c1DmaWjl}(O7 zZF7Gpks^P7^$8G&y3Oz#sKUEqRMRk>yrj>(j8p?b11-#@y2`Z)LAW|cj=nyiklZ_* zY&MzP{Fs8X;kQl^{1j?Q;k60sJf7H+({>;!r zAl90Mz#muKJe`ir)?mGppad9fcGeMGn#ng-*B6uS&;eK44`VUBOZe}L^VX(YDr7+z zOsUx>o7;v>qDutQxIkSDyjCcfMFBN{%ovGWpjTcM_7iRe2Q7Ua_kKHSVK$nDD9>q$ zpNgG_$T*@X?Qf3afsx+Ob&JM-KcoD=SB5~wdkeEkdH?mz4#mTtw*~w@Av;S+68DDN zmmhh1?hpC;a|*F3m^C)F39Vtf!}3Tj@Dt3zuPaz!fVCXwT<}R)E(NMYm>jDv6$-Qj^Cu6cQA}!pc=(QN1`)DPNH9x z4aszf42+@(4Lds*elRK;Yiq5^-b>-7-v!ty;+--Yn7`4SpMc$k)F`ttE&?)LO9PIx z6E%RAh{?$jU19zUg*S$WAJBXPH5`HqJ_`oY_(G>TpD7<#16UYD<_`$cDF~vFr@!=b zXyo;cYzO0LPIVXK2d}zpV_(m*F;VfKfDmM!{Vn85P`vo$`AX<7yX(*Hx=#L2%`o@C z!uh62^N6p4O$tYl5cgfX_V{;-SHok#Wharh^#Mm|mcDgk6LkSRRt41BfSrl>cL9+B zhh^_fi;F96-qU|&)Cq_5sJ5xcVOFZ6o`JC4Dfi(k^a7k`*c&%1*;I8HisU!hPF<{RoOqhcsnJJfQvXjkkLpc{)SWIsLx|!3WijcGCq2!^ zhGUc5o@_!$A+kmn5qJT3ymI2CH*8eaq)tS?ph6>o_0 z=+hF!-(ucEk(HOT!#5eqVU%ao1=|K?q;e=c{%CvhaC&5ehjATJiQB*@5+ElB_$Bk9 z*sqQmWr&KjgSop174JpEOGP}B?;5=&>#q>vY|O^~Cm0cxAp%x`(K{1zy}TbNCJvMm z53`-|Xge9z#|tNd(JTld`CPl<{EB-<0PgC>h%e^{=g1DEb^5)cb<0~?7$zl|UU9>@ z8f!-a54TOTNF>hVZcZU4EJZKr>J5xT!q*a+ztIWz4*GJqsoYM*L@m75Ip4H-sxE|^ zi^IDV-hg4cOQD$^Wv$MOar^nx;jI+6rRC2q>k}$~P$)Utwfnord1YwMf+}yeqNs!( z^hFKSlwLV;3!ryrkbz(jLT0^AA9fmuxXpIC;1+)ePlB5i4JD!X)-Z7n3g$C~qAu|Z z5nxstp2_Ehxw#xuWmdiHHWH=y@MM@{60x{KO5NsosQp67#CPuL%%bF9(oZdXDOY-# z2wGP{b#JnT955XN@b|=n01uyq2o}sPk_iuaQ((-2mh$3%i4=ukIHxMon&sm|=g5Gq z{3bsyD0ETbzp*XYed=w#T$OX7*rb~}g5~b853DfiZh!_#3nLuc$?)HidnfO+X&11b zL+URpiyfPX)>nTaEp@*@oXvz}&(q1G`^nt$G}Uwas|RyyeF^~(qIzY2#9d$e@J%*`R0Q&#JA39?Y=C^^<-zG-J)F-{+)WftnQz!i#nPI~Vqr5><*xHPzU z@V>5Y=V`#f;DZ_OuRAKh#KXeU<%#hZ&=7v2;l$+LtcgXymIpHm5)I#K(>Q5g&H__{ zalukf;a_)^`6Dfv^*>JuX}r-R!H_IY5omID0;nET8RRKMh%>nVpkl}TnN>M5Vq#_6#>jXczezD5mUCu^-f5Ph zRf~m-cmEn-?SPX*K|TW_43_)tr;92%6J+lon#G5VN9uK9w)zpYxbWjdDo%emw#W-? zuca4iPwaE7PAZy-25gtTyKBdl2&uvBf*@4Pi`q#i1@BD_&6fhV>f?3SL0v7Vhuvm2 z=5{H$@eUXavhTNA216fZ^_3;6zWFcwv(E1cG+|^rm9(WYdCsYtI`kOh9oCGzCGNq# z@2AI2dtCGlx=aghkTwXI@g3mUhmaFHj2^p<GAG4ozigp;#sVo` zpKnRT1{L}Jav3v0UUn2z2LF*HCd^<8a0Ki0-Z*1nyPxP{r)r;7sH{?fDM|AARKrx)A)^T`&t; zApwz2L99%mco$V4mZ@o0WoB2<4(@}QAQ)J}f_e+R0TJ}I%qCr%-6ww~wm^C8osMjg zu54$lve|GpQlIcj-)#6NoK@WiiEXFxH6PbT-2TI{bk?nGEtPjj@{~>eVrM`XX}?Hz zcPragU{enPsrNAIw~(}IFR_So2rWM#b%+oa9b-8?y;!?a``gjS&Ch_x(1=Qop|hdY zrMpUKPuS6<59Ni+6K319;0|Wi5;}7nxgs(3@R_gvo+ivysF}ucg#Y z&NDeC(U7;EKFKS+XPU{)dTFQzJjVQ5;+c=<&{ifn#luEt+J9e6U3pzprBp!)L*p zLnX9$XHqzfgQzr%Ez82Ldw;~TKe7HI3BlB*czC{sOf@*ynm;q2^`@j*tAd~J+(_1b znmWF>-rd2&GfXY1|AG`aFYoe*<#IHNBsAZ&!h$xWFe#JK&*&@LFKE(eDg?CTP{70X zD}!K=LY$RIwI^C{ewcxjGhMk|WeKEc!K_f$IIV5Jd6g-G5{&hd`Vvn5S{CHLX+~!y zuVgQc?mE_*iiuphVgQf5-uRq=A*SeQ-Truv1ZKjyGO1Q%-kF&~URbns2All{zkjy; zaBC6_ADCCG4$K)%R21TDmo@qk9xrh`zJ&OQ%7I_sm)YfDN{XA9;DG_?Q=VHYZd^>7 z>HKXEJ#r7THrowox(LG`oUP$(kxjPbvsuJt)usSl55|%+M9DGGLqocF;b{m>t9Y*r zW8>a1CfPyM<7SJ6{-M?=1vsi`*ddaY_~o%5W3>S~;LFX1E6>OCE5T5IhpH}|-+9rF zRR1WVh1VF9@|z^$d1vssrkW1pST?QBMn<8>_WOU3GRwpEiw=`9Nx|r$lfAbeG&1PIG-eJz#M74 zgoIwegj@bwi*xPgxTUTEuo%elZ>zn@m#-UH#@d8h(nZuiOY86|UWhX0n0Uo4M2>cQ ziQwn*sT+UVq`2v45qAmy-^!?-{)dQQPzgZ8hmtB8>g(5S*e*gVe~4<$#2l(b0qx|; zpLov|V7ikyWs{aYZl;LEYiUp|-CsVtpn`M~o~eTB26_0CuVIwtV*rXd=W>-8lp7N( z<{1A}^Y=r*=Ef6ov$V8VfQR#?c(dZAC)4#0j957Pf-vix%8w|o(a#y2@X%=a>nJq2 zf7~A;@F7&GVU-RzVbWTWOxmRE4o)?i;)U;=_1o;1)4^qvMRno^enXO&XlsrBj!=ME zni)A+@4c~?&(oXczqZ-Q!k;^CbvcEOr0zm8vicDI$zHjNcU2&Q~Z0N zSnc5%h6sd7+p!cP)Zr@V&x3=nPOZIzj-^G#-OESI5SH|CI8W?w>}a*=sQ4&3VAm^P z-)nzdsuvD_!^)1xBy)Sq6n5u#pJKD3C_4~Uq_>atE(#oMMx{0E)vlZ{GE54JD%1VToLNAS@UF?%Rr_gU&4Q055xt6&(tGs;DloZn;-j?39GgNDcksGj30dtD~@(P%pY%vJ=X!a zNGAk>u`t+Z)f4Q{viv zDa*a%*P})yFh%s2nz{5mmOLaYHdh@^#;Ae&L={$BYLui-*KdH2v7aW+f>lD=CO#`U zj)MUA>lF-R zdOow|E7J{^TOJ~bgK?O@?T+TQHf&I32N19I+o?QQ9P9=VbMCH{Y!gksyBYURW=ZEh zS!&o}$E)(*CbuVi!D@8YSEYpac!tBGwfaFnV82!QNg>&iqJ^&K=$PS?y-cf%eeNF=&g;fbFMMlgXEP*r&iiZfHX!h8$JW$ zBqiu?Z}*IGC>(;s6qF@|SoZStWYHG{j1eB|ZhvZZTy7`*PRP(oR8hT$R-#;a&m-J$P^8&|M>Sq?uG+kV zqZ+wD7A!k^1!#`#%oOmUeShx}Hy7T{n*C5eBU$(*QYGQ8ombvIyw(JY7J?(7?hp!318bJKh4<9$}~Hg-97 zM|($m?fcz>?Q{Ef*C$fny_=}5_($JqEUt?~Y%~0~@}EAIA$r^zajX=od(VI#UA0hc zpR&lHx&W5O8l3T^jNre$%QLahbKT;HtlT~{uugH?Uva%R2zA$6C~Fy_I8W!6tcTu}PPut&z-idVo1IB8B`1M;FQqiw z9@%Vd90X!v19|#{Ok`?_!e6)*MdT8gqJm_C6DgtVd3lfi4Amec)e!wdjvOcM136~G zr3p|nfq6FQ{A~+r2{iR9thzcM!NG2|?AMkc(kX%t8p1GJMMJW{ee}L`m5=@XzT=!Lg(I)X&+WN&T;I zX(1@l?vrQ$y^_SzvMD!tm***DO41_gcW`R-L~5xMpHl_ZbZ!K@NirDcV41<& z49N_fqp-qqm*ikyHD=t7l>y3u9kb=eH{*nK`F zl;6FY#oqy=eFp?-xL~ zDIZHkK)BfV5nnAFXNvc!s1Bj#S=+Lk3cnJ=K5+$;EitM9(d>-vLUB>i>VzLQQFLg@ zf!uL6rD|R$gI~v*UvMaiOG(>dY>eV^ zq5)b^3GBW3Ir@KFMWWqDA1yoA*aj>dtbCv=@ef2!>J0)?tH{a48vJbvImR+A-fnUr&CH96lNG@ z2$MB+%f0P|fL|#33Yu>Qc?mFhs|iW)-2KKdiGzl`exmCcOR}_P_uA^3Ms5f!nXyx* z>AesYVr#*DJd1iN7zO!Ty7XOe?Nk{2zqBu4TLKE5*l$}ST~qtK%E*~z=BRb@&=^-? ze*V`${rTD$kgj&0N&*?@g&&LOZdr1|&}u;cLysWv*Q+oE5|CdChg+DNKPTO}gdib> z9PTpZH`-$aQI`bpdJm}4E2|$B%fV^nOE>iHCte*;Fc5l!xg$LC-I=RKUtA)H9V1Kz zYzz&Vp^-X<2DWytKQbOhruXmga=`!+m9)XLv^4j-v(RK7rxs}NXTp2TV_anHBKOv9 zAq>1=kvia;N4`+oYH^Uc3$^a!iymrsK62HtH;LJ&O~dj_L|Ra)>2oy zuR!i{h)Ov(|4#8P(C~LL0$irA#2&3T{p}5>93x%u{cBla&IH@S22!mFtjf`Wt6S0< zJ41SSu(|m%@VTmKBlWUQT9fbL6Y_Vzt@W+Jxg>pkouw69hg2fPh)C9#hRv_c_3#~& z&esAyWfm=sEN^r~HEj4GfovqH-Pb%WYxbM{3u!4hmmKo*z}*2|t%#@f95eI;w+YEY zPW-c%)}cd*Po<5%N#t|gJB1fYa9<$Y&ayEQZy}=GQ8ECfMUb8 z4?%#(8G$`#~%f-YRw5Sq`XrKWica0MdMiy%b$tFGJDlI@OFV{Y1LIPJ-jFYrG$ zG^JBK%_eb_v2%Ao39!~uE6UV0p9?z$eJ^}F!GUf`IouwY)Yo!*dyVH5$tCQij-C2B zO?$JmDJ73n!x0D;CKC2-%`|0Ji;svQdmFKvb&ISlqyAf`i?iV%wU;nbt?$Vlky8rd zcmoQRbLqTbHDlijNsA1r@RYow3_}O1pF^YUC;>vV9*O!iBY+7_o^q^HoHeR>nC9p_ zMEzP@w7uVeOT(%277Mp|>xe|4N1HWh(!w5wEpXqHS}p=DTZ6AMOXVaJa7(_1!wtMx zLDB&Chl<88`E!nMeE%gk?QU5dZcV=RcJ&c&g$p8m*~Hoa^hKCT3&d^_1}g?clpz*3 z!ull2aWq&z?oRtvO{~-qVNr9^!*7y{LY)TEX(oVGScy|oh6sROJ{NyGlbc8mp~8Yg zb&1!kM6<|<7NKCK_qg^Xo-j-3g1ca{q2_E`VyMlCbFBK2^EC#qp9|DfcGmQ&=>w8i16bK^&cO$XQQ%8cqp zbSXrDwOQVP7Bc8_o~Q)$%uA?u9)5IdzIr9s#sx7~jmqE&qR0KfNMWZeQ>wpkUFQ z6dW3;t4t&umVYu1zoj4PJGv?0TD>UfOvhPA8Pp-c}CwHvX$S`e|{HuXt3Z zn0WnHN}oy9)8hgb4SS0>n|AjV|Ly7=L5*tBi_fIXJcaz)E z>YmS_=lFAvV=z!1*Fh@HxUye)Frsrb^`xvBnD@@6meV*|KaT(SpE@+@ffp|^lEn;4#qv$HXnlnP2Fm}f?#~L+zO^HjTBvFQ{Ryde z(KID2JMfIgNv6p<-+K9-Jv)iY1gW7k-+#(ccA(4P7tRIVfZ;AuK+04r-NOq`5@ zZ~ZB9=`x##S^V2e=?_1~fWF^vwEw%&+jjLkx-Bv`o?$LQ zzkS!^&(Dd2vF;HlIfp12dhSryxG^#Bt?(TNlCbx+ZtYDqd)CEky+Zb2MRVLb6FLhv z&Yl!|%O~?3)m7mzha%V`p-qdpkr7dB53F ziQ*kN_ypWyzYQRWz5&vL`1(7@Hl+Mqxv0Z}fg!zU(xTqa&HmWv>uiV7--5?JyU`4@ zB}0P-VU?wKH^*@PR$X{L z^aeM(XIq#_{@;?wu4-J9o+_0skW_g_fA)%lvT?C9z1P`fsh$I(T7Fr;!(lL3M+S2S z8*}v}qiH8dV1=X3?1$K|aKT^!>WQ#dEghJ5|+Pwn)-l9ErW^s;~UG7P~Is70V!^9l(Wi~2c(=Th*vuT{M z)2(LH^XXCWtw=FzRbiW_duP>Mq$L^GAINv>l_!GKpH%B2>CiMTI7B+aw~%9Gu4R`Q z4OF6iuGF~EUmX3K_A@+VTn9Uj$2>p(A-~Mm^~L?O$GO<>5Zw|7&628$=5N*sU(Zoc z6(-+%<#jkczLb4aYi{WKj&Q%RHMun8$tXc5Zf#2MhKjYN(%}whqoNmHY zLj%2LzN>u6Hpnr%mwx3W<>QrS^9?%?9P8mRy}U5aWB20b8fEfK7t^EA7w2_)?KU)z zD~F+t3)eocM0^T{Mb9HO=>-==E>WVR1+_}vtKRI`{rBzgNU~wLDAUL%yQ+TIDd9X~ zY>u80!=3VzfnncuG~y;aIJXDkFhT=oKmka?kGiGFW1mj;!e-}4A()0f)BMH zrv19}t!;`4k7gENLQDF*r_7Lvuz`zr2dE%P@%d5n(!ju$?KSd6{Bt&xx=~zQgEThXqE`_(t-+|)NZ?iEogmdSa3KnJ60dNzwx_Y4v@D0r= zws4k$XwXaTzJro0L%?ygY0-V7q^^6?#SsHk1mTZQjl8@()pS9-%J6b^Iqf8bLP4}$ zyXh>O{NQe^UE*SGVa*TeoO=d0-%_7dm#HAc)~T#vXc~CNd$k9P)G2>q zB86UCSH%EY#Cop_%gNCekb+R-WV+C4Nmxgp)Yp9Ya%y^gPYZgx_|yEfL8vaJl-+j_lD_^z?T_BM@ozo83ax-Qk9m{-H5(s)f1jOIGtin1 z-CJ4&(HHDvoboFAD+}f5GUUKhCAn9!zPMl?QC+*N0m^`Xlf{iQfq}X#N@UR32~ce< zovhe$_iXs@zN)yBvA{o_qjkll@^z@4j8hh&nSQ2*i}$2>V3~pU!*Q0=1su39w&6v3 zufNova?0`j15M6Kyja>afUOBRhy4Z;u1oDJFR^f?yoK$Y!`bfRu?2?b(?wDB#?DFr zT)8>)ev$+o6ERVB_c&@B2KQDAP1NGv)yreLteqvr^HfkIB#bolVnq}Ux5_Jo zgkYr99UQFCEXIZ|3)x%7hpI!NEl#}V+Nz0jyp8t~eI>OM&h_h-#(=e#mts%YhCH=TB{ij6Mc~5~TaU2|JZeT%fT)Tie{|rp^ZWBsk7`TN zSH*3K-7_?dv%xQHIodWH1F&HgPfi>hJ`x`q6@)eHz+hs#mh$|Ox2smic~=DLj}AGy z#DM4DIspe8O$?sgC&>^=eR*T@VEf8nKxMD^F@ra0yyvZmZ7WUmYh3XU z({u-e3&g6cKW1C&J(}(n@ZXQ9Ou}gb)9~{IVL%m*&fzAqq2I$lA^kQdWai4<&Kfut zz62l6i)2xz2w@GW=;nu2U3^!wzLd(-G(@%)ETOhVvo~xyZe0@?Z;V9B2#8%TvMnpT zp^hefRn>x+7+`ZlgQi)2c41VMbK#H!G1VjcDRiF=-wW{F;&q|(CzyDtfmEwQ==c}O7V1xU`psc3+UlR0EA#D@--akP!(`6b{cFZJd@#D zAtTj4;Lw}v(~HZSk92KKX2~b?E^6i&Qa;IruxghbNef&;$j9wVxcYK3+ zF_?g*uzpDG_fEUhe4L2Pn4q&??DO`TS#T+p>+F6epT^JsBVqZj`V2x9f=tCamYCWT zvp`m%`?)>Y>rxM$mhvvFP(;wMH=zqsxeF>Fo<#tw41@9bjpw!3hGA#bWK+$d(<++@ z)rMRbWl%I@;moL9m!VoDt{I_9ON@Hyrp_8XVQ6?>iKhBD1C@oanp?3hJ_=1IbgWTG|?ES^Xi| zg?C-N6T4KIfz=<48?77)+=3<0*?Ex*LIAw*^j;}AMejgDHGsClPCh1)EErQ849M0L zOsR7wwX&)%;jj^M|s&?h&d8u)ya-_!nNehBR@pq@w)1C#P5(7xRjeO{$zP zYsy-PYHOSGWr=VB8HIObNqrt+2JA2wxDxr&}ybs1m~K6MjUNS{wV^w6TjUJR#8Xw$!b%Vtq61de=y-=P+k2Adp zxP>NG&|kq|a9rc_-O`oKnfdD$_0lzsX?Q^7gV~s=nZ-*0V>M{&=IYwcI}eS>WpZLW zKg(8)+=G#Ummb<$i5f<>BQFI0eO3uWD*-+nX^Ol43Jrh%#Bx-{CDs-mpMfbY&G;Hx zeGxo4WUqw`Epg(ht7{F|cRup0dF%_L<#9{|%x{Iq2lVNjU=#>ZDKw(i??EUtj^z6H z%fvY~E#;7Fh1X=Je#cu+S1VR>?Y>D?-jg8QS$#gDDPS_q1l17#wF>zEU2fkP^l6vL zfg=Fv_7BSM^t8az`znC$pJo%g2m+i8vjhWAU^%s@i%Ni6oF=`a)j#gD(@^X2-dBI1 zBk&XqHt(2h{R#|5rdEi-VQBL6iV=~en}#2#^o@&mGu>E}v3%@>{j~4%y%yt*ZkOR1 zZ+Y3)=bo*YE>PF$v);kzPk=#}kBzgLQ)9p$5;0rfG2`ki$?Ha^^c$L?Nv%V!=Z|qc zE0@qh9us3Lje(dz?YrsUIjT3|uo3O_NstySPrmP25NYSz)^8QnNdu zkDdMLvW?6<+nr{REyzE&j-444iYBqrzDhxZ!kA}&joCHup1(WAyjV|!( zc9BDwgaI@rrt~vK%DLXPSk%Yp{?p?xcUC7H&e>4zZt%n4C>ShGExj(%TC{qK0;%}m zZuXRTr~F%(3Q2CEUlF2&8k z6i8!T_0_%4qgIlNjkoESx~A@;@XmlxzoC9E^gSqe*Fb<7{r&MBXxvv(C{80!Sy8Cg z0{nIn~{EJ6DTNu(RYOCBfj1kCWn{+svsT9qHCwR*zg>=2rXdE3K$_43~Gm zz1nF-8X9T+kZ$r*Wfen^C*;Cdo5?6{r7thq>CcDT|BUG<9>*dFbBkVqsj2UV%}m($ z#+Ee=ZaR$-f?GcX1$91J4!RAZRdsZFZ_5b*LM<=#f848BEWl}>u3c)PL z3O+-Zba$maX$Spxim9zyWS>#LUsTyx#Mdm-zWKY%PO#INe^R#Ib!NLk4))$_!rM;v zok5r4zlGasdLo0{J~GWNGRb1LZsh1wxSsXS!^W+bYy4c=34Nnih`d%%aKGfn)1yDM z=k)>ZzVoXMH}QWcF_jY{g*Bj24DV8{w)cE}mFb^S3t`RCic#ZMnbSBQhB91VgZ9vz zo$v`1q$IkzRwT#`$UomNED)`>Z2G&~JL$jg1iq2-uPEZxL8(GV)yEq?;=D>A_RUS_ zhMEAEdxrV@JCPPmK3ROPFu_PQSozSPEiu)G?8AtPjNIPYhPvGdGC6uBT^0D<@PYcJ zC?|Q2QyrBhX}mwxZLWx~&LXuV1?qP{8SnSBhS(Tc0~j)QvtYMK*2Jh&57i*aMH^d6 zL$R5;80optkK2qD-BSPW-F)4LRJ|qvGnfK$-kM?xWDRbw$y|uArkIU!67YbbS(Vdp zB{YrK{@q@CpZ2U7ziIl6fV)&JdS~h0xI5FQwMV^jvkmW-*?YBhmTKR;PUx`(+mJ%d zk8>1Nqutdnd-E{`0&g0|$J>2QBcM_O9#B_c4z@o=D6DJuF%++`ZO+~CDh`V#{~Kw`d&n_u`}yq-q3VZwU_pgV zB9R14M85jCao?fABZki*R#GR1Tm6fO3SeiH=TTKx6=h%TF(1tRZ*kgMD)p?lbAY@j zjudFc=47xN`YZe@jS~hvCtqafeUUvM>D=V%yX4s~VDGSZ@Dj8x8?hwa1`CEAk^pXI z_3y?}th}c$E0BM?^H%m*Q2##*K)eXHFB}UrnXvhTP;QfXV5}0Fazne~?m*A{2GHjs zXv>W=`V0jDQ30J&ZMY1(lGeFhNnH#^m=qX`Hna z-^hQm?N!{3;-1k(5cWyNIVvy@vv$CC<5ISuX3Va;Fxk=+3tcy58)X~F=81`kl`*g4 zoCjE%=v^GCKLlDs1?>H{gOO{C$_kKoJuOmGF0irGy*OcL&|^37#30L_uOJI35gn7f z@l)h^@5K<{${_EITvo(}cbsH}apBE|=0M)o>i@<(M=Hjy_FK!In&?vHBoqvpjlDv1I@=GDZ_s9!Hz^XrWH=6)75Vgn-_aivG7i@FFu(j9W5t@lJ4g2p zjph*3j44{OE!%xuZ?f%GTB=4?XGkqwV%Bz9{lG)Id3T_q_J6dx$C6(*2q$?3b&X#z z@JdjwI@+UgrMyi0>hV{BC_xRu@|lAM#lzXch9EyNE};LcQ`nlokDIVJNPbcRI5f24 zKDxXKagUmM)Ox)GeAd4_yv=HbR|2YM(d4-&HihHCbNtOSYa(}JOGT6OJn3ivI>iLZ zOeEmcuZS?T^b#lxWXxF`Zib28X>f~i%NmUB&?%Kvff;C2e>y8c(ft^yg#W#b45}Rb zRl0l}{#7&typ&*}W5@cF9Bm%s?20$%b#`)5Xaf*oIOb3hE_7Szu*0ZS_t&Wp8z!F= zvnjk#k0#fni*M`jBylw^{7P{sTb13~owr~=v48XF@-7Ht8xz0!K@#yA(w zGeIwY%}A5tVHnEyITpe_*q>AaDR$zWHZ3wcXg)?<_^aRCM8fCU>FJhQ-R(WYaZ#RA zouB`YrgINu`v3m;NSRXRQsz?3UCAxxn#*!sxrf|~7JobjM&qE z(`zx>1%u6g7n!6st8I7TI}$8wh0`N9THY)|OE{QxJh2ilpfya%_|(}`CEqo=R)~^b zp%D>^E;6HHg;>M(l40t@dJVn|qK1C1!oYnjw!UNWWO=-6<~#D?7Y^-+lf^}U506HT z32w_~r)y#~MDV1uvxy2F$hk$pT@cBaww}H(t1NJy@X0TeIg5cwKz)T6z#u^C0giKR zXZIf{>neJirXCq#-c~PRLjH z;o!J1py^OY8Ajb8#95vdp2e}j+5q5DKsO9ST8QW3$M=I#;+$j+2q^iZMqSgD3#=47 zpX-QB&f}vJL$7Qe{Rh}3Tp+a%3dVr5nyrvaVp(9_8X1shgWUrxh-Iv7vYBbQ&8tAx zY)f-+AZG3N=JNdfcf#BM9PrQ!Gx;SM>K zm1$d-dS8f1V<0eo*Ll31N6TkE8p>%L@=?YZtBg&ptd&}zw6^&|-3ZQd#AHCZrGr7N z+u2Cf)ZZmP8m(Os0U3+%l~VWyet0)9g93?7iWF6!%b?5vA_STJHz#&ChoQCqFKi}i zi=lncx3IUf?X7<0ykt(64e*sbVbcK|xl>BRtflJg51Ihg+)5PGOoGSF!wDOsah`f1 z84K6QamxBL&?eV;7@=O!g7l*_h0SuPDF8)dcck&@p5EYT&u<>=*KN*8kN)y!ft6vR zcK2vigMmuRPoQcgEZk$E#@RMw#7H@Jdlh9GSG*@oCo<+`k|vTGt)CO zT>+l>gUzZsuI??(nY+ru-;;hwpJs|UKI{X!|M_j*V6E6g7B^MCHPx#4miUc{$JDzQ z#eYQ3@Wn>ad@*mml*L(KKSHJ-HN_lGm#hih^nN}-Dmo{uvskSWeZ-~9`hsMd-X7KO50Ojw1h_l4Es?zjsQbIASS@+eGxAT6>yW4ldFN- z3zXE%Gc(Uu_rFk-kbe!Ct!W;73Q{<$VEL(R+=?B1>ns0l@L+bM3ohGoG{nK~4twm2 zXOfD~jk%b?ocwP2ZP!yY6MqB)N^Mp%Fq^Olwya8=JBr}!<0dbGXJgM&&V^tUl!<%L zrqBb{c6Tyi%OUxiuF+F5p}(Y*|CEvG6`KvXl-Py%2e{c(X+2 zOq@b!H%DTRHDFA75YPDuHJvz{wi4Q};a+t3I`CIxLjS(W)AmNievV@lC!Lq zZ^eNE$yMG7U?uw--5p^L_WV=nx-IP7ka_?P0rF;;imxDlNtC~VPdsNFlPEi9 zFG$HcBqr3})(7fV^k{1WxVO4Gh5_p&(*%OdP}kmW`$SY|Oh7gYvJ)X*@_{Wn|FR9ebw_|%o$YZ0&7;3O_&a;Bv~ zkDAYG+6|8TWyRViim*zt~;X zXHhVC)!5n5Mg$_WZM8kn8?x~Y`ojs}BnZ9%za@4N*ig9~{{w9XHg4e2ecM=y2X+w= zn31+hH+JFpU*uPG-1{?n-=r5xc=3CXk_@CYP1EhCh8Z}XQw>0Kcx5Xh6BzLUf^)#* z4`BE9yY^DM_Ny4$`~O@H%TG4fXBX$k=vxi88X8B1g%)-=g94!btRAQ9rIbyYBXyIJ z^yU@7a_RL(IU>4H4I!7}BG)?u&UF<)pDn$~yU_+3FG6x-!Eu2h3*RGX z_zW%2n!HqW-HZTx68K}Y7c7q43f0Ya4_lqSwomBu4nYSrwP-K_au&MMb!N~ot0{2H zH1iXjeh06*j-&T&0Zl96A?}j4H-DX+9eu`LLt$}|Nrq-cozV0!dfD+{UF^=`UIWdn z*clH*n((1cVan~Fa2E+opTsch%L`VCqECkn&BsvVR}Iuk?^M)QUL`L1d+5odmh-LZ z2V)D9OUsmNi8Gx^egNMBT`Wj)gQXf*K*#RFP$797#7yi5xzm4V${mYHia_vLJ~$Is$d4dx#>6E*4ogpH8m5ne2ZO{ zWla}6Rnjob4}!oR;y4j(Fj(S>X#@$bJgH=|61Av)vskWr1bYtq48m513rt~S680{Y zkDpS$Ap+(;T%PZ>9~Zg+4+)Au1J7jVy{|1GVGM-$eGlUH5qu5R)J*O#L)lghcyiym zTNy;<^8uGn@?(MjMZix!f@4iINZ}(e2NKQ_F&1MHWB#ai`(c~Ll``qk$wreT&dJAD z*EDIy*_XEZmdEG~&^Q}_tJzke5jE#Ok3A2&=Qi2KM(qd3Gpwf`!v!#zcXH}ys_2tX zXYm;j*OVNY*VsQ^iu@PWsIBc`{y&6P4}oQ+#nowGNqPLFzi+|)s#UkD`&a(UFk$G< zzIY#t?mgUT#Al5euN4AoH|wk@)^^+$AGCH#4|SI%vy#2&28#GK4^{aZ5g`}w2)4F zi$%P2ggA>-mTPP*gZL}!M%m@ zdh@zY14OXG;Y=>LgUs_W@SL6mx%G`yTkTWueT4ic2htatQ3v+l9ZzQ* zYV;90=3sTDe5hE>kFQ+O9rNaxd_T-@gfb`>yH^$aZ(>NJWVy^VmFHue0?rZ}nn<0J zF?rKK&7auW+4&0`+!}xpw>37l)v+0M4anC&Iw0wS)#wQ=mi{cScVbA)zEct=4LcDl zQJ+bcJ|+som8DRxIiQ12oOpcZRx+oJ$sl0m(v4p(n`mQ&AjnV_H})rxYFyEE3XbiQ zlsL<+On2j{y8x@SXD1jb1vk*}d%pY@f;&qqQU3FLbD-_N8~l-LO>k;^4ddLNY;^Q3pTj18yN`t&EQQcD10xUhEq%Hjh<*_{!2D=A_ zUpWt+3vagqUd-A`R|j;pzche<0kk;!=(tA7Mn>#me^Qd+$(Q1zJ?(=pX2*NQM@xp< z`}06pURygd+QwQrC6k-^0bURrojm!WaCn|dXjh1zCQL){aQmuD%o&`S2)KzM0Hy$@ zDSF+fX^-rn z!?T;ee>!k?#2zj8t;`8vIaz>@u-O^)XVfQAUhmtfaQbSr2o$riyD_Z7Ayk`pu0&Z} zjF|Z-+Z;YI)q{ch)XI?+{)7Gl4NvSfQO+>;LV59A22dFeHXP zErcZ|MIN*p=Y~#-V&p%O^Y!AU`VU^*2X@?4{{e?7`ruzUp~9i`6xPcg02#VjESjM||fxCwYp&jYKwa z#hjjv#oxaV_o{4DLzG=)6uJ$3uofWy_x2L#EDz~;FzDanMowQ;NK8yXNOWQ8%USlg zAHmaKz8L3vKwv&Nj&vh8d+{+t>(D%8#s6NofGvH; zUzG}^$I%Yw}-e3aMmnD=&_ICXe1;DLMHkbS%oPc-xZ92k6GXt#M#x zou+u~&Wf&g-yq^vU(90Jh#xWq-9D+&EZY`O^HL*OVAQL+3KzOtP-*hWkvnI*#pxWk z-M`M9{PjQ=NGP>eWlEgxGQj^eM~>m*H?w6;g_l_FE!93Mq`fpZkc*@xvdLFh zobKQ6^{_Qj_Gj5d2E3E+vnybvUOb+X7;0#%;7vtaWo!DqpfTmQz|RfOTiDka@k3emyU@{n?%FJ?q>bpVJSlRLF24kqG>)(9F@gnh9x51gDhXAX&L0@10 zDsSSREe7fymy`tQVdN1;;3a@I&vgd`GX8`e(dw;NF-JZ}TWk;1(nG_-8Z>8+yd-D8 z+eiLHd89%ddrleZg%S1~XS^nhiN`=FZG&wTsT4?$cav$ucUEmGpWLH!1{I3ltv@zn#bLc_yZ}y*vlpv~E-LjRwn}ZfY89p@ zihAH%imU*!&xn#i*cRn{>CXSYvvnusCwrqaQTb(oVVZ&6M@c8Nwa4SW%lzEx#X}_w z;og`o4{U2&$NUR%V}88Z=-U;3#D8~!U<=+&vv}Y+B3hR96c%=TcJ7GS08m;#S>;Bz zXV*PFl)7utN4>wt zgMPxqPUYemy&GuSUS>Kv?;l$?S^f4Q)&j}r{&%NpylMjH`W3^T`BSxRh3zfij-@0F zX&V2WOeUxa=DJf_PP1GPyG*5pYLj-c&dfenxSEV_)RlQCvF2ZwRcZqHT_v-$h z_H+8*MMflUJ%K~(!^!Lu<+Bfd&>5Xa`=r7L6Kkaj&Jn@?wTz|qFLoUPj=}ygc_P7C zZ82}mTaBP~ve?7OO|6ET z#uwC<;2r2-%#qUV7oG*pOZJ~UJ=i~fOS<=#zyTag8zpPw^fOkW(KkJC7xr&uNdODD z5QF5|>o4Px()f@Nrzg6h<&oy2 zL1<}-T|0JQ%tX*;iQP3CEny6XJPh!X3`~;$UjBO{_iNrY)Es@>1M+4~NLyW7TP`xe zp=GTz;3SRJuWO>x+nYbafLh%>6Ev zA6(coJzAfnOt^?@1`yF?g`Z_Ag6>8*M=oCDp!MI)zECH2Ejla+3x=u}kM6Gjz=rwR}f}L+JK=|>ya@iIoz`0H7 z0SU+9Ebo9nu19FO;koa;;jjd+9hOyAmJz{RP;O}j3GiH7>hFku*gI-)f3P{HrwY z$ug98jWSKfWJJjXr|{yN*dXAVG?#ucYH*EkuNKeI^UEA*EQ}D|9l*%7X<|1MC*amt`WHiftg*hgco<5BCu%W8Tk%O~of> zrd?!hx(%l*oL};`;<2nR{@Z!f(9$)t#vvzL4pi#LNx;@X^J7(0K zmtv5OyTL>yYZ70B{R0+-Gq8ID_j2=+g+G~3UB#fS3+NM-<3beF5y|B!J`hmoE?;5_ zTuVD(`UP>_zJQ2R7>Lx*F0~y8yeIhqn$)Ro`TIOg7KSQ*Uu0;GRL!=XQ}CqkeK=#fAjQzV|U3wy%g}Js;%hninQB6H$+6W*s12yZBwtBcHc0isExlBH*DU%gabhHF3r|BP@Zw%hn9r<9(Sy*LmV8yeAqb7tK#LDv#{K) zi9vy+?gJUpnV#-SdrpHI4)AN0)oDUV5by>+F+{F+ul`%z$hxsZw>6u56vQAC+Pvj^ z4W{PircxKqGJjOacXGP9ckD1$D_Qc|0%cXVCODG_QB09eOYIv2%sYXd&R@%kaL{a< zFPkpjoCijP-dK)aRKFbUPt1=E^gT*qR`u_ ztP1vS!o9%I=}vArQo2N$B`$O26$hBi$%)u(SY6Qa9k|^Q6_5Z<$WDt%Ce< z8}8O}aDo4BD(S^R_;+t~^SQG>c#PfX?g!op$^LVXK_4SXr{{2&?DCW6{~kKhO_A`4 z=_&0W1#(wSE9PC*9pq)-Fcb`Ynka=^5}&>`Uf1*gM!$aPhUS$&5QOx@b*h8phwz=v zi={HgRtqLmAx9!T;9?g?cqKi42lCMJLhA2?79ng{VsY$o-+d3y!snL0`O6axl5;U; zA#FYyrNN`hxJ)R>fQMOl1b4f&_Ugdt(x0Bd^@?#o-k&W|Aq!*(|H0-G>a8yKzN;(% z37dsiwShiq1Gf#qRg+ytsL;(AN1Qlf{qOwSnyQ7UN&-Wk%RrP_#g~fSIzDCU-)?uE zW(6JIn-G5>#mvE(kKJANMx#S&)0UUv`(UQeqdYpjAGT$yb4fc9V?w*|F>k-v;(*sR zH@g7aZ!Y=eg6o4qN~N;>IU?NJ>e|Wb|8S2zLNxTtOXygSf4nD~E`oxq78p03oCJac z!*@mKGL;arw#Uc-Clb%lN;q`*QY(JkResRu>rDi^1-HKNKtHN^3VCbnihaf@=Jn|` zheEKE03r@#iP)+J!{VSCW8#*+ZjXWGF93dzZm+mD05$lxzCIffF)f!un07+4VP1c> zM7&RZ5)=uIo~XVS-$L<&Ki?wr zopS4i0>~EOk(zq4TMAR$Gam38Xgto9#O3IBRY-*8zgoa>&BjDQ3e4fhpxi#!V$X zAh6rq&+hJH5^bo=))t+A(GDU12dB>J7^ffmAK~bnG*Ib41w}EOxnjnIic;JF6mlva zqNgMO2YZ{Cz|qa>acf-{$;8=lGCLSDtt#Y}OvzW7=@?fY^!Ld8v-DVNYHI2!*cV;^ z`31=8)0*pCy4pHE9PSqQ0fo84{6eb7&{X9U&HxD$mhsU&vZ)X{7QNqA<=|Gh17hY8 z)x*}Qj4jb^QC21%wv|4GA;2w~5azzQ;qm`j001A#cXCT7Kl?6H_TDJ`C?+<{Z*6h$ z-z;(X__#ZQ(E8!Sx|V5q>RyzxOSMMn={$u`{boSN+o>4u6t&Seo@cw&=NgT^c~hhP z$6f2(=ZLqwyted^=VE(6cf|F5TSr^W@$ZE#UO56s_oZw7_EG6~uWEVBz(t5a8mW?#7Pz3{8MY zV9~Uv5KwP3$_*>52m08&OuzM`6OHj7g_8zT&ROuN@oEwQ_>V@36WBp*+fz}k*z`K~ z3gTsXLgDM>HiW$N(=F#~rD^e?L6yo1=T^id#E55~Op`GAFbsyfj5Q2NAJ6=Z`U*oB#~kU6X(TyW)U?zuT9 z_ReBnun0=Vg!}6|_@q?R=vvnaH8PeFc5+2{kuam4GNLrNby8fWa?qr7d##ZgmNwG? zh!&m&xqeN?H`Lb?t1D2gC}qSq)T?RXhcf42-RH-z+yB1MdpHTzAW4-B|PO$kYYbhUp82B?O@NvV9OOEh=5g z!_4e2{UNi`3Z^p^Y#~_a*may%7rUY{vrkE*_j~0dVWO}aW%}U$M1x1{MqaEtVT~gZ zt6=c%p=S7ylq60p;HR>3sSF4Sdn1MDH6pTniD&|LDe}cPzBJ9r3}Ka#Ri+iHCIw{+ zI6I$ll67`3F5n@?d;ofmJZ2&w$tG;?p-MBxH=3j!d}y#S85Og;T8e!GX8!Akj{H*r zAa~7`m3iYi#lTwsly0->5~V;&CbuE#rBHEVeu$lNVM>W=x~m_mNZiEEgeZ!ThP+WX z0i*IMo;^~d1~D>(bue(^$(jN#JQ(x%2H~#g_jXwW{lwBPOWn9xs8qJ^RXQvUv$h!JZ@X z(H;{Vi?lV)lbcMYamp<57*w3BadKSgq6m<7@9v@6Ton(a*q3lV5jO1? z1)6x@?PyLAM+ErFp-Sh`V7KRCB!Fp5N@4}djfpA0So)Vd7iW#mM}W+wO^}_H+PV|b z?z|@Q(t8EEpyK;;ot#0;(H!auUpH^Len#wWve++0bwLiiO>s=r$?wC>Uvq%#?6@xa zgtcqe>^R|MeUUiW9=0ayaf4lpG_v98S(xJ(T38Y4V49_fkV^giS*>NN=E4QQ-9|qQ zwe7Prv6TiAQv|4^jpJ!?cL>_1g9sZu?C>!lbt*Yww2geaVfEE$L zI0e~L5JUxsQKo}ij!fiI>A3L6C@uO${rv6bG;j5w05wspsJjU;S--{h-Ma7TosmYA z{SV0jwg>pg^#jr6HC(|gY z!>p$|P&XX9B{mR3_LO}GhqKIL=j}H3ed-EbzCr{&9yd%N`2ezbSw)W6%fUyf3t#U= z2l@vGhOhkn{r68{!FFk+3UAezR)WJA&}-K3iVX;vXf$!=!44~>w@htLY|*AFamJ4e zr+u3x$4ylq(0F+bUiP_4yX%3U%_S@F1H9tQP1V~C&a$o(!G-U;?}(Br&LK)^Pl<3@`5WmG*qILoocGx z`FC;hSFqv-^pUFBZ!@j^_35zV+RA1+DkP-o_DB)-pXbkv5~;zh72mmLREWI`%!0_>12*v)! zl?*;NYil{%sy5%>swvswO^(u~s4S10zr?zNvE=gW&rW(jK# zlvDdVnJdg?!1U~Wnbc;qex6l+sdNdu@JB73J6_Xpr}BCw36=&WDoO>NyANrk*xKG; zpT%Cx`cBqD$JpnlHE3lAev{i&+A!cnUtoEzNNJZ!VF((L!`GRf$Pd&6AO^&Y@j<|r zzMy`?gf)*oUV-`kUEcmIAYtSK!kb11~!Y20YL;%g)2EanJx&A9*<wiL@@LE7g(eg$UQxBSG=m8S419R zErYLA_spCeooud7+d9WAGz_``ZPhKGLzw@vx7ydHfZp_S|{G@UJh|T+la2k?5|lCVS;E-}ZaX8k*1xNk`r9q#|H( z*f%mJyU!bU9?fy`dCYAx(PTu62CZMpZ?hn3YTP8W<=d5%C$YMm zP{L0B8pa;=&5aH|8V}9&9~NLw2y3&l_dS2{293vV${FEi!Bg%2XPM}Ley zk;7u{`Ls8m*8+3e`RqDnDUsf&!pZ6$39Q>!K+qBvX-j@U@NgQen66%f8@6k+O+-HI zg{CDdra((7-u74s$=?G4*o5IDrB-wlPf$7&a~wR;!c?jW2KrrgHDHF=6aD$A1!A%} zfax@ELQIhdAySSSdH7FS_jBrF0+k(L@_IGF5&oqbLWsK0F3}6h25d0ZE4y~(N^Xu` zK@l-U?tHKB3M>@f{{2HBNWQSlA}U7h1~hYPuy!C7sFEDkVmC*NkTOQh_0_9by7K4mgjcL8audimr1k3;(VHWp(C;Ud z+bh-8wOY}1c=i=Gv1htObIL{cyF|+|y}&;#hKQt`1iu)X5dLRp9_>`AhV)*j?Ndm# zLU#xd1GzE%+_HYh+kkJ>{xpaMYHDCyRIC-=Q2}p{c-|3qQsoleFkaC4PvmBFjO=M4 zL6amXXZqdb(Dvxf`H4dMxCo!d^lpkKu+ACM9l1to3nc1^Ab&SjF3XVGnosGhouUD` z#VXDUx+`Bz-fe_e5wE)HD7Fn_LkbDp7!7O&mKiq#F59rv$Fy_cp9~Z{l@x5|C z2@Ye*C5=8B#23oD-l57@(g+OlM9his_07RYv|H=lS2!~MY>_gw!sSQ}eZY}+mJ_Vw zWXtri^;_ul@bLSP&Z||^zND<}9Fcon)6b1_<%w@`I1AxL$7FXF(4;3!JZtg!dmvx9 zg>oVQg$p6iSul;rp%p97kHxkC*vQ<-wJ>XARi7!FYfkfMYgenyrD)FQ_$9H z*{W=XDPmy*jUgr=3TZ59jZoarrW-7~&DtZ-;vBxcxB-Y!!*>sZRiXam(DuPlh2jg5 z>~T5r?W)s{!@^u*p5A!vE&fzzn|vTNE)n73PXpuAd})@61^(MW-c@As+F=E5+o zS!c{M%ET;yyw}7E0Yx+u2W~MPg>VjXQ1|Y33FwJsC@`n2Yt}F7+T5%n3(z~> z%Z9fUAKU^VrC&FGPWAnPnZ=G$DnaR-?A=J+Ge<=`&JJcEy=tN1ZQB{!i2Z(E+ zd}}o03Z%Mne|s-Vt(ff#m~A{gS+Q=3`mSoazJI1=gePO!EPb^b2NYJ3zzla*aJm821o;N!YUl^4@;@==fWt zoD{cW<<#c#?`$r3A^U2_zvcOVf1;+cq!>hBpO)z0-6p@7s+!!f!1s<{)oU6lUioBN z&>G$n34}6!aNBWmGJ`Nj%`aFuo~Y6@A$mU_Qvw9}+^|h3hZd9osE~D?N!VNmFbPS$ zCckFDe#~MAvvH7MatW*O3$YE~1}0%lcAE^4H-ojR3Yrmuh?CIS{b5}R(b224o0jn) z$^>W@e-5Kcr-$a1?>Q6bX_6QWz(u8{r2;>t#Hp-vkMkelhLud_RH?o#mIj13;~`Gj zM21kzi1KvPm$%m(Brw>VVB6=$Kn&I*Z=r9i;Y;vU5jId==ce~)QwF(cXRr6x=h08^ zO#k5J)zwr-P#({a_22mf^c61!zPEp%BR$8;amBP;biK$54n*hrKJ)dl&>Us*s($$| zVu3!o{_yBPsa^f_$_t3%B_5D8n2Zh5gV3Gu54%st>wSKgw=l^!*2Hl|>u`H6gRT4c ze#bN_E6`y%iK7b~=DTfaS7YNe+Gl~I8T+(@;4Eb|q0fzTprG1fN86)#7JurLPMYYG z>^v8ApSq>;MTps(7Ya+&j~1zsCmv1S(2u`1hD!`H$g*T$#y#+}BcxqL@H#w*E`TgK zDAts^77`jtZM;~jBgG5>W7+nFjv8jp3>+_M9~DmjPJ!f?dD)Fktq|KGlE&E*%}SqN z%)XHc!({F~CiC3}&;!it*R-s_uyi+}C>=4JB6-rZs+LrbRro_7r9N($HZ9M&x2w{= zGqKmogD`s8s~{3u83fmi*#?9&iZ82e=?j6Jh8EcX#h~)e9s~svG;(L&AbX_mXQv;OVVLcknZ84+1m=+3^fZ zu-j!_VI#1ly)HtvH1NaW!HNy7vS`?!&j9QVep5g{un3$Mo{+TAh-K|Q) z1NuXGVz0%+CS78RCI>mU{jzYx+FRV~b3MQQLrqDgcQoKu8S2e4w-L$j`8lh~l!E|Kmn9GS zn6O4TTK17U{>|H^dXoS!t`Qx|b~tmEZqNRu9iOBCu~E&n$=d3xLXP#p#p<6;^;!4v#$zk&aKikg%o))7X4np2K>Lpr~6G#BBywR$Ca=O z;CJdbim#jb{%jtw~wx*WgX<7x2%8E#~;D@{rc9bW-W6diw#u;vwRr(l z0f`p|$lxe!%TSTFgIt~;VegU%6lF3FW05_LdJ$r?M7F=lU)bT#fXBIG7093`!r<^{{H6UO_r6lQ!(1%Yv%*}I`-NWrcZXejyLz41VYA~yU_g# zdw^?7$Q&Umk(avX|D!$Xczf;mPm-OWi$>d{j`x&RQUyib<1baG(eUu-<{g&!EqnSb z3?x-r&~~*RALNTY9d~m|B;~C_y5;Xvn4`<7nUMIcGn@<|KBo$)G2Q_fjZ2~h%k_&E2#0$MeB6P}(@5$_q#Qnc z9na-+$I2RtC|UsWSFv;okOB2Q+&l^c(wS#^eub-w$;yjiv-4IvJsX!MCpGHQn1FKf zCW{ZMiia0iVmD7Im~Qi$aLUaJ^f4%r}*R6d#mNgB68p-&Az}E zrc5@VvoN|6yY~S#>20fwq7x*+CBLN7=QQO$WMa(MoYsH+KJ4&O2l+J-;|fQfSOO&c zP?l4)A}gT|fn8QWN=R^Ya&(j#pV}f-nNHMo>`)3d7{@?3uxqIsqX>8STC8~#*yOwu zu@_3H4lStsnbw~(5fu{=LBwF^9%{byhqc$*lvyMD14g6^O3~SG`whqA-b^ zXKdc={;@P_Ro688BY5Rednx9ReqF5(v2|G8*b*t_CWDa|WQV$K?RB80lt^%TNIB2z zhe}XBAEx(S{A1D*_p)dQE5O#q)Sv;l)4pc8@{(g2(9gL}6GZ%2yDuuu^s3f@b{IkM z&2IxZ%lqU)UP{5BZ#!ueFmsANQ6fP_0|ak$i}G3Y>UPoMTgZLJBaJo9x%D?4ouhUq zJmMRcJO%r+9^$Pg={r*8RXdMVfqi1>5&)M$Y6AY+YlN9ob2X9Phe<;vXG(^XBJmRyLXqOpXBUD7y`=Hf5}A`AP3D{c=P9IZYzj_72XN6@HFsG~1~1tkd^vAdC72Q!CT zvB!SLgT+xRHFfG9f3~Vhd{`}0>Z{vpb1cie1aB8DJbSNBY7jGCja`qCF9KyL>V7&Y zK4D}4R_(DPuh5-PX&*>wFuloG#&PrZz?y>-Yz@nLyaCZ?2w8V?}+~x~Z#d~{Odwnvw z3YMGuKaaueq97@@qSjx%qVcqd=s?lcNQ1nI|$; zD`#Q%j{ra>K2t1RYwz!HVCx24PqV&|iB$_EqVB;6)U8qGYNV=xdGlGZtK<(Ca#O_oG60CTPX_#y~GJvU%y@M}$QDh=8PI z)q-oQ<7%@5(iks>EC3LQbCuV#ZqR>5wAZ%h2P#6(Yt)pe+Sl-+b0cZH_xIjNWh-Tf zTGk+1P;hX3$>N;ZKoI+!QMF8 zo#D-vD#dux@=dQzqu02lK|F7av&H20tH$hoR!->!XsT%nnn)C&tSKlb6<%JC^70`{ z!Gf!Tiv9IE*;+DS-`jhr)OqsjXvh1;OF{X8vYcl)#dKFU90euQy1ZHg zd}Lh%ao&onmm#nMBrVO9-+fU_`1Y71v6MGTCQ;y{7!FW%6NmQ6;Rde@kN%bNC9Rz# zj1&rxXuKSv;WB4$)qS37zD~NHsKY0U4>h<}V`f$y>5(HveMw01&mZ{%h*ZuUe)#N-RH~yJyc+52&yFDYy9yjX$Ar3$0iT+`CI~JvoWh zaIX7>g^0LW&I^qBYUqGHU9g0mGu4^ee4Sfla3s1#=2^}gsdx_k;c*~|f6e_X+ZGIz zS+!6-rVf&@8{iY?(HO(_pGxgLh05O@iUnjBb3OlCD@`kCZU?4&Kvqa7=6Jn_vBpU3 z5jyHC_9@9$dN!hTEoH}hOj=y@<;4k4MPS6^1Mvc7yDzOwsgxLzWqF-Y%x5@nz}_|O zZ|>zBtQ~KrnrS;ZIq|vK6kOCFp>s^u)>N*PBynK9u}dQ|D|hL)z&g)E`X&1fSq-&M zCN#)xz*D`50_z5PHEn^lR6*GnmpnCp;VfdapF^TLCGR^vnPAQ+Z1Vr@gDl{mv^vDR1J_>z)-jz;+wrk4XZE(Js<`7j{*cQ z#g-P({Duk63Vi3qX)apm`kyuyxy?2C*Dn?9n1U_lTf^Wf+(Me5do*l_*8S0D-iA^N z@Ewls5i{kY;k~~H2hL&!jImB?=H9*_-ht67S>Y|TI4#m ze_Ok+X?MP2&AFljrjCaY3=`eJ)~(!#sD(6@<3pf|*Hl$iYdt0vpIE9mwO@-g&ixW@ zyBg{~QCXWu3lJ22qi~7M%3czkV&n+MW>p)d#texHyJlU~FR~INdLyM_cT>XKr`ftA z^?eIT^}*Wp4?sxIqCdoYD3fWpj(^wH&s%p55KF#@^{jmkA}O?gJaUmI7e`P4B!ff+$lcC)+AOdemTl zowuQCYt$n{NbB(5@lk#CZ?P==IWkN~>>*yy+DY!wR^`=GP=s)L$%elYKf6TFui&5B zFVf3$e${BG2*vKr13|z$zrh`+o{$nf|33@R3jt+*H@SY=Eay8vy~FG`Fdv;wV36-! z0~%~isB>`yXP0Zw-6!fiPsmqXw1HTYwe`+ycfv~O6n$rR1X2220Zyu42`$GhtLuXe zEUPJ`+038^)f;4vGq;e&by6c@zSf3dE-*Cy9L%Jl4E1R1n)I8Av1*yHBWE+@gPJ)6 z=nV(V)N&2K<-fnZ^lH2~-H^)fb{7;(IRmfp{;WyD#L}Q*`EI#`tf!!Hsk)FR zm*qo!xj`vNiVnWmQHhvUjcH&j<9pysQCNP_L*KKu29bANuq&@ zW;z&#=PF077XiOn6FF*g=}1gE#kor=!n!Gv!K)p)GL~2O$99tMs_OH2w#kb9g*=xl z>;}~EblC0F@pCwI23c+GJdBBxUO7C#l404)^ToSqa&^E|E&e-H0Q6h4D}eU&0C1!W zoUE&)jp5(R7{_dmYip@>`W6<~jT4UJ6r6!AO`-;rJxM5PJq8@3$}bTh0!44nzP=xP zaw}~#JW5qdP3=v5pO?f#j8Sz{HyU}*I@cg1Y1G(Bh2b2tBy_mXalFuVn6UEu>r(y= zrAcb*)+bvaCtO1xKkcF7=h)SzO6TaO6RQVSj|~}JJ83OtbGp{3v=9;GW3U$`@^F4{ zqVKQEVd_aJq2d^DG)}V${d7TvW)$NKwTcM`)T0Jko{MIgF-FNIlN%vS9fIIyx1 zTJSgCV$8XiRq1S8EZa;Sj7fe}_5C~kzwlvXff9!G;$W!Nb|fOXt&(vd7x$5c14IGh z46Pqo!eY9(E=}5dJYG*frRuYbh#L&$mD)+hk}7@E#?ZN|A!3)}6&}T=2O||=@Ttq@ zSLa@w(**(X_sPLf?mi1AoA`z@A0RC{(i=HLXAIQ8#YGC`rY^i%l%5t3_zHEZ&C6Nh zfoOG}>oXv@D?xVJKHQo5H2u5_+U)T=7^dQ zP-y$~YQT!gsEBJ3;0|}NidbXH5|%fB0%JCPr8i3HOgJJK3 zWP_+f(?33#3JJ*P_o0{ZT}ZL$>gS6-nL8l7fo3G)zBOzCA(hUky@g0ZbvcguxcNOc zMZ~&N;Cz3wp4VLUR`V^c<$5LLn7cCH?kP6hMO8 zHOg-BEXnST&NZh+@j=YJNpVJePjq0aEgfy%1-s8}T_RVS#)Y(F<_jsvi*}Z_8dpyX z^Sfan=(?7Ew$;iD!oBa;ZO-vU3fw7&7o>f5T?35IHZK?DM+%v@6@MQT`2xD3 zzluD^&?r?JAXIZ4|879^x>5tLx*u%$P?M_=7?jQU!igIE#t2M^EdO>I9IpuUbqApI zyC!^RUqXEv#FQ!95l1myeveY6Xzw95*YpH;laAg9W47xbYw}yBV}D0hs??*!E4AcB3RA~h1$l6n;UrFlblbSKRyNeNK##eFe%0=bD-~{o9d0PY)*F|UvO!q{+6BB+STZno;#Wf zY(}QVymj%LK3?$|C@#@!j|*5m9DBAFrtxgCTBh$p(rQs-+fmzz=m`yIoG$EsbbpF4 zYFUngNInXlx|e&=1o9HbnJ}n*lGY}SGa?t}yT+{j{r%wPb@<|gx<6QRL&CD1gpnCnpO^M196>E-hi zbUU9(ZvZ9~j&5+QVHQ(j24Mz`A;^omohmo7r6cmokXDQi0YXc-jRMz8`uMDyg2-8R zu?PlfgCb=u+=B(ZBVXoU0Mv&({^0K}jj1-A?H^JeW>t2_D7peNBS1bHTUc1Cs}OBD zSUFs;&G(ArY1_)Z&RKrW@C~nU%u^+cI$*&Fgl;7TJbX2Ze|?Ot$iGOfHyoiv6V!c3 z>k2T-w9=hX?c=_Y+jnu}(hvIIN|3(|mRQohn+opVI>^t{aItvj&^9Ax+aKb&M zXMoS|8?0HoJ*jJUYUFoIMUIW>ZYLHGs%MN8Pw+^Tg#*J z^71Vk*=vjA4PAa8pI^?Wek61yuDR{bFVzi*YH6sd8h#$R?>v&8GYI6AYOY($&Z*pA zP73ajzLEV?wF}0kgTU6k_nA;J>7C?6y)ce$J-(;n+wA|*{@oFtyG60-SFVjQ$PEj0 z?F>d6aU;u$Y(kyS8g&r}iJF^AU{QFzb4B_~Tr^D@QDpP(>0;uJ7KjH$;vz?OV&5AY z>q5${H7;1H5R`bPR6T?jZh6KU^4xnK~q zsspMd>Pk4|T>+342E~k>Su`3+Dhi&M4AT&H@IjAqqY}AnzA9Vbh9a%8AT)Y3^ztbN z|EY-P#I(%V;=rjq&!7ptQ`6{cpQ#5Q~Qx6__LYK>ifZF4v}2Zq}y)n*ONqjjO_ zh#Ni^AK6#gg$}EoiL9x>rOo*&3#L~PmS%TX$F1WP0;fcs)$t-0Nravv^>F47Vgu41 z=7fzFekpGL|H2(Z1qY)UNdADBt$v-dS`Ze5EhmD#62(q73E?y^OSYq1PWiO4g^?;h zb+5#ohfrcpDUMb2*VKdwL~L@R1==2I3EJ@^9YL1$Qc9(tlrC*r`3x(khsTL}0dFNS zp#6-gL(QisxI-Mu==!98eml<4^kG($PgMiJ3%Hjh0cAFr$2~xFL^DHMMhy`cv5N4| zrv?Ph;~r2lx%u(bRO=ySzmJuG>91|{X3;(=elue#{zSYtVsQELpStY1xwN!15G@@z z_<7T-uh}Zrv1JN8+Ub$j^0OLxE&ziZDW`j2M=j{damcWLYE0$~ac;=eC_SD87# zh&MYzkR?S$A^^1YLuBQp8k@+@GkHF$`LlWy9jIfJ5JovVP zqVq?G^Sk3=&DGDJR&ewDtt!C*V#-QdXx0P$-jpBXihqImKiG3j&B$w@hO${^7CF8Q zkz~v6AqkD9hl7z9zn$WO+NE8*6uP!Rh@zePViDT3+!Ee#Q0-IaGN3ACP`k))tO%`j z2&g1V^6CZZXeJQAPq}OURmff9)y1(ALHN&WVa*Guzz%}38V%spsKIC2 z6+0TP`VI4-9^RG^9|_BZwnZ>n0mF=UjxbJ&T1b>j2M8k`IZ9*|!1eU1>OQ4_3kH&t z1LB+LEJc7r3*bK8C> zRwJM1&-c;LGl*9vfV~az5PApaKzlk9Rd)<9Xx7sM;x-yaU8Pbgyef>JvXh^=6d9(rM5^F-}0Vs(80=?&RgP=VTB`w(I zuq>xV?Dm+H&H7Z}chU5dO`~`d&lZOO7M-lEYn}&(w^yn%vXo7RTdo7gJyWI$Mc@pT z+WbI8kQJMd0xGiB;YL2V!`*!oNKysUR)AkY_!lYpI}RGcoDDXVH!7(It-5V6jp+T& zZMu{5=nE;%6g@`bIsBdubLka6sI(5mJuYZ(H!WG`YlQO3&Oxx|1baU?}%#+)2XUj&CW7uggB3ARXKLAPzM7Qa(A z$GyW|VaO7A+3hDMKgOPWV-H5!*l)v}W4*_L)hahfZrD{SLvP7?btISj?YDNSjfVD)&7e|l zfAm@dY%$kt3^CSaKLS-!#kju={#(yFvv#tvc~?8Hd?$9gPM#6AJwCcpytJ}37Ijxe z!oWt%ypTs+`YE_CNk=FJq#npKFUI~L^Nj0f9e<843n&;W+R zN;NFuJX|DVCIuPtRyvAKk;#|8Zm0)&m`vH*yUiqYQ6R_=0fKp^Tc?N-erZ@{SSFKP zxWvKSKc^hx_YWT#tqzs-IV}r;RIniMcPFldopyIH>ycd92k9#$Uh-G-v zoQo;9<-9)0&W86C3MyvB8(A}Y2KABGQP9J}!Xj_@zp_o=YmBXCu!os(X@s(7&3_(MZ=MV4>>jQL zY7~DaefYNVcGSt)`EuWb$jU2r;vn@R&Q%fdtg^8VLgHi*{nZEtf-LK;{Wab8wBp$v z9`0MY3&0aS|GcAz8Lxr)Fa)6><~U*K06x?(7nsAko4yIPaMEK}7b?0=+?&ma+pW_+ z*pjLF|r z=q$J~cF%)UM`7kd5}+s(#kpS&jMfU?Ochza;D9Qk4=#lT3bM~JXr5$!Tb4eHl8tW8 zxlMRpjufzjb>l97+@-?wkf#8sQ!Cq)Iw}aQOm!6a`r&+|o0#fDtOac&GOWJ#Bd`(e zvS=Tj@s}d9?i&lESl>BN6Ke5it$3M2KoV?%I zsY5CEw&wMAiCatK|E(bAHFUTch`G^!68tsE=2OVp!p-VW`#|VB{&072K}PrVx+{NU@&!XXA$|?db&|*q@Sq)%3a}lKYfH9>Q=ZJe;VsLjnHNf}l|zA@7XK zIN%@?9-i7<2|w&AZD$1#G~a!CnNw;nODi%IKqmG|w}o6|dP=*9dC_|&VYSXnzG{O~ z==&0R@s&4p6}o$~+T}>}WbkD53ZsP`WIEh($rLFe@k@m(Pm6a3*+tbu%|^uR?=RnE z+H6%n~0(WmmN1ual-n@TzS#y&Tj7dy58sj?FhYZ3lL{OJPyf%QEDkv1IOv?(E z!@Mng^0#T75=r}$_6Eq@LVyx!@HY=!Zz;G>8wXvEeU@)2qWuR2?UgPgTam8ne??hB zA41#{@WX&%tPCRV_ig>ojDm~SiJZsNAgDiyq?fTy?8GiM&Eiqmgm4%Ne5iCW4fK|* z%b^0G3^0L(o~Fo72l!m#0T%|&Sqh1q@NTTSO4zXG=~goP&v~nXqEqslTp#>pG zOa6=oC9q3`+6&GFL7@dSgOj6d?QJLuWk!e!`d!t9m+>lq0s+jW zUbnZkN-CO~-H^r!`hpJ!`7_M6ve)r4_FHX?NjV@TwzDkD0*EMnFcT1~ll_nYQiF_> z!W_<{(T-jM=O7*_OB-E!y%5yfs#Kyh`^D@*UU3Y!0YuNZ6K<3K5VYdQct1gJXrRw7 zsSH$>z8*Gsh`20s)#=WLL3xo>PV^$^CDfMtk+(x`gFonA3mdG)ujkp{FDLtRh%0l2@wCCUK-e+1Z{@C%bUV z<O{@68cIsS;G;FihzGRIo@Ci)ap0_-$0JFL%fA}1Gc zc?3NG)MySnRu%{_Zo@LZ7`WW?>m`=wxZ#R|At(W3^4srkP&ZEG(DzHtg8w5moUH6Fy$b_$WDIfP@GHDJDBZM_9^foCzC?0$_*vHPL=RJZ-CH$Th}@Uyk)cBJk1Y!Q zGeXg@U3ED&FQ06W<0kxYnov&PdGSWZ_Bw8+>CJByJ918F7t9G0HQe3lLu=u8PvBNE zANFqi&-te3-3EsxE+SDR{fmS35A=oPOb(B^)@x)IPzx8cJBd_z37W-y8h!`oO(I>z z^psaCc224KgxHQkFc&|ztBRjW?}Vq^o@j@RE;33*&Lgy_t) ze!)UZ!f?NN4w$hOx7%$y zxv|-6ufJXK!iBycG7oqw)(MGtQE%OgFHRTHiil9t&{R_!A9t+TsGsykpbjdZn=~6J z7N%3s&aAo-8X879PWq*aWAgHLeqr6Bc!kt`=U=60|HI9(x|} zDRQmsMzgxp!9jDgdb9e3y849ELG(ehI`H+sPk#B8bEwKDrE;8@%gu!i+5nYm7ykY_ zqTcRc&v$M8Mt)%vFCGXrT|pF<=P?KUGj~=z-L|?dR5G>e786#hv?y-Iov>l>x5@)| zr57rePKAKLFBMIf4X>s`tJ2q}5D2GcC07b29_ zC}C=oWN9Bk4)|2t+a53hr%Ho#y6*mNZrf`+qVDV3$xJ zcLCWhLqv0LK6{|Hh4YRvGT@@KUzHLC)>ivz{BKB_lI6H=)@Me{?2V(`j_aS+NXv}4 zwe;|*s5yFLOzjMCJ*&!3vM*YgJfQvvroa=aKW6lrt->SID{4il$&liS z%da@ZZt<2;C2=0hwRg3h?Ex% z7D^TnL#QB0y5nmkPFLm$Gld|XByv8IiJN_b-Am)~Z}<~0@B2WRVUX#7Aq}ES{>h_Z z3MGS3AVqgdrLwbvVNp0$z?7XV-Jhz$!D8YRv{)1jYCRe3ADuoPx~Gip{m=1#YjxlQ za=UkTPHF%++}id>Y6K=*B7k8g1}psG!QTB}^sg!=j(!XfVt!m^^wYtltG4C^5setA zF}G0=k5s5_fSm^KIUnFZ&iS=Z(JDdI7Ttth2cD&llkGnmZS6aNb9PAsw+rNSG*0kE_q^7 z-xf(yS!^dC}|mpRM*ac{}X z6Wwj{AVfgXLFoUz0LnnD1;siQg#obmgX!zk+otQprrn_%bh~6FJ8Ey#9n!(S?IPL! z45PD6OGFl+{aA}UMZN0K>zpN&fPNp~KUNd;sI1$9tCm*v` zS=13#ri^`E-CL2tx!>vnO`-^5pa~zQU9C;!6H_TbzenA8lb{N)y`ExrgIl4UwPW`` zOy=R4kYiidr+$r1h1s1+N;djJ*^QH0D}M)ce63kR5SAqxf4*7;EZ<(6A50uvjfm3X zP+1Bar*!T4YCWe^T}|u&d7OqPkp+Ueu~faV@!uY^R3Y6gXsTO*J8#ma6mCk z=N?1eZlqsLD}B9eDAUh=_M;AT`z9-4slcZAj{_7-NvtJebPP%GR3Pa2xBLmA!0pnb z93?A9CJ;`k;JY*~_nnkfMeq2lY=sWhiUjk-GH)RB$^+hTseN*GS94ydvP z{5X+??39N)xZpB0uOTo$=S3EKPIXDAI+65QhoYgZy1z^%v)>GnS!PSVQY%?Kwi8to*qgSETTOM57Q`mV48kE z&+ojCEXK;avYwQ?4hb}E4F`34H?`-OB9PtqE0m9Q7N!8%fqbcqpm49=fk#aRXlM7} z#lksQfU+cs$9H5N=PGiEY9IZPKO7pTPLcP?`{Vohz?qi5g)S4s^{j6GVtQNGSW!PU zF;4;V~mYbQSm^9N3TP1g}HMLhu!GS zo6Ai@<;XfSp)*jM^mRy1D3Zmyb*r60{})irAd#vW&c6~Nz~L1ewLwkem%1tEIy~+i zw|5)HmSzwY7Dj#D)HbyDcl49}f2w8m6Lb=ZVMor^c}UDdR-KE*CmmwHwKfN@2ayY&CmHBn6sfH6|bsSy#gD<22A&0^zr zcV}jPKRT+FmCSzZR}aNNnVAakCE^fGY=h$RveURDmm6WLV@`@+?v`)&<;frTnbJ!@ zgZYgVY>_l5lippwT_j?i`K3@A>##28Lr=h2aRs&2%O^nXC0Gq|~lCI45{WMT7{B3Q9kpZ2tc3WXx-&Bij1a(0)Rt#Q_<*A0T=V4%rO3^)uZ4hb_4?)*$GRY`3L@0Iou#(s6A zA*{$i)c}Frs~vbV+26N@%k~Y4&%D^7B#D8j;S)u*RUm!W{h@(hZ6|O@Vpv5{`N#Y9 zR6)2gyB-J|bg#(TG2h^k`s6*W5l9?muu?Qu3RkLR289M(iGPlt`A9mws^5j?PK zWHNd6pRdw$YYMkyVs6L&I58(gSqp*n_xE?_xM^p%-lC$d&1g{fd>^qtuLHRz%qirT zrBYB)mpyDk$>U> zkZ-JnZpw@-ZI_6CQc>0VgSjEM+~kd8h6W-xTE5oG;yQ_P2#})>S)eQjT3V0nI}LxG zi-HAr6zvR;Reiky(SarPoqChYhZmngU@K^}Al|KgXHWt)^-3?I9O`adbq&WeBMbn9 zA9B0A5?F;GzDjq40k*bRL7hP!(76fa!QVtbVyADiQPs&XuoeeKwvV>)C=`CbA@@C2 z2?WCGsGfmZ3^PaRurp7+E`Lu6MsSPW*mH+rr_?+-P@h%dSmhfL#6g_WzgAvlj>Je{ z&k(e||J?PiQqtrJJiix_u!>m$CShf>)loQh{;ZdTul zTw2gRn$reOlks2UF$?1(T-y6HyYrExzS?ix>*Qw&{`3{+d$>!>9Afh?25Nb2G01mz z?7B#7Wn#xfz^9G1YAr^bEp1#H3qaEtOyPFe6~NBay^dF5I7sv zdWK)lTDIj8?B$5AB_uNJT7U2zj^ui zLnd*3o`Q-qh{X7{_`{WC(aFf;fAcXR)i@8Jx?*!|f8VruLR?G|rwgtN8D!KGFEPTJ z(CFOIvv|GlJ8GAa3KvDhX+@`~*0`79X?r070TmOeko6$3n+JZWfX@aVv%FoD0Wij= zC%PeAb~o*=vyoh)!{g(90s=fd(x4$g403;dX?DX)%E%~#i<7fN)9>%Nswmcd$X_#d z`;~N>^b3x9J_UDD(>2~D_A-}%gh;sHlp)8F8_c+kzOw^v93S0Y=Im({J*mL6|1S~YY}NsnQH^ZK^_h-?auFR9)_6Z49Po3smi3WWfWUkXm0ZaldkH(;BQ~wAesM6tygrH zfZfe9C0!Pvk0Fuj>2-???xCFM$yh#3@7)$ttJP@Z~SKnq0JYfXTbbZfJl@e za<0m}{}gZ=0}G_7&>Vf_q!+C8ek-1Ku=y{y?)~{M!%MG;M3u+L&n7u={Z!fT@zbeD zFVb=E_2cmY594}82kXnka(ai2qU0U7hnJs|BMb9K2G`t&OgTAMV&WLyHH}f8Cs}tk zxlRD$;;T0+xxN^0v`v3)S^nTx{?b(d@rxZ%d7M~jG>us$skZtwLTrZLf zPP0C(`HzHCRn;u&ACeF-7AX9zz>L6*MrKd`Fv>zI?1+P>bvP6|u|J6QXvBvZR7jI1D8`Z3C*+)%G0=mI^iv4y zGa5{03X@*9tC;9_2?B&)eF(-;9w(%+kuGz zG_ysCB^4ToY>n4pw1%fsvzIZGd_tBJnfyZ+V!b(Yva2Ewu{_mzGO}?d8#$_yrkP*;=I6oftK< zS5I|?ldRYN1$qQ028U^BXbGOJ1pIU9*XNFb(u?`QuH;0EN&rf$8v%3+GU9fcYg)I* zcTTnd#A~ohD8=4~-+O;|u+#9{)JgH(Jth6OEwALFoheZ?U8uoPdbKS`*EfBOl56k~e!0#@V3Hno zP+8fktDQ2T&cCDB0bEG1FXjltqtg+#Usawsxyve?n;Wd60E|s8=q41w&;(6QHlIYo z_x}88QshLP23;fH^-hAmz65_&PqoD;lGANQYua8mTuNouE%*}(XC8skV$@2ej}AM4 zyDt4h#?v5+%bItvHn?XSao?BQ0N1gP&vInm)TdY{R;APW&NpG%VNy&KLBEzq?Xwy( z3CRV}ML%1id7X;M`+}Z$y#k)!&{Y>9oy-x#Kz6)OZ!Pi+;to`9x=YA|gTE6t3~Dvz zH<1Az0bH^nFb_idiHwv4S;gcwp`n2_LZ7{X96?j)psF#BY{H*F^33ktYYm2C7Iel{ zZzz^R&VRM!%a%?7pZnhI(y0FYiDCz3Vs7^Bw;R}*2A`YU7%q`t(-YH2^W?JxGx);Z z-kor-9YDBvf|)ry#9zt!^RYU#aS~x7qbexUUnguOJNH%Bt5r`#*^%26g<#U}Td9YZ z_NFGV_ueaB!15przAgZ}AebF`#IJ#tjhwr!Cd5Ux(}&kp<=EUdRWL+52Z=<06)%2v zr(NKeg@~oZOe&KvQGU982a2%0>aXE~$okSMdMc;82>kNY(a|)qWQtH(j$Ms&blLQh zhI))U;^T35_{pE?Lpjv$T1R%|LH<2suaF13J?x+aHLRAFK z6=uIkNtH~s)T#ZfTA%j*FIcPaTKdPBJs!+1kPg;Q3aSX6{hQn4u)0*iL5Wo@NtYZx z9=|VPfd2E{2`Rp;BMoS&&kKXDS@JvNO}B(@_(tsCXxl6j1vq)oPC`%1Fhk1Z#%MaR z7xV_^5#lk5@?oah!?)a-c z(+?6h7GN!{HZ^^-1?=Yi{Oovv{5E8{>28h=CLh}>X3k!Q5B4;-_31Q5=i%O7l6T0F zCf)EUg-66~iuG+&SeDdOSKqIZL912@W92!y9)^QU0UD}lqxxb<{Sba5u7)j7+G+$w zfWGAH1lsa!QF9i}zJ)~VsScGVE#X)wC}GFNc&T@YB?DTDRb#xG2PA{5hB?7x>AovK zgtB9#@}>q>3>PwdkA{2+RSB5fTeBLu?-hLTChBj4yZh_VM0OUCa%j;~ZPoowpyYX3 zt`uGOTwQU`?tx?^sL=nQ+1kbSAmjg?qH0P}m%xK*k%B}9Jeq+FuhrkWwNolZ9liB6(|Xj*guNjNygiz+=AMC^F@zNT4+DNi|?}= zDoh`MVjMp<5!YqWWDo(_C49w0)BV=vL#196jODxPFg)QEB&lMKaYWhalRZNSTuOE- z78M5J(rSs?$36WN)1CbIh5W)nhxf+GU3ErmmPE007?Tq@f6`Xv)b6uzX0tIO&> z0f9=3ER+a>OYmc4hq^horw)-d&d;P4eq z(tl@F8^*b)qn~za+87`eO>L@anL$(2kgF@*j7$^Ni28hLdVGqr%dUB@rLAOPi>>6> zI&^;N_Ys$NIhY>6u)|0+x<2!}e!$vrB;y zJO(CB1^tE|PS>Fc0GH)+5S#^xArc1$25^IbDLx{~!V?A-tMSn{shA$g4WptUMB?eL zx6-H0AmH}M1o&IK8%R|EmMiS>8{bHlo`E1l5~8^{_Y;ppuC45_fk2!s^I$zLTwi%G z$J#cPl9Hm z2Dtfgm*1*~S3d{dEZo@dx?o(mJHX@-1hcQRDoRQRQz8~~Z6GMaQ**bNK=9Z1%W?^L zxS3)SDv;TYhZS=Li^%P;^GY|EOs5~o$L-yK9ndmF4?9E;wddBr>dQ?3nKI~f6)*qT zD31qGA%To-VBhY$(58iQwt#$Pm7`?SW- zmO>Vb1{l9~=K#sYWkF=KQr~Co>V@?P} z>(D&5%n(kE$X(gTn77j-rt-N-fNDQj)V#x4Ec|yU{f})KZs*0NKCwOp6zXdi!Naq^ zyQsfOad|=rs#kG={3;iV4Nk#sR9Er7%TtVt(^Atq-F6)8n(laHWSPP337d@rAa#vi zb?mEDrn8w`DDFocv$H1XWn~gDNHtFQ1a&AF`Uox8b^As<0Q@cioUE1Y(Q^9E`7h^D ztaS!QyGt)gX}&JGdyAV9wRLTSD`Xohg3NG&&~<-fWOVD)qci!%+VQvYBctPMMl4n) zKc;bqiM*dE`d^>$ECyy?Z-+ZQ_j0J=st95}y@7nKK@5B@6EziB&}E7%UP#f>A;Qj z-orw?FhQme$s9Ns+KG)I!+_GW`a33Ol2?{N{2HhAg$*o(I#fNXqd(?NA`y5E6(9`+n?-Nb+Ei$!&jDDTnd-*0Iw>qTm&@p z@P#l6jZu90f_-zDrfYOi>OY7mYS$J85P+3AyiPe zot=$S;oILPM2??d0Pslk8tzfb&{vVd7UPS0-~iDD0|;@3**#->(ztW_DH|@{-KV^8 zBj&^Ou(Z;GfxDq-8ImJC4_aD91kfBn=ly*W6UZ!(t3Bq^Dmi3=omIz&egP+s+9q|kM(lhwHi0FN}5M##>WbFQ@m?DM7fh^NKw z$hKp@(azzl3UlS37-f`*mJ|;Z|IfIhdcmB}!Fu4&us^Td-E-KEsclY!6rNwo4G>i4 zJv3TM-UW^;DG^SuxDpUU`msMQNKomk?bbN@bG>bg>*OH*b!+(dt$oe1^t$a8`anXk zJM@1F&d5#II?m3r+8@p3b^)&ObMuR9E0nv??reut?!H>t0lta~sl?n*PapC!VN_6DC7#zM>?I}t+Bk-^pGRtNs>9i(sF?PrPG8H)~)PP+0|G7b~kVJz8+pO1DY6X zDR78l**(uP^RMf-SrXW!q`K(zqW=E$$;rv|tu6S|P;_kAfj?9qjZOvzjJi+nvLx2- zsQnFTYG?A&c5Gv}MQ zOiy#CtEoYSe^e#!WR`)%GZJ!`fu>ISmLtG#Wx*}EdD8!F;(3Va#TFF-ty@&!kEu@I zZg$=6?EMRuKkcWyR6lM~;{hZePn0QM=3*FDzA3?nu=P)rN(snEUazhzJ)XcZbo$*L z;K?+j0Th4;Nm~C%g-McLbc071lp4$HWY3CaN<1Dq3z9fJS8C79s=3L@-1f~?&=0Dg zA8Ij{cW#;i6mEClY^zOH zx)IlkLj_S|fVQwW*wuE}rHui1>()oE^=@xdH!3og%Oe-ImK~qNAzm9l#1H!ePGTz0 zi(F{^P7Y~K?CKID2ZEK#%O!5Qi-qvT(rzgM?AoCrMojzyMWChEN`ROm&sNQACiX8P8@gR(W!K zKFdC^xwShu_CGm7K-}3sr;}Hxva&vea?!+QB$tC3%?pYmT+L!4FZxE@Z9vxI&tafr zx2FGvv(2rkKnNjuAuun4 zsU85&H@5fZNMC*lqBNHoqE4&7vb?;UJ=O`+V+TRY9YhSRf0-88Kob{|Cmj30(VO!x zWG{hdsDJo2KYa`Kxe9EWo`*G0mdYl=zo&~qVIHcp=EL_04c2|HRFb}`j(RtwmA?Ia z%~Tu&JBPMrwXUzNt<_Ick`-75>meLS=kF1(yGDDK@%uO*TAs|8w5Vw8?_dA)Orl2$ zpt4LwYwruSZ8w5KC`(Pf(7>BDtxEQ;sv;t-+vG~ulRu4?14e|w#j>>7y}jMVJG&=G zgQ6ESqCyUT{}dnyp0$XDDw>)UmXlsJhX=I{?)z%^<88^eQ90M3paA;1$7huyd`1SR zE9f&EoGf45;5gXZn;Kp{nr`tVL$2*miFszRJ8hzop~4kEcRkKSN#Lk5ey ze|)JZdADcyi>vbq&qWDyeiSP$JF#->1u7&BsH+L>w*CH z;b{ud>}b8_@Jsd}I~auchj<`ToFNGr_o?}msxYhk{Zhkt?nhRuwg+3M#a_#9`Q}wu z`)bD>zN+r;e=b^6eHI9e9qnkxwB>#V&JRA&y^w3MJCpL!#!f-&mL(#2k2*l^%ON|7RW<8GDNh0{`?8)0^N?-`a3c>Hh)J$ zq5uj&g$ovst{mN zTrEcJD2%bK%uFmgk0fE8o`>PaaVHc>IPTvK9p*Lo6h6BEOcefAfS~&&do4uGVcK3C zq#3;}YmxOOqh#eDV-{G6m?Af*{As_GQxP~}eX1T?W^xcO0`n@zP{0R&RRjeF{U8g{ zSX;F)5vo=1+Yz|GO@`2gNInAuDkZoB_S{VJmV#GR&P#s|L*vRqTONo7^e*;t?QJ#Z z|JnYas6=W19AL9es;bq6olk3-Sn~F47y_T8xkHWUc2btZO@nwN$gq6eth0~uD!{Nh zA8B{f0L}MRwWBBI+8Q-Xjnq#v?>LDsp89vQ?n?83({j9V0W?4h~^L%~)R!_Qo>fuGHJjeScnzhZ{l4Fw+ zX?HTK)UM)fLoJGygmw;}eB50;WE1-NQ+}$I%Gl9Z-{W_cPAwf>Mu%pSO&{>Y2pO3L z0-^M0Gfm!qV?N@|Ho9vSlTM$PZZ5DWA6_atie?JZ8UUK)Y*NoWgiB{h*Y8nyZs4QQbIzs^=QVB$&*vlblu>_fLL4K4^>x0`3e$VyaH9WD& zv7v@uE}Opv2hunjd5Z5%7eP9!FVg?yWEkoRf-;%i#(n^drs1CMbIr|!h9LB)NN2C= z*u6Sp5#`SnvO(jh0gBip*N2C$QmX&{Rmw83mNY>j9fZyb04^$(CrqomyYHSVsaPT# zs0yY6=cXbl_u8fnI6^1Ygv=`E>?MO_%Mw79Zc&rX@?z&MhD>xN;&_RFB!$rE5HrO`Sa?`N>TZ@o$c-7mau-oBYMEe z!oc+Lo{W6k{>|xQ3fI)`1S5vgd^9^F6>vOH$j~nAmo#^3@as}lV?28i>coyv&A-Lo zx!RGKj54^zZs^VXSSEiPnwZo32&97#KM3DJ>h&rnjQz9^rZ_i;`GtFVDGPdf?=Mx9 z02r2~@re3sA{Vr^F6EB|UoYMpT6TSra|>@d9kbyzyrcn+xE%vPW4*ssJ+W+*exL3O9d!;d)e@w^Xc3E z$s$Xwt8eiImLk%H3@Ej${(Gue%nj|JZZ_%|ZC6BZ1P)@5pZ{Q@Qr)l zwOc>FyZW&pP^9%_mflalL3)p9R}W}wz4b=~ii}(zUl1B_Wo#c18t5*Kjo1EFI8&;st=;HK%WkhU;NS0ibEhC2i+5WkAi$I^P(sb$g6~1 z(gWcVp<+z)Joln!o(gra-dZvTB?xs*n6L^;r;CNKWiWNylyFo1ST&D71?1M))=ZT> zt!xe1Q}qOX;;nZ<$W(dj0H_$J8S6Dzb2>?NY*h*VC7t;RZY8KC5jrRvCl~rvrF|vv zBJ|njvzg|Ae8|yPJd*$Czu3DP1ti<9N^eV>iP&YdaG`Haa+n6!r8q`?F`^9AAT}G3 zWB_WDA$&>ccI?uTCJEb)he2KXMeme7;2so8ZQl(uGw99+j^Mu;eVB1HBS!i0je&>moH`0rU->54PI?w| zcaI9ppdi^&%cx$yPz+J{d#$y2u< z7e=mNhxGP8OXtGZDFrM9u2n zNu+~N0kK+Q{zUuG?S#h6*_aO|=SAX*Sz;XvYVzx+4ch|RH?F_mnT%U!{@LoU9zbEL@jI^14@2~0^XoRqaU~_xMz70@qXMjb z#S<{b?w(BmFg`OT4;JjZ`2oXea3^v;FXk@U{2dAcum-7d=fDgCto1=o(!5Fwv_p*P>N$b;?o{^^CkJuBTvPMt z`_l)?B3TngJkS2CoV-%Z0?>-+LmfZcMfv-LYcz*1W+b*Yu^2yRc-0}6>*jrL{KZs^^74FCYU-_u_1m`(1O~tiX;qJ1E0+88i{IT~?D{W|0KTuoOo~JlMp+ zF*4tA!1UhZhTc_b9P`yShdXR}))PTPSYEGZwjJTZYpzsxcVH&SToe=LANd5eI}3$) zc}){$!){@G)UcnGUuIe88Hx?(DzkqL$g2qKb$>RkU^IFd=pPyQvAy*K_zax+aQL%f zc<6slqSpfK8T5p~MeMq|{%aMNpm9Oge&JGIKR=o4sX&af9Er2KIt%KK5I|jdaZlef z=Luq_nk}Uc0icTP^TK{}caQZa1l+1Dg(L&1VwD~Ic}*gB0P5jFP$147{LRftIZwaN(!!I^b31FK%^(Nj?PjA?^hmS{mxFwN0{>=W;izrFwwOF$}PCb#eiwQ&MAn{jrm&_^wSP@=U<;8=PN7@A-FHRG$b%>+C9=SknlKsJmW+o0SUM4TkWfpDuH zMAmOZYpp z(MekeDyp!cz|r!m)cd(jw;2*6K+ptUX8WP6M#xRex6aa^#P!SYdc+!dk*ug4K}u-I zVb;EyE}-r01rpG+V)V(BlP6#ORB!xJ#yab~w%|w0pruTuwBX>%mVv?I8gUaXUwaO{ z&dld{SW+gfZ#pu5&E|bTZ3tohvvQh*c*uq3s z7{D5__qVPDt_h0CFziSgWgb4W$O5$IFs{I~P%;~d@tMtf$eM~MedLPK zzGPT_x5!Ai1Y?-Qh1P@q7IMmhh6}pRG``~Fo79rhe7o1u4hjx&r|nKSwh4(Czi-_C9y_EN#S{j|)K$)LYn9I7%;|Exl?TVxBbHg8SWs1b$SC z7yX#-h;%Ejxyas&+YRc_qSg!T@qv#Fl6#A-7n*4uq5~=YZF4p@5_y|vTOw0$98MOc zqE>D@q-5@_heQKKTYMh;!t?Yl5E#P1&v1>4URF?;`MsCzaeqO{_Eb7Z0ICriKzEK+ zr|s^1RPk@`r^8EOpueAJ!yJ0rOu2$8nnh?Lie|brMvw%8yxyrx;>mzyB_xcR)Zbsx zZl9ubQx3v_wCP^iJl#`NzD)EmG!@fpzP>w(zrE&JJW#yTjc_~tg=@{!8&P<{3QIqV z)lz%cGY?4$xeQ&vHEAA=%Xg=$~tWN`{hyZ(y$3 zo@XEe$2I0X3Xf=SZ+1en!{vfpaDKBuU>7@eT>u0^STzA^KdYu(yq7tG{hCB_wzqZ3 zkgP+sAT!+1>uaTY#^a%>rIx)7>SjmC$yn|HGkpf`*y-5!t~Sr2|fy(YHo>lJvm5nU)Xp^qHY)5ssP|M!o& zxiLqGYGyOMxmQ z#BVu2%GeF#3Sn&UQDYxR8y*nF;Hm(CUSjOoo?2dB{&BuEj{ZgWku}Db`Vg1ma57%I ze*ww(^1g{?)H=mv@0AHD2JqsZPyv4T;qcicf7uLQXs7L0CShB+>wGHnXPH$Qt(-mY znWIyWwy~AVqD~BS->ifLS1l=GGAt%(kw`ALFJHD-4%<&!(T6Lp+fzt~ci%hqyNzHa zQc;J<`+XvFXKS562KgK?%fg)dAej}^-q0|)Ce-VkS0?79mR3Tj95yytt&Chr zwKLAL>w7J;%5fgJ_o6w2&G5Lp@N73b#LPyl0JD&9F8~&ML-4YbMs4fo+vmX~@pU@V z+F}<(xSM8~h2Lgya%MJ;4W(cNV3NvCgb{-`^Pg0tK8g>*4BzImyZuzT&(zq$u478H zc$iyO@w@cga_V`PATUHtX{}zu#*?j@3^&BGv0egs=3IA2E#UC9Ucn+@{g#FX{*nso z0Dj;J2IuvxP%ZlBO7LnP;E?`UCKey!HYq6H|#mP=vcGs{Fv(r1tMDx(Kn4diS$gh&vZ;g|xTZ+VB3HOAEG z3Q*J-95G0*Rl;jJj=?t3>y&x&eg0Py6Ii$(ud;i7nLN<}Gh7t;cL0#EG{qd{#w8p& zLmxfLyP)KRdOFQY_4FkxT!pqsAc3%b8sfXh4FN3yp0#|2rcqz zi9_25{USvQEn1)I1Ap8|vyWOI?}_hepAm7csFt4%+l&G~m!+qR1Owb|Or~f~iBpV= z%e8bt5Z!-&|JlqPrHpt)28a9k2M7OKhJsjOV%NgVnwH*uVfI4H1c&U89v=2SxYC>s zjb$;-M%*vUY@oGwzq6D~Bk@7HDl3$4`bkt3_p7|!=c8llg+Q*VSu=W{FWjf20QBPqB2Pr*+5D^1t)d`RtAQ{4C%^cW1UirRV>VY8+h6W)+@ZCNt>4g8F*Q`X zo~kf0F-#&wtnrl0VtaayTgJPmZ4~FEQizRvw0`5F3;H~s(tg(4s+rq zOgZ{GHGV&qi=I`B|C6(fgN+UItoiCWxL3P(w4#F-1MamYPUREZ`tT%)BdhN`)8pDmL` z4E^Qu?}SJ>ggN`Lh=uSK{+K@hdD2;%u6p0IsfVjosq>493{$%PHi^8!0xa#S=MH!0 z{uS)b*zqd?2lyR?ZfNpzi87I<*$AY)2477oYJTpN9MT}i@yTIoQYL&-LG-PigcL_Z zN=ic?gAQx2W)zL;R(Sulv(A#<$f||Ef7tPP8%g~Fl-X**ebyt-PXZn|F-jJ*eiC5` zc$4M2(a}NZT~H7B`s9+EcNGra;d5+Zw+dcDe)>v3EZOaeI3{xuUmGl97~>GF1NYzn z&I~YtsWQB+lrSvV+uyu_CKEj~emLUfvr-1Gf2VuKWuAO1P?GhJY z%(MAW!o{T>o(#_@OCqPT4b+BCgR@vS?|^o~)pY|&O75n^|%T3k>{+uZ;?7)6h^?^-5KZ4&76XIhm0o zN!o?~9-9tnQe?DhGPki=V!z6TzR#fZ@4spFPLEugm1h4X)<9$Fw?X#@-MD#wPR5u@ ztgRQ!0MQ-!wW;Y4&GR7A;!6L{f@@2ijIIuvruQ}g77{}EraGf=n+Fb##yYdcg`1#v zF|;!8;bC_o3iQ$PYg@qUx)_SYl?#1HzXg1lCU%|QpU2Ci?;`C0G~E7_uULNBldKY!GSAn=0fhlf zP>|O6BlIZybH1yYLc6nc@Ahxsdnb(gpWxvLU6a zwM*Ou7AI>h`k&d&ZD4%#A1yj}DV=Uvu^~EOq0iR06AZ?_Tl46d>AkB#g1Z^tWeGrM zuTvy${yMni+I_@jo{AK~5TW-VRgrlnBq4vcZR=+0?>_LU{PuX?JgL@4z$lw-Ov<{~pJz zJ=Q$fx~Kbhers#9#%KRUNtrh~XrEtgIk5FOWaF!QgM{IjoD5Nx7*7XHXgJ;40===c zaoD`v3iPO++JUt|YIL`Bb?BSJ{Lkk8t!W+tNdng1zstXFUhq9VSXjjuH0E=7-K1_z zWw+B(dP|O*5)vDPqIb4R#gkjS@#kI3yw>KUgb)a}l*yfgjSfj#^)wA+tEb=?A`MA4 z)3+9CAnp^jZ#A~l_ClcqW zbX}G_h9hroRsXGxGuMR~mKN9lcg|F7T&PGl35fgQ#0KF8-J%GX#}?i@nOtB*YEtMs z@qVc{^6P~0x#OrIp6oU*WO#`|7!hV)>W9&Pz3r`Joj=S8WkB9pR9jMWkjxBS#@$Jw zzj{f_Xw|#vF`M3NPES@pEJzv-#2A9e1S6jNX7&q)tcQ@~#ro+r1%w?b#ZnLax%mUW zJ&4w0Luv+^9s9@a@9UrkY7V0Pom&aHbB8N7hM2&+>UYO1^_JgHuSn49r`JiG&13~b zPq68PJob@qM>SHM%f(e1a6zusLs6zs25L$}8`&%Gb4>*nl8`b;O8@^XKt+0b3-0bH z1rtEzaTx=o1BjN?(w$j(gt-EucG^W}$!(qPkr3VM0INrrzn6K-VKK60y8n=!+dL)s z?taRcvB)B9_H@S_HhI`P85nN=c(6CHo}ghp&2{;u8DawcT4~7jUEHX41{1}Z^g6%@ zIy7o%c8B)KX7dh83&d6Kti<(~@!zv(s7G>P$1XX-;fx5>-!&ks7{o(eTc9k#4EXWJ zPfw#Wgea*&3<6ozFC-0%^Yo=Sl((P5$=2q>0kDtfRU8Oqc-f@t20a&mjjE;vCZ!}g zJbVI}r4^i2`6tuYux=;M=m$ z3%VeFzzUztU~BjFyh(&1Z+h(ANA;&3rdhqm!00^N=k#w6BMZI(Cvx`h>>nrHhlw@w z7n?sTGB7jUkJFYxW6sN2ezzA<;+nHr%@NaaKsN_bH2iffRc9%D7a( zqJ>9*4iJqxY&!iTMKYEIiD`krHq-f?`z&YA^;i-$1Qvfj7kMO+vpc!sy2doNvU|f< z;Omd_|*jeM}V`k6OIo_v{YorUOHC^;4=Zr(V8`QauWy)PYl*$ z9^Sfr@zuPui%Snz$;bclgY_;3lgxyf;H>}22eb3jW)+P}QlZfaW9MzxMGGkCAnY?7 zY0z1T5ASxK6vm?UR^b+i=$TVGxzg`~JXgN`>sR;229V-(!4^wA0GQRrg`9>NA0Tn$ zn&}}3R4T`6im6-C?V7ZlQAzO^8y;a#iG_d8aEaX6DgW2kU?1nL$k?n4v6j7ltW07O zp%kx~?=up&Q!>IX`CV7@{nT-?t{8n#qIgQ0=uA#5FcwFB3}08dxkEbbkyt;M@z{P+ zVqnzrwlc6>FPe+_z~4I>FI813G1#%f$eAHjkz72tDP(1_p!_Ykxl>JD$y@D2a5g4?0VhY?hnDF^PCNnLJ!P!64BUed{IDzlKavTf6P%5 zFv^43+*3};v@}Sft18xFFb?aS)6`IZYvdj@R^4_15)1n5SBZ!7*sTvw0GzawGM{iMCYQ zqYg_~L$tQ~*+1I;22kD#pS|GTo+ZPu@N*%I2~}ZmH5oLIj`H0+#Uo8*NDXrAa64Pf zgd6+)6*UJiu6bVaqh-bXKVRv_+fV*uduSN@4o@KIzc%>&pZ9fL*EsjKl2mgpPwGI+ z%C5?k^)txL>dNcj`}NidkV^{#=DD+BRQIfrxqmo^b33n0_+qvn)c#wz??bjbobEia z@i{#h%HQmW**hqf%oC~k<1fgSo9f-#ex-!%x$R`D|KH`JN@Z0Zf|~5K-y+x5gn?!g64Q-uPF}MPzNv+kjp{_P%5pq7pmC@0KKqq;a^D zIbk2M_-DIkGiE;`Xv{X^$TK!wsQ+54Dw`o&#kZ%oEH#ZVL23w?xVa)gv7KIj_fpOf zvyW!dNqqOo1}q7IF)<;L?L1N%ik)xr-DZ_2@g`%X)0-#9F=v}M)Ya5JhG;fz4OG=S z*kT?Kxk{?c%E#`6vlurSsW;tm_XU=o)z|jJCxMlM%{2^`?OYdWcH>zGc((TPgrcH? z@-^ZGVHdDM>`?umi5Qw9$l}U_OWmFOr>!{eY*w^CHJ$~yP@naj9cZ3N0io`btyIOL zmhEO7UjFMKf^KkHfPquI7{iT(zM}#5wJd+4l1rT5TBKH=60-(GNBNU;2bgp}$q~cj zg7JAwe8K)&T|fYiGXmR-Ew-0;zXV*k=;)>Ec8e>Ian%EF$O;A@yy!r`m9A)5Qb@z3 z2ICB&{yh@unZg*+x4S(cj+v@)?Q(?ss#Wr^hKN{i>RW)BG`K zt$=Nngk#Y>m{i^Td9+-HH>%B5Syx(&11^o8KIvB!?juY^0&;stdLs6Lcgj-#%CioM z7s#9JeL>TSqU_=vFs5Gan==yXA4B#R4qik2-eIbKoD;G-`aEl2JF$q-h>p}{@{4Vs z{T4B|xsPQ-fmq3nKbe{z?*esYRT_yN;uVU%tL+yHgvK-Zy!QG>+o z0T^;-JtWFEE5n#KBtt1BQ!WjSPZZ5!(=jd8*#aQhkm|dMmg9JumhvLJu+R=dssiFU zEtzgv?}E}f*#T+DYq(@71b}D*a13+gA0W3GDbsm2KU@26pi@LCf9MtxS%Mq76Ss4) zP1z1zpWk}!nd)d(J2o@j%0_>gj-q>+cv4;zv5|Rl>^9TrbxrT$YfySwMH9d=;G~9Z z{JEyX#EP3X&avx=3{xmN-6{962ewa*BreqgQcl?Rp9V$9hl$OoQ!J<0IiZhn;?~IQ z#|`ql~nE#?@Yj%DjNFce#D(NGEhSf{c2#8C0U z|GcQmY$j?~d?k$CJ6%+Fwx~Vz~w4 z8X&wEm!PG7#lLm+{d_*&DiuN_0iXbI*_2vW4_gl?ikY;gU`kxE8g7rk+)R>IS&2#< z;vBa1nPZvTOD_`P1Fjuk5vBV1`9%?n*~JprbU)s!#795vID)L?5HoTJc7aP5PK1(5 zM2#~neS^0$})o^Ev9Q`y|3(nYp&@JNHgLEN18QK0V`I|R0b_w-Z(8vO`nxy7n=*8cAaM;j z0@WGIRogFiN!C50%(GT577tR{_tg)&MDN9A!GS^XZ;Vv(MUYNx{nv9Ks;#IYw^u$H zh@JY8Y)YUE$*yi3l2sSet97<+Yk7lbJ%RqzDb*egOg&R zTIFMlSv8iOei$Wc&LFmdPY1MAqU8MWvlTivwu>n>;|+r&n&(z!+lSfR<96pdG({R2k6X;@36&O&W%*5Rb|fHz+KcX&GM_2e`*@b3bR6UPngyhi`cp z+8&Hn)r!3+@UE?{s;r3xBmHFWB)c(x$%c8yw3vuSE#fEiN&03@qJeg~;$~)fmsM7X z#E)+r)HF0^rY57*l;a(xmU~<3( z2$3ec&Y%Sgr~rGSR8UA4+zkIBwUmO8Ry584Ibn-9;0N<1qQR1;7l}W5BQHV&>m{Mp z6FinKqS{b~$DS{pd0H)Gjb=N2Zd6%wZSm}yw9m+5 zf9F{DD4E&4z}x0UBIcZvS*difm)(A=q1|JRkMnAo84yVZ8Hj6jEX1xUep}jD@Ird- zWh!qvn8^$y@XIgbkH+@rU%yI<&i>8xz2aa0<5he4<>txnlfy_2-kmTax#>k#iRss= zV3(-KgRM6Wu2C-eNe2tRH)c1kFoYde%=Gk$=pjL0h({kipDt*n-^txwIh=G22NZ^I zYiE_WKc}pC(pqvQH~Dyfx@FDA_=foS_|(0L`Ndqcxz9-aA@txVzQ!9Fs|6NxF3)WL zH^5ol04Pm0W2ozynSDLoq6g`2Z_$uuA=Fg{K%Mw5%T!0K*wZHNV1!XIqF_Pu*yN0& zc`~N?*8X8(_-X~WyOG@@!tZc(%;(?y{kenexe>YRxL0vxpq7*yclmF9CDKy4mz!Rj zO8<(%sqw$O(24ryC72V4bQx;a zs*ols5M?js=Of#_MN-+JA6M7e5r+RQ?_|_QQF5mU<66eIuJv+TQgLQ+SGUgoI-K6N zv$>?bcJy}5bQ+|3%o9OLsWdNJ?5*(M}Xg5ZW}H`S>6=gbMZQ>$`bEV$^?!oQ2T`%a>joxzmP*b`K+?7YDHUikih)ve@sA(xS;f ze<&Dcw)`gq=$`1~7^C4D`I4?e9pdhdlqTwfl9&! z*l#&p&>9^}8s978TGM9a&T4MQ)+d_c6}~^3YN2v}M9{1=S%{hMEor5qfAw;(hP<~c zF2tW!x~eP#?t=Rw_Yoz^RN|Y(NDg#9V1X(uur5grCX8cJ8YevS%1Bk-BC2ZPUxe6U zl1~POk}6gD4CtiCE?jy)MD5566K*gT7Zynbwxs%#JO7HOSDMOF6E2gc!qeo~C2l#2 zP|HiSbAq#8=G<*o*tpDi?)`T`sjEzSqy6x>owx2aMMVWJvFkH;C=YXpttNkzT<9S% zx26V*3GloSmT`aMLHFM_G^O-w3ev=3O_%BBGU$47RhwY!;Gs^_)bY2?K)RKY5tp@} zQy!P41?Y^KOxeWkr+>Bu?yeT}-1GhLMiMQlY>t9cZ@?YnK9Zjl2wh$YlzmVFjyMS` zlmfV;1aJGaxz;Zmi!{A*%t!RV5#WMdST=TM61a^>W)5x8M->F2E;)q3NsY zCp=1eBx|fP<83u@xkq17LrGFe&`FX3=riFg>ga`Rr6o~*3JhD&&{#qRH>ZKelwr(D z{+yb+W)u}y1fV+R<~my?Xn--O%5XG=veDBMul46B)HHu}l3El-N!^5IM0Wz~vvz!Y z6krC6c*z2k1U4@JE-#E42(@&WW7WCLIN9It=QP-6nMNkBm8qz!(@4z1zYW;KPUlbC zsy}V}R z8dh8bTmpRDQxbm&`e}R^mq{`ZJFmObVJ#`xPe}yw15fQ9pKa}*cK_<3Q2IoSk?g%{ z#)*%H+jst!WSW2KeP;CphVxlpIBZkoV}Z2Ef0Vr_NcXvVI-uK-U8XC#Rzy(#twbLD zZue}={!IOUN9}keXD>U(9YZ!Gj=O{*ar{ComrKk6(WLsE*tpNXB}M)s%*}MUG_gLV zw07o1FW^_ZtpR%9-Q4A2wxH(5u z)KpTU7^2hf!3_ba$A&m!SU&vCVC0Y62b95GW&_f(wsvKlCXWRqWbQye!{sR_2-eub`&~dxZL*Y;LjF9*d4=y*- z5xwkY71%oS;i!&YuvCs%!-}rb z6?XqbxRdMrV;xUiwmipFCIgM7(M5uM?tQ?}jB}piq&C+diqNP&YOS4TVo>1ouw*b- zN;|f!g8Tg&YO~CR=Z!<|wd7+h-(4pcHa%!;7ORYO@@$yUJDZ*gF!`!Jx`~=;h(L6C z*3J#4VDAHQi2}cx{*>_Z??QS*PFK%TUF(|~)YVm2Lc&Q3q~-SZ87Xg{_<+omltuqZ zIU`;@U@dRRrc9;pHqQG*Hb&&?Sy^Cnb;OD2CO8a=V&udo%|E<&wR-TyIkDz*)yIaqqsYNtzrGoHSn!Y#V0P_O>vVQQCw?xh;N-Uc^`kY;7wq@6owH){?T`A*~ zwAWKoxPoQ6Kks_G(IU%S!Z(koXTKA1La0fA`$67cH2~m$OlyvDJYw9GD~{5C`pnec z8dnDymcNu%(0_mh606gVPF+`_xbIxt47!H$%0*`Me!LM(H$Ni>Ip|E&3S{V*me>tk|_Hb*8_k1``=fZj()|s0yq+hlTUV()_2qM?z&}IoGl1u?C?Q3 zp$05eTyS?u)*E3}ErLp-e+AJx#2@0$55P=nwcby4F|rrw6sG>GCy<~Em;iW%^p3JS zIM(bp1~79*$BK1>UEc=iE4$3|(zx{Bu}P&I9V|$sQSc+zU0jyv*6fZ5q$l^UF6${jm-EmGBrOQHGLf zBh*3f!-5kAo;NKVQ1@MwlaA8#KxYC^xKw)2po%r%y9ZDy7*iw z`+6-4-it}!VolHo488JtWQqs?Ye;*NC2Y_?)ptpBO79y-CD#LOCO6hMd(Gl50n@<$ z6^CE<9W)H9HR17>=dT!Fd1X@mYC~Q8Z)BT77F_-KYlF$&75<+w)t5gTy4Stgk9cii z`h9VUyfrALQB@!5mid9m<;A@pEM*&L&9k=JLKGTA`of^@UDmIDjg^#Wo;Jl?;)>Vf znpDfT=oP#exgar0wDy!XXAt$*zpa1IU84KZ?f5PzLt=V;W$9=%8@;9RTeeSJ@k|5| zY^`2Y)$AGiN!HQNn^`a%Z!BA!;4_@nI19KN<&6IJ6y}UU;;JurvFU%f$kA&ig#E;I zP9Fuq?Iu5Ik`+;Me>}&5s^iEoTMcV_dVQFd-*P4H!&g`dnxL>E1au+oCcF@X7M87_ zhON-)k92H|MC}s#W!`%ya0PMDRbQmcYdz3=PK++C=77O4?rShO;Hqy>MYIPm+Hj z(D(N7V|gsw^D*l~r&8>*sTYnyc-K6r?&Y{CSk3`QPo#{Z#kFLyB|ol3+5LC{u=C_V z{|LoD*k19eJ9Tt%kW1WdO;!?6DcwmS}ng~vMEl~(caWy&9mjh z+@iUkKR*lXv!rcA9%etf0P!ecde3pSBCBR?`-wp6ZsaS~WEnxO;3i4S2mfM~o`K8X zpeWkZ$h~hgxMmt>1FZ!YS>#7*kZ_p$0UVhrY9^n)?6=Dqq0&<%*7hRc58U#VjBxNw z+Fe~g2nxW9dJf91*njlprb{j{t+;S4j+g7sv_6}gp0ol(qd1>hs6S;XK$~mA&0?YX zo+VO;n>+aEO-oz#(%>hh5<2S&G~Q_X$m|d17CP=c7J(5Wy%hzgx=Y_8X>%Qr=secU z({8-6F#FoY0^hibZj=cc6M!}16CoF4rHg^-+hg}%laWudufjk3>8RI=!#<=%bd1U- zw`M`Sz5*ztzW8VeDzCDovNb;1?lA>uk!5F@N^O;8(gq((0-dESSmqUa1?3{i+=L)+ z7d3tG9>1pdfU~=MzGLM6hTR+sm4=lkJ>_`;{j_`<&sazeYOO#_(SAI=R+II+a84qv05DtpT5*NvEG`i* z(3CudZh5hWltN7GItzsiO91Y^xjw!A$*--ySfDtM4~aR=6uMk6=9$5v7abkE2b3sw zFZAHnZ;;wkcZVc~SH)R$YOu|rzXZFVy#}7*+B>T%^B~{(_qg`s1Z;U;sSn@#0z6(o z^l$C{RPI6<;PzOq0DHl-v^|*@eI|UphAm$QA{^Acd7h^Wqv%YL*+EOSr>mN3`~QZT zI(PR%)qKe>oYHS;=iQnCro5Q5t>IJD@rdeXTMsY7Abci|Z zP4%0zWWEA?G1D}68eBe>jR-n!7#=R88nWTN29-icaP%vaVZGZmw#`R}j=jFq*c}np=%6; z!A@~ZphOG!fU~Cm1(ydwZ9dT%4H6UI?m9_akx*GM&9H}K>gZ(gWU1T)eq(CSU^{&(>kN2+6+&8(>@Qg#mGv?d1;{TZw>+3o$ zkQjd6L=+a^uuL3NB*vfSI?TT9dfV3y{3lv8aaz5cwus*D%`F!x*Q=ZVsW`tExcpD z>;hyzloiR&Is=tY6I{`ljWW;e#?cDB`H6K3zITRK8J6h!yPJ$Wo?r(nHG z_*Qw>;R((o)BF4P0jq#DGEU@GQQOv^2CvNBu?vM@n8fXG;`l>ogo3XJT8ifdeF&fiAc;pkr=pzQTf;qZPCW3q_LRgG zK!&2b;>N=5IgmZ?J40K4sKcp`)y=QQG@Z4z$)AIv2s}c*rKKg#==2w~}Z|?wCN_t(6qeMR0y5UF@ zsAIwC1csSiZYV8adceog@9;ug5!xTa9i7nKljFauy*^)5b-&@e!Hq-L=_9E-wZg$< zr?_0V?cRb2vK7%lG0k;+KDMC9NWaGk@MhLkN@T&o>#}la?WK zxm4H1eh9d7^E=rHb4%Ojn}@oMgmlRjx=(LpE?haUZMty&(~eKfUrKHJE>FyMNvH3( z%M?+g49%mGv(wIllNcCs1jfA9-ZA_}1_&#?Wa0Nu&J^0%9c}UCW@)^OFt2?zfdaVc zU^kscZ8p%4Vu|cgz!@?|>t}o731QWG0}=So+h*V(P@}ezkpG#1qUO+c@H-%+GaRBv zr@a^GPh@(FDe(5LM&fQjf6|!drD3O4XGfirEvFB?x}V}B7JnC=trSVp9>TD^9(PYx zhG%DHCTps~-|U&NyqX}BIa1ty7_sng#;oPf5kB9kZ<|;**V$D6=;KCp(!BJ^hOA1(3>p-5NL>YT_nmKFE0lUKdpUf#RfH0nSr}D8w^W=K4LX!fb zs($ju6`|i6Jq)0up66z{cOXmK@h3f*nb$y}M@#0J4GmJ>G1~*TeL|t*`Y$mvp{vCf zUOD_Of5Hpo-hE>m6xhmCO8#W!BB zf}G;b&KCaswE7sm{&Ys+(t9>7${nlpPdBSt&QZMU7_D{1MUE+F%sM zMvt7<5u04!TZLnI3xs9@f2{dEM8Q*8<;yv$<)0|$3;VS=dj_}O@Iup7WoN;F?Mv1( zKqocW?2e~HaSZB>5j-(ZtOzZttgw87mG--W0Cb(;Ft-aheH39fk?K+J*3pVzJk}_2 z)yUr#eW-c^{jLTAA~gs)Jejt!@yz?m8Gr%-_Pxrr7O&}*z=1a+s8MU4Rj&8>$hG5_ zjOMaET+C3_f}Mkdg}3hB!72qQoc(}Vi?^?sT?bs@T06#GjL@mU;qEj%Gg}~js{i8c zt$yQtG^<|K^7<0_#dvVAhIXPW0-@+E&Bbo@nkuXhK9svXP+6&a8$BXI9TQ4x9`2*O z&XxoQK1V@fy^$*C%O&kwjs}pmH+YLY*Q8_NFvI5kgI_?f{n#+;-{0I#f>F0pW6=0Y zaB@9n_*T}p`u_mhT_^3;X8wXsjb-jRE#L3fhv<^xsD~*M_Y!Z9n_jXO zhy8aiO`tKEVg_4lVJ{2Y9ja|VTC(}_{8?qp*<;P4_POIIuS>UdnV4gFW#^yexM`kl zo4mTh@<~)Ti`^~0TASoLIl3QtCmVv3$zeqo2!lo6$MPz7jO)JH)Cw31 zKvzI{Z^}HmC{?9`^k0>7VKv`2IWPdbx8n%>9bu$Ayq0_waEaF7FZhyF&|9*DL1TLt zfJ|RiCGRE1FpC|=9^>-k-P)L&X*d11KN&Yo+$BCFiF8oqQ$JXg8~(A_dV#R{!0yC_ zyMjcFq0C%)w?sYg68U+);hQ5pN=BKY#o%iXmEzH1 z%TTCUAX&gZ%@eS zrpWoQ5W}30-`D4d@BRWed+qgnUf1=w?sr|TdpJ91J=k;TXAZ`r}`V%ccaJfdAZD0gh=f08@3op2Mpb3M1s=HrPv=9Yr%XlVP@12 z6<>{`w!$x)^*5!Uw6q`_0Y*dnsQ{AT5GRD@a^zd$Bj@(qGIIxjy688hr6w;aHRXhb z>c`r3z~i1QIYgzMsay*I-W7+PW^3NdxU$ll%=a+WDI;8sQp_$zO=L-Jd_CSJiB9K% z^%!QvrqQu}9=q}HAA#&WZmhP7*Sak=gns*M6FF$rM0Vxd()}jwB}4qJL2P4y$I!%&vyr zG(uoZOpQ1K#lw@GQE7F$I^D%Oeg5A<#|triXZ6FgW6I3gd~I=sX2I4eBdhA^zXtMQ zNly>a3uh+RwLYCB%ddr+(xKq^D?%Fulg1PbFb|>q+ z#?24+M<4I=t9%YRbV$!oH`d0dtHZFR6A4~tJA=;cTcmN@kd#0Q*wFp{=fi79hEVV)U^dK40D{itlYb_-lY3bCm0VUCzP@VkCp~j7 zk|ZdII!#LJ8fz8B2*l_2F5nEBOE*Zmw~AQ0?8ZWbp_LvF#5$B=g{LwVuMpZvMiy=u z$)fKT*}|@)(qN$?Y%R(DKC~8U?9M{~V0y2@X3P^skNxlHm(_^V2)uTj+0Pjv#h7Fv z0IXJ;xa8egHMh$y#w+)T3Pu0M;|DRQL{kz zM_-lteY)eV%OrkqP<)^`m1+GOQ|CdL!mVvoT?{*}uv%7vCAJt3>GU6sH$mIO)0X)7 zUyrQ#mEtdl*TH>1$&`G)^H<$fY9K>1ndOn{=dJIf)G&#{LJTbf3Vc^j?2&10pI=B= z*ijCpbs?D95vlYiu>dW}0Q$4vg_O^`rs3*yUOQ=a^PSVf-w}Idtns6Uvkw!hN4#%5 zr57tG6o!JX)P3JBcJEmj-rLv+s#3AllMpZFbB4kQ@*ln{JO*~YE?$Y_TSEWH$;lCZ z3Uzd|Q{vvyC?MMeeMm#~HThvOLB7ZI@zPKo$@9xrzssBD;H!+e{%Txl_~(-o zmrl0cm)uW8dM#niqhp`oL&8~1r$u(6_GJ7KbbM{j&h zUIgiwFq>f;;T`JSTAmK>Itp4W4?lTAd7dKg#>PUKo>7#~ZatguJ)N%V^%*WjTx1f7 ziZU!kzlZijWa<)`^V6i;JQ$-F_UaxNbCf68cH$$C)bc-`_>>$|3=j4Ps zl+@!!YSgM+q@&&$7gFiFo(Joz)KUjVNb9T%fFpvL&9OJ0@_!p z-ChWGf9mw@$U|U9#!^KgMJOf_|%fPI(h2{V~I{p{wN(q#%`LB!F0~s))8~v837Wu ziYhtLU99}dXVd#iAC~XijW<8ckPxr^BVPs5?CAjr9a>r3j#q&-yLRSg8 zIv*eF!Q1CdN zs*<7YS^zN<8Qde8Sj)vL=)BVGyQ%#e#DpF*&tm8bTTz z2-hM7q|z!YgBAyZfR+r-b;NLyu_FTD69ELtBv?z702RgKB?(Z()p7uAdo@;UDa|NB z5W^%n%WJ0dAl)g`&XKw3r$r)fKKkXC#@bq&ahZZ|3XD;2??J&)^+a}^8u2@Xog-kg zlIKC%(hHfZyc$8qE(Ejzy6|2Zy(q8;qKQDo+r>yaE9oktz(Px_oju51I@@%1SXf9% zXTDu^X8Xa&0RQ=_iTPvKEPxblq!#~(z@(c(|J7;W!iOLkCLcZ*civ*?m5ora{mg#7 zq&8Qq-8=GK_7~8h^a1$m+8USsXH_b~{kghC>{v7<6eko{BTi*K_1WB+w; z?w|;hG&S=v>Bu9`a|-{N>bXbgu>}WXj*WP~!mDFk&!0;y*0!b<#%LGI1ktBpx?&rz z^9|Gg;R$l+qvdw6gugyizh?CTD z+wiS-JaQ~7dmZL8`{kryb3l=7K!iJI9@>C_l%}zLL2N{W1D2*nQi{;d?+XGTg ze$bZ$F7$_ItIeg*4;F4i)TA*ZQ61Bk2$w7iZLO{!)J%4%&88nZ&jyh;JgmyeTB2(W zGEULgKAOarR(B#a7T^dCAx7+BOG^d>Wo%sOmxzaeAl+;<9P0KBW)_Y~)!tdmZErtj zHRIQsujY%OdHML%4gaj|Vn)y-&7Y_>rP=9-V}0i%1F=JAa4qDXWCJ zB5=CbOMn;mBBO!RVYz8=y-0 zgzQSC0&9d`>qkk=Y*Te|IfGru=f)3_{=b6Ry0J;)3`X_f3s5$~J4)zhalAL*ZiQ{+ z9*<}EsKO7zyTHN2m2ZOd=vO91S9$Q1KTXt;hqnV-tnq2}tAB$crR4Ez3QQk|+Df0b z`bsh?ZAw>* zJ?=*$6cm&~cE>W3-V*+n){rv0r9w{*`UWc7=D`f8LMi>dJ;t_ZN*rh4l`@eo0BZ=m z{wx>pu(@0*mN%$h5Ae@K3pohf1SL0&zg^nvSeBCS4`$JpOVGWqQhL?C6`!8WcAIEv zyL|Z$oy&AUt1;E%20v+@3WE}qmMay$&VpcGEXL~Y*S;y)46e;q~Uep}8?e(u-)G2!d0~hogo|UDUx_ zN|hBinR{WNnEKi;WUgDL#<$!sbct+biKRT6{VRHZuL$&3gor#AeIY5yP%Z=gQ0zYF z$Bj@;nD4Ly!t;_OdB&i67GW?<%??vdFwlv!%iW4FnwcpFhk|b?%mlQya}e7y0Wv7tg;c98X;%?UsY+% zM|642`x&k6nr2_hRQ8av9PeJeY`%B${@&%iQ-NaX8(8F8oitHUkM^p)vt`lhAy7ee z!fLFRyM5+xk|0B9QO*V<|Jmy1<~MudsQ@OW*to}eKwzg;fO%oDqpR)McA5@I5yXg> z%z7)>@JR9b0WB$1UhNH5zP%ndQwb|04H56KFh48PTOc!_#Rfno2%kyiH`XTGwkCW-lUX9p zHsX3T$us9?fyu0_z*EZhVn=G|XrY>PeUZlLkNkU#u$DMFZ0E0GrRsbx1w%#LgMPf= ztn)9<9?B$IU+Zt~Ll{MVTFa7(0qYg;5s2nxX&NB0ohZqtyY{R5qvdeu3!4%AHhUM~ zI}+Fg3*ebMNam9bw*(E+l6=4*{}yXCGw^>mq;Ef6Bo*0Ioi zb;XbLu=)G`a_wQwP4N!!u_14kiDdy6Wo%7Di?8=JsT14`cXyvXwuid9-M^Jmn24`U zR|z@@a&ul-zN3H3c~tR6V8qrmBayA&tij4p(c1BG`;4v3L!#bLKB9(T(-Lxx=ABM4 zaQAu7+(7Cnn2SdY(WDy*qAg*!0_f>jp#%hXU@YPde&?%#7j&W66%s``)cpi>UNfCV z?ETaq0ajjO0#Isl)ECCvG<(U|N^sfZjV4@*erh&)SpTsG@(}Du$Bxd!-@l(L)Pu`o zg|*f+uArQqZ{&DLua->dg)H?u!G8AjiI$X$Zx7ZdEi9z&*4Izly~nEL>41bje1BdI zt@MPfj{Eyowa=^<Qm?Ogjwy~3raV_K{- za^X`+B|x(=Hs*b42y|Lo+Rg^Eht{wCE4q6C9NG;oS$!+=1hjWDU}3{g`uIAcnS8Gr zzTOVIs)-50-FYzotEsBA)MIFrXm*M4agx8?R(vS2mASx6HplBDU&PkK-wla}g6k}? z0!s2KJK?O4Dx@u*$~!%VZ~aXAU)_9k`+R=J5oH^)y9D2+fyE%q1fY+!>o0ubu!lw$ zWWwG3#p;cWM2k57*XC+=uYE4*CY5_ceIAixEo;QyiSgG^#DGPZ<^R=*t#&FTO458K zDQqxW@OVWrF*?7k|7B4nanW({O*)E)E(%9y*hqf`)X2_)=ufKdg^6&$!18gD&;q7T zjlQugwy#Foh&hY0;&O|h70+*b3a;79~}T--Gi9C>oCm-pSE_Iu((}CSl=9+djIM_FGEV zNc3@50LI&U!usT@4dc!l#F7*BDM@#9NkEnO7`Qo4>Ye|P+@9>6ZQTD9<>Y_N8|!SO18%+_(c z%cVYRLa-ku5iS_j8A1?x!BDe;TO;v5JXG;nt*oL>V4R{7@@%_fTJC&0auozrUhXEY zc;xQQVZqfm_u^+CnpO(C;y4GxWP3nY-%qYU-HM(ox~^Kk!m5ve1eP`Ly9yaoPbueD zkq7@qCxPx#Uqiiyt78#DS42s5H6RXJRqIiIf-if90R>;%2o_I(g zFo4+c09D(h?Pa_Ec?#vLjBF5C+JxLUp53SuIUz%ZsI!Fws`;+MaY~cuCtp^`1kLFVBzvZ?a8l~%=?|DY<5d){^ zzB7E#j1LU+dqaL9y}e7GF7LPC>5^BL4-)Th^$$4h=0q%HO6jeT1Hb&Z9|FUgCko3A ztRC$S7y|TFCG9j4Dih%H5}nDh-nOn&wmds8m9M_+wI51;AzSh&%d`2FN>ma?&sJ@WQLy^r^PU7{V9))v!w4A}%Um7}akq!@9? zGxEd`dOc^(otl4c)#@vu8F<1GLuDt((!_0V$CZK@+o zWepPm?2Sj%zeSpy;V|OmyQcekzkh{z*2d`UoSK+%`&RAA-yNU_U9r>C z)pMM@TpOH)PVD|k4RZc)@E0^7@9m-xXYA-e|BW5d@g8nI%-!GSC2X z*m^Sg2Ip-Xc+Kyvt<>l5{6qT|A3rvq21mcKCVmG3=61-|pu>q9d66>Nx1t5&{uGI2 zq*J>W;*twf^i@Oealh!hSr-Ssu9a11BvwEJ5~64MY9150e#vGj{Hy$`_y4?Hj@T#E z3r<*jKo?=*faW4wxO!Es-WEhd3&3y28e}?I!-f<7E5GLWcr58{f`MS+ru+>ex0~n! zvm^QW2(!Vnz=)ADKOQC$5b~|cuY!b0R@q0(Uiyj z`FSW}U+MNHngbLS4Rw?(*6#IaC&NLV^fZKDw6t+==+JLCH)|xI*0~w*1;M zQ@`5~e3hfkr7v@&nMX>?(?|?edDrXNKX!O$z0_(|lHU!>3s&*@{HcG~>wzdN^H3=u zt-;8_s{q)07b>W`@XxW~`xo3LzI4t$eDxrOBFIl zk>SD4Zb=N>hXH&EQ$GZ(j&w2Zk4iTOt;`?#y_9b{`dQTXL?vhF$cEEVu)ZSQ9V)rZ z*y-|C4lv$tFf`yF3hJ6;HGfMw{oL;Yx{#F{;aYT0@nVTLEtmUOjsD(kjP&{3*wV7@ zO&M9@fkJ5+eza~8sGOBnO!N2UUhW+9E!?B)6&(cApzB2Fk5N!&dc}2}GOX6fXLxO? zMCfUK;Y`ctfM_XOH>R>X@Tf6amQ$0mOBsO@HoyF4znX&z%kAkehjfr$3_gt@M!6QW zeFdZ=mOMNqH*PQ<9|KkaU7>*6)<+wPp8WsTgZauVyu)Pu-)A>l+uB-Af#6QwDIpQF z>TLT#X}4BOZPrxcfCN2LYJ#dv7GLcO)NgWCP$N$ zcBoDy{T6%Zg}bwen~C{s?uJ-r#va?yLz%C7z5V;ACjE+m8|6tau_L=3@m?h9qUv-b zLhO%Bg@HQ+GYK9$yB>T*(v2h@!-@q);G(WT>D7mFCl4*2VZ4m$$?)?Ww&ck*S3 zdRG&7lP<&1{6V=rbw>2>JSt5ybgjopSvBJG!YHVBKXSpM*-3Joco1#-UlS$N=C9To z@jAItaD;}MAkOLjP*N~Tz9>IER`13|heckIa*t;OS22rE*m|PNl-6i#?>ti0 z!v6cb@L6d4VcU-aZ|p(D=cX2+qz)|mh9wzty*DeO@^-cYn0Db0V|y6oceeh%z^-y- z_H}|qy@U8sYo;+@KH+PnNBH%^`25+XZ2iFFh02ZT(1^Ns|22)2j_OujNO)VHF7VI$ z_K=>QzJ8_EjP;Z5F2+zGgU$2X$HsK2UMwT>C^b*X_b?%Sy^E0?8?oQH(I8n``jGsm zZ_8WEg4nyfob_yN3cs#;7#OL*jX|mY^KU+#wxjf&EuMrSpmiuF(L${MDD!bw*Fr(k zR`ZCDG&g{lPu6h6TobUw2D2MnCMsNG{7}seW-qdyBw03+zs-~2SUQI@yjXk{T$+3Pi;xM(Mw|EoO) zU(F&8I^Y|(P;^VG2h$Ng;@ygbVSY=uov?l>4}iD$TMInaoX7>^fMJbRLH{aSZ0s=R z)>9BWG%xKF%yl#y3R8_WK!dJ0n4kg}2^J#vXM^z&bwlR3d)l8kP_FJ6bxT)TOho+ z)Rs^MoJw$B&X?Aj+W`aTUz?ERe{H0YnHfs((MIUZ@$_NemQVd>U&@`LpK}WfHZ5H} zCAWc1r;z&6GH%&HFG>z;|1WsLYVn4GQ)>an!(I1nqZ(pqICd6HIznBXu$5`XXp>sUrm4V?+W>&3xFNRFVn%%i!g}xg_ z88)~f=Y?T`M4=A22>Rh&`S!?zc&$DpCkmv-p`MYELC9>b2rX)^;92Z``t(}QmPURT zv}{#D*U0%#n92|}pAte=hM^^28i1I=3-H%qn*PtTyjT8w%9WhnO}N7sqZ$&1;(E97 z93W+2YNmZV@YOtyb1PeKFWu#u3RwUB`?r_Dx3`5Dc4GKfC*va5lp-zghxPv;@j#9! zwN$*GM8l}2|5?>MDvBIw)Z{9;lRs-dD`eUvEdk-5~Twt+{I*}arXlkXar^m_M-&z^^ROJ_Zhz+G( z4}7oR2eaksywAt^Pv-6nsd9#WMk)dZf);v#p}6xc)w31OFPkq^k83IIC;espNXp5H z18H1FCnslUhZv{n3NIFD#-V@MxROtad&H2ojjXF5 zHs_8h*tNrjf*#`hX>40m%wqnhae6LKX~=uDk0?Xe@SvqWe%yaFAa?GcKdlTrw>It> z!s%hv;=e|~&(7^V8v17L&=$TlmhnFbE8_Ocu9XJT^wAHuSelKQNCbSlf)f3vymzws zcriA4@|g^8x3?f&41~6Tp6)%w3Ow1;V%Y+me^cvO5<#|UMTY70*!a)A+sK3zVZCiX zgGF`22ck?LPzlnyBhrA~VE{PYYLo_Rbijrjhe1+&%n3?Enq7Bui_LR;s&P6uf^#p5 z&I@l%JEEbE+1IbqVxkRDt-di*6lIZb+%2yz(27`y#z=zh!afh;`0YU`rs0W$*%#P0 zBkeVK3QrTJUgH6ux@1uyB@};|jhQ}g@V2}Y@t2>$KYrezHT~DgS;d`EsnY8$Xa7#b zAKuZ9#|{S}BdAGot+mn#^RsW?>u|-g1!%X}urUW`8M`an-V)+6cSEp%VG`Z{d`JP- z9O@>nI$xWrT52ibNELZ5X2ywM(nAXPC&H3;PPm>Qd)i)xX=^|rpn)KjkT1Lioryf~ z3Ji6QWzW53(!)7W>QTHfd|kyLU5puPWcK~`Oz8ep!aOK^x99nu{`sVwg#J)&TX?N!_G}v~EJY9s zyd0i1i#R>zxaVe#xSkLMo{MEwJ=r<)9$f)A_)C`Udq?B#TbKW9)%>NPU!@wdxzfGj zIDT`14$>+y@MV1-{yJDN=*Ge?h2(2nM1?ikv8D!hdGajV1onV#8*T^WpE~Sz=I_Y8 zz^ZZJVf zKlP{l4aeX6;p2fADe^S~ZBW=ITmTj2b#`#@B+xm-rvfw97U37fyY+GX@ni$ZTm!5D zyXvqM?v?ASz{?T@py5VB8ynjv8*^g4nyes1qI2S*Pq0(ucrfq+G&NpmwG=l+fk7!w zK&KKTiTdg?D%O1=l9Cgc7k+l=>^T#0uxU6cZ4uvKRnld3vAVY9bUE9TUT55R%pQC0+W5kzG+&9?OrCzY1-*>@$L zq3Edj5)bQvTEBX;2LIE_^WF1<_OlI2#FlSmvDOKJhw|rmXQQgO{WyCj9JtK4ABxSa z)~_`0G0vP*1+|`+Bsi$O`?fY$cI@r01Q&z;vikfQS#dh@n*Wq^Mv5}<@`)BnUDW$ zAaeIM! zbJZ~ZD^)~$UctVeE?SVUcFLAZ`=V@KQN|!ZMl;%t=PK@zn{s2;!EmkC5 zx1=qa96mtPnp*lC$p*oBv<%zXwM|Y;Z}?MhoS&(J`MlqX=YMlvNKS;HdJCf1I-_E#z0r-_Gzi!eV4oLCqun82bN4?X zH0W!vCgQh&hiDPVq3e+*_<~zoJ!S+11|Yx4RN&$I`$WNdh?A4E_Hr27;8~kGvEcIQ z6qNQWR0u0Yyif$ECw^WHY57na%8y|9O7kLV`4{vac&lSb;x^MuctVZRqteQ<{?H-l z5aYWZGoiqcfCT)*Q4UAmAB4YA34*rxfiG+FoYk1PZir(fc_G>6e3x?8FBiG8F*O9= z`#5gxD7_H#D1p{ukkdQsPRDIv!_udzy@j(xYuq149UUD_5(}ueVXgTNFG~8I(MX*gjy#_^WjzN7X#nD}ywtd0 zdk&q@i%h0Ds!<8s?6r5mYo{Rf9(4jkW|R-g%v^>BCJ;qekzMN6BK$hL*&!vgtmusn z5PLa%>N{X2h0{|xT3jedEl^6qJfeNOH9=?RnRquQ9K-<@7;7Z{mm;YFb^Z(7v$)o+ z@QN~go<-fWq}rif7%~}GOV2fyR&pbmO@w65fCg3cH(MF+E&A*)j}EDv)~WXfoGx^A z0ZJe>dav<1A~%Lj1B|e%366^PCI;^iLn)k+^71*S)8|{qW&WqDWR>%=%5d+t=6~7E zm0}ns#B!T2H&;Qdq&YDlu)(yf1{g~D6IaK4&i-zGSZx{mcQSm+*zID3A^1=IY4vuL z;x6Z;YOY_j=T#z(-c2c{9u`69A*)#ono{%m*E6LIEF86|N|lopYt4gJmfGgV|NV~~ zSjPebcJJ&`uf=?!ND`u|W;@NvIT=O@lr)l5f&xWuEN~51OA2-?Cs}ZIS5biW{p2JN zrv9U>JW4#S@I02ionmie5QC?dnzoGIn%aB&=82L``M43d^WE@u{X17$y&EVPjG)PQ zV)uMM(bq!ES+_E6-(J$z4qeFMniZg%2+6|SC>xvK-X4(;^$81Gp8)PG6;o}YrhuXJ z`^ZlJ^x0HPU=B6&z-AYlLZzCkK%X~MO&=G#-cut6lUrw%v{E2Su=@|VM(fJQ0Zrz? zU!;U!ra$4SI&r|L&~GsX9rt`GyYmBcKm=g)e$B{43>mrS0S|8 z(EG@T>}9u59cJMH0mK5N?)=!ZfUpyTPkX7!(`%uLu#;oe!v+5)27zFelhF2~eTD+V zsm~1(jFzL7VJkA)@f;Y4)J=`0XT!2Nh0^Kl7wW9=h$?u(eVwHBoc-G0^OiG51Yqn| zdA7-VP7&AL3k)zRD|(NW+}X;}r-Ai<^ks>u>_0U9a+Ice7I_AYDW@;RGXS|1=#ORa zhZsZJLlUIO#c4PfB+(mb-SH19315g`E$apQ!#9 z3xhG+qYdmho@#1B4YI27>wSaSIQN?UqD;pb?^KEie z6@=HvqwQv*Ly&y7qTBUYL(2-f=ng+r=*VtJEu2-DeA&^|~aZRD9 zeqV)$!@BJ$#;Bn>5!U!&joZDB-3sc&R23^`n&S_pC2Ru6$L3OoY7ergAKEAHyz}ow zDSa5uA5?^|?{@*{ZbUtBG$r{51B7cso~`J*=_ zr*;C=sfBy4Q%r!9|AbgyWE*^1n=R+@ot#lH>=hggdvembTaq|j=zc7ixLW$Gxxtl( z -!856rtG?(LkePnZMQicHO9x-!E>fgpm>M;o{%9Al$Hg0RJBib4xX5l^od`??! z$NZ2Ov@r40Tvhy?-}}o4Th-%lN`3>LGwim;6%J^T$}Cdvd@XWoruAe5c%oI0TLLMO zdtZZEKJ{664qspScg^Re4^vdRFRH)6wP}{P!wb3COCM(dO=5t0n!V|eAAq`9`iF!} z?B}rZv869>?LE-}XX`Yw@aL%<|9jZARrqMNiEInKoap2KsW~D3LHuXRMBe#glD^6* z@-{>NJDNl;5ugT3TIkWdt#pn8Dy=Cy4g{>DC9!t2t4FhKH5LABKLDsaX#X7zFQi6! z8`m38Ed{?+2Ht(g(>eN$H!O*J);NR)Q&E3r(l0+>U^GyORW}4!U+^Nhqt(Tt5DXXu z5Y@?z;Z`vd|3gBv+T?Iu;MqjPU*y%8dpwUrsG5?WsX5TXMb4p5NplN=@OKE_0G*g>x z6sCF>qQ_JOibMRp1MX)&Uro965{04j$nt0d?7c~z3S{{ufPGcwvud{)+o~dCZHXOqFydx=)|Y%P`#j$T z?A@_nVTE5^ULA`qE|ZYB>SX;|vzzsNH1B+!^;}vjzx{NweUEUdV}CzzXh`pZGx)`9 zjDLmu#O&a|ZKWX}t|GL7<1ME@LX@O*+!d{y(SdHkx42h7p_4L~m^mDO5LBpte2sh@ zk4kbS>Kpikh$0NM**q}N-R#CoXh8m4>gm{Fy0%o)`mroTw&lth!$%(J+S9S zqaC4(gUehZMfaiR<{YX1lI@ zxTBHz9NbjlsrVivxf-L13|fq4ccueDP_6q>)!0s8m7BBrewz=;jy~#cOdUyOIOs(b zWOX9lcjKPfcXFv4LvXGz6T|^WhjD;a^6@Sj=BL@CAp*IAL?oSdw6vMEjd;u@?M6k# zN1_Xd4l2A?yXG>V6%6SSS@!}YLD#XhpGheKf5qhtnF298P0BP;9_#LQv za@ZJ2eOiR?=6O1OJ=sw*zc&=kb`cg77pvKEg&A#Uheo70GqE&ynzS`I8UGh7mE)nv z4|)K&0jZmF_Z*WhNd(0q-b3E75*3K9qji{(skSMbY<-op#hKF<)kEj=e|bS1^R4kI z;sUcMKa0?~a(|OXg~W7faOIFF3~ImFI`-0+0Pg~q8*|7fbcM+1J4Oipoustxr&UI{ zN63#iz|cS4?}_$sCd$nmaMAlYdB*vEsz=%71mYmfQP3->=Wn6_%>OIFro%y?mIvSP zZe5YTSu`R&bz*sk0O;HxTEa!&L&qDENH6VXu_10ESJ=qXLuu7I{XW$@1hY|*CUmYq zEZS~hiCvMONrn3|+sobN6fF+OJdW|J?zpSlwzMPq7vyDEG+leeYE(FfmV1aBvxWsv0c^N|ev;}T<-Mc+O%>cj>cZAP+7y(+fX~s-(MI4ikCY+`p=}~h{fl<~`9y>T zd}$OSb5eQaJieT7#idFchx7MTOFs3G$hqWXE{K-Rj!pcnKGgt@*3^G_2MZEl#;}gU zp)%K4K%1pEGpJXC_Wt-bMr@raE(~8yRnk^x*X)=(e7?mRxz@;_J{Losw&zU|PH#?gUA7Krf+sf^8BnFbJTv`WgcQAs=47N$rb&)DNfU09PeN&^-DYRUkZKLH9-} zDd76O=Pidt3(WTSCDZ)J>U8hGYZ|QEPf5wqb{Kn^8$g&2nNT`*6S?0pNnuDN-j=|# zw(qUAZ~fhbjM_|g|C^upX=3KPg3;Gc7G#OFmlbD$YAB_H5Q?hq*|G!d_{%UqwcpRo z1Hun~pXzf0s54(p5(*V;NA=yqU)Kg1$<^m8~V) zqatCgJS3|m4F<9ug&_1YRssn)XRXqshMT6I+NJ&fp9P5AE13}+cOy~{!_HPp0zFiG z9g*KvPG$=@bHBilGry;}^&0w{sbKuoj6l`H_+Ki6fTbhs!@r*-qHL;Ry#AP!KKV4b!8ZQx{T;D@MgFDhG1b0sornkzC}?6y+qtuiA_rO?0jm*5z`h zcE>=#G?@Adw^V7p)J(|*V7V!+oKrozt>H_b@T}J+(+u1kr*liBjseo}|ra z8;Pme3bIOHa%c)W=j5L?waI<0sj&}`c>d`}Y!|5?v?#Z;)$O zh%(=QJ!;Gw>4y**C4j(XAWKYl*W3f1YcZDJ$?nDu;EoruZj7O(l}LV~UNYC+Uzuaw zFDi~7`_Me`RC2|7U}}0Fc9d7st07*ZHfdf!2n%mz`;ViPzJx4I1W5<^ofEseo22%R zlCq7*Gz_04aj`IXiyt@8E|%YMFJrPJHi}-rRIfHusnnKzzAEJDuzrLJ?`3Q??0xC8 zQvZ8k-BFI#8_;)O6vH-MgvKTj$6T=3IS`#0Iji~h_S=92!*pOXJ*VN?hhD|+T2>kU z9Gc#inSyK=$TN9ekX*P)^-Ke(-ThB zyu$8B`co?HpRFXWs)6$nwrRx4QX7_pe9y^&+AA2GVG`+D@ncIet+G5h>aHoi0JyjJ3pp|;$S{d=Bw$#iPjC8~B0QVPY(zKr91 zC5mJc3>?y!dY`&ByQY9Nq79NE7raP<{D5z3{nISATKHj|33M*X-$pom(%=6|OhG*R zS2Pp3b-0=7W2Rj}xd1)S$?V*#hK*HVs{a{MPBk7Q>9!~+YeuEj3vpffep>=SV0SwV z*ST3RGjzOr-~~*HN8nTYIkSe}%)lKt@8s$|o?&HBpZaOe_fT}Q;R;5GEWaR?f=URJ zw)<2F96;a&XXla?fsATl=$-cyJE``tS3h%Lp#DR60+X5z2PdbqRX=>*_H2aHW2(9P z#e3YCdon0Dc%vz2_h!NsiF{xGono{||1QZOWV*uCMKJIv=`W>^?j zJ~DO z0S-uKlrjOA2y|MI+a9UU)Inx$PBC{G5E|i@_>4>aD@!Mx^4W#2_9$dEU~7(jAT=gI8{jP2*gmF;KiOWPwZ1@#T2a?UbmfcHC^tb(l; zPv{7eu2`#Ze}?MybNkK&SO>3TFKT4U65=)w4yrNpy4+rFp=E2K=zEj(m~AEEYE3@Y zUI&5-&b4%FX<&?^*4EB>{cTG{1pz-HT2zg=aWffRZYp;1{Sn`V$G1sc(hF#si`G+8 zDC7kT;co@5>FmVuGJk)`p+pBHH#%_L> zLoc6@kkT}67OB3Vx0g$ss|oa!x06asxxx)>I3tZSa!u znqQWNyQSM?{i%f)^!_1nZ)~A!U}0floXJEaWx6%U^QCWr!fTSPeJ ztc|rlPk=;fUPe6=?|qmR+E#I`qodn32m=peq=a zW(2grARth;m4T=7MV^23;Jf!g6uQn{p=3i4Ms%Bp<|0e%^)2DAtqD(Wd2GMUp-hpuWM@0@4hXdkNR^Oioe2T z2xz_dF8uow_GQ`oB36qiN=td`J8i)Te#9KJv8ro zzACtm8V6#pl=Ztp{Dm&!1&m}AtIEN9e1;*1daHta4DgoWy2^wAqEpaR!bB7ZClqD9 zc_^@ke~J|DxbUQDmJf!KNBo+Y3R&{4{I_nkB7H;(JY!3|zo-=)k+oD{r&DindVgcy5N%~WonOfm7!4A4x>%5N5ZqOg3Z4_jaAC9LR=*Ns-QR!-|XWq zIqGnCcYM4n3kDBIT@fv9e$@7=;1Aps-!G^?QEaaxVJb$p%5s7_Y6SD%ASsMy7nhG9 zKV20Qx}Q!CPN7kIl-4mJ{;;J&2>K8Pcj8kd`)|Iy6eIA>P+a(7$^(sI&oJ`%%u!2Y z^hF&rNnRQnSLqV8$pml^w^@1HbT=`|JuIY&;;5>uAF_LHS?mSny`PG61_KPiAO z#>rW>^c&bhAB@#Zz6Ul92+Xz#)IF}ZJzH&yW4$dgUd=%r82B=-F00_JIpL=9`OaDW z_?IX6Bs6o!6>V0Q3Jk;Vg03E13F`)bcmTzVZfNk5EAB1_xR^Pm?Nm%6NHDYOuE7fE zYMFo5a{T|%bd_OEet&(Um6R6g77!37 z10@Cy7~S#Q{}<2RvTNIQ-G_6|_meNbQ3wT`t!&_=Cd=aH1iTR@1!%%wA=)aX|P`lJI zA(t$znKZUuo$<`mj5=>QrH=U@0ss98O;+_nc5nr zvZ>}Fr+|{EGSs%;oa~rnOlO<>>kVb>2X~orQ3Y(AyQ~Mww@WTBFV*E1%xvcSVKC@r z^D!;CKzK$7U*aI5!mc8yM5APEj`5;C*<`*^A3%rke?}& zQofz5*bzc)6cs_25FUpJNda{*5Am|tf2A*uAAkP^O$d%%^?xS$7dflP6bwy_{w0;% zL>VCzEv%8I#<-)S2zC3q4FcF(n~?e8;-aU0R9j8;;{FcMZ;q0_BO*`Vt%a_Cup}9$ zuj=pL2DB@G-q13$q4;S`PqX?vYUVs2xRlaYkr1xclqM{cLW-T7wOTnDcj9SGf%>T; z{>kbow;4khKR-V*n6gfz8~RC&pFACKu3PX6WZ{l?&@C#;Iu9}YIfN1}DKFpUeL7Q9u7EPg#qU|4r`kv{GrRT`=1n_s`#E%2T*Y&Wj^ z>w1{4mpDx!eyNINBA;so{jyScn3#>r9Hr)ER{{~7L7+m|)VVn$@6(CF>}+f*E5%DN z2DTmP*YoNv*$+tU6TbNA{CuaGoXf(cQPk$i@~s|)*2X>%yBaywbAGisfm)SKUB3E9 zzkIoX_9?dr{MTkM3Q0K>C#Ds$j?!_c^5T_jbHveG1m7H80n!#+OJS&S)tqz;St&H5 zAw1k`qBH}}V}ooqe&j*{kEO262s~fU<`qi*?*E>sNDRXjUM-C8K27ilU1jWdJlorA z2!EDEUtV6G=c#zJxhd>Wj2HX<%XpN`sa=3!EwZObXCUB>r*LvfqrT|GTh%g&jF&Jr z4Jcevof__FHXpJ~LkOT2A5H}{8|qCTy(9)Ca0KaFwh2@@eFz_>fnN{M4DG(NnM-m- zQ8rnx{u1rx)V7ozFu$7Pv&*gBF&;yWWx(X z{rTbOmdORm_*PtNn*)ZZ`0w!~p=O<7Y@wgK<#JxMYn_M3M5^yu-Hv4LzdqXMW-(^u zVFit~zDQ$>D-~7oc`O7m6zUNofd44>lRwY2xZdc!q_n4}X9+&TWJXpId;|!e^+;@w!r5fK&)h1IVT4| zcdnpC*!6tgj1H|4i+pF$se{M0Y?9K9F9>WkDaptg*@dqLID%jovAzIm$iQvu+ePu3 zDe3rkr?H5am0^3EumldBkZ&K|bDL{gT2!=}sJPR0LOneZ)D{%YTG~mfs0e2hI4kRO zp6NExf!eI+gpgr>4-fp6DKI@#692KxxBM+LNoLk$_E`WRkR*IKN|n;Q=jJ&%ZRKU2 z?b;X6ImvS{lQ^)$gvc?BRDa|6WuN5vwceW;+n=*a+u00HFm5jiFpVQxFa`7`M6)Wp! zf#=A5dxgg(Zv@`B-HobOo6~zo7%#bsaCFF9AeQ^F5zOiN@T+3DGHrH(-Hgf7sd5&u z@n(w~0`i%vnyge^J)hT~!`4T-5S`vxceO|g1r402Tija0>?Wm%h^YuCWUz$mrmRsY z9${nEJU_FTl%&=7qA+6035J?4gPspP(zrFM+T01@$f<>Xq(%<570ICjhS+Dky^A5C zQ_TR#>HIRc%6ctZ4d_1OFCH7G95Ek*`SFR9|H(DnFDInvm8V;U7_=c}%p|~nN|R*a z_`pp5)=iC;)VElFQKkV02TJ-XpiCX|3-VWv+%u=l=`Gm+amwMO?6t0$#GG*f(i5zL z)BIvdGe;4=*fld(Flj$=N$@iHwL>0REbChcB}@`Eua^%#yLu#eFZx+|Ad*al;O&#n zot!MoHDNV|y9EzfmPn(jXD1kV`^yW1y;=E4{ z0mMj7Gl`7#c-B~CAd{pmAyJDMN_MDdY@NL3Nd z44n7d8_Isy6yfp)y5y0Gi22|4f6-Rp)1BSlA%{Cm;oK>Mk7*wL%HrV=qjTw|t) z@#FcBavpN8z5}sWBPSvAK1?s`O%1r|9e|ScX9ZZ1Bq06{K;xJnGO;Y3AI;>>d%PaD zZ@3R3CZ>UNrBB)FA_sc)^rTi}RrQPrdthf>cp?Ia$Lo!|{~BFp_+^5FZ6lvg8y>r* z_04;jHs~uH{~Yh~IQ8{wa&C#X@u=~$Y_D|DRC!n( z%yP=WMClggbVy-Wh|9}1%JdIF-j z$8bRIhPmyJ!O}OF%%9xpU1DRgd=Ui!GMGmRG7fiMrz}K1Lf!?vtW=PZo6&y-cLjqu zAk>7rjX?O;gXD*VF8`r^GSDl3*%$Zs0Jb;C0CH-y-`Z@}q`lX2=kBD!;7f~^N2wbi z%V!`BqVGy-b@#KU<|YL0|2E9^J~8P&&aKkZt97yIgaDevflXWB2OeGhH3e@)_CpzP z$RNek77ZUW2e-YsAcq$Q#yGelAaA)_cw2ld&Qg+Rjr`qI74$;QjUS`})zKJC*O~W$ z+K?-0Fy~?Oh%DXs2Vx;_g^7Xck0=QCp^BE1iTJU0=t+{_P|)RgU6_=1>)cY=c0Yr+ zK-73u2K*ZVD5t9@7Xb)iJXqU4RzJe?+fWd3y*Ey#!)ZXQYj7hM*1o)7e-*r_nFj|@ z*ftqAx#e<^sQ@u4?~0-x7Ea2atzp{CU$GVjotN%xHR>^~b3|FzSRuW%4rSSCp@2x- znlPY18b?y9iFQvORL&8GL*R%J$agOz9rz~*+=T?{MxkPCg70h*Pbw~}I27|(6kuiP zr+T>p2V--~IK%&nkqspeqS`7F#V4d^kJG#~hWgjvalbsyKkQN~wWP8s!9Vcew|Odb zvnzvt<71Q^glGDaiwg4;(PC{luGM{e7F-@WI4aL?!h}9JqmTKVC#f{!#cOz}>Mz)9 zg68sepLzXT7HyBYM^0J!*qWw659HREl!Ly#rkURM$H0tsCmjyXdfs1R6krjG%kSOa z!wGI_7~VcMyhA*i!jIrk&e2VGJ$bogwq)jQXQ#h0EZQHppL_Z_OR%`4{p){yF~640 zaUq4}#zgxj7J+tcEgo;$3M>i=@=Kk#O5qXNf(5*sIhe=vht0tF74%tR4(=*$@)pk9 zAn_rU6dPhclYWhA;GP_5++;v;&r5_Ck?;}pZC}u_MIc6%+YL=+@QK3Ma;$bVpad6& z&m7CViGLDDi(uy~ZEB_%8^gp5t^MBn+n+E)U%nb_id3ET&373D3u61 zJ}m6M96jYqPgQ(!BnSOa8pn76WlLq}vOJl1l-UPu;80H&3%6Vu`t4^{VCPie){@DX zH*N1%o=O;bs&1{E!+HUU`|utX{Y`^g9j^4S)kB8m`|Q@Cj*teA|VU=nftt&s3m8!`bF5KGw5gF+*ASL2^u}AwRv^OWRiB zk0l}+>SSY^rV67cciqf`cA8GZj(Y}K!XAdth)F4!2yEzO*%idT4~ZQc`!>;v^wV|u zm{C7KUIG1a$&;z+^PNJ8f6cw$ChX?WLW?WC@?Sd3zr^Q*LA%f3e727)HhN5nm387l>fCXI1((zoL^Wts3zfo5f`^B z!cJ-fZR|!oyj@qB5~tiKT$R+NqJWpJB`s^XqOi#4JHK<0Oxr$6focFMgK%)B(Ix4m6r|pf(nm)YXYVZ1C-3rw%pY@$-eA4o% zT60?0g#A7_nWET(bz^)n!B?BkD2T7KFTv&=hiQ(DV6U2sy34m z>-Uh9j69sgQpt8;2o$cZ5O#6!++)4puqakoKIr6pivL+e$dYM6;eC|w{=Fgr!%Azh zRv(=Gd{gYt(-5PK9t#Weg5@qBRq&Lqi%kvf=LOe|!>TQRS^w;8JC0A4bl*X=AxN&_ z8L=wd)A$swt^WS=e}SHFf|XvVTUS;h(j?GrJOq0RobwTM3GckMiqz6e+}fd?vs`_k zc4M-5vtqMHc8w&8ygtGjVf#19F)Pn3IX^q2udhA9azZYT305cGP=I5HD8OFrZV*l? zRdSi2EJ`W@q_E6JYQp}3SEz5O=jGtQo$QNQKr-jaFi5 z;}k!hb>Al6UYEuQ-Yqo`xqgxqnXwW{2}of^e@2q}5f5QnFSgkX_@G(uD*lO23SBtA zMql?1R~~9Ek7J*2n9&s2l;pQFLD-3?2o%kH5EYS~At)b(qn>vv2m~0Rkyrsmcp2qX|6-Wi+Iv?OnpWqVlTHkGSN{zAMy@k1{>6;~v zPVW{TRbgtK?aQa&HxoKCLZ7p&J1a@}lsGe4sbhaPM_TczDjU(xCn(SSq=3R-hYG1M zF*B6~=yK-nPQQu=zj0B5`xwxpiaTX;vfdl-6~# zn5$k%@{~_ZwC>-3CR=cu|GeCn{a26MYD@Y$)OZ6?dRd%oPx>Cleu!hZ|4B!OONHsh z>0TUd0~~!iR?Quu!9D@<4@ihX#EPDtK2JU{J>Wztt$pGUT6IO}qxm!ugd0#vB^VV< zgCLw1<%e;5)Ri}h&!(~FDieDiCnc&uP7z5&2rHSR)A_GArEKo}QzO+|8*pLh#X>`Q z;Ul{_-0{?({TOWpX?dvtY<^+q^$A+xd_Q?PaP>KsKHH{-p41T({v#? z*fZdX*wQuWX*~b`-jC_@1G+vmc6W9ZLa)BowHR=dw%{>R((?B(>ab$(ULoM+Dq)h# zVGPJdpCMCikW^3AcoT(zQ}M?s&yQEXeG}DuYWe%VGA`czAQDNdnA)fxzU}u##O+^O z)jt)d&Kg`XPwXe}q&OQS4=1ZMUZ9qqMLtyIEPT!5cV|$OA-UUPs3W@BqaB+6LpsW` zaraJnNqnj}ns0czV{Ft(nAoFwWV8ddEve^s!|AJMI-L8ONMWbNI6)h~PR)vVUha0aB1VF`7k(Ot4(&B zoxskn5S)Hfjd-r+a(i3tK>E~=H~{^%w>#foy3%iStcH!SI7(U8O>M?O?5_Sip z>bIM#=9z!ft{4##VB~m{?N^OHns@p&Zd>VR85=3t{Ki&m#29u+R5Sz@0nF{#g+|o4Z^w zwbz{2i_70|qW%pUBhKU0f5Z@X@biTVH!a-ejq?+s;6wbi+{ZnOtHRstCUu230p`K@ zpyfleAYWg5YMOjfE-Y!9h&sZuy#^23QyMAGZ_|S`2xwfi<60n27P61UQyz89f=uef! z`GI|tbI!;)%zqF}-UC$@;p=%w3f6)>ndORx^$|m>r-z5Y5ik`t!&?0ju3pHUc^4Z9 zRXA@wNXKvKd9wL}Ys&{pm=ZoxonoE|^)EVQjrtu2xl@h?FM9-S3bY}C)rHgV88c{T z+HmdN&uJ)oRCV)?zpSr3!ct7Ufp@P~nn1+=Ij8dE5ed`1QcFcHumJLa%C`Tg)F7j= zYIg2Fc_oa#o26qQjDVAXoa)2L$-T%^`f}{_FIjEou#>YDOBPo5xzUeqQg?KDbU?4? zPh&-dD1Ig%hM?|;_UI@_unn-5B9&w^X+#No(+3OP^mCh?OLkf0f`#&tw@WP7!+<#} z8`u0tO*je~aumAvjqu*Rd&KFADR3vdtV7&%8LAkJDOV4C?SJ;iX2Cbapf37OoYcV5 z@KAtGUVed#O(QKeNxz~Z>*rdRD9dVP-nrbJgoZ;#zk7+AC0|C~>b%s;tRKeQP>B|F zO15{j(HSqbhOA=pY4F#My1LgF0Q?_tG~LTFyfHtzu)PPI)D8jr#~#5!;<>@AjLYPq zUp>7VJT7M(CJPlVw^_n&PlJe;Nm-=t9B&>QP@X!NHAuDkLsP*v*2aQQ^L#Lw?+6isFMh@g_${9q<$rylyh9Gtm&>PaeU`t$g)dmyU0@ zMn-n34N<*^zFQfR(U%hTIX<0P@2ux=vPIe zY;4Ay+o|BXW-f2O1N0t;Z~#J*-Uh6PW>d`K4#;`n^7}wqbGn%4W#ze-PiW|VW(($1 zmHnr-;)m;89{N6OW_HpH7ZWmq?~tiEWi`1ci4qvsf4-YRNd&3ft86NG)UtpC<;b>U z&SjvmR@BB#;kC!DtM~^qi%H6RN#R>Z2V$cKo!3A(IQdwD>lf34hlR+&bm->743^L{ zFB?Y8ORGa1Py3CBNbOq+X9e|3J(E&fecSLrsc!kjT-{?XgyTQ^P@n6G$*|+;-WUn@ z0=373s+USpk;_eN)VT(^#&IPzXeB#4smtW7K3#wI<$RqRIadVN?Wu0Sn}%qRIpwR2=_(zI-arSb{E4E20DhZ!(jRtfSc0 z%7L;AQ9fIybl1&#L7VRlmp?y3<;KK(cp^_hoM*RXT-odv;kZZ8vS5bC_> zvM)w~xV4g6oO&t>VN7OyCmy2C_aBOyiW_xcvV0~j3fyV0uC_azT;9e$gc0^hPKesy zOf!0DshnT3bcOkU#*)2h?73`67*)8s!QT!SUT@7F7pu8CQ}~`K_w+$0rZt!E!azLF zN1--3hVgvSASK+a$fNk)$m`0=YT;+-Oq5QV-RcxEL1{|*K5^#7_40LR#}JS|>Ib#U zv6GMbpPU)Je5H?F8ck-d(I2H$xVS%PSTZbhw7Re4vYPi?6qWG_H{h5U$0t(dX5E+p zhoq*gM2C9H&Cj(#>S{MgRk_uzqrP=^0;DNOvCnMY2P4>W?A)MS5${Dyqz+S=x!#O? zk^@4As!hYe_t|+%GpWbcI?)Ud^A6jkeD@02q!hp~x`g$h?wgg3M3d#K4RqCbI4G4Z zoK~ZV8u7d-H${|{9As+`h~5XF-0S994z#_#OF}eMyrm34G$ptQlKKuo{w@WsVbzf! zAZ|Py+MwW_?rZMa^$@gp7RY z^t;podgNAZC~}Yg&9ej(QxpO=vUH2LMx|?Fj`Fq{KdSEGwe%wvr~OdOVx3j zECG?|$KS9IzWb5{AVTF2_xY9VN5v(r8gWZsd4?{b#dDAlTjB^=if0s0h$6nJ@k25* znAvHZIA4BRA+@2-58RBe^hAmd|#r%$DApy@P6W6Sp>to7foFB))erO zC0rUJElxC73UB(*zTZEu>@XofEq?nBl26`%Tavr`7GkrMJ2i({e`k-0Cp z#MKKGWHf8$2otB>W)OQC)_Qt}RnK4VcnK?XcU<9tN3k_CSpYbvM{l>8t`Ea*1hW#> z0~?s{+qfjoZk*KQs<^lu*~(sTqLL>H3W0e<{_^TW7CF2l1h?U+3*gI*I~Yu3h07fT z{K$vs#kV|;e@EL}q%5H#e4`H93g?*9u6+A*?BqlnCIpLKP8!2$-v1y=0|E~ymNfn+ z4~Br@Megk%-O=m50Q){z*m1jK;K3ek6`QK)!cHQ|qGIRN{F`(d!N(h`296qnYgmG5 zNeBs@QBi9UIVy%yXwh9AHD&oINi`T$(b0;Ay`;^&wn1zPE-XsE{ZETqg`13sg_)U; zH!%efKYA!iU>z8I)T7GM?SJwYA9fm~DQ6~Fhx}r;icIB61%rrnUg{U8L;?joLvA`H z2%Okt13wkT%ohKsh|@OEnX`NhG<;}p7#yNdtN7~;56%jb9z?vza~hWjDPm)fs_t`K z_wLebuS46=PDRRe9Wuh31CP+X9el`XHomL9&HO|_>4OTJ*OZ#mtDu)9T`Zq@kcg0F z=X@}2IN$KdxNo{cD`MKvL~r&J&mo)YT5ZKi*?PW=L>T@u>@|?yRCse1qi}m%C!=bR zZQzGr8m|dCp6VS<5X~xfLmxX&wd51Kg95R0XnNMZPPAVwT>?}}v!P>bu$1}YsmUw7 z+kzY**}vWJpw*8f@MnzDuCt zNM#dCj9?RW2xyMH(+_>d`f=P*7B;}IdGGWj2T-IH-iR?KPIDyCUjJBb3s}Y9Y{clz zhMipXhg~mU{b}zG4D*nFO3XG?|M$Ra|7f8Be?8%G8WMyXc={!E);D*1+#Ej{PV6L26PW=g#@|Jn;ILfM1qa}7cI?gYC zxOL(WWEI-mB;~p(wqdcgTM?}u=-boe+cnDDy~~CLe_4iZ0O1B;@EisIGc}E)E_%Wk zc`x8}ofZSi)yoogbq*}UM1nj6r7>vy1?;m8xnf*Oy+^yOV0jRi%5IFk*ht$`_uP}S z4L7&7d!HhCK!&Vu6|r~Rj%>wu(DD=$ltdsU7GHj2JPM(qAqDxECNkut!&3tX>!W{N ziacUhtibUY8!6zJU@A! zh1tbQj{Wl&L(un)bA%*Ri3hSmQrLJl#^|S|>q9<~!f_(@r-tDm!g`}F)3F&C4g4Nv zXI$mkyq$P@c)LW?)SHY24yD`ehVoO3Ky_y`TDzrtgDvh^b~k^wu&edZ`>4Z)Q6Z&a zk;mt21LKqOm$tHeh{>hx&nE6C`q{U&;zS$3tX^$9amHVK0p$9DERMJgVpgVY$c zKT8%}7G)o(l&sWdq6pH)m|0jR%1|>{2SF`C`LLVc?>YKDn;NJNs$%|k%dVZz^$5eE z=M(q_6g#GznEw_vA>bNz4aK$)F7NK+_HMUE>tc)Ri{ajE3x-5ewgW52%UXP=ViWr< z_1hG-FZw)B6~j}lQWkVse+Tbb1_g+B=gmB#wAKYWn4?x8C9z{hY}M9TbSYG78ZhEr zDBDDUB_!6Ex59_xp1hYO_LH9(@ko7e3!0VASi@TXQwTU9Ct3)UqNq$2B@(OlLT14! zjq7bH8$;=a0ag#alRQ}HQ|S87EiE%(?~BL4jF{l4*eK<_lffC!tTKxCSSfa{Ida~Z zE|xsTyk&g=e_RsVIZSwt?VZG2KOr)<84M!TlepSmvY4!^BO$lR)Gtc3v<59SKa=7c zoRKTl&9O7eaxiLZNbk7ZZSTG%?Y7uJm1|Gltao3{Pijq)3`m%VomqrpaaB9T9@oCF zL|;*8fu4W7qn)2@ak-dHd3uVSpFccbKg3RUohR0HUmR4?XB(84PrCnZYx46yI!`$4 zzR2xvGPX5J)vh;barg5H@i{4W0!ZR_h}`}s5IZNj{8x)7dh2X=V+|5q=-WomeSp|} zz+Qe5Qdr7BlsGb7#!KV)(@uVuv@jXCrW5^lvbMIlu(j3y_u|00_NCnI)$k{tw7xMx zL0@$HHSl0K0;qYf_F@#y@Hbluobd{0e=L?e0=&hSg7&6+*PZQX*r_VZ@ z?={GxU2}){GtL0t!O=gLWci>g!{<{M=A~QZ$t()DS5C2tghW3)Zs$%<%GgWw@Wp9E zRA3n5w|h1M*Y`k4^v$1vsXwYXyBYCvL9GOSQes}^*r$(XDD%am-`9v=29XBMgxI7d zoa@cJX%`MhAY4N5nCJNJ+pZ=gVZQfV&c{>ZI5utC=YPS9us)_Dg#p04v|^ocmp6O# zz6da-#d#Wuq~b{9*E&#-PnIAyVj6(8VW~UF8iE@ti zKyI5kzk#;Gt*kapgg00RGF3PbjQFb5y}(5LE>mF26%I;!5) z!DK;!%C=g8joe;TZU__I=&^Oz`Ls(Z^RMDGa;sNM;r9B;TvWGDrJ^pDt8dn?YFax5N&jojXw{=R(%q(u> zS^U3s;W)_gA;>SMi_offim=4yiQ~>w@dx%CiYzGBzf2d}n}-Qi!0%nDaA_a9QuZhG zj9EFr;EC@-gO{mTkG{nUy+pm#4}C;j{LKucsWChz(`^UVr6mE;q&7vzh6|4#n9=%f zc0xWy4W)?2}=!>_2x+~fTX^Gq=)tJ$x+P9VF zJuG(4J+^;ESNhT#{S!Xiy9)TJBGeEcr>32sN5yHjeJq@)A9l^)$YOPG_l%t~G?~x$ z77%%CFuH(Qb8MD43TdbT=~_>B?V!t=1^^K=k~hBI&3Qfs)w{azr^ivYvbHYsOaG_e zKYa@9CN7Ty(=+XKw5}5ppq{!}g$mbas)cf9k85+S6f@jr#_VZW_x-{yQOC`2CzW*d zEQblH8XtYzNWX?ir};Nn1NwjhWjt>RHQ^LToSana2RnAfxDws% zpUGQe=i{a2tCPqWLDG59$AlzaHjzQY`K5Fm?(%e3I2}>x;2F}{W?F4ysbbae6F=a< zL-a*SpD;Xvhf7}yL`+P~<|UxPORJ_Nd=wHJ0WCGS7AjeU%(yo`qs?dZW%v(IB=V>R zDXclGKkF;IL}VWu1p-HLaPY(qy?=k@VD&)U+5*5Mcb12#I=-Qni ze8_vj`EqRbgcJ)AIqy3*LVT|fMe3%)JkdLd2APspy5L*y>}>im|IcA(M_Ud2lO9Xb zm}Lbm>TyL(|6v2=0spIMp(%ec&f*m^P-A`Sip6!+EqCSokw7&`r z{}|Opj>}6@eOATls`1%FyQ6z-c5%m;_S)w&vhX)cmTAN!IbzCq62Q~lHrnBh&Rr@8(*Y%K~+tL`lCHE?E^=;I=c{X|G^kNwt zAb!}_B$>-6{LnjhII~v2OIfrmaZ#r#agu#sSf90TSLC9DlU0=L6=Xb#^zQ%EabDWe zj6SjSJp>xY3;jpqZPT2gZz|&UTCD;^*r}>mAtZ^3>I4gsn zDPd)cC|=ZuJO2H8sKjec$WhUfJ3GkI8Fssy4-lt4GA6d?w!!$RN17(xH;cI2m6p(; z&5QoybmepV>D9!0F!d?#$?P6b{VC?tA|Ycu z(XzU~y>7rv^{&<}If+stw-io2B(B~>o$kcYp)Jb9{!WNi**WnD1GDOMb6+YDpdW2! zpQpvFRKy(}SzQ~~f{SC8fYu7l+%Uxe(ncr3Mf zdfAWyk*njr4O1%lza`VGRlyvve&1J}w^Q6e)Q||XT;SGC&(zf4z}=u0+yf~rq%*^q zx5I=Yioj;}fc&Kz@p~2RVskoI7t|Aj= z67JrCWlYbRj$sks*83A;{5*cQhg^1ATsz0?-G>Va|F~!SBGNltGFPil{`b0`rYl!|73pNx1_ ziAB9WJX2I(XpGE|Zkl@lgxA>8%=nDkcZ!cd-Q0=+OU|Fl%71hGSe#Lyq|kGE*R-Xs z(<1ja)nxOV1A{J-5-$_J43#SIXN;?>^-Fl#uT#uz(PDM7mX=|$-&0-&UJcH+<~fyx zKBS8B%q$^HG)`YyScT`ej3obH1LPyF*WzY&nR;{6@X@18$fvZvioS&5n|Ms1*e-~=NF?Q6Kb#m8MeSIl-k{4X zB}od>(6GMO^NK<#g00c5-Mj|WKU1zxyHeNv+zZ8K=UTrS&l?!9h^z+sDjSR{k<4#t!lzP&Hv&WD zn3F$9iQKn~;EAFGag+)T@Hu4&3;7f72?MOx<+|KyL8OVoTS4`EA$5_Wq#N zW}$pYb)$%gT*!%RQ=mvL+uo|Sf@Y1}d(F~sV-EyWoziSo*k^)6GwInYN;Ic)Tij(N zzCwfX{til_Cj&b&v`hZ7t&$dQEj~KP(}6*mfRUBnh4Z^E)w9$8)lh#ozDt$%o7i5& zvc|k-Uf5dCEmJ@43E|L#kPv{F)T(Jhe5$P_v3_mNQ_)lgje3gm!N;5j3q;wcNO&aw zYttdGc`|~WY2=ANnCew^hc@TBHJG_n_<|{dr`C79f^2q5W3^6u zul8aLvFY6Y2?v0se=*lV)c&7Z=E^kj_CZ0Kdcrh1AV}($Ds<()6G}?M8NjOWdO|Mr ziuWjYTsed+1l=?l?baZxU3$4dd3!Kk7i`3E2u!+$;3xSL=6MAgB_Hu~RXFE%y8<7# zXOPM^Ys-o^3X)YjE0Imog!V>lOZtmEHRHB<<#8Vs$9{Wdk-*r3dyBNqu(lx7fp(BTa>SfQx+k zCmac37joj1(?R&4DoVPv}G#f(VFlpTi_Pw@s^nw@?8$U{?lR%Gk%AxYsDf5w|4cO&9gMs@OIeLP$b-3+i846#NXTe&whX3>|TrH~3 zsn96n@9@?q=%{a{3-+i%s zF(-k|&JIEU7ozYXqfc0HJFp#kCG=s3665sKDF+GY=_)U}GQkj(4%~^CN~b8fXEQ36 zmM5J9369mAU+xORXX9@cH~Rwg5fCqQQ1K6+d+!uEh{X{EDUk2}c8R9g_L`) ze+VnH3uPWW^60W6)`&+q>r$sEf{IUwbd;=q-UC}^5b}0`Zvt65o<+d_uH+#eP-Ucn zSAHvkCP+DbD4wdT)1oJKh8bx3p%5JnGB~jH^Z+T)*3r!#Dys`PkB-)sZiTNfe~a0j zt$u0&eR1_tp$Z-9l38h`^30bbv0^)yq3sKhbj7E%vCncgz6G`$m8v&yJ-~J}ZTU7d z%}rqEg;O##7$0YjjWz;UaI|LA$XulhdS*tH1toEEzJ&#%9Oex3xguG_aZiLcIdqJl z_lS&AC+Ic(TNI#}AgY~cIjrhu^ymoi_YYU>VD$M&LCcFER#b#>5Yi}dmLjJZ<&Ktw zD5BomJL$UK*BUTF3abny9019-Gp9bwfy7(DmpVyxbrdkVG>9zCShylK|pc0%d#nmF$7zrP2`TDO}!b=`?Pi)9rpiGDYj zNK)ocYSSKJSO977x{AC#YpK$F&I(*OFgO29BK{=bY$n&}Q$M}SsdK!ucXcRgGq%(2 z7YBZN&rG}eUU>s90ZY63=g%MOFJO77P3g~&c_}O?3TQ#O4+?tJTKpc3BfG`LD7#772H2uVvzx8?{E9lAE3_Qc@TZSilFcuRj(JKHHT6iao4Wgx z6gl1$v>R=%_UFnnz0a7zMi)`m;H1BX9`_9mscDQ)jZ%VfvVvGWDaLp>bu5YPbT^r3 z$aqPy?;ZVM3BrV4dj;Weu*_K6TpP>JacWNr*30gvjvDdO9_4%YLd<}q1+MU$J=CCv^PMs^ z{`av_w0$L|gtWja)SH#W>dpK#m^VPCWWU4uAD)b3fLyM`L)nu8TGyNherSbEW@aWQ zyNj-!MRCDb^daCL9=Ehc?+~LbABk;Fdl9~v+R?*ewL@4`TSfVdTzm;qXO7K#xlsen zHYwNZ?Ah7cb+b?x`uJ6DsnfF0sr&MMkX>rIlX23Y|E=%awS5}<+qDKD9bXG5ws`eO zVz%v{i``FuS*xB2DkY7K2bs#&V;~+)5djT}BTHBFET7pDbwVoNumG46h%0tFN8vU> z;d(%#Tjqf_Qe86q_W~+TXV29bB$Do+_?_tsbIlXus--%@F=JfgXK}qDf#++HjDBdh z$7Q0H!w?d-x2%wewXzDMl32ymOx<=%XE02q_)MAn2XyJEGmV-D>ei@VqnIT2An~$U zwJ*N_)IVX!m#CS6K(}d3=MmuA-ic+#NlE?+yB?QF2o|%bRk*w|nz=V2V_y%nZW2Ze z-z_p=!N|yjVCK;KXTP8eK5{RWEPJ+1B`7AK*Ju4U^xuC_&MaX1&(GgT?_Aua4=$#u zNP#7(tPW*lGPtZ|dAkgxTZe`y!ziAq@|1iYU5A5T%m4|`Rp%Y}AdpJNK;@+$p27?l zon-neS4*ofBs9SD_|PwmjHhyEV{SYbk%Fk_SNY~h&0ab!^NT6{@Y(B~V|yTAqME9Y zb=IpvPFhNw%{!uIR$V&u=4vbmUc+D}B|yrO)4b$97boJB(;V`sNmg3+O~@p1DA=s& zY;L}*t)l}D(VHj&Zd|+Jg>mUW*?Js|@ta1U6t?TLQ8)`fxa$h#(p4c{+R@ zPL|F!I&R-o(TSbG($~obe=1RV{Lk%lA)Pxixn;M5gF@8Gq=i14zOL)SII9dX#I4Qj zy_RhrdQRW%@6pf^`1-YX3vRZy(B;MtHndN;G*rf;=<9Jv7ui0&J$2WI_cgH!IN5|Tn zE8_g>Ktw%FM=FgK4lS9Mk1pZ4z|cr>&FL5Zmc+=->eELUGIV0xDUi5*19{JZE-M6*G)4mlxMn@}8b{)Zj)gvLVx%_a!bj{45u zGGLq9x)TWc>bZI{$P)VC*;k)SU)y>kD#X>J8j>X7M#gfV zQ-da!JBZXE+xxfhAD*OgJB}h~4FJsqX{Tl&(ig&hT9xb`90va z1R`wD9=&{toM@d5L{kbpdVYRUMJY3nq76tzK@h{Cn{YstMa&XY%kq1rBYhG4k*gsj zUU-zIbV^4t0!B@E3CX)lsEm)+YwGg%yg2B*3`*Y$Y(L)~rn!?b4U8lYcFa70x@Q%a z^*ruxN^v?;&gdRTnF3%_N*Y{uY&Uj!oc8l(JKv(?6hpf1|CTxmvV1<_chRMMpb@w4 zXq)&Yjs#TpzP#eT2Ixdnh9MC-M;IQrSW7a{$AKQ_iYm(F8we;dM5;PvZJckmgkk+U z{G4(U2h;cc^OEDMhekc6J|taqx#Ny+ZkS*HR6&a+!U!$RBn%7=hu;*J7+2HvJc+ps z3dkW_saL}U-I>k>Jsc=IVVI|Lp>_FN_A<{vEF}{s|UwQhwYdJQ9q>2Xl{7tMJ0lHaFi> z`}%sB{tpG zhK|dNZ;~H>5Ky$Qvx=e!3^3AX{)S4Q zPi6t?0$WZ0vuw{TCE-!|1!fsO>-o1A65U0r)H$0i!yj&X-WD0oTgg|>yL6zf80c(VCdGUgvYW@J;RYV zXlr;_D%?>%-z}*b>Fu!kMI>4XK?~$H=xT82z{wb0k0_JP2h{nM2cbleFRUGTV<)xd zKm@yi@98BY3I}{lhmS{)gNL_wke^5Q=6YnJP8RSNMx(5Gy8usLEn&|IUA;KS$RQgA zJN&ht0YFz=?kGAF5IkVL(NOK~YN_#Iqq@2z{zSIit9R*@PA_rzLGu;U^Q zlSD?Kr5V;p;U4C|s0vjuO-Hkg6iBEPxAL$o>SZ*zUksE&{eV!B*NR0U_|5f34a%U7 z;JXnfedOwjzB}oAMtzZ+w9D0b|JQk(DDV-}jS>X{3ZZ-cK@NT*%nE0ltM%Kyrzg|0 zs_(5eWH@>6ic3h;e8D=T8>p6B(GslW`_<4wtyG{^zXLZ}o!_lJb(OVz8Y^V;^tF6f z^}jNnKEx2>Lp`P9&W8Q>N3l}2T z-Vd1-**BoYrTlzZ^}S_tN7g7X%G}%%9tFV!eYUT3cB@8Z_!cWetikj3vp#tqa%P|B z*pNcs=N6yv4MFdMiZj@d5D+}RDf~U8ILfqKyt)Buqfr5rQ!@C@!D8n`-Qh!lPZCyR zh3%0#8bsh#$+zHxa3GVx=f3iv*`0hgjc0UyPoX3P(c$b-1cvQvb8Xd6iorH(5u(iS z7bOT!S{fLdhpfr_&ew*S{~7n@Mlb%&%5mz=iVX!hQGklfYlSvehpiogNU13D`}4%j zVnEb$(N?yNWMI$55-X^G3J33ZH5XLIN7?!Tk%2@+9+ie?4(C8??JnB{1hzU{GLQZm zbbEtxNG6Spc*2!L=zw0gHrK1-PiPYE428ArUMidsuYg3hVlph&nYXAi`|^YA~ieJP37)vD6~0n?Z& zv;kG5AY1#a0-~bU2u$Dz&^ujNfn3^@rOHp3IM=Q)v<-e6BN+pKW{FuMNW@DPDV@zu z{n~y^o;YwSW;mMe-UiBR5KhP$NJjAxB{g|NgRK>!1F>2uAEp3bzz|`EKTjlJLEb8h z7bca!#v{Rc=WkFlt93FoAakhA7RjRJ;wuR_8S@-l_E4PU-K}44j{^gbmP(}I;@;y} z;~y*M$^-H}pI+CNXp0$G7}|UFNHdO zIzub&%=@`$iuqEvg3FQO)r4jguk9u_NX;p3P2QwjUr1ewT!urdosDrQ!&Fs=*7?xB zuy{$WWH%Rv+qM#{^L{1{7*T9nGN$NOOmM@`QS!pAUy~C7-v-Qq7Yd1d{1`+wW)n@} z%c8{sVi4J|WFL2 z5<18hhNWFioNnNe#%e$vaU)Bl6CDnO>aEAO?4>3ffy9HoCYqsmQgnquBhpwdi!23k zX4)WSg;cIiu|Sm^_-fqA9$6;kyb@D~hAmd#;j19Y1humR+afhO_T&bmD$Q@9b4mYc zzrNO+aK2IPC%b~ekciQ?6eh*I?jUb~HE6OteY@0p?PWN&0m9`q?Il@&?B1Fw<=LA$ zIyyam6Frk{jW6?L8BvYR;GX_PdGABOwlI`w84eg4ZROjWy9jAZv43E3#2=HVPO?!6 zk0w6fMTT$~xNgs-)>!CPKALDepxLZ5BC)lC1>Vz$_AWt{i$*b>z~L*YMmC7b#Zjis zuRZfXtqK~xlB4!7FvLe1r%2hDJ&KI>IqfbeskF}(!44Qo*K!#Ie6jdVxgvS_vK#4r zid5Ep!$i$yZyStcLHSCin4Xc5QAnK*)pCXA)0`Z@jNnCA!L6Clx#}n7Z|$SjR_iT# z!)z?9S>T4y5~z zXi3u73^>H4gwzf)xgDFY@N;aze8tWf6;o^Sv+~Iji18;Ym$q^GJe^(=WQB;YH3z*m z4D{pCq$kO9FoHk@09=C0f0A3DR3oey52dhc+*ag5*M3J~%7-D`&bJ)(^`7zrK+ARb zZ4->MRBMJQGhhO^T10!xOq46a8?!M$vn@xeRjcD?NuNq{7iN-TOwdpUs;j0Kq;i~Q z%?UEWaK}E`rocGai}c+)6pOHy^h2x0!QLX1&}g3@?nPuX3K-`MnnOC_uRXl!Neq}& zDoH}%1zfV9o3Jfj)5(!|y$63ehtw~xg1xI-Ei};-Vm~}Kj3 zNGkRmQthv?%j5+)>ED?M)a0RSOULIUU$z65J;j7JyBuA_9+i>Kg{CR3M~<_Czd3y5 z>a0pZ2QvbK9Vf(kq1RKmDk|p3STL{b_aFhwJGTnst7A;r$=gwnKiAP>NY{AKpvdNt z%5gSypOR=i%8=G|_4fM!HG}h)<$Pa4owDb-EYP}sk#n@w+Qn<>Wp%5BJ&F~3SPmaJ zwV`66M$&ho=kEd~uRf!n(_YB92kGc7n%el0cb7SI@C8z@f6>GMF916Ib z#6P7KSSaQ)mk5-BexE?uJ|Mu+GFH*D87UneYC?~0JHj@hj7R~cMb5?m_msOIMowH1 zzbU?{CRD{&`R}EA#n^`w^YOPL{@zH~CT4rn&*`|;0yTR9fDfJp#i0uEjQ?9iUW(qC zVJg~95>yyL_IfJ#02J}L{oTR8Yk$4uU$w#64m?Ou9T%%te&1!2(r>UU79%0EOMw&s zruG!--vWdd>sD$>)<7lEgqiz0$v^_k8Cr=9uJr2X4e-palYh|;hp@UdpUhXb!BNzb zgK41uH1&__b4pb|oQOW6j{6K;r*=wo5>iem(}zSGKLP+2>Qbt&`JyG0kKKvTCV-#o zN~ibo$AT2&p3Gq*_c!BgLZ)J%cL&AXO?b4&gUsV%ZsNE$@;+RF{Gn1G!cbU9+kcSF z-`zu(j&@(oB2|@@t*@oGC%vl<_KCLle8HukKTTOSgP^lPbL2K6KLOO7B~V{);;SfPWp0 zi|3fL{4$-}8bctl#ny%rz&BUbpU3GB(Sze}{hQRA4ut_G@eA{1T0I}-*+dc>FGDyI zYl*${kxsP^(DxOa7#q>NdTYHw`AKWH-KDZO?ILMGw$~n(mT~!ZDM{3_sP)W>CA!!O z-#Yr_&S%V{5g#gqE1`G5duyDk-k18*jF>J9ywvQ9U+&3bu~?f@Q4BxmQy%Id5th%#mf@w`SCLU+M{0vM(?#o8ScFGtZ#{>@J(z;RqRDCJpeRBO%_0rEsp ztgg&$n5I|K?qoO!P6-xbiXu$PoZLJ61J07x&9c~9vuO6wjG6vtr8%NEnH}G zv(XR1im*b}Kl8`sQ`=Pa$bCh96HYGIch7%@FRFe8!9hqy^Rv!{GHf7J_O&o5db-Gj zW`(|EA#XcjnHMIcyuMPpHOY;eLk3dNF$i&C=jV-nG^8ffIyVpwUJ>VwX|cYG62n@q z7k$H?$Dm?zZg`MuXilKlEQqtUKWNIt3-5j^%@HD2RzupvR8*SrJ(lYTv@wt4pI#5+ z5r7=pn)fOC^yHvp{@*3l(8s~Tu5bM+%(9;gJ3*2ybnfXSk*t@Kx5W~k+?=$UK1auG zCv!JtTqAumw8Hs*wl4Bp#u?=!6BzY3J71|!ey%PUlb>POiYl055w;`PV?Oj&18f8x z1~4A3QzetW*<$09R$a~i+p1-jTs9K2S0NzE1;#_C8|8Qrg|!oDB_{u&djW&)~rXLKIc@6+F#rpvQc^Pz#S225q0gY%Un z0#PJ*++@B|E(HvBqYsUxirmK2eM?FA4aD!P5XrBZ;Z^#9aXc;m+={ z#4p7mL{=%NC`fgqC2TzS;=C7XvEG0w#zxBq;sRV9TuBh7bg39go`G1=drHOKD=mXb ze$4P`L=5;%nX z3rOHhon?1&Od71O@fYX`12Z?;Q7DYgir8D5__vsNL299(x6nPuQ=;=v1c>LG#kS>1+zLuUSD-C7N*oZ%auSV** z4!LKFuM~{VNpPO4ZOLj_Y5F&!4q=*H-<=Z!P!ZDsK1~yH7qEZ+Jm`}Q<~8~1;yR0T zzP*v`h-0{&IL{*z=%+@lmW3$kFsr;my-?JGXydvKL(7V)Af^ZxrYAQ!81W@aD#zR& z|DOfe`S{2NyA&yN$=O97`^DC#G2GIWmP z9p3LH2oQ|;iO8^~BBjE$c{*H6hNSKmLhoMQmhDaTvLc$BrCpZ9ep*qcDBaeOl*zfj zk$kVMHXT#en;0&WYapIl897hh1A=}&k=x|)kv*kX-=$_5>Yp87IvuzFs@F&+@7mZO zwav`jC4Q-&3fum@vp+mDL;Ki*1sG1x9g)iJNy~iXgGi3ryIUW-5*oOuO8WawR*aCO zA#{)GiYB`Z*6Ovc`;V*Dr4_wq-Xu+!i@SOKIh_ac_T}kU!HzkF)FoMio?$j8c8~@n zZP-KJmM4xuGY1ZP`mXz|w!znwc@wXl`m{hjJPN~Ev2J(Y-^I349iDMUHN#Ls*#GvN z*hMGwcAF?#yyn8?J|&f(KjAo09jbJvM5T01EuA3oAIuYWj)SAFrct4xdWCS&+pDjH zd$@as@=;x=)^_;nphLdh?d2XgbY~in>r_l_ z#Umx3wfDmzaI~=E9VjT-_!%HqkDxPPVKLp^WigIKY!!#bN6YKg`7!uFTKHLPkZ}v^ zGxNJ8xEo_im3YjM7=&r?#X(>(=@~Qv5W2B*dwP!q)0Fh%2cMa=FRr{c(Wc(%Aa;<*?UP6U{QghUw;*m%YD z?Cm#memQi_t_^{l=@^-Y(%#0dttfdi0W>W`F$s)|QfJd5UKaUb$%3-(qvLOiq_t&y zi@8d~*M(K)IlAF)S_c?H+qOLlrA6Pa#K}uQ9C#P&;SPSo7YkAo$XVx7`Xs#v3@SYYNY{fOHS{-5}=bPgNuP+cP@0txjTYbZD02J!;ymcSA2F-G!r^P1ZaAK(>ySuBqo4r(Np zj)mEn&-;FJmfC=cLdJ_PXJ8$n9o-LaDNU*Xg8ovulLX144@VoMSb+ z+PAlRQSl4gE>{~A4Tl;R3msB;tvqUDX^0r8OW-Xk)19w6ly>3?;)5W!oZ zYViE{WHRk4_WO9q+PS(qX$fw&1AnFH$HCXXNKi9QXZKF|r$%czn$*;ofTPS;CHsnW z+YwFBNK~=E*~8;}pt$;m>8BrcrTVX-lB>eAthwIJwY3Wx@3|7rvqNfx7p!P^xxslX zd7dhRL6CgeeqtFV)o(lOl(phQg7t_CWTs{?$2_Zr~6{Wv8J z{fevVC=5ICYExX^W1+?6D-imNdlr#N+1{j0ci~D$-t6x+2enfJL$byc5vMeBzm#*# zDOPZA+O4IQIS&T#G9VB8davY7Y)^Qh*u*ylQt6OXGlYTiT z9XWHBYmQGsS`MG@nIiV0EzesD?RIa6KHme|8|`fml7u*QiSm{Zbd6K?s%58s2{nZu z_@6Gzfg(x4e`J=kwS><-Z$C8aMJBbO2DYPoe51lXD~(BI(KJ8(Rd+;_n9%M$VJ)ID z4if(XH0w~{V(?!9vAon8a?4o=QJA)}Cyx@RDS93?O6J~DNy(4cn6`p`jEjpat>6+D z6db2sq25dRDhwL!M&04Bto_@<DM7*xv62$F^R8aE`OzR}A&Dw; z0p}e-{c9T#NBS+wPq!piO$Zu7-kXeYUKMDRY~avbB+M~{fP5)W_E!9 z8lv3cdX8ubC0)_e=k}d-_+a0QB=LG8?DI^xvbD+We|HEIW zRk@gH#WQSpTL@m0XF1abb>NZU692SzUCG&6vg|R>$5s+Ke-Tf^GIfpyFP#kZc6{&RV7f(Go1V_xy>s>AQ%$opm(K}pF)|6z zJE@AZ1h}gC4M^;$)4S|*ZE(Ys-D&d3rT<)p<>cPU_HS2s$83&|t5kCnk~in^-#>Bx z-QQI@XZq@AS?bV%Qyp2Zn#RNl)zOIn!Lji&k8qnUOb{XodlLgeJ%h)NWPjWx|NK(4#*~t}Zt8j+lFO zQCelCMdvT>@H(CT9rpn&kb3Z&v%Bfp~Gnx`lQ&Kd(B0V$3r=_N6I_A&J z327+89)(WVrsS`d%UPxTXQl;7&F40OqM=VfXiQa|hjKO}@bYXvod1_~+)8x|jfzsr z>TkESfw=R8C*0C5tuZ0GAN!K5tzuGK&|rYo>M7&W7KZVEo~k ztqS{{*!a_J_5I@k&V=F%elTHS;oO{@s5xK{ykVhU60bO?3a9*B?Kcn=#5zEk-363O zvW-pHoaHneB3w&K8#)?2zC63vXZ4bGath!ZH2C|4wIcn5%SYS0m|W%PjUy{*E=7gq zrKK=-$U9ukXkaFt_3mh-%)mbzhM9bB4v;?VZ2r)8;&aa2lep;p2uM}k5R9Aoe#*1T zm-ftD3tWfKoBw@5GjVdoZbVmluo!0+2DBgSZ32*f_OazptGt_}Q^JMQj1i&0o+*E}lIDzwwz`4dZv{5NmyJof0 zl_HXWW=QD1Q>~1u`mN^2bD4f^%4cN|$P^Pz5J{%9(x|kdNwK-F1`K*7vo$Hw$Pw5& zH#eg2=oj+MS?BwcE5H*sqL|oV$N2UMmtPfd% z-#+T^(UOx=C-e-#lUQg@YpC;|l@;utUxe4bC)Y0w;&fSWIG0|ZK znl0IT+R+ZR9U!O0r(R?WsRhDwY)ZvyElIjl8d$^8hyAU1tfn{T=K%o>fDCZ+<|>AA zEi!-s-?{2N%;_wB-5J0>qah6Ob4U{PR^-kikV^jS=eydf%UNl!t_Y~A6+cbZ0Xh%& z%%#AsBI(Bmp^?JcN5B35QjWjC3Y_lAx=4Ph_~0=eX!^z~)0%GmLGr90v^ZXI)U2#1 zghS*H;cRb|9O5sk+Y1iF0N%_X}46uPeHDp*^RJ&f5MQl0)4{v2BTwKA^f zwD}LL^4c@Nl{W(MX^tW?Xb8q3VxdkLVgOAAElGiBaH8&~mle!8x9ta3g>GyNW{)dW z+K;z$cwCbaN9#!zk(k5Q5gWAgw^0QginuDK7LS$kb>dsTFnqCNkJ4qxaK1@)`dBK; zcaopeibvdvOZ)XbOc$>SVC-R}CYkGazQCplF#f&;hFl;!HCcak_Z%z`;-AVgLu448@m9 zlDBq;fMTKO-{nP)|BaBU%-!_(YoJj5aP9J>zmujIasUpT=&}3v%lgp-u((@4-F-!s zrf5R9;P4CqdQ{D(m8qFa&R6^W?|el(r!(qDVG=wsEh^1dEc7yiF;M-&l*t3dyUPum zlNZAL!onCpAYo(?+D@-EOF;c1kXmS^2@%=? zVBEbwja8KA2x5;%L_JW;uw8$`a__3y$gaom4s%CZ_OUuZQ%HoiX&FLZic}Q-Wo`~T zJtx}XLHcj(28JuPYi&d1A0=*P`$02i-=m>&=F}Y(M9dTEUlugc?H+{Cz^! zr>B?GuBt$lVr3BjIp>$FsVVg)0#b}Hqav&S0BsjHq{ZLrWiSA6Edo<={K^CQp0$=* zy8!>}z9HG^FGEZJeK6F!_*BXvP&rrabmwzOQ|Xm>ls3fF^CBF}g~sAlAwItvcgd&w z$0~bkA5q~4qa_lqu7qtv4;D~9yTkn*7SD5k+@k5z3kDQMmva1hV*-6CD>u4~IF7^x z*X=!PPeSS^oq?FdFFv@@Ta7na;8ImpeIVsaQFdkk`!sLM&l4QP=LJ@Ep0IFea>fL3 zi1a~L(u;Q80wRpqWZ(8n2IYG)ALo#!cXno{DM`7FsI=Ku+% zM&L!?N$cbXw|>f+-v#FZzkWQI^$1@LCiF{8o%%#e*RcsU(Ej+Dt}t*CEyLJbAJ&QGzILb44B_nWNiZ(S39_Y-Kk_)m()*K)x$dfwlhM4p5Df@%btugeAQ;8j7o)*x0;qK94uJ zz}%WQlA7dC>2PG{vK!Juy1q*ag_WC^NddT8&GSrPrH9@_Ld|MTQL9(bh1|9yb>{Ii zd2Xm;oPAEN{pk43ZvzigYhfG;^@qnNfj34c$H@_=QRDI^@tZ}8O1FUGVpho1PoY)C zvvy6PqrLf!_T@c?shpR7efCT1(6>>^?FTCQ#Iz^L$`i06mCJ|TT5(+h$IJV}U)H09 zLk*NB$AmD(H`x=UC>ocI@330^yfE-R>a}{b|5~G?<{c&-ly_F9Nh9g=LAKB1R2fx! z`FW2Hm`^Pa8qHEnf5YP#^UcG`yjS}xlKGKObhADCqp7A4m%TC4iUMg9%IzuTJI3!q zs#rce-cyHjURwWS$It#xPoNn%cr7=aq^h5!9{icjnmVCSsqzwwiyH@VES$wPqgm^X z+b6o504*vv>SQ$}M29Ki33SVSTS!rt6`r9an)KT5ykqR)aTGy}24jzne@Z}It98RN zKO#x>R?T`eO4`@Zb^RD zT(ONo!f=qP24EtoEnUS{RoI%@6uhn~=AQ5;{nGRe_8D(9S2J@uDMOS6hX5IuSbur6r@O%msWeP^d@e1IL#8YTAUYg=cy_^aq#$Y ziYEfvY21RZE|Jg$0cz5cF7CYBx=Kd*pYF5`d!6?~-}@1SF%9;MdIo4!E5rmfJ8jm+buoMG|EA*dd|rfz>+%O2*Ys6RTP2Lc`F|6d8g63 zYuIF{fX<+oS^y0U46K)S!!hpcdFGi8U@p7%b5YKHao-qyY9Hd1=y~?r86Rl^ppQ`r zw;>VhNW@CKHjg%-Dc4ac=q+vozcE;4_(p?cToXHJ3rKMW1P{6sxh?E~YxRK^LlK3f z;BVX%n&36jKeI=;zJ~#WL3%=_y!Z4U)@Wyl^Zvu@Kt#J5<;L7s$yr2x}ax4<)iPs_C7V%tR*0pz$U|{qr4Gndt^*BWVE-qxaa( z{`@`b)cND0=ubqA8x8mvxhf7yJX|a>J03QM-=4iPmh5@bz~E4ryd$OA8B6k&=KzvW^{FlVVdx0 z-K)FqU~R8?@2IBTP%zdF_7x-Gm3>p*s0OYNLTB%-U?G&Bu+#_cwierA_0hW?BQK;@ zE;gy^hx)ElS4W+$7wM&BIx9F~0`2SNmF*8)Y*nMp0qBR5&hZ0Ki#=iJFOXVfKU3kx%$&WyZ{QXwOtXk&gy zTuyU;_RoWFy~uY46XK448V9yAZm`uq%P>L1V=9mda$zQr!GZ5}YyY_x-ngW?|8Yc6 z41m?+zE3;duo_Q6p+QW*6rFqqfdKyP>Jghx0RhvuLU(?5mlz4J`TP|`{9dw3*<(P+ z+?IvY;`pRF)c0sM1;p3Tb07^SkeA8zyDJ70vTykKAbF_YFwr^v&sPeNFY{YqOoTX? zjVGgUC;%!m7i58=Q7`94y-r3GwR-j`c_C4LC$sb0GfuwS)8SoK>A(X75MLTp&qC1S zUldS{_scQyaIuZ%gY^>|5Cp7&F@AG_@tfPf&A3;=A%A~0n7(Qyjw_rV4V)gQN?h7Y z{F8fp()=lG-5bi>Z){na*S%jxy?qROmU(%dLoGn0Z z(q6-VPK-5O3)V9Al+T3KV2V4jpAXXl1!{#T($Zq7akeI7hn& z=#yxDvQ^~+tMHsXV%UJnf}(Sds*# zSmoT2uzoxVn8Kdae7h8Q>j7u3>YE;zIb^G{QZMD?uX@7lq;U3M^dp3NOoon>t*m0o8exDCzqanv8bF3U-~;ZI{F0& zWYeRX72a=)*iipV1Msbq>1S8YyxssahHf4$Jy$>8_`P`BichD?13%5!azXn85tADF z`F^^#OKXSTeZ02DW6(z$$Uz-4K&8&1qzY%-d_u;QYB<5b?&s4fmQ8jjh?;m~DuySaX+3{1UtH04#y?Fk#9(fZ#N>Wwo zk`VVSft%g5tu()Hc`H)&@0{#FX{WvF=Wtu?cc*`rEP7|A$4H(W&aQ~0IWe~Q>7WTH zD3>*H=7Hap1mzbt98wRvEN|w#{LAt83|&})@ToOi{bhdKG2h&hSAcgJl26BK=3v!u zZ)5uR+THqkmI*$irXF$A+3P?%WVh#B%$Tbe>Q@WaxJ?yNE@v}t6CJv;(As)3C*7>7 zuAXLaGgn$w{TJEa#dU9Mb7`|cx*6CSwa-8u3)8HwZ;RyC=X*Z`fl%)<95mu(3{lr> zoSY*C%R9Pm4qc}0boER0?$Jh<5?zQxb)9;34?k#p-WekoqkYFyG)tZg#R)@e&lOLJlILG6t_u>+@Nr&>`usUaFEkcfiqA2i zTln0kCcaH6ome*wP`#x2|5*TZp)qZAUbXj)wjJKg%*X3dct)9yjLyO+?#6W6Wxu{g z+TXM?t84AZ!wy}}XK^$8PDi^6QyWan8fRz1ayWl>tIpvL@c7aSHoXs1ZrYMJV^{>o z6Ax;yTtMHsM?>;sTmKf_t?6idZQ{Vdakt1UTi5YHb_bTfjwo(ubpT?5sc%AS;(}@iLLu z1;#{mJ)0X}GdC10?Lw&V<{+69HVqYqNjv0?6KP>fPoK%Aswy?;lMO72lGHhrIH<_h z{_oNR9mjw+vo$CwxM~qnlK5Ho#T)Tak$(>BuG79{slm#uAV%LOBWkKjR+q{zxOBj{ z7Ok}V*ZYPN8>S}^(L9sTvJ{QJ){=hDgVlD(A%y}9(){{F#)epkqSo--+m z!#}j`u-`ZA_;5<9s`sf29F7<+M@u~mxeEn9o(zx4_gwLAQw*fZ8Hj#D_I}?3@WQ2~ zv-jbyy{cLnyk?{Cy9%(zrKQRn*cJ!UAm&Y?2;2DrA#OD~Bh=E<+7JIVikOKuXGBmw zK!w{Le6v?qyTyRncHs(jgzih|KF`@0p*;&4j)z;?OtGs*dw*;qk!**P81ATC)V<^V z1K8T8-Th*|bVJ%3gv|>stEs8E3*Nicd}Sq4X?xDs*>xQ8n{dJX<3!W0{pp({()AzNalnm~F~IWV zxr|34Gh^ki$MaduCt37@s+8rUouhxz+s8gp+p8-Ik0yaitJ~>8$))4+90S#a&(PK2 zvJYkRB113PM@FQn(kV!MJ^%TXCK7l;d4N)x+Z6!jjW-7VzjOgYysV9sH-N;KtO^rI+i({zyQ~PIksT3GS0eAIX+8pRoUr{!=sG5*JRFf#C$Ef}( z_;{hCL#7z)ta{%@x-7v&g!JccI7F1#zpS_%tP-aQSTC=(&mSMe%#T5Ft8BCj7vFu-v{2zGB_kp(uxeYAT7L140N1a?Ah1w zlFZQqB?pjeS%Zd2nC5hto$0VKEG%}!%#7#qWe6bvGPYXxzwJ$Fd09g~R)ENAd)bVl zY{~zpRvsn_G_CrS=;a8Q4KDkiORnqFMg**#ZT=-nkxxR;RsnC~UEWUFYxH~*Qd8R1 z+r~ePAKQzAKMMLz>*(fpwRJgH(6@JsB+Y>6dFvf$W#P(4$4{^JpTnZ&@UUK`627^r z0CP_l(&nvK5hBuOF|5p;GV++9v8AOsT{Gj5=iN)AVPCKW%w+NYAEL>(wj6<@{fxqw^W_ zy|YJ0k>qAg)@!}XTWe_tUZr?h9i^DkE7JCp+8JWTfk7dAzjx5`%+46rAR59KXZkVz z-meuBeYCM6OIB}emA43c*3O*2wZbE_m^R%QebjksWH^^LraqN?uR8h2` z#Ym5(LUwkVOVDu-34?jj0`nxEnL{D~@ER<(>W7Ydz$#_8_sa+t07~cFzaPo}?6ve) zC*`Z@+fHw}a4=C0f=%lU(0thBT2PS}gaSzpczI7bTc67Tvsj9rK~uByVcP6x}jfdIj`aOs`fR?Q599ThSHZda-SPbTX&<(f0S3)jFPUt_5J; z2DF?h(7$&!X!HjS+;mCY$!Gm(KqvmYqPH=c3vFO4p_fTlQtV3SfA?drQPHqCb##GN zq_gz=)ura0tujp>Q8bOYolGC#YRj_8!Vczljj*%_3n`R7S{A=>gvxTbD(&t4P&+Iz zJb1%teYldGQ|A=;8(G8wP=OuF<@O!R@xd_D>$PWEKbcTy{Wavr`cf|CCg-`SC_f$D zK@q|=`MSCySq`qAGxNeC?7;g~-T+W_YfeAj^EqxXzmjnNER|tD=h8F3%t8#N1R!7u z8aUsQ{vfzJ+tJkVyCadV3H?gk_|m+&azB*7t@9zE!o#Cy-|6-4;mpFJPW@1}KAo}3 zyev(cFZc0bw*uhI@sjUJ6e5rSXD-TlX!MtW;N^Gg|F%cVk^Y>fJ-!n^D9W`SJd9h% z(?vG*x1`Y=MxA`P0O@#;(JkqZG|P7CK&SRQd{G2TN#d+e$_C%GY#RsEUaHW<`oqFZ zyR^}OVf}UQ^E&kHr_$)r45?ftl!585#^7V$=;n&$v;!BzQC1gC*gZ;mZ@Eu)dZ~HC z`_j~*)M_N5MtF}%qbc8B+*}Id0XIpsz+&!09Lx3E?p>LCpDgel>9w4BuP$YEhdCQ{ ze%PxxiSZ9kE{bREc9n?$w-DvEU&ZSLF#cXF*Ll1#+FY`$bT;$C8O6I&bpjvb1^~~* z{>B5DtEgFnB0`Y)ig}6?j^AZkhz=yj!FR5P`1{w9NykSAiP_n`kbCv@!sdf)rmR2p zhGEVO?`nsu$B-Y)@2PnQnGJ`%?lkKI-^2(OY>PxMQN1be*Uy0Nc(~&^Zo^4xmy(3l z!UOl6e7;?RGO8ahu~d>b7m6l&E6IO73V!^%)EIJ1x!_6E(tv2jB-J=(h!6qLA?$Jt zm+0+M9R*~WXB$cs!7QNjLCaEpH}EZR2~9W~nS0YvQWMg@a1+N+E2HzpEJF{9fVC*I zj3FsV2VE}j%!g@}r&~!()`LFTK~(G%!|%8I9cgc;!z%8!$jY@*`T;j=oTALKy~OUw!)$D3u^Oyvtt-<3 z5hNCUNE%joBTsvFOMPd#95ZA%w)WmSAwFDa)y{g35P3K~WT^0Xu7AYF@5m{-x$EYN zS4kTFz{CbcyWdcIOTZqmWzzrU{nK5bJ5pgMTtP~7aRhNK3(dV=@21>Qsw^#*y6efs z&;m2X5N_rS*aP!FPzqW4tGpt(@|;B%B6``tRw3!TF^~FN^#mYE5#=8aSaKB%ws#H! zzK-^*gglyPSZ#5{4#{5MYEyc@;&CGj>ljmIO5JaYFZfge$fzFHM6OTAoc|Lx`+KK$ z$UX7f>F9uZHS>XHAwGPaoU3CDWqd2WrKoAHqGeDyQkkXW@f3ujsJywpJ3?FNjlJ>O zwI~RJ3Ok96R?e;)vvt+C;@v)IEO!}wAHA;|y~yelsW!s{sluL7k6e$kP0v|x4x|Sg z-&teTfEOKgJl`uo0)i*&G{=^n$T~t2mxu*kSH*nRZHnqg_S?*WrF=Ym2KQyRvNmi@5}f5MqEU-fjx;bXb6H5 zA5d3um8v}i#MKRt3+Cnq)WYs9JgvDy;|2LqUQ(&n?mdzUIw~Nt{}UT6$BXGZ$h4& zNtAT2w<)|E3kMvHs8XVp{(@(m+}VxIl3XiSBMwfpYbB|E8DdyCb%{!)xv7%Fwwayv zJ+;~OYdyWP>NZn}ByJ6Qy4A?#pBA8hlw_vUgY%?fOA z_j%+aMhyJ6?zoT;{_-O+iy8RamKz$Pj;-;9of0JwE>A)buh6}=Thvd`Q=4_kCVZn+HrkbxEs9B z-c=Pp^3Wwr$2znjM@agqwS9@zQc3bQSt~#iv$r>R>>*Fs{T~MNP|VsyCEw5`N>Ym>w`q!#_IoRtwqRueH7g z(tZ0a{Bv~Z(U|9?*XNDcn1HnwckjvQ(>R}~Ib!Gk(R7~SY`*Uw4mF~bXq6Z>+uE}> ztpb7^d#pb1m|GtEN^?MsKCJ+BdkfDq^8^GmN^VvylNPSA7Xkp4>jSrs=Bu<$ zr_Xn`;u-&_wbQvt{d*BM@*i35JFA>&+*GlDw0?C*Cw31rk;sutw~E z78c@Gt}o^D3-{EV!H*x&I<}rpw2o|CYNbxi@bz!c9UTGtZ2J8kI!cp=XVLGmF{_B( zQqs-M(~bgQB+u8FE5)v&R}2w@4kCq5`0Z}HLK&V&%3X5)kH@d{qme;) zIPuQOX8c-?m(4ftdPOrYtmVVQ(`HeR_YvD$@omiWziLU`MUZxV$@ZTvfp?a6MNqH-H8J zIA(pi`3eJVHhqk5?Ul~Cq-IKdlz_+&v1tDzr|@uQnuq#@sbdk9^_5#=Zh6xUK^Ls) zK!gvX#9UyB-7{Uv4kAcpB#E(#R>=!KL+mT)Y_`9d#`Gw>BGWi4OXf0bsmX50(vGR-AK?AWD zoPEsG2c9gxK8=qTO#ZH_Kj3dfzmF#oJXf=o7=(WRXUJ{}TvdH^4Iy-YXlOy&l4aK- z52u@PQe7$X`$NC;0G#SHgJ_{UcE((=9^aB%HujP(ck4b7 zIXyo1EmGBcm6b`Sf=jH7VCRCJ2nD>pwxDSa2K^e#6_ivY6aiD4g*?ojBxO(cJ()_pJ%1vGIX$*c@_ zDJ+P`Bu~w(P<~#t>`SlH_D>rDdwbS1OM#CV*H;GmDa7P+z~Nw7H5O6xBx@D4xfMGnU2>bc{;6#&{t}l*)wEv71fkIsgaP3zP{~+_akF9Rv zX|+q=B_woNr8`T21c?FbOtPB=*UMMoFz&9`lt5EAM<~AlzvS1Pnv9wnE@~KG*U$Pc zliX@}w?kbr4Q+^m=|HpWP<9QG;m+aAu?%hu&Ay9+V#y6TzzI#)ilb!m%@Oaa!|w7Hvpq|& zjO|oY#KO~agLCd1zpWmK=MXc_52Ls2VPjGmhl}Im=cmzUR`LS74O6G_WLe;0{rj)3 zRe6c^xw(~)*Be&0hSS)MaKO~+kxO~yFvAvgzHz#)(Rzd}mT9-5EB1wneBMqBEd;oLDFx0lU*y2I%0$QQVpaiIN4%DmIhc~C=u6BX5Yrx#0=OtR_ z>rc-(Z#{-}*DdWd=vk>=k7(bs|Ch%vz*eIYCwKN2pc)1T3O5OQ?91A($@g$lzy4Mr z0)WB`SU$mjVbh*W;X&gU+jB%(Q7_MmsEd?8OGF1+@>urg~7x{UFvPJ zbNT(}9KR>#Uj)9R2Hi*cjxq9O`_Ezbe=Uj%G})&vghZ{4qJQ^MQA1%h-nBywrNFe; zeQ_E&IIq_~wAU!RE+Zr3Dlf0iH`PQ{1h`F|tMj$IYj{AFM2|)5#OfZTJym{YKlQO? z#lMS$G|wojrN9{RcWB3KV8DO@RY_83piS&d2)thqRXO%C4X6yW+YTo-IKuB8l ze#hm%#0)zX^dp18?;n_E_B$*ZyPyUnZnx?S^VP~dPTr`SV0l7Ljd50~M04Bf^{-V9 zMK~~@J^@Pi>M|&9cDpD?FW0M}R#_QuHsIcq3A~-nrIR8wiJO`w&|URwZfz8H5l?mN zTyzPw^I5}(g|HTq0K<1tfKn$ZY@ExLvZczZYjVJqVh9a0X&DbcTyR&&gcd+WyjJ7; z`<04fa0dr}6=6qN88uqR+hYzs;ffM+oNKB<5Mct z-^x69!!pPg01rE>EB7NbhcKwLt9n5~8=b&Iuf8 z!56Kr__4;Ye|Aje==B);581uKy;3s)_S5k3Z%4_)y$DYrFInH>2-Fkw?i}HWaCF2_ zd~)#jWaebSelaYw(4%!KnB-DrRoRy~(soS*wIzGo4XUVWB=1-_2m`XP97xAm&({zs z&Ln`9^2MP3%gS^09A94_w7!VZs|#`@ckJsfxrbK0Q56Z-($R`=1JfU>Tygen74cQ( zruTHT!9w5{rZ$Gl3Gaqn=?hrmzDO}^T~xQo2#Wp6toKV1EkG9+fbEaSL|D1zJg_#D z1pe?9q-p98P_p0R@g2e+8o3@QV)$?}F!glvz^$X7q=|HF!A;ePqZERHm>n`msL1| zh-C01&q1eLd3FcgVdKUp>V7RXq$l^;AE!Cm{ZV{iE_q*$#t0n5YUmL$9m>MF(98136~&tGey90Q z_)EKgT4UqT%Wf*QwKuO2sU5g4z@_U?K?+&bBkP^D_3AETe1pVSNK#q(O?q80D)=Yu z(G8IVv#o>WDot59w(x6`ur=)`vE)>F7@&hK!w6d+d=@D2FgNd*^V7_PPNgDRK0HV* z6>ooFoAeOsmIe@vod0=#El{;u#0TvW&{DN~KfF;5XcVQKnGd9?cawD(#PZR?2I}t3!LnsrLrzyF+PNtuGiY*Up?RI%Q%j zd`{WUPx3areIA?j7Vl~5K$zxT)N@|O8i31J8%ldDE;9p0=h;)PH~g&;`^oRe4+P_4 zg#Iy^h+A1)VwlgaG2ZaCTdC2Ac~$u`fLK1sJaCan$rkzc^Ie%t!fHpiOX}zgeA}0| zJ!POCZ7|n&IJS($-jA7NIGyCS_cyIO>rsh{uhpro* z)ow%*;lE&Z&Cd>1qE=NXNqTnarm26!IA6AyB|63N1(O_*Vgv#-5x}gsFZ61_vbe&D zsby4!EB8X91o0d{0>G-kZg%_pfc)lsc;?)Mu4F*yZyS_c4a`9>I=p>09t%wCy1BVE z+f|JCX6U^J8=oAUoJbkMKRoZD71R~K5NCbbQr44_LRMsfwj&{P;ka~1sJ`hBF-+pK z&SiN56niQNijiZ%lqTlCk|!x%BGi3>^@Q??lGOZ?%@UcQ&MT$Q27jERqvMC-*D{g8Qk)NP^><yaNTqbex1FlJG92?v?WlV-< z-<=&&Z*QNSny9idtY$^; zheWHeTp(<2ZFTonH1Tx$XHtT!b{eL(Ld`geE|j6SG+PqEIq_V_jHgk=C*j2h*r&snN$h1qwV>vizrw zA+6^f0%xI-s+wwQJE}9|)4up|e`va%e_(`rnzze~?1j`?b=!oWN8|cazme}pr$f=q z?W&A_`Dl^ts$I9A`b0YWL>7#!`D{#y{Hpl>EPzeef>*^%HRAIBo*!f2e0BoXf@Fh#B@RluFDu?O$K_t)02SA?p9><6?pRWc10>VBj<5JewG$ zg2BUZt)sbbqiZ$83ohPeLccXM0W5APuBLKuHJFW!wdLG0T5TyPt^8W$xDH3HoHLTW z?aSA!;E$d+$YMW`7w4|!0ViD_ZPvH_IAFR_%u6Z9>S5?_;W5A`+To=!Kt&IZn;)v38%*9fO` zv&+M7VY%k!{$#?g*QkufFO*pk-<3X|z=(*m%{dV*mQ%UNmS}J6#GfZwvYZ094-}1s zXDIyp`GWi`jnSJ4(VIJi&P6Ev=0b-7Du6)enEEX7TgL#6YEP4(G0h{CKUAOEiPM4# z8Z}Jma1cy6LXM|^Nw&e$H_uO}cQK=Hl1-}RTLez98)t+p`)KOY-=$uIH^IR&?7FI4 zoG}jf#2fujS5&4Ws0W*`{0OQc;}>tX#a4nf0)r!5t1oK$FRU1UsP1V1(g;o{fW8@I zk{f}qZ*j!xfS_}o5f&=D0B08`Ofk|7KRa2r3_m_T9;m;bJYZ}LJlh3gJ1D$O=)^?E zc0OxIXk;Y$z=-lv|#2Zg!Cg6no40xe^Re@S@6cUvFn2#mQ1Ae zxLCbpmmdcVp$=dn;3O#KlInqX+L>+eh?udLzF4kMnig5<>#6%6W<>Zy8BQk7zot*s zISTS$(WOsY-tsxJZdKeg5o-i|7cuuNLE!W+rXu$SR+$oaYlS(MPf(k*bd??^S(N6Q zssUnTrO}0&`ms7ck#W@o*o3J=3(v&s-om(jsvjdk3hF!bRsv?mM&x{7Oj%Y{Qc@eU z6H#D?0W7$4H;=0Q%1#4;%1a(#jBha|z?sa^!6BwHv zy!X#3yV!@O<_o5pEdK+#5WB$`>xQzKdOk0AIug=?mIF}sQQJF)nBk8oQSg872?I;r zp|1ErlH!9YpW293!jpo`L&kju^hW-gVY)j#KKy77jtJar z66d0Ogvz}8YrW92!hS7qyzffRnP23wSy5?&2cO-IE-;@b&sBX#zAo^b912B4uEwjg zcBt-1ViQXvme+e*AlTrIgM-JsA;G~lm1<4Ft0ZF7cFJ`hM=x(vB{Ne39R=ov^%22u zg#G#W%Nc7?mX=(ww323PCB1L2*%-OH=dBJHWnY-V{rHcBFP&=I|9G8&=(W@M{Xhq; zUz(fE9}c}HkV9K6O6hIpVjKs0|4(fjF1JLHiz}5ri(S;k-20}7e)b!|(1>P(?GIyf~PVg8?o9Kw8B z5goBi+Qn#C1CO7B&)>l;mFNYx*1G7074+H^hP+jnqK~Kvt=xC1t8b}les}$BdHJxj z^Cz5A<)@tM#_ff_(k|x=eN6UzaQgNZivy~%V@}E6VQ7{+yDjOwJ!1pe7jtW$`0rF%TJY2k#vooDjxQ?3KurxC*p z1Qs{xsgWgxO^3>p`wo|y8iTsu%&SaK^4Ovvt^=P(?IWGlGau@FmvcZy94?D?U@v{` zpWE6(V@8>D-v~r9LAAn;{tBGUX+h$6L^~`rhyhxEZGLHH0fg&tWnNM2f8FD87l2Mi z&xg)ubH}m2)hhz+NF)#J?sOI4%;0h>802leY**iaL6Kna)jDFuR8!PBmq5Q8)wn|7 zDk{7pPTX;^!W2iYiNvE0US=5F%;^;p{~eq>^4Y8K`qoL? z#ilU)gyAHtwDkLI_HW=L@PGdU8+!iNT`_AXp+gZJWX@>l-mYE{zE+;_?U84sbMuIC zDJ~aH>6nv~%%G0_o9+$idFH=B*qu9iF8TTuQw7x!5P0@MY*ABPuq!w{sqiA0a?=9c&pKkqgGSVcPm|cK!yWuO*-l(c^F~%4gT)*G4!2X1B&CI<+-BFVjo#-?$k zG*Q?n>=DO@x4`^r(5;Wg7@Weu#hwm_8*dn~N}a#Cy|Ocb@fP3FSg(&SFFW(et;pEJ zOOTi4fJ4hcmsT!9?J0B8TMJ)Ao^Yya0>o+dKXY-R50A}YR}UO(hu?gE#qD!+SLTOz z{p4gz;KqnXZ<+W0c*?Sv&u)cH^P*{CsjjsT-1;Jt(|fH- zMjApW)1M}+?Cqm#_UHdb(AB}E&um&-j<*cWK~Ho^ zl^}4FYN`9c5cNY1vs(I7K?iWElt{s?Q$!OI2sFaijV>c!%M(14s)tH#?0LO?eM*bP zlWuNue-{*UMy(dZhJV8uKg8T6xc7YfJwW|4*M7zpwRu`BK7k!bF|haX@fQ5MQrc4$ z;p`l)d3$>D$!hTU`QN;gNB24#H_jG-%H$%7UUO})F~?Xv&$!&S^>P<5>KTu}^zuno z`04JQ8=nFT@W0`nSRf#o<7@AUK;;rSE1I5LiU&m~^1N}=$f(sipAVoslr+Sb>lXmb z3IPd3?(G>3K+%GmZm#C0|LlAHL1xYR^6>3;V8Xv4b^G6ZlZws#;p(y#Ib-Z?`ncOY z>y!0i&!1a#^IQ?bToft%=&7c{?@Z#B-p%iuiQJcMI9=a3o8HL8>9VRWIQ$#6iwe4v zv$pQNaZ;cKPWk)y?;kc~5P|s~)BrVnoi%A;exXs;wC8v&fqd$wah1*IMv|&@7-a$gB7> zDcaQqJbM5RBeoO#{<;EO{KhWq&*CSk(ggd6$`Ad3y5zpt5CNhMVs!=(-cOLR0MPd) zR9qZA^k51sG_UGg+la7w;+7;uK^=d-rTxKSNE` z0rUVaIR=c!c=N1E-KZPg*gL*WDN`yQnPRG#;abyiA!a{o(=fbJFy`j^Fm&ek(4y#qyY@{}Cy;6Z z)}mF$%h`yp%k*QJ6Dqw5=L_*vCXKQa##aWpJU)verT~MXCCE=&XJjo9_}TjPRRaL$C;>nDssOvxn7MZ?(DX0JO zWn$xj!IdJVkh4Ga^U}6x$_A4A2+d8%uXmNzd9Yu7C zd*Jg&&`JeYwdE2;MjiE+a9=JERS3m~4FP0}*4Cr-{h8DAv%T}vkn{EPgM$Jh5$JFY zM<2C1YyEgD80RAWsgfgQEO2~n|6~86E8p!;kHrCOA355oZ_H)}Zfm_3)ClG=by;2I zHT)=y6n6$a5ig=A@f4tDQ=L$07C%dcAH3vp%kg6rxsG)~IiZA*gtn(GQO}<}PnLh# zcG1+UhzS8rX=4T(IL=Nr)n~bOFO2y^^+1AOt7%*#f_#hOS}c1%`i-M_k|}~l;2Zca z7^kq!?XMJ^aida}aS_M3*p2HCKVGK%`#V4X4>$PAmS`wW3$@749Z1QjV2#ka2bL7K zMvM8r#M)IzNY01q-H@jV%Y3BYtDvE#`6{AoH_R$c@13EKc!!mOhQ@enL&N0cbmTsx zR?myVR2d4@SL6BG^xE>0lQO@ML(!Mi%E^TmivM~M6?vs=i&HFGbWw`V8e~$nMlgu@Tn>b4&fiBG&ycFF*eno zbiIGrxYqJ_qGVlVHj!NtrZ}jeH^y#X7bYR4@&64Od**9$V(xR4T=5TW`TzmyEo76!pX+?pMzfF=?m1SO{Q7CFMjFNMR7^ioBPsGLV&lxsdPMW~ky}d>VeE^*9GG zTe_LFFqqx!9h>V_Ff0b;HQr-&PeQ2y35U*85urx=f=+XJ8%p= zNbnxY0tPNBR3^ZguQG6gKw<@>L%@J`ESNPe2J)U#FVP#8{sQglqqr~$YO^)*>ST&1 zNG%2!1b~Hv>MrYMT>X_8Fu=WQW9b!eY6BAw;&TpsclFnkt{|x&U~6Gg%7u;!L zlrK(Im)Q(JzI0WwhiDSF?n%>*-UVrUrKKVrKyPs*XuM$ID_sPL7Kn+UAw%$_r~kZ_ zKC%}Dwq%Q1N#Lb=wl_EZRQa_*AUaf|E~0nOfA2Ax^; zGa&Lk{J+TYXo3P#`^!pB$aH?{E4X5o^h^k!KHorO*R@OKc1;od${$k?N-ZkvG%az@ z4>or#N-lj~-W^XFoORPWJ?tJFRANH=mrVKIBJ|+mUfD#m|97LFjP&nQttGvZGNb_J zfYh+!wDf#_I~zHD!FCE4SMKWiKkxdMEZ1dCLsTrxu;(o$41+nv^a>$=v1u~@Q>yO% zvl{%RlJuW>1-5+WC{h$$+OXJ{*$+T3+#o_1$~b7*%kX=&GdvIfzEC3VpTd4;-(q&K zN^N^GN-a~)FTH0g5(EA05B*uXZ9B?*(#DoAR``K#6r@V@2!exYvDah8ScUb!S`?Rg zB786tYrDt&u3iC=WT0mCbgG^W#2hzk{Zy+j#alU(uAJOhzVST!p|ld6gO^wM1|fIj zh53yyTzBUSU#P0Jo*b=Kw4TgkvQ(a)b(lowx^{BqMf)r9U1GRG$g!x(LL6c&8Oeix zM=&C=FO&vM^Hu$aR;~~oFD#`#RRg7w_A7p?uv94qD){&K9r>l17x?vW_^YGsZGZ+= zJr9PTPCybVFW%+3Wp+%#No&E4wKymCcjID!a_i=Ih^|kyHssm*LtU(CEM-(ri4Uc9 zzC&fZbKtI-d(&guvvy;$6_|fgY2vy4{3OWsH6DLSKPO*`t6NyM*R_CMg*Oa9s3PB+ zF*`q=J(Qd}!(<$L;3mhXzXHGO{LF^VM$1qGw*UjcWmsxD>^HPDP~Mp?H;->IjJC{H z=KZ1fr29Rc$<0%DRp|Q01{=fOuKhScI?g;k0nzRg!nBNY^{Cb74{nA!VDs-TdP+Qi zr^KbQ&yJrjJgTm;W^b-5@1(;d%0I|IO@^yt&pzt(FB8%|+>KcX7~?Hwbuxx1XRaEG zPe-ic^UE~5WVh7~aX@E?=Teo_YH-5`KSW@~%wjTif$}B^2Snah_QTP2Y7Gsvzr5G} zO}Ctm4{j|3{KtpA7oX5Srbj=!Rx;wP1G+srhZHP$@dagO_%SppMy~wDhX<|@S|QJ# zN{Sl(OX0&*4e)pyncvNy1E5j&Gay3G$A;xLqqeGmVAm3rT17q#RLnxHPq+B{ZEokC zEnB*Y8ZcJat^7sppV3TJ{@RLuj?0SWg^mV=4w@WroUBHPsdMpL&;>+$7KW z39dYMqcGe|m1BG~?HO#-wY=M43IQQ)MtNBn?6sm!05byd&e;ytM9V{oCmxezSKHiD z;~9I{J#&8A%(!peUo*5aKYs%JWV9aWHIDfH*dh@03r2*Iv>?2~0eqHu)}c5P+t%EGvwg+3v{b!-IDM}hwYN4IdJKC29)zbH zKJ!;%%0d@=b863=j18@#e_K^Bur zjF5x=4a;;gx8~NSb_`KOd19Q#uWwkia#es-j{p!AE4%9j^_N4(`}EZ)M_Hiwv^m(JCCIIGf}7F99R5BX z{Yv*x;8`R=&F>3h;J?#2kZKr=j@93u4`UH~-CTJUSRVl1latGj#a2AV-K66clu|U8 zey>yc7Q3+Rub)yP{WkFzlH7GPUIyj89 zvDZ^d2j#K?2#6oi`cOL9Pr-|>y=pr5Bww(RXw2#b1j6ad2w=AWSlB zbzRz&2|Vkf{K&kMo2@<|&|kHMr>;D}=hJ4v18*%OI>zZIkqL@ z&Yy{?Zcb(lo~*iN;ia4lXRcQE_~@uBQ!yaD2q2I5S$=HtNV_d`Zp}HVO^r`w8Wk6r z$+EFgn@$d@h?-hUyXx@eCb6`K_7R6c&`_-YJ#m!t%`_(zV0T-9XXZ@VURb`p$irNL z0EjY*%u>1!VPVe#XX|1sKMlHz`v4cs{nPw0U#FjoRK>)6GpMk1%#VO;?sLZ*t>@F> zTL1QV!0qi0D99ak^~jwiOnioH^iIcq6!q-s%MKwo8;Kj{LHh%%yc1b1y%jRD(FX+r zcaFAu4ALtK0hU*wYp6e;GbU>aolI$lY#!6T0-pkmIawm(L80v+7ZM4I9;uP&hejL?#)aEf^Z?~Cd?lOz)nOGhHx?(UXmnQY+rv? zh18m=1dZP#i!e@8jMm8V{Y zkb^~~nZvBms?L}!YbV?X>GbbE^-IKyPR5AQxw6#gy=h=$YpQB&q|SE^Zv}oSKa?2< zKs#mesvnGs^(E+MiP2lVYa=5Tm<#NgMkN9fn`Z*2?Hi*Fc1Gn5@17!I#lxp7{#C=x z$;=iAaikolnDZxkv}=+nEVIhyCL}-qOH%%Is785XO9QU4@fzcu_HSYm8IO>E+!e+r zpB!%Y5;>EE;y8uhAr=%e`LFp#Q8Z@8$HxUBBD%R+;VmTlSW-+5m~09#k+dR>>Zt%Ny<65Ujg5`*?MtLJ4N~bZkyJA<$ob#=yi;_vfFmu< zEHuoK{C5*{OBZsqQ@}P8aooS)wAVjs(($V`@|Z;KdIMm%WMySHrdw1pjac6#>knID zM#2s@`@JS)L2W$u!RlHXtNRW9A}uYddBl=ot0g%vv^;!-Q&%hv+ySt--PD{<8q6*U z&GK8q(h=QIW?HSn>-|ZC2$FY=YJeExy>{Cd(;lV^Dw_y%H!D`5K)!XxN@bWK6T2eZ z%DE!`EY-|Cc94fwq+FWZ#!4t?^M|&_l2x-CbpYppueYxeB?&WFD6=rWS8fq^O7ddC zE8`!_?%PMLT5kk4Hsi_|;s?8zzf$NOQEn;n`j86j?sonwo_<%%nz|kIW%+82^_mxl zHJ?iLAXryxb6!j$k=FTNSnftR9OhF^R%Lb0HX}Td_Cy$Au10Tfm9PoinVg=sv$f9Y zD+cC>h<6T`QraD|Z+4E46Z`-L-&E`V`1<-KuetWQt;0?S&0IS>)|+G?Z`Z3=bH1|V zDJQ@NGysram4oYT`15RF9-P#jrA^@2WFq=#X16HS@co05fPtK`h-7eb{u9Hrn;x^r zqkS-=hvt^eb{PtqCY+~dJxLh}Z(0C@s$^9swZ!C{dQMd#@T|Wb3*FxCOgg2^JT{N} zWF@u8;6P-)*&$vHOywQud;=1)H7)6duOSzO{;8szK8Pl@k92w~{Fh#}T9qsK+oLul zIHWds-;ST3lI9(9Jki()A$$G&2T&DEIsEyon9~&WtZ0}Ee$|e7cKv%9fKykK$f zL@N@JkW)M2Zj);A#M&N-luq$uSv&0XXq@_vfhax9l#v*}EFn*vQ1bfWdsEz9an&ey;%c+4gviH48GHaerf~ zwW@(6n#~&niEXwUWjl4PYBqXrQH2(Cui?ekDRG+s+S=!m&2}YTSX(2}EU(Cf_rVx; zq)ycc40l3)qm@IXOwJ7tUbmIOC{%cT#`bUPimx%A?F~$~&kaT>SN)PpFzuWF;z)B3 zTsx6tT(ZF^FSI^4c$i@yd3u=fMx#0H^t6Cl1z5r=9|GO{h9IvH^(^BO5q)+Y3(1AU z&o2sxJ={EQrZRw(tk-Z-?A6)xyLjJQiN+=-tq0pxma_Z627ewBwdtFifqz@h)yG9W zX7lAjoP|UK-s;_ov#WG_o10=pW?ILR;h)=@C?5NWvwFx2(;@@^r7&En_-EZOxSzek z4^nOvR7*$>xLc(YbG5wi>ZTmrN&4hL?-sFM9wFhv$FQ}vwW&Wq7y6YSR%It19+hS5Cyll&0f*~x-w@!WmhK7$hPJ60vi3UvjbjH41fm=2 z>ql1iu`kg21yjBaEgJj}xJ6E*o@(+d@vz5%XymT3$tU-0xUnV=-6xP+xshM@Q4 z^ncL$*$xQKb`<|SD{o#_lbV}Tgha>#165|$OMH8DEd#_1hne5tuYvG zW%bVNz6a|Yw&Cj&)6+Gan&CBh8A?c(N+S@`%S%$vYBqe|mmRp!R&#RbEjP&M{(}GV z4Jj?9g_L7=@urTm2ByC^Lh3qbzEQ`dHgD^`UJa*qvk3k6z>61w+ZB7q*ObX8TjYv7 z&9H{^dBpp|a^8FX$74xcpidz!yFP@REf)nSYl_ry25a}i0yZ1f;@kh;~>oFF* zoxpg3L!9l5DXDKUKxi%RY|Or8e|p2Jz`9?1WMQh2t&Y6Yu(pQnw-DL3!By2irwsJ( z_M`2hAHb%3YvjKN*_sVp>mnw``L7?-07fs(mL^pVH3c(2{pVA`(9nK;XE(P-sa{c{ zy$#FD9^wD$aP&nrsT8lw zL-8d+qShhb+WERnu3f3_?{!w`HxS0=7XKR>$~@9}2t4T5k>3~~_r!#7=?HU~ zlpp?l1xg4O5f&+kxp{igMi?rkLBhq{z!5B8`N12B3~$v<_#&(%JO@1$?@6=Y zLp~f0QC3#|E(bBYXZj`f!SLUem6Z-QEmaMT?Yg_{+`uuKuVsgi?E+m{ETm@K$7(co zgBK(rK0c*P2(5YYP}e4d-Qlz8uMZN|&%6QL#jnH$Ie1ML8oiqqzP}!I+&D8aISrId zTh7N}w;XsjMtK7u^{v;| zGu{XQ|Fgfb*ozO^be}6pbL%;cwVDaS-i75!3bhu8Ew%W@+S-r~`0cC*WtC5xcd>JR z-qL=y8*8<#yGQXV>Nx{z8nry=5AvmH7jKXLTsip%WWcX`$W%{FH-?>`UFfm09c|Mk zgyM`qv>@SoPcXw)w${uYehNHZB9IrLKgO70&uS2DiCc+PI=6F1(!bfwgA`&5G+8vr zHYXd%w=twKzjeoM4$1aM}xS<_)=j4FAmUGSF^J-Y_#=0rY zE_w|eA8%=H3q)MchqcZcxDEXIWU3T;*tO=hjtDH0 z>M+SZaJ+xe<)>-~vTibxjIK?6nboLL)M;q(AJ)X!WYmHL7P8kmJK9ZP!!($|C2kam z6{ga)Y=jMjYPN%Yp8DPiKk5?>eICq-jGBBUsDQeqD@JB5LdmT^kE$B+tOfYADFnjhI}o61bu#^bt;A8nV6WsT0DZOrptdi)lmV=0eEwH0IH| zi*%KggRorBB4|PRsvxQdXOUl{tHUe@Z1B2YaTe|ib-*XGSe`{eyuS&P0JFdRaT2T@ z`aoGP^%1?d1!p!jxDnsd5Lb3pR}6T^hUGpYlvUmdxjTA;P6*u7p#O>^D2MBCk+4YG z8|6fXxrV>MJYjfUyijq0kNxPk;(enluZt7>Uz-OfVY#OmJyM-b=o zIVo;jNu4-}o~VjZ6hPCJ@^b#y;~5eVFg0gvw+Ox4HHX#r@>6<#(oYS3dKL8BJNUig z3lLCqGP#*jT85CkVK@uMO1!BPF!$$9^~P< zb(kQ4k|lBucRMLa4;RWLHb|My2` zTV*dCCyy$k&xgAM{ezVFSPAj%?x9Lhn@fzA@kvQZ3r@LGiz>m&kr^~zK*(&7QNE~Y z#!F?qAMyU7{tUU?8wpyWPt|jZtzL@X8izZR^+ix3M7DUj>G3fSWnP47 zZeE^3a%S(m*t(*|BQjJzK-CwgVYShjZE@}S*jG{f@o z!capYp%|okGS{>9k)Ue~c9Wi?X1;6d9w4E6rVu9rA5kRr(#ww0_bJQy<$!lgC^V>O z-yr(L0JYsv_Of6Opf$-x9o`rJK{)cXO-t^exd&Ti+_$e{fZuC4Rl2w2R9{VCW$0Ll zQ09Nbe>(~(XCt*(-hnpjO6WrCEArULyzd0iNvlAGv!>ywTQu)^i$;zyFhm3~H+6-8 z#D7!Wh#hsNBfIXZmxFF+^$$y#B+VC?+`*R4_t#FZRFpjqN^|{6^NV_7f$3BQ7Jvk% zjg3F@(A?Gn6ekE?pK7HX)BF%Ke822cjcZWgV=F4XmLP-zeM@~?T82~9YjgDoeqh`n z(*n^IFM?xMU(wxr_>;$(PRIpi`n`xFm+bCL&3_2H3#(fdbY5+G8-x~;BiNKcfJ3ZK z5q^l^KP8tqB^cNQy5jpb4K8s3NxJ;U=Au?|-KxI-tz>8BGSW*mR_(g78?Jp@C;A+X zV}Uie7M!YCmOAt-w+gr|wS#tEr{L-p6jS?XTccdE z_>GviyVy0?#_+H(wI)q6@3l*gc9gEJF5N|u(b!+Y$ZK71vW%Ywq0Inkw*Hj_rlR-P zbBJ7CtGoa)97_pn19^=DQpPRsN~qCI7_3OCSgKb+WmE1Od9ZEu%*6~>-`we4?pJs5hAWT^rO)gWajD-NNC`X zlYB*Dq8Up}kZp;D1o(SHInzx5+xn%F!SO%HdXPr;tb*)4Ta9E!kYMVQ0{oyO#HF{> z9mr9m>u-JRV>OmhK9Uq=l(lOLt=XFnxA0;SqT3v4pA*fC+)HRZ2hM7%bd6vkBZzC6 z6#X{_T9EwE#mUBi3W+3PSx9k?ugU!z2%Xy*8oBbHWax#Ux|%#hi-t9v1ezTbQ&uWg zOesl7b)b{_?W)X!mPvg9V%HT5iWJcJ9n>u6{qVb5hz&9G4I>yXncAT$#KP`*sSSlH zu7dG;gA_?1AM{J0#m-($f?JE(T0(eYK;JjdPLH{`$ndmB=JEvYm!&;VwVJZHJUCPY zqNxC+?ES5hzHRC-Ib`N^JtsWGm?*=9@W9boC?uLLjTFT)G~|wY;_Eu*f35|Rg-vQ| z_c@cwX4ZZqihay2K3?WYm>VB|F1^z91?TO7Jzb$1?AwR`TGM5|j&M=Eb|-3QseNif zBa62Yo8{KQjt@ontXiHQcopnMR2or*lbvZ}1)g^+>~?(N81EZW;h%iIJHIfnx9*~z zDZA+Z`%@|$RQ3Wj2#lyaZ%O#{%9-_>*nRdRyYw5dq$UZ#L7~&OF+DcXT={On1NsAw z!I?o`t0vnwhVZf%;vQ9I4N?lWm> zsa+M0=TNlHDTu$~@=oG@!Y8Tw5u!1IPiuMln3RJBa`|t+(0&G6l}MvgvwM6$SRRVc zx+J^FES=Rn5FvNn!rIgW3n}Rrcp>H7PlVyWEI~$woiT;8PGOo|Ep1otok>&K|G zKtZuvlWnw;$W${c@e4BsP|N)4t1)0R{d%%Cs)$5)3-ylvp`l2b?kk6Z+oQ2Dpzzc3 z-%#g)(^XT=Zwx?VJRdqN2yk0bpOxsGkd?n-R%rP_co(`@Kp*P-^>K922#?>C^sPOf zVpshXrq9r7ULR(VT)I;qm;}>t)*R(BmwsXKP@2N5Us=PW?I0wExh(uR>A6CVB3Zv` z@GX!;DAyMm-IWl^TWb{y%DJkSzQF37Umh-bjku6(Kz7x%m4Y~j-AGahQC&bj)b$ik ztHhV3DFWw4k8~!)s}7&9r++>}@4jkodl!_GG=z>=SL1Lp{_yaKc+eLhdD}AaNI+R^AcbJbg6oswALM9AoBwuSh|M!}b2VzaAoqjaZouq#AH- z0=&hxQZeb-IK)RAyGzx|1{HRZ=Zsoyz?O@XvNAS6SRwT8WXaOp^OBT=XAT#T^;-T+ zPkAafA}nHWLRn>iY3M`Q^S!6%HMvadn-Y?_S~HA<%LB+kyV(&Oe=^~nz!UK%UgMH$ zCW};HT0x1pcuuxIH|J0RU$3ycX6h=?6s+}%_y1@*_kSk;|Buh1Or()m$SGw+Mw0Vk zF&T-KVRA~2Bj@v(6=fo4IUh!0yu%c7&YZF(rzoc!7Gl*LLik>vAHFw#!ESc#dcB^{ z$K!tIUKk0e$|(1JSYm;^i%Kf}0F}h2^_FI_f?~uyg0ZOa(pq>|J7Wkdj#uoOfK2|5 zRT+>RMh(E;OxM)a9@_&tnx)`f1jq5OKAo*Hm`%9>X1|coJ-^}IwjA;?4)@?B9J$`& z7h?7_PVrSnIo>)h!z|G(g|ClUaviz8*f6B2AT%7rDi|pL*;!k})RroNfLwG^t{7vT zKXF7_@sc^wZ8d=~cCQ&`zOPxIi`W|3r=VKLW#gJNvA0-Q$}^hS1aY?&FX6HA;z-1* zi}zvl-}Md^A#o5KA6gHw@M^3eK;k;~z7GvCZ#td6Y$a=Mx%>;@GHwk@zH4o5YnpcD zH*B}be5~|eYfA$xng7pd^uPaj-!Z2?`sZd?w2msB)OFCJohA2nB9cV4BhETij;`P9 z?RNaYswE1{V#ui!U^{BTWp3HNz7yVthEY~0cJ_zpb-KkhS%I0-MjN4p7!T*bUaOm` zxgRNba~c<&IYlpuJeugakv-t2UeJ}ijcFj~3}+>M2y6>#xc*Lk9N`kGEs|WQ8S2s~ zv9+{)!_Iz=yVf?;oFDl@L4To{UsB;YtA#tsgNP@`XcT6kQQMZ$d-Tz%%vbsrNk9wF zrHp0aA1UDs5Cb5F!1HCD8{}RS!Sc5Rho+S5R|7Ga8?|pn2u~~T6t#tfezLc*q(I%% z9?q@@j!GU6==^)2c&F(`a7^vvR{)uwJOS=r4e1B_&cyh0uPoh1B^ehz1UcnI<_*h{U z2WH~~!gZr`hx-$0Xddx)&5ks*!!!Rx5mt?1fTcPfb%u2adLcy``#P$w+G0b!e4`I< zcFDqh@a=5GHKVkzfEn*Q(C9@%^^=iotia&fhLklD6fT@;LCWwG32rxO!rVy42-166 zY8xrOV=SFMDS9z-ojH6UZs&jBJ$~)jc(V{7k{NzLM0V%sa8kT+K&dOyNT&Ei2Hzx+ zxtDm>N8e2k4{YWQ_K@0RkwWn^YbN_A)GYm2Y;u8@~3`>Rp4b`*WUcH zxGG1uX#&6eYU)`xJhAkX|Am+rjAloum78s!z5Se(jdcO75^N<=t^x!ol&@U9T1z+? zDE}Q9aTw*20T7oG&Jxs|3QY6(2og&nmV8^n=jTTWSftTd2Eo;O3?V`+p_Vfdd594tX&Yw^<;5Gx+voP@ppr3 zJVcoN1rh4yQ8IZvKAsJv2Q|R12QJgLf3o(y_yP&(o!J`rF zCMylS-w>HD#&LkPNy$h_-xDkMSk5*(OxwnGRYfS4KJuu8Gc__aLbcFjXD6t^`E#OE zpD%LM2%`Ud{VYD|{Vz=p3FU&}l_3M`NeY&>4I^3?T03!Gs$B=PeF!&Ree|u(catrE zB3!S3R|N1K#Hicx8=6D4q67c_nJ+$fLPJ=1lWdd%9Ps-5zpLK2xA(&H#$}jSRvEvp za!xzkKRnYny1FvqVmryfkzfwR;xs2OL9NSRdX7-wycq2hk>Q#?~fC*QKKyY?NCyIs?i6<}zn)m3vUV$p?XE!;Qn z*ksaW*n{5WtYe|CBPIvx1DdU7+rr<@Y()M0Z74{ubo}A}f(WYghir86N`Xpq#)ZEi7clH^m$7&3P zl25KRaF0b!KoTaAGOHAYhmE zts711w&Jw0t=|^xxfpiGC`_IWe)0jCY7Tt zwRGm*KBa|mkim<(5cd?QAFiM1T3dTbZ+^b+yJALxbVHAK*m!}0D@&(3;ku*_&!MD! z?QUzObV9~2EckT>ImZ79oCSi#J+#FUapsfGnU`g{p{yZZFAX{!2*BK}P?#vejxr*R z2d4ceH~1b_j-Kp|Fy*}1SbN1h)8fUXLCG5GiX$10#X1#_citk&;!Y?Fft<+fx_WMd zlJOWvR_TV4S69l&7AVeG2rKw3A@YV4^eTPSQ_T{6(lNDS0JzN46sSbV8T)9`oY#4o zfytC22$i5{RCvYwY~0u69EgW_IsaXO#+Qn{fbWDJTKEtWw_Z!bMxPL0QhQYB>Ig9- zT<9a>$57X@xy+lNv+*`gqh4264GJ1X6X^+EHr^fM?%PxpYPYPzouD2Enw%ExV%!fc(%q=k!C3J!M zAX^&!J}fg!jZOuS@f%-nK>i!>``zo>p%$@!-$l(jBiJt7*4j7p7wz6{(&Rh58*8~00ygMkK^ycv!;j#Dn(1fdE`T0+tCn?{1 z42pdp$wZnPZT{&gi`N`#>wk)1(2lq4A9;K7A{ws`!Y2LG9}YnOR}YJyD{lz39!qR+ z`L-5-iM;U-NQAw8)Veprh^(7gRec^WK86w#6@B!`yR|UA++E%Sk$VEdi(XNa$S^}s zk|Cwz9!4@E&j(wSigh8@PSsUEn)1M3Rs&W-UznrZiOErPGRN_H$I%>(rzq2U+Kplv zU!9`8w=_Ze8g&r?fk{+hU9B@OP4zA>te;`D)V{rc`G)u0-j79E)Zx*A&QY6KWoW3+ zFF%~qC^Le<>mO=6>7E6_LwisYfwpWPA(Wo#A@XoC)=1*qhpi#QI~s0>RuO$fq>Zv&E3@Bjep?GV7+ThU`kw0dP@bK_TJE8j!wSxJKAnprj0hpvYYl&Y z3zWGC0mY?e#X(Fswbayrw;WF|=tuN{_i)V?D00p-xxwc>i zb#VG}x3aZd#>pW$HLa*|203#C5?6Vr(28Vv(DrsVs`6D*Jxt$LolsZ1Rs1G9JG=g* zK&gGl@s-W}gu24JgJ}U_e#)W1&KsB~*oPmIf#4%;bEfU<>eia3wP`}7bYE>B=i{-( zoNMf#0y%no!4#;|y>rf$Ur%@cn*U{XW$Mw}ok!oyKI_}z;q?;^C?Kc$dT`lO=}C^K z*CQ^OlRZpwrT{#1o$ncoBh&%RDZBn>w#}CI8-w|(zE)lJ|5*S4kpq};72dwR;lkV- z8S!nHq9nSw8^|z7HDj6cnm+<2f%S{G{psgG+!07|ip{+X#5Lt82r%s`H#GkKdpK8e z3wJ`wF@u&3q~AcSiU$4AbmA3Zn_*RLn~wqVB`WyT&R{s@nr-qE!T2G6hb^Y-0YQCN zR5La3a9l7Yy*EOw=$R~Id*6b@eE$mfio5vv?v$&2GV&TSm$B#AITvy`G4J6M7FGDL zcm2%VzY)gK=G@_AhmMw(VIq`R!%K4c>l*z>fqF+lEP9*&+R=W`WJ=1N4D`mM^?`J0 z8ylOlksOWtIA?+$h!p_&zZ*C|6aCv$yGY423dqKH>`-jbviMKE%SMaD=zx&_n%ZL( z$shs}h-|QcENuDWV&4$dC`SUuw`!#eLE`aswgf2jb$JcWA)xI1*$#|-waWZo5Ms#qyn&rfOZ_yUvnIF8#mqDyjC(y`#e$GK`>a+Q7uCza&uP8hm zt>@=Pol1!3`6`^p=X{qpEl$ehMGXFOBBo6EX2<5_;ff_={C;L;rvL2wo*UsWiWxI5 z`YzuLW|;;4M;&vYFLO)iLma?m;sFpeLa_pcK^d)zP(HBG^KFm();-Hc#PRotpC~Iy znnOxp$N3XRB8qF*kTuuQGG2{o^|I$;K3V5vTR`^#Nv4PdzY}-<39uv}3d@Am+Rlh> z-vQkt4yFn^3>sS_w<|E+5RVKvz?khXg<4qf8FuUhAJ?9!l}*}<2vQe9nZJPXe8=9F zxeW(`U8`~p6OK!Scogm{D)jX+AusLCZ}Z-YL_LM=WNYCsj1`eG0)WX za5k6W3-pW+I#m;6Rb)w%((w|kaG(VDqOsy7O+&PfC<7OQawIR}WpSgbikCg=NDZic4S6`1$4!J5T4K~bc{TuyI6+9mP7fcAZK zBt41IDCC}o%t6zbs>IQ$3_l)73|QXrWkxE>Erm&4+xKbjH*VhDg42>P4WU616zJ2q z;+aS8GLJfZ4yV%lG%TAA#WjoW81|H;+^QT;4P6BR+Ca3>vt!HM`1pnf7%^g@A~ zBc#`HUQ1Q0YEaG;muZGQ?+O&GRc!voPChaSrvbi8sI5ZMiQUAsLFlytlgYBbI~!kz z49qraK3}d|Vjjk0Tze4_0b$*+jqUJcyK2btL+z(HqbAszxz{H#z^U5w_J$h$j%bl- zUyqa#fm{aMV*rZEMw{!wSBHD*oD6%gq_2naw_FC3CAlKy==GO#Z7&;+nV;j=M^iapqxY*%e4ujXC+99dKJb?^tlsMmzp(ue z{xE|jLDrcTcKDt@$KN@B40EgOwADSyE02{;-QL2MX~*9c98EIEpe12Kk?XXhjh?u;c z*lXf6j`d)7@5$qvgtNr^XXJjyxbA3c>*rH*uaS4iW&|htB+Ge?st| zx?>Jf_o!;@Z_EZAq3p2`$)P{QkyAJI&o^Lif@>6`Ix{|_!7C-GQ@GRg_cgL}yUB`Q zte^Q335rOtV{$c04_1OlfQPEEa(*C*t{kP8V|+BOd^Yf6{i`TH`lGrzMs1^g$bt$* z|KTab3w&YfepeX>xMY2@_8e2`^j-D~mG_KfWF1Laz3<0ui%bENo`XC9590&_4SJe( zJDYeK)~Yg=4AK3be+{GYqg1LS<1BlcYB_)M-e}5agE*4N4NuUr#6s$dFaPBFbyThy_EfKy0sy%Eu(J%rj~+A@x}=-F z1vZR5u$Q!zj5lxq`ryKRZC)|s5wKpMndkJO{6E3Ay@;k9+D`NWy+eJter5(>r?=iI z!s0N~@^QoCxNM>A4_`bAhrgE}r9|x(O{DDuRl*cQjubUR!d)6OO-c{U0$h1JV;{r7 zlpOIyb31;>&5!?tg*C$aBE3+}{X0Ryb#pCk@0}e;% z9>M&FT*=lRvkgF)dmqho{4SGvJq{2CkCVOs{n0rTJE{yV5h~bhOW4ir`>vcnOt*u~ zybEMD1_wn1g`MVIIkAmguWR3p#DDTW++mD)Y>OTK;sC|M6Kj0UMXKv#a$sDC@QD3? zxv>sY!p(=>#>d;Y#ki`EDBb?vdhrQAxNX1rg!~aTOMwkF=Rxn7BJo) z%)BcElnT}3r6Ompeir&n={1`6d<%9ujOv)RtFBzVFGQ6D{qzHIll=eZBIl#z43jpH zZBvh=XoXtszL6Xf|5-hZr4c^??=dSPd8yOF`FXB)c?^p*yODL!nvqJb*^lDUw~y`< zp&wVQ&F@k4*cN6NSax$S7H0u?1FI{s=U2}F^x~hh?|+x(WV*IFA$_Z-{HQX-NsQ$v zF!Nl=uA9Aw7P@i>pPs&Nyhbj?Zcz`Q54yilC{Gx`k<)O31t;&+mF{`~`tFWFD~t&^ ztf;Xc!k>MAb?(}VV$~lqUz5A6CcvZTqC9AP8l;Hv-30149oxNc$#!M{p#$37MA*Ci9;DkxE^a7X@#57-_8;vTX$#koYP~k@BXjc4 zob0PK>^RgohDdNrNJ91qQNQ9DGUkzg7dS$#%?7pq{z}lu2I>G9{u}Bu=TJuSw?#ly zcOrkB8*qxz&aHeg*4x)Iz-q6)Gl1VD<9->{8!h;~(?!}c=#WuXfOYp z#_PV?LU)P*r2@e`3Swq5+E_u(bveKA4aoUk$KFNAzE<76A`zH14y(wQFKPh*B83{R z34-wj!^6heO<{*eAxi!N2oP8TkyynyGzOy*dG?6jdve z!?1Og+gR3EBHp9|DE20Uy9j{iW&Nv7_R%tcYUvY;UJLy}x-lo7L8`4)8qD{nS|z3i z)@HEcz`Su_3H*f*n$MzlygQD5t{yUb*i3;C>)JNVLGFQFTwZc!1w_()?5h2AbJ%v( z^~*-z2Rx^3H&Caec5wE5d#uonJplJ;9RtTq6c*-(winUI0f?QCs+H|(`_>@+kEA_i zS5g5!!NRdG*n^cnSDJiid$8*3g6&)WXEq~) z0({KelS17<_mI9tVcHrxI?iB&*gN2K;>+8vdy)!+ChPT6uM*7v!w=dw2a!fS_M*V> z$wEGh(7mYRAQuVpCu*xo1!>*Wr>Q|E9(!fSsY^h zfu7REk7oRjS+>=;1$^9in0(6h9T#y0=3pqfTMD5uQTCqSgK5qlelhfq1e_dBhW zb2IYRanq-CbVIM6mn0*(W8)xtapIo|FV4(HGgh{*lo*z?(^AgV&V;?eFhICMMr3}4 zdtLMqWx}*9bBDHTAGu9j&S=jvIBhMduLO^x0SuF zdstW_1|NU!&+V1u3cbi3A(3fe%Az%xz~>Mdi4!q13SKFL-o24K*QhzUH}kT$;O{Q zU^D5?{0SE1ccBLrK*rD;E|Mr&G<>oOtNJ7L1O*z$8NkD`l+`FT4;++q;|BajQyfg- zdIGHT;sDguDVYu9#wp(omNRGrOQ2q5e0IAH$GEI6AR(+?HRzMP2(@^252CDmj}!)F zL&{WvmN@%yIeE&zs#>emy-bL%T5CAT)+gg4T21+lds8BBHR-cj1Q_jXTaO_ZpPyw^Mvc{E1d|{ywg{yrc~;k z=P8!z7i46;K0bH@{s+4FQ4^)=EE)@XqNfWJuvm_HAYyzezk&D)$axzML?}ItJ4c23 zJQo-7yTir>vtA8IQ#A$npf@-D>EBYK{sJL)>5Q{+z>*U`upQR6sfe25dt(A&2X5I16ZD&#vHES&7Z z{}^?EJ_XXX&T@pv5^mQ~`O9HWbz(I@|IJ^) zj$?(4G@HDyHozZl!&C#{5t$D3)+}iz-crgP)^0uiHG5b|+bIeZy8iv+hRxe(Kl(+X zFcPxm;O|0%bP6xt4k9gZzuC`dc`qPKhRE{4yW@~Y68@_V_#LH9*4f(2RTw6Oe`K=6 zx$|AL;jQUOz2yGIZM=5&-Th2|H4RIuwbPI$ZEWmRmrQN%zz$U#VQ^$EzHu(r$kPg92k?^4S8 zFMe_7{%P61wfqmDD*pmWh&vzE9sf91|DsbrEs1Y<|LuEJn|U2%t-a07{r%}hX^xfp za|r6nl;GUn;NY4IX|^~&{M(RVEzjMr@g2J@V z)6!HQL-oz^iomUv2yuUjb&dOU@N>4nwBxJo*Xh}IB~hCA5(mfOm27*F)6Y2#1s)Jd zDk{HL(HCBkzRlVl|0qkTE`8NoFgxX=eARnY72I9lA4WfXI~SG2(Y1!;(xvOqYG_%U z>#x^5_3zVqg`-bYnEJ55m!!?eusJBa@S%lsSfwCUf}LFGtnoF^AXB)Sb0;1)i0mC) zTlwwo?dtF39JsNyB_7BlsVd6zwr&PMA*)-^6Cf-O#O|DX(C(cL)VvFTr3N(Cb)@8IeeG!uCFaHs8GcV`()Vb zgeYCGFLRF_$-Dd>a;^t@QL4NiWHk>#pzk4N*&SPF{HTYG=*bFMl&OpZH%QlI^zlhk z>x<rWlf=qGV5yNN*UJeo)qI4``bI>2c2llK@pfyP!X=z9 z$yzH>{*>zDKP0zgbbI(md}f?d(WWN{Dy@yFMG}h$DD~Z&`r_51ZGV5 z1gn!LV<{lZIYmt8fX3;Kz1N1?|PB%3`?p|Ft$iohj7cmo8W9%J_YW;fNH1lxd- zqi>od3Gd;s(lB1mYLWa2il5f3Z&Z`lUIh#zy9hAuUI& zTsdtbS5mO0CBT^jalh_{xSvJ)f71c2xSZnQ~T z!z#zEbMN#qr#`5GAts9<5m7r`yGJPZuaDl2VrO>Gn~$G~{=?g4EUh7)VS)0tZ~5jn zmZ_5O&v8Nbxg%C!9PL}0{21bZXiNi15=zpt`1t;c+{~dUBL3rlpmL>XvtUc%YSja~ zC!;P}UUfCV3be~vJKMrtYgR`G|49if8nyrXx5GU6{PVu42P+BpGAiusIn&1+efIvG zMyB3>2v(OFbJHxwv%2OzRj?ST=>_kBc@diItLZZ{i;GMb;DnjS;9vVV+(^y})0^iw zNQkz`urA9KC-6!nV}{f%pFOjOU~s#%slvZQa|1MJce_F^veva4$)z8h1G z%eP%hH9sZeOW|Y1sLy2EMesUSmteZDPhYY7wj+7G(361rTAx-Fy}S&Uas{d~5xzY# z!M`HX@C$;o`-2=he`$xzyC&e}_v0Re5rroU!QYSEJe~@k_+1?R-4WSoRCzu`)8X4L zTV1W0#Y$f#hmpu%U(J`d2{Lt_wgdEQM11_u^zfozslt^tFA_&06e~49O)DWr8=ph2 z8k{#&lr1JBQLi&YfBi1#3lA4Od~vU0%1u=C=YZtbDXV1YrF@CERPcankD#|*FF|n- zR&qylju~O9dWN@N$kW^FTZ`{FonL|=Uhfj>&{H<>zO{a0qn7*RO%U*OLB0W{sxQ3V ztQ@ZK5^Nxw$cc50gyK<%1Q-+t&!Z)eu%C6k0HnV^V~u6TkvBQ+U5c?yQ(|H7S4-eT zLNDUW(L5l!9KhYFPVP!nr4uG7vS8p+dF>Ru@e>PoK@(KMNxmZbVxNzx`*J=Lt~7xq z$v9$#yI~Z5D2@e2EY1OOfC3u3;)?xZ+7Foclr?@K{OcgIQt#;k=q#CeYEw!zHAiv$|f8_@HK(frdDm-|O!R zYEvv4CR=P|KFX5Er?&SI12iADGuUFvGu-73z=XcCy^v1LGrVcbfIWAxULVXQ@kcHx zJ;#hsnzJ!WGOPN1f7QUl^2UJ`>#|v0$cb+XvTqLly_)rOwhjWyO44txUq*dL-C7s# zDgSEs2CMY!ysPyKV^X>*2I)?U%W)zUG_mZa!Acl%*Q-KE|uEmp9_p^PDXT3wBdX!{ULHru+TY_VXXiy~pe~8qZ%&+yjH=E+%8S zdrfSx&de$91s5-C7S*^H*9_HXGPSyF!9j-XL+?sbi!1bc{TdyY#|W-W+PK`w7-S|b#2b3oor>F*QRz=*-C z-kz9V$)|UboFDq7ee5hULio+NAeEj<=ToH9nGFq?26qunb?sh=l=pk~nrD*UNKnC^RLM!isNvD~fX<-_=lX>c<^aq{zw>py-$V$DaVfTJ z>Nbvae?{OTGM7y8Fi@PJS|F@&F*g$(KqV)i@0GklaftgQnxQn2nmavW$3OfPzJ0N> z_vf+VDuweVO%(@I+loh5A%jBOF6No&r&XzE7*YAd($JPt7`HCsRZ#Wy0tN8zD?jV^ zx>*E!7Z#We=8OpVI|pvE#szxKT>+L1^EGP=Hx}2&e~n zyB<0@-OZYcXi@#9F>p;Wms*j&;Q8{7^yq?vWM&OH&-cC|4pQ_y~jVe?cwKtce27*QqPPI(tv)hKnPO!G2?&qOeaOvXlKxOL_ghOKvqtC3Y)j+kM+uG~&?l@O0>Tc}(|3Pa zfz30{zB;~snwmTE(syT|ugJuZems98ia9vGe!OOXG<24Se17l5T{jWnjOm@_U&9 zJP-m)_mIqGR{abiVQ7emZY7~T{E6HJUcM(Q0evc zwVeDDNpT!VOi@-MoSz~kdx^CDp~OW?OkRlQqiPG+0@XEuGP*}jcfp`e%B8>H>S!?rg10d{)C=RQ~>1OGuW#h1z{ znIbyN2+)x3lcrAXNj6YV>ZytVtog}W+wH?wGj?j7Z=j)x@j2lnj-eRIEH{Qg|Y6&r^lw zf`7qe9tC8%T0;l}btXm0>UWwK6P>!c%w^*Kr#MrfkOM^n7yOjS<*O~uABdX z+FTC6XSC&f#-yon05|_&Pc|j!0fb(?eSZmN>eZ$U3d>?l@>=e%(Q=R># z&Ar}4e;w1bQaOndJ4k-P_VmVchIA{fD1}nCIT*&@H(6`1NNKd$7|MPt;|q=H+Z7Ar zPQJQ7j4Xo%Tr6`Kt4$ZR8@Mug7dA?nlRTk z*eP(=%%&`&U(F}%GjQkaQ8gNs+Ez_jbPG@fdZsuPo8gsHyQN_y3r^n(vURs6NqTJF=)YI5vNJHM#O$QSwtqTha<3@ik zZAu4|;&LY>b*iozou5xs>x7Q#| zYU+V+L;#4Cdt3UTm1dfff`=6}P_11r{O6zs>H&F>vPVy|gOFA-UZjf|s`E7}dJuL% zO{io7@3I2Fd8nX9&!Sk)gDAJ|Wj0_=aZ1!rgMNS=p^EOE*4{o78oR1xc-=S%1#RR+ zB0o}-^#k3yluebz1Hp+0x4@YQtM!<83Kak8bJsg|J!>Z!Nh}J-4RUZM-pw>96cjBn zg4Q;EZSU(5kD;EMD*d{_n)vUNnC*RCa5Li?&BlK2L(aX>s1e5hpytz1()BnfXddJ< z0bJ7A|5B21&ejti+XDgJTF)W%6SBne3`i-_@{?7z^Z8EWR~dyS70?A$(^5DJCqoHQ zFF>Op>{F7}lYoyCcN!4)^vDgB!y@OBx^G<>hT)X4`1-}gML8QO_h)dAMjSxofcj+l zcf+ntn@FF1W+cxoQ-A>sw$T zxLb|7yC!^ERA=gRT%r=7XFeMj?pk@k5e}TnEG=&&KQ5%-9ejSrRM5ZdG0 z^f+qX_sqpc&wcmTF()vqUv>)uL#de&*!-K6-r3R=IS$9=vr(A94A8Vh%v{n~j^87aypO>VgFS~zsyZ#wDZM*7# zze?p0Jk+}+OI!j}t(OLYmaxvx4XxXYszX4wdElKZi7Os_7SDUKQxO?a^uheoMw9Sx zh2k_c82FCtDrizK$NO8mVBP0MKtozL3^|W~j)oTm9gHkWhtqb8v?JxJ9;gcyiWF(i z%|tTVcCXsEZ{3O7?f5#?91sc|_&b{X+YbF6J@A&$SM{U0(5r4OS{+!xuXtcBW zY9;pkGX0PXVb$6uOAg@SZ?3t%W?ARCq4TwknXb{7a3H*X#SyX<=1O&s1F#Lb!z+k> z<=2XvY8=n%!}hlZ21d*a72wFwCIC8?A-BQ=#M5#^G33xfg_T^kM>zlWt)-toe*FSi zMLcnLw3{t)jrNfn*HPdA(~RCW+NKNBn*T{MQu_8fRh_i;dthYPW^z#qmDc}H*-Dn9 zC#rQc%;#8C_Y-t?=c~7jJecALeLxV^20p+Khu~db^Q^k|ohq^Y>Y45J$wv`K%(|$f z@yWMMR~h%4`7V!;g(qJYP}jZRPq|&M!9e1YlDHB_H0<}#mrisAz(peVf4h#Z{u(5n z1{bTm+>^7pXIVSf;(VTqffOM2=QMBwn7&CCkd&Oc9GW!PR;?? zx<23O^Jj*^BRVVs52+bPCnl1gn5hf#XcPqT zBl#Dn9!fE5J`OoX&*z_{UM=CDuwsAFAYhdMsi(X`@rUxTWT2p~1aosJ93^v!+iAUq z9*&YRf#V&N3SqC|U058VU#U<5uge1hrN;B9vJu`qH#_<<(6Gp~GtY#)!<1dle4^tu z=t#eBokf9yB^JkIl32#3LHMyhX=ogd5Xf`ubw&E?@vLjl6<0*-2Gg!pkguceA_$*_ zugnaS$uUgvUtk3P;(%MXS^@;bu9b4vB!XsBD;I>pfIb+!*rnZ>nY%yaKg+l7K{$Mk zKm1Ic`24Fs@{HtCsHjtotg#6|mxba8xu%tPG~SHgppZ^CU;# zS}~|u{Y`!SXOHW#4TbbeMn6SfRaH%S$`Ap~upK`rF05?j#Mo{qlpXSJ`DAQgE=>)Q zL2>kA}|cvP~9z?iZ;Wy1iAiBw>7!<*r`0rjFYBb0LKd!?g~AgJS!=;PKq zg#dTEjMi8(U6MIYwm)2{n|UAUA4xh`yP_cN`{focIm{paLnrDF=q#A`mu55$=c+wK z4cB@>UmQ>-UC%JvK*l2kL+)cjm%{brPlChr+_IiZ5`j&=sjEtn5DruixrsRMl&_Re zQM~yu(hG3B-F5+p-h7YS8!ATJ9_ZJ<_k3%)bH;QK5vVTQTbh4oMU+eD@TZ>0B;f>l zEy7$94}?nd==8QEdiX)5v@7D3swvaJUH;V#VQOq!n-)lf&W|W2$Aa9-3jD*|le^gw z&?mf38GO$;yYPi)P7*&y0j*XB;aR*Hu%uyXonf1==>=ie2@?}SAaVLP*7b1h%K?Fr zW#)HMcv7kn`9(zv0(+i-c)&G2smn(d`;e>JB2CJ&&bBq`FsyRa&iy)|#LRyaYKM}K zhmC#GHyUFUkb*R*Le*oyfPFo=f^8^LdPqy*HqMC8&>RxN&1%dU*C`MR(51s70=_W{ zGWQ7AYV?U@QSOs?IPo+y0(SxNZpss>_uqsU!?Tt|3i_;iYw=U1RYtQwubZ-vUA|7# zzfV@oA0uT0o`Vr*By+~l-Bxz|9sjO${4tI`$c|~SR_TFmQEAD6@gra4ZT{xC;WGWI z(lX{BRki^}*?`@t;G;hZ_DA37Yvi#-;~4I?#s+3{ww=iR`*QA%6S1b1XAK5?LVg1+ zZiR^7t{(2wRhIxY(*tt}_P0$pv}g*%pS3}v+AVkB0|EwVWBNLJ}W5Ra)P@`w?U*M0#=^J~Skb!n9PgryCTS$JI~08+kS9 z@!CJj>@tzB>dW-(e?U?fxK8${^4LY~5$*rl=tMJSEA#U5ui7j66I2j zK5pAZ==}RORM%)Zy)L{yVO12K^GWPzX*2q7QgFvM$vYZAS+ws@=jG^nWh$Yss1;G` zHF1HMs7?B@K-`$s+xGUO;P&74?Z>mbwRW@lu1s<6Mdi)yC+pdDAB-A1-gZpbYH5F4 z4|+Mez|T@l0OCXdC}`%mES$2IN3GOZ=rp+tnf{68Tm8VSzj#T;@bXs1FCQB9V~90{|?F zqLb&qDo}ZLc-2^exAH3XHG)zK4I#fHXy@a3n*fUEd8dQ~Lvk3K#1F-*M1C|DtnxNk z{DX!0DQj^;jla%@2|)B?=Mj$)M@+EPo8&%rR2_B!OwkUIzhFnwIr^-dQdNaT^-R;W z6;5G4k^*Q79U)*D!!q73h~6zuD)Yo{2=v4`Al!*8t8J78yzjR-*}$h{*0#gUmz-q; ztOX2S05E(-S5R4Fm8`2Lzk%NTO%CxGGIEB=mXZojbg{O>DJQV`1M0F?vALPqFYlu^ z!gBN>2zqD4i*P$1Mwg*jKm$3FoqjoR;JX9 zU|#2ha;Xi`nKm~bl^bpSp3y+d%=;A5sj+Y8!mex`nub5#XQA6Me##Y@BBvgpmkSCC zHmWVT@p}0tbgr1#nhy_^L{lyUX^B^jmv27+p(IZ4s>YVjc%l*7E&kGZG@N@2c{*}C zGy56(XsYO_x7Xp{-`|@zI`-^sJAw`rj=lq;rw|V85ZI-ie!^)p+?=1{=s@_Rx#HX2 ze+sGkK{VzQDn?T(GY;g7jO#2KUQ)7qCh-DoMlJBi10r@-2=HU~u#n!kA}UXM7)ys4 zfGCdr;H_N2FcDTa;MdbEk&FR5nIs1Cob{|RfcS4plf&#*?ucIapr;>irojR71F_EM z`A3-(19^R4j<}PThpGpHs}WD~Y^t}h$q*B`d`6Glm&hGW8@a2t&8W~{ z1C_h&hZ_v`lH+NdLS0Q`%ykMdR`KVN)V%VCd02^03zOfl-)e(B$>0@Lp1v@sh4|5S zkWy>c;k!I&;d)yok8Cq+Z0WrNq=rBBtm1*eJUe;iSv@~u&0o@BN{6va4P!6U*|&@i zamO86Mr~WZB&$BxG@V-HIFlg^P<4f6c00&7wW+i?G7vKH$cz$B#i+B`8X|(p@`t z??lzXwIjMcL)HOQOHl!geHq*=mcy`}BgFx(9_eHsGRnxmK1Re7w35Vhc=#}l` z-&-y^FYSV(=JpCUrsl}A#3q2_RVCQe{|HqMLraovu1&yDHK14)4PA&ss_#*ZI1As> zRp>{l8v_MS=beNTFNAB_P_79XT{ORq_C(*_8Jum!tyYEYE{7H^|7;FX^S5}bu=ZVz z{x52dK`;BRI)ODbk|TZq8x)@50S@;>yDGd43%w>#7p{nPLdYRvVp3`L#_f!=gvV() z5N<1X14S7WFMHHWD(B_-`(!kcU?gK8!vr+hPDmMvA;+gMW4v71w@&of3E%6Gba&`p zrc`Opl5>}8C8!hH1a=~v5AHwjT5lkb@M7d-%~=Fk0_s3eq&(cK37o)F`i(vTNy_I(3!et@u&EYr z`FnCG^-J_Y%O z0d1b;%YP$p_#I}UumfGE!S$A*-H8`KXov2|(XQRejXHjqS#y?xzt{18XLdJgT}<+$ zedzYkbRuFJMcVG2oc%YLHM z;Rn>)D|>=L3U#%Q{^o1oYxM3EYP+idKIZC!%}8Ra?XfM$V84!%^}2cKK)*w-*tWec3ryY zWv}P+@wne_H-`6@P&dMZjlv?*qlu{Ph0!0kZhu?Q-FC316dCbOL!vmhV@GF5K121c#i8;i*4VNp zkyKaKr+pnbE~lJfh1(tzQ^?OU22@!)=&w?LbgDaSpwM3JUwrifecz9+OrC_YziDm7 zk)EPW8DU&pcJhT`Wy~+R6k8wjDH|p=QuRR)kO`FA`%c~&_uxbgFVU4c!j_x%Bou#pEtgQY7lFE^DqJ~HvA!6L21t_U4#jPnK=n$!IPPAC(*5-zh zwVCFfq(^2%d&L)xec2}64YT2O1x0PR1E~4H7*hAQe z@p5zmZldm+P@C9vTYRK4)ZO%A%EsLL$gn8e+ROh{ZXpk*ng@Vtcb#p1n99L^Q=6a> z@Z}SL#@KsXSW#-~`FM^*J%6uvgyl|b@5=F$;SXQ^)J4?&&Sn64(QF#L)xLzY%G_X) zmIf5A`I9f3`uaBJe;5~jnR!ZlZp#04V?(2>L9kokG>p#(cm?TtgDds|Ucd0*Q>q|; z0VvTBb}mhJ8F^LrKqo%juuKMRPh!RB?b~-hmQGhRLMW4igg~YAGVOTh8lbCdd9hlh zqd9SBdv#@8@9?KUy--SqcI@A|&UCvLTKOIs z8+e4FUX(XJSz;hE+V?X7Apc~zUPk^4%k(sb-G?rGzoIl+k2mU@EQ6fC>$JaXDY8`|}j|IWR!dDLtN<^%k7Jm)8dD znKhE($`jR@CEQf0F*7+?YBh=zh$riyJE3pG{knayzbB|mp~S`u>Gv#f8l4|rpt%9k z6w@1hG&N+-oq44eyS;B;MRck*S}ois(qoT~=ekaP(n;m8hf8php}#j60+*gdQ{sXI zEz1VIY(%8YBr@)42thp?sl{KVbfz6oaj}3pEqwj4EJ?pUiy6T{j)5|GK6mj2hI=vs zKrtH01_GZ~C^zvWlMP=6R2|^F$=u=|A`#i#B6jk~ z3B--+EVXRN$0@X67WmZA8Hk}X1WGtBE@E1?UcrgJOw|$>M-@}N&86M~>nMt*1DuHr z)}%n0pF^GcWiPrakHfFI>zD|WGQJ79yO#B~J_+Rqnb|-x@~#6)$mmOjug7@)IEVd_He|1+ua#mzjwB#>zg{nXd&)oNdVVRE-mC?|wdK3phGo@kkAoiOE!Z6TdM&E_vA3j+ef3dKV1P-S%jTJ z8{I>?EjwnAsM(|Kru}a25wA$^^C<@bVN)gNa5BKPD~`+vb8GBLk2{<b$)EzIVh-3aRfMuI>CMCW{ymO^SS@ZN>YcG zDa6qo5cAZ3`zT&x-@txu8*d=G_2QFQ+-}K*jkIpwWDk*z*4Fs`@8sXlRQN$5YqGN3 z68y5YjiaZTcxo(a#q*oB?qfbYcs8nI*|Vp z&qBTb>uDUj4|MTKhQ2Q@t5W=KYT{6i{&f+BGRpRDf1o>dvP6aJsM3FyXm$AGh$ifB zC+IE;f=6E#VyUJs`}?nq0&6%C7V&fGOkLnSL*;&M6Kb=kBrC7qG`;mMh?8RGsg5um z+KGI3C2zQ`SE$g>hVS{8SJ3#4{;`n6xPL#5MS4O=z+|u{i|w~FvH8LNzo%j+yS)gw zR1dOgY^jkO-!)f|BFPy+`xaC2hcp|P5xl$k>u%0`>ybCcrhifI@Hj}4e`xd1Ojb_f z@o0O@=3<_l8jiHS_fSj%#MJ}+ z+hQvcW~f}0*>kY)9W@e#aZ^{bw5u6Z6NnfeA5AjK=vN{KI*(`&YdaSSq!7_UWzIZjui9ZI88tt?%n^E2NJQ+VFQdV#58F z#7zmyW&c`#2j{lU0hhz%Ta_4#{3vA+m_^oG#BzhebE7gktRtyYC=&$f*hD_Hl`mNO zhs)86p$*o*4j-54MmS2H0xcL?jB=_aMvZhs-TS*_B#JfYz>^iTwQT2qGf!|Kcl}gs z>;XAXI%kLNC~rMPDjb?B;Q$!h_I75EDNRQm=8PU6?dl68Wv*15EPV!V?m)pNI9(fL z5!3wG-qh4aJzm7^5N-(!t=kJ{X&2a=uN{PloUuW<1=MXFii7|6%2};S41d*Fi5{e@ zEqtjek1PE>I^hwqPF2MBM}O$R$SBI(EIvwSfLJGkvModwf~fG@IPRp7`@wM|ug05uRmcUyV3=*K9Wm^9aXucd za%v%V3dWxFAM-+omVcIU(pP$y3tgm(m4z)(z4H@8gV`GCMi&uBCw=wQSqWt=$VZqx z1~{l%D~$;Ao@Xl0Tu(zoD0VMF9dzd}EPDS6F~-keEKkJy-S+&8SjF_gxAj?Xup;G9 zNwHIWWG8blBfgyvAv6evB*CTf4Q0Kxmxb}>K*TEVIu)9xe|u#k-L;ayrVo_%)hqZk zy&Fx+t2m3;uO5qhPZja}riJ3T%y0AinuSQ$7~B~1OZAIklU1OQJLXoupMTvLn?lC* z3wQ~%zc+_ublxos)^5I6q1iU}Hzj;6Y!*rz;3EFO@150I93R2eB_2jW;))!?WbrC5 zZR#ITa*ad2a~*YP(rgg*mzPN<1p70|Ng>%_O%08?()Oqj^^%*DgD>TJ3fObX*2M1h zf0(w%k9AmH{cu*)TKnbyWdVj5McDT;*?xnTe5Q}csSu@X%-e$D_g}mjpBH|b7iDt+ z?9M36rT-Z|w-$GeMNAPjGalMyL*cRv3t&mZDp`e3SRHc!`ex;qGB$$mO@-lqa96(H znQO~$-~*QOiJLhmOSqPu<58F6t!uM~5qw5wh!C)53;LlD+6IsCZPG$*AfC@2O*j31 zYKw57Eesw1vtq-!@r-T_Zi)YcG9n@)IlPu6ZsrH;{%2|f27ya^HG7TVzA78qL8?NZ zKZ?)QgdCEEU1qdNmptdwjAS`p9rh?C05Unz{Wg`t6!c@e`#rDY4pP>%+Ook@@vZr8tASQ@AXXhu!0hvzMq4JsIf4{SW z;ty^Uyha6Yd-a5A>x8-$F>|s>cMprFcOh}km`9iUCFcWF=TTu=ij=5Ud*QQeOCAsQ zzdW@klnwnR+&}oXv^o>q@4rfmZE&^Qb zIT3JGfN@7AOXSnEX+Mb2q zer^wzFg8s1b_@MHwaV>;FU#VuQ@A%h)^C8XgWp-!2i=EP*AbD=9O^%!mAMTcpwE?Q zU(;O1PTq-hRrr3bX)Vi?7!-e0vUhJ-Z|&}f!&9T3G_y&kyLKkLhWO#w*jP7frj-~| zcKE;xWG^egGEnojObMTay5-Ux{);HNcGum`i9d3EiUAbctA%TgwL0ttu@Cxx6M4{X zpr?*9cM*TH)QR(pl;B*W3hPbr&G%xh`}m@w7pYlUq=Ev`okQRoHX&~^YYeKwfOpq} zMSqvQ3?hZc`#%kKs5|H4_Udg+ED0X>APn)F_}z4Lq(YL(j2ip=gT zYr=sS5jRaoI~bFzzdzfoPsWbFYkK#tZQJXlj|Z)67_mov%kTcNwBYc+WDu}ab|(wb zJ767rlKOBz_H>n0S*B#!N>^_DHzwrkj#84S*MPLZ154Rov26`Vzd-Ey8V_hu<$|bb z(vkRfv1#t=U<^O>9CN0~T^=&&CCbOW(H81%+58K7boYL)iXY~Zr<0iZn>j$3iZz7 z=|a9B@JG)pXRws3xtQTG5~zjfRIHh{bL|DEyvK;}AM#uk2>5bHRX7g{T;bLF7-E*+ zKXWYla(>TTNf?KIV)FTOu=ao1n6E$-`>EnfmzdSD%YWWQTxr|Gu1C4qR+CR=%a79- zE#4X%Y`DDoK-@%)tsH!TDR5a;Ct*W`S4e8BRlpS1L|r^;6-YZ6GQ|mylXHKiiA}$c znnwV35p>WwGRx2ofXI#bfN|vx5pMwM4hfrA^$zCGB?6ong%M%@o9K{QQUr}=HPWMC zw<&g1bTTF}a5_&V723c9G5GFyv)JKwbzAJJK#@z^=KhL{rk3E=!4W_go$%56W0eoL zy|*IrR0(0!_mtQYeT5PC97+$h;J{(_ba5ydSxfAUuC{jFh2eWzgXWr}tz%jCEkxaC z7K|RWTA7jC++Jm=uxDJxqqn7BWj66wlB$RC-6pB0186Rvi@b96 z$8@&At4U|y2nUC2t2;9-WWn;A7vo4rTaj(Q58U3~5StQ&%Lc{$+o&eoT8}%bB`TB; z3Xo!GUFO2R&sujF<^OVA#1#d_hjxr~t-K|Nb}EyuQ0^-}2nm}S9Z@PA)3;1bQROw2 zPLZ*koPH_OL#-xQ`iH-D6n`F+u=StEG^JWmc3}DpJ)XicdzCCBMO4VFu_LI@2Ly&6 zP5Y07-l)lOvPfl7CmHV{$o|crzlus(ScBiR14k;cgZUDd=#|-%_LKR;Uq#506^sfH z9D3WO+?VChA>fiLJz_3lAEec1I8G1tqS>hVXqnXi5~^ zjmx{`e_l$TL-L#Crvmt?Z@sAL_aQWLmayJ#=efz%?TrmLL>9Frknn{JHMHZ`Y@rj*iE{Y4QURym zYBd9gt^Vr(3uwLkaP;IQzv;CfK;oz5!#9Q#QnGR4wY1G0_~mElG@L>EZ0zQuS*)ig z-dUX$~Orlzx+)XmwWrbm9samY$^c z#Jb@NC4O%ZSa*%WSNV+|A!91*j5w_C z0RcUIAoape)NB$3I{UfQXR&2=&q5ot_v(zJ%Q$3f$7_cECXrOnDlPm!Jhj0PU4??SKIA0)`Yx$PwNW$t=#)xAp<=fp^bBy;qj z&qwFIWGMgB+<`nm)&N=t)d2xM!^QQYGgKt7Vde+D$ae#_=y(M5mOIv7s1%3M%520? zk!i9Zas7Tjc=eT3Ioa=<^4Ilc2Q|+WI}pA>p5u?t!2Xm13siqp?j58Y$>|BNK;|7; z&$`RxPi7Wi85n^?x)5SkdWj!OyTGYJt`KXqw_nZzs`zFIP3@?+?><~9u^LrZB-+YL zdF1^9hOWP>u3oiT{kTmQ-ZJrg+jr$EwM2f*duS(9`_7NWZ~kMdMWde^O`to6V}_W+yf-u4fdP|BsP zPZY)ZIZJ=VM@V0F?@`U9*ps83*YST#WYT|%k61c+C|AJcyp^FkqGf2dcwC_kS?HR! zpdU^7I`DAX@SRP&u7^&eRZ~;*9EQQILNMqPE1{01R$r2p^aKaQpbfu?qM$S3;5bRE@-fZYi7uH z->Btb$^JR{dx8N4vB0a;&~^MKz$1mXMdi|m%IjZ8_>}V0bUV#8E{}5 z>D}9%gvqxm*ZEaSLK3tGKGaUD4v6U_OaV3+8d&oal-Rc*5or6945xMVWD=L^^h7)= zpL4D|Ye*Nep|RJI!tU6JwSN=DlBz4Cs#lTOzZn`CdPo0cLET@57*l@3fuGnWI(B%= z(}Y)LsuLql=EJnUf1i0DcFY{n@zAl7`z2LzM+6o6x)6w}p}vY|6kkqDOQUVPR{&Jn zcQ8`8F#On^l?V-7A263td}GuiP@dU-Y<+;wR2q2Lh@N9P4}H!H%GM3PrA`diN8kyR`J~0>PMMK z>JPnxTD{lNkT00Lns;0?D@IQeEar?L;J2=6@7 z$d>PG-V0;KG$B_j0k4ap&pR37M}00Ofe-1{78mG5L8W_gc8FFomRkI7>Lvb4OXsGWlC8+6bbt2YV9=+d=gLfc^N|h z46ZoB=l(I^r7F3O1hjX51~~H#T(^1Bg}lu#MK7bD`d*=aH;HJ-;g9Cac7n@nX^bN? zEAKqnYkY^SRTx6?q2?}FDw92JG(27sqh5T(D}8W;7G#Nn?<{NN|>+x{XA zP%?=94T9El=o2V2tN;2N~albVRphnQ31<)H_jNJg5LWdaYpN zn_xIVVVHjtd9Yoje*?#jy%y`GTKZzNPNtvV9a@mM6?D8cJ+xLIq2+S4KOX6lQTHnZ z5xXv+_ruv`DQr2qEa-kfu&8drwnRojj_!y1S@sQ%w*!Yp-WsUS*+5g1U^gmy9_58`!Mmq;=3Tqjd!>D`V{7-UJ$2t5#+UG`BZDTz+ym z*{pVLc5nX&%|Ps$ciqPO9FU|wxI)8>4L7W9UXr!n506z9rC+p?+kn@~;xC|B-E^{P zl?uhCF7dzY7N!o`52d!Cu7KrdD2(EAvKZ4edP-i)zl1G$vlAzvK4A zS9H4p$RIpDf6Ci}Z;$enNQSxp0oYR8zpFq0^}zk8zA8ZmcRPAKrQ7H|_qG4?pQw?W zvH7>9Fs?E&<>yY$ufsl^?6w~VF&=bk?)}*w)W&jJvTd2%6r>%@CvG3j>L$*A9Ek}! z=~+LS7YlQ^wo)S82Lt}8M>dyDsJ^xFLu%wZ+KH*$C7whqfnZssCWJl|4|w-%Fd{3& ztF)WdGz2Xhzj?SP9Mm?p7^aZKmmi8q##*H2i0Sy%mrediM9GSswR|NXNeOV*FH$Of zojUJx<>>fa!fwF2uhUE7#w$^2&H|A;M3N!6?B+{DaEAtGch=ybbG-`&f7wr6P)t

    jOluoP zBI9G)xi!6yC-3d+6Xpwxy81?u&Kijoq>*p-)Z2rz2kR#-^T96)U)%c?DYgIm9*g35 zK+%nDYg!4B?RldY47DHsK+!T`fmuLpgJ$C1#2)_~00u+{6rF`X&m%{!eP3yG5E`UP zw>O8VLhr^b{VZya+p0fVuJ5HSQMQ*-Z~{h)WZEUb1}*HBwpwWqV=LqKFFMB3Lu1olOW2=g!;C(@xL+QY!9#Nmr{X- zFko>%n;ZDL(Tlc+8(Mo}tSPdsfzJej^h!#5#Brv7f%pGhY&%y%hRLItF zl^)9bUyhlfZ64o*0zq%WUqYljzra3e6nQ>YR;I|p424c>pm|}T`u1=Rj2VoCXj@kj zi{o;_T^8?^Eks@n`Lv*V@(_<8BbELNqv0^@Tf=lW*#U&D9O?Ztz8+@xE={G3WbO}* z2MG9!2;yEBtfScDf06J9mW2q46DoZqW={`>g3_L-iW{a|XYkw;@xfzkxkM_$1Ys9l znjZ+lEN5CN4NkDk(^#yLi<&b?EREZSM`r4e+}wqL&<}qdlFay zV;h34Hbv0gjgQSODL4LbaU)E%HEb!L9u4;$+G$W=#JQX)q>OI(lq&MK&V2UKR;98& z^d@n8I%P0dpFmt0DCRLUBYot$^2mS{oZaNf77E&W;)M z+SxRBnfrE4SCmn8sh!@14%1&6|9++tVa9Nt;12Qda z?@f!F+TM=()Wf=j2MZlue^eF9xO(Ux^vRMAaNLlf&5|5Jkf(G_hKWP1qk}(Xmnmr zVTKA=^V{83s0U_ja^lsBf+&~Hn%t&r`)Ds=|DnU(`0k}PuLs^Ql^clrE(}d+1Dcb6kHilD zb{?^plnA3cXGWzNOHufVFAa}~Tux~!%!b^CA*JF;F2|eG)6>MP7{zKMMp(iLF_v_} z%$s<@45Cj$mJHH?o;Y7>;YY~qF|{dTXua*hRzEPp{auY6E%XYF4_|c+S||R9Y($`x z-KV0o1+!AS4gNQzGU;v`miVg~!FIcVLhf6Ji@%NYPi6`ae=%3A;y7%6=Jy{r<8> z-S&bSGkO9-388U^m81_FdWSnqoe`Pkgn zDcF-Vd%Qoca**fvo;@9-U?=p7;sE^*JDpkS7EnqY}>DPj+Mw_x&xB|KD(~>Y& zx;iIr*r##C@o|1Jq6^BzYFq}~2igv>K{=`2(I2egg6?3$?t~#f(#~OYkaBRJoDG~% z@Zyx@I@a&KoZ%5(x&Xvqk?jqthHir)Xf&ij>VE8oMx z-|#6tSV@_`!>Iz(;G_MNGV*aU05a5#c7tPypI~H7dReZY>QiW7gF?>FPdlxiqQ06E z*TGIejsc^*AcEsl2Ck;f^HHkB7Hc|j)_gt4NIMMP_B8BMyi&ETN-91w#25CNF?Hq; z9|Lu-%yLecQXzXfX{~??5H<5Y7MewduKLsu2ymJR3=uW7JGpu?pBN&6pCvcfr2Xru>S$;<=(86b9(!O+Jj|ltHAAZt#Q%@ zqPd{Vwg4f2(z5l7-}q_lAJBGV6kux@DW8Y)!l9mESeHy(S&UKGXK;vDvnYG;4UR`D zlEsjIWfO`Mt2h=;CtB$q@j)haBHNs5Q;1O4DAUaY7?rA4KY?BmiNRx7e3s8@r8wC5Sxsb0U8 zJe-N^95o#(n@QZq*E(QBv6gAE2D1G@aWrAz66a+cazGsfE*N(W4@Yk|0fc{yx6HRbbkcN&KIK?IO@ym3Y#n1JD;q=>Q6s#yr;}|BN$KPMq_$!KvKwg%)cRi62QJ_>Lbtn$W*wU* z1A-#_FDI@~-11ONBHb`|FBZ`HV*D0jXqV3_0x>}kXBv~8G(@uH3O~V2WhyXoQUp@l zI?UhBnK@Pbw7VY25cMQw@5L~3BL$>?kT93ai$r>GcqYt+<~>XS)Fo_u=n)E2&vz|< zOa#TQ#xC%WtA;H+t<7bjw{)XmW}|_yc{rEunopsJ=uEUmMO-m2*O_ffI_miGeTuW- zm7WNvw`ue-ntE|>6CZ3QTPNpUrz}bEs`)iGZ+EhTUBgKO&`7G5KS>2-4SvW( zQ1@%`rufN944D=O)e)F-kB$T|Blax>Ok3RErjPc0(&Xr86t9-ZSz}pnH^8v3QMaG` zynZO4*C=#N-pVptH*US?AdQ``8Sy#VMq#rwHbJG_c4bS(^5QwswKBbOTRDch{HBD} z=tMxOEU%{%7!aoG4ymmG_qa-hZkfsGy)*t;dxRN?o9sxM+}#^WIb@t1&1mbNoQAh{RtYSWnL)5k&+aJ zQYM_Gmxjt2JJs8D<;Fe~FcO7*e-<21azn?5G#1fiT{FJY*QCks4dza{ogaRYukIjJ zFpS|z1?{l25dN&jM%E4r(R67rZ;vbG4z+G1XQtk`pSd>8wp_k;G$oZfupBAD45!+$aT zC%`Vtw@rFG^SoSM&FU860+)_qHAx607b21Qk*@(_2>;J$SmLg&-{aho=D+J#wSa7P zI0dNey4kZ_1b{!DnJLceQD1j(?^`EGBmYdhFK|N1V=?i0o>V6o>rOKtAb)_;N{c*w z30vAjTDMPkLJtmL6;!REOq}!ju7`55g?NcDNf4@TRG}cB z8^J%v1159W8>-Vi(lFZ91pMGN#4||!^9u#@yi5FpF=J3kpw9If5_!I=^NI^lyG`W^Q<@s|Cj}KNDG$-tWWS$HYv}4NZqI7t0X}-zG8f zI^G+W^&DtKvozhoI0b)lv)GsE zZR@w-@0yw{%XR4oum?#H^^)2wla?<70tc;b?d!3ko%UwYG@P*gkF*>y0jFl_l5Xs# zhq{m|*(z}L=F3pSis1mkg(v7eKT?JY8H6ySTbI$%+_j`rr}ahSA`(Lx>e8Gc*Tiy| zI)qwx{_MeVlYaH0qGJ9IGJy|s>%P1$ja3{t{YQa)b#F>bU;m`{WGOMPGHP>ihGyC{ zS?doCc3L2L8T(5Wb{6ycc~%#yW(K$socN!!byq+tZR`3nHL@Sc=+z&()xia0m?Y8> z%X`jq(U}&vOk~NGGU#`Nt;-9Xj+v$Ix{|I`Bq>bGU_Z1VONGnLgG8iWxh-!-*e{@}X9I~%~ zhLfrJ?UZmp!Pa4%+P+UBuXAx5){HHOY0sCsbvZ&*Y56s0as6h1RP{LJ1p;eHk9OAZ zXjy%ixYf@-o)G@A-H9Q5_y4j0-jPER3;ezr*wscM1V3BzyhpZ*cEY=J7Z!8K{Aqfk1u8!z*l@tJJ0LrIARmS;}2W9@r{puv~Y<YDO^ z04(8KiQD3!H*sROQ=%LWWY#vQKW2AV#g5a1wXrW*hrNeHk6IEB09+j&Z{+CqEY# zAIV9H+y35bFsjE$fMIANB6wEprZ?%rGX(_rqX(XiO5tb3;4{!1-2ncT6cHV9(uu=j z)j|-1r$a`BLGNQO!#tt|4U?GMpJUt&fmxv%D;FF-ZiKX8M};ZeB*;ZDz9*4EZiCsSxNAb3|?`j0&nP91MSflPq@ zEX#$EfJUwqkS2SQX7|7kXs4r@F}Mfg2JduKWLUucm>?d}!@_4UoG}Os{$J)wF2A&o7h89v zk8n$27avhnqqqM&x?fdG3g=SfKZ7=ak6qJMuF@6Km z8m^SV!9TuxTc(8IZkWAuvOB?GL48|ZULGrIf7AMQ^1iL@-dhq_c-0{r%|unU>gC{P1!eNoIaEqG%3po)78jrEzbW;gPqwL^3MV zyVKQ#Qs*_~lW6KL;z=7fiZ8G&__<+rooz7OJ1aKoC01C3sJlIQPMahCG1ia@3)X*c zN(iM2x?2$J1x(JFNc!igN?86x;wrK@3N(g7m0oS_AKAxxhKH_hK4LKKsFv0f2#MRf zA;jrZ7O_XLPB7S>Ea#rA+=a=hI#L({Kz0)F=r2bd3{@B#@w04)8;R!=Qztr#Y5o`= z+A?k5EytT$Dn9Oexowl|4{QO{v7VU0)Q%INbmjr z^4QYzNPqRH{l9NX>2p#y@?jUU!bW=z57*2=mV(CGe0KgMd+#09gUM^N){{4?A!K74 zX0jV!8u}OGbNR_q``H3zrIA-We5&n{C!Ny=IfV^C`d2#fs9Iz!St=kW29Ag;B3aHlq3;m&u^6R> z(&&e$B(jbGg+t6rf$+m2c{7R4WS*G)ZvYp8R;re43u2t$O`*X^vgbtasj6f)WO>YKtuUlTDMKp59Hl-R;Dd& zrN@=^tqjV&x4VD$gHlI*2?*b@l9b~&tqq3f$EW}Z`y(T3eOLFcbI*EW#QJ{y36(Z= z?r`tp9gj?*9k>l*P4Pg7&pnXSJuEzs(UkBv=fca8JgI_HrEbtworJ^o+4kwBMwt*U zU;Nm}>x11T20%QF_M%&~Ogy_;Wda{^hbAF1uxFAX+^VIDqB`*(M*M7_o&D>?XKdNm zcaDI8=Gwd*U%9rBA44EbR)~&M5R@*BZA}{5iC$-nQX#0r{xPx@HRurXcQ;lHD^Q)g z_4DLJyOll^IF6ld+DEpOZ~sd;6Xf2?XPoEPo%c%hrW%da?9cb$ry5-Mth{){|C)Dm zL3+XYyT%Y!167k;jR^J6eQNnHZ`>0z<1@}ED%#oHKKOU5d^E!4vJw~V#8s>`t957p zsBL!0)D=~9ZPg2Ms?18Iy7tk?m;V(By)ZtwLfcG53^gV%YBR1=FcJjVCb$s@iHx_d zec$m^_~mjzT>P4#f8$8s^Ja6J%#}%u@k2;g*u&B=Fsva;vLAUn5PfR$9=MSO0y}ee z1Wi)0nc`p;lOsjNYtY5XU_-oui4URm+h3dsaj7(PQlADfK&w=vFHZuWtvHOIJAuWt z>IhIZ(tqwTR_*1%*L}YP=!ST8`gDLC(M$$VUK7PPpo$G2g+gYKlRpdq{g5Bm$p>Po zlQ4PKl;qg5b&iV09?buqu+HuiU?QBBIOvzckqpvhd?Dh77dL3V29R&zXG>QiTflDV zrKFdAnbX)n!ar@Sq~RClJMH2eFn~u2HFH{B*MpCWfZn%~%#?@weF$`-iuYF`S^O7b zX)F`$hP)mB-bC=<0 zFZ-+4;}1>_1>B|_Cme$=CP2TcmmK{LI@v#BKOoEGj56p$dkGNf!JxRKl9L}|heK)X zIS+|AxA7fcCwl`3^BlO7@^mBY9@AWDmbB#T8SP7z%3ntA_;-Ud^Hcw#1WuWl-5URz ze80X|W2?CDqU;V$LVo!pGg-Fk=Y{`>oLV<&KfeP-;r89-KKK=tfchC34T{+VQHq7;$pitHd2du&-3FXJTSO=Fq zDbdtI1axT|p_bj9k|Ozu;=DWM9W?tPOIcA)=f86^u_xQd-I7lIv&XAJ{{e#O-M_=+ z?fbFuM?M-6@YnSOO4Z)yC0IkS#-h2MOIyT*h6A5!{kM=Ny7=+j(N5yY&Pga8!WO=1mB{tS-KL@zH@RgxPX1!(KCu%0RZW;eZ3*7%H2ND9CBaW5bv7i&qO zI#8+OO(q4t^?Fe|M=k+@fxy}~%n1&*X=!CvF}cI{vXSdTDHl8L*oUtd=p0<6@Hemt zX>0w7pk85bb?aDaZHcU7nRK+&48C-eKClV^E+3$=5e86l$ieQ5G)OAHMQ_3V9UtFj z+9_R>M!jc5)D79&ckiC!2mU64RCRvxnkOS&B3mdDZM}ra%TrQYNVuyf2z>0#*N`~8^ zxl7F62tL#9E&`oJ^?fE_eEg_L?}w9f%*nJ1XDmyq${Vtb=6~6i=S1UAa*nr-=Z}Zy zA0iN+`)PcV%j`DZg%}#g`Nm7C07(O4SlPIdlB9gGQszcwZuF!<5(EX(G>4Vu>|@?q zt<7zleHnV)>= z^pVq(al3f8P;@(AyEoY$5rNM5T4UAvL}LeLVVnlyZb4 zWNp#QKHMW*gi4}eCZrl!SVeDqxjyRo!%toK7f%Q2*@$#~MRSYvF>8n%Y~Se>vDH$w`4SfVYFF@Ha#A3tz$`VmuhKuZ z6eb2r{F4j;eJ}YIJggdf1ti&b1Hx8(j{vBH4akCL1?CLkOU#5%kE{{BA<$T+PAKU4 zLmQGI$nAy-;8?Dd6A7ju{Vf#72CddCiJO#G_VM!g)B|THeu&`*$1DRM!XvJqRhQOa ztb)K|6YF3SX?4(N0Q80V^}PwFfS~K6_3%maQdMS^WFYJ=k_#^j%Nf5iPPwZQ8TDqJ zBV_OKK+5o&3BRysS>oV^25k+U#|0=*9G#+5yBcbxGv;ed>L-n%c$igifF~K$K#nSF zZ)+yCCl>$i(I#y6Gt)~iBjhf{-3Yc3u;CdR?Q;6+cbNmvE^P`x=#O(|;#!D}fNk(a zU5-`uXxPWrRZ_jIhJscDto?(jJZ_Qx3VEPHGD;jbJ(CAu|598ylkUdH76 zKD!^V`tLx;W94{BSso62qINJXm>y3?9N-1YbRylZ%5N%XD+U`X*EZG+>;?P@H2^0U z-=HEiDl#3usi$)Q8?H{=zjW*0r3~$d91TDeMI7by#Mmu8X-iW8Ac7JR zMaJPV4<3Yt<(~I#ihTy~PNVpHR`re;;|+!e7A1t25cQ#3sSgXIwMur&ywMa!zfXxe zvRJ{^)HNv5TV2GWidN(TK>?DFYjwlz4}@wJieM3 zaZu0_)VkF@y;?Ykoqk1Z2tEF}Pu`z+wf;i;`>dXp_C-`(U1Onak^K`wxJiq~{ZyOp zI;+RaR}(!$-B~oM@V4QKwGG_81`DC&-TlK-+)kyL;1G zcV-Uulx7lxV*Lr1G6#y33Zpq7uy42TIsu3$SMBAVHnCmj+Tk}fUT8D-{b^@4U!lOp zcb-m>2i|5lrspgaJG=O>I3uu=lk<6r_t7ic%l$kC?gN}&_1%d}wod-3y7aDtTPV5$WMB(<`+d7)MNQ;{%i-2QrFem7o zsW;nmfY6(s`<^=}AQ0OUwz1C`>dks3Gm4KG5WFnJ)yBZ;sUpvG>NSTR0G1&qXXSp& zma4XO#mRbh_Jj7_xs=Y};Fvg%#^s$4c2A|vXpKJz{>@VXGK2yXHOu^-7*SY<=9$Xp zKg2E(2(Rm2JI;xNSRFb4OAS_swjGiE%?ZCZh7+6@RwMia;~5MfK;fg^9KQ0qn|S#t&$Q)1I>z@?`qgZrNp6*bx>XFhsX zXnhYmiZDP6oRI_R^BGgLG9HI!BPua+n-Xvd!k|P^r_3p~MdX16KuC#3Bi-x5lje*~ zyM&~(5~6~Y2Z%C$s$`+83!KbzNg@2qiyT(t{WnO~tB&rnpG4`RG`>nXrMl2ygTW*S zC<$VV?6E;9GXo1B3<6wPQzMIq7_vX7KC`YN*^^845)-tsfC@)RJdCkdHywZqY1D`@ zWQQf4Q6vzvt>J$vlhZmR$^+52Y9vq^?0(e(@|T#cRm!f_N-DXQ$`Zss^)CWv6!Rjb z*tWj@WbOzc7d!cCw15|PUgCn{nM){@2#pim~BfTO@gfOrd?KnWS%+{_M zQcGHLkcyZ#58c>HKc zF0k!nS}%I7c_rv*k<@YSWPA3or1zZIY-==d_G>AhYF5K~qaUz`RTcVR)iO#R&&Dk; z|NcGM`XjPS`3>bAa#h1Gc#S*Y1&dkBuY;&qcN(B3)Jfcs_$7|@Z0+1l(~GGcbISht zTu#aWq`$bwbe>tFPiK7!FQ2$Cpce!5u_@RVNAuC8usTx8@!b6M534&`S4DSvN7d%{ zrWnvOY||qeO-+%n$ClN9)N*xvxYT$>Z#Ppco;H4bmtEXDAU2Z4X`V#5Fm`>VUfhbPt{mX(!rM ztNy!+uZVo(q$Y*bTe!O0< zDBHA@_~WYHhwTMYCVhv?%4$EQV#tT*D)lN=>2CA(;xG#b=1ITLBNe|$Ewd3$p;deD z=(sDCO%XR?w&CD!=V)`le|=m0N=lzVg?Rh6|16kw6WV}?Xo=TLeeQZ1ZziKctZG_MJ?2g*SabU=id0AMQ~X~@9dff0x?S=;eNy?os`0+9e=-=20$m%UFyrbPRpfz2U_k9AaLK3&5b@@dl6WN9L7 zE&7WPXj$vubq{Q}ZEyw{E9;r$&bj(0P$Mn((a55pey2rh53D2e%wi}rCvD)cNdeyj4Sx?JlSmXO3pUiwPH+|S0I<)dzvTzL!fY!ivmvFhz}NKtmfH2D zrW?xoXC{&OnQn00eIZ6tG4ktq{H8-uH5=FiGA5Y@phT)&VI@jNis_AEF#1iM$1*1? zgtrUjL;gHa9$Wom)g%FuYG8+{`SKsC=83KToT~_#)s5BxunFda|1QqiIGM%@MCgdx zdd7!E1pqG)OW7XC16V(@=7X-T?sBA+20RfgK#Q#+SS0lbP7 z?$Fp+z#cbf-}35L`SC<~`{tMfSB}_m>+Hd_e38=Z(E?kFNfAk|*9ocBmo=Q_MVtum zC6u!8Yv_wh7~M8jmao}d{C_l^_dk{Y|HqG&BhoSA7-eK;9xE&3gg9nooMZ2dviIKN zkT^yhl$mjomB^M;@pgn9*@UdjLpI;*^TXF)z_~fs^?E*EkH`JK>=YIxA+e7T(a@;c zn%-%bz5R09Cpb7*G$7%{4|X-`aKfXwo)eOxa^x-zZ+OuJeYE`bKCR=4%MDvDG_C8i zpHGYQS51*2Z{JnND!TKGPRY||e%j)Z9j0B2rbzdDZ0gMUMN_!Yv|I5R2GbyPy{ZgW zVJ0hJA#%Il2boRS2+8L~3-$OwwbFnyI<&Gd0P82-K1<7rsZAr&18>B%dW4%Dr!Pn` z%X!`I$5*Hr@RMhUf#CE_&3czYio#-YZvg6v0vtM|it9AMlzhQmxX`aiqE;?VYqMOU z%Xj7VDvkYY*0x0CrOnau!P722$_GIgNP+e}?|0P$7J%=ikqAJG-u^H38glyjbI?xI z{@zxInb0%WEFYC(hLl>WpdD3lXL_8w9OGhY;U7e0BN~|uF8hTOZvhH~%7e0;Nj}PJ zhk-$WmHQk_PQl>bTu@j}06xsU@w%v6JilpR#RdYdF*{)ZOoStex)NoXJTmH=WQ@v@ zO?>`Swc~6r>2km~pD-vTk>Vdxg~Jx=RhZTIt91D+^^G6u^XqE)Fv@Vxy?lN?llptMkR=L zLeRC;g)zO-wU-v_L(lZAb|>j*=gL#Lh>RNKMBpJLR3DCxW*QGD0NJRpK2XuRxeST^$T8Yq#VzK(b;}xKcF1dI(`W5(?t*1D& zb#}&rm4mi>r6-DNS?ayOxN#OxY?Yu!&FpWq5P#Ix{m$~V>Y9zc9!H7Y;;`-4V;4#5 zPFA;&kS|0sRqzvQI5_XC;E9u@{9yIH^b#SO!IJ21hm>lBJKY~=GGQMG=ii;Wx;k0| z;c{oBJFZ-YnEe=%)4+^9iFNqmR29DH0~WqZJDr>}K*mbV4U=Gau%qxwR|3MqgJsVjT`vd}&|USw_Jv{LKy!P?82)_zb^CsT1cV1oM(_9= z6kwt709z!RqolP_E6N?cZPEh%Y0Os6+MLt&o-CT>Q-9a2IY>;*kKh;iHH!^nB*|SM_~nH*Futmx0 zvtJWj5W)Zq^6M)ICHFUlFKhlku8s*n^))DG!YnNTHPukduJiY-$m}{##_H?Qj~zd& z%B9S50!%kEt_NN%_(Vy%14;hC%FJdd_PbNtq9^LLO?0sf2L~D=9i0vTW_K>ummVdJ zAv-%i*4Iy`7Zhq$GRbi~W;Q{~%T_B}x}Vk?#!xs5dqso~PBQ@24TjaZje*mF4V0I6 zHCm1k|5#?@jt^Z-JvJ3ZfuAJ)GeeqT95zMCl8pzbCvjwU7eg+`tN8>Fz9*LWog%LLRVwh``V4oVHH2|Hg5SO zAwv@9azFkLL1K=-bg^vA9ku0day!VdvG!exuU9}7rg|lb_DG;79+Zqej8pUIS1>`q z2)O>#_5V=nRGw$cxNBD$3RJQWXCI zQ%6%nybtZ01S5{8-1)9m63R)Cqr1--c=dD~#Uz{mg>xp3;PG0J;{blDC7l_yyk$*- zf|8;l52f|zz>qzS=x#CW(;xQEV)5My9<^sbV`E@%<(FkdQWw2H%-GbkOo#S#{(lz0 zV!3RfxfWMXUlz1I^P*r+dRS#pXw?Qg(M=AyMy_b_U*$Kq;>E(W@h29m=+(2_IxF#k zhWVWd=ff{dxt$>^8v`3tI~UtgEXSSoISeU4e8pa`LDcd;OfUEQ%@kf^)9i|OulR^i z!{nxK6!T1IZ!M)75&H!t4`FZG7B%EJfH&6pJRbi0_sP0Z5ym(klK8`76FU;{pa9K4 z-YHmJZG@mw=PqByu&uH{4L#_96<;OB=38 zdgB?j@-i8pfeT;I>Uv-v4P8y)7g=8v)r8&;OhHZ72h^_%2SMTJ=tTPP>l^g3(KHnsKy_rE zRAG99#|aan&gW{fc=B0ENo!y-nDH7w9NW5a#vWZ;JBV_-QNq3Lp9Ag(!Ix^sx{-p) zk)sdv8LC@kUfjQm5+cA)FcJ2X1TVd7U{iKD8Y}Ph%D;eut}F3^(v^2k>81kjPDo?xK*5@6PKfcCAIoS-n9O#+INsru(Yu* zMFY|#G>LbtdjI0X{HE%sF54B7?d5MRF+WGoSFQ+z)?)9w8{ED`U{~Kwl5~6w5fTyZ zq1A|5J4@z9yr3YGgumL1TaHk(o>jWC4e>7uYG=18_&dpjNMe1muALQy( zv_7U7@Iy*#>szQQ6cL{X41_A|2WbIriU2vaGitr}MDjYI?Zv#&>~1kLm@XXJ0@^2M zK|3bBXe#`@Xb^+Vvmd#(7l$D>Kb;SEw`Z5K7PtT5aU5KnDsAR9%KEO9-CB3=q+PSL z{9N2|Y4zLj&7Y&4d9okgiKz}YW`3a8uNaMOas|*O4d2q~xjIfxZ|0bPygWASbj2M$ zr~{Uy#L=e)c14vTJn>%{czifj=Tt4W{RbL=@4>U@P5DFZ-?B4{Ru9kOHj7(}DxHzz zm{E5rk--6E*oP<$$)8gR>L4_a~km{8cn%ob;>84Jx>)2?bO6oL&S!!6V7=h1eT;%Ma$RzdNwt*{YGaQr+;-t zn8h~MMQn|ae7OHw526Kj07utfdzie-+YiDuLK)B8yl2(XLarD;UU?=5^|cXW^7!qU zj)#&Vd;PgKC;Pc+*?n{0M;6!pi-b4NyZe6J(&YExSAI40HEyhQB~ac^Jq0&eF8;b%zb zCm=P~|4IxkbEur##dQ(dW*B=Y$SL7#ek7=A1Z86IfLos1hVcv_j-fy1QGnHPB1zHp z`OfUGKb3SYu{qjlR+R_LP8@^!Ikv}A2`Nu z3W~1^AP7+ara!=L$Bon$hP|chF{_E85gzc32pczr(5=M+m zb%aL{66wz|FzT2<7j?|bJ`0a$X=4aSI0T=Op%#p1r-YSScv$D$ihVkAmmER{X6>fm z6zzG!5y$CG1TApKgShGH0m%lG>aoakUXTocb{half!$RPk~FV?BPI0>XqosH=w zy(3d!a6}991c=>^h2HJS16tJI75ut|tI$7btI1=3kl$x}iIW1!JBkXtn{=1sxKXPA z$^`)!0wpt|i;0atr(tv@dcYBJF1SzP_X`9my7~lS*%>CAc7= zUvJ1wC9{c(u2WjIr-aq?gIaDm>~Qt6V-kaUdT;`4a#)KKoo9oF()JGoiT-ICoENqCfOvn%Ko$_3BjR9|Zq= z+LRX9AWk&PRc+r}oZGH|a8gKf9%RXL7T$>aky=3W_KEO{WFo}0+6HN9gR;pVa@8zi z=TDOYscqVsZmy&i<~)Q8X3`MC9{voIyo=CT#9Py0#aE~=d-!Cp*k$(zIIPo zm?;qTt0Di!XNyMQX{0A4m`lo=9fL+53&m36}^a19cej>GY9TVqUwJ`#E#}ZWGny4!uw} zH3KhlbRBCb5|#OdhGLAh9udCT^io=#Ez|tqR$ibl?L}uJfEZYpmFq+v1ep;9@(y>YVp=x zr)MBg(W)$mjp?8gSCr8>KTs;>Yc4ED&OB95Y6zLyITY%Fz+-7xXV@lH9|Zd!eY7j7 z<-f~p?||!x_tt7M4zNCsajg&h{;)%|#t0lFP`G%@Jp{=V+=&0+M^FAHjRAiAwi0887ms{poB~8C z$-$x-EVO?pqPtPLY^DYm(;vdR=5O{%>M)`+Ku)r5c$;^)eQ>rZ4XAb?_VI>~mzh)E zf*GSA{t<`)aG0jTO6ytdn=&RW7NP^RJnY00A=1xlV?d|&3r(*QFwIusY<6f5F$N9r z?|wS(nBizh1j6VG1e63@#E zm7Zp!C~YZ}0t}-IA4zsh5{>`yw6d8ID{Ok!S@+4TnZ@c!!+z;Ec4>C{KJG8zM`ZOO zADbGaiigvB156(yY7lduNMlGjTN~>VG{=&_5{&;p2LGMQxU8(KVdbD%R!$z}!Nxs* zmS$AycX`eKj(G8GM^9flOD2OTx5`(RvbJy9hEY2l99{K9!D(bsL5hX*$3yd>`;)7J zV={xA7jbbfy&?}1hP%QSUv!jUH&KyCO2Ag`>OfUxvg>fj_Cz2Kr2YiF_|>iGtW&jc$o67DWGCWSoc9+`)5m(A!S%`DUt9l*!+l>eSpjGd0g@=t-zbT9 zTWaTa`<+oykTiA7NAC2J@_)W^21y+~gA!3R zjG@QJFwJ-OYJly&g`4DE-5L?D$X#i8$ZPWgr2@?ygXlk$O;DO8u(}4%A2?)@VZa9` zH!-nUozZY7{S@>|1~qdg}@{Su)U9DSEM%V*dO-hy$H z1R)&<)$|BMJJ%KOpRQ0j)NPL~PdQt)yj0$-05(eXmU%&_i8wc0@atEDg7Ot-YKC}j z9fx?M1u7qA*@CnYyKfJMmuB2Kz%Oaur^zDDI#-{(9>!xrQ4{zzn;n0-0%;;2n4Ldj zSogP)$L;$|RH`?)pJL;{w>de_Nl};cM`xv4GuRQfO1M#-XpNtF5&sA~H?w@$;eNKy z&O%?o{mTKbPE_T{*7VW8kAV!g8fC`K?#8D{hh&GwlD~=jma4h54*=|bQ^y2t62Btz z9R;RvTFj@w6HZZa`@zLu-Jx>RO#p7jm_oLwf~z@rLCY#(+p!NwQLfJWIHH!k&T+sx zqu5aEfz$H#-1Dx9G!A_|urE+1n`w_YJ57~fqlMsSp9eiFxLTlA1+F1%Ip~u%EjdiH zsXIa4oLt4vw>>Wgy{;H&a~1A#wgE4;$K#civvFUkCAyB0yvN>BZy|r5JtNmMI0Je) zs^=$RK8*nnGBqf_PJ82LO`3YOsP(~O+l^XeWp)D| z`mA>3XL`h@jTOdD)JI>$aRttH>x{fx^ z8~)SwK3pKjoVX;fsQjy#uJX=HAPDjDWxZw?>+ov%PhznBr{<2a4gWhcCtn=HRSNw! zOijmAGDC_UBS^e;)dNU7v^~a$&?w4;GlPWE*)QL@I7UDRLAy8@#H6bi9^ zly~9D6!h}D>()+m@js?CivVA5bS#L+qiF=sw%HWejk0SF_~j7$N-ohpo?G&oorZ9E z(bpHSL~`ox*tec6xuyg8CcHG6&M$=JPz>;W<(pY~koTszGTwO0)iN`k%rdtW8XqFk zk?n2gLf>LE%uJVt`^nV7@adyR)Vv3RS>LC!MF1f^wshg*W|Ys=4t1nA=^qZ*hyle{ z`jWEAXbcE!K%c(fIx{&(OMa8dTT#*Tl;-BiQ{@WLQ({Y`5_;+CPw_>|)xyrzgPs$n zTnUPMp9G1q$45~+T~GP-9Zetp*uE@$(^J!M=P>&_}J=82iRd`un~DKLq|rSQ>0U zKy%c3ljbd`x4}4oKgQ1x;H<28m=9Kmub1b#02e+f2;INkBXN(gAs2IMfXr6+_qG1A z>KfiUNj3IgZTFz+4dQQ`;Sioom%B|Uo~BPqHv)b*yupdouq*!Xl(}}n$^Dg57U4&r za%E;R_`r2c*V9+}@R?_0vrKViz~c(yA+{!^y`$bhxCi58dgp|b=Uw*un*EW!Gd&}X zFK;F`Z$6^8bEQ+ylfFC{8?ME@SDu<*Mdt=Y1pEI?W?G~U5Q~!>XrME3!aY#hG$d%% z6!OO#K@tKUXKQ{>FyyIjCdEfxNEg42HFu7X%XfD?>xe`mp5gph$QiGxGgE=!&-4_B zv+r>CwzQa)3ZZ-L4>$ zKWe2-5fKkdQ0ip(a~=rR1dYqQP>;$XEOGZh9@+TIsc_JRL7>A+vOS#=X6Cu7r)zls zB2<#ugdq(-n$$Q6+;U&DSA>1}CchgxyVRF;p=(|YkWkMht`=3#xvr9~o=dSQ>X}av z$-aQ)m(aDFxS;@C83hR5)EM+!aZr_XP79P?CX?ePCr1{VIDC#*Bs%h3?~4DL==z6v zD~eyH2AC7yYt6s=d-!=h^9zwH7FlAfaTa^oW{nW??*3LHo=W$y#=~_t+~!36O;gCm z)R^-tOR<)Zgc{Vi(fc~_Ixz_fY92m7=(R*z4U|yv`L0NdrKPy)ZJm`z4>WwqBM6L* z0C|!_iYuZZaG!e=?ftQ%d4IXN2H0?RjF}*wE>OiA0WCePe8t^!$#f6o?SL~Bu0nLU)O^We`6K43 zTV0<)S>7to8F1GZ%4SNCyhabT22q61-zQ?6C%1x@wC<)n1jkUYxHAPuzAcwi9Bvd! z$sf`xa*c!-X(jBWt-94rs)KKwl}e@qYWq>Gv6|*ubRxt&giI)FO2`qSmfW!Zmk&%H zE9~DbzXXcz*5PL*dF#EvFtUAsKE4;6#qA?oEaTFeTx!c;_faxE3q5%J0x zuaG2p4J6KDoot7H`al>5OIFhWueMitW2C+xDaehT@y409DwLY05vtuZWuSO|2$$TK@ zBUlQ;ET<;RT`Y|%R$?zLDRr9SJr~aIxGeQ#NV&vRU>p)DdgSikH!uhVZBqF<2RO?b zFbaFTY;5|k^UQU=CVO&5WffFKN}+ilupWKK@Q(yAFJ+k*P0r314TXAj?Dd_OhLl$a z0_rB4B88xaD1hS-e3`J?b=hp2Ua~AP9}*;kE#kc0q%_z|YZJ1Pz4w&a+vj*~alEqV zdgfZ(5%sEEiw1?MsdKa+h&>uj6@Vk(fJj#775WRhJ}7Epw;$c_)3SL2rK$QG)JaG@LY4jM02hpbstG zGVqfENMf$3t#Tg%ot>SfUK1MpdHy=(@jWh!o}8L`^ULioMig3^oQV+bd9WP)NSF+y zq>JUJ=T0sa>V^8^iRKeHBEUPMzTIPWyslh_p{HT6kyqaOmu_IqYVihE0X2zDZZu%a z`r?yQG4zWoJrRiN6cKQJx?8t+;xi9p`EJLn+c2YFxs)!36%pIUpF(S1HZpC8469!C z0yLPm-FAtNeSXn!3U%Qj53kGP^5H0P1NJ*ytZvqn{50W+N#&v3oat2wtM;%R9}}6| zc0lY@pE)5*U6uagAF*0)qql!cB65*d@B)CpRU5M*m7anHP_0{qv!vYj|6Qkgw4?0y_93`9Mn>6^R#7+vF>)5h={H!lK$*rIhn>XVd&+2 z)RC+DLgjk6)E&7j3rGyN9VhL}M~{Czm))7`xEOiVLaN@6`}A&{$^89XhaVT*V&!B2 z;Stgr2Z{$h^_UOYEY!`dGe#?Iu?ThxuJsRFnHz7ZMmDvyl!~6u_!$m)F!`MK?OdtG z=L!Amx=gEcam$fmj82xx_e)O>4aam=Hsp<|87=86YSombvnL7|v(Qe{zO zpcFe!Gzb!%^e9OwZ1vr0VV8HL<1<3PEzy;Q7jF%VocJR0Z2hb{vAeu-AoD;J@WL)#9^~w-Lq#~o}OEm%d^EdlKKFS zj=6IYVeHb*sjwsbWKyigB=#9Z&8|v z{|T9UE>jy&s70X=_a-$T*YqDlFWBxSFvvptA<+#OVjC*QDkthl^>jKp<-Y9|!!-f0 zM(M4%s(gcC@Zw`eHxtK{)O$B6)ERObv>*=2V4iP0AkYVhqq~>|voEgR)D-!wR1yRM zI>F@-b)ID1QWh*O0=X+M|5KB>}4O0CC1KZB{! zkNIE@`DJrT_+X9y8va9aIQkP2;_X4u60_=A!EsG=v^X7jFcO&7as_ zRx0b}rmh4#`gMq7J&MkL8(z%qL^M_x@aaozd2(@bwg>ItJSF87RnE_A>Y6RH7ruMK zTILw8&+;`Q0-kgT>>x?M&S%}(7Q@*WaNntx^auV`Z4>dCZMM`6U`SV+z{zQM4EW%~!7 zaG{IEmr=>_7c=InmD0_v^{@vD>&t~bcJdvcAopN%###k!p$EY1!S%p^^yO1@j5IkR z)MUEk9rgwQQ{VItTV<`R__$f}iFAJ3DAaK$bksu)TquNd;{C;SvAAg%{qL2yHdb)%qwyUFgdbfM`U*X zTDOK@#T_N+MQ0|LJx4#Q%_$-Go{Lx!Q6=HLE=HCrhtab6eO+fqm)lNK)Cew>VD#Ml z`Ikb#Lu*(!+bPy^Kk(!Ik1cX0{P11)0Ev{Eb74J!59@;65p$s(lW|7EUQv<*E7|$# zf>RIMvnfxxh>utDBhg=YPcJ_R@&TOR)c)TC&6}KS+l0V;fwX$E(#!_U@!5#Qgqu66 zAo9%;p^a+#x9+01^o-OParMBjJ^LKcYzdb;p^=VbqGWLYOkQ=5LI|%;W*dz95j87m zJ3#ZT7AKYce<|7-Mb&Z|;aHOy{&TTSOW6UK~% zoxl>U!0K?lvR=rOl7bQ|aaSddrHlR-#)xDW1xxIm;=jOG%(_$RwVvm}E46&Sj`uGA zsYD(eXXozZwf&l8zj^;-A*^QQo>m!#fl*kq$L`0@jZ1>meu&v!iyxlqDSpfk)L?*Q&u?^_->Igd3SAd_91H1><0jliVAnUzAuK zt^Q*T$*E(}z5WyVRYAMI@CbH_|7ncCQ9Al7vl}BULtrm>22H#Q8`EjljubDR3nnfk z?5cPZMv_?e=FB?5CBI`eLXQEiA zX@L!d4|$BVXc$*<0f~Mi)sj>^g*IL?oHOkKy5Lt%lXG)(jTaXhf*b`LXT$$uMi<~` z^70=R991`|(8k(j3kCRqy{k=uQglw3!QAof{W1$2fe>mAGH=o~4{OChwm4{`M@ZoLmba zBMQA3Seez$Eq$kDprtd_x^PJktJ` z(6FiNW7|5sU$mvlK`k{mgT$Fp(lCMu55Xg0Z)8>&3m-h_I3B*tx;j3*KYzNrXJQb` z;`wV+lwf#@MCfn^klbN|V@{!w>CA0Qi;E-Q`)gA)rq&DvD_7X{tc8+WGsk^9P&g;V zn3eU^Bv=I!zxMaT#8v=lEEPbW77$hoMV+xjE@J@RiZ4WN<3^KN-=eoNJJB>P8R6k( zZ7R39qR73cP0o|uZ2YZa&yyQlMe(9T^cE*?&*;y=es|X}j%Yce93JSx%^5Y?M=8G6 zbCq80@cFaR%wcLuYX=t9I+&BT8+6ZheqrXWd`D1+QJ744!nu6(i$WMop-_MI{_`2o z8?@i`H<-}lv7;yI(Dw2^PbM|jgHKHg z+W~EcTn~zBb2X9vPN+GzlxpD`V@ZdCDG@^68+4`dVOt2;rPV?+zA=@w_lJlNUb4Fa zfohM)*XIF_a0C~d6bsF(==b7tQCA%XK^ErCqu&dahLv`N9J#*`3AD!F?02LqV6m__ zSgD6GU(_VYwW>e;^;Zm=w$yfOnSgy{xL3uo$y?!eulyRGOC|i*)?s``-PLiDM8|P& zrRs$a*ZH(pdt`9%w*&{w+^5KniS=`mSHxyZWJJft&A_9HE5Z)W+o}$Qa$V+ww?SeRXhZk?lU!< zQP&J#(p=wf|$ zYLCj~1jeeT*PocKz_E2^d=8mwHg&m&iez^!bQuaN44Bg5e+KZkf)EeEFiPRF7W(K! zXnwDgPGYhO{$HHdj)EFp)4O|g_0wBMaFkgaM(WG2NFE-|F{pq=jW#p(5tpO}Ipmc$ zUWnJ*01P8s7w#ajW>wwnIpfYYL$o{$#aqw@mSE)YwKWay_jclpQ(9zUAUiq-I_(UI z@qO7<8WWF;p$JwoNdiK{0XL=&_qeq3$1@XT)4lG-B(RV-!9|mM} zG9|C~P;)N;94?1=nktvU6;Bv{viXrX6I{>qanhQjy+|zPak@D3V75_aT(q{Zw^n!P z4mKBoaxGRq{`O?tU#^OS^kUUkUU{ZiPrM{3z*;$MU!E7sS@^o`8{;qNzw~ta2~+8* zU&-H|&$UH_9{fkWKTv6NJ1q&ppLPR2uPU!N^Xr#;ewD0#OK#XIpZ(QA@%bMjk>Fqd zH;^>xaO>gUqickaRio>ZMN&9eT~|ci#P`+(boB4c$ERCYN4BC9{d;lLT#_ivCP46V zAN#a$w>)<5bfm3-?*-!Ddn<8Zd+%#tb2j7Q>guX`xmf(-Y2Eggs7s^iW21^%KP8UO zXJ^9=q9QDtC*h0OAn0I)d#zynojZ4Ix&jmYUad?L|NLna-KgGJZas>WD{#XV(rP*i zW(gY+ca8*8k&gOX8?L=TQwGr@b~A$EdlT14ja}qH*BNc z{;3fp|sVTR1u{viLE8 z6&z>}>Raqq7zANq1xq7d=lHq{!qq=jCc7ovmhGuX6mELGeGhLa4jdV#X0zEd7J$4S zH4-1g0H?o6pIfuPQ9cL;l1<^w)vKhF@y+5l#x;C()h-=ax}=Z~MgC|!W5R8EDXT*a$lm!BoTzp(-nz8(n0CXIo+l|QZF!%?P6&N(7W&aWY?-c zsw}*sSY2~7Y3=uXEu=oepD)c*Q>}r%r&G4z{8+cjeACy%b@lgw^3cA_qG7R$!UH8T zMEOE&V`F1h`&brSuOh4OLeR8zZi@523RmjkhTLtHDF5BR-%Gz5d$`T)eGfs8$PSt8 zBxD=`)YyaXW6-5RiLT6p(==q)>4xCWEEA%k!NT0sbRyj$cz=0hd)ua7Jh9Y1(*+P+ ziaJ6Vgg+#MyUU)?1v=-pg2zjYPla?t^Z93PD6N z$ymN?o?+Hm>y%Im!spqai9f1ag&xA=MtOA(r;j2JmiNv~ALAxG$R4`lj?#U5posGJ zAY)+!((zfoz~;DO;s=x%<0{7ZSyzhhh=r=K`Gt+wM+>r;v=N~%-mur6TibL=ONXJF zG4ViWOx^_lx$XV-eAm_baO9kVV8U-s2nEmn!2vT(#Qxe||0GrE*3N5VgllTQZ)?L` zKXelh*5Im#nP$4oDeTnVgu*^fp`)MX=!j#ysu@}4kO3M0IN*O))U-JX{? zPFSK`*PHb}nvubPSm-SHd@r~q5%dH&{Q=MC;>m&#s9tpB?pK|Iw zIF?dkrL+{{p-@MFLx-Bi(`IDgp{uo-_wdp2GWuc(2P#kxAu@zzMBsvzU2+d~x&L@x z?Q|Lsh+q6P`IU(pHzqcd#{S10&8f|tmlqPr(7U`ZU~LODGz0~Lnhr9X-(lw03`6m4`|8$V z!Gy}m0N@XhW0QoV5Y$KIu9byB zzGy4+J~C`KFyT4&ZN1~~rv?Q6xXDHV91%~q5I;!mMNm4Zlr9>A7WxFSLh$HY8^a0o z|H_wz`>&!E#~=jSV<<~i^{J_XJ?t4&nshN+`0>G9;2VnBPYuW3a`+T zh7>o4dzUrMZ-&t&zZD|FuJL?XpF9D)>Z(v#)2(L_K0e}kAVeYQ?9uSQ;=*E1u6F+; zLZd5neBvX+JAbV^(8X#%y zcRDWP+N4zE5gCwy)(pBF(n+(&M2z~9GDT0cAEfdTb%=m%*kQJf1Ql4{Bvwz}By%%p zuKnmDXrApEdQ*UXUOve!=cSxhUHkq35X>5q?@LCxflg=qf@+VPAJ4S~gh{S_U0`rT z*SqCcR5{W$p8R~`+>)Dizr}0r(;dh2wbG=q^;jR-!a9TWm-AN(4^o;$2R=$m77jrj z)9QC-uNGV-c6^g-PRhh{D<2JSt6XuuI7~X4H)Lw=x;g-uo$;A`-&s-}I>eOMYN1va)%4=aUOo5AoO?`a5c886oE{5ws9)dai_*l&0z37oVe-pRb|=~s(w zF0aCjYI}!yFqJZ?#o{(cjo2LzPz}`$q!V7sCkRLx<-+bUl*}`^aYZT~)Qy_>^hA+y zp!@?-hUo0J0atrtRb_X3;)|?{H70h?MsPxhrK1npIy$&w>~R}rW;&aKojPIRbr(}H zxXFtUwp4s!kO{r({8OP0Lw@Z6kLOu0nMLkq;I{|tbQvF%zpMR#QW!ztPn;)#CU=_@ z{)<37lx^w8PlU&HH6bd*ZPY-tj`{=now89rEzp8-6(3S8cgtSTp-fHQ8J;XUDDMac zFe;+PO2T#AMC6gIcU-CGf({)z?MJewsM#tN(sl2CH3Wj#rH zIw-j;p3m5NdfFMJkJPc7JJr5>0~$l_NQCxlq8Y$~@puT73jZl}#G;SttD3w~&ucGF zZjI|Bx??34bp;3^<4<^AO3?2A{|uT#>jqCr$|;v#Q425;i-e=fv0 z*kO#X$NLz5TVMa4wd6>NQVzkmxCPC4NY)AhT55uV1IGBhd8)=A{K*h*XpEF45x!1~ z%(>=T)9;i~w)*uevVx?(v)*IB#5=&p9rE$Y-_=88i=L@aQaq@oWt9|?6V!gh5K)&k zVcHLfv;if{{rA?Nn;J=TN=JyXTJyo#4(qr522md@aPu8O5}VGs;yVJF(u`zp#~;4LGl z7aCWOpPc#$PdN$i>}cjMql0hD-+9j=ywPyYvE#IQPsnQl2@W{J+jo%TWQ=ToGqv1byc-j|rasQIgb=Y$CtZ-Ft zqp)Ms>cynHEDIYyy|u!fz{E+vk%YFY6zA9ePm6*axC`64Mx>Lqjiiu{H?)QMyW<;+ z7&ojk5Y$`{w`AC-Ub*dom7$=Wj*F)m&AusZ?{jOME2le-{(UxHD-n%AWBO8y!zX1v z-WvoM()BR*v?SM66P%1OqoYMGzvP`)P)FCsR@e@gocNTs-KLFB9mORM?t-paZ={cy_JX(sS2CDV-Bx$L)JPZ&$TM=2$k2g zF~$~D1QL*AzaRiZ&zi-RHEZt8Y8(}!qnVEp*F+joDqaZz!}OJ~_5Hpm(?Py*ZJpWL z!G=XW?okKpB0U2UkGmfrG`aT@)uLHU6DWf{#GKxY{)d`&xxq`uTJOou6I?k_N9>U%b9pAGjZ>#U&Elf?HWoC#VO>f=JsHk$wmm?$7 z&gA3Al)cc>;4ZT()c_)48eGa`gClT|2F zpbqb9LYrWL1O_;{gH6LHhHEtgpJBBT3aYFnV`gt(Qu;U)x@jwPs!k0Av9X>Og`Zh#?oRj z*40!humb0enBQ+EDBw>4de%FL?Zsr*u}9ZwOYv=GlgyRY%e_t2kmI%W(yvLYW12|W zu753&j_s{`+Z{pqZEfwJzsB=XrUl#^0!u>L$0I3NHIejM56c6_WDxww90?W?_J`cZ z%e!k|y}GQ~$2M!DM@wZsr@?W>LMV#S#M(lxmn;M%+$NcIl z4tzAtWv{M8Ay$8&&A@*Hy{GaM9~gE~QY}Dw-RvTB=P`mTPTD0XC`e{Qm!MFZ8~E{2 zpL)rYuKBxszTbgkgq_TNnOgY$iBCtceveB(2%gfV~60Il9 z_1i(w!|07H>;_BkMn~kn?)6^wjOm(Y>ihi0M>=n&k{4U zb2Fi5b4r!0f=6>9k3>v!{ovMf`d^oZ_=d7Xt;KXb@?~xnJ`a*-4^(^|BufQb12#Xj zI*ci9GFPMKo&N|*JF{&OEBoUdUAu=}=fL#if~;jB zWxuiiVIF4_B{O9qF)`Oa^$R#;-o9OQdz%Zmh?xlR3l9GEbNk%E$6r}N8Q7b8pZi~} z?d~p5F8XKy={Y?Tnwyc4Ep4oEY{j>}r7@H#xXyH5N~>m zTv%U^pz0x;YXqQl&lfST6VKhuTJi&F#pF1@=A&7%0^fpLh?%3@aQ+9cjI~}{h!3_^ zmtm5BQafPlHl|MO3XjCOU!cA#>sm%8*W;7A_@#7^ECtj~3MV z-64^?`9!40LSiQaqJ!23ul^Ti2-a~Lz4Nn)NT9BWzu9A1?BXUktb>Lp56ED3-_&NU zy5&pTZ93Ou>$Ex|RR@b7M9Qrl9o?ii-yFA-d85X}-^}cm&u$X7Gs;J02Xm;Kc=)BQ zR;wchlF7Ico?$#Bzyz-v-T(a?E?l1F-)fORVAa`Xjv2JP|9%-s4#N2I+>*>dP&s9- z$3g}u9kJYR(WGkMmv@v$?g3=quY!VuB}NF^LiwF+Gpmj0r-iOqX+o_Z;WJC=BQosG ztNp)>a6L>3C>AKokH};jGeRlgY_3EUfsIE4ft+Y=HbWrqAG$X`XH_L026659$^KrKQs^lrM{VP?5Q)x?#t8KyWK!t{H$Z{sbebd;VTx? zG_tft&9MVKN3*Q>se0EAcGIb?_(PxEk9B{m&Q|NRb}|LcdS_X zO<}?P@lReB|8?!S9Qn@1uc7l=U~)?-DDYn(*Ml(6+S@mi8cDQ_7w)Zp0~;gjvdUj) z@(yP{7u*T>tdsd5^k7Z8uCon=%N<+^ZlPRMw%}Iv=K5Eo=8D4=9;*cDn zvayjwS`4nu4isMw$w%A@-_@=z`Kgn$rs0_!YQ1N04RhmKpBjWlcrXRR+q4gp#JijL z5MGUNzG)V0KiIb}`nG8I3H6_1$mlx%YL*-FeM>aPxz$FT5qJMS@V5KJa5v)g?+XJ) z{;~1!5~gxWY~h{RsH-iTApfJ4+-q?$Frp%>Fmpg-@G+QX4@Rum82j~vYVlzCcww@% zvPFDn{Fdnd(RA+dOh4WqA0`uJq)Z8O$w-*wervhslKcIVk(m1>_e&^ZQcT29uDOg{ z=DtK(AJpVFA#+O$x#xcSy}y6_{`c^h%icSe*LgmzM+>7*zx0o9_Kjk;_W#Zfdu)xP zSYJPA4U!+4A&EhbyIN|_c|eN%YN2R&!d{{{v0 zLUKriEqS@91Q*gqvUZNPyw~?aKY&!X5e4+%{5=UL)MS63veiY6&eH8>D=Z1LmpM?6&r!&R{(}sfy;K?zwK{94I=Y zB*gJ%B4N;~Rbp4lvHp0~we`mjK7p$%CLTQt*R7%X+(n2=-|}=Y!yftJj6;K+6qtvW zj|$$6Hpy*8Gd zhs5cbO(BW3fO*~8L5s^##4zPgJXH26;>kKKd)d|YRtQ>=g%Co1&4p(y1waS*AXKA% zK=~5~f>pk;SeRJidukxu@I5fm%r~p7l%(@e2ZtaP#+JPeBfE!7tR z^`U-=L+xGcAobR>L{7Iv#(R?%dGoVgM3j(-IYq_A!QaZ-GPou{M?b5)B1oR916=0h zRU|&udm+e0c@k11eJgb^(m5;Zo|*VDaz_X(VKXQH`&5ZF`kRio1R{FsJ~9 zHLJYAzJQflm|e59d`QSLQ$6ENkg&7`T(Pkq>@I2Bnv!wcF1T$bSWuy>V zbjUNL@|%&p_mzDjqf$1MIF}K#3u_P|Pymgb3`Qh^G^5wSo()n^^k+rBG)O{Egt({& zd&+2iv5v@|YQHoE7--P1Oir@sCY}B%JlZv@nm+m#>p)E{sq$5iJ>JiD4%^Bfn+~TN zmG&rn*ocjoQ?`{*+M=*h9;*BbMz+MkUI>b6NzCF^+FQOGoQu3_FZt~HOL9+Oos)D4 zZffnAR&i0h3$n)XRQa3KiX&~DPd$97{dBN6 za#!PMGrO}*fp7av0x+VxoBhb+i$}ikDv~{kB+?JdC@?mLmeI>Yrb;|@5MtcTQfXOp z+{dxI>8FDaJN9c&(mMAO1W5PuF;8?FdL#$h4N_)Zz7P49SimQYUtRHd!HKTe3fOUr zMayxcy#3Ph0{}ZlUy2!^gSIUQ=W#E)?9pHE22wU^JO1!1qRuAFkCiU?aNSAVo#25} z4?p--n(dULryh11eOAPXJNxL!)po2-;>H<6_su!B(BE6Ur6sfC^M>6qVpg~BX*_LzG|`6_zys1Ev+aE!bN#BDCqfeH!RHF-k=?S zIn?zqsA!&!J++Qm0N6@Arx(!%AxCqF&%38|JpVLMN_@q@E(Lj8l^5VhpmBlD(IJ#*Whp?GTICP<8J|KSTn2ARf|W}V-xqHg-9ZFUUna)`d-2rAuq%kce11`HW#)!xJV{ZZkX2mZ%|N?jY>{7sMwKxkEr}3%v@r^Jssh=AH`CebWS)ExnUfQ3%Q>dOQ@ABC%`Y>HAb$|9GMnRu} zsT8XZfCU1TCTSCm6o;?BKeLF7fX-12q+CB1y@SB@i;y}7;%F{Td;>Bp9t;bjJ^uBW zs}Hypaj@39%CO2Qx5SK# zF||lmDhGT#9g-Xtnv zgmpm4B7uS;iO{(=uNQT`wf(&2%B>OG2isQ^B1tDZI}d8dw&9Z5%K%{^Igu&Kf32V- zSUvw>Cf(Rrr+6^1wJmB}LbO_qMPNf=EfKnIrB5=4KDZVwU0ld>Sp5EdI3L}sT7#Yj=Lw2 zc%V4L4SlJ&mKriBSC&b4H>DZ{g|Eq$2FtdBPzO`1QOck6P|4IERb##Y46UG zH|U3(?8^25F15^)LXk2yHvXREN@Axt;ICQ(C1&9Lyt5$j+iQPa<)im|+M9fr>g}Ym z>BGJIZuL2orAmexY3J6RzU#FedvjA|6@EWk3f%QAvqH?J$1nnQ8Zb(kIsD&fe>T8T zzC!;RtiFFB4LCrOIEF=lAp_tp?}t!+Z-qEsSq9*JD)ycKvO7<@w?bhXAj)roN%zalPu}=Tx53-eILvwSsh;j?8gT=Ug>bb>PVG(^Xf#=aB zoTmOdob=3~WOWm{gzqcA;%{pGatM^dpn3g4HW#a4FNu7=^cu~uK{Ibk42K$#x87QK zP1!U{R(ZeQm@tV(4(?AMT{)ddyVAT=6t%1iaIa4jfa8{pokzK$3XdM?Oin7Vlz4`! zPDHF7ADR@Z@}7^h&0u2Y`L0}xYfLM}2?}v(VPTwcO3N7{vv_lZG~j7kP!9CuCVm>B zhqIpmWBeqLOOdRapWhnyRw}F|q<;}BcQ<_!r#)J2wUEGK!c;$B-0&$Ov#hQ^#1xlh z^$aQhjmy9@k~kW;Q-Y(|iZj#W187$2P|u8aO~Kj-gDzfZe9prx5oM!cIekMPzvFNNI87g0ZRvN5{Q$-Y4B4M|Dnu8SVw zeg`dj^6d*W4ha$jhISAx+EXuaqv6DRXF)#2&yjBk#C#}dLUGx39rol`b74EFmDuVa zWmUC6q4>U90DXV{QT(x-Q7H}{W+2`kG@oK{;d72io99v)(zC2VE;Ak@j&A@~ZK}$u zDOC7lP1oE~yIw;B3S5xWK-9C%;j7NP>8ORaW%x1{2@?kH&A@Mrh9PgG*5NwKe2g+P z;Nn|pLn*AY4uaSU5jgkL58wnLYn8dO0wLsQ#xZ7yKFu}96WDiD{FwS80&v>uSj+$O4g@Z6vSW(D9?x^lt|Eb z<%-H&LH(f-nEB|%3~2Nl+~wu-CIdS)jw-6kTxKf*{P~3@EK`q(XA(@fvfRUMN59a^ zm5q!!I5_y#^`8uxiP}1aTl189ex)r`>FEvItN~-Ao(P|+2){`B?5Cu1I*~zQyTmFJ98uKKg8%W5!{EJ3CzG$OpRnp*BhRM!+DL9 zSZdXxtJ3Rl*J78)Vvm5aiz5a5pW`MR^Zntjqe za55)-yeWN})fp2Wy0(#!#6A=c&TvIT#TDg% zFMKqlb(R(rXZ3dMkp<@6bJA|eYwZ7h^ zo33&6XZED4x2tQTA>q?}adD;h^K@eYjffrZ)Ab~cu&K+c8ikYx{bll4*0o}`+vU$f znvV0tfQ}LJ7UW`>U*>6#@_N04-?D;gi(8t>aNVqEvwiiDnOjdJ#Fmknj^~aS3?wt^ zl-$EzysrsMO}5QdM3+MKi%N0H4+)s)4=Z=xr@aLVusiHj6_@H2;o)@aCy#P2l6HL_ zeptE50Ae|VYZ9*8`8j@>7{3L6HX@N2m)LkF{n7}F=AGmfp3|`CkPm4g_u?KQo+PhS z>OhG@>R>GA9W4X#Cs6b&x=&=~RR;zTbKK6%-Dls2!j=;R&Ls^@wcX-7mklIb>VTuh z-c4i3W42di`n4LGSju=?4H_%poFfE3Iz=y$3cM$4wmu-Y96Z0!@=es~1*v(`LehG1 zAci3k(bT{$uA4r|uPm*4IUe=yXb5Vw^u0|fDzMwF}&hXsimxvI^%#;_w-kMKNgh=~a-GCV6LwzHWT?QK}zlRi$$nyw_(DX z`WfGoIlf@#H^MMM7$s-b@W#+b5ngG5Crl~tgSuLw@k4g@JoryJjXF2Uf?*(qKc$zF zasql=eYtPLQ*8Kpk^_B=swBD|vNly<;%_p3j=UrD^#NU<3o`}&h17Ak{jBQr^-}Q$ z7;bX~@XTGgi3%#>a(Ba%fuf7*=7S%Mx~Mg~4oc9e3%f7ZW@`fi})4yMzXi!CP~ z8p_at047cw$)C;{-{XBSI1u%_>(iH#ca4L9AykG}TYrhrdHQFzVXXE7c86ch?&4?~ z0AdeY2>g(jZ> z$vzK;=5dE7e&jwE!LZ`KGWqBl}z=Q8KF|P z+&@0VL`KRwjoD4NhI~;`xSXCWsDJtH*H-L}kCAJn)GiN_1@RjYJd@+!&JW?>SKaI4 zpdHYbW4BrdV$`2y?En1-kml9ZW4f7JV^$`nPrGaNQ|32XY$SnFu8G(hvdRQ+96iGT z#a>}HIZvkpv&r$JKYv78){nLX+Jf(A-;HUCHOpG?vgKV+)0x2yo;O{(p{a@U_q*k8 zXnPK>g#(?zkXZcHH6f7jH~)g=WB;vhNT2rA#x>7K-YEbqk7X2mb|bna9PS5&&pD$q!gpxhh>wtC!6GM$a#PYUb;>PSclS zB`2CKql$4`l>Lt|c%l+rLF|ggVMFZUYYw&Dsj=z3gX|B1A-mmqejS4&0+}zv7C+T$ zIfNxKc8Ayp!XJ2usm~p z!UQfINk<7^5GNvih9ydc#FfzNBl{Sb=+%*@K{Qhu!y6xaFarDs)BqUPzlQsf(2x*q zB&y3^pkr*p#o%DMxXu*!V$lDG#l;>lTBsNT3KuBBL72#n`YFnr7vR5`4lZ=PgWb-vw>Po`$cmblqmcI; zF@5YUp0El#Sjy9 z>Xh-XMkAc57)Wl$L8;-mcPK+i|c2a0hgE3jQANk9C@6Wg#Qf3(Gt+=;t

    I_E}M-SEl0h({6t1cQH_vm3Jzq>Dk|wYwVG*VVAK(v`XA8t6@Edg_7ST#j%P)n3s`7RJ+9SK--5b#ovs+ zhB=D&@dklq-0?^I3Ll2#?OJ8`l4TzGN68Ls0WcUppA}V_MlR*I4zq`kdCgMWUef6| zznJC8>6p``wQz2LweIa`ZHlj{EuPOr^J=@l)V+gL(U2Y8>>^x*|CgjGuAB2ilNNEj z($jGUOj(Sx{U`$F)?XyJ8_Mcr1y=ejH{D2ajr91U*pJ|eM{D*;h=1PSH{1++q<%=Y z{?NAjXV(7sgiX5RyWFT-&~PLVF;Q}&G&ld`$xjFqpz3-5e)GVM|)(L?fJ7aEuU&z)Q1W8z;ndw-U zz8~K5w{#9c5Se1bzIUj;%WI_cd9CYec>}DXaZv@?j-Ro7(+!0z$;oDS#P&x&`MbrFhwOf4jm z?y=-#^oF*FkN=O$_S~h=qRGc?m)&3UBtqd@rrG$d^LIzWgVDSyV~cV(5;b|x!C^l5 zP^_6|4m8(29@@>@KzU>*pYkl^67zeiAU2J-9z5EkZRtr6;$(Q!WQh;QIOdWWK0dso zbU3)v3p+Jkxvsb-1?7o{{=8bI((BCPboPe|5R)d~w#AV|+~fQ;Ep1&%|P?(mr zyO2Txekksbws(0O$oC9*(Ezw0nY&y0x{%ULce0ac+&Wt<9Zb>f!GA z!cYvN!steXiP?#dk3G5|;)ETaVmI#lPhW~z4s#h)Z`UPf*nHStZMSVSK|FUIm;cr~ zn7I%b?&+}$c;>dEw*NK^#QY(j1J!0NiS~AFm`*j~8Wt8SphZ%5DMjD5^(W;F{oUmj z8WCp=Dt4Q)AI#hlK^Kocl--fK*S)II($9>BNjY_Ju?5KIPql^sZkye~liPxF%Ro#V z>w*&R?aw&-l=l1+AHkEW>$CUISP-vXp}S{98s1O-+D+ z;mN8uwy!CcEs~y5W;|~YI~kUvUUm&_t>4I(Ta&g(@A-s z;eUt6HYr^Tcdct2B3pLdf-v*6smTya=hlcP^Y^k+n<}IaQK9MVoLdq+Xi z4~vVcbs@a$z_q2W-_Z<9Qj*xXOVsIX0&p6;+TC-Pns=xXb-L*`Pvq#dh-m5D{qg$1 zKQ>lb%>;0+Hvm^rQ>36!%WND{pkwrRs`Js@@gWDmW54sCTV#-M24`1`1L6E{6I#S_ zekd)P10K(5gJyse2rN;NBTP zHgu=x{U_N4vFBaY^9wHar1V2TZhXSrTAw!;gam&jC{*^uagu2&hVR+l-twyJ<3&dv zMq)m_WvekO^By7T?ly;x<<+08>pDdP#)H-4Lye8a0Xxgn(ZbUnF^&C2;Cglvn@ae$ zLRiTc^Es?AA!U>lRa(oI<`m61O#Z3&J~>`H*5wdcDc#zd&l_+6>SlH-*rfWFc0u}> zPV)QXPsIYX4?G~-W#x&*eOF`N3*3<`m8K2`DAUB!hJu?z?$2E)GNpiM%9L9>?z@=! z{ssKj^g(A#f6l?UN9|O{BjIlc`;|ETc%|rn>w_ef-MghRtA58vB$Ap3gD^c`yedjo zFHKfGj#Z}rIwUwUs6qTvhh^ocYzk}`H%MW251y=~D*07!L6{S*-7SMVw0SzVaPJ5G z|6sQ%)R2n-%C=Wj5*wQ+6EjRMLUR!4QqS>o%tCxxqG878$l5e2S=NBpgYp`xO3n#j zkHgAVdUot0Uh0cXwsB*#+@C-gUtqUD-(i_!S*vq%3|T%GfdA9`@mMc>Xy*1?y&-qU zYQGv?Y_m@l03tR6NrwHxFP;%fg!b9Q%Dh0y84dRghMZx-)`dEWA2*&pm2tPgoP)c7 zQ13!%;B-(xS0u^F_LbEYRI(c%s5%rowCY;|6Bc;S()aAkW8wRxQXI;KqD)4BGR&w( zccKJw5I7?kjm6b_UgqtcQ6>Kf4M?M2_EBZ@a72f2X+sd*KORn*dUl1EUjNG&XC5*i ztruzAh(*9nxzUE+?`N1$Ka$=w)>Neg>9jkEb35U+j z&8!bzg?xN-ij=Jm3`EQHr^Lk$fd}I57Q~6jbR^Eb7g36h-oNgA%+k59EwQ(I^1GcU zG_(ZQ3N8cOx4h-W~mPtA18qSH0PE_|F65^!us+DlTKaTh}d2C$ri{U=1VRm1ouU-C*?z4QL4^T|)T#ur$0eeB+pUo=`t<6_2L z<5#0zhuyxzjaV)|(dMa+i{4if)ND zlzp!mT1k~w6M){pVEmQTG}tJ2`%eFGoV>GnrOqwJQob9>k#Tz`DRwVuKqGYF*DqFg zi1{;Bo2s>+F*B;XCQVH18xPwhCQPsKeH`xy|F;)l`P*Lm_4eVefO<-X7NphY+g!oD z)U%v#_{2$8k_&e)X$)wCh{r~--b#1|})hkl*MPOr-HCbKy= zbIj0x0q=IvkqN+Fuz|AJ`iF z-4nYxeaexbc*4 zmQ#(~pWaN*<6XOUO^n+!+kXju@nRVlxOVeDT~iCIi*MN(&eIg!FKTyt-k1|f z9j^4+TUfF+70+i>l@Q<{1k!Qq^ zshK#JMiQ}CX7Rhyl+~~JY_nJHtRNJmI7GyKvdJ^|xBG40<+fDt3#1NYFJFy7g3;zEsK=i`VQ8fl3tVvT5h{_OIkkCyAcA9Tym`X)5Oox|Nk1t@W zk+6A0N~3&;Bg+~T1U5l1L)61qx;(X!aM)?`;azc77;mW=uM$1Q@;N7MYJ4=SEY8^Y z`2fX3HiZ>cft3-p=p)++sFr)jT);cDJ&*NRAU5G?l?22z^noz?cxrOLh9 zm~9^C*khIXu6v$oP{)g7`-}ft$sB7ZM!%2F#V*x*XNg4;w zVq%N(e*apx@g#M2iX}GE&ONP2=JE+~dgXk4;EY&)HiLjpdiAx|T)g(fR*m<$`q9hm z&K;u0)#p-@JXO1XQ#E;KZvW6wp4|!;eB*r=ypnbp_sM@`dWy!on^bnIVQb%8nT}sw zU40V=(Y~$Hor4tt35jS0{QJo^Aa7~ke6YRNshx9=EVx8FtXDN6J|>vz^lN<%aJWSb&>;s90-3FLhI#^@K(Sw#P$);9F0U!MxOIDtD8C4K z$1CThSAEgkjC-RJCPVyCuWH>miBU6@Oc}vTSQ06i5@0_D^Ou|lz4Mjmd%f`h=1%cK z&#v#WUwF!^QYif>GZAU1n3>}#5O3-;MV2KeKBp@5&0O|jx8alggu2J5i8C{>jb}Xr zA(TRsSwPg+Dw)GXz z)xsC1mp~Twk>#v9`46)0#Y4__2}58YVJ-2VL`4Dlrsm0}`~f=bzUFu8xgOY^WW|99 z&sWzxGxU0qqE!1!&nSA2LE;!lX%2h=TW@D@8@lAKMj(VdH~U@fw=A!ij(U+ncjv^X zmy{%4Mqk|njul49o_-jgZ_Pe3Rv5=y7s*=o<|_T+TF_^14&0)smh1udn} zpDxzpnEir7a|pG6Q#HL6_JHKBKBfb3#wC3$mpd}^tKf;Gq)3C;bd7(EC>zfN$n&{B z%4+UzuDlXWX!?Q1~q(S_d(oBf}>)_;BQ|D{WacKq$g9>Xeqy-n=H1=u2y< zlYfm^&X9{fTv13mmNVv}^SX4@sejlyxnV4ft$=2@{>=~2*^cnc-PYoZL}_O<830H* zr;f1g-$_pUf5e>HBi9~DGWUG7S#ezP$u^`mt9@u^3*SD-Z6IkCGvgc>C6dmr03#0>(MqmsK^el%59 z=h}y^^0==!*xcA^7;Yfxa!>}0rJR1guI8w9o_t;H9&YLD<0t)~LDm_{4gsDA_<*$| z*Vm_hr(aG_NNb%j`*TlNLRV>>pfI_&^vK6zOd-DrYrWyC9}0NH?{0wMWi~37YuAhiB2r8V2nFGYa8cH8WDB zSW<#$3?3>xxSN+kZsc;#q&Wu%kWBP0hH(IGJvE z9I@t8o=q{lrLE@h6WpcV;YJ3+Gf&50@X2KiVN5KqVf?G|0E~H!Q_$dHdEI9Svj=Aw zdye^z@RZ0kL|9Ur5)TTHySs(%cJGgePsu|BfnWK>uK#jg1yPqpJu_qt$(Z7eFp;^3 zS#+?!P;r^(^-@-0qe-&9H=zg|NhfV_U!Zqjg|Kza1vg*)2iu`+Du5-W{5s3|-V7JJ>!n?o%><2m+dbFt( zmJO?K%I)~|s;CyPqe5lPa(e9Ce8O!3bW7m&lE0i}N>r-@HtEw{9_bGUeb;HNVv&bc zQJi=6#f{wzSxI4wX4Ex>%F4c0kEq^$mp2DK3|)O*I*rb7B?buLXSWb4BLy7x1r0 zQ%pR{zc?Qc73KrOaDJdy4SeEylvR7OPp}VF6z$x&(n)de*ah;*=wpr;fZuX@vO68S zMjhO+9UjS+@?F!QDfDee@RD0BCBR9XhS%mro(;#uw%X+v7FzEM83A!EePsu!t>)?Q ze%_mZI4CCROKoQvcrncB^>V4j59RaJ#wUl{SY0?3$*gfKSb2aMC-qmkSmS7^-!#Li z{p2fU6&QOvUV?{-YfUvC$HdC=GVPe`2q+jG%Z&+xQTn-}C>eon3F-K)HqSA!%$V9~ zi!AwEWDVBfK#heayhdX9#ffr?5VU_F4CD2)4(B(|_Lt zg5|SiSjZ=uN+}^4Kx7O2jP*ZVJ>E{+X5)EOjig+5#7!UOt$o<+1JI^NmaL2}T}EAuhT??{s}}>$M$;?2CYpwY9u3TOtl>LxrfaI`ugbe}A2J%wtFfyG z*FI9t--#p{Uw2LWlJmg!LG=cW1+1DP?bwE=@AvisA4@mD5U8?n(0W18Z~Ps|OL~pt zoEa2_4+YLgk!9ff-uNJz$u$hAv2%AX4mmENl2@Bj&gmg`~n zc^3i+`XZzYAr6%0>)fC z3;l>fF}Ag&UZ(Kg2BZARpm;qpq`1u&u%z5W8v;}^1I|&S3%aHl!(~#4@!7|yKc%mc zXQ02_r4pfLO_kdej)Mfb6xKJ;kNcXe70YML=TI}K&$1~(;Q@4%R=B<8)InbM!v4Pw z(+D{rlMq5{ky6Yu^TIBvgE@f9qIXR-UIx#CwB84bDdgdIL&bPnMH*8cEy$a}ZDhQsOBx6!I>>A&9jh5Sh~DV49Q z301E5L(G3)_mJZZv;`X#`(oW!pjs{3Fxb630y4n-wB>LlhJr00F>8(BIg0D5Mk)xa#7W;`CCA5cpkk+jx}HWe#8%V@fo# zw>GN#I$4&I34{9ux7z`1A+i2NPsd+9fk+iKb#>+MMqA`vr_&gh6o zH2G0XZ8R6UzByKg@4QpYMrq;xV&REO=X$7f#QrECGP!+;t#2MtjFXr;KSqUawh@^2 z+IQDzE#X_;PuNly<`%M@f5vW>NRE{Dk8KroMDOk#xW&gW@4CW;QQF+@+P2d4{$4i` zSoGeXw?smNM1}+LoX~$tY!JJtR|`wMw38=O{f3_zG@HLIF4lQfK9A5ud^q_^ggQ9= z-s)jj>-ot_PR2Pv9^lWZhoLhO&x-WU)(}^B4=E~!GA~~2n4@G+5UBC66Y%=k$BJ6A z&mE9rB7y_M=qHYS$P3&TzREZi0`IS_zK1zyej!nGI>27%5=&x9>fFGbZg-yKPftz! zY^3rF2#D%)vDLNK?Ni#<{v|OHwxB7#g>=hQQxVT%qkw# z+3gG!%%F6TAa5T(JInz|(rCEShe8iRy$g~`D-tm-LP%9gaK+z?hXN*7DJUad61=W1 z(}%xl`|2$edkbrdO7@*pd=9ym$R*`&J64k^b@M@EZ#_4#wG}m#BLvb|=)m~(A?DCF z-JF^_2TY|i>xQYJ5*;|(NxaLtTSNT_wR3+qWvkRWSK4vgI+F_O%>}k%J_MH zH%AvdgA2w8^bux@k+}vD44Z!ZM)`Ctz0E7%{M}&}EMddkKI`z^4KyMsAUF?k#ETWyofjo%vPBC$su-4o#P^E}NSfKuXvHs4~hVd$x(ZrB$201Bh0nK5*^Ma%v zb|X7xadQ-Nx)d7YL3H51devm0yqrEvN=S$WhLam)>hDNk#RbGK31%K*V#ABvXvva4 zUx%iy*(wlTFv1};G#K~7il|ei_>2j>c9jgYh=iU*5zo2&axCx}zDr9Q48v~&`8IxS zTD#tVQZsjm5}JC$1;_|RJ|ua$Y0&NhHdEwU;u}z!*?F{IzNwvz-LF>pGn^t%^yauZ zH~-8Ery#XI+viDdmU(4J38b1Y^SL~A%JU#zar57>3-qHLlbRyD!fVWOJu6OF(hO zI||l%74C^=28j!i!*ffpreJu6*%k9qqSr;V6bvUvVn-N zIWMnkauM)L)TDh$%r_~2`D=bd@NQ(k<@UF=s5L_9w7~N*jnn-?b;XJ7mp`VbJ+N{{ z7sa}nQ=yw6OY>R+A?;~`bkyux0Our#`zGr9#^7VNOR9*e65GwW)PaHD4YU4X@@ikW z^?7a4;$5F+1&uD05<`4d`G6b1ATo(VHUsxU@fGN?YjSBxj=%VPiH7a8x?%x;;nzpf z4lg)&6@NyC4TOJEd{*MZ4d=Vmzc^thZ6K1(Wgh;&i_?yo>f3RVq?gDOVECBYJRPHZ z>)Q_1IAeQfXZOP)Y3=kV_Jl1UcftL5AokF?Mi16k@wwTKx z$xA_S*nB*zQsIr1q72jO37v|aMIQl_Sj{T`9KIL_>1t1`ERPS11Cq3DQ%vv@V$8u` zm@u}3gQf&DlsWe%j_VtCnE1{FNAjcD3sPX3i&7;3)h)+Gs)U1<6bA~Y$8!Ymg$(SC z#2Z7p-&jl%jvW4*^#{n(fvv#V#@KRzRGWuqE}3NjAuRo~1*LTOvd)%x?*7-XRGE6J zub;1|X;j$zQ*>>#taK3l=R>&;|NHcz(z}_x2Vt`N8-;rTYsUalh)5(ZV%0QM*5- zlfU=&S|n4OJmHDuiSYRR=FBwxTypr!n>t%UCc^+CL8joFhwSreHu%Rk)61@eOp!sV zivepltu>~Tht-ovNI@C&LV!<8cV5Q#wEHMGk>Fvc_9*w9eMbZnjvt0*h1*Iq#f=8G z?(Pi^oE{BO9?K%*9EKu-#vK>*&J0WcfCq(QS`{!`^|De?ih8{+jO1 z@tgv)o`LNCfta0}{NJPM9Im8`cQvp6G#YX$;ECPJ_nUWdj+*UJpoLvu-i2xd9oO5+ zK4?64Zg%2;Of|06u&LSHrL`|agV;aK$~+e$*nxl-ahf6AQ}tLM-wU;$f7C+hXt!Ub60g-PCqEVeR?cFJL#T2 zEmfF~Ib?I*1LCqDZn)$B)n6I-2|V8g40VM2{&SAqRgwPiZ|?M9;AFf!<}b0=e{X%3 zwBY)j^BS1VnD-MT2MUC;nKXyxsJSA~=M{nRTwj!Oe}s6k#Vw;(pJ9SwCQ4};BX$W; z8FGfAJQ<)!wEHF|FhBreNN0@%!EjOn^qy>C>4V2iQf>V5Q|CpvG6dx=pQ{(?g5BgD zhw`h@@&>FXCgk*o6`hv1lUZ~ghMtC!Zuz89+b*y{DOjpwLsGr(gEc}>+>5Qp$mg85 zK@)#!+!bKJiOTXFC#x^zkd%peL0}@ z-%N-1bYHG5$REd-NTm_OnqSc6mlDq<=zWxpqlNS zMg!lx8wVA#8I{ksaD=2FRb!$w^l$d+%kuJ;GSdStpBwyhavW)CS)y+sb02q>!m*ncK5L5ow1uc&Hg-t6k@Yx1n!Z{vS=}{?GLPzwyyx zq>Q{XB}~rboaTIpoRd?|ha4Iq=kxhc#GHqm%c+u4WQrlloHDUYEQcIgEGBb4eqWy- zzWW2Px$XISJg>)f-LHw^167BP;T02~eD3|heY+RH^~0u|o;-WkC@v~0ok2fPN^r^v zi}xbfTHbUFsNM2XtU^mn!2If)v#P&D8_O;@zW0j_iMcHvs==neXkF2CPq|hxLJP*R zIwW!Pc7Lu^deXW34c^n2?tf-6K2+ytbQj8Es(;-gb@-!Sc4(itd+Tx7KHulOX?@J6YqO zxlM6p?04^B;!oampHSn0l2c31`i7eZ3tv=*dE);S6xHScI22WNl{-X5m?7ek+o zqCq^5<4)ISI!1ruq^r|hOKMgIr+BK4qWzCTyCkyM&7!=sIdq=>j1NkA#h-QCp@VFZ zMewUIl+t!+a6>fJOL+C|UB=Y<)R^<9VI&D!*oYAofQ`i16qp zvOk+YHZEL=$K|U!DCkAa_|nI5b0uEd8h@53anQrUmxOxPEZy=8n!vO#X538Y7DdU4 z$Xakfy=zO_y8;*SQK8rwbR=5Iy3>B-X2#cr4y_=LzSmX~ zBdOql0*%8ZBBFr4|N6_#O@yBcophxeH!Jm?^N$>-1F?9D5D^Pl5(Geoy4qI0?cLp@ z=C6d*)l8_ueL=qMKCi}cO_06pd0&D8q{}HNRCeIv? zguTf*OA)x6=XC`F1B5A4eRzZqW-U$3(8A|Dl5yZHt+e@PV}{}=dYqx>J!YGsoZk$I zS^L0kJpp=gFG`VDnn3t)SHN>B3~yI(TL*%U`DowR?5o7XLQrK_SGF+{hcQ;2bC&E9Abyye^i(Si6g0BV5 zW|jMY7`u|OVks6bW#U{Am=3R=ZoQ@_C^?5SjpMP9;iQi%D$*TDR>sjWz)fSWJG=?A zsyK?0Gb~{hulYl@7J7v=3uFS#x|h`Hi1RZd)etllV(8VNBW|E?cyTO?R4;d1Y-+kN zm}Q*lY&`*dGfErCU;NPfM+07XXvcM@G=dn}$<)>5&Qjp9fguWxL4 zM|vy(^Iv6x($(gQ*V~~(^=hg>mQVx^zN!!U9^&UjvUW0iY3cr#P8qG`0^W1&jVHkb z*p9qEd{4l1lyXi)sHnaEimR9EwX;ocL^AWO&Al+f$b@GiEP|v`dEyBb;EX0CwBItj(MSdpYF!qiaQ?Y<^{=P^zechC-PbDfkW)WBs%3KvUlt*WF2Qb z{v!m#C7<$5X~F|JUUE5iITPR)?>yr>9pu%VEs-S)LqSFeT zc}@2+48*V3F8Cr~D3M-Kv#eO6u=jL#Y=1HX;}QLIIleQHE+WXTyAlwvzaeW%%%Icx z;}3`rTb{NCIY}aJ39)%N_>5gI90v6q2z>b2a8AHg?q<&+h-Wgl5WtywFlGrAt>^}@ zm7Nm-vD9)Y8Mu87!&tGxqG&|LwKGemkra$f?AiFFrmm=~0-(JW-yz#m7?oXy|F@ylJz;YJHVuT194|Xo zugy;aw8~6ROG7mk`cN4u2b%k4r!D?R2RG%f0(RVOO$OhtGw?i61*hHk zla)%r)XL+nLzlx%vZ{X3Xs4z5`?m0vlVdae-m%QmwhI@sL-LfbBryw|T7f+u?C{!(e8{QaeJWKrES9ba zJintRYXb$X%Fd^nr2h)Aoe-wnZ_mGX+!JEaTue(z<>~I} z-|o(+!@65h{}#BCD4*>YTcmdQaA$mO5fSj`3So+uIY1Xbr@p;D1bXqBYOvz^Q(zdJ zRe#8UN^04gv`{~0h+!Gb$BEL=S{BHy z#;q3N##S(20pW2^3g!Z*3^cSFmf89&C{o+A&IP`6Y-}U@${H}Tz!6CAJRYBfGz9{v zz(NN?bvzwb0<+^9T+QNUFHv<+? z{F)y_0zSkCY}mvfmv`?*$NS4wjv|nGFYQQ5=Rq4coj=aL)II2R47%TGX&*^BOCfyl zx!EXFm=WY4AuYsh0b%d4geF-+H1^shva+P-aDj`nFT*?PO!HC#@jU0?OWsVn_IlRV z+lE6LT2rb*K$_zm1xI(rrQ8mLdpv*cA=ElMQ@$c*-*^wG6#|LXy0Ssi3M1<_ep=aJuz^<)- znMc5#H*zBj$88}%$$K;D5~~iIvo1hy9vvO+?LW=B_+MWv1oKE@{wwSZ+tY;LN9Dn! z+x9-SJnq$FY49C)pIYn5%TG-7B_fa}$TICOLL*7x6>0(o*Q;iebml)_;%V$ z!W-V90tvb@>rvYiHk~b_6>9JB2%k1Gz^TVIN{Ig#=|BC@5?$UJ`q2}GOn!0Cd~U-a z-^1U(Na3fik~%-I1c>h7aVHh8J-E2?!OR29s*~OEgHIN_i44Ky=WN5$m_`6AZ^XtYr+{f!f(Yx#M zdt<5OD#zOS|e@yBhhN}4y6w^MWVGPRz}1eh8c0L8@RbbBtxh?4wIwDRW-zccWqUh|od(8&our<*`amxlvU z{>vhDcPcPp z&evbQl9nv|GH(Ez>47Lk;p8FgvmZKvJf_#A{LO=+4uxr{Ufs{{Y!wK6@_fH(Zj$5(9VP-8U z2?%!!2&+e@D3EX(fP7-kh9oqM3Mo_pH1vM~@}-;$4?lVh9n8;!j+Fu6+qS%A*SF<%uNJ)O@8BOqT2m~hxQW} z<=$b-ieIg>v-yv;7}+fQt$iXHM88nvqi8Z=Nb1ETsWS?DbEJslkZi1y0XL90(s*zmp`q^m)d zJ1uzdqZUZ|t(OFTpWyK`^nuzegWD|gpl4P7eGQ;~u3lx369m-(ikOnMohI$|{m8|H z2tnG_0AG^~-jDOabU8Zi9Z0|* zbBP0d`9iaHy_;~&cyy}1S%tc$T6cf8v);EqT%3<|%{gXM< z&y6XL^z{{6nAfysS?39XE^P&-n;i5R(AbZ{)bA z+I}6M667v0?9_EY=3`_D(6gX%BRB&E_foQxO$D^2cwTp@O7yk6*~8SLznZ#Qkfp)h zb8j`!WATH=7OKzZKP&e?o-a$)nq|f#7KTl(aco8W)UbxlXKcWGWSm8DDUTwwJkktH zNY*2;ThHqrhK28KO4ipt zc$AG&=#2`h(JjVB?2kIb4p&>>Og6d9k;$10LWUN#-~0Ca`uSrw>ARXCglNVTsP_sE zi7R4GCaK(Ur#aP31U$Rqjys1$(nlVYd#?C2%@rnPi@GyP)DNk=L=%|yU1eXD{ssyo zhnJ_7IgOMl&1&ZXebskE&+>Xee0X-%s6MrpBptg(<*2L>{t5FkpXxI4=Mn_eM zMm_qy_XBELACX0#D(3o^+%}ltcboK|mCi8b6!tC&C6P>-2XMPwYVKV65>KrfYVyi( zqeP(yV}|avWx1_CON>(ymzV|Xpjm%1|M5m@nRbaVf9yujWZb^wOC){8gYtXO3MC zC%Oyjp3avA@9ZBRc679CKRlLnIc?9{a*M0un(f}5@<3l*2X5f^bdHwF!~MHAhyD>4 zDKd9xuK zblYB;LR8d1{H$Cz0g$7e<>fq!CPwg@l990ZwaNJFPpg}!*J&du^Qy#^w$s0(?9x}m z{7Ugp!>``TNmtMnb_az;g^lrC(UTJ#9yc)(1{e;M$XTWH^0#$$hQzYMkS+hjTri{* zSIkKB_oz0h^t#q^mQT=x20ywYUpA9Hi_iipSUM%o-pAd9(|fDuJ#fptk6QL-g$mZ9 zR+<%o0(cdp>KX+QMo;D3mLZz>~zDc+MQ{N&aq1eD9|U07Nn-`uY}n*)oTD8Ft^2h!}%6}74H ztnM1CU0K7V&ui-mtiHZY)`g}J>yb0I{??b9+8kcgpqu?vUfc5a8~MO%03$4+*kGZi z(n*#nF{T7hvK5>Q@#FQOnphWETg&5Hv^fVv4X3ScFieE<=$F6+-|^+VO38C{`Z}6n zDmOrnJ6$Ok)e@;m-^!%g_)Yp^jj6ZnZjcUy(rbbFUD|dODw&~TERQ^Pdk3hk_&mjH z3C$AJdhL`!kH6{+-yXKI>iUrh4-|+zglLJz0v(w9rlL=MyWg~Nbo4QgBNw@RB`fer zut<&8^Rx`0LmByceC!|bW!XE#(?#3S2dWklx(Hmz#x%8wDipo-XQfv^yS{yh8Gyx? zj+Dsl=%3E=kJPoKvTJ6yiUiq}T=Dt9B?30vnEzF6Uco*N6z%ZxYn~fO{C7gLHrktC zFu3@*UTj>*>8s2FLWEJ;L%_mb^1mCVMCM9Rg2L?t{Qg8#@bVucPEkU~zW_?VW>mOZ zNqIQ|Kw=Q~S6<(o*`K0!gscynvp54<2fq~B4rQ1P3QzdGp9s6&V z;g-)#%)7lov$&%f+R?JhNnhpZgi8#7FgygtBuzCnfOGK+aIe~QZ!QhqLax3vTd(Yl z*!jD%C|aq>%a#f->f;Vc7;^V!Yg7E1q>E|wAAJDg-cwtyc5k#&BRcL#FrD6SmMu!O ztKqt(qN&*(w@8{Xqdl3I=I3M7)`XJmD@Tf;cg4#eOc4l#07acIK9gBl+59)Gy?v1l z=Mz7mK?BMZ6R*BX4fWaLHQ`9X8a3s(ce4#;H@rEo^8Wp8*FO8bJdm(2M0$y&0A5(0 zY!T~^m^XQWxIp@Y3U(Rk!uV~Qxv64Qa!b+9?lg7lMsVH~U+uhckaryZ!s#F^K z;*aKM9!h73jd$j8=DFwH#m5V7Tg^3Rzw8aabf9&j^STDawk8@YzCB4p1%qlfER4px zMW{}FpxKKtxlh_i+iru~VG6|~3qn^j_1V|w^ts*Ow4Wb?kCwbY&TLFR;uEh085sO} zIXh`tt4LzHhd}h9nvP8(nbz>I%4 zhL$O#mFEcMH_f>ep0JJCsq$ni2l@DN=~+N1YVIaM_pC#GOv~!3e|e#o>%?v$i^zZq zFIdy=jc^l?K?`k^{acO!C}}#yb$%svyH%{>IuL88bK)Uft$r8NluAwWYCnCmgn)q| za)YbJ!hWT3E$OA&2sr;u-{r*C&|&4d;w(4_q|BWVpf&|hkQxT4j_q{-w$F5?@t)6B z(L}KkPJUhnXpVyO8!@oN&_n-te+2IrbJRe>uNaL{=E#x<@NYpM#nJ^$Et#PDfg3=x zPOVX%E~_CR_>sET4qBN7KFn7mnn^oei`pel$_S9Vdu@x<#WGW*>f+!X-u~pCPf_vP zt7DVhJCaJ@*y92JR_tl?@PuHd`<0|{z8p}%Gj@PcvAf^PY-E@sP@qUS%San!k|z~d zhb|9!3Tn^Fv8 zJNczu!cP0SzcoLfbB#VbO3487i8t?M{C6=1F;HMtzJ^#NS6yaH_0Ibm7S5au2RU|x zZ4HW6dU&G@-fWiyC$cfHn1ie42TKlspI+)0yfUBn^0{?P*nyyF)ku^w-|xu63nHqe zrq+elTyJj9#!w|)PNuu}DDi4MnN_xdgeK?CbrzTC<;>GHhq;60rWj8}J|RQJa?{Du zZMSz(R6yYOKmEmjOzJ-ISBuz+utfL%BgCI%pJqg}^YLr8#~<#j^|%745io_i{Ul+i zy>7ng>Q(8)jyFM5H4Z9YAXrQ(~y6j^@ z4mHxV(|{z_NcIMk+3Jc6!RA3fz=29<6Zs0dWx6*0uYrV&!J97a6;L z1@7$fPDPaDPUAzMO55$7B54Qb^ty(00Q8j|Ead|#kLo20`^6M!WFa%_GB&MBZ2U50 z0dYG;Y@GK)y0zV;Mv5devzPjlZ=?~d^c9K{S--^q8u+~BYSI&5AKGbKjSu3@hI$8bNd&+#qRFG*A! z3<`B>Q{d@0#HyBJO^p}+taf;d~upP#QQ-g>lN?D;*t=?ByBHniN zpYf_q;Y#~alC>-82?v~E2g_~U*blb2-StsEji~R+R|eSWLKfp3m`lM~zG}R8URuJz zAoZ9n0|-gUPlGq|(?p$Z<2~;Z!&*XRrDIo&mKHa?_WaxH^?fmqOqo&J7*+Up4`jVH z7o#JvOq-||d(-~9T5SEAsQn6-nzWn7mJ^DP+60EH-@s{xztVKvqq#T3f4UKE>h#54 zED=BV5Ay$B0Mn086}i(qFkHC$dSX7HtMmEY3novnC4cAqumz%TTf7`xU$01aBYcU` zsH~L1mSX%mhEti7)%KV2vs)C8=X-bQF8ah-DN3$x=Ke>hfq}pLC?LX5V85lTrQ<$UJLf$l3 z7ZfP2@SF=+~)AcDjB}uy8r>vc9Qhd4+nm zpgIqGVhpcvzvw9QegJ|GQ0QWIJLV1#Cc7TAKZp+xldE*lPc3R<-~5#ww+H-fbJ5h1 zNz7WF(9ER?AOAS-_V7KQ)9IVDv9wPA7g*uto$RUMT`4rY68`wtQFP zL$egHX4>0Bq*tl&|2Uod+0X(Y*u|bcp0~EMCGI?&{T9r2>lM}BXD0M21qBP6RTa3% zNHGag8Vc@#=IYr~yoWgGK&~#Bz~o(5BS=dQd@%Q4n{y`v$T7{9+QogZ z(DSk=$+p%iug0!0>j{A2yakVd@PPpQ`*z8>3W{AJ^6>BwIM)$FqSa$wW!X<|QPdV4 z#XVJtBtN^t(lsRkj-*g&Xsz8zX*{J=-==9P*;oFmoDc?mHysX~_?BGMiMqxsOs**H z6fp~XLyU*U06yO^ua5K)>)jA;UZQK1o$5{ul_A`r(9cnhU1fig=SG_qM>Zw(ZSvLJ z*-Xju9;V1@q4hTbW&fJ%-;?mujV*+B=+VR0AOb+Om#(o0ibviI!Sj&q+|!&L%QErq zx@>&!?@5EvpWm00>>(PkC47iEubn?&Ak+!!$*B6%PKfTFd4y@1Wv;y;0EI(;C&M|F ztgpkaJUB!9yuSX(|6h*L{(Q3%$e0WVoJOwx^WTiV*_-B1VogLjSZJ1VR!@Mh#jSR|Q zqdbq!S%jdpN67;xvRtE@g-M>4fOtco2gT%(?~+S+e~rEySvy-l-q(>jg`vk zp(L>5Ih^X?m!gmnM(^{S90K`BrIFSJehwURnCdvYKMjV&FFfp@E-$VU9w`A$Ss}n0 zgZKVSm?=@2LMB1r?bysk#CR?jV{~xj^X3L{5gQNp(b2+DezwNZR(|%}>3#>Tdw0DB zX+~~b->)C|7j(xgUO+&TtR zpOOSgDu(Vl5ZylP&qo;}Sd(!@Fuz_D;xhb}v~CGfx69ie58NN(4whJqoRzi(M%j0y z&o`q$s?_@WuvunSqyF6V5MI^I9_FkCH@P`0&+Z8Qly>hLwAQ>MgbUiE@&+BGE0LAZ zQaxPMZ^tB!pjdI0msKz^;`J=sjKl?3%K~+EWP1?uigm%WSf^6tN>oc$evRL>78+@1 zHZ7XOhcgEEoY7|jC;h8%{OIhT%&x2LGo#o#o+rlT2`_l{M&hZv_!ln(7fP;XEI@W@ z2FO~3ew=!wMEKagh9xs5GOy%$F4mhhej!lI0w`3%MbX|DqT>7-4~)|Ssq z1*om4(2=LBWWXUHc^%ATX=9|1Ip;a?P`njtpOnxDQzp%>7SIyt{{x@B^M zdj4#GUT4D-tkMI!rXGR*;J4qX=HGYvk6`}Jukg)UC-W|bPB?6TSb~+LlFs77cYh%( zWA8|dVKQ4kfdwSrBq%vf$8NI+P_It zyJ329;7np(v(I$~CeS=vEVd-CF>STum)?YoY0o#9G`ApMJw<{%U%jn5c*@9Q~Ir4F| zbzIOP_O6lfSs;JyRu(KBe{z!ASH}hfHZ)S`8Rw|wC@T$Eng%!Mt&>0OqNgQy==R1+ ze&dboO0_rufM#ctk+C1t+Dzy~r~;sZp2zi4SgI*m@yqj85~7I0!?=j@d3}iN0cz^l zgD7gUbs;sOY9%Pl4WqR7#+;}q_H%Gql8sd|Jxd|0EEpp}Jj)7t-=P4+Eo1)7?6AR@ z*b|{+mK%g!$DaA9za64;b0xeCk+kw~kd{`N0{<)j1x^lkUIx3$D?)#bEdUeES$U~p zqku%2)7QoGNf6i~JZFXN)}Z;-E%t8V_Jhtl3n|ww`;@eY^#CXZI-6|D^K0coh81-d z18xpq%-fwCaW^NM_&K&ExYurZt%h}q*Vl9CgyS_d)mus7_($m&y7R+wcBT~H&e{J> z^H@xW(%`s(zG`x=MZ2#LcTD$h76z>6{>B)vCoaW$4;^fbCyqy17HWW>H2B$H)mItU z&G7`}7_`OG{&NMUvlI(l81+)?rKgS?{4>XFFyodo1)v%ra|P9^5n*;e$1~L7iVw98 z@LrkLaOn)KJ@}tL_G`!k#AQ35TLPF?sQh>!WGORvR?b7$nN=^bzWrgxg`AL@0ut9} zZs!}=8Q-wm)d-8(V(r49@;fi{gIb)MCKGkYJhh?Z@A>716~A@AVXq2sCVUqh%oBRr zEVemI6_d_*=)mQNL{JjN?zriS4d?0nnZ)`L&olM5ub}T8gYpx^B9P^4?Y0Aht__dD zTF9#m4DJH}mzYX12qoeU38NZ&^NUsW)H;TMPF1GI?-{UtB!@ROY+OmAgPzut;1rYt zEu^LcyPXJIJYKpA*;LFm3gpB0!jTQHe6BFM3z~5<$qu&Yc3N#BXsYgvJr6o+wf?tT zQ=Nz&t(|uSB^OordYH~YKaG^$#D(+6>;dJNqEx@!nnk}U>B1{utU|H;f`k!lGFzqQZo#4#Z3w*Vzfo75T-<{*J9}xkyoFmEub<6N(Al(a3y>W%X;B^rMGyiBIn;4 zb}LJI&BfjyJA0PU=cUL1W?#Z(S1m1%Uts`cG-naH7`JiX^YdSNeheh#grlyRiw)}- z!3)+=deSu}WucKJ2y%sn=978lAVF7M``0HFmOc3gOkh(#X##ioyOyb~qOJpDAkmz~ z_^#QTT0hk=Y2IK}Gp^|FICFYr$Sa!H>!AomonsG>Y_FQW0yqcV&}?*M9KO!tQguNHw)jZ%}bp} zg$a<6oi$rWlXI}f=8=_V?z#=9qiw9HAx;M5+r?kJe zCo1zJC^FYOA>UGmmCtdNg@Yhz7OYwV0z2|59Ee3NtC z&Rs(`uvXH1>_(OX7+hP!#S1B?CnkUxbF;4DbKwDaSZ~oBOVvCsbvzIsWtjH(Zre=0 zs2N=`W8BM<%X8`(DW@grmzQFRNjS@1-%*vfQ5<#iMGkA?<9X0n)MTj`N2CmvrqY`b zidSI|UyqHWtWzlT+I#K0cCi7Ji^U?n<$+~iA`2f%mxZUXodH}sbbR~CyrsmZ2800k zneTai?6?`dXxtRo^OBfb*jzuo9OP6u6ZG-5WU!n|MVVUDQ2knabN#*Hk^PviXENzk zn^}2c`4;T`)xEvRGM)c^3m9IkMWZcNuzvZv3MtwZ-n9>iufK2pTGa2ADiV7%^I-(0 zs;Rn|)-==A$I_FZ7u6x224YBNCn$T^-s{7Z-W0LJ>-;fk^R6du3yxTL+?_bf{r7Zv z#WY&Ulz7+}JlDA9Tv@wQ-&otx9^H<7y9m?SaP4OtG<*%$a$w0n-AX~!lOsp3rFYHNf zo%R~^WX+X#%UmH>aIgr1IXe;58fIr&AtSIDDIiE){%wA;*h5x{;RxL)0R1ZhJ@HjJQytjql6M|DUZLxDDHs_ zNkWhj4<)u(qd{eM1`Z25s_gAWbgF1gOt8_+yOg4*wAF>+7rDzqV7 z|G7Vqfq$vxGN2SThCJVW)G>R{lgV{8QzXSz7pK%xHNe9xhoE#V z4r=|iGy)lkTNp_*QKdY&F6xM#0pS7Tka%4et;J;Kcs|+5Ni+Um=H2(N>f<&}SNM;K z@q6s?wEdf-P5k_T_X->9&^EHV%KCY4Z;_o|COZGI##Hm@Z-$G7bhNwwEG{-EsC~v4 zpZGxOI_7GOtoW1OYIle^ITSUPkzqU}Tq`L2BYXz%bG3D}mzl`kwzlI$odOj{BXr6f zF79||?U3m2(ygr7t)i?RP2V|Qei$1V+1f;IE{Qu>LAFdaNY(Gh#2p`u7~ZHx%MM-2 z=uKX{qNl8?f(tx23F`2M<$EeyM>?aIKDGYC*CBdpN4+W913gQpAvDM47mM#vo;iT?Hk- z%0RrKQ93(2%MBGu?2bBK&o|Tf7=~k;{nPVzHB70JrH|TvOxHXu+T~X}I%1ydj-+F; z4A(3!O~u&rjlQ%g;%2#cWg*Tb{&00-(gkqJo%kt>i+^_Z@jnmt?jQ#eGL@L=kz3Nk zOO3OtK5}pkU>m#1ozfBqL-C0TL$&=zVl*fKqAw}D=*`4L)L8+9ii*;02Y&%@b=W+HNC@8KJ(^gUuk}4~$UEO-UlVwK-=>*$p{8iqlLhTo0thDj+kA z`w!XfiN5_O;pG|(zXlCFT1^#w;Q_cts_&n%JzfYRV}fh^6I zvb#oJkTDf@cp5YXjrX_R%0#r>ORk@>I7qHXsK5Y@a>M)!zVTqWpFuI}+O^Ld0I)nF^xaU+*K^xD zYlf4%z<->7y3wy8m^c*^7&1^05x;pMK7@9`o!5PHMwRQDdwFP<+$9TE4b&x>gpD`; zb8*{$si3<~H;MK2LEa4_We==>-4X-3SLJ8gJia?Ves#!j4J=y~Vild~)Ut%DAc$}m zAqnIvK>v;0z{5JG{+84!Osi0yXw!BazaZ5P?ydG2OC6b*X!Yr5PBqqfd-dz`RAi$S zYwkH^wrSgbSpPE#;m|o#(R}7zO)cU@_GC2g&^h<#;%G%r$ zkiqJ>$nAylmh}msB|XAfeOPwJ>_3w<7CF*-STqe|5#%z7hrxvnyuYLyh(FGm?P&Dl z&YLPI!gp@pSA6hzR(>ejL`)13BL->viQKV33FRMY$mD)}7MCBY=vC z$O;EPREy3AcBN+M{W}n&u!jwe=f!PyR4~O6^}NJ{+_m1}Wc?q?RedY{o%ap(GMNmi zRPikT=U`CP-tRRs07d?j`fF)vD?_HsYxUB_B)P=2AM=>jykMGd#WF;vKoS*bV(z&b z6x>%}1ie5i^b|*!&5ovfqvC8Pbp}$N(`W6FCXZGz`X6#@Po;R1}G7 z2nWnWRp=mGa{vLii-&>qL(ZR{%_a(e{$X!vD%$pFuKj}wGiVkUxwsp*$A3Dgc}VFD zP38g21n42Y_#>d}VAICsm^0y-WMB-gh6@fkB$!Z`PxrD<0p%<}n%S@Y(T8Zt3Ekhh zFmnIzRQ^;5Q0y7On$7}@0@BhM&CSyFQZLcYPR_s!V8sI0-QC%%cu3Fu4u%RWD%-=3 zr{nisjwj=HWKR0{j{&IGVmu%k9aWxAY3?s-?&oVB6E%U zXcNfoB|PRz)E{KaitL{^6D0~2TAb-DcsIr-=lFASI*?Q-hYm=~gohg^#tIQI*jR`; zJ|O4s(ni7VZT@qwHr?8s&H<@uw7j|(&9sni)8z62T09U+|2~Y}-r3@E=yVU>b_CN{!e8j z21C8d}Ha zP6KoxQ^5gt?I52?c{KMi6aHheWB!^>MEkRm-z^VSdUqf3220D{c4y?cX2Q}3$?E&c z#V8__^r|N2WK-CtS)%*{?$qaOqlJ#QDM%eb!HVB9bsz+zA7_* zBo^DDcSGm}oWxM0H{_+hzP^kzPU?*gl@C5&=0HI5$8W)eT@Mqra5L)-!7zo}Q;%Bu zpCy4iurrg}!13m*ls||H281X}BMV4c!hEwIxmk)M38V!yFOzJ89I`Qw(ccmN_~To4`3yH z3b&=`7|1c!TFu=+zvW6me~#u)zM0%Ow0X2;QmXB9QSeVIfD%!r1Ce@dF_3uO_ic4< zT#1Q$x`hGqiJf&K?0+?Y8k&w$5J3_QFvv(SCdls3QYsaC%ti^a_*`v5N}8%5rHG#j_qQ@tHm33cY>H4yF$O-=1590FhEBrtIDg~lKzqqLwa@S_v{ zlV6$SwmW8oxXt{^nEecy%rF?Siw3|no^(0z@xoJXmX1VqIy?C_v_h)@Ul}I+FgL$0 zHLh)H78hE|5=UDvcfBF%sw7!7Z0CHbGVWw*^G_PZ$g_T+rFq~n7u#a@KDC=5&yjpa zPFC6tmF9Yz1vD7#kI5WUZDL@Q$e*Y&5s)K*KyVSZK*qZU;?{(eDwJ`7aif@f%0CM{NqE z12B%A@Nt+fTId> z1U|RVVn{Z6=6Bu<{n5~_Y31Qbb+xkH*8=9%vrxI))r{dPAR2s@^3K(9Py}gXyTDRgTGM zL#(zg#pw0Ihbk5ZAs}-8o@8NQB%3mzdc|@Jepg2armPRjUfG5fSiu0V(&y@RzS=SO zq`;I<{Rp;cm=8`=$7}I-i(OrFqaS8hN%!+Wh{f;XY1%`-5J;R-xyc)zxBzN<9_RhP z0MwrWglk=-WMtO4g5`S3`R-Bw`=TpuXC1kl|^B+ zk$C_gvusyb)Q6lqbvF4u-I~1Oo5b?lQLNa`UBF~kAN4e}k(P?}1KfcuFPND#q=vN_ z^9O6BfIPUfKuQW1Do}VoNJ)}@w6(OgoB6^OHTNcb_b~OndLI88S zbmUWL!%I@yEb&^XzqfiGt(pcnE+;bw1FI`_3G!HYba{D$pXN~iO_hK9ctD06?k_!6 zv*c;}9XG&9?goTem%8&f6EyOopHapCYXORZGU!w70I);-BtJ)XIDC%T#J&Nl8a6q{ zbF#9s+#tFY5n3uOdqzBSPMTMq*SD=z`WdIbDJx+qF$Cfe5b&c-=n0DmD+q%+*PZMv z(Cshg84ZTOt*i|~ES=2Fja)`Z(E($3{{>%pqO)jenoh#u|LKMqd>-2lZxJTx64Lwi z&2JMvZ*GpXRArH*h6FYCmw#;n)b;?@w?eAa9y#C?idKn+X!Fg%#5sg}uo$SQ!N-sp z_d(^lF#{6R0R1`=2Ariv0;c!&n$PBsUdbo;*fm}0QWn>ii`@EAD0K4o282=oxNK1@ zjLY2wVHn7yS)TSM@Oqb1-NbokIBJ39aK#gW8!{;C|f% ztk4X?zqDi%Un|`(hKw1X>BuK>ql<6%$KpNyEmjY$Zk2iRu~=2J;|@uM;B$X>JJN6C zcr~z7t0S<|bEl>9z-4?@Nq45DqkOkjHfnv7@3M~D?TVb7dp0&U7xAujA*>v8V0%5t z{w(|v{0RijIy{x^tb%`7bY2Wp5rEXu_y#Gs#qGeS69f3b%e&`(AiugY=3U|xKQiw=E?j$z(L#*zBj0JPs;*> zpf~R;wFh-AlU2J$ws)LI6fGtC z)w{uFwED5h%+3D)7^hNgxLQ8eO7{~1QRRY^TFCA*+`wZ)s8iNUY#G`aMR3HaENO#q zNb2M5vAbur#b9a90&VQjtq3OBYm#=iv>^*yw)~LDjTT0DOctD|`} zO#%GVmerW&5O~^B)V5L-KIfjy1x9)KYT%Ur(dYw>ybF++o8|)e-6@Y5MOezOhflOx zf-ZsHD{sPRXSp@x>J`Swj z*Q24PF&qLE%Y#s*tP4OGOjX&&hGT$FWXQ(x%_zY=J>@WN1 z>zvdBQ(GdUMvE{=d4u#s6;~`*_d`Ww9rk8OcrZeFh~P;2iKas18g*eAslPVXGC8tD z$i|YwJ)@)NL7yz2L)T?gm$(U^;?{2~vRxKNXRiioX5acb0u8rqLVt{0PD_!pAeiR! zX(#jWv}cgcCY(Mml4tB%C)*ibARplG|M?$Vu#aj^q&M?;o1tV(quF(YI@|u;+GIM1 zR23zl{sdY_uZ6aYlAJ;W&AwVSt!h4g75wuC6y6o#1tgzwa%LbYRjZW&1b}h*K{-Yt zdl1?M{V^MhlAs2M1iXp+G2bgR3Y54DN1sLYDgtnZ;1|FmYn^T$k0ihx{po&vIPCmq zeSs;jCUks_G`Cq7>%;4}N1cT#$?xV2E` z@p5^3)p{Jzb_f&t7i(8nRs+Rh;*jI^nd3@k)N#9f#?;`?+1a%R4KYxeboQ}H)GrL; z2kyN7dHk2|*$OzAgLi5tU;h!uwcio7w=r72bgwgHXJN0pGkpE` zC)vmypv;>I-|m;iZEfxmOy(-GWjXCSBRZ$X`7<)~P1BvX7s^Xhe_{JX`hDS}E_Gq+ zgXMeS$mSS19T1X2T!*5u!XM&I&J4$bg)tBZY;sDM<<#g@U}qjp0_P0uY$}?Xxr3z# zM|SS>xpu?Mq%rhiq4!P>(2=7ziD^1=^;HM0XEmfG^L zQcDkCETX`KwSKRAni2cwOBa5Pl+JTKON_LU6&m1&ip6the7QKEqco->goY3|TxJF& z>OMK~u)GcmgTO`W$;Kc8@e541uG(Azu}Ip$E~1K8BQ1iAwER8HM9)c@pSF*IBq^U~ zo+|$OKSePMc=FpW(^$BRxIP^j6%sJ9-Oi;+h~{P!PNFCxf$|qw{@^V&L zQO=W=*!y6R!^50Hl02m~@^#R*{h(n^uK8&FYdNs9={_t}1Ga=hhooD(=QKdyLvYa` z?sHIoz+fz57;m2p!hcucLb1eyKs;E8s1R$hSTGmv99;*(Az_*BL+k%VFi};Ej+%D{ z!yiGQhMz+JL+B8oGIIGGucCpLiK@0TkLvYqK`eNDx5VQ>y?moU zS*vx{=3HzEfh8G7$leAbD~Sl|hgSRgOQ9NDR_^XOqJ%Om53x>~(V_?sKH4{8+QyqA ze}sQi`j@{9(U;E@aL^rBExcuXtNxNABklUmbav28N8|`s?DZ!;k#E(ZXm84M&gXx= zH%H9>Oxo=4pCyk{L+)`+&)Rqm?Ct4G5ENZhbDpJn3E8B((wp;{9B};?aSL#4?MK~s zhzLbR=iA*&==YHG&N^}ePvC&y)QwvY=p(S-;7BK-`jm@_rr=kzHoh#5MEFiO2rZT= zOw3BY4bg*iL3ov6YI#Gb82$`?;hyQLKuzs=a4iwq= zn9h*hCqC)OW~*vqLw1D5@oUQ^1hCc$wcSQ@aKNp+#**y~ZzQz+?6?BNsLTt9N#N-O#ko{D&KTSVUMrn!s5yUpg>E^kagWu;b$$X zS6BWLD^RZw;{kIJfC6@Z<(7rrX-#_ukv>O$_L|8#*|!*S8PO-)<#K6q2PEgW zFPLLAAHj4pNsB**;rT_(Fv920<8%QpBMgeImxIHK%Qn01G19Zqnl|xc{YUFAb5lKg zC_{8pd}uRM#PF#}XowFt`eSi&ifD3~h>(W?5ZU!y>(~jEcZm@=b+otVY-zsPLq02r z79lKVsoM;A0w?2;NF50M;kc6LblC3BG*EC{oE})>#cw~9*HBfrsjP1EgMgOQquo@q zL_l^OkpaxuR(=cD>fFw*HB5~ zp5qVQWQ-J?Tn7i38hWqY9zgL^3h<(`GH5h39~=Rqhh2UA9suwLO$|E9zhR`KE;yQm z7$YjPTNrF_30(^is$}cd-cy^lUL;S z*3EJw8F}Mx59-_+JYU|iHe+5qhjJwVC7c-K%esuKv?2GYj~vY2P%gtvC|v9VB8Gqx zIK@k>sS(wegOhaPA#k`DHS4VABfZl@Bt1Se8f=N=hlWH$04la<%yx^AkcW+T*B-3A zQHIBW8xF$jz231?n|d(qziL0Q{GN~r!=p;3200(Sip#HZ$9fx5dhb_q6Sre&8)Oli z#Ss4sXb8#yMF#g?7(FQ8zJ3ud)G|dZUM@d-`^mMIDbHIo zol{kJBmuMB-u|z^ruj^LAw1Z2X7nJUeP-8crY&IeC*W$j5l4I3Sef0Zc30YXCg-lJ z#er>koOC}#1P7Ed9Pn5{gLb$?a8c?%5nAVTuOktnV-tL4YfnXpvq5{^rj&;{KpUY8 zk*{wDMU!Ub9vyiqooi3Q$VtHPgsx182vMFEoV!T&i+=m@wjC+N5*lMPF0LmDpxx_R zS|F4rTXv8Ok=MZS90BM08@6awIbJ>(h#ef;?f~@5m75)9QcREZH+(!;?KcA<)kQCd zTyRgpqIlp9z)C#+(^`N?-xLQe_iF724Rsz{S?da1s;`=oFteVECZC(zzpb@97rjO8%g7xC>}^Imx=XGGhk zJYe`3;QWXu22l3-(97&ea#+v@NJRh#2>+1C@|<}L?H#G+VMWVX-<~-+G)vtjz%tUSs$F*+nSD&m@1I{uwwZr{#S@NZ}Q9z`2djZFY ztg-pC6NV>B$wz+!?VBgj1odC+@BBstjnb% z0;>e>uIm!eZX2(<@~~+N8nZ1^4Axb*k!e%XgJOLQQALQyVBz+#O_`w$PgskN`+O9m zDXP@t02mzhWKNc4=W^_n1Ff66>?I3}48kmsG?s$S9O~m!cdjox^M>Fj^8u>+R`*m) z(y%DBJz)6df`;Tb0bNKB>`&k&nUL#m0$U?y7;#)e641`N!{XQM5e-(q9H3-+tDl<1 zgPOZGosmaB2U{82g80Bt-!o>a>dJQ2P0)fN%>(){#UUZul+*t5lR(^gXf$BsdrbPx z_;EB9)O&*+8M?GpFI75XIUX=S4J?KH)pi`n#;K$~af6}L0Y)=Q6fu33C&@ej60l#o z6mlwABwps7`p}lWUF4>3XLX(Q|Nd~2b(3#ed)Pr>JK*b%(>Y5KjzNhNxb;9fhMlb) zP@=cDj?_)qvtc-abQ|L`FL?XrY2gAA0At?PFt}^@RF0DAWC^s`uRrsVNYjJ-hpY^M z2NO)ZsDEm&QR_Vz4`Ke#slv+eMW-)2?SHHcK6Q9H#=}zi920zSq!wT<=$?Jy!v{G* zBXQdiG{h_(4UxGG84k5*8l1IZP4?r)@!=e>;Y7?Lgqs;7SpN?TiWM2T@!L)5T&9U$ zJYNb*h7gYmw338`$5)OSjkkwI#c=%E7Zj;T0#x%Jfnx_PZj7pK5(}i#5A_HZ>!p2De{-8XfdBAsMqOxASd=finZTh7 zx&aBo-h9n1l%fz#4SR8u_i{XP=sd-L?WM0v{a$(0!AZp(hPuT_ZRV}g77re*`SlmL z##LzLwXxUI-7qRFJ9KxWIA_QuBsZy|lBwB7DTTG6z`Exg%zvUl9s{AR7h?F!V3z5v z9vZ%3&GrGdam%-}#!Ei&HBrwP!{ZUfN0I%Ae-p^U%KjdvBn+lRt;7kUNw_aor;-uQw3k=} z(Qu@(HI&(|l{u7iUDv;v2ZzC96S!IJ+0C2;FmLJOW0PD$>cG@*^7D0{-(qaM>K?6D z$nDi~uRQgL$ws3Wu8hGF@@>)Hv%t1x=QUQ>BQmr}(jKV?>A4TSV_^qjvSOidbap6H z=jFc_;C~^MD!Q58o$|B=N5yPkbh{#o0Gkh2JcTq!UWxd(c!S>Lkr;hXri9wsKiVkm zO5A|qS?ys@pln1WMb9uljzxDlhaIV(EJwAJQH~SRI$j2HV2!5K5B9V3$Fn_-=6V>} zO@Hq46PeGLbh40iUQ|G*TlVbXXy`Q{aPbM{5~1tI@Z6tvwTN-_Kwtm^pCD&yfH+UY z@rUQSYJ$;wsQ^=RVPYIq1Z0p!FR;V|pZ+uT7lqA>(YUS|jYXw6H@Ac_E_S1eK_a zVZbWG@uIwhN(n?PURaFQ13bNv5e*@G8-qUzq!L9kJ611&933x9e63Ilv77*#fQTFY zBZ&`GuS9$Ry6tMJ9iJ>4TUyQyk5Tz8AHjdARyJhaa_R3$>91f8)=3U|+A(WuRn^;m zJp4O7v$uQFbaE8s5j6e7H}Zfwn3!l}J8of-&CX?ir!TQQakhJ9<8X5QN0C&6=aYPP znHF-^1!#teWPM*vaZzS+JN zxpP`uj3;t;XHc!l%S-7}{Ex*@k2o2L*R|)aVPM6?;>`N%wo~wAC>8`l!rnv0ox<8H zn=%V5RgAcwy($2@sJ0`49-THavCo0Yt>YReo)z?-6v8aqQ-2~{N0fU60k$RZN|ioj z(b51_LsPQ7m-apE-ks)MxWh6UNT4V;e}Tv7u*Ue6555W$(gk|!MGX`Jc)N zI|Py@=?VK7w?DVYHoBf85)H)own;mJBGe!TP1&|HTp^}5b`{)|fc9Pjv@3nn63e+C z4=tOL>3Q8?CzHPFS$bRIorxtU3!2~}@*nag9h<=OQ-6v}liI-$qdbeY%Z^Z6cF^X- z>y`Ued6UgcRU@cqo=PRoi`Uk7$=V zv&3ugIc%J({W?|kQcNj9&Nw4+k3zwn5kQM%>Vsd~14DV$od2apg>0`jF$O)`Et!o6 z*o5vqK9=_g0RbD)yqoem+&WNGtT2Jrl0QyU1{wmNt)_M&rUIaNwD-&|>BXvNt5+bf z?x7zxxfd_IKEHtyev&mS6FUDL02yX%_8_hY0+Dh5fDuFIU1R*JNJZz)K66MQFKHcZ zFz7$Rb~Ou#t^&3LrDVBG;bK;v1mzns+%%Y|+}p1Q51LM5jO(s-9;kKN z-d^mPKo*Pf^GIrQJc8QVRw9 zX4{+W0)*n!YT&p@?j_y`u)et-r1rr|g+|1|PwM(Mki^ua^)70cmQ%P$JX@yR8O8{F zQ9iSG5LGS2hBs>Rg7t=EUF#$D8T9&NX8VCT?#gI($*LSxKZ_fq2_V@}`4O%~JQ+(& z18?0I{5TiUvI2y>`2r!?W)bsAy+3o7=+mcfiX};%PD_2jDg5Ao5(?q=qd5>Z+Cb3o z^_~ny`KJ65IYwk?gBZ2b&Q&b7tMx9&xr{N@9b5d$U(TTQ@1|_$yO5)AYOOP4%o#FU zvS8GP+nsdApiAe>t zF?AP;>SsLoN8X^=xWD@Y3~c7DTQ5r*sBC!vtZWmeK}g1ZX=v{w@q7szf*BznXWmXX zRaF&yjbcM9z~&>gA-Z7hn7Ropz^yO>krtigkt~Kp977tEOk@Q2Q6=QMGOqzFZ+4Fg zHrNYhOf>=3L9ghq)dS?4159u&U& zs)S$?xHo*TxL9Kj%+$yfF@ zpOBnGMgn0#ARstIP(wMsdIbx8t}Qvd7fMZ*!+|8#s^{$5nYu zaiZT&jl)^dCf)|V#&W*&mRYo~jrSX;TxUKJIN^`#r^h_usJtZ%U&2gB0AqG`c5b80 zZE7?$BHVv9Hf$G}T5Z=6zQ0gD=rRvoyx1 zzG>qJ8it=>Il}%Z&e(~EV>nC~EE?)4opqm~SoFDJdiY2FEE-aiIh0*eITaevK!y2z zf)hess4YPj(VvJl(q<@e#zP3V&Tr!Cfu@;d!c(XLq=D*78+i2?I<{9(_Ked@DlHC@ zbkA9vU0Xm=)02$g?lBSC7QO~`@?V%{3WbF*z z|NRS4WX;^m^=hGQ=TM=7()`XZ0zAr%GF)q=oX&aH+%+yWZ=dm#F}^h<=ipij>{>k0 z^_5fI?&FCzgC#vK0o#C@w)M!EPui!@J1hM-?GPQpBr zvhFyu!mBsx>Ugnhg*SlUsfd^S4_a-{XU!3-l@5fCmc4{DB8jMNx>r>dq+5iaJPe+7 zlDDlMBh||1!Cd9oMvK0ADnecjX`LMZ_yH%ZEgWv$13pTdTJzz~_Cevi^~reWv69x` z-AG2~5%V}3n7W!Jd~%Y1%8>=qJp3Exn!!JI5shF=h5}jwkRkevN6tVZO*#7G{BzBt zSvq^Fh|tRtuU%qMbtlkYN%YF(BRnl}|K+9JScs4p%X2^lE|C@>Q(ScW395jE>mzSw7Oa01Nn43?Xajr`kP=9@!*clpk>U+F zFm)^;;e<3?&#}g%bU+3mNC76Hral|Ag>pa#w%V2++`N8`c1?!5EV_7^cMi{o*;Bsw zWd7Cm#%#2oL@{iA4#HA?-N0Kh>)esH0Jo)+k5JJ6YXR;UVUQ}WB;JDUSA+y8A4VP{ z;apsVkVtz<-vhCvpb30QV}&u6XMVH|B^DqO`S6x}_{c98uL&Y6>c&*izvRxvj)hnX z14q+<_PES<(8naSNg=xdLJx*Uz;<0e%EL(?h-cqaG{Jt9c>Kxy#>**uAtSrnwV6o?53BEESw7KLhvS{l$mDnAZ_?x zxpNUSaeU=vEeDhw>n1Nw>Q76b(7^OJ-yf*mcNZmNU2uKLKw#FozveDI=*T;yVWpuX z;@}VE2b_xNCz0kBj;8qLT%Kb$IgiaJAUKMN%A z*i1F1)^>rd-Phv@MNV~=%pkR_H$eLn=0V~k*4Wwt-zU_hJg86Q$QSOK|7+i11UDTZ zC1(vF99oYWJzmyIn-MK@;Y7)in^S?3r54jrr}R8>b>E(EXn6P%g}w7Y=r~qtUU$Z* zWV210!xb7mYwJ%tcLl@od|)0B1HtC`j+{E$T3Ud(oUxbNp$$_W?OecD=B**)8Er@# zFh=Waps_;6rp$AlBc>GtMwF5kD*Ea~%u=o;z{NivcsE#uF|L`1AFh{L(>f~x`5GWp6gkIm=^{Q;pozjfh5qtD^f3&=j&JJ?2 zDsWWkGUZFYZ(WS+4itqL_R55=;%bfeInI)B7oks)IJp4OTK!|UGOvS z#UwTeRQM7}_>01uXt7Hqr1h<_*vpOGjfaj`yN=lpXCYd5qgcD^rQ>3Y;%^E+G2qn> z3JBUZu^qksQ+;}!7-kcxe45@weD@-R*{n1)>0Ze^h}1d>>CDKt7dd}5jYxH$R@Ff? zw6thmtfaT@eo|u|u9gDA`;bF*#&d2*=Lx~fMtxso(ntO8q~MeIzt zPGvOSq0XN$hE6J~%G}4RgO{FkJMih7UfvE9!2eECqJJR#o5;#bCBTRln{DHYqxX}C zWN0~K^tkGXO?T=yL|=Qi`LGQ+ce|Eg`T=(Dp7qU?VCBngpkX%k_DqvcFudDK8Ge0p z#s38bY5ko&`r!=)A}o2A)|n9pyFwZfxngg4=C+pa%jZC;gjs0v>}~hWZlTDN!{3Md zN#)U(+4ycQCjIy2x1+B^1z`0)VVvxAp3s7h*W-k~xB48dbROp&FS(D)oMcCBMzOgA z42eIBS8en;ez%Y|wI!%HB z0UU*;&jUa*MZ1)XlEow(EBFncu)@88G`_3z4o&Az5u#tEe%h;*CYZFh^{U`WU@s09 z+Pj5k+%|yjp>gse*6^isrDyxDv-xRlmi!Wr=f=hm z%8>%V)VAd5wY)QKWSfRi#=PDAad_w`pQGL~|Uf?`5L_ zcy~VnIqKN#ME=>1)n5ndSgg$c(eQm`se}inx5rrcafVq%0{l3nfc_@{SSqopFlaG8 z779qym0_IhrLLtUdvD{WRew}@fP32y(z6Y^+>n5{DPPb>0W_qP$h|_216>KMb-Os- zNHB#HY8pK*f`D|Arpb$S?d?fWE13(?K9_rG-#AgxDDljT^Xhk(E{l`=WWX6{F&|v| z>7{Uwh{|iuL7$p|X??)aWCs23A3(95Go8~Od$j1gzR##mGB_%ea$PE|_xtYigkz3O z#iVZv1dlsELt%hO7BIDWp+M`R9r<1b(V%~?O*#Y6ODdM$UT%B@BGs0-RRm=6moyUta#~V5KV3qS?@+A=tZK6&c zh%f4eBu4^vq{t^6h^pzY8}_bm=?L_=hHWW7EdU9k94Vs!i1g8HPMs+q zJH%r|PpS)M?WG&7oM2sv6qibIOIKwI3)A!=lx7p@vyhKrw*>yp=wH7Nf|9pM-UiKe zcOW!GJ`8X~X(Ns5{;s3}==QYDi7iR5&dSORDIFNoZsH2(!KG|>{bprlWki3==u5wv zT2(ks0@(X~TsoBz2r2HB?9Gchw)ewd;l13u^84>MYe^EO_Ms^$vBy#Qa)dY2 zu5fy%_==v}h+=YADzZFK>mkv{W32Uk};mbM%f-y}MV>B|niBPxzH5r~NM zf-yCUgDKB7_y4NR?9qZc4*+{X@5x%4MJEgzxs=hlPm9{0KKU8-SE%zSE@~^R^CYfw zldI$Cr&rX`SidaOuCuwJoi}FY`!_`Y;_!M6*V@K^)wB{n_}ys|{98#CqXYny$^jQ} zj(A${orzJois+HLXPh8kVg35yzt#T+h$*UvTMw~(8+SO zp!(m1At0Z&&-pQQa(Wuc*qJ}zDl=%B1n6Nv6cQ+yjSj1BP^4M8o)XskxU!PqR-&wI zTr;=T!xryY;zVcoNwnO3fX7ZLZtk^JF%*oT+H1Mo1ykwvUmmn0`X9QAkUMYR7 z8?erHcC(Zg;0HwM1di2Rc7VC4W($8)#)E$dY#c3@=pbS0{oc3FQ(q$z8r@i+OP5XL zT9Qa}WCub{fX9e01r1?&<#|!>F65D~ol*dQ+{eeCsfI`>daSkf&BbX44om)o z<0E7`#uD&i!wGu0K$t&MqnKo3AbyH~=%HJQi{&c_4~X+)LK=x#>dTuEyK_(+{ z_~j zT??@Ftg6bqGykmNjJ6zR{`IH}a}5UXLYlppBLiiW&K7O-3b6)v2GkOMuTOv=ObDl_ zaX#YtGVzu}0*p665Y|{V1fu0H#;|`E9}r(rkc1-IIF1I&W7?ZnTE)_3>FVItN*_JI8Geq{p+ z1|LVgKV^cIqxRGq&N(>;6pu5`CyG1Y_P;)L0L)fPK(B7|h0l_B(aNc#zHb^Fh_FiT zuA|83P~7-+YP?^1iQAf>=+^Qkdtsyt!})q^<}I2r=gwrK=?kfZ$9@JD&dqn_(I^6l zVwDK}Q}9U{->z=q7V3ktwYGK7F7c2mOiJO#&n+*%)>{4#IW$yyb>19{06oY~hkpMr zb$cBnYm|y`BncCUb(DkSU=KgWm;HSzg-*W}bvQq3Bc`nLPWR@omL3T6%5T69(nXXr zc)Qv79}WZ_Yf^ z>brmr>3%4>dR!Mcb}==y4O76-m5ziO+)cp8EkO_wHkw9j<8BsOBbA*Az6nrFin4LR zkJqx`vykomqol$A_Ur+vtFze6(emmJG4ZPmV6;g4nYidXtT?!;*7URP*TlMyZ93uA zdf&S|@hNKt=#lBg7+$m`<1yx^^R_?JUe3x#hD^@8*Blw);c=GbS*pJWKB7%N*Vx7V z5+la!d{5!9p?6ufqhhmR0pgu@@%N5;HQ2eCh+Pe4MAYY|v1h%745g}wUrGP7pP=jn zw)gjXdL}ym@&g{>2}{%eS;a&5!=sc1t1BuitGy0s%#Q8esI54_i2}^m;b4NdWn*6C z&YGmw9un>!5U{;I@5+8~1GIJM82B~{xMNrQe*Rtf3hS(^OMHLUfH+3|c1ttFgb}E2 z*FX~zypn56#yyFP)w!%sEFY=6wshH5Cc{bt`cLD@Sc#>KprF=k?jq*47ZNA@eF4=XmU?x* zyW0=FJf(H8enaRm!R%yfy>M{wUkZNUo9yvU1`vnYZYSGcS60=zHFAz7qrlQw26A_K;C7IcFi^pz}BAI&1J}cmSVi<(^bWHl^t2F43nx z^@L~*3E<7A*oY8U;@q=;jX5abE5DhRORz=wdq*IQdT(xA`3A%Rj3+<}UnEonSh*vC zf80@zg9<4ybSo5aC7*STcqsuS%R)qdR|L^|eVlT-iN5fkiKoHIXsVAic!_A~-bxPW z(dX&C`4U@t4Npu)W1K6p23@HDd#rR*z=4k&XC6?hTa@|LX!>FzQXkUbakcps$&yhY z00f1bQWxu%4x(!mOFXT)drbM7JpO|ukwh~61ExEvF7?ZH9N~X8f>0e zLpBr7yxw9Xld-A731Nqlr9O>_jkFA=iX|54u1!JhzJk>_d$nx6>-rX#iWQbh?Pc^SQQS9c&+$4}?e zejlcYuapR7g;+CdbvoL^oHxH1*GL1ln!JdeUlEg!b4A3`9{4kIn#KTtIb(ZHS>T^1 zadGVAI%r$+7nL{;jZWnzS_pGPA=?HE<25(qxj9mNefrG?+6_Ej?7YEDfCSG-qaJ z)HF2y>~8jiuMjoqTKk71aYKSy2WxS#J=bz83-vmA zJASF6s*2uz@S}HE6G+ZoqqqVHH?@f=wTQ!o+4cGE(jm_0&$$4q+cD)p$XJ%f{N7>7 z*F*WSzF4kgVW9+y^;zxi%{%?}%K3t_m(oKVln@|;Q%_D&Mw#F|8Mc>}QCg=0uTNBe zOXCCr0FPoDwv$>a)uw*^`9r(p)rQI$RAt$9)SS@z=0547uyTzG?JB?OPD)t1wJZGY z(=Q)ee)>z9=s$lS?(;|O@$;A7kd68gnCrY)tFEb1IpuQn<w2T5yjJDaY zYWFUP2M>B#MA#FW*@i&FBnkL;MIZvU|AA%H03e!dbCH#S8qWZ2lm zv2qch>K54p8>Ul|I6;|-LOWZ++*1^aNdTMGb5g-bV3ER(S77_9U?nxNsHe8n) zX~Q<7L3r2cUp;!_SvWws%6Subqce-#&cGTxTJH{+^PSelek_neIbT5Y_0UfhSJa8f zQ3{pifh-39dL)Qc(hMNwXJZ@)%EiiH@2WBk7Hls)|L*!r%+1GZnbHZhW#x9c9u*bo z{mz#qw~DRDA>y`SUyaC60~SyrzXP2B)sFA@SiCEnZbua+oO;D+JiM;g#s!fp2CT6h zdxIk;84DL)_2>7JptO*+s%}RdwXa1c9f&(vPc0n+dd5kCv@qm({5ckz&cODHm!48D zokOa}vu~BsFOD>}R4M1*Vc54XkR9i8x>@vb7%Kk!i)eBU3o9CO>N8DvF?_cS4V)SK z?)H{bbEc=+i$!z<(DA}u%8YMWW0NHh>HwAlnAz3@oJY$lYUEQu$t4`3d~HK@_5am5 z6Nv_*klD%{V;5MyY3D6g9NAny;AjlU$QcY1id0_SwKKU|yhUqteqs1DhpCWs<=s`V zHuw}=28=a~20`yAHCf|R#DJo$q)PQ{!kFr_)B-CYe8?GqLRCKNCA<<#FgUU+0xxwP z*b~!C{SOv10;_DqN$OFD3&XJhv?pW=cxK$HZ#`De!ydG2qVKC_`525SJCI^`TRb+@ znddazQbS!H!P; z!xrmo$@xT-db-%=HAMKUc~%LqvRkE48J8}FR7ZJx!z4fLPg+IEtxI+-_6j~vs^F2Y z>Iw@R%h=jq;51}-K7i-_EeEC=Z>RM5U?KkqZm4&@Q_dT52{2c21@2vTpVd65xIJ=G zXzRvR^=BN5iM8~ps3$&~X-XZzwNdXmn7eUT3sHsO82%W*dH8KiAy&t$O?CMnUx9TU zda6iQ{GI-ul|Bf|?IgOEx+$(W#4%P=L+ds-bKBS0IhX6At=|)IQSu9EqqwVA_w4JN zTVp{!RG28p4xqYwyi{av(vI`gPyfDMBEzw^oyQ{zgJYAKkRY3 z7?XiMgH(2f!HLO!I_^fuI_jBWZt8W>A~$!S>8%h_%^&Vfx1LYviQxgJS!4b|m!gwh zvI1yf5D?5ES{pfPbQVgkGiU+^1dmK)iYs1PHT_Hd7TPOdfdRM?)8%OibBGO^rF&d= zM@{4Kzv6e1k6B{;a2SS-yFcU+Zmvys#ib+jELF`XYnKKqEK;CiOH<1#wHouMl z-?KPhcw0)mn2%Hlg8ywCwahie#1*pi6xH?a9JH@idR&h2v_1!a_62c?9{Q`H^w#c7 z7*k_l*;~De@jx@%1Po^Fj`w%E{=J9j*wwt9YcdBHeowcO{@S;4vFm=Qk7k}77_hfP zKR?vm{s_QWj$hr7>-*xQuzW2>ppf|4(;;M&mSbUe;OOCRdcoZEvPKjJdfQnaG04^( z{i(2bNF7atg5L`;7PExEvukA!$%#(q*H&FRe1KPLY3Uw8W(uRex8p=5}Lc*#iz164q+ux2M-Cb5$#31>&g0% zmlf5O;%*`&5mLtEiJ36FjJmsel=-r<$;Kjxkot@twW8XKIHvg1TrG>Anibo>R|}MXhB-t!Io^&;0#85+{$@7~MXeqz1bOZGR~q%vl}$&$?Bq ziiNXoGuGnXe%Jai%It;7Fwin(NDTRQtx?CUrtV~Cy94e2jmUI~6+oDME|uc_*3X%- zXwmt$rbabyXh>E8Q`*v(6BV|ILe{CKtVC`y^%I-{|4Q)OvxW7Iv29Y|CTGf;BlK~Zn>_4>RN z(}-Di>^PkL6W0#tEsLD0J9bhUjYxU{Q^Ew8!~we`Xkj()#K@KgSPVk9Cuu8_n9Db` zq7E{8Zvg6RN~h4m`iSK7mj<1iG+FKf)9-$b+%~Gr)BMDBz*3wlQNu@;lPHRrrC33p z_%tGbGIrChdI$!5eq$bjYWlPJlmItQG=%>>`)}RlcT;GL>(N8S{<`m0y2#2&Hq!#Y z{u4hdb%E@M1WO>ay=OV{uh`U#daT*W{d~a=^7w79AV0=ByXQ|sJ_hMGi;?0D+4!8q zxbv;DC&Eie4+F}L66JhpmeU0wK;#J)l*_j{)2DyAhjOY!0fPq#!)^eDXBJnkX@c&W z-3_!bn4(4$zJoEjD9JtFr82Hy1WLx32ejXnzR~S-vA4xTWr^N88v!vs;}aO@ST6yN z10@#NqrD{vB*-HrRb1bFTP0wZjW*%y8B>)}aji$B&uX}0y&WQ;HXtrok?Ib_D=*^+r7Ku1MqR#aT+4wZF2ax9y+w6!yO1??6WrlTpWO@cC~XOQx-T%D+| zp?t4Sfvj8woC(6r9KUC{@6M($ylUF3%||>>I7EnSL}J6(q)gODx9Kzk_Z+@2)}em)SxWc;#KpuIq%RGMUX!`XN?j zf^=S-gfc+=#02Uj17uDwBB!Pt75+-*yaIR)a)0~;4vZp$NW-45zU|GR3>j%dWu=bo&7J~(021GPfo-o2m{^&7n+YrF zk71dEo&B`mo;zCNwxW!~^hq1x-zZB!O!8Ove~w-9>fnH^GPUw@^QKz@S2LJxyf@Qa zRGf+4f;}}TE2>X!v9hv|4cUM%=GsN5YOc{7Wj0(hTjr;XGW=ai-=4OBBvz(>W#M<1 zT09{I&BkmPh6hs!!*?KV^$w()@OD3betw_Ju5J&K-t_q@T(-o!CZ3)r^Gr5Y4p+{p zKk_!t0Ru6{2gm+!-ZOh&rg1gln!wO z7MfQ3o#N9!|L_&z;XNx?g7UoBl94GcdUQBg-3|~RQ2O@M+=F&@I4M(UY5BJcsT(=VJwbPK?}mE}oGg zd+%A@xw9%+{C_@|n*YBRK*TA-SdWEZ=6bv8$ylJ26)? zY^U#Pb=wI&PRWbz3kPF!*zs3b6Up3UAd7#u1oqqjz_qxOWf^Q{B~D^#eft`PgWK*( z7ZO>+XKn1U?Qu|Y!dL1Tb#+QuhD~K5?`}9QRMcLZXX;TKKWo!pq$a-W(^1PwjCuzBn#zfOUl17KiA>eOImmlm|AgzF`{cc23+Ha8nU?vUnru};% zQS4?#%^1vh!m&nfs4j2As0n8Y zC}(nq?|~{@54l+3_kT2gF+7xhtn--NoM;a zut7Y83FyXj5v=JcP2$md&U#(tz72k^mjoY4gW*xa$9*E zLy#x04y+_Dm{uu^lQVo**I;!4Y&jHj$fZN0kD4>?7?0xKw0+V~ zwrrD`C*4P-v*?b~*+aNzb}Gs+RO{oZU$F?TeNcK=pSC4x5Pob@r-#CR0~ zK!noqaOD$niSG)IJR=`Wt9T(&T(k!3Yxbq9f2?-mo$1m)hk+@+Ay*KrGo4UHFw^%^ zHD_Tdri#rkQsIb&<8|QGd){lpHEi7V?7LU_J<(z;?0JkfRNF@iE5r~Bt5?L;l|6#Y z)?VIh?LjtD%8`c7gl5HgtgCffTTM-E0|~j;u@k8!QK29>JZ>ni(Yinp~8np@2v<;^U9s&H=-@L>9k#=#0spbff%@qHyj>^>UDhp4P zD2{QU{8!xg1g!h1{YQm`fSaxMGIEdHVw&tZ($JJ#S%Z63NQ|IO_r1P?{n0f$3&atw zCawl#9u-wp7)D>t8FR@XWox6kOqNbcnc-yZ_fdEF@$tkCKo0$F+nHRhZrh(zn*6f) zG5wv9=?Xw)Oy2)WHtiNcTyo>ixp>LY+3lj^yDY{2&F)9fVZzu<3pH+J3C;{NSU4bf zxOM+zIMH(i6GZwc->;}NV)Dr*%e97|bsr#{`61uLsn8YhwLLXfV9MwSQnlgxy9PBC z$wBGT-eRxb#eldl?5Mp-g4!~CpH=t z?QDHUtb$-}7HDM|ovi!nZ8pabja0c3;q#~uBt~}4-P?xWR4y^Fbd;Bn!!#tsigEq| zr3TU8y@py+8~qMY*$J;g zgPj(4PuqcZ`0}%m%bG1rb8~YYCWxIf_GIehPwgl`#zXv@v$a(7xwXc|xX@XvI`RQu zn~HjpjTQ{=`8;G3WYcv!L0iJi&HiXk|G*tA9RTW$6O+c{qB1OCrgwRWQ(0-((9h5 zJjg65)IQn%2DsXuv%h`({WlL+jO6Iv^`~KO_T9?jgE~O~id+-mI;(-3buyAljoO?Z z3X5^DdwmO<%aX+5M}Fv~%EJl~U}GY;Sa>3oi;KpU=^>}(c-dsn#2$pb!jty~1T{Po z6ARqKmVfv);bw#7`Na(A<5~|lu7JG};3o9y3r=PkgV*;OD_+2s*f-!WRt)wEh>qsK z>33aeX#u|#WH`w^t;83UiA_x(QeonX474tH<-QbFh_6(|7R3etZ$ty$*m|kGai}kO zjdCxP5DT36cW`9&Ueq9r$d4$(FHD!>YNDfCg&-eB0}PS#c6XoS6fyoNc=tW1wNjvG zK>LX2c*EuXNa^vhNm1m#&?Cu#RC%66y|H>@^ZR2~C)?opFigH>3#ze~uySj=$43M6 z39k0(G1`-Y+l9(vc*%s$(AXD{PKT2peC4z2QM*}rZR^D&g`(p4CKzQz$>HD!-<>?# z#L;lIlvfqwP`&X*h<&>+wXuD@g%sv_1PHT;_ezZLKJmOk_IB=J=(3qoF}@i~@NZ(^c5(GPdYBrssX%rm@+Vd>UI=CB>}ajoD{jf zEe#hj9%=*3Mcta!dG8+RWv@F3^v7p}TEjQlsQ+eGzN&UHp2u{9iC6(qiz%xtz6a9aTtW+M2FBy6G#)CxrWV|)p7~c*d18DZP-v}# z9`enwG~M0Lu|8g#ADXc+Uch<`jSCjJ5GR=z5xLXTX8!%D@7V#CepX7JQc6V!*?s zg{^J&l9m!jLD}B{1zjbjB*8Hq1#u)bT_eL+vlC{NfuPt4cLRzA>K+cU7s>RfMvTmn zb{;GsAQ;wdU|GuCfs@76;D3bWz5C3|r^_*mF`dueq+BhZ^Q-w<#}#tleD3Xa#|-7! zAEG>LdWg4s1vd+@9Qk~+xR(XHy14wBf7=9m)XmcSv?cu!;9OR{$qm_^=0Id`-Y#^) zi9v4_s~%wpidZe=a<(sm0s4uj2YxUOLvf`}tGh}%{x|Foj*vHferKneK5?yR@d3dq zWeD6e%c79G`=vig^%E1D76$?g(@}jDP+Gb`UYQKT`huk)fpiyj3L++YIIqRg+LHsp z%1O+zOj+sMeu{%}LSR}8E=|yLhIILCgwcpFIC|m-3*B?@f491GO+w8LaRK*Q_XQo6 z%R0^P_G`QWzk$T1RFCln8@~5=PK@Jc2}3l;6#)ZH{w-y0tgzl2$Lwo=v;8O0MoY~< zZ2UV~b{4XAv5wfvO*OR^-6qLCS1#~eUvf)LAdP_w_e2AbKpFg??KB2GvGHP0y4`ki zBq*@D%0iaVBioSQ4C?6`K$1;d>gl3yUPdi+F|k|db;%px(;H{LU;~K!SHhYEp7tqFl2@KM@;Rj`x)n052_1q!uw4?_;k)}a}cqB->Ei|Gh&fI`sY_Gq%Rc>Xc zZKq4HqN_q;}BrVs`I_e}A}|juXP7hQ>k$A+AS*an5aaU%e+kQW^ryxltRv zqdZ;iUJ+;q?xDSkk%9dq^~B*|br7HR<*&x+C(PA8en=kO+v_HHj#RLlTWdr6M={Q| z4Q*S0di_x$DtS}wQ74CoD+f_WmhItG>hbJKyG}P9GEf&7~%Sz{NaJEC)ZX zxT8O*15&iVk-u4j02VIp=KBU~P;gjTSz&vAMXs-Y{f@x(i~quc9GVpzc%-@e!vw>9 zLPIllX4aR2J(o>~>UEnyD8vbfck%|fp{eS$Yh>U*SSfs|DQBZ!qpqTQ&v2fIlOT(3 zSRkiX>fz<8o?P8?Ce%Eiy$#DN5DyOSUlhp;+Ezr3_p3j>+(K&Nl z!d{Z46Yfe6ncrkwd?Ex7q4A(662F8_z42Fe!`?lwFU=VRU**4L8ZZBCtocEPEU5`5 z;Ha8)t&cunN0ye&-fnW<+;xy~%7g?jhVf(GF54K=LC@QX_Pz3F$prWKs0+lSv z3?5^O0;j8qEJ?WdLO)|?#;qh+?m$VlFXoG%b%1OU>@HL@$r<$mhLN@4Vifv>cSPB( zK}8T^of*upL>I&5t|Sz^=j*VtPBV>fu9}sLaIzyIUg6^Kyr3PtQ3k_7iGYzb4EWrgW6 zgb6~T{U_h|s!-t~+HVw2qoR{`D8_CQVhl_)4wOyS<7tY5e13muP@Cr>Xs{A9Oi!wIm`*x_^RXXAwG{_FRnI ztcbM^U-5dy5`sbYJLKiGTgCU%#5_HhadPE}idPZtZf=+2f575u+K~MXUI_&id^xVf z%GHTmfe-ar5Q=AIhA{$&Hl5_v$rYUnY^_v_@(@nUc9Xs8POf^y#$JrJbk{T;;&LI9=NE`qo6$?*`#sw8^n6#c z8%iY7`$f|(8zkL+sXu#Md@E~q-BAW!QCanf_Q?BD#m;HsoHH5Dk}iOR4yDnXGq9{aRb{5zmU9S-W}{W@5iRST+mNtzwrGDm-# z0DaVh-$Zs=MEE9Ub^To|1Q>rR^vn6iD;ui8t9);-36nJE!TAJT$bz`M*Emv)$o|R{Ohwv0Pi3o? zo4vpiPER>rgsj}5gFH_k0Q2v2&;Fb-Q{o}SAQ&Em8PO}Xeoz5o?=l@=gj$WoqYOvu zUlSUxFPtLjn)pgk>#Wm?Nj3~t@7?`mJ(k9pWJrz}*KEmzf?+Rdnk?{|P}Ei>(O;RM z(TkPkYB+y#Q;-AS#OUecs<|_C)-*^ychE!dU2e1dc%K=Jk3v}H#lH>q!;4?<6p45- zEd1LQ5Q1!gJwF|NG3z-D%(sIHis$^tC-i_iwKV2}VLtQDpErLRq_DnM(JhtT-dR}r z3PsPdiWLpb1Tntg{2_m~Gehn<%#Zw=`_>gB==Nm(NnY8`ZjGeI(4nSx5>YW+XWz&o z4Uu54TkG-snF|LiT z=4H$0P2@zgI>OG@sPk{mf~k{Xdab&5#1fOvP0okJM^&x=Yd%?A86 zgtqhPPxp^b1Ja7;xdH*o&k_LdpFBl9bgq#sFB@6G_P#mN}|u`PRk-LZw{_jJ(|n@XI5g$E--hrt9@psYy3z7oXC(|-Nk;u9zUl-C~0 z=upD7Q;^s6!lqTXB>oVqe`O6&sUXlxrNVy?x)%_5TvXD3xj&O#I%s=$*~{Ks>D5~( z0*zC6E=%I6BVVPIcQ`8F|9ZbIyt_yT_w7PLiC0#MEUDhU2Y%k}VPUoDPkf+#DQ?iF z(QBlkGRVP)3{NPq>O;zZvPR1a193Ykz26lC5yyNq2$L{OA^}PdLAde<$8n^Xq9C$* z8N$>@BTrz_m6eH=mBu7jlllZefeJL?Ld5}k!X1GK3#FsI@HZucF8Gna)kIhPm0~vb zmov(3CnP=teqEFO-?4(?ukP8mG`93G^l$##8@jaYtjlw7xOvIAJerA*Z&u#m0XKDX zw41#B+%#e$u=0s_+on|NudoyD>-$kp8uU!KBr01PJ_Z2cE&MHFD!idsTr?a?5=rVN}4;yi41=R^+hl{fgDIDJYo%~;Bp0Wa&mIB1@u$A zy&mJlQwts*uMC{bEY_uukGFtSD{%6ZjnDU{UgCBGoHUT`KRG%6HU%1^k^4g>9wkGG z@&<0{{-lqw!RooKz9+}cR@Q(zVHaPRP>r0-1ps(SbmoKA(LNup^ zrIyot#Z@LIChwJ9*HEpB-`bvM==^lgWh|s{D_oJ~I#=E39QA&Z%m^GJdC)wr`3;GV1q6dS zR-m(qfim)Zhx0jHdB#P8gA?)ytWfke#7Fzg3~tVYms#_xTrZ^ zHFi=E2+r)X`%oj+nI}Qim>Cf`G!xdy*17{luvcA3TKgCa!P+>nJHk;U86%0(AzY_h`rz98+;Q*<%ziR)x1&iS)z5CoLS zM1eDCW$;X@q234O3ULLKpq}h}3m@BPxEivJCo4kP zWukRQFKhM4^V8Gea48Wf5o<+ru1n2k>D-_>Zn+#dMTi)2!pJU4rV&D)0rRR{*Sa!$QMu(~JzQ3TxJe#EzCbYGJaki-k2qhg*-##RNf!HYN5 z-Egs%XRzTz|9$GnQu2QE=+RAymdVI}gIzB*BLkj*<+|i#)Cu3gNYz=rAzLR}3ti*|l)TvA0zWb^d-tE) z-(9bpo7?!CqlVi=CNYZ{`54NgJ|Zc`W~OJLpUade?$`(uE;h)`xa1l_sLYp>ZMW;1 zYHGRC($s|hmd3|ozB))goOsY=aDt4lujT>M$+RHxh-`VX9CgsOJW_okcye&^WOwGg z&%(cdGhtH)$LoXZE6#r_%!q?yGEx-Xrp9(lF3;g0${6_1_!J^K^F?KCsT+aPd@&c= zWc5utRT(7fY^UUnH8WiR6IGe_0p@oXRo~cp^>HGwO|}hXWrYbivvzB(S{B6?@w&Q#mUe0jR`s~yY_d4ojCi{zhLtfzEiEh5I>Pr~c$z7{*$ zPg#{`mW)kJj80AVx;W!c7VjKOy%-9#hSS1|HwWF(=ujW8>%Hd?R^x#lX@6q0Q|9r^ z?4N|rdvF4wtMldga?`a8^lon<6U#3@koU6xI6kCtj`^dUouZA!8_`?o4?NXquFzI>Y zlpK=wz<7c+_6EZ%Q&j_Jx5T;!s&5z;%O7X@lm?N7v5@HBJn!&nsJn)V#FW1X9qe?2 z7rj6O%{ET9xPlgnWroNg!?1&*Nijs3Z`Uxg;#OOR9;xhduDBXa_x$W1bD=L}QcQH< z1d1>QJYs2XY@rD3pH6sXq94V*5<88OiA%mF^=o(CcIPo;leGMctAHDJ~>lkL{m9qinH%?b^DK2AHJ8jNQtJ-)1Y9t=U85&53%HP-}NaH? zlc6G;cOyVV)OJFem=6k-wXG z*iazMR`t2DZMkwM+kfJUAyS9V|9pxqlpg+^3zh8eRH2~yRhOL(1>tiYYxc@|epgfA ztY|t+XxM`xzu`3f+kFAVe}NMZo67nM7FE%!y?Yf%&+~^B(1%{F{!SJwQmvaX1ep;W z@!0_yCu5CA^&`PwBi^OPPI#e-i_g}Uj}P>`dq_X4fZ>Zeo@I-Fd-vSh;U0^t*Z7Y1 zg|$f&@(;q>qS6VG6&5bMZ@rB6# zYqT7gi3$Ero<<-@(C=5BPYHt%*pe(1;H;fWkL@e6N)*O|*>SSIT%g{%70<$9U_D~2 z`K4Z##OwWNNZx?|76N|Gh7S?!&a*=fqaiy;ABjgXd`eY(@GS z`a}hlJ}#5ijA{-0u&j|GO|fa}9}V~P43p<|@c;me)b2-VMYSGd1@2{f6V3k8{Y>rq z(I*E8WS$%i}>?@5z(p_WfniTS_J4nEu{i z8_PhG3+;Ogh5C8whifD4k-O7Q<`fb=yGdG!sa~vpPy62Pxo88?b5gd(WBNtK!?gL@WWUFtC|N6#UKS-dS4BbDO zzk!oL+xh*jSGlfcURL+X;Ej6N{uz3Zy#Li4crDG{Y(5bJ@Ix`f#d zA>&$*Z&@17QEQxvI?;fD2r2$I9&o$pPX^ZGC-&lnp+R+hJ=Q@>~D8;G3Cg? zev29)^L@E?%JiXDR009#&;B$pjRk@IPKN1aI8s!w-^-9Poi^_qyeoso+~YYq-c^qK z*+U>Pu#x(U2&*esB?MWYXTaF$it)ma2&GJG z#GUz?97F!tX7;JDwoJwqE<%QP{-k#YvtCJhUH^J8zT^c=-I$Z~aeC&@ANhgWL7#U< z-mj%b$`ikRb9le!%+a$x_vm?RX$C#}4T2N+=%!$E*{Bz}F`RvH`>W{;P9RzBNRSHJ z-f4}+ZMLm;6~z_(SEiq=g#!^7ll0A7)FbfPD?QJqZRE~b+TTsD92DtGC(8f}2xNk} zkLej|BRd$lUGoVKKqxkS`Smr`wA%M&-G0wt%vEQxLXorETQ{LbU(8kFYC3$L3eiJC z7Z9jP6`brpq4>->`cEMAlf+O2do~jVVI=e%s@>;a9STwZ$L927`=Z|G8!p+WCRH3YAW$mBY^)EY|ndJxX@vKNr{J?+}!ukS6<_?t=}QVdD{l5Lntj zfdcfLQ(n~iM>FwnKVo9+-%KBPPw^!M3B9@?0Wr!I-Q29};=V&1@=$#%ucEG+bnXq+ zn*V>`Evu^|{lm=~-W(rK{Y4Q#m(^F^LZ4eth|sldVb%{J(HSA};!*w4@Q4BSpi(l7ko*tQjE zO>rwN1?M+aRdp3LmG;QZ?Z&pf)dO#$hQJ*e@t6)7&L3+2o20}*mFldAo}Qb#yIuJ$w*e-$%^;&gO!BM1Z&B;P~rnzrR8$fYQ>gECJfWuFpD=?;^AhgMjP48UcH^&SS8m0U^H^15C*_GYhm4pF7eI8o5scEegMb5xM zJuD>B5A^6M6>c>}6kDo>Po!K93YB#`aBM};u04!8*+IxLmyLx<&wIKBq&*0tO|CZo zEd)gD4)(|s@b};5zl*b=Q`~KkGB3eB7=S)#KM_3c*#TcpgN1;Et>H%zGuhtEJ6h`g zJ=i-sDy_LYw>sVk(-mkY#%L^G{CC&3vBh5t3ib%Zhm|#WX6%RL!SI^kttB6#o!$88 z1C*R$!tiC|9}VvX)x(Q&2I}b0I8%Di(Z7KOrlT8BNC#ZoC2>%XMWU}vUeC?CoS(hw=vd**>7TZMzle;Uim9%VLHWi`LAll06i z@yJw8qJvPHs#c5QDtzgZ^YQUBKUFP95@kz}6t9sIgQXm|-y#<@RRrv=4NU%LLJoJd@Kxtsez#@>YqYY7G(7-Y%#D|eu(2! zcIK;)XaXCP3A_^`8opX21MQGL;fGAe%+ZNJ-VT#g`jJjJ#^_XkGVd%g2Fiz z%}PRky!vbTN@k5z+7I|St0$K5o)3TM94pUSbhXh8zUVSRQ~XUy5TU}e5CJD>%-9Pd zG;6STg#t*URb1?0hWHxoaroi$iVu*|L7Z@Pud**Zh(|lb&suLuJhh&gEG{2@I zFBmDK@qh0~liy5xq^Z382=nC+@ouS7ApJp%zmq>LK=&?jgKS35Y9MBOv(%NCRUYss zh1i2B-$;ncYR^+hG&zmFTogdIrhSCzWtCO@kY|3x1vF*1J-P8+9KFS$R7|%*@HHl#(VqyjPt`fl~*hAEfr~&VO6RB(PuK^>GUe14eNw zSOeKc0PKBT; z1mC0iNRvwQ(tG3f4w4N|wqIkI4%EENSje+FeQ`9wM?uZ!@$cKxO&!!el8O)i2DN8B zc)v3}%OseWm)E{EZ)>vy!_?Z@tNqltt`Pz#jXUipM+pFjI&`hWCEG>Xp>1hj0P@jJ zQnu6B>=Y!XVXA=;v_BCv$%$zT-FoQn=1H`9^w_ApR$1-(IrXwWUNgCgU%1pihcgB5 z%PYUVSC}8X#C~b$ea+wQ-@g;mV*yNme@^=3f~p#M18Lk>h7xEEUw4t?`HX=Z*g9n#MI7u@}3;OzpghdIs720vCxpTRQ^k!EXs5 zr%%4|HAFGvS2M_C4RN>c&Q;^Cjj%ty`!y-)b|L}1k{z6^wC_^YTE>@ap}$%S-l?2} z`Y*g!cq$r;6tVXfxE^v`8ny3+ui;aA{Me|}-h3{kwXr=YAYgZC*l8pHJ;x(+AMD@OddiOz|{&X>ln<~HRgUP z$I3j+q&zGSo!H4yP`&Mp{`LAP2pC){!p-l!rM<>;qW}9Z5Xh7)hs~eKV!xmn2o@9% zfQXTdcScY2f+BsIeKqoT_KSh`VD&s{i{(zx!`zy@f#ZkZYt~&buqO~ZI|nkAMM^mO z=13rL!a3GBnDyc6u;7$l_*u<62V@WQDr>r%K|;gJExUUmo=dFwPj*m*KJo%adm+Y{ z=w%ykF#gXVTUZDGgQP-!(vPFzPcHv|vqu<5xMv z;p{!2-j2pfDNv!s5#y(#m8pvIr=BHV=lbAe1oNF-9vS&4t?=KPpsF3MHOP1ZuRBQa z`X3yMBiz+y9cG1wVda&LWP}++Ajo`-KiR_^|NREv&7Y9-f&P)Qn`9NY^yR>m65Qb8 zyk44H*>V!w{fPC&((`!c&0s*rXXbxzEi;)prX49Z9m={l z10y)~%}t(ob-`yrMS!1S;J$!`7q|O&ukpDM5*&>S_BNjiJJov1)!N!qHlNZo=ckKI z#mIKZ2xkaEUk&oo1Iv}grj@)`tn9`lOK39=e-+?XeLpn>jY367T<{$u6nq6lq!pOmFR)xwk8Z`{1;d16q6I<-Umt zBAB7%$l_UMJU!;tXF6X0Eic%hT+GRB9NVUBA{Rq*&dQmOq^>XcHLVaz7#tT0bZ%l> z>quc<9e&o6ZT{8f4`kq`dgCRp?BGKx-W7B&+k;cYOmcf-^{Y2PA3d=v$?s@?%VEbP zlf7ps%)3<~Px>X>o$9I9n#Oje(F~hP&^U?@>=4U^cH{rKxw#2O{6nCf(P%3B$xu|Qos@F7Y$-#BQk!3+<yQ8vOWBl7iHm`}EiXS$(K`i=`7I~u_4I8S{xpoYlEW1ODK`Hg5=xUrbg+9= zK8s@@Bi1I}zrlNeobM^qq$=*z*c81ZqKF)_{742whAM)bEJCOpfK3bG*MbFWL3AMX z#%onQy^Ap-@cu_*6r8Oq>%sl#ZA`dqYnuWvNv;`8HlU1H>=_mfa&y%GF9Uc zOg;K~1!Wff!_KM~1ImU-ret>Zm(hwgYF_*=ov~{GQqheuQbPF%p5ux)y{{g1tTuJ> z7#{M^62s3fWFp{lS$`Z6)eNrxXyhh4tAwkez z4-WzT+xvuYDL{TgQ$@o}&sgcSfc76c@p?H6+tRBQwv2Sj*VTHTpCV;Y#=>sN;;{eO zyo`N=`#gD^wAp9%dT!KDWlHU51VDIbp3GQdWugJKYvr5L6c%=&oA+FJ_!B*`yvJUk z5V5!NLq#pmexYIelNtj-iSlu-EPS`Oloq~KZjib5K6roclC|hTL*&}>{j;?h==;@_ z9ojD`i)V}%o|apPtT;)|&DGwGxcrF@ zP+475cQj;WV)?kY${X>_m$%e9rAPwO25Q~*DWAzPRkT(M6aLrTHqfW68{c;V)5W?- zO3?f&uWJY>0zOlK9IL7$i@h(xabQ1d@p{o)$R}}1eRkFqOw@yQeCYizP=l9s_GTy+ zZ))mC(}>(zt#-tyuL)p2Tzd8}H9A-e#^V|DRDp4>Avgfy*^fYrwrI{o9D6(f6Men;l{`sQnQR|_4lU`gpTal+uPsuS8g1fS%YY! zB};I=4~WZQjM0r``lz`Q9n0+VtkF?k-(tUq#leJsstCgFLLk`bVW0${z&)>a#t9cx zGV?e=gb<&@zVAFFN{REK`__Dvfm9NiYow$bw7+^T*uo!-7O*08LKLW0+2yAY=N zenuS#Y9)JMO^QchJ*?L9c`~H+d7lkbt2AJwadOOI3xZ`#SEVIVbgh+FUMpn481f0v zP3JYn3FRal!E2n)YgReUR0xt|4w43vcbHl?}SQnGwc*$;@j)scr8pO#_i(3KXFm z3HJ}3f$AcD4v5D?PmZ%l8G$tdiF%u(hYJhAQ761ukV$wwE&sxUizV(m?Qojue0fj*UJc{asx(eM-Lll3)QwoR*dY!=}x;J?FOg6s~ip zVJe`%r)TXib z>Z2znlxLLZ92dIzA?*$$=A*yb0@3OMie6MYE6MpF+Qc&`<$uJj7Mse1g2`V$0a)CE zpM}bWfzTrvvL4|Y6&p)Z7t6Z}WAoJ2Lj!~VZ7l5m`S<5h30}bE201uI9G)L&@>NPY z=V5u-Mc4XPG_HO z(70SxwvbQ&ER~&cFid}K06E><+MEzq(6(CAWgzM@)Bw?5&e;;+ycg)jZvZ`VS7xAi z77`TTvyNB7HvYZY5zyjdRuMQ0)e{Jg{HM)gw<+Awup4Y{E#9SK=?YD2U4sJCG;$NXToKCgg*R*JpW>SrMRAw=BkZkgt-_fwr3ZEkFM-@5*2LTA1lNwu~sLuvGG(-gGrOuv-3K4$$R!_brb|kG=-in)MS=GLDZvx zZ!^(V4uF~_ebk-oxLn`otWVO>D*Y`hBu+v%UO~e20li-aqQ!S^Ti3gKMbw6Gxq_1E zFQA(O`=7bk5tpcFD6up4u9u8-@xjt&J5Fc|23#|#@16?cDCxg5M4MqtOyW1+XV*KR6=$u&be`?$Y`GgWXtvDH1`;pk+#wu<& zr#{dmONR*B|FyMwu-aAY= z_sBR)>;<7}Ijr(30Cbc$c;Wmhkhm{?HOF9H1Jq5h(Y8(@nPkh`drQ6>x3Dd*e>k25 za|k378m^ov{nu(Y)fV(pwhy@};68K%e5VP9udOF$1?kPcGWszQ1Aqxpppy;W9SL5y zWGCD!D=L;2NnD%(oAX)KjOOfj&5B3je%o4Kn?tO#hw_`#C_JxJ2VUg+B4Zq!`-Nb5uTAtk|QOJHZt>9lWbm>ltvUPP|$=|vT zADJ&XPrg5GyHf7_y8;|PZl8-2>i9EPUMMYaT}@rZwxVpV*`ac2bPmL~answ|di=Mf z7}4qmL%)4K5bF{UH-#N8^pCDM6CJ88mchuSh}o>F${~=S)>hGBJ<^ zn4!et{%zYXaBZtd!06X1UH%Y>6eG8QGaG`uS5^isp}JAAgUwYVx`Xd?Wltk+{(z&B z#hFF0X7SAHpF}_q$Z)IgvY|w&OO%`104LN-({L(y`O5fs)~s*t16j1_z^1$bk1Lp0 zVW>g{ggl6EhM1&HszoQq3W0vbZMo4LM|S(B&o*yYH351UrNLh7P8_8J>UC$wtB zQ$ojnL>~Xyzoe2vJkxX0Ek`lav=0~@f~iRK1*?U(px?NZ4HT!q=EjiDuZ@p;C&}U& zn5zSW&~i34wc7uOhMNHd+=Gm_<3W!jc3P&|!l)Ne3&X#C->Kbz?GT?(urGL(O&ILg zAsW$e4#9AGiZvR-07Ws}t>$u*eCGmG%( zwTC#O)G;I#szx-7gH;vC5Y6VmoyUrBfM=}*10UQj$?^+3uKJ7qIiJh_ zp9Q!$dGKLO1^QsK-+>Pys*N`}o!zdK}`)-!>$_H3U6Lu{uL0&H82* zXE>4=*8nF5qyzD51(KO^xAO*j+2c&xV0 z;rtPAV5WN3{Ah;POUos2z(*qE0%H;#&~pOAj!VBdB%VJ zyqSu>`y;?UvzSx{F2%#9P=u(C%q_D*Lb9{s{p|?vM4+|wu#phy!^VP$o5sSyW1<6x zj&eT!hcjVva%_Wg`iUj)CD=zHn+AJtTt|kEDO>GR!f8l`%c75byx1MH`6b!(jpp9r`g%EcjC?Jz z6RHg{uTH3~9pe`iJV#RI9>^u`u8pvRv$$-YbboC5M=g^7s&!sjEX6kPMNW7ipFmT;g-5-zIoi?$?=V|V*kXOf3dy#^!e5taSwY4=D zH|n%=!;ikU;PqOMC3)ke+p?qrtL>73(@l!Rpwrqy*dlzyc5k6~#PYcD)Op<|JCMPA zsLU@6?5?!N?7E=86Qg5eTAy^Yfhwa=T653*@|qAII6anJWuRm5Ee^C++L=14+-W-^ zzPujtSz@&r)-c93x4~P*x1d zIk>n!xUy1oIjy|=aBc4Q_TR|N`8#>Q6t8kH8+GJ88A8jN+WosTb+8@Owz=9KL?u-g zc6HU-fPBd7!1sXUqhO!FysG9(XjTR@7?7554~$m{CXwL6G<)8jK=T_AI-NRjE4wYh z9MaQ9lR#j9_$ZX(lxa844B1@4ekZ}HST4IWm4L@*oe7K_B)ln0_LhL-O=K_A`(bc= zYrY&-DT~d%OL`+mQX6=dY}#P&l~Y4utqs7J`hHd_DXebaAq)m9=K`zr)+8g%R&;Kj zG#^TIkfLBsjeNL&YE6z9pB3UV4Q6U?a5WM&up2S|u6XLF@a@lg-8_gQudKwxvvIz` z3;uc%g)osgIvts$LX)%`G!95t_+4{?|6>`rn8D?uweLI4FK6F*9(0Ebu!;jHnd@*c z&9XmGNaZY3SN|w@ll8R$TX6Y>8>EGsdText?__UFoWJzKp8^+A4k9t8n5BqA^K0MB zU`#}7MV~=|+43n9n>;WTa%-PHhx+V`J2|FB1j*&J?oqPR)49P7HI$lD?Erp&M(e1P z&z|32sWdBN*XYTAA`Oj!2|*A(n&Ev;uY|QlMgPQWCpjk5P@jLsNON@W-pZBD|I9P% z5L?w*fw5H9UdaX&M-;9u0|vU;*D++a>3f!M=w);@+O0uU{w|#{>MchXkz)&!LJDjdqn4nwee3c>+r9+DW=ssn}Xrod!-|Xk)zrzp7%12$-_hZ|4Tke0AmfqRfNxG9H^`H)E z5LyhudgPJ}MBj))Oi+3uQb0n^dsZ+1NlR5fG7W}6e_h;T6lXPiT)7-(KC%UhyP-7; zExC8c%8vasSq^||LFiru1tQF0K#iCRGDrbY)}}S`InZG&F{O_tP}p{xz4T{aooZXf zH-r+bLfn`_k{~Fksh-UL(RA+dOuzph9*L1MhnNzEFbR|M*+MMJSe! zi!hW^Ie(mUm_xA~GD)_OQD~U+`Rw=p{_)%2O^@2#@B6-A&*yb@VZQ(I)dz0WsRlv` zV2R2fDt2%4wxFI8u#1$ck=hZf>*t_CqA)FF;wFHJm2> zvi`7LD87n6$PAFVTQ6zAJ$T^XlH?kBGBY!MHsmI@P`dR#ZT&0%tvmJqj#(T z(#${|s~JaA#4PKqq`<$59S@Z}K7r2mh_xG8^}UG#QK4r;N2V+b_I$mA7VeS^Z&U7Y zGX0L2-aiC>R%f2QBw*N;d~3%e?bd^8QL$mbv2dw+`fhOt{Qgu_F>xm$kx}?!1|m5fs9GcwE7XxQ!_fBsvSsN^=MUXbBF)g>7>uu z@dwQk&_cCxLEd!}tey$qiUBiMe8j9ByaLLN|;A1kE`wWg26gn*zfQp422F%=Lx0YXu( z`srNjPjrdTVA)+hW7 zbefI<6wjB@@#H;|LAvZ`Bs!$#(AV0^K9$|Q{5eOat2I{SPp}Mh&f8whM2+tfF2HEg z37Np^ov9xLWM-If8wBJacH=21(Tz`) z5=_rzDNyn*ix~^T56B5%f9&s_QbL-V6!&&RPFJ&{L!yE=$3GNMI)aWW);f-s7W8+n z(9ht?a#e;IQSJ-x14!p)+L<8mqP)GgrYQH&8-8?b=g--YwLy9He-@YVMOeD%%Toyy zCNqFFEc`ex;wGaI$jKKAV>s$a1Ubi6?Y$jIKA3NRaQ(}}^>53oUfQX7CeJRe!M+oC z*XRiRT0VSwJrQ3MSdGJp*&&vD17UZd_)SNKQ~?4-*|SRFx#<->6*n$z@lW4T*X&gH zx0A)r`UQ?p#JTZH2pwAZExj%|c4$oq9>t;YrV7^gdzV`4#R~ zMO|HaYlT=y#*~){M2G#kE;HBpj{5Ur~BfiPlUbBK<65yy)x<~wID_>yk6c^ zu%40+vaqxadd1E=s~C-*nBDAsB{4wD^W39 z6$cGu+I$#Enq@oxurJ$5OZfR%_`&vA#c*e&f~}?PEaH5fjnqUneDJq*M6kbFU-H?u zz!|0BG&S|7Vd7#E0D{Uhd3~#*8EfoVW%FX-R_?QLN2*4nbk}DQhT?db#UvQwT zVbg@d?6*sM(+RZE#JSUIm#L$y<>Q|XuLp=~rxu`PIO(6M8B z?L{*se0{~I6MlZN_0?U`>$v>(@GVN*D3A1Hs|KJEUOvW}J?6fEz9~~X@so`b$|)k? zlLDVvq>b7(KN&8yYWa5*k&!i=pU3K z-Rb_V*oWbMr>g)>XCs*{iIgVFeJ8s+K1c>&9plX%Tlqgfhuz|PVsH12 zl>COv#?38r@ocs8#OE|s^LW}pJ>q@*#IznyMD{owH z!}c|9WOw2CI25h+I~${88MU3v_SFq$uuf9p5taeT<^55q$a}h#k|+?p|FE-9b@Ute z=!nxtrL7Slpi&N~+%!*91kU~loUW|_tGvMR@za~V&WPJ0UD;dtW^$z8ZP9D})Pf*y zdA>`<0DdHX>!&qIfc44m_Sf?{2o&-iBtLRvK76XuGC5WA(A5*Yx4+X{aJ*P>vW#8> zNZSIZN1eyx(we6;AEMVA8eF+&#MP;-`fOmM-WmLa@WHxs0Ou@+}Gn{d=l5=`XXMF;W4r%P%jjiW&i zek*_N5aJds&Jga_k;WEk4G2kZnHppxpWp%n{tI{oRv6C#aomH$pv>0ZOT=&%E|3fZ zoPjQ#+c^FQm!L=z!wamed(v${##VB-pq|9!6PJ50t8cHhh2b zP6n@d;2oZj26sHByi_I;L`=Qi%l5vurVAu?q%6DyV%i7!9FBj9$f>riB6T0sEz`kl z;23bcgPq-z`=auw54ZnLP9IUuwlz=d`%nLL|LG2)9Q{jnd`cOdUtUTNpeUpSXwRLSnrzKc zm~2bDq;BQwzgb>3xf6cvw$iUDMvnGdz_Y6jKXuaDWHiYRb~CxeG+R+|m$s5J*_=5j z|KgK_B(#M6kH3PZQmaX3N#^G;7sK1%5qkIU-D@T8GP-!GbC75kKYj1qv5ii>Z~(*{ z50>V)y5F5Gjn&Sm>8WX|PfkvjU|m(#-T>e)^7PT_9`Cs-9S7Hnouxsvw6yf2xbCj7 zkpDXGf_>iuKh&~9SI2bw0o&YSL5LZ;R;neVUxDL6p zx{B9O9`{lJa0d&x{lK>KEwBMMkU93WsbS zH}6fc$GBjO)nC>OUSIb5}c&=dGFJKUkB-gdZ=8a>O@d3ut(h#jm{{5_%Bp3M`7 zFZ$xpIenEix%&an2_R;_;shCx7`!vj(8(~2db#coUhmgVT=nWcou7$^4! z$>f=no%;0aKd+mZCM2QCX3n{N3nT?LRpnIEz*;5%bP)M5z!Ig-cj;E%8@KF5FS#rB z_D0ES0C?TOdU+N24R9F%%k(t>Y%>66sOGE_%eBzktDOFyJTJGkUzoByA=rEL#!F~i z5F>Ta8VOU)I%$U0!Jx z7|Kcxp_~vrrc6uWv%2HaJBQzZ+Y+Cs*`37~exif2W%12=EZptF@piW)AaD@jUGZU# z;p?RqGJ*-k`9kC2JnpUlLwpiDZwZox15xJu1D5rukz6H7<#-}|5z6aAcnc|-X?Ns) zS^MXmH2iuJ3Po+-AznF$-F@j`rI@#92RP?WmbZXxqDplRK{*$#Y@{E0IM%{UUKymh zFpfmjH2jM-8~Cwf!gDYy-SKN$6&PQM-u2ZKspxgCcTiqqm~}k2HfojI+8-|n`-qjS zEBv10)B`ocJ);j_lai8dfhB*mWssC>G)4lL+;R+jtcmO+ zHf;`7;x1oC{+nJ)faaDOfG)fPq^=`QZ_#1fFy{rYtjjrIo9zH%w)yAq;gWBglJOw+ z3!E2%#cYkTMTQ?z%|= zmuXoNg0Wqx^FPW}8W@x%BrWT*LJF;*VSrn&5Rq--lqxBqe^rCN&2R4%ohmT=$jqQ0 zC>m20clQR6Awb}DMfl$r1FE%W(H*b0a`N!eN%!vV>Cn|?ndghk0Hsw&0J)ARge>jQ z0;GCEI*wL=ox%R@P#eQJdX30!VxUT6UfzA_;rsWWZT5P60k${Ow@THccIX9dJoDH( zkGK8Ia<3|`NoM7ajwY8s$*LFv{FHX!Hq}Yf^`TM@q*u8Iq9FQk@xx+T)ZzBx#s-{G z{3X);I)jy|MuZ>kOXqX87!Q*k`JB zZ($`wY|=J){@4n*Hatr40ev^JXsiOFAn6OANhFd}gzPU0BZ^wDE8;u58@Cg=vpH_| zdVdt-tVJ)99a;{6w)YP43sb$l*60b_=CweAdr3+ouwdHTN1wG#A5uan5!>tCE4FuP z?l~OJELFFKoJDm?S|;-XGfu0-#3SJ9qvgRzNtak%z_o5~k$6Wj=9Wm$9XSG!vI54m zqJcv^P!oeiJkvX^B(`o_ z0hbw^0qpsghpf+lDSeprRlG$2i+^twFt_DB@U*Hp?_7)# z1sWcbf9h$E$^u&I@wd}(d3k0mI8!}3XUTdyKNDA#;ks(?H;@D(Z<^5X%SwH@a9FQ@ z3xgmlhf~riQ`Y$s`$;#6IN)pEU-wNJ-74kQBU?4uG=fq=^M1GU)Tsmz1~lECKfX}p zPwRhp#~L!_APM$tF0S*Q1W3y_pIQ4^7*A*p9Pvb@D2UQvgw!hj%>6>V_*=sxt>z|z zH`&7bMhOdrNx*c0j=5}7Poh^qEqsr$y&io2u}oU_BV1=>Q2Ti0ouZN5 z-Rk;3GwUD4!z~(Zq4W)9-eZ*0YnsJD&b<|G8F3Rl^0+HF@(AZ z3u*rdEL|xd3OCzkxtV~lKg^oLGE%Ju$KFkgu~as~2zDp}FI`~w1vogS9@e;xc+%cz zZ+0ID*O&2@gk@G`R%|%w$6)bMlL{2&VEcLiXa_3cFZxy&qmO(m%{~84fc@2dhx<)p zBW-foKT#&A60DtnY5XljPm-1r)s)$1$}3o&f0tZw88l)u-TpLmYxgQ}+!!C^83uGY zaE7DxqWdL%DI1ALs`m>tHb$nECe8`8dyfvzwpL5kR1=B7a&#Zjdh+GVy#Jff7YIS^ zzqgHTq7UXri@sd7uFf3X0g%f7w%m05!xfH}>$9vzS(u^Jz}*`HUmVYdh5_K##hWFI zHYna%uX=0E@NM5{pFIF_wVZYEpQA?T>_}h}FQ!Q$cb+FzGt2I0N@u{??w=7lkm%^= z@D>%7U!%xx)X~*XPs+=kQEH*IhwB}Z;pVPmkLH1E zIFHTiv#){M9@+d{}wX1A@2y4Sg**1zMX9o!i}`=EH2Y zG?i?s_oytKSqmH`BMyIqH)RjB&0tT{7hKGt|08G04NlSW`VXCj=4+b1+KIRKo# z>qEfw5aKWA4p1I5%Ix9e4jXT8fL}AF;Jq!S-UxM>tEf_-syVsh#z-pEP04za7`yXi zQ<#Z9A){r#Riv$&{<$112~j$dS#Rk}hw&(DSB&r4*w`4dO*}eM1qp^lH`-WQ*k`)E zrji1YeSbnf`cE`nL~o`fhJ3IBa&;Yl?daKa0tiqUZY0*!Ly7@#y(`lah#+?Shj?QV zd^;Fw55{d7S=gVE&B}}aVnTrLL2{Efvor9&bph#auNc($IyQm|1qq8hcbX_IyOHOv z2RJ_9(ZkRi14x!IKfexqy)O8p;fK-lVEvM+M$^T@zP$Rf!HNb(L3mi2KVwp{w{2C> z#3KYzSP#{$@*!cJasiHjczSPZJny2MkQ7}6Q2@osT$Y^U7bc%8Y)n%_J9~P{^7+uY z!FtN8nT?%rGWqURjfL2Q88fn?y-B*ojf-EEsBmIhc?X8xm!+)!ycUQVR3gb-u|USy zV4$z*6KLP>wG(%G1(k+_2r=Lo!=)L%^8?U&qNug}Jm2l&B-WU_;|~H51#~=BwYXbr z%Xro1kvo`$_Pr4?;=>+rd|J{X3kC*)+4*X5VYGFS`Zdd0C)(rEM{#sQ&md?kD;~;l=nT9{yJG)S44!74HRa*BsA>>bSrxk*6H9yC*A8a3woW3 zZ|{A`9U@F{Bfjg48+Uo;L~U#Iyv@3Pj+;I8QmPbDx`9L*FZYPV*v?jsylZ{{NTFdM zz{WApJMUF%)2XHbW7rf*MQk(00ek81Q+V~>5>jg!jW_{O2kisTkoTY#Qt67g3(%F` z8Oe&vXCt3yzs~St#JZ-K1@RA{4%w5hioV_2UEajWK97Ov?4wvXUCiy2JSm@|9ho2E zhLQ{Wl6S&a@aNtEhrHXHNlchLgg!)AwBOh|lf8C&Z5kgEqTy&~ha2MAn!@MlRG^}f zZ4pdh`cFz4>e1UoRiKHxmeX2*7U(#u_v>u1w`w+8A7Prl3M^>%^qrD`Gdq{s?E%}_ z`oc6*z3rr^I&}oWj6aqsKs_|hr9xnob@#OZ8(X38guMvmJ50_=JA{(MOkc)I^Alm0gJ zA`|MynmswY-}QnED-n3WQ6{Gysuj(KK;FR@eC+W0@pJ8^&f^E)Pc$I(vsRB z!wZ;FR*Wsa?m<<#;_CF|bgp>!#E{-y`75abRp&p%UbuM~;)=NoV~Xnr3b$St32~I6 z+&f|)#1umHJ_ZCU@uxP0ocipqM2alzEySXccRK=#xc-Vc zra2R&+!_{uMw1`#2$_E3&hflizH_`d>SzE11RZ9Xx}{i>+VC5WI;%{iFMQlXIpJ~V z$xukLp|sVO>u*MSjrgJP`UjHQeZ7(6aw+B#gIn=jNeGWBajIic!>9}<;8lEsQCyNu zg+on2Brk%XHcV$=&6PXE2*MypHa!cswUAI_xDGi;#F=&E%57dy;U0esa7UF@L#-1>y0G04oqt>&lA9SlRa$_0$APf0qdrGXb=pBV3iVeRnXOMp0w zXhp8~FXN~!w-gBCZ+@Br2Wlzu4Jv+5+rJxnCsqr79%8CO{T0Wwr*XU<*Lgfx(0+F6 z7(q6Y9tNyoZNzFz3-a4);1r|X(@%1(Yn12rM!;-m|H_x;-6EC{p)TMw^BuC9a`@BZ z;we$l(wp6KG*=v*u^`3-Frkq@CV5H}%)}Pk3AsTL9IjXnPziQVV_)AHi&UW%b78-e zpfKHmopGX|P|>%DL|S%#Yv!^@L}lJpH1{Aq4!uAsD+=`^o=_T zobuw@XQ+#tkMGv*HQ1XysZhlN2W2!|BwW-WxyMt_jQ#?w6#cjr?+1%aBH6x^6moA{ zUGiwMtEt*5+TiAi4DkVei;@C@Baa6Hy^}J9fCA|o<{l(7hy&zYHJFS<0X~vP_1QBx z|6e~>{PCNJOgCQPChrQ_AtixViPEX5ubq-iBzl!>t1Ru&b&_T(7Z4IiUgFGSUan$1MXcQ49Uor>->kVXKpqo0|;lf^eS5AlT zQsQjY&Ai2?>dDg904g^j2H;A?ckS*<(a%aSN%>5*Y*k1XG+E@`JslZ7d-QAY+~Kwv zCMkI=HtnNQKS3F6nW zf@rMCOgh})NS8v(0-!a54g5QarjO1x9f5hy+16Q>Y;bURCcK*0X&qz6^UjYFs^};w zpb=hN*RIHSEDijL9CTQIzmOFV6>UGY9f60&lIq+gSiY%D%S{~|jH#|gnU%GBUxmF5 za$p`eA3HhP1IC}f1-5yMUiUP7pU_mod96WdLIf-i1ozM8zO>Yl?t6<>H3tW~@W~(} z3k#Y@hch^ z*baP^B(*;lp7(jxd(zFC(sU69{k$`Xo0EJ~5L?fn@4x2XUBX4;oss+WJ?JJxd=O{q zgnb$@0d+V7WZ~IDX>oN~&VC1n}K@C{T zbEto@-&YM8i`f9+OfyekQ(^HQ^>p;uI<-M@7{-+Kb&v5QyiA3yu*!61VLwqOh5oC)cfhPAN^tL zI64uC+`Bp*8c6$>GQ)SSuq6%2!NB@TiHgs*x3BzHUt0F&$LvO^r>sGX>}=jweej>y z3oxuDmY%~fQgc&)c!MEE4rwHC0pWDqD%)Gxj71DQE+2$-&zvg)Y2C(PO<=AQLF^*9 ztt1nfS4mJIj+kxxFaabhOo*<^9IP$=C$=b7858$VAWmR+P}?C5dK&}Mj}bBehth)p zG0xlC=dw;XQzE#lQ9l8q^BK#3U$pDvUR0wUQCb=SMA@GeKm6BdBYDvX+4a^x5R8Gv zG%6^izLr#^RV;d$k@NhlO#qs7wm!FvunG=YCx;4cZbQnKU|9zR{V6iy{fvz$|-MEJQt^({E znrP4u_GESuyhF4~o+0JC%im7R#uq$hF?W7M-h`+g{16SDZTdgb}rml&{Wekmr8N}wQI06 zbeLIl+2yYZbtF3n9NFkLxNK=a^#}+kJ%i!`!t%|KLg`0rl)z`7z%{RiI}Rv{1?my} z_&xiG&A;yNuY+odRNZJ50EU+jcq5v5wsafIIwN;0Dt{8>C=GbE8~$b2Rn>kIu`>2N zkv!}n!IvhRjv56{XZ{`^_w(FmV+&rL>g=@hwnJBX^9m+_F~P(Ww&-=H)PhI_zKch3 zBd6W(2R6GyS#f^E#G;Yz5fhy>)XpK^N;-eIruq`wuJH3x&(Vs-)BuvJg48NTN@OdZ|vsKw)T!7Z)rI3iC_Qo`u1Y%X9Pn8yf&+dV9PcE$!I;NlCp!rE@cK+drFX?Hpp8xpXf;5S15#@!+itEDDAIC1AuN^URkfktb%2L~+z_lxghw4Rw~owPL7 zhw0?=;OksLvm5_e?TYKtiww%HwHuc|@wDg0+`8ftE%U%z0p(86oeX+CboDieMb}3cp;c&jdjlAjTbwckrt?Ca1 z8M?Wjv2YEfuB5Wbel&ZN`q#fjSrs38`geZ%R5f~1m&ZjAX5-1dRRPS^g14K>6%ajK zU*_$eu8$fc6H3MMWML zE>i*gL;WI#gI+|zXb6)9)Vb%HD7GH**!l>dZ#X;&(@&Q*&rDAT9wwtMp<-Y{;SSLdb zYZn!y)0&eey)^*qQR2J*YFO%$59Mg>Y+T@Y^lY;;YMVHTxu7Mh{0OqoIBa(>SUGOPw=X93jw+DPXj?iCRMAxX#XQ0YT6-$P7`I1PU&r@~5x3=Gwll!N zo-E0U31EccA)l?YSlNIFVToy9oj7j^=wrhVmAm?YBpVQ8+!7tEJAEe^kzo2`5~SZO zHknr&W&&X-Gk;CZ{t2`$5`)rKH&0&BSRP^)eh!lr3rWCn~RjpP7?acEY)@)En>nCiLkL>KBt7eANgj?c)QApR`|76DR6b!UH~-# z7LDN#_3kFSj3=k0P$kO5ODHml0R(3HtOV>Bbza`pvPW@V;&A~}TII$VKzi`^`s)*M z=i`-VV7ti*W(Xl{9mXuqnWtft*w$2p5#o3!#~_`s+07|}bppfQv9UA5h{`O+kMr)z z_uT~}9Ev`Isp*iH(3+`RT0(lLvShj#P7q35xa%1Vh6F?E6rl`jne`R(+b@wQJ0a&K zCws+r%&=HLLmCeftgWZb%lA!Ll$TN|Qydj9QPH5VqR&&-r!3IVy8ibcD*}ax(*-v^Uc+a~LT1Ff4=+Bf7`O z=5?*-=(P+o-NIO173}RDz7-ERi)c92@QJ@c5NJjvElR&9YbsJ|SGTw8mX=~3%3TSa zyvT%?9PK_*y8#7+o)F<8I~hI5n;B9VFb@ut<$dCl`sxzfVC4g8MQMlpsKbM-*ezLU z;O1j2A=Ece{5sRRJ-%t@aDSX986f@NyG6RS0UcxfyVC z?YBm_?;bHQ_`FuhH2OnK0a#; z>oPY6rq4c{jZL57r!9Kll_@;ihx7^jugz6(T%k#sUZtZG5G2f0rD&*#d>P@MJ?_q% zWL>YBKC@1;1dlZQb2{_YC=j*%QIYkvV(f5kf9I=!rUJp1e6nyy^FdXXUEhvJH{7_a zDm9|5ZMfq&mO(mxVTn<^Er|MLGJE8|K<_sOrMFJzN6`hq=Mvt+I8ayl-3AK~=LYIo z5he*DF3SrGkCk$~$`7*yG%b;=EWEIov~HW1-4W3U`)^sEB@Oi&VO)bkRNU8vmyd%8A0;`FzAR&pzO*DUaCUuG{?LHRs%r8!8)$Y1@>?mjhU+>C zY?Qrlw<+@^kww-LE@DfA#L|T24ZJ*mvpu?M1#{UHR0w1}`aWst(8oWe;zJ+?;GQEW z!UklHu~L(%56Gf@c;41%G9Uxh=@ zy@&Q#U06hle8o9)XJS&DOv78d6wX%;2ih%nnDZ z4GuV%)L3Ov(WUO3hr24=(e`UeG4Up%N~tiB zMSWQ8F>xva+g~V-9<2~d)tu+b-C3Gti(+pdiA50^5~1pD%fu7K==~yrwbhmXfy>8E zm_lx|5<|kObHeS(cf0%FIfA>3T@i(~4*Dm5dz059X%TLetC#Lrmrjrx2;NI$8PXbG zAS`0>0-w4<3O(TD+7(*UxM@mZyX837DFpOmhaHWRGZ6o3$3z7o}2B*^I`>FmNc={ z0y_tL2YY*XSxzZT1V~5IW>Ym=0;mp+){5R0$^1pXmA4M}$NKv#+QlQ>c!kDQ)dqlJ zg}F?StS!^aXz=e#CxD{tHOV!YFq{FdNdH$92^e(Ajs>o=Z9BSingp z`tvv+#j9m?x?|9*IZfBLk91$}4aoAwrYle$h~2v8{L?z~GXP9S!DoNkvPrW0f7-hT zhR17(09LoI2y)Ohjvu_|;w#Ct?d*!yd%g(_Est<_VGw4*CkH9sbN$v1+{6dki@v{r zi~tM5_+9;hzeddUV%ToGXd_gkz`uL2Fbz4^;!p8|7jq##EgV0>_iw5x-G^R} z2Nk_7ULw-jwSj1@`G%r=;so*dKoT5Y)o24$w&;tWEH%+AbB$V`=MX~$kYG@cjWATk zNjLuvref&jg?o^2AWEt1BI&+@{bAz?TEJ-Q1(vFM@}jL@%X@R`7jwzzz+E|V0`1AP z9dNh9_|=PvXezqDz57?=!O4|pBJo?9z^Zd+(W21%O6+U8V$KrrI$~h|ueS|dAdweH z2$&EOowX7!BXM)x1mbG`0?LQ9~dhL^zU z445;CPT!P34pTefROsD2k2Sn03I&e`cPBz(K+djMiLywrow$?ab8+zyiZBd^Sc@#Y zP#TQvioegGzZe|ro_-H(f zUA*^QwDl+cn=`yiM)f55$?zEkH@D1;CSRCrfQ9OXwWgLPb>4|(h)iNfIBip|0#L_! z6;7P6i}&Qp>WZ6+trU;x%bijMQX6zj$g#@ms7)1%w6}u3HVyXQoCs6oy9AGE%wy}Y z;%5B_2s$A}Jh%(++v_$GD1-m*`MrScLzk-Qh?W&49ChEV$qGDHStqAmVZ+K|>}E6$ z@VBhH)b@e8LaVv3YT16}%dtM?7iHcWedunh6Q^gC_)#GS&;>k7{Hr)KnUxg1vnZf6 z2o*UhM}GTfhBvP8+oemFV(KzRM**O&u@n$HHsOA0QiyGTN_{eFE#g}HVA+rWiF5ic zZ((26TKx*xlM^ylZqD*$9fm}&33%TZ1)9mHUlgYejlu}Unf{(~X_)f@4aB8V&lFCi zd(~3V&cC>3;L!L6tJU4=lvh*!W=7I18@u^$WpZo2(7i1x`i9Pe%GunO7;vvL)gET1 zZvZdCJVFI~=Mqr*>i|`q*hI24nmRcJu5Sc7HfB!tqRZtRZ)OqRSppq$m0{?twL`w6 zQB`U#;b&<@F2IFY-Vs#Re+@xxNfuy&pG>#P^S_dPNsjYv# zM30qZbJLBiplc$7;^nk$Yh&nhRWb$~U!x36TB$$jVw0Fd>5gUX05Iw=qVO zLa?yRl9IR|5| za14hBx{mWUD-=DNP2zQ9jrpac`JW}29luApKxp{UtxU7)c^ht`pJe_cOu+d+!ew3d z*tIuqhHHBum0=ktdn=Sahp_e>at=Tv{Is|pzpQeV-lHmGfd9343GeKS;jZ&V%Ql}O z&fjf#tg9RD{re0#C-|P>rCJuMl6(V{lNAQ06K7bfYNRl|;{w-(Ot+GM8vPxo*GADH zj8QLznn^J2d&)wG=3*~jn_giy)w|9ErH8x&B3e@RbFI}LOGG)$=tig<^i`eOZ6q$W zOZ>fH{I@}*dmi#4mX7`ftoY%T7xDBm`UW8!NJG!znm-GU1&WI@TNFoC4t8ZK!)rfo zXLDI$+}9-B1~m4YIry3AAA`?qvU*@05%!S>gE}5&uNmHQj%=r z=wR0~a~|!klWmuZGtq++^dTi&&~u>oAhP6P&si@`R-PcvkYzJ{be0{S0Uc~wR`aQu z%6~dBsaxzJ{$%2&Ftg{+M_G>$Oe7JQ=bciOTA&lNdCpGC~}q(lr)cvbZ*>n4oYjzaD)?m3^C@N}jc6y2wCXkHnBLKqw24;)qn@yW+`{ zeDJ8HuRahRF?ls(02;yd)qS*y5)nDi_m$N8Jtm}lm;(;&Pj;5M!a;a-|334q(WJKm zuvHS^UtSY62&a*57=5S=(jMZxGeTK)m<&puFSIJ}+p=QcEr zr=I?F*$E!Ml?3l3m5M`F-lN zzS#wzWB)J`7}fH?h%N$jI0qOc%XW9!G*0J60ZGf}tms8g>CW(@`AHz)y&BQE>Dj3P zWtF}MfF|5&&;82sqBlr`ZK|ra8U3rf!9qplHk#_;hVY7|M-dTUg&`)9+sn&eHBVpE zM}?qygtr$zutjZVXm*Cpik6t~Oc7U~Wb*L;XGu`WD(?Ss6e6GrjORos)?-(@dLFES zu3ghKs9)Z#XdabQ4?o-=ZQH{(5gt_i3^f%WD|T;(TfK&WWcV&s+pGR0ucE`4pwjVUm+Hww;dPFbG4~hOm%w>pX2iKbtNx zg1Wp%FX_2dZ66$ji8DU5*`Mp5ReLp?q!()@df0Ss?ZcMt2cvXX_jDOO>Q>nF9{8ZN zEH3~Q??>^x{5HU7bS~^+!^Q7vF5c3)?N~H(m;{Lf+!s zbHcS4X6HQ&z!ztD^PFA(KMP=16_nm5`Qr5*8(z>atY@}P(Z++Iry_sR!}l@=uR|m= zdLAUI$y~X3$JRQXsVB8js-J0a{&1v7%n#tTd`{4>SNpBp)+8J+J|^#df&U>Z4jAO& z0&L2<>cQy8hQ7vX327Hm;%+}xJR4qR6pO!9GQgUm7A1|$$+rl6n^jAb4sh>cEU;;5 z-{N=S1K-!afv&XF`)W`(?o}wh$?r$JP4cuL{|{b+QDCRqEQ%N~>N=1cM+jfugbyoM zq`VL|5ZCR?Xnrz{TL^~tJqRrGIR+zZ z<4J9ox4AmiY~Nzt>@6m&%SqU{$$6+UyF@ALw$XQbZ4{3c3NLW z$tNRfDV%_zPqnR0_63<1gfDAvdXK*NA`6;mC$%1POdjKCE}6u*o?AeE@H zui6|^pS#eO{X0J9G+C*%3%chRBY}_adZqaD4O;yl`!@+Sb5ILx^ zZ19h-IKT<}D|Zc}=bqndP}+F0=RR!zl<1IN3>3VdloP_gDw9!RI<7cA%BTL4-(CYF zp~Wd30aRegbGF}$-XUuO0N#p$p`9;rz@vO;INydXu0Pn?J6-9@ zMJ6`>-!+Q!rN52uHLe_W+_}^^rjqJ16@;nl_Wd|Pe0-C`fEgdQ^=~cms5xIf0w*#; zJgsgbiARL}?_~f_on?T1+W9=xyDjwkx2k4aJMLy_ZfoRO(ftX%=##6{$Gaf_GHn=t z^cAQ}i-~>cJjt6LN@l;$5pOWsRMETnCobZ?fI4MrDkbB1jO-wANe`DXIG8+(zW-(w zQa3mj3t6r#@ba!v+{xS1d^H-2*cf2~%wT;P`@mte`BL>YO7uR!l@mID^QD>qtEA9F z272h#D$Vw-tp^b8_iJ1({xbQ+y5T3ixvI8p(!WE)JUutJ_xpEp6@ea!OjC1PFLZgu zYpU}M4okakJt+rHGyL0hOL{6?m-kjS2E8@!)dX6Lp8*@=9!;N(Y7W(l7;*6H#%;LD z@S*OF0_Fnd*{{^C&cj?)#Y=2@Mep}Wk1y*<0;m9IobVbLM))OiFJ?yMUcS02olmk( z=o(#pllx)yYU7LahBClTY{|mOvF(gZ5;36j&8NN>91FVn2@saDv;B?}F(@zh$gz}p zrB)cPR)QRb-YVUi5rAvyjJxE`@yxTUO zykh+COFilIYqs%6shJgTYFpP@0R^RyfU7l8w-~z`?sg6J!?3hWb{E*;7O`n&8Ul96 zy!?VHOInQo<=6TdIybH>S=osB@ukzX*URpI1mS|zIO0dr%q}Yl;t-e@BjIvan!UdQ zs-%2bOEQ3xfqC(>d#U+@#UBz6A=_7X9{?^HAeNQ8b68*eTL#<`$I< z9~0a7Wt9z0=O0Y^2H-5#bbU`r&;u^yb7p$Bc(1ipy4d8c3usL3m9)JWAQAK9yC)rE zD*eyo9ur_OpMA@b-h&Vp(Q<1b*{v%X(Y@aZua#1?un;rQlQA}|m#ZhF5IC#kV8vv0 zAwlS9Ic>s5uW(Iut$k$T>QniD)k_DFMDcTL;-Z)>BQy7kud@%Y+NLmP1-jtFqG{gu*Wqe?jI%h`m6Ebw^rN0 zU}4|2(Ny8?|L$;|Lxy+QaTl%BoGvMzoks6E{tn$ZFA9XC=6E#E#_>QcR)|%xk7IFty9O- zifHv|tWW1rujA>PnknF4=@;Cp&O0db^k^yshm-vQ|R&#E@ky z$=JsmA!HC5Obo`p{$8KoIbX*g{&3E4nCI($-uL6aE~%tcA?|HQnc=H(`>m|}yLgol zAJVd+>g=3a#L?P%0#Cc)HPqFXF-+o-E1FGDCa@}nayYwc#HZaR_`D{^JMwJ(y!c{& z)INMws78@@&reZFRbhQjHtEOI))u;lsFUuh^E|gmSSq+@ZG&_c{Dew%(nOw3ffE7o9|`;``CZtq_BTy`ni zG-oy4`IHcnAk`J(=@${9Ts%sDZ~$7atR;|34^!O~u)uqRkM|px>O%*y{m?z^K6bHy zN(ecvNZ9(_0;~)#a#c6zD!EbBYrC^Nzli@@Sqtm-EeN3=*o^&EzG0LIHE*EB^rMXNk|;Im!wS{w~j&?g-xnH_Fn7qO`%( zSdeT;Nl}SdYg6GUA#jd&rJ+4nujy0fEQEj|`frCV84^)~jr=}mQSjmloPfL{6D$_^Pla^2ckU(QzI8ygNV^O_|4O{7^ z+Ra=k@hw_4`7l?r*AP8$XbpSC`n;dW{x$&DtOOj-?LvCaF#Ey zD@aZ}9PBv9vjcauldY`|k2%lN@Z{sOwXuh8&kLMI$|s<=0ty@0(i;;?1m8@^Eqqg% z;mk3+yDXTkQ{)DSR2PqOxIvyyKIZ2z?`}vk5T_c7FaJ=HHmA(HeCe(V0?wAK(mwHE za||~<*2PM3W#Z$}%2vrOId4r9*HB$i$=x&WixbJ9W|7?VW2Y-1?3$&Ia0ra6T!#{G zLOD%eR}am@0f#_@G>7Np<(`|G-7tIina|#lZ+fY*;5aba>Nx&u1Kz$^x<7eXFfPs( zlZMu=Dq@Od+?)C#9fb46WeDDW+owMPw8q7UT5HWJNv&9*e^u)4@x%}^lB8T9FxS)z zri>AI{$Ga781@+g+#S=7`c|Lkw^itmd#xQ1NvO`!8K!2@kizAaUCZYt*>PPe|%%{kplG6bHE>2*Z>D(D;^d3*EX7Hd7FEBBbkTP3$6_dA{y(1S}d== zjyF%bP7kUvK~CF{%<8_=8+yjI8>X*p#Qnphe)UwMWPFxcp9w)!A+rf6;~MlM`^3*s zz(}7V?~1xX(|bJg&Yv5h3y1*v+`m%?Pr(K=%~!-o9XG=$W3QE2)SFp6_71-<+Dh9X zlFOV_OJ_#S_!UQ`9s(#1*CJz?L{@@9F~R1ZFDV38(B>{?wb{hfwgT4~9~l`yhr-xB z`>ZrjeO1e3H!+;pIL;TMf9ss1ZYq3F*^c{4XAZ#hG@cweKV`_t|GK5f^cbW8!%aXa z`L2Qa^gOS`P`qg33^fG%PT8HOaEHc&z~8$dH}2l*NUx5&Uj}^z`eG|yAPeDJF*f@4 z>Wbwzx?8awwUj;W9qBVM*Jp>nWGp`qcdPSmoAmq8WAsZYzMJnY1hrr0a$9oKW2;9tcbLc~17 z5Xx}7h1ZrQ1_}f{sTDh}K44W0P`*3yHWd~ZkFqD%R)~Jk3h(-9IkCSnyMJrO@fTnf z`k`-DTu=b!8yAFGzwo!>Vn`@y+H5+kb%{&MTz53G?Ti8jK7k9Or5rcS=5O}g#WnC3 zKif>0k$)}F-K}_c`I&SPwDj7Cgaosl8U2OJ?Vb+rBIT&@{gdLeiD=HD5RCO6zMv;U#$sozI=tLAp|Ik{EqSP-7~%E&*7=20(cn$QyO@?e9JbyuHTzQ*2o!N#G!k zbUF7RJ-0R(7lMjD_H?+Uxjc?OUfb#Ee%}Sr^lfZtXs{eEsBf529`Wl6QLqWZ1mS`! zA5uT^Jvka^AWl2vju67bmE8Ku$wOpvh6tcUwo=s_50L7|OlH*FCF)HFW{g3Zfxftd zElz{g!CpebZD_!GSRwpu?HSCW+)BbJl+-={qzr5;u4!jJF;igN1X%5TeVv}LXby7_ z)4~m8L39v`txW!0X};xgV*q@(i4FRS(Fmj7xmdZnM{ zPvCUm)5RCnH&M-Y#2QTqi{3|VW_Y8lw2nN&`c|y3RW{IC0y8~+hplgT_4F?nKgx*? zui&O~#RCoFdu>ZJ;@c?O((eR_9Mu!LEFj`-%6|nsH(pKC(0*qBCLJpxt0~vQ;(D>YZhJd13rX~!XvN}K^e5%PEEm?=SlaH73+@k3;Qe9zlvLaQ!lFos&@Hh2xq`UrXXPb} zT@y68+GCve=|fsq{GP4?2yQv7$=nC944F{mCK4*}7YhkNfY>v%NL|aVsFp&p+Q7X=RS}?`|hsxQ6RWy|Ax{ zu(U*23|-MGavc6;_WMh?!3bDET=0hrA4yqyblntdMQ6d75+UDD6PK}EJ_Ni@?vVT+ zCOK|CY8-^x!cr^XzJI%klp=wG4<`?@6@v4F$Lztpqcr5+ua!1hqP)W|p+l|DD`nm$ z8{@9Lv$Or@<$WCs`EGxzt-X8(fK#sY;U@!Mir$|p(|iG@=%RlxS5b>>5WKz8`%LC5 zx3aL=ytQY8j1GA?gjC3q$`(vjj%j(^w z#iNcbm1Xy={P^+43+{3EhqgxSNLNn;No`kn=A%vKL z2$=V*aFT{1SCBOm%D&b2-Vn{i%C8F2c_S+j(w-s@ z=e}J$Je6POnWt|RrqM)y@OMavB0?x5B_0+AE5@H6olj%{V>aN^Q1n;XjCgjHnOXK~ z8RShXo>sJ2HFU4$a^;o|KR`3dI0fn{!>Bz>^ucMt`=$!Dm+jZc16gR`Gx{iy3fR0a#Nl${z zCd|$OB;b_ulN!luCIwOiKHZSXCOPkR6on}~Ey1q=UtPvPiYm}Dw#bf8h3edX<JtlZ7yBAC2MYtOOjJ@$&0Y123_~>|{g(S2k5InwwvHRQGF4Bkrm@G` zSZjB^MA$4aY5Xb1axh}z)2;I>7Fsi1Wj1$Um2E{l>5$Vh1wuJbjVVD@fd7vL84#0Z z`kg9ALOZXJtUn=zEkt8XmR>-Xn<^1Fc?1}tp6HtdNE(;hrX05Wgbx zYHF^5Q?E0m(PYy64I0H*~f&SW3WzxL+hL*OIE6(^&DXj>EK7rLDE1 z2*?9*1Rpi_zd#kBG-8u)K{2cMyZ5~FnYBjpOK8PW@P%OP#So3K2d4(t>H*L?M=YX0 z2OlXQ^N??50CJtXohDuxn=74^N)r*tE*#IKd;9AYC#oAV!qEq`laCo?-l`=h?)D2% zviA6=6g{%|$xotS6!@hyeIIE$jhqN2{*mXPPteIT#m4++UsX#|fyXmSXmCCL4s~3F zhY)LEOF9&xH8PI>7{h|1UI8hb5DY3xl%OtF1Xf`6 zti%n_WU4AEb-t%2JvWqs$L_qpN*&wQF+`@gYMXV7PF;#O;^heyh;FgH56r~;+a)@= zg7(!N>i+OA`0IQJwYQ(>qjN{Q+QjugLTRCJJ#A2Qyv3*jO-#&tsq6dP3Z5JYNSA|3 z%XRPjT{2=x<-p~`(69z=W=1&X{Y>QypzXVrVktnCfjZYl#(##oRkKJBHZ*z@dG~^2 zz#ouviYpKo5V!K3BwMU>Kq^K$ZYjo}ukbHEWFtRJ7!}2z!A@RB@ z07}WGeqZTH007(a#Den7fI>=Y9WGPdYFS*HfoN%fU@2N6{d?$RCMQUF{U=D0ax`&& zu9w#zZ&d>HxK~$SPE|tvv?|Q*I62EeD=W`_hZhrKtC|d*tekt7_HUVBiTim*X)Zl# z7t1`+q~go5kgtK{UiQnJ%l+uK!^NHQ!>!_CU{PR8+;u`JShY~U%I%TJqeq577zIc{ z0n0w&$E%Up?Xd|KgHUD>TGTCUHLoj?b{&8d~F4x9Df< zFi~xrC#xPp0=qz42*^g%ZUVBqkO)6rg+s6}6CaI9Qf&pyk2nd?>vw>2si*Ud+$kTn z`^(xJrKHp*bJfKi#`&f}<6^KbLP)1Us}28)oRKkyoT10v#(A_7{JbAGSwHLnceFw|{7o*qqT+~?frK2w z=*1+@`Ss~$$NOJ#iac(;Rdt;>YEqu!=(t=e4~C<;~lx7S~0R7=loN> z6Z?C@(ABp*Jjj&hQ+uKM>Y+Q#5i)vLOX_9&!+u;5yBgOH;kNDEVq&~A{``w55&vs* zKGLPe|BX?*eH~NmM`)6=VMDw$r!P}q8oKOGzTn8XOjf#*HyBj@t^c0hdoK^(Px#EC zRmGM3d%AN?Lb-mpYBXwGToTNOw^IL1vPPg}*$~Qw62Ogk=D9AY;FEj$r`*)47&Xu2 zk6^#pXNGSWxI)91^d}P zaJLNNB_U%DZCHMIW=eU|efVif1);ei+byVn?`^wD-uQpqUs{px9OD^d>odQS6gjS` z+iQHc?t$v_S3Fs0yj}8%6jpPS0JJWeBi&L;<87_(Dxqy9L`y3-8R70lUW58|VWs-1 z(KeoGhmd7K9Vsj;pK~FGnZg?Az{Xnwt_7-8nw4v1QVPxw~#;MYx-^M*PxuZ+XdQm+17>-}?AOgDA8J7*uzsWP$73bd+`!_@y$)RN*& z7gE^8``qB&X!Vjs*9-qiry$2nJZSn{1!W#4^AA~O`|4quXj{7MqPA}Od=UCNMx2Cv!rg^jf@ik6KA zS-p}rB|N&T4K5ALc7gndJ20Pa<^~2=t6R>@zB*Du%Hvagxt7Fu6tM0(8B1ZLn`xXW zU5;*cmEoK;GYu|e)_Y&lh-CCz%5@fO z-R6>}u3xOr)Nk2Ygdps1x!q+%F$PT;qeM%s58>dq-!{TIG*P?CZZ4)6pO9y>Z|->% z*oo)J)dH>Ft-#77#6@d=?{T9T-OO+onDzvD1#=ggz&b8z>3D&O3p5F?jzXc zIuJnG2fXC-UW2;;e*B`RucQ!IzB_tc?#3STd*=8haHIuCMVV)-P<(0(^9}9`J6uX2 z-SfbfbVszHG#l@~6E`Q*Fz^8Ht`H)U4(Covc^jWg*Vh)_(zjT>nZGfxTq0*5U1OW0 zyANSW06mQ$zqCQx@Ejfao%mV>_V?+RWMb>^9p@`!86^|Rz_%WE$1!+!9&DUOljRD? zO`8%qt0jGp3eE9+1Y2Xes;?S25{ky*5?$ARdK`@2ye6!*KIRB^LEJr=tcz6Pc9tHo zNS-X|d+SOrUGX86Fchmqrn{|YxB>n8qc|F#Na?|eO&tTU3AR?2I0=|u<`LAkbJ3*3 z%V4T=KTMuM&ca!Wx9!|59y9-%O}Ak;f}P;;)tC18v)B$Dyk`22IfL*#xS&iTtEYuw&nG!gr(bTTDhlKDHZawRY75E($)Iv$uf z-@Ln0SkLy9nffVQLw`L*+r-sss&VAGB0K-=%$)z)V52TH5Et8%n>uYDjx;sX z5BK(Vvk6pLG0HLf(c(`J{Sd#Wf2(iY>3OV5vPmf`=vfVPS^1;2dsmkf=3_`WsgTra zph3w39lEhh2^RieOjKJJ`)<-TT$%!u=K|stc)^(I;$BlxrA0K5Dk5Bo3C3xfn80V7 zd~pc67+wPw1d3`@z9$|ED1a$VO9GAVz0$GSPDu;)>U5&Yof05C&s}`V)rFR)i>6>1 z{C0@9tV$6^Q7-<+c@Nw3;X+rMQC8mP{(rRXs(Zgp9z&1mn3+)K0BDAZBDPk~&U(L+ z*xH1|)c1y1(rH-%y3H(?K!rjp0<07qPOYuMR4Q|KcTuX3m1O`dMBKmgm}NfLiq*~c zPl_g3Nawr4wDm0n6wyrqte1nh)j7gjEahKWaVf1dC-iO|$nHvf8~J`g2THHzjjuI- z>8lzN3^_4?E?9Nyl}qG8=dYJ^F*$9X)Qh8sS_ zHrO+nO>bu=3V-%K&XQ1oo>e5&)U#1I!ZQRL@Eo4$^0HVEB|$&06g4iGO$LzOmH>nL zBZLzBG_SHof|z15Ydvy>;k&ImG%bzM#Iu*8vgzF4BwfsRo)SAR_C*Ze;&5;3?9{%* zprsqg4L~WkSvY^nP~3j_a+K%yH!Im1^2OPnc#7qn-d5`&=;imEsP(-+N87Ve*@8S# zK5m}5B0B$6%Ehs$!^pM*eWKs-_EtjGexvPZzK4HQm~yA`p?SEcC?mnhdWAomeF8uY zWv2HK6EeTb;V*vo75~mRVDCSDU`);UVk5ki&V`ka1|mxwk&L=X?(q!Is4-p$!f%{1 zs9D{eo~C!$j`?FL?E9TVB`WCWA!cK;^LYBQ7_~a(T%85S`RVd^f8`$?|Ca%{9oyRz zm!U%}Ag%#wkVRm{iEQps3T$G?bYSKSKr_;xHpZUVBd4e=+c7SU z9M6oKx#*6v%C00SESuw*9=78>a@IL-Fchra@Hj zlmbzOh3j5YfrWYBYrXVOl~s!q9<#DP?mNN@4j)uJ!bhC5F~)+mM*Y>{sc+?(?&Y4m5G+fI~CrC4~h?c8Jng*sPRX^NGgZ|$G^&y@Q>OCl9CvI z+-#Qu-OV9I_QuHVc8CKy3#ULm71p%~O6peE4ULHShwA2rVZZ-eYsi5L_S?Q*X5#NY z()vsu4dseygmF{wZ?6sXv?6!AK~Kd6M3=vrR&FX1o`Vvl3{LIM%rMrqDY8IdAe8UQ zVZXpi8{k1Q0dptI50ItU-e%;QSWjocBtAP1eWlBGn-8*3rl-~-&N$WA<~Kq&%7EJ{ z_`d@jo8z-tHoiv8eLl#oNgY1mNdQ(L@N?K8+5_XdQ|)Gy^2)q+mFwnS8QszNiMGpj zwLXLqVC-}NI$hL_KM81vlG-ng^Hvs)u-?Dr+kHcQKV-dL-a9(d&~TC$k4FuaUH-A? z&<%}+-JiOJU^u9~u{*|d)<8ldFE36>-Xy)jeP+|IozY*Ko0Yienwo_fwxUj2nimGg zznK<}Zyc@2yvZmj5$K+IrhI3}12Yq`H`W(8UxDAB-Gvs7<{XmdbBvXL7eOXGR}Bm$ zGRMvAyv)VQH>Yr0$1}(1o`*!n?;+vgx1h){&97%Ka~$U8JA=+oKD=L>ndpP3=6GQ~ ziPy~GK6^<4CD)Z*gJ6}Lf2KS3H-kI2OAF(A&U=VT0P3u*O{p#X`27*E6Q=+e54L1i z(}EKbKV|pJJk0aceWOk{<(M360$QwPR`2|wevyB7YT?*0nzVP88`F6{SVdlMgqm=a zw}nea?5>vpBo-d7e+H5`34=E+pi*m)xTf=yNA2Z&`I7>hza5qF^JIX>jg`~bY?sME6}ZHZAFout zA-XB%fsrgg%}RFRz5m2zMBr&*Uwn4pWJSkj+k0T~Qh$#6UiHQ#fbk5&bbR}^STF=_ z!ZPXAG~fY1t`S&vI82 zDT?AteG`&XLcTSl?S*bd=^UE-Vfw$(iYc-8U5VCkVVM zAJM`NC*SAdYU)v@#IX<=Mfq>pWukB+GqXJ5*n6b`Yd0vCxBub8k$R3pHVD9_!w7!{ zl6?76+fti9S}2(Tzgo4mF<2F#nM|wy?hvPt+};Q3_Iabsj}Is2m09I@a_b};!?@mJ z5n3++an!WvCWhwU?GRlb&R)&Do9@ytPwY327z@t+d8X%g4w&oyGvrn~Q&OIA?WwKyb z6M;w_+fk8;hS@yCQwqLX2E3@Iv9@SV{_aKGqxkeOA1O{$x@8m66IC;qveBwQ1}8tB_Z_l-X-i=4(@FWw49pD1Gy&VNL{V<2wA15gT{UuTub?=ffPcgNYLsdx;OW%`|!dL z`!exISW8I2<%{)mV7OU6F_SEb2_T;Y8Vqz_Y%N{j&%=u^MjS2yD#^~gp{iMHTPS(^ z{E&3^hn*yrQr!a#jr>iJY>^g(xPSQzXD8kfWMaedPx&?srlGmnUqK}!eLige=J!<( z%v#pnSK-B{XBJFSU1Pv)rSs%Oth}5M*9|oopK*G?K{}aIl$@w%bhnY~pY46#nrr{l zWj~JRVy5#ngC}ZtCjobmv6RaA>9nJAP#$L=P9iTCs>IjHmc<*zf7om_R67od4o@$G z2?qd)3Y>w|(azL?N5lG)%a-5;U;MPo$Th|9`3E$zZ1OyQD=KAG-^lP z7J!~c?PS}&h{2&_A8sd+dI;=of$&sU-(wZK6|Pd_o_6V44Qpp&XMDZ^`3&po zskm`2776|j0l@@!GTq+WfF3s*(SPqO-yM&XEXCn+#f>FxP9FR z>XW>lD4p@&p`-E>Sma=ybY;y0NUkG&>it*J<`(-vqljcd3{Q;P& zHjcrm6Y1__dDSTvzk{=k<3ZGJQ&MQY1CsV8~GsC-!sJuLSTFnbpDJRa}r7X zY>S81<)MF>HcnN!(&EtlkRFbFln5?&--D`O#5f)%TwsCp_f?pm!S}|15t%zNCu3NC zz`^NarxtOR>%Ucf-+DUG&P%pxUl=rk9t*UplO?VP7&jN{F>_x-&=HKw!#3L!1^MWt z9^^{lL_c5^;%&J^MoqbD4x>!Xa0a7{OP z32I>K@^5Eg#t(g!H%+fS@PS;hpgXe&%Gj-14ky6#EdE9ApTg_EWT>eTU7&a;iEoEf zqUd`Z4xK@eFiB6qTj=9~p^7~`U;r(TgdxNBZI3}fW6&20{2j^JjDL!v`$D&48k@n6 z!QO98g7)?}x}lEwX*AzHQY}jv?&E{4`BpN-^&4ayi@6Sx_baQbn!M#!T}`udd9jec zjhn54I@OwhoClWzvzt~4+dEoZ#LkBY8yXm<%hXiP^8Ys#Y?mWk?D3w>&W3PPB0oT}9T(=D&Ib*MRSPDCGNphpuKa0vaP{(`jF0UbqxrE-#^)#tpR< zn2;vWFh-@zz?uhJX_TK(=k4?S;VF);7@N ztLz;|xUsQihl^E7*ekEjpyYe44fi3P{)%a`nrG#{zA3z2pl} zuFGSM1;bi#W1v!b`F5uXy<7LV=wB~KL_O%vv3fVBA${x`9CadC|98^DA$+Mfr}OYu z=gw*Lp|^d3>g(DuX0PZ2KwBVowTImye0h8D=9`~3M&X4wC@%&sft|sHwtL(RjrxK~ z4HYz=H8ll5cC&c?R&ElPD-$w{B(C*5Gje@hQ>g{M+5foY@J;Q%&D-|_ z=T3b%;6-lkd5@CP{*W%V4uvyz06AcIP*8nybSeR`ka5%X%^?F1w@OG61aENwz#hgP z(Uz+gc`$pQ|3ivS^$D5h^0T(7XUdbj2Qz}V4236V1VXH0ta%-)C=|mH9`a`O9Rc}O; zPY8tnzMaS?W@si%qtO!B%p862UPgLo{9;+`af9;ci*#Is_D!dtfLHMo|2q(b(#Kd3X=eF4V)$J-fioAZ%$AN+9&gxH0H zyArG_e+)PfEcq@K#+AWw9Eh;dSLwPyH;l>`5OqT-9)RBwLMLS5y2$G52GG}V-5-l8 zFcJ5`M7#nrz-)ThaY9DNM95{k!&6DrdBR-XmQ*P%>6S6GoFM{oe9j-g_9z*GSQz2w zKL)%YBNEg+iI9lITJmh}MIqqb%C{ug7RS)BQgolj#F*z7**T-G)e^=XWJ_a?$44Nq zbHm^~d&dDWQQuB0(@~d~4mm!Zk`@nsC9u78q%Pe)2Jz;n())KDmeAwLjQ49xE#UKaHz+xPg=FBP zsIYKT*5*ZwI*b{l^+sj0B3gPMb|BWe+h!p}HsCQ&U!V4g4^wewaxyUBfhV0&s;x&Gj25tKWq?Ahk^wOOtJ6`2Uc zWv;2@rwD!T>0@|^f_rK>Qs)a>g9SX=blfpl7S)+W3ct zzMh?t!|U32#rXaUk?9B||0R#AwAold1W)M&0KX90x^DWhXJB?IU;Ic@Ya{{Zf#Ig3 z=?aL7>aeL3mBnx3aNLEeq5u7x3U3&jnCN3(x&W9$S3~yF>?60_t?uuMMWh#Ej1-S%-z$NU*N;P;=Ip*g8hrPm5wM2LS9-L z;)zHEr&`%KyOS;`o%pt^Znc}VGFa~9*kpA`O#Dn?cp$1jY@M{<+mfAI3M^A~^`E;w z(sfFQH`$%W@tpa{6veBX&}vBv8kU(Ns?DdM6~=;B5lzKsF zMf&)&5l#;wfYpxuq z${{wz?|vO|y$u&kLe2#uQ-0IjwFJ*JM3w?gL+9=8a!ucWfZsABe)WyIfPI7Zg*p@H z9b&p=-%BK3+r;K?%Xn*@fdH6I8+hPPgRAjV0zD?sgTM;z*w-di8$R6RMp%^`H?qxbz9ftXBe98bBzIwixaEn zbm;Vz%;aN}Yau6lw(o{N0aQ?;Uxv$ilLy4boZjdTVkCvwtknbj)Jx^XzdR=gEwQd!g`vmmSl? z#D5XhL367f_qa3hffMWEqd>YWYC8&T4P?Wcuf}!1=YoD%IPC>C998o4Uhytn^dtbM z6xwt8gphDi5OQ(Mj$Iy@NWLGZJ@MzA+Z(hoUp(VkSiR!6FeKXc8PJ`i|06^p}83gEtMn4iLz@b=YX@1uaLek6+0JdWe)OuaD^R5wyN;Cay z9oc8DDS5S>i{~;+|5%($kO4k1arKm)=jm{?73Xyx#$T8)_KnVHF?kd$RpI* zRe7*0dJxSY?>R_IpIqVK_xKRrYgo4d#{P;8ldqSJ&7W@N~6uC5q0 zrSS=Ejt@4uMFIcN?-$p__z*o86qujY)6RA1y7<%8^aWtHHa4M112O8R#gx^eWrnLI zJiq_sQG-#l!ap$P{AE-ZrAUl9y&<@dPmhA|{R@7bNC`1Yb*2`EQ?ju>lP%oZ1Uvwz zy*)I+k2K3Da!daBoNp{mtm<+E+@72dl8R6rVVOoxx-J9Vqs50n=>OTuYjyAkl#F&- zJdE|<5gE}bSg|(XX4-EX`O$wWyJqo zy(i=eiK$nbRB5|)^9MqtiwsigMGT9euhU%wQ{mtjf?yC7Yu}S`(`pW#KN2SU?oMg= z&SU4+YI$vUphlmB2c)%@!8l7Z_3f^U>ZkKL5n5$N1$Z58=ygd{Oy%y1#gfEIV_m%j zDpG4xZ391X;1D+cg^RYEQZvsIfy8*`&Tx8G1H6YCw7J{R^%tL+!|SamV$;9w;GO|B zM_-Tep20QohUe)FP5CvGuZfDK`tt$2jHO^$?homV;5Xg2!|c|B%A=)Ivw4F00y`n{ z2G76FKOYoFPst+1QY!Oj1$ByYYOZrXB&hQfG|SMLK(#eJwb|QyyfZfTOqo((3P=V9 z)y{~6)w|YvH^#z?dC#&Ay^Q|Sgg00?0FhhP57#x*g>^5F9xc!q&28#dAa)@ohj#aF zGvrr#Pyok?f9IDtoV`zHycc5?4>3#HSK7%-eI zlma}|IyN5vi{^#Mr7iaF&q%MlA8yV2ZXD%`TaG2OaZX62ntbTM{jAL>2(w{v;$ zs568(=Y2k-1a!6z;=Ci5=Kx#Yh}uc{WzT1>#t%wr3hvGGGXt+vck>rc4t!)<1BvE# z&DOT#v;UU`FzLF$+bi@hL?6~UMD6r0_w-a*yxEvE5uLmz^OBMB_~JYqIG|8t&rGv{ z$06OHqYbp6C?UB8=Bmg+YRVsRHQSW^A^3n*^C}8-C;jahvN>Nv2N6*8m$JG42h7Xj zmO$SuWFhce`{K9%D8Q%t(cavt#=UAb*KvlPhJKZm9ZFjDQz$YZmT4}Qxg)l_6E=f} zsF4$1#KOa;Z2caQzzIMoj>H->LMN&n;X?7(>8;qTqQZi>p&kfpQhM3&-1&oyP~!jurzV zeh=jVqG_wJlP=_(bQ&OBKvXy7Y>fX(cmPM4p*Ph!5Q(t}x*g_Mnyjx+QeO%zC=d$e zu$+ibtTC3XFVPkHWM!T`HG4ocSSS#$JWA7(Hp#|>GccU1WdVV!vou)K;L#VFN$~5) zOp{8_TSBEzDx+`TfW>sxt^>Hf=Zb|XB3NKIj})olnpyMKaCB5;!piztX~3s7+p5N& zWlyX{bgZXGoa&*w1p*wNpPYqUtp4ggcG>sCu<^?OXoMC7BbQ^#H-p4L88VyGMa2D9 zuZ?}zn#|9$oG*ume$!TD4u1VjTlnd!!b9PMr)cY5phm?!G1aNJtl__MA0neKP^!Ua z)Ia8ILb}8Dtf3tYAZaV$k^9?&A1FO_b!=7S2VPmU3-IcvPXL*jY*EOW%cf$S!fv7tdPkpUcf(T)gmX^Cj5L zmuX!9_VS9hH}LtNN{gxG?%8?Xk>veR)lL;II^YNO@?`(x+MuK;-g)UpiU=a$m&X3B ztOK&$sHQm?pkY5UR_*)&M*#Yz{}LH$xztpYE{_^UiIt%{Q;!$I$eWWM?kR#!qAQN_ zs>+JEq_aPNxU#EPAkkbc_(OQa)l>eosY@#`fC%Zw9A9$ zj-B$$!^`~{x8hG$VZ z<E>d_ys>>|=_o>8qjSF4kwo!6PV+W%SKc2K$agWEjBM;@L=pVV!%)|;S` zx!!jY9~KdS^XR%H=4@?;h49;>rQQE9IXG(f;nj%4I=tqS)%TVXY;g~QRtLLnygO!E zyz0L}=#t%vTUzI3;T!v5X{!VGM!D(;?6~8@g-ai)Jdo5Cp4Ki66}X}fGrx6Bj(fIt zMJu-ac;zB40g#Ii&DSO|rON=OlIR8sP=y8^Uwl^#{tDldWzGj@Dbt-7gUO@UGx1jz z0(<<70;3vcbzh0!*SA4~r(B+@YE+tkbr9~v>dsLweG6WwV%2fq|m&U1nsf9+i z{3Drmn~3>wcVvn&8D9e4TFO7Q`xHB4Jt93jMjSmaqIb3=?T=@Hjx`7xzuhgsui%!x zlHwg*n#J)7R5*1by|cUVZ8b~K??XG>&VfBdD@Sj!V}^1API?V)zH zX2nM9R!g($)e^l4nPZDZhEii*U-7TfKYl4ZN=tJ3)l}oX?A7*=`l?sH@DQ0Xmf6pU z{?q_|*)%gs716@ZjBgoY@ocjO2v&To3B0G|haVjQ_P)O98xb(?d&4^a;&pTA>l2Zw z$7M?V2l5{!$KX(P+udQNQ*Sw`gNnmCS<6W3v_$Z=wXfu#Vr+;+-uUdVB_Vsi(PQ|P z`Oc%qUYOV@^Azh3-sb_z{5mGD#YgVt#~zLZHP}fo!Uo3eEkQ9bqqkujBApPY>A<1h z@j(6U4mDT){aA~Qa6v{4<41OjgA{w$Y+XwsG$Z!c1;st;PP@C)U$%q}U10r#5%L8` z5MywLrDq02z}VJ%sykfF$oo+K!s-e zE;hLr9P-xhbkq`eo|gsk$EPx57$#-{Ff)t-yhWpu1^()KdVH_+tdTxa{eKBSk}+w? z(O0$8ciHt>+lVWoW~2f2u5WoKpfV5ln2$#_s&VGIt&ieZsJ%obGEbQI$1|Bc)T`jF z-}k2OFd|JEcDYW&QvtC<(I@DnABHc9?za+LGVBE%S3;HkscEjEZ`I(l(Cgz~|dbCC&J#Q}SGJRb`mp?$O@*JI|%=o<1vIyAK6=Wjfi> zrvQRX$4 zi*B9^%#X72w>%i~d2}G5`@Fex=asB*NVKX$Eve8R6BsP5v<4^5Q4wxcb#eNV4%~Y9 zMKkXtwa-@H>S~x^Ns-S*#V@Wq`>guN77hQ+KbT5khjEyh-JrF<{Acu0!exp25t4yntEFQQZL0%fdIbCBjw zzgtHxWA{f~=g=LMvLXP^^nB$Z-=f7rl#}2wubWhq z*^B7>u_48=d%v;eyjsy4QFCp0GGAyR{QD z9nh>CEZKy7%y*|WYz|p@Z{bP>tJJfZ(faAW; zeLwH(dOVixBfiexOUY^#{QCii{_^qE-4^{rM3zPay)hY~9$^Slmo%ZJ0rA?W(3Yo& zhCq70#RG8OU_dAPqLsj$N~_n01Z&X<&|k|a72x59Taxd^{n6pq08TnJfmdz_necIE z#KC%~`S!w9g0yxg(x~J}-qff3dK_Pwhdzau;yB)oYh}&vtgzm$wnjfe{YYJ@2(BPTg6A zY%uF&R*%j%bdL7vn5_jZ93_#jjuYGwJ_4+qQWmtP`f5Urb! z5xE`p{V>i-XWd+3SA1^N{+C~}Ntlv#?z+k8^og6=rgmk|%>JN0WREGm0Sqk$J=>*s zS)-V=_^c}^hS9kZ7&$SOVio#V$Vj_k`Moe}H}PWnp;x=x zhQEi(aKDh_0ge0L0u91)rb8q#&+`Zs@djyyl8x5l?o@70;R$T@42ldqbo)=})WFlW z4c%6H#_Fa`G7Q+tLy%Bu4yma)CZtj(R%Tt?|-~pT8Mk zAoD}|Sih)V;^w%18wX>(%jQzfrOAA1c1eY?Jvju#jzZE439{Ob?H;fZ`mlO2k=a-l zWI~~=SPYc^r5VV_L0DZ~aP1`=Iqztg1_ux>McuEnMUEMM`=qd_2Hg^3*A@W9>GPMn zuj0E$gD3oF?Ha|m?Bog%fM*(IGqvm1Eio*Odpg;gW_;7a0g!bzrF%>=mB))7KxOI3 zrOBTkGwX=~z$H{6Co(co)#tGmODwzH4`IX&l#h=bEGfYUs(dN-9_ON4^R1?y^<1k- z1#mJO@{Ze|84H%DPo;*aA)B~_*hYXeCkxXncMT_-{f}B*!gssD{&|@=?fRl zTCKn`=E*=;BY%uD-K-(h0X(l$?2)+R)uz^{C2x>kIn>wJ=c5=wG3^agwRxVachiJf zyI|kI;&uv~Ee6o$<&7S#t@Vfxf348V6*n5!F7cx7aheu&UWQ?em_sS$oQf&3u8Z+G zLKpP*inoi?rRf~_K7}fdAs-V|JI?vRy=pmZsr$uzedQPpBUeS43#FRGwwa$@?#XZJ z^_>=rPS>0PK4#LU-#dPYn38t$^jb8F+R>ugVKR}R;=8_@WHD8w6#f^$et$)WuPkxq z2aZ`q?8T}b0p(v#y_+;~wDAXt-47x*qKn=P_V*qi_tur2&13iT>g&4SlpVFsosg#H zm~iIy8Q+k_Hxhy!OE9I5u`)j>k6Fpi%?yT3`W@ zR=Tv^PL&ZqP2$c`qT~s|Gi-l5S*y4cFg$5Np3s+Kx}~oNo?yr{U~f=Fnw07O-zBaE8JGp15wl{e!j1^X4cdG*3Y z4r4uaP-oLoX)j! z7xT&_wzS*VS)9|)-grJdBwQMKmRwX{Gt3~L160>OKjjRynsUu`DP4aqIV$}Un0wpl z*Z#9q%0p)>jv1G>1{MHH*47%gTbijepSkP&AP7Wo%9wf_p*?=IwZoGA4mDWpv#Ih$ zF~>Q|YQq7uK4Qn{j}_J%{|W}2#=iTRt^<+T{-K~JZ*W>dsYt%@H=oUUSe~L9T3%E= z^0@tlVPf;Mj+y+ZUH2{ed(<%W&jwFr1Z285#0agG3u&pTHfXhn58v%1zNkYycfn4- z1&SQ>U(!nI+}#ZvkYY;YGEBTd7*R|tY1{zl?R)+3FGwi?qRZU{2&dL*P--hs)ZiSS zX&Y^>^_S31gOyUdKJ=7ZLLj1Ls~6^MhoUJ0~dKlM7(-PE3odafGFo2#@6pVbi%4rH8qaqP@q zUnuQbvf1RtE|5g(PTW`ivgO;zI1pO>r{wmLT4&aKDRqcP>+ILPy}NJOeD36_sGxqC z(!OhNgmhYZ2A4Hrsy(_EY$HWK)RyXM`H`+@x&k&Q_axVDpaG{2TYZ_~77^juJpI(Y z))NkC^sU_w`i-N&z=}3YyhY+ zE2_R%@M50S$QV%C{=39rFljjKjixEPme~*BBsms_GZqsQeT&O10qOeP9V3V!zumNd zlI`1{l~GZR@r}9~o6d9R3v=iFYHz>MmOKtemErsBJ--f7gx^gdfv`UO8iB>OIAbKxK8@-mNEo3%mF*CYJtsr zigoaA`A5ISzXrW^wFXbNJ9T}_Id1F1k2Iqi_oDZKrF6RAU>)M**)~|rFe9hsmgfLS zl>fI^6rJr9dc^_6qoMTX2WqD+ z^?|^#ZQE0kTxRS)t5Z%x#|V16;DGt7NH_L1Ha6D8YG2%yum8RzmaQbOK~9ns>e^b> zA_qD-SculhYg_l@i#Gfk&_03ltIzw2i+-jEyZn$JWZ*n;I9)Y^=)j4L^G;#G zQh<@sTs$6l)U*@enwjcbgI z{^)#6%{Ft57ESwM_&OTaA-d0==Z9Yp=pORZ`z122?s_rC*p}}rMINP_Yq`pw4KgbB z!B?6k@Rwa>P8D!1Zy}IE0Dy^{0ehY>Cnx8UEyf}9>D}a;m#%>dd%b`0&Ep>Kirw6L+d)?{a`t8XrIkq@U(3%iOJMkw$2EFf%n) z1?1+$A3d8w6;&z6d~22h55q1@Ed781sTe>1yfWRn>w6?;GXkM?|3l^P5~$UbKS_iT zfN#X8j9kcmOo>96^Y7WS+%3xIAL19%N`P;yd8tX#i#o(T>$djHy6+?aDk*do;fjpU zd8%Hd->Y15G@n1$TRjGqYAo`I4I9MF`JsT~I zj%k@Q=xdxPO*W*=_TRQJ_KYb$o3WVTZ@A`BM@vi`u!QnPL%r)WzBd0^US2*q>3P9j z)B2WlO#nPx@o!7~w)x=lws-~-2Ro)K)=iT!py^N>gu!1!XiHhr?%v?NM9*b{1P zVfu4r-um{u0iPG>mD_S~oX^9(Q-^3R#+P8%T)H>N;WiJT#SjCI?5e*9=^uA#Co)z& zsmT~`5@$+yJe7e7PRSzqe?;>q^t|nOWX=c7RTWX+JEeG&R0fvps>->U8De@mvL&C~ zCx@8};<69z3M+Hc?Buxk`2HQYY0fJ*64!$pU4)x+r0HW)%%==AQ@h%P++TdyI7y!X z>KFxOt_z{294i^6H=|2B6x5vGJh32~gEIAiYfsBJV>`fFzy-VrRd_^SjN=CjYSDi3 z^NjEhXS-g?VGhhXDUv-0!!i(Y$8C z(YRvwZW)8_`f>9CnB?CPEH;|clcbNflo+cWvJO5R@cgj38+f)rGE!%Y1Z zW0yMNej^Ky!T#}p)*-*btJg~(*{T<$b^jUXwNeTHceD#}Yn*A#yKVR1sz27O=ji+P z$B(Rqo#Bgp=_1{2VQ08)PR{Mo0Nt(!kNm;RH6?`NP=^ z4>|El$$LG4RO-x%ek>HENo;k^L@BKyh_qQ?y{0}#5T1V@vn`MS3Lho>QRotbCH+lN!)nq`5 zdmT*&MMml()YYk3{AOaGi}cVolE^PZ14_goQ8%qD|n0Mut&-yHp|nS?K4&OhXlB`TH4-aV7Qc z8at|yP=a|K#~|PhjgcY@LnB4U=_6mYjWdvYS}S~$2)S`(4+ZGT9ZaUeSZ^Cl)cc#a zq0(MMPaNOy-h+sOjlp69&B%wwIs(F%X;Wx2FsCQ?PTd%76}Xcsk3aLqfmeMLYAIG0 zQ{#$G>b6yn`8?5K&(@3ulTYtcdR1GXDU#>}HlE07-UTT5_>K>ytL_MDHuJbAP zgfvvU`>!0X*9~S}mVBV`Rn(F1ksycz#EcKAk-4xV6kj-0*Sg{%0zH<%sH?||0urwW z3uz2LlV5|(<8+w)4x7fZlFh&nET>^H2viaYiHwSW&nFchllJl*>~f+&$j(Mz0CwDb zy^Q-orM9*yUQ!}=w!Vm<9lf>oyCn9EXlYi!_!577W>Hbjdr1!te#C*3QlD-87Aq!p zqkNh{Oi23T8xHKg_5D=WY2Exc!bn}r@0}GOeTp{jd-WN%syzJp>7({mjGL$D`P!Pk z?gEzhVhWhKRad4@FT4EkD}XLr5@jwSlu;)KtDCox^8*6|n;AFL$KUJfgTsTvGqW5O zxrO6R^l%m2m+!xMC~H8mqJ*X`l|PY?fz#XVePHKJLXv0H8|5!j#7%IR^c_kpGc9V0@@uvG#k+Trg;)As35>~&+|rvq=T#){y>ZffL8<-_)b&eA zeBh~H@n(I-F!b35BF1F`u(d7)mnJba-cSF7Unh>)^nS>;Ng-FnJChULOg-C)LnID| zu4ya3qzUUg51gG7OBeeWZ)&4Tu5RDfSO`l&s`;*)y&=g?7M%_8-S?nh%xMgW@I1#m z^F62>*aW^tYUPN>`)X=;RQ2_d1^}jnT9%Ce$I`Uaq^hPA_ILGmw0QUF;rimu!S8>* zY9N?~c(b`cjUGHzDLJOwLK=aD4xE31Z^zU1_5V}@PhZ8A>{?4}L;*xky9qz#92NH8 zp&x!|DFfI{|3a0}4O@f_q&Rn36&up-9xyHs{0^h_6(C|YYAM4MH*wmv8L7a zTPkuwc1&e|tv)GlRF3WDt%v-Y+T-0%*&Eg4Ie?G%%{6e0zP7r zb=NEL9%;JeR#OtD?i_JwR*j-)HzQ4(9_ib;{C59;|Mx6WjY?#4#>EYFVXuN zh>>9)04OCo^10&UkAVO9pA+&1f~_X&SPG$`JMq$1Q!*s&*Q515s-%w1PhL_xisGD{ z-J@M~HOdIuMpp}umaAK7hL`oT0({o4tcI}{#dX!&+a_=TBjeZ5;H=Nud_6!A{}k&Z z1AfWOaowsrprc zN8X3L?%5Z0t&5vMQoR3iD=1y6T%u)VX8>j9C{jxd^ac)!{KiCAqWOIyH*~rRvh& zF8*Et4?cU9_o4m)pBnO|1bC7~8AvR~t&F(7K9;=p5Hfzz^vEOU`)k%zMvzXEhG5Uv zFdYme62hyvr=w2)(wJZCuR5YpcP&CaIM|rV|Axcxq8`deqUe;9b#!>jOG{ zA)c74dQ6y+Lq+!g@O!)JrRr!*t}DToT4iP7L&uONuDeN?Vq)t5mdGjoqSYh_Pp zHC^v(gl-)eRD z?AiF#?EIhz_k;G^Xn()DxX@YeW9(qMgIU1ez_G~(U6*sZT9*G+uhMd>H}j}~=r8>A z!qpRyQ=u6TZeVFU*`))pT|g(&@jrK70FA z^Ro(IehlkPmNw=<6*?IYSG(PrG!SN2e`EUx`HkQyR|CYsj}IGqrb;&taO)PTwo9{< zhdKY`*dEoidfx#9^8?=}ke7%Y^a~XDah&>w9rjDGXr%v_Xb~g(M1HNhdnQvgy9D#e zmbw&yEz8#-r34v)MUTYf2A~8%XE0Ma?JA2gD|-mJND-CwI@eVF)x)~Wp|3YhxYP$QH6gXpE6)}4 znaeQTC_P5blhxm$3SWx~l}AS&3!c=q&(%^4d1fj5!u^Oyi#oadZO<@@6|xcY9TrBx z7XVgLc4q!W8G4Yno}#^+LX^7BHBjh=!IY1fDA{HfyHDt*!ueq|l|uoy&&kPZhyRY} z{_Xliy-yheYKUDDy0<@x(lvJk_etIPRrEM<8kiTl-DxF>ptMA{Nv8hpJ(nVT_N%@k zA!dc_ zINw$B@XA5z?_6gNL$BOkDey%%Mq{xCSa{5^jC*&z=y4xvsB_#3Qvb-q%GBygFe=_^ zdB%xS+lW(i{~dMx#yr9a{fs}7=0X5|;9ilhgaQLCDOf9>V?gkS$lCqr@pttU1@nFky?tbgj4l*cVCW^Aj~X94`>Q-ikvWe&r7JqRw5x+^bs5uwGW{~dqJ*&4(F{lP}XZfPGF_F ztVGTC_z-gczo1KfgE10d_#P0_;?Q<(M24jcu}EfcZEWEqjr3EPQpH`ueyXVgftK){ z`MXm;@Z4Hr*MD43wr#f?kc7ub7E=Wepow~)DM$0``23dwJS4^5N3&}sE+rJz7eBnj zRYfH>q_*Hs-O+*B-$7p#Vj26;Zq79J`eM(Xi@^Kl^Y4-R@8|Q=!`7+3eKz?8^wj9> zM%l+R{4to-qyF*G&QIXjdCq26Gmb3NETo=TdWZYz-$OI!6c#9yK8m&p_cl_j!qH3$ z39ES4?zByylPF8^={8d$n-Z(P+}9GLhhbFuI&RB7m>8|FLuWX0-BWRDMwxin8@t_L zC)4%?MMM~zSa@8aEyEDZjgTyR$qM9&6=3cu=vvYee)fAH7`q9{tytMVCdC4Abx;b+ z_Vh2s5w0xV+%I4{hq`C_Qo{Lij)e$biX<2Mwd3?iqCStWZ1*SdaMN4n3`fK=kbP8C zRb9Qr#1U#D-|k6LRYc*+ms#lZH?dgkVJM+(6sTSH@pxhbD0@KCktoB_yx@Xa;(8_s zZnvsSLg1GxtZmd(50(bi=4wr0aQ=nXz&XWkK<#~aLCe8aGi>q52%f=*`^`T(d-OSOdrfLbUWu@Df9Q1@EedzA&JCDhSdZu~n zwlZms@uHVRyVz--p`qWa!_Iand?)kmZ-D*Cn}R=EIBVsRf6;rywAeC{>l+?=dK5y9 zn7^QtqpE@mKROwh+ULvf?KoJf>?wdavf9U|cJGiLY_(%Yf z(z$hXn0NT$!ah(&8Ktc6wNCxhZ;*I0A_M{mWeGVt>9vyILlu_qO9VTP%S`$-OA`!* zqtCp4+++ZZTK-c3zz5n~wJ*%zXe4Ebc+C>AelN;9vmDd+T=jVHd~a^1n)@;XwvYd< zI>OqpG6oct@|UZe15$~R^%ntaLxn>^PRB{(3%6oigwuC@&T1a0{pQFr`&VnzAP0Wr z$-2egY5Dak3m>VsN5NOih#8QGacTnHlvc#!habT-hFfUF_mz5&t|s|;FyNkd0Yt%r z(DEixV=;w+kG!j+1zc{LZw8is?3XuAeA)=| zifOZtoM@oG-tbwUW=bvP6#Mf-tP~OJYKe zbPHuo3N8T#Z7c}sU4T>8M?UI;gE&vG^qmoUzd|lJ6ljVnv@{oV%%gA1J+)6_iL+(% z7AKfHV_WG#gVkL7?`Ys}cQ%$?8lUy%K;l+GZw3Y zJ1JZ-{PJv}M-4>Oy;bTl!npJ2h!cN?b0 zMt&W8`S^Tq8(q(n|E_PWr?9xsr~LGmDKbvpI^>enGmO7SmgB(E?%ns(#j*`nR5LZI4|e^`0+Nj+<-#x6h2a38B)mux8Dt zlIO(pvxUHjZN9TTD&Xr)9C|9af(80^sxuE1<+?tgj%S93*x?#jtNmkaJq2J&IinwK zjo6$fJT#ZTRN^34aJJ^G7Iv~6Pv|nu1XjQ`wcw!ly?nHtJ-HEkhgP6`=K-FE-mA4X z&u7GeJ4Ii^ENXpsks`l;xxvaXtAG4+hA?7@C}MA5*L^D2AZ-8N)b^64 zpxvDU28|J)$A1n(sJ-drau&?U4sP9)suukFWhhlX;-+NCV&D9q%_*#M*v`E54R+^Q zLrcwN?V|9_gO#CHineQ-U|OtgqWGMe0+86)r>gbE=t>YPJh=VC8-LbP`n*!gSAv_* z($x;rO|4N^fc!3*OkNy6=w~5CP)6mG+I2G#NY07-ydcnJ7M7OrFa6Ui7wdkEkHcfs zVcVByQA-BuAGt`iPC$yvFojr4Y~WL^r|j(2GxbH?!QNuf6Dn4?^ z&0Es%a3;p2M7_-lMRLed{HJ69ZU}@1s@`YMP0K_mZQ}iKc9fU5+f;Sq4^}@0`sjq#oPs-x1(&;kePRI8~0vvO#Z z@3rJs@sTE(q@G5rCaH2Qv5)-a?{e4OuoW1TyS>E_S0%vVgyR03?)Pd+G4^@mV9u&? z5AcKEq$n4PYiFKc-R^7;2tZYtaMo&HGjq33qqj$cTuQ@!!ha%W$`e4)9fMDcFWRpp zKGOezgoC5t;NJA#&)B3CKZMuK@%=hpz3I>zsQS4*$%Q*6bOUkIr=9NJPjjB$tKWKI znWb$G@-=8JE3l+TaQ9Mo|6 z3qri?R0;k_Mn(y}EtO(HTQDpokmgyTAj|BV|Tm_8^53A9sCXfT^h|>|QD-M!j;!4J#D+8p~FiQs$aTHY=1jXtu7qx;=g7 zAgK!$`e9x=^Pi*J-}5@ zpf_bCJLe(AAvR%?av8D#txw%%Q8iqBG>TL#$4YCSd=-Z8>}a1--F$|}k)+P{4uVSOkD~hq z4tEwxMQp;o8{9|Ni49eTkJJ^OuKnkOwqD-UPLZzZLvue z>w6XIngvrKw)SC=9pJjR!s0XRRp<DNsHTEC`aQ7X^}|No*`ryd zSD_!85A=)eI?Z{nt+yLA=Z}r_c#$rOLBTl1Vn2m75k?WPlKY6v&Ea3y0XlPX!+%+h zo~jlPagp;D?Ve|Q$>9fhC2IYXymKlb^ZMUqcD3yaKzZtV!pfZQQ|>QQNSji#0swd| zJQgK`3a?x~tZ-$BhSN$BnCVZ)T?ET{-{2k;s#u8Mq-=zClAhO8tkd@|xJ00#=AMM? zR2c(D0oM5iuO7=6GXyU@QVIt{>N-4IlNiMVC0mGl-SvYc;{bm}M>HSrHC(6_mDyHb z?0891?YO)5y!(8oC>#jb_b<8K<@Xxe7H`HA{O#)uCVpu97x_b^pgmRX+eWo2khVXS}Q$pYV*^)D>Dp%p|l(wDUvu)k_U(tJi z)rxC6IPCVEhO9u0XmMmfO>IPy{U9uMzEpnQu}MdqjWy>u?fS^Hg=eqt*3Qc00Nvei z`PP2ev$a4)XHmQe&0>~fZ1)WaY%%L`eT2tJRKbp9{bQZTpGWZIo^3q+zCk)if$=pI z5PAG^3}wF-wV&@z&rIbIie!a;R9Ky7e8Ybe{1CGQ-01;21yRO!7GL{1W&4G*_C3hm zkKiU5AoN+?cBSvBdlHR;{rM3IthD2pUts5c3I0P-TZ*0*LTAqmkjgalFD>dCVZOw+ z)iwW5J%vU%*Iis#U1fp`zFNcl&c824yJcchRbNw`fY5?efCrQ4D#c$|DrRYpFXm7A zhoMkFQ~^J@uxl&z7HvZG_^Pcl;n!VP?J-+b??Hso7x8=>%NzEum%O@XaW7h{^T;A&T)4zTS_U*y%KXA*bFrcF#(xxTV0nixhV-^( zOB5C=v!&s$HZS?*G6i?YOKjy!uU=3{P8kGy5&iQFJZc%3F)4zhjGT}ZTL(oO1q!Sf zmCNP$xUvjmGU0PW)XChR>^#Pf#~a!x@bGs8cZZ*B0DIcLoZMoJu2~S4Mh>ua3r6AI)$cHmLzdBBjg0W|Nfh5B+*rj8WR=F9r;ngm) zy4|txz0K)u=Y}4i>k8*U6soTJXx=MLFtpQBB5UM<>X|0dUwbe%GKF7I;X0kO@sENV z!z34(nHOyYGyZJ0VOV9%-f+{S-B49u!sTEg$9FSdi2$6z@?CwQ6>!fZgK23#_PNf! zwuSmwnG{FD$fZM1-Bk+kU2Xn-7S2(D1{1+#F&vt02&G148K!xrFt#1t59mLALf4N1 zKWvkNq!m?Eloak{8#bK%mOLwpIH9WLNIbEs#QI_$i8*FEi5}E@h@|T(7q$@KKsyUk z&g${6r-m})LWv^h|22D!h|>@Tz8`CI{~ZoICr)b-4NQO+4b^MOj7Ut{-Ci}=n>6LD zs?T6P-gSF`rU{}($r8*c7y?AfmKPetm%mGR<+6yF;Rl=N0U~KZgQL@MWqoujY%#jO z)b!skgt@cXD%PaS7yl5+CV_-d)}QDN{g(cu2vESx`2{6IJf@8Fs%$rHOE7?ts8XsA zh@s_2pgu9EdrZJeS))98os1+zv(+Ic{*Fny&1mBruvFu&sNg%^ zXcB&_z(c$u$RV2mdo_=}w`{|v6|iX*S?jy($bsHpm{e-dYYX=d7?uKqRTDt=PX(j? zMd zLqVWe>Qy*r6cL^q@Kj7MF7O%zq!lwC85Jn;#xqp}&lC0VqeA`Wa1#jJr-aWYn3pwC zet5~q;R?hcSHY8~lv8F9xt%4S?Oj zUU1n7o2r{87|$Va@X#b9u+ZD7ZbARKe4dQKrB+N@%N)Q9mP^vkepr$8ENYkj6gw2u zXbH@H$c|>l$R6LxF1MOYZ|`u`^!xw==X)dB?{1!^7lrR=N9^!536w@^_uuWEI{sY) zq@3?YbeK!{Ia`MW;)PX^jkhJlq#f6rC&+cxb37k> zsm(TF{`=!Z&)!aw_-bN~_SO7#^W*2(GUc36`N&9GP>cswNMGEPxak6c)b3-9X*oiQ zy#A$^d6;uV5v($oFh=X`%)T4*Eu(@j@&JH~$t2rrcI2K21F5s33aL&wO0N_#OEq*J zsa;m0C@>bOoPCFpkzdk2aa{+%(=B?6?$WyXPEihd9tCBLwm~Nc<3Z;SyCu|p0`@|& z^=BjJTfO1O#JR%>wbSMvo!(tiyV%PHKIIv4cfIEV&!lF~56Ha-(dQeBJ@O~BbLXey zUOJ+9;~`OV$%;`Y)ZuRo>kaTM&pwwzP5%CuqmOj%#DEVfqY2Mtu4T9$9rRhLOTu>6rr3q)N%LseZM{Ju$=yJusc@uZ~!FRFEzy3?&e6%;t zED^DZcXtmdE#4N@-R5b3kyl@g3Fd%+K#h1s&!iV(aOMs<2@1J?oL~3*X3+CG8*u_~ zKeSN`4Wces(LQxI^{4^hwNdfn9W2)F_ahU)(r}wZQ5RFx z#jeo$!(RLf78>*Y_)vD253p|){tEi<_Dfdoz2V-2ZMBe-`I`BjR$*#}9Ds(3?I(GC z+lKcX;gUp>i(Z(%nf^8HKPv;IoMi3A!O6-Ai=uVP$d_z?3)*ogch#fAF;Pb#URv${ zn!0>oP*_?0!aD2}-|D^?3)Egu*LSp#HO#gRAYnA&qPO>J2x+MkHwNuXTwW^5 zHsQ+<9{+)6eW(w624e@qinD(mj21G}GDUtol*-lbNZ}-NlFT-)U0{4heoNovejug( z>*^hHM!@M=w(WP>OO-LtczOD=5A;R7zo4iH8op2&y}{4<5G3;#dwsi(+ZA9)hA}Na zxvn)pwa9{6yGsKCT!ou`$@Ex=ybDp-;1S-jkQ~{_0#E|10cWXfdCQlJwwX13F2E}H3uQ1? zzMc=53lBahdfVu4!R9r$RnDwZTZbQ0lH)RZdS4Ep3^ z=~t4hdW2!Eo*}$W$&B6{H?TLV>2g}IMErjiV8|gwNH<5QiD`c#g1V z1xoUiE{Tz|%}rSfFZ?l6XLg-+zV-9=8jY5nA>5~{H}D(J8;!I&ig^XfdT*lV8=UhPRtUj~vY)IARy-?9U3YEC8tM$!@>4iIqp* z4cq12BN#jLPxHhQ;!MY~bt~SxFR5ALATnU{x1M|XPDOqGwy_RXIg1VMP`8rdnCcvL zoB5mUs9URYSU6j4@Y$cffoDvO18QN5!w3M_9Iw3+!gYLt36wCu>YCoxBodWq5Kfl`x-=#+yLKD zKk!S-LK`+T^fD^b+@oc@?n%LS{V$RHW832QF~*e1E>~`S-N)Ess51ZJ+Q@TV4iisQ zAx~YiOqkfWi}}8MJ;r(!VxJyjG+XP+FwE)I)#ygeY4`3n3I-vJyLqD=2FHB=&weAM z_pA?q$bJY2QfgDV1>F>F-j3c-IVuyPFaHAD-- z9wil|KJKgz5f&W&9lfpk(eMX3|H4O_yJ_X=r$f(GFOuBKX}lnF%Dim8FKqX{LD096 z1-|fuahDEDiP}chw=mADyD5?U^_zC~WFs&5>b(H=r(0~LNUlT{1zm@UHf*@39MfA7RyfQS@YME_fRUpw-dQ(p3IoLmt%AV#K>@d zq-$mOPxOl#k6F3A;C`Vj-6*JAccvE`l$Omw7((+2Qmml^Py<5W8-E9mLGBH|%x+x; zaAe*%E{`{RECfocPFl^RU6*+oDpNQI+CwpqV!W*L(A;5Va&kbV_h1tEIU%2)Buaib z0D|nj+j~me1JdAc!+Q*lXQ@Ccn+JG|!n~_dM}OcxTEIbUb7$JOd=-28a>4^^=A*U0 zCv0GaK-N@WwNxN?*C*zSbeCh=tV9$%S8ss0lSM%9>u#i$nPqNiJRBZe49jr{?Cl9b`I~u6 zeJPCqSS8`XTl!W1R<_fDkx|sXM`>{M_%YwvOheeYe6w;o^762LdtL(ox!an4WaZf% z?2c|DxU55jPn$T9H{5G40_4!4gZYE@^L1dB@o%mR^@!K*VdHKTD+Tk#XN*V3i;uYLF@G1 z77#l&vFIj#19LpAG^eB{)iR*-x?IgqgFlKfTRJ$k8LfN@YP__z-MUwHw(|V~!08CVNak;1D=L(Puj- zSvnwe{q??WT{$or{hePR>4Yj2iI16A9N1nlX`K#oFYqO-L)?Y*vN3yJyW ziKHOleIXnv_YnQC0rBK_<##0y)8=&GP_X+gp z*Bod9#CS_eUSL8a$jbbZW%_Kokh|B6knKb!)Ep&)xu0R~=<sr#_3KAi+6%B!Vi)6=b`MIAy=CZmtlINCyX5n!b8K(#{)$Ku2x$osTMCuC zO`v&(@u{nQ@|sNxU_r&O-La@`k%dhNrlK?q(k+Ku=BN={n`*$!lt5w0dvZlH zqP4oZ%cO4g&TMOLyoPJCm5)D(T4+jV) z1X1U?1ZGEO$kC{~_rnquxwF~oOe{~eo-*62BX}4Uk@0uKTdiKKR!>na$d(&Xx9w$| zWpvXF{jqn|biadMO0Py$Vy=IjsJR(6zD)++w$-}2I_{__DTR5rk?Mh^hM@kpxJD?j z0H(tvQcz1rSI>UUgCf-)Phu{AY>GV2Sfbg^%g=A!%kzQsDq4$1ku0B=z=#T3BqW(y zZ}%;soa(R<)PHYn~m9~czk5dHaRx^bdZHliCXtvD{wc!R~D<2 zRwllM8J}K4Va);!u;yPGbid0^x*=}*uK3mD-n#A*5FQZP!|)|Z`xHO}IaCG+D{zXav`1;3uWFX~ueTwsim#?!HjyA4Xw z+tIDXni!Ptr%=0z%Z*}~HnIc%K_Ofc>X?&Duf zx!dpTtm?TYv3B)zC_vWY?S0%aDjnu9M_>2Fm`CXh$ z6CiatYTKGRIc441(_v}oj5nvw%4_@9ng?-evlyjav$(?i6AWg6%QimiaG$!Re7bEO#w{1idPV zepu8t&EYV}Q@X%Pto$BC@N+VK_eUNoLhD)-%d;s?cnqj#n}*K*D_}sL0sh8ZmqcOi zv@`IS#nDd;oJd>DK&-yhbVdZ5cJ`N25X>1h?pI*kHAgKf?0r|wO{+J7fg-tNaeDZS z)h!uqQiwa~)o8F#hf5wnM;%n<#~<2C!QLD>Hh|Dlwt8k$tuznQ1jmbvrdkp7?4rYL zK#C!X#q!Ifo5!62SUS@7zKQ;dfn(^I#5pvoqCHkSIHzj`M9y3}Bg3PX=Z z#v%^-=NM^D=VQl5}UgfIcM$je#c0gz0S5SV6A-~W(kk0y1~z~s;k-Ap)hwjK4fZTd&`@Da*W zDn)muN@A=@=6=3Ws%u?A-RjZ&{Fe~t0-*RSC%>vvo10_q(?|b$H?fmuCF7| zsQIsoN_kehiA|*1h^^%F6vklxqx`7$Cp7$Te>$M{~KAHM&< zxpB^Qy{^~wd_5lb`#(0zAQ-zA^#D}9wB~_h+8r}YW~Lm);Dj16^Z7)R!E+;LBQYbQ z)4)t4-|eRXz4)?<^2Yw5Vxazj|52>3{G{<~WGDHk>(;e^&{K!YgMV4wbGI2;a{k)Y zRo+He{Td^e3P_kZ3l;yeZMZx;0YdGK7I)M1v6&+)7q*s7=1u0V)A#3_&Mjcz!>4yR zQAY#3Du>6%AF|41TsTNu*BGzgiwuFu&MxGl{jHmJ37IDE?*@fR5WZz4RJBcB|G2%p zyk7iRuOy}T_fP!yFY`fNtd2s_UVzNZJb-P2PbB`oKvG0iWu;Ljfh?uld1PmTl>)>C zDSMUAp-UYC8VCq->z`anoDV~Ez%VprZ`hDWlbJAE zlzY@iLx2{sLvdHDp{7!n*BjTrudtfu>GIMD{ataaX&Nm_qPqGB{P7E}or|+l%D$*JWN8X|=Lie{rZ(mmfiEF?#MX6UJ>cRe$3}XI!IR99L6)KR#zPi+@g>NE` z&b?MeaPT21kL@Z~YMqkoCc4pvS6El$EwoK;sy{cHo;z*<_qs!&PHtcdDp`^^51i;k z8y-|Kgj%^T7H?Q#n0pRi9M;5;G zep1?eVhurUrjE{_&x;*{^oVz!wY9|d+T8znp;BEc5^)XR20xk3=3-PU1(~ z7l@KVd|62C;u}|vaTwA!hsnmt=b-O%++j~Eq(=Vu<~;dWLl3ic^f_Pq<4+@{}@#`Doc!29zJ zu{rB+V_<_i0UTj0HV;9zjy&x5cVCDbF8k{*=L2T9GJ%m=r$(JCQSlAR97)qva^)%a zB>r>GEgJ%~#(dNr^Ddo?tYILt4q5UhTOnZls+vjzE&KoNAfgmn-B%+?=Zjw#PPa&x z+rH#TrQ%lMv`T`HxkJqgN~pB5@+mcOr42c1?L$XMvl>ynKf)Z_!+!YG0N=FuwlkYv zBkxUu;4J)w{W6^1&M)miZb1<7N zKZ!1P@^sVf7W+o^G`sBYQ*WGVOzMo(GubEIhb#lPG8mPEE~jg9fzIFD0bV94DLMK2 zQ7Nn0XW?{R0~X46I^vY2w<5+*64(Hj)EI^2f2{|9muFc>`X>9Q=UpiiP!^d~uxizu zl&^_uBs)6#%mDO_vHxO^&wo2iDzMv7vL}_irXO3ZARm$o+6Q47DpD9}5YyLcC+N z5RYMkP`ei{cQ6V-wB=TDm}BH>$D(44j0cXQhooa3{#-*akxHv&Brqy&EbjdIi=T`G zOGN_ZjrVI-%2^t6|GECdXjkg90TU9o;7 zt_i!D(C;Vl5oOBgU%(jqwX#y9cpP|7m?oYC;d0_)_73cy8yIjHKi8(ai{FYtz5yn2 z$o%1nZ{+Vy`BV2&)7-HF&hN{d6l_E&LqB&bvnO*Z1wplpUTn8JPfCfzM_3ot3^nN7 z8v^=oQztakW8$h&+zenUmS6rd9M=s2fp_3hq9N`*(Du+r^pG2bfjP#156#`5fkajDxoq5vDZ_QqD;U2h_ACH$ZrU9F=BrGp1 zUFyEZ*Bzgx?P;JU^L%P#WrEi7!3|y&y1nTUH3$RX70DqaZU%*PyLa$8g_il+7W}AvXLdn%t2|Ja zi8ZXMb!nP9|6J3-K{0QY*Jl{$mE&Ax?baMn zC>dS#EIxl@@Jcu<_wVA|fzg6rK2lo%^B(82;6Eidpgt{>zv5qhizF=W;pcUX={`~z z_R_^0uhOwN|)RlzI{EW(_%>O zd1Zgppc+KGMiOVDQc~-LYirDeSfjB~U|6&F{FfS?w1a><&#dwkTx&dYN9D&7hHM#G zHuGAhfyhY{+NxK5-=_a_dELMHa+HIKQ0aHm8GNPFTx}&C%s|Lv1K1VNsGXmKTE+wUX1#x|kN_-+6L2=zrod zA$6}`Nao{eExVH-0f+m1Po9IGX^R*-EtzGmL@gc!*q~ma;n+VLosREYZ^WmWVU5i~ zm(`zw9uH1lj{V3z(0qT_A;8|@+;G8Wq_m;oaARY`zOiE5?LCz{Us!RQV;CD11?B$j zl7-@vJGbc4KG9#NlP({s<-wRZIT(o6KR&*2c6eaUk<3%aJh+c?^KIo)us`e?8<8{8 zj)68RCd2sb2;YwY6#r{rct8hYx_9upWx=`ScD@~=f;z&D5DTe>r^a3GFCFDKGR&UO zpZj1e<`)ivW7SNx_`pCc9U>mUWwUIy2yEYL%r@ zL+q;w%`6SQ4GHS#vb5+3(S>nGBp0NOv4k97TVGCcq*iCV|K*3jV%~)Skn`K@l|?a3 zo=3p=`{Hc#8?{^>v%U-3uaGF6PWPgkL~T`crpQUSv)U z4FP%BSr=(|43zSJ4d;}@&K!UtRSofQXN1C-#?u>ux zI*RUkUU$Ix70|u(ckD4+J~CckeVW=j+n<&^jDdEDB>?08!{G9aHB1Z)FB51p+9DQm zc|MZ0q+b&Sos%B(26vIoEPx(W|)d5CF#0CZQv7DfOCt^;pfr3m&7CPD~?@^nrMePlchuhI%|p&^jnMu z_+Q8T+Zi*7B@s~Kz!G5KlbQZmyH$KZ$&U4tD9rNLpYfhRJTRa6;#?*P^V7e96vXy> zNpyF2CJ~0-#G?Ml7qI=3+ABLPAZ=Ot+kGiaOCTnVsL{S~UWVw=( z^psDRSt?4b_D?acA(vC6vSOk6m4qVHcpw+Vyam}`CX~Q)dhLQ>VxsM{Jga1=FrBwl2 zFx~@8tfU0h7!<6g4=tZ=49kr$eOX2<`ZT)WedKd|R2A}{W)Tx7uRzueKpKQ^_1AB4YR%>Vt_bwRtwz%t1nTi)Pr;_l0Pz?B zv^uQSxNe5Oyj&^9egS;1wzjs0zQc?)W9P=a;KLO%g3Q6#4oPrWAf4&K3UauxKx;_lyG+z$SXf)#0|_r(7CM#Y#4k5K`eRciJ` zW#73omaNy~buucX%|bL zbd=HHaak57n+aVto+1^cXF7baD=HvC30kJkBNf)Ti5Ow#XvoBCc(mVLnFi#^&blB- z*p(y@v#r{9*CrLr1m&@TSX0}gH4VXnX2*pKYVua=jXZ_l%AE1nBXvh=Ur+_@tFWqS z23A9PJqk3UBlf73C{(OEDm7peRt#*`N;z7%>PCsluj0!lxKwrpV;hN@J;f~3Cga*>5AHoYGH zFpFnw-%Hy0eI`8)dOzW8tEF(>!u$dLjt!U^q5bhonnX;BwJpo92I2U20m%yXrJii> zf5)3rBNC~GK5BXJq?CxdFo9qtrjNCc4fMsanMX&ucu0>&)9G%m>*46dRtw?H5oX@! zq1RSG)2&k%=xN!k3BF}ClO8LJX=@wx{@dv}Ek!PKzDpzTd^Q`z&^!(jBQ5ajW5dN#W5J;j~4a*iR&8Up;7;NabeXsQ~=xQyWo%t14~lN|T$yveSCVgd+*Mc*<+(X~}bt?0OEIqIA5u*LcX8QSmKYg<#^ zsm(WCQ_K>Lm_(oTJHQ36m$Egj__&NTh#d3A5wt?)u9x0BKnY z36?RlTu|EunqK`2=cASup_k60ZqgM-BZ*BPEAIu*kX4v|uFtXnkLXord`?%aCRQF~ zU;Tu-4FLVlO6g9XLTiqc)VQo&V}mDe+051AHv!yH;n^|&(usAGiDXjac;ADsE}g{F zk4|LGzPp8^1O8=MBjl>8s+IHk?^4A9wy4XCm8$fmVwV={MH$^tcmJKe!pq<1yPRR_ zke~Jcp9Kg#ny;$sz5rGf3(eUt50}o2x=-tjW@L=AWPk*St402T<-(8R_D@xf{9_Go z_j4D54v)v-R5FD+rL6LkfGVY}qn#shW8Ck@mqbQ=$2+`ynSGxsn~*4YhTS`Lw00NT zqjUbcsu=p)Fv4k6t`TcWlqM#kuL>k-6!VdWzZ5(zN7a`(+ZS(m0fiHz^z~NZgmJ&+ zqR`+Sdv~w1zX$3v3tjiiJn|~R5grWQxea6b>BSV4|X3Ku^0lELr zYp6VlYW3{%yH$Vxw;B3X z$HCXv*CdsOr(&WaOzF6m*x`Bb=`WXZ=&c}dYF;D!3K7+a^LI_u<)?DUlcWe^okXl~ zk3Jdp#`z0vdSze#1KVGU^@xr|#-c#)-2d5B4@~lp5kw!`=-K8;sE}Uc_q=nZl8A#>_J>NvI=HKUN0ly&x*9h8t9rWqZ3} z?%EHb)=^O$I`bWRAF!HqgFr2`@gztppI~M#XJd_m*pv)LgKVQz;8$_r=a$*ooY{YX zFO1d!DiM!v4vzFxH+fpV_exxKp;YqJEmGx**Xz41n;R;OuNcE|?^^YfgTQQAS-`U0 zW>{QlS_4d)%ono!9cg*dn#wiK|8pR;r64Q5$z`p`NqkE%6Rhzn`_eG&beH!ez-#~- zhe+k(eoMdr)jqrF>qCxfdG|-&hzDn`uiGw1TDnRjwXC4LquAmB{_=&OlMHJ!k6!3l zLWDI+Esu_e8CCvDQuU^)8?GhzF~~$;Y0x4?k~42L3_|e^M)8={jN7_B;=sJy#I+Ry z)2P@F>86LBc*^sC@3|))RT4B0xVR{v-Ma^PbL+;)p?C^CLna*QT#-oB;YCSxMv{A^39Mx1f7( z8L$Tf-AX&Td>jyMW=rVzk`_r2#tLL?Vtk}3ORRcNX5R|mT^i(88@0=~Gst{|D&{Fn z+z=Y8YCs~nQ;#gbuo85{{g2z9C)KTl$DY`1eiAaOvNO+YTt^|62aT${F|IPX-fkh7 z`T2!kGJt7L&34+viK>4s&l5`ncsiy&iF$~H?8$^q0sD@ig#+r>)lJxHncGVdgH_{x zZ>ovpj{+k_0%EQ%&18FEu{G~@djINkQcB7ZR-P^0ohlo&oGK2ic^|(ejd3RP@A*Kh zz2Vfj501_F`51bFmwBp#@6plY0e=4i-j9$!qq#=PHJ&Y&-Wda9WiC3_K_-u+p@0=6Yt5$j5N2ft;(1y{F<-1SWj>rt`tQN?rv^w@~K^} z?Px8K2>#?9FGbTDL+VAFF9fu=iJ>}P%Cz#pWyU8FQbY=H0!Hb~h+}9gT9kVAt<1h7 z@AspJ5D9GL-Z)F(cBw~_s4SlvA6F-%y<#O%-(aTLMI65cY*hRsPIesecs$uaKWSr} zZ_Kl1dE?@#N0+%satmJnT3&6CQn%y31(hwR+F@MycZffebERY8H_ z2M`W@x{8bSZaPi8V*C9hRq0^~S{NcqnN|`Bft*ZU$U9`rN9f zKEg9T-2E-4tFn^s!*|mGs0^_QJrSMqK{@qx<7`r;(DMLjK+Tjm17aBc^hVGR?fVst z61QWnGetA2jjI<*?;v-J2ASeQw>JT_nfi|bh+u?O9*?X;B>h*bG*ct(95V$*$+p-Z z|3!XNEIYQ0r%r`1jvH6NwH-ulcurCaltWk7UUv~{>uOz*>GkG>02_)hdQJ*p5;)n) zC|ksu#)Wh7Ic7--lGR-2Qi;$S-2Q$Ev!N|3OonZ>N2TORCJCo5Q$3rjhV@eU(LpJg zHSZ>R0$_Vh7UPI)!Hlr~Kq(Ld6aBnAjxAq|PfPJ49e4Br9LuZDcNM*}jEqrg*7XeZdzC4Fa=1v3pO&FQ5IMg|UF@$;L!Ur|_`E^;$&pm!aF}Ki|0J&iT?$>l>pvG1z3&lm zG{n<8*v5RD+TURQ*Fs=KZ}yPwn@xz#Gc$2e&5MEx%_wT-?7x-Y5`@IQ80IjmXVSqy z;{%HwEz|78iEoM}oth}vGn7=mNOlU+k<@883jnpq=e}Ys;CstL&nPHIOASVv& zt{6e%3V0uKvlAlD!NDQ-{35IS%+5SHGI?ZWclT^`fGfn$!()11!{N;fBZj4wej@bD zPrkdWtqMC?RfVbR3fLKyS$G+nzf*X*d1ad2qkqYjv3}2SjBV*?@AaU#Fxpz_?&R}uKBGm!)PSkn}3lD z|C(i5WDLx6d(rAlc}7UV(s+O-e=oo_@c;)`gB^?SGeE^vl8W1hCGJLLkFKhl(DG&2 zrT6F2p964vf39YtLGAv_WX{p@=aLL9GBdtMBeOy999@cfqQc}+FXkgrc3|Em%P3=y zFDeDKCGB*jBzk!7o7`##P<;c&LJ>m#tB`P*X760B|KUDdbqwY;+Qr2H(S{}6e5|gY zSPAF-hITo`GzciFvlY?1OTFhS-Vo20n(@V%0EwCZ&4HiPJdh|uKP{W8to)J^yg(0w zJaei*dl2Yht&rk3QczDXFKQ6xoS-n)`g7|Lj^v3EfaRVOOcT1#d_&Ku0y6H?(Ry&* ztJ8D6BGRa)s>cw~r(epNoISBH`DrUWkRF6m-Tqz36u}S;N&S?qvk-9Vw}z=2@m!5a zkr;WhYS!{nm0HwKJM2mrpEE?wkv(%ioOW1L9S1FW3yVi_c@ZM$^`PHSDcg(f zE2t-;6g{+Ae(d2z?xJOvoN;j0K{NyeQQdZYK5#wndc}*+hFTdnL%_lkFN8u*_q8(Z z#DIHqI>3o1f)SqcNv-{Y`Zib5PXrhV=1Un;!5&k1g}!E=?dB*{3OIW$Unooh&IZ~1 z3%KMJZ5bG;>-Q&+4B1DV5HmOJ_4LNZqEFJqgYW-Z(c0P$oAX=eD+i-EQ#Nb!8^{ea z2Q>>V!cmRy&o7ap`?EuE>h@OI1#f4AnbDBY4%u6%k&zO-hENmZ69Y~QZ~=2$_^6} zM1WDxG#?FCd-{%$`CXMUmbK0J18ew*7Z!TjtFRiz%O>GJmwu+ErArN63hBO`2L#0) zFUj98fdCPLTD4lNH#_B2I*mKUAkDy+L2vux3%u)Kpa_i(((c5*bDtoABlusQ18;F= zKv8c5L*^NK?0o~VNSWx3qQm;l93&SiS>%aytf+X*Y=Xi)GX*;r{slqXYhCfcw7A7t zRZT`l1_;aKpx$t&r42wKFts!Uk7`6*-*tDj=_dspZ+co)u*me<68TmM&_o0SyF=d8 z)F(*|hxZVgRl+Rm#HgGS-y?_wLpZ9DC&SD~lU`4U6}2xu7!I(D>Y)5Qi<(Kvdw#XFWd0R*Lse=Q9 zxWOEdtwVAF2Unp|AbBfc^4Te;otUuPf_!@fL*uR5#Q|mbz2jy9fh(qJ@7{fl# zRx4kQuGV!ccXxDXl#^i8i>4d@j{z`-M$ujBEErK;vA{;w1Tx4n)}l|QPs@G)@VUBxX48fG_J7|mVzF=jDFSNd~j7yxk1%2AJS ztZJNr{D`33^x}t44ud@X4FUlUkw=4a{ZQ)IH1REi%0dDu}+dhfE+|oUFsp z2ug*Cj=3w@dU-HKJbJLy^})mJ;$ZN4J|oO5udpujh~J^ywfp>Ve*TWWEk`)>l(OA} zbVg3@(?x_AwLr-;?MHkXi{Cz5IB&R%L{~p9o_e!)Je2+xL(IR{3tRv(57blT2Izo5 zKt_CO=7?S6>^x!NVF=N2fw8>2yo^Zk+3`KZ?DT`DD5NI2UJ}dV4%_WO=O|SONkU`J zhSJNiUUBqkUWS#`QdRpKddk>6fc9Z;jjp9n#m2#4I#n+nNxTO`}FYJurM)3+U*J&HK8b6Mqz zXsvrx8DhmaKTC;dQYQ}iu~MDW`-1=b3eB!Zf4-4w3=*h%pHT7*QEC8IIvG2EwF3#} z&amriJtEv9M>Jv?cv-5re<5k}(8@(z~lD`q|C7$``4NtIC(f!uNy0 z#HrK6zkiKFPb@E%F88?xic^ybfyC@>m@M&f@A80+sLQWD+7{1*x*c+|8hTM&7?PHU zX3%%L*Q)uohB&e}c5!+ce6~DfB@aV0E6T=#;Q_!ICVek&f4}u%dFbiFdEyy!k4Z?6pri!OW4^L$vr0X5W6B>d#=%A2O@;RfPqnd5K+O09AIZKJvC z*}u)>K8BkV883R=7n~16i7yGSKI;GS*pi2t7I?bzPpVRCzvbC5^f?4tPaV{?XYFR?Zzg zBzGc(f_vY+h6cnvDnb!xc?4IwoWD#&u1i{Iuu-YQ+OAPiLKOr`QLvf@&7a=EX?L_m zV_!kDUx9nmHFI;n7|KWvMs*XQ|VHrlpGB;X&Z#C zsI7Q*{vBhuI$UEfRuZzDXLxO}(I;MpMpL_g%Y+)BR3KBQ{G)e+QQ!!=m{b^*T1j@n z&?8TZ*axPWcC5wTq9AUY2$)*tm+~mIL>@Bvh7C7LyHYKHh9^mji%D)N4ub50hf}dK zdP)nbz1f|ZmuB8<8J(S-wRQ*EYU0`RE^HA;qQ4{A5!P(a7{XyA=)+!<)ig^Hcop2kH{zED5m!~v;hrNt|5Ch8Hd}bWJcb!8%kNP zevO${m|+Aoec)2b!c`LqI`Q5cw$t+c8H~LzpWn=ZAi&ZLUnk4;d@&l@&fik(*qK(; z$E8Ojxi}a(dV+J@RXbBUa>^f z7fu>(Ff_7-m6vJ|t@Z(|{Q0FgQjM#15hT&XkE&;Vcq@V}ji{)~O%0|yWq@Z$VU450 z02;OqH9(`wqlgw)RvMRoDMHFvCT|%U^}kk}lL-{u_i0QwRTn|H5oqt0vKFzoR}XgV zEwu|JP_kn>G45UYck*itee?EohH9NV6EX7zk_72<`$mU6Myv);jW@$1w@f=Z345JF zr{JIaC>T{wA`jXA*P4ldg!|UoRXe^nBeJ&iwt;vA)l%8i_^8<$WPiy( zq9H1DeM_+)$0~;vlq&}Q)c+82dT%e0|GL+*%QQc)z*at)sl7Itfl3{4PSnrJlsSjj zzj+};&R;Gf#ik0qi$gG^p7v(iU4#E?CPFEfm{Vkz!dMZ5dy13nJktki+UtV0b`SDL zANH>Qy>-^w+tB_#>UNO<*~B!oXzJWU3`N znJ4T{GtwZuTeLOz3OeE2A#@+edT#kBlo~v&q~I-r>fMW|AM)zJKbY+QmECLlSgm4$ z9>#2+B@id&`St6)a7ZdbM-fGRoi-k40=o;E>*a0uf#iO|E35|OHyc(0NE9mC;gmhJ zrND5BXRLM6NJeJbYfzk7vs7aVFcJqn8z~hPQK#em3i#r~p%8`bnaPm5On%Ql-T3@f zLmT{2ju8eyM1dHYo;$uOK|i%6^u3WkE25?8P>D%dj??TxybmjJ)Zm8s1sL}Tv>qQG ziOmp4fjH}4ku9oj<_Ymi49fEnoJR%G7|Z82z$c_GXbTRfEQ!5)=DNW{w`i$W#LaUR zcl`r`&jFxdx!UiYSl2@hisxNqyv)ImByjBXaGtOi!qKw|t5pruA8Kch%=uG`mwUos z&yo8N?U1ZFSE&hdf_%2$o95rj(yVBM`Wl6q~Rq1mPyyj5q%;>u#ap)uvnDK(WwUaj8(n!2`xV^=HU{ zRXHjVgSc>O2{TphBQnW?8}6F_BHl9`gaF&>T&)F?Iny|X2zP1_u4FNB{Ymd&@e3Yo ztE}7(+_1P~)}<8UpJ_6w&%lr>kZB;dj|~)Sg_w27DX;4MRX=eEJtVohxG10R^G8G? z-$=b@H2_E$jjnapQAM93m*Ro*3GxJcRfz}Th5?Qy@Zyj*SjH_(=SfYUOUn~%#~PKy zb=sFSH|+|Hbp^LI+@cxs?x5hN_j`*LQNXz_Vm~4Q61;GPWl%CMZ7kc$Edw-ZNKK9U zc~bc#6P@wG0yVKK^dukY;r_+AE)y5MWiJNA2;YcMSSfNA<`tZNydzeYI~8y9=?Qy8 zXh8E?Y^`gHt3~G@urhg8FS(pWGP?y=02Xv1{WAm(HUc^cJge(BKcR=eu%h5sat!?o z|tr zx&@9gpT0DsR!lNiPplYLI|SmXK@!+wNW7v$9)In9*yj7r#UQif<43|*u+aE%h4SbP zvXWn6g)p_zO*yu=&~Llstf~X~`%i4P#2J87>wySQHUyvXLY>Vv&X@e}a6mc7e^qBe z3-&i5y2ZY!!@-Qtz2Qf^wOS00-R9a-^`PhC+wDi1*MS8%v0gFI>+tmKZ%7+Q#!8pd zUZp*fXB7o#yq;rQnJ45PGfCFS{SjwS&yf`D@UFi+lobH zo5FR_FVDhnLZfwZjAJW7sMFrWDxv4Yu`1KoBG&^|cRuVDj5&b40z=E8!>SXsckZc! zBIt1b3=l!S1?Nf?1{2Dk96{BL&r+5(o+9Y182Fe|>!n4OnM1QAIc>ZMT>IScGC@8Y z>cJ8ST;pEbo+vW~=QJG%{iz9|2@2`{h0<6$`2$U9GGC3f$+JOGYaKJeki$t)kq7Jo zl$0!a>T&SzROjcQHS(*Udp-5?n_nj0$9m$je^$@DyDEDtS;N2?HB0hQRR-~>SwU;| z5QDS(0yDE7Z5*c-5?A2zx5FgWJ`qoMcN=Q8J(8YG$v9`S4~!Y9=|j`&A0?1xa!pXf3T5K3;J*s|dnxhs zADeETfs(nBE3IP0lr9zf)@(E>pNK98)yF|<8e3#ql>FlKiN6jXK4V2aAe-|IaNVN> zcEe-2^FH^Zwgs=F!<(>yN1L;g4V8q;?XOT^w>s|<`Zed7DZk(|{1?iH{+C0sT+(Fh zb4bp9Z=V(EU+w#{`@5UVYno3^wqz`Au2#Ul#TRh_C5l@CjfCnFG)xxfpShwcQzCdi z{j$c+Bt!6~gHo<}CYEh`UK}pxo z8o$%ZQ9YiMJ!)^dzPGnWCX*W~(MZfe8J=XHE{}y2v2egBsoVp-r@Ci!hf@dr@ZPEp za-St;ru|F(Ca=FkzR`V=#;yRuD&~q9Jt0zNjc(0v5XHJ`D^1<%XU%^7`b8CH_(r~9 zv-!4bK5hg<#5B}C9ec`xdF>y%@Xr^q(fhOeqN@8WvhaMo_;E6z&<<%)P%!ycHW_-n z$+cI+6K^!*8ukSslYhsOR@EJ2?8T>VWo7yQN7J?li$MP}NeKHY&i&`L)NsQ$ zlM$#VLB@RHaNbsm6J=6s2u``-Z$0Ujq$Ep3JOT?zPb4Ke}=6AQr zh3@V4x74`nx~9PMS4bUXivps=So`_Kh*N}`JkHE*l{3jb41zGpjDRqufRNO|w^I2HWb~|NqblNPD-mzfAaY1~ zqzO2DFIM(3ENB~>z3#^m=`f_WV#c5}mhcMXy5;vGdBg)V+qX!U5&2_=BaMp*-uGj< zUv;V17`gC=%IX=|eNa-Tn9m1VewKoGo3A&P2$^`9L)|0F_Yf?OOkf~aI$==?G*Syu9b+P!;0VdH zn|+!5_wjSrt>lpX9gnt?vpw`HSztsx+rM&~S|cuahQ3speAZ%09J1vpWzEy-9kt4L zH>riENlFJeVD_p>hk ze2LU0TOgJV!3A3T9j@)X94nZgCy!#HQwGy>XbGM;*tm4@~7ud1YrzwFOI-?aUn# z#sIg!(vYYNunjXGbUFuGI@}76xYo`Jd8JqowHSF+?%*IJbCkRFv~shir9kK|V%tt1 z=v32&yjH#>ca!Hy7PcldVDpyqV&&8Q`J=-7Ll~SN$v0Po>M1n`MRWp`4 zgZ%U0h0-bH8@@bWlgt{!`)d3Dd8#4RIC=Ujh0_;CgJ4PdVVt;d!u$JUCJh5xke zdhPr2Zq)SL|0^8k1X6W)!u>7f7J!sA}L@J{p=}y5h~h^>V1o<8)D^qLqYH>VIv8|q5v=7(DWMy`Wch`w$Qh3Ax(3D?_-Ta zZ|v4PCYwBU9#Y3M5BYq)+c#lVBNEPkHvs+1IkHNJyIWQ{boaO(qByd@@y}4;W62ts zBGoQBP21iC;H4)7AX#W8p?6oh;0SQd%I-xH{XLta{RYJm8x-zJ4fR#2$a?!vWd@T{ z(KzUm;Dy8u8@3LWI2a{j_^)jkR-t#Li~W7ss|ff0k#SAQi(L$>pWr^y zxjz?Yssdqcj1;LU^&een*s2Z!LcV}{YPXcncgp3(x=#KoSmos`Q^yv*~n1q>HZ{FVYi%v*}i>idso%QP{1Ch%(1NT1n_nm$xlXoUXUR~ zp9ERF;I;bYw+FaBlOEe(ZSVW-;D8cVwbWC4A%$$Sg>Vw5;zXRaO}ypYJ>m@q)k*}xj)Ny{ zO>f)4PBFoIhnTUKHpx$);>POiCx^x^x69{G4c+X=0Vht^fwV-ASST6Oybf)cVPpFc z^)B4KR?9DY5IQ(@wH zd<8f~#VM%741!blBFA&!`*1bt_&&J=z=XyQO#5qXmpdw*R=?JT9GIYX_Ww7Ujf2$~ z`A)yj?u&vya)cd#qafD%5J7zvZVKmgd%mXnzA&gNj=euF_BFcXR9!=b+SCyX-*OyC z-?6S2h~NEt@psKu->~1Mv8@|}!F0O#j-HQh*>@(vLHco;aWJ*8$Q2dsyCs`3uR8IB zdBRvyQh=oKYGwOBTFHIY)C?1gZ)^i51t$=&xW;Gf^nq*??a~Kq3``xj^WexT#pfzasVR{OABh;&le9i722BTTuwc|PZQiR+ zo3&d(VC~_@4&??W2F39y0N018L#z~j{&`n?AHvK0z`SwRIpkzSxx1~?($yzUQ7tZ9 zFeCZiQplPOAN4XgqH+Dx_h|bF;Kb`7Uh_y!dMI=c)aN9iE zqUulGr-v)ufB~6Zmkoe8?2x&FSZ#tlnzP65U9N{->H%u-`>CF*OCD`5xi`ULqGCA^ zlwie|6m3mGzGT+66m|Wl8dF|o{;OAe*WJ@NLz>H0zp))w$`HC-_spnv3f^?${*8*e_7Z%BpV8{3tm^P17sY5q}1O& zjhuRq2S0NpULmGxNiulJhN(?{VbTQS?lMlFF6PsBpNzWVecbHD%ifJE26*@c0hy9u z69ea&SQX?4_oR_i#>?D7ilQbU(Z{O3b18XXubf#s6HEZ!J-Yl!<_4I`0QvH<@2hc& ztPbyrG&QUt{PiNT;6L2&61im_xlqYIxvN+>ymrj$*!b|d{d%I%CbE3!k=jKOzr62gyg)LqYJNg9BS0!MKKSN`ie>=N(MHZ;?lsnruR2!) zT;RZt_~nC%W#o#1T38lXF8tyvNKff-`8z3&v)>DW%ChMULw6D^&lU;u3eyZY9o@{8 zoXV;OQF`2<={(8DXthpG-%FI8z;1(bx8{zcC1Gm2LoY8}FhdFdu|G%m%j%*MIs_{MiI@wOB1n3-gQJneJNq#*iOEBXh4n+}t{1)M4VNud+!7<^v!tlZ%t-uk-(H zOic0UI&lMb!lq2<9xi!lt=gu~whZWs%dP^ca4R)rWxq93u}uX39g5Q*Hu10_HdR!F zr-LwEG(3Pv8Boec!;KYRTs0MT2;PP}f8?R&&gS|iS|{qS!(%Q!eLejOWshtkW`=A2 zY_nYXq>~hk*Wso7X$7K{Wbl7-Y;-(oSHnGTQX$b;)7u>h zFuA)oisRN$^h$#|PXX|=GYX`X!yq`7$V3I=zey3atp=sgglxtZzC*|Leq9!>}zaLG|tn+DId&ApG-jDXX8Pg{>56u`*%wr2oGu9PR6GdZ#f>TnYlKrNdZdr zuI{$B9mCts8?)6UYBj@77MIUXISNyi^cvXrHN9$i(X zjfHK1A*%ZU5~x`ru@rc!o&VLlo?dV;HloEupAU22CMfS7*2J83QVOnth;!Waw@@dQ z2tjPHV5WU3zx}GwM4wF0!#`&Le=g3ek-)PX$Vljcbno{9=Fa``gjKNy#YTcB_TplJ zOfKy7Yn$JK?ntrm-%Qy7yv`(56jaglwxmJQLx~I)ZTjaHaYUjn5bk5QZvdVk4@^TKwC@gvz(@oHbqKMuN?E;LV4;ntox4`&%C_z<=MtAB1t$| z%%U5YfDrUiJ_i&E@H)BKI z7isJ-;L>k&7(+A9{qrB5{y&<|{gKJ{|KmuRh)rTjF@#ANIYlF9atJve%AAs%b3W!c zEa$V~ol`j$b3T=vPm_euP!5Y>&gb#HKR*ee7n{hCay*Fr;Uxfwr=Bf zyB;(IH#$SYpsy;1YCq#KMf5Pfh2s7vq#(Rsc?mZlQtSG@QR;zs&UvQ*2w`vFpLmEl z@5qnF{chGr_a{l}^w8R6?;wjigt{l?$nr)L!nJR1GvcQsX=d~=V2C>wTSJ{h{}+o+ z4Lz7vPu%g9pw?da6ml?54!Jm0H8LafJ721qaJ?qHgVFCEIaryyb$H?=BX7o1tI|9B zT1u0Cp4rxFg7RIWb9N}6RXNE(yf?0VNy}AAPFkn=8IW2sPYl@9_3VlJLC39x|K;Jc z1JG8FS64N?#2E0Sq|#h|{Qn-@&1Npr8>pK8T=N^p7Ubde2kjxp)1RH0*TRoIpnIFW z9uiIxBGJ*@4-+J+@hPNc|RtsNUB}_i5FZ-+I z8nv2{jiqm)*4Ot*6C-hsuRNKWK^g}35CiCJnf$E})+x~XRo~Xy%5;O^*%kkMgEo3+ zd?d6lnX0Wmu!N0B^`ae^oX63yTcswTq$j8WN_V8UMxDu^eHwVKo zZxVCiOKPn^pev z`#D{7A3nsW#~ADoT%GGRTRwr{HE7y0#!IvyF#SQF5vH;E;!*db)!LWL15r%{YQ15n zsVvw-`5t!OZZJ>|nZQF&7dmg@PYXXX9J$%%?6m*4w8?Hg^ES`L=ZynMrs4$N@R;`tuRnq;q0p>+~(xGTW@P6 zP5I6MYsk%zal{64opeNil&t}V#0g&;Q7f9w<~UaHV+nA!xcKb#5uaegz%bCV_5`;dr?o7qQKaQ(ro$x6r=eq z5sACY4TK&*^+((BDrbB-Vu~p3_T@B+-O(|{Ub`%!>r%dCUtdB^rE46(>s&fJOMyB$ z3%CG&w$O_%W(74}gR8c6N&d-1e6s>2m5bwvUO^ilK+W7&p8Y9#B*@_O`{nS~L03$` z%`b<6UoJ*3j=9eBzU-1gYOviy^8D$KOk`HeAELtfl(r`eXN0}VxY)8_5_ii&<#nuu zvl7tHv$nRLYxN3ne^WQ(qN}He4B08ZeOfxK^!Y=dx|%cQeCcQ_^tj;SgYR50xliF} z5rC-%1=;Prkttv(IiL7)a^3kh%)vk$EpO7R>z@$=RXAR{E}|mT9N4QdxZzN5$_b|5 zLiR4SQ)WZAq+@Z!(a|~&6L$7FIcHAxt5lrP*tCa>rrFH!W#g&(2X@IVt4k zs5LTi?ukfT;U2PM7a!O^Q9;Vxe^qZz4f*0r&Sy2ta71?Z1bKLRvce7sP^t_%Izqrc zaAo+``}sA~T49GZK|bJO>@Ofj8U~CxOJ^&d{%xjrV9F;a(j5Wh^SpwKp3&HNCH=Jn zYPG*u=z&@v*p^Y%Y|cbWYZcoAN?Lj5bn9j()M~l;PT%;l&HJB=eTjgi8P9drIe!H; zHFXak<|Ta9j4h~jR!cT364AoQO47qQbK%;;mpS~VnGfEYWym^ys;(yP z`j=^`?BQ>WylyqWk^Rfnm**a|c0nF+2J~r4ge`AxR}+{Po2;rr2?zdW)HaVSet+>* z7-FD(YLBNaDE096*965!TxJMa2M{;PBE23zdX4>6F&@PW?PHgC?X;oJRS2^To$>DE z#~6yMfQ zWPlGa^Unk7tu#r^jWRN6C5YIk8Qetfml>k&PBf&1vhdP!^?GPqVt7VB=*y7}ItTv6 z-m|G%K1G7N?F!;f&5hOsN>}{DDR(EI?t$rTueN#El`Y`WM1Lv9OPg|Ez81S9{`2bY zmm>j7!EhYc`C6uq(LB$eSoku=wm;k#93}%OM3&kG7*}(WbuTw$GCtPk{Iw)L*XohfB7*+=;!j-RaC#b?~{(xkk75%{93u{1Vz>8V=r zvZq;^_pEQK1dvwS+d@bDYk6M~p!6oyhl(gIZ2)p3?EFg#6A}HStE;R0xi^9E;>1;j z=Zd@g_utJp%v%rZe9kYxgC7qr(yy(Wi9#l+lR)n6 zQ)PL@gpSn%e0EDU3Y|UZpWPnfjWg3@C*D)+J$?n1BXjavKLeU}A#JbK9!cpudOoah zwD1JeG+892*1x`oAJ7Xqy8bKTtGuJ|^=1|hu*BST@iIPT6;!V|)l>hu14^Z^azB)q z{miU%t&qj?ng19Nz?Z&P)=l;2WPkVN$!`4aZkKYnsgb>zq%4C{lEK=-i}(A*^-KuY zDY+6>fh({Kqt51E^#q?rfX9rWLDU-S1-z;LJXx3fKWYKKoi4s7sL{;AIWIAEasJ%5 z-UkM3v5@`;(~f|8!gm&+Iy&$X<0F>0J&aio6Ue_U@;4iDOUriT9kqlr)Rnf1iXvKE zq1(&btJ^zE?#)5_Yrg~4v0jB%>-5{J;{u`uA%h&d)Yi|j1wkIi_%7d^a(M08z@i== z4_pd}f5tjtO)B^HGc!N=ZX_`1PenCIU6ZfGl?(Q72iwwcuX@VpwW>3NbItT6k00#& zZelkZOy>MMCuFjopRFxQ&jt9AJ6DgFkH`MdL9>PNN6s?UW1mLU* z!wxz|MjO=v-{kLsq3o8o95LIlXiy?osJKE_W;3gjR_E+ogKeg!6F*mM3`ohIuhym2 zmNlI|KY7YYKhcs zVNgb4Rg+fsVg)=Xy6{dR`>>hxJI#*A(pLPVEu_}Ei17?-DqI?E3vqKzL6;yU8lBl zdVpb0(yh+Y2ttfhDY@%N%)2(?WgC3?ynZ`^%m$I#U6GNjHorH-VYg8l5c*=pZXRlb zLRBg?OxbvBxStA|5yyHg)`m1z3I%sV^O zu5xNk1+-UwSq%TJDiY7@?*g3~) z&?=x%mcW#-Q)pUcY?RKMoU-O=d6|oe%?oCP@xZxE&Fb5Y$R*BECStfKw*aw0xloJi zsowdjLP+pI%5{qeBR}^6EgkV_?^lfJ(!|)nKs*j7JXAkv5UUMH9Me3ZZ_L=h(*xW3 z7;quO3kawPxcX!+7ah*ao3qlzmy#NctfT<*KK6`{o-&UypMZ5RJGsy9%eIbf{*{A{RVS0XNCa`?IYd2#hC(mLwk z&ec1ylJODbAaWpMnegC3`2P7s1u)#L03?Es!w%9JFaq&;{zW#-V{7>~OScc@z{OWMG z4*x?SnvH&usFx5d)}QXNaD}o^?rPmU?oHw_L+&O(138v<#l zRx2^WgG-;e=FNsO7LiYpL$wVq)PIAJ1*J9pKbM!6gC^5}pnmh%CB@3}S2_GtTfrA+ zxY0c^xJcXnM#JuyUMkZ3&bviHoUmcGcXewAeuq;D+OoNH^i0oTiit@4#I`HTo4y={ zYv7UuGZm@*oSnSQbw@4C6}nbBhPSsbs~X4OzRhJ}Tkiq+>p1$n1z<04V$I!vGnA^= z%9p%JAXFP_Az;|u)YW`splh(a{6j&~RdAXCU_~xTG24^seOYgW*y+q3Wz%TMG~k4*E? zk;&Lg(}Oob4^ipuJ8_2PUZwK#yl?OfkB64W_D2R~>0o|bVfvm=OXHt$|Ltbk`R}Q$ zqDmpvzo6RJ%@3p&F&bCNdCW+0RQSB-EH6x~^AVJ1iCYQO`-&&UG7@}=B_4bjUXX-3 zUG=!d{d6s(q*9iO#`Hf0&?O^*c=uNjoSn_`^a3{oCu(bHFpCnjlMz2~kq} zbC8f`+Fo`G+T~JCb8+>&A`**90O#!%*j_R;Q0RRb;fP+;lZ?CIIE!e)$fXOJu zA!rkOAIjY%Q)G1Ko3AMq4|Q8lJ~Pe3$w27hw= z-v56Vz@IFu{zxa+wW65Cz}hmeZ=oa!z(xpKqA@kyQtQAn*&;1!7k`t%@P5(mu6%IcL%F&MbZ-07=vR_A#z`EHRfO5>k1={^gG1ii?i1s(a(6)wx! zP3*PZ!kj5!_xyFhqAyz!PtxXaL4OpwhxZFeH2XBU8*zo(F3y6)@u5wy?!aa0713AW z6vC3JMft-;NqxrX$O_!9G+!f}kG5-twN!p>%(w;Z<}S);rbA$UAM70RMveGO{Ps^K zR#!Vcn}1hNj#NITL5-dMyPwP078Ja{sBpSX81Dh3dSsuC9EkKJ*akf(8|>HA6cqfY z%?N|wV}^*mB3^N+^itBgt5UIF?GlxuVY z(Tk@n56ThSE6Q)8K315OTGP=geq1~0%tXq_$vI2Q*$xAA&T3a1qUb$UQQD(6oB1-(ei%6jY$;oYME(3;&LuJh>zt9jW+ zkac%&Tn^^^Ul+3;nV=wV#=|Zk;2XNv#WmL&c)0jHl$D0j+^sb)MT;uO>5We%QT-;5 zxJq=Kqj02&BYTV&h4N+FjrwhUgtwYlLRk22WI&1mlevlab?S!MYpFjT3X}}uUW*y? zg|K+o4hs|nc^+=&$tz5YLQ$+(@w>{ATxZjXaq_K!ZQNyk{Kh0B43b{z?PpSS!TA}x z2`MinDjr4y6y1cZuM|~5QZ`x$mHGbcXj3amyjiE|RhX|;?(4oTmG|Tb~E^K9lj(|9CQ_{WV|)vp9ZTO<1KdOB&H6JmizdQFXU-{~wgt z8>2JDyHLC#mf$U6QPo%^#dEzkr!L9Vm#~z_!HXGp{nzM{nR!`ntsmUxRZ*?}P1_#w zU%96k_rSe#$bS)f(^QxwBnYY`9C!Bb-@mi7-?F3N;2dvN zuo4xYHToS)uml_ii^uc6_u%h_w&|VR11KetSv>5(ew}0Xk`KaZ(P86&$T$2B3VU7b>9P2;SZx5K_(gHlznE z|8(jao`VO;ab2l@DCmbdDEo?`$bK4(fGPY^@87)8PT!r~h<`YQrbveT_eAWTcG&TQ zC%+RP!H>T}pL`ITv&M%{-lVd0?;u}BL~CCE$NM78;+J4IGz`!^htJPP*?zm4I++6% zC6$v~mj6Jgv;$@;CviQ$Re=){ue625If-rj6v;6&lx*#=WlT?*Y!M!6JDihK%z#7q z*lCFS)VAvjFQ`G%Q^1afoi6dtqu>+a-hP=|`?P6Z@Km}VF;E)QTQclpUB%Z>8fjN0 zobKYlK*bCDe3&?Q>hUjpT!&COb9?c%@hHE9PM2xgUBsZ>3dX5%qq2-+CEUZ=%IpSa zcX4^U=UCOyXtLL8eoB)1rR|9m7IQ$ids$h=^ua;|%dk_|WslzUzx{%dVin~CS6_Gc zELWwuV-El^FiGe2Sum4sB%obQiCFpKK|y-h^5O?k853Xf9J@i=c5lSb`gkyy=lX+d z<1$S2ld4FX!g}2s&8m#i(H@o=_7b`5M$6dX^Y!DrMPB&y&O#FKwU-xSK;iM9f=Rw& zhI8r}g;zmyX0~t49L9^=4>ix}5p$5{L0XmPOIoBqFO2iB!Uf3SgVk}p-NN-2se5tI zMcin9^g`4y>MJyS0bshT9vr3i&7T~Qt*xv#q%6qVjQKJQ)Gao@T%<972DX2g1^Rt{ zgTLry|8mq9dJ<7yMmMX@l_$yi6|?ep{cOcye|`P+6f-b>$s8T!R_XoqqRt?W+SrV( z?uzc*D?EV0MD((YK2Oszl-_p~EhwNAkwk-+8JIWo+J0sjm>keiA+rI z>Zhco7mMH8>ZgsB2rh)92Me{cxA}hXeybHevH9)di}ri-CavuCzrd1b=0t|KGf?u` zpD~+RGC=e&D@mIub;|h%+?6{_Ifa>|a^LYvi?XE_pb?5Hj2bVhmX*+Hez9PzZyDDT zWo|tI-6@Ao%7Vbu@KD7!0BYC2Nj~6UodeRjAt4jV&2fp!k+T~F@BVW;9xT|h&_*A2 zN|dBoXSYkzkUx#_o{=rdO5N@Bmxkv3tBcKGbq(F%I&`|S((Wrl#W$TJafO3Lth1Q` zq4;L*UT@xE=kbGJpUFAb^&gq^a5k8X`hQSF6O>*i6;hZcq*RCZfQNVM3gNsH~bh9;S?9b>UM|Q~CPi zc}>A1mJ%1cS{GGqd1gDOM_S#@zczeCBFCDcN{ltxl3ik)ckVO+Dv2Z0s@dj zUEeU*9V^Mc;qj%}{^VYd{@uTugjR1Oug>y^L-CfL^|P;YTIMRHt)>)0k1gH3eS8`S z)kC$qmq-9dsU;s$+u?S-RaH|J^VL>y3mFNX>By6mAh~!tdEQL|Ujo5*gr|&o!zTka zj8*luyRu%qaJV_thQgdwyR8Kzeifhvb$!>oOQSTK*lO%1O`*{Ff)O%dAX+Sg)Eg_K zrQUz461gL5R#WZATO-<<%>RwNX_9{`1Y{?1BM!UE%*Z5z-?Hr&YwPtmM3Qa4cyjE{ zf4Ahw`~XQ^KHA+QhWCFaQd}Denw<$u4#ouu=57tGEoIWP#-QqF4plyQ zh#`Md;Lu|EV6&ZuuqdhFcD^<8kt{MT#Y>cy9a|H+7fM-NT;2(sr|9MnJ;zf164c4m zsC>u%>7I#K*2YeT+>pu%(dS>ReO-*%hL-g~$RTm`3yY2RdqZnJW31FFVgHH0A8gAX z1&zI&VkSfs6_pEf{2AD>TlWQhz3kvWBEt+hu{m3D3#Npg#$0TDIUBu@xD}rCs_y*6 zp``J)r{imY;V{{XP7Z6MW2a8`CknVE8KPM&#byG&UYv&>kvD%oI{!QSVeaKpw(?n# z!udesms5%>?w(4i%s5pF!jUmv=G_&ZLE&3{$zh+Wr~Zffnyt>;d+;vxsi(NqG!vjF z$k6E(L&d~Anb<%p>OG=X!8|{Dr|!y`j|}#4_uTnMIMm1i>o5I|@$+wXoyFfYG?9E9 z2EDZKcflPxqRtiiCa8|PHd9)3=)^|WISb4bLn0(RDO+=BHS;xLkK_bHruX;lf2fXx z`Ly11+3TWnOE8ZYe(rl;%X%Vx{4GG4G(dYmNrlaA9o1|6-APkDtU5*}D#bCen!h)t z=6Y&{YlW2~S)~g2<#KP}qOa@cS3HnazoO*MLlZatAl)C4Ksi3HkRRF=&IJH4fsYP? z74|4W2w=&+(bA7*C{gD{_fbJ?XPIDO!s68eI^DFy0o$zn@r$!o_PV zEJFu0NEDE=Asz?fgx*LnE0FF3v$S6c(qII+-7eXqPO8a3+~GZ1phmi>M1jS;bAkGG z3M`7T6TqSf1oKdH+iD}2(zFVf+7nrAL9u%4c~7>J-q2{mt8jC&Dt4;|EXheM6hVGT z)VEFvEqf7mc^(gZA@ig;?H*o2+nzfG)4V{{f0M)`rZyl`7P&QPOZ#GAPK~;#KEuPI z^6s~V+cYdiN3sUrm0NrzsEFE_B(NbG11Z(=_VkWQdS=cE31?vBfWbbu`^eHnHWf^M zxVWT7^+ID(7Vnn>kB0Kgm6d1B+~C! zq~4`U+fF>tg2V5EW!($~Y@p^MQ1wZl`?0c_**ot39^2F7>_Eak;ZEz?e_@POHH!LW z!*3k<$J2B+tDIs+1_u6!Wi{MpVx#MRTl3UzILGPx z!z)}^RkhwImnkWGNsjACApLhpS1;^>ucEXIs$@4HuLrSEAA ztVq}};74{^$}W`G20NMqdfQ}2y)seRe}iU8s3NYd(ZR#Byow!&;M;;!#w@&oJ&FWQ zIt$MC7`WPe&ri;PWf%(6v3>2amTa0l@grq`5Hn>Wx`Nv|n|LNPEiv;(Su)o#`#0hD zQu>cxCn7aM)JR_wCP<}`ZC1p=TO|OG7f4hY)b_ zwXRG|YymlJxRZ5nUl0F3ZO&_If&=NEctWM?VC{n{uQ{5p|6TK}k$>cX(HVdCOm$=} zW^~ktf&!X$%9wjLn_&6i1?{ckqsvX0^HgqI$?$L z&g(E96$}&=Zm)>eqE}*+Qei~gsX_k$w;L^ZS@-sU{#FQXj`Oz2^Djv9 zsZCDw^lK^SoDR}l0O=iY?)*}&B;}yz{I*`;2;!Y>5(+aiKXGJIi z>6t5cjjC(0#7`okb^Vwz6+6ryYza6S!C%8!U$a||hDqs+>k-Dr9#470XwhQt49A~o zCr@P1YQm&Q6K7lfbcxtCGcOPS8hOB#3>XW9#0x#395v3e0x z3LW=k56Oyjud(T^v*~!|j;&j?k^RNPeelXj!pQ#qA50V`*B=B8W(5CPakv{V-rF?0;h@unPBT!7B{W!Z za;NSZN*KeVpw!=QQdV-^8eA#_HrnLOMeedM%CM>CJEAyy zYs>e4UNvfd@nvVi?QEdn%qgSHtQZ&n=OQGQ`Yi9xPG_W>i8NFE)J${=h zZ-iRZ ze-0chq`d*ayW)fKixY+O##S5CJ0j?@4|)Z5W;I!(kzi?Qc85J*^8JgI`4bDEwN_Rb z5A|=oePR^~40M2F@zHZD?VQTp)UnCdLLpm#efpj+;0g~WmA^OZ1?4;ZZm!ui2o`6S zp9s9dD(4gJ_1)Ftr#Vq|lWeMpR|N0WiSZt@T*p^6rfnTf<)mgX3o7Vf51>utU?@wA ziG3XrS))1MW@?5#$+7lkTtgJDv zt7wP4TmZTq_`@~4HR#TG80EIG_f6N(S>oFxFbdOcI%wAY#X$6fMEq+5pG)*Jq5f2R za~3XdX}OuY&|#C!jEY)Jh&!CaQ49D}4^C#_hlz;jHuhZ={|> zj;BS^#7<&~mLz>XQngp}pw(8GV6mX-bc4&*d!fMwf{}f8Ef!Fm+S;OV4*Vr`tySf5 z;4W9(oQv;%B|U=Wn;0fMODX{A40`c-M!!Gzm5-QXIEOQo1!ltI7IP=I5&$Uqa|X#P zD1?&7a?xn*fZ__HK2r~mdRq(!ImSs|_F>cX9^@s?`r@CuLT$?sE+u|_GjADK*aTS% zrawB}Tjm00%L;8?qDTEQiLe&^C+QFf!a8ljX9~}TgBDF>NEn!vR<*au6ii5_etX$& zdFT2fGP3$s;p`{P@I!y=gvBkn`E%op0r^o_K0QnL6a2B*0miH7cBZOi(LXi0edhUq zqcH(JpH>$m2d9*c+uRF34`~t6?ja!_#B&M&pL&g(wz7H-^CMTLuz;DFnC62I3Du;T z>fqzQJ!50RPht5DEKkDmcbsm^K--~Q+G7~d1d%XYDCRzi;rf8qd*UM43ghfnx z-==1{q0%jL3C?P7#y=`5qV58}mjkTtfpA=Pnot}~666jo+CJMt&a=04ZkT;UMwc$W z_b4ep)yRk*&f8tI>jG1%f?~8^O!9I@^qif(wiLRfwKIE2q;y>`$rztsCrOmiDf^Egc z8(nhk&01oBP)!9TBa-0`MswCfZdG`c`g`*NmLXCL&cv$xx)skWvZAx)iY)MIs&5i_ z@mz~863U@e*cZJpuGvA@j1vd`4vR+fk%Wf(nLo^9Xc3XDjgFX-1nKKo0{=WqA#Y?D z=Bt3k>)+S2puTt(563fNU_RJ3>>syw@6n4(;k(Ib9@New2^flsopVvR=_QsB&k1=O zR`N(~?GyEjzsPRrb*vaI&q~`9y)zJ`>rO!vQ5SMo<0jSTx+e^s%Cz5tljIe{pb)4n zJ`mF+J)p+LE8Y#Zdbox{W8ODvV1l;bH1`0Dg$y~>0u}o0sb?kMn=1q#@6ZW7*s4ma~;2RaPBGZ!EoaMv3$Rew*F{ ztdyUZ=Tuc7@6U6C*j+biZ{%bfR|pQj6bblq2(Gs6*Ff5XBd#9=a4!K+H@kgovWzEQ zCKc6g?OeqkuWAl9w(mikIRlYc5hD>ZqBd(OA7fJg`fEVy5d5Y||WnmuULEp{tHgf}hP$Q1QsJfkIuFYuAwelD; zQH2M(AKEa!rQ+b_3g3SWDiQC2l4AZecI?0Fsr*aBOG{d3S2#*ZlSJI9RHkKrUtUh| z8G>E_{l-kZzjGC?8YjnJI)B2q6}h=x5tq1761nm6%n;1A+G*!**Kt)36PXfG6e z4!D{oK7|Am=bUgK`EU0+@z~kR1_m@gL{>H};Pmg66tm6*&}QvDa2nANi!22wuhp4D z#}2b6$?X^4XY|GTZz#xotPqd+N7Qjb{FZe!-E&iDI$gr=9LG;-6u;99f-4$i zi$@Hl#lggNRe=5b*uxElxumfdy4Wv$Ycz>H_+AIk~f5d~hl+*AkOW zux0VqU0hOb@;$7ctV-g5+F4%C(f)b)unRe($xQse%$p7$X)zmmIuxJ{x+sRiheAis-ZPIwVjV64@$$r{Umc#Cx}a8g(N#!6vTqUD0!w=}R>ZBQC&`i$gD z{-MqltgZcX;x&}N7j7fc&YXqsO*{X^Ww>=*DLmn`=n|O-^(SKw%X~RmrUcbgG`{~H zz4&C$pxE&Bd&`-esryioQF0S&#7-3D_h zC?BV>+e(>;^UCi~DDzX)mSk_3E-IoeP6Q)VC9X8spK{Y}Nw}2H{F?w%}!Fy(0{+qWCa?)N{_%kTq)GCJU3; z>Cb$jU`U=QGRr6--p3IT1q_+hZL8Ir`5a8|RN}bR(zt18ROrF98lmsL&x7B*PgY^# zMu}yuIvpfg5temY`Y{;v=bW)40u59nG2m8l8&0eK4pH4m2qOD=hj>-v|DGpLmOatY`g;ir_o{WFi*MHyS zg`3&`Wxb=|r(yO@o?fZd^3$ZFA__Aos}SVZY%P-0OXH`Qz2ffWD_|ES55HBkl;x=< zOMiYuN$gClvh7dKO4h)wF~#`QaQ`R>IvbdJ9@4JBN#&WHsyBDI$VZF*$sAEH^+dc9 zI|*!Mbawwv4DEaFFPyP}KHX8UuEr~JR1tQGqxC<`Nt6RHDyMX7ZK7f~9+)^^;yxw3 zmpfp-gOpisM0hDh|Nj3h0KcP^_K(AHlC;~5Y6N!-1$p$Du&JbtuqVC-X{P*C6BU|b zR=0bVSz!YOW?HrmLBxU7k$^{x%5YivkTX*YI&R0@i2};>m!kuco23=+&dA8f@$~Vl z`nrabm05CKna`>66$}E4xk?psuq%^ake7<$i$jgpHB;cdXKrTV!l*NLxu}`knUtW=VP|aoRLle`> zBe}E70m@o9J`$VzfZFD5^f_^U$SOprLGI5we3^adver^tokRKUtqlLX z^5Z3}qa$R(S9x&N{WrU+9Jf8yWR7XXQfYZ*J&%Ejkwqiry9vJ507+Z&03vGww+%)| z9p!k%sydcn;`!3d_#knM>P=eJmc2Q#M5u^+3;l{9jc!GMwl4=?GDg!lc$ z-qTBF2`8O&&_WF2WF7fSe#Vx%VRYflNiJ11hFzJmw_qWvUwz_exAHoS9>Q z?7INbkAA!)GJJWu(Y$J{d~UPh@_4|n+iRupPb-LM&pQSpw?97P$%+e!vq+b}d|eTF z2hd%djzq)&scpx;&F|iQPWj1#%l|7TybXUM;4gO}^vD>Q{aANL>9H(4>h6au18prQ z>Zj(;Rq=_fVJCw(x=vM!Arrpy3hnK)TnUut=lk^)P}=bBEPdLZ zzNbF&ih>}eEWS)Slt)|dmza@DVCwWURarx?6vG#_+84CkAJUYx;hI`0Kq~<*)teS! z;9T`Yv(-+Zabp!BET3!v}d>tTl-K{FtI_&bdrwMq?%9liLEjnA!Mm&RuoGll}= z&`;~*i653lspx?T=6VlfPOouJ_SoAH&Vo20yh|+u}L)q zWI1hfbM7|)Z6FZvAxhskQ@hiGevuClC26UX4hJ}6^O_m*p$4mxp!W*RUvptLt+I(% zMn=_6q-q7-@j6rCXq(zn8Y-!kU%tRLh5$gp4q}vn9HX+fEvRG-!P(-UC1gvj4>|R> zY#8Y|&PG{(ngZ^bQ#0lk-c}boJpkSL@FJgso+=hKC_p1>gMaMIvP!v1Lz z6xaP2YVg*&&LWi#k_VQM1tuDUOCq_f0=i3fqJZ;4$e%VWOe6c zri9tU!~(y}Zd6uOSKpBj*gM+US#w_pRw!|_<`rNig#<(|w9B);C4>@?Q`$k!97<0t z%bKyhiu9xQz$116b|Y|D)R1cJN}9@?W3$n;o*2ku^k=KO4Nni5I}I@eF(;Jm1&l;kS1LB>jRv&yp1`{>Hn47NOIVqt829{M_}Y z@O`Tz8&68?ab<>kaFr`Jf`to)FZM%EpCeD#7oF~?)Q(xo^`(82AMFx^FGFEN)2}3T z#w$!d4OZsGK3N#idkhnuy^K3K$aULnw6GQCX=xF<`G&itsm-pczCpXxsxs_G#$WvF zr!UL{?}ZkP1x!EC{y0IuSXR$;w_EV9@^`gM{SU5PwtDKrg}BQjoS23!s=uOH!f4(a zlBG+%gN2M4PZYX*aQbWTUJc|@>xAw5^)gCRdGK>27D9$h#+70oHDmewsV zkr*MCjQGF6-#?X&SHt5{<*EBq6~ZYhVTx3!I9Yp|pIYf@k5e!zvI3=l#cr@X)q)uc z{b8hGMZ@VI51`}iXa%teo?Jp~uHa<8XU6^|YLo_oWM6jr6&0?aLCxzCXoItifXm@e zX;|$QOhVqL-Z>{%bSrj8twn;k)ASzx9UtK1LGw@{`jiCVLsFXAV2EsH9UW?{zK!x9 zEfpFb_5-d;-5lai0siHn->SKK{gqVlG6jFdbY!C{c5y(>l`|o4a_!_~#%$Jnwk6QI&v=;<0Ml67 z+}_&S^iaK<)nIVi$aQZQRr9a+vGY50d{3bu*+47BFhe+nxzBdXW=v#sRKy@Fi6geu z|Bd(UZ^LQ~Vd5=jbwm5F8s{5~?9*{!P?jT=Z={_+GuL)3K z8=boZ)3~B3o6hizpEh~8ds3#9RjZ1H{?GmMt8m-6x$DYWV}kh*jU+SbWDTYi!?q3O z+DL&y0fu1y`DC|wv3vZ$Ff3lo>Up)deX3{sF2CiV4a3&|LQ0dYXl3WU-scmXVepUc zV%0H}20dFn_3)<-Md6GTT7|yB(mf#C5^@aub|~xYUsRl}1_Tlb2zxe|t@Aa@=AN}w zb!4#!93<`NaFetd{k05XK{?6uS7T{;Ew&bF)*98eH<7VdOvT5S;oefkF|}qdn^k zBxicF#IjZmbG9i_UG}Rr#6H+l9KM^;tNqx?ycGu2~ik=qYr4{=8B)U=2?Cdn@MYF5&VAS_yFI@!vSJy@cB+osQskzhm ziXl(AvbBeiTa-kFXt46IYJ$60FmUlCx9={Dd2o8_s-zWVmFEQi5;n2jGRc)vlHzu( z=o#4`nGUE*t}SkGK{xYxV16J}B8Jg(qm$D=B9I4^L%qun0#dziZ@ zDsA{Z2jdo(9R1_+YTG^hv!a5uiS%+1_$$-mN5F+AKyJr<0iXx1QjPC$jwDGc*E^p` zgK#CT#TqW~_R7eHXM2a-`fIDQ27_>uL@qo+kgBL|OwIXz3Z{Ns-pSrmcQ`U7y^K%q zs^rzjSE^XU!6~f$bxTkO+MnjUDvvS$g{6#^y;}Qn;(PJ@sz36Ltm<%bT{tve@WZo{ z+0qFuH!_(kufUl~)l#Yqu2x}WhT*Lc?Kq;jELAb`DU?EbPWj8;@XF`Z%CNCod{L$? z$iJQ7dhw^=oR>5VxJDyer4J7eWAu=erRDwoE_HUiY^<4hhVT2d@#ABE1;(xi7KN;l z`Y~yr+^oGRS&xYf++h_+{c~A%OSp;eFM-`PiqnO;Ly5B zVfKybmA?}sF5@j7Tx&D*ic|ZGV!}Ch?Lf#&LnA}ZMODM&<^HBd6MXhM*yxZf2Jb0u z-n@c>`U<1LvNCPXzG*t6X8*V@DE)w-j;TUuK&y=0;cmCu-5A5YFhP>DS{1UJsvaR_&qizWk~OHQF4j_+spE7` ziVYoj9BMD4N{>4u=n8@laHApHUJmQ0OyEu5*{l?)=o^wQhOgeI^cdj-6C-@(l|W zJbPTuDODM#%|H#)q`yl8x&9)Kn#v#}O>Z?t{6AUMZ52hn9>YO46%-?1PnAYE&)u1@ ztYub`4CM=&CyXkRDl%#o28yIL2oJi;&T|bTo_>Hq+fz(L|^{JiZTe z)P!f?GZyGOEp$5#zQ)1wcwjVTw49eEv}mZm4w`DNt{g~(MRHSua z7~2AIY?btoPg(X%OLf&fHGL%>JEG7)HtQ{yoO1Cvwse9pn_Ah>u9vg7m65l7<~!#+ zIp^8ko?7qf8eIwAKZPz;6TZ^EMg*a%#Na-a#qR|2!OX*`NLk)~;61}zs`LTlBkbp+ zLe|E2Ln%Sn;H<{JqA@lt$nB>R1y#n8O{4>@Jn;&b@!sj@*gU6_(~!3Id1hcvmG5OR z$%h~0)|%9EDvsaJQSsDrbOaQGMD)`s9XzV?hj}Ks6*oaS|2&(hgg4I{kIaf~a>_tz zC;d6bWhQ+KSO&TlHynnJk9+!nkon)Uzj_yYdS6b~NQ-}-UWL(Qd8!o(!=r!t=Gn!1 znHn3}Yb!M?_;jCby&i}5XyrXeew4{nqn*_r9MR3SS^=2ERFfKKBgFYqnEGt5 zuI}tyjTIpCYT+!wUpF_;`^aBD-HSnIW||$jEhl@_Ex_fOJ4*kVEzYoK(D$2 zfW^LjPy5#t%Hind=H_HBz#V51!!g@@k$Yw&p_^~I(a_qbcgL(~bTYowvtoBw)`3RT z=KMUyQSZ5BAQwJksEjN0VwuY)W-+yoxwSQyFj6tGqD>Wgc+9SSuuqz0AGHoTBrtzD z&YjnWhn^p^XEIj<#`2?Ma>(J%a(w}D{^ERSsW^~0BO)@Yh~}?Sq;oDXvzA|rFkIp@kL=j2Q%r(q72Qx4;IfB*RT!^7j@58LB*-+N!z^}3!< ziiLb@;K{Mg+%75#D}w4>^&u0-oTf2ay&Z5Nm*Ta4`W@sutl9W&mCiNjgJ)$F3_?|j z&yGpbc$Y4IlwNIIn!=Jt&0XzeSB3k&OD+DdUz}&eKyDbh365Sa;%{T*1jAeWzOqk4l*Kwm+ z8*#e>7KYEbc-yg5jk9}-cu{_b{?WKBs~GeRnuOg6v|WZ`Scj0uzhLC z=U7btM{nDmCU0?y~6tue=-`0Bk?~JXm;%D8miZGtE zYAK_9yf7M{sjAcP%iGnbTVv>`-*%>23KG5Wo)}I_Hef`Nt)p#)x=TrKu zy*TeCvKc(ApYX@&qw?EZdeGNemcHEbF==FhlZS8p&lg!MYC)ACU`I_10;8(LbcxHEzH2FqM=5YJmfyBz=qq(=rO#C`(5?4-I&%hHek#c4Uc97*+aws>h;#h(t*c0hV7AKVH4fPL4$MbFhfxqac z<5Jje6U#qeM?5^%BQ`7*zlWx|ff(U}jG>81{`>uPY4p6I_@wXQM8@vk(Z7HTMC5-} ztz+rRDu;sNKqTr_pL`h9=r&FSc^T(OWxH+H$9)_{qt)VpFpLNUTqY*!G_$k7z3ekt z3oz;m@PNa%?JQ3mpZT4P27D^;T+3YgZckauFiIvr(btb!nxF9k_{ZHzX?buDpi~^; zlRsQ(hPo?g1jmbCI}!~CNJScm40`o!Ny+j`631kOa_-TqX;NTnjefcPz9dM52ID_L$<6>rq^D@DHxTdM0r}q%$67^9Cege zezmHXzkakq-vi3J&ga)31UB6_nRTi|SQ3tpJLuebaet2N=FH5puReX?7f9b(joRLw zbQ|KIm(xzJO?E|++rHg%DpsQ}kGH}WGw;=*dV!DeWqh_#5e5Hu&gI9i&CM3dTH7z3 zeTXu0(gKCwOR1Ni|Z{?zT`i)hMhf2juoRCi#a9;|+e0iDT7Q zxxxR+vao0-vc}~^&EYhx!*k6rj_Y!~5ti9PLZYHK-w_wt7;B`pF87zftzR`fYw1-j zG=1fEiNRFlsZ-<2n)GHdv^4@?EoX{2LA#04j9IugF)p( zaq#(gRLutCv2|7srGtyVS*!IM#QD)Ggk7uV|8MaULm)vVa zSlh1;4$}n<)?}rvsC%D{^$RF)1eGm5T{{J7J7AQ?qWDTJHeG^Y@w=KyjZ=k9-0Y3N z3lSW3T??DuC2PK|3Ti2}Mo@#QMM@c<6&3t)(9yAxc_cnq=1H%}=|ZT~Op<1r0;`Nl z89rF&W25uGCO+`I2Eeq5^2ah-OPuebAG~}8W(&0HExARW(9?3WCZn;e^8Z=X`|7X? zR9PX20m9cEgp`<&#=r0j@8fl#37Frnncmc7-_*vyfWE%OVpyx*DPHYox~rU)_e}TMls=_{QnE z*_nWo1M2Ya*$!Ls>CjsYWEc>7FX zkVl|sJC7Z8SjLFhfLAN}^=-z5<9K~FFzAEvhS#*V{PFLDZK`T!Ek0YpPdZkY@XLFB zU_g5Gds9>3Xm#;DuNk^CZ-L#0gX@YaY%Lrn@b7Q$mV?Q?SdN*%D)R@;N524(jI0LT zdF7rR6}EJigYV?9{8akp<*o|+G_g`+SUmbNc&?HqWsJ9BbIr->_OjA!I1#`Q89(K| z0PE{aLoqoz4d8d~UcH73laq`Z6TjziO<5#vcgC4UQtrf)YNP~p&2};erl2=&XV?w4 zFFk)@aOUG=1av`WVC+7;cFdTzj7KYh0JW}7Gw_y_r{SE7@`7OxY`Pt}w0xmg~)$UVG~ zIbAlb;O&iS_ybJ7-aX=2_VM-hAalB7ej4 z2*i@!G9K1-y!ZMVru!-UHko*(FyVbun6DbAZjTX`oscGO!-pMs;?|Q_^x~KaS>R}68eM-(P2OqR&tE@tKt1?lMTO0qK=Rs3~jMdCNo^n{|35{Lq>%La}EiEEu@v`Y&=qjmex zX_f87rW_+AWYcrMn9`3x*eCK<1$3_9Nupw+ z;C$KZN3f5b#)U)o9gW<6l$6W=TYQBI?{FLP2++uNa>SJo&^c)9*6IC#@xi1~q43qU z&!Y#vM&q`Ar_1wyl|X-2x7qrH$zWw}@GA@&C^~fSwaN5t=X2kD%&6ncZj1-%m0$#X z>kS8SJnqIW2ANeg?(BIvSOa9`_XSD%$@U!m*iJ!KK~~m8?52W+>2r|Hb=gpXZtaB+ zlOokmEVKDcO$~7jA8H%$#k{}%9zS70*!&=wRrl7o_dm5bZQ)}NI__!(`k@VOyW5$L zOFybo%Lf3Qqs5%3S&rMDypqDlJT2+kXa_82ihEFZS{k@*rb%S{+QJ{jw{FD1>w|-0 zD%KgxJtOwFUJol-*O(sgW_@>MhsSGM{!9G!rJ=}9;S2+3J~tC$pn^hak7n#cGj(3E zGY#qJTPTU%JbLJuqdcD0$X^nAF zty9!}jN`>GMeNn4W&9EN47Y)>9^><1T(mI_V1)vf1;O)X*NtIJa9cC%`W3|s0b4jQ z6M0v%A8lW~8u8BhNlAg_%d(8lp<7Z*&ubpGlPYahK}sTR8Yk-u`(&LA!;8bR;FR1e zkWOyu!}5Wshq-z?`7tzjF|km`=9libM+9y+;f@J-hOmMf>PC_+`J!V7%X>q_ zJomQDU{4x=V!ty^;{u=iz=W%ohA~6FO%XtxH{QZk3!u1j5-@(2H=t&Z*F;w1b4972 z`QaTz;+UYdfd=B)|7QWx+-y6Hg44A>YPXZ_f`qznVQZi6)LM8Pz9z8#ECXlvxNHkZ zrM&_CzUQ2 zx8OTDqA$g!+>>4-QIZl>OB`e^7wBA}6LWWJW>0PyX(exUmwb8;csFa+uWKBFb6-=KgwRm zMJ8^ad^pRrMPGlw_|HeQLlvHF=aPl%fP(~(9lO4o`EFYKbza+&vQ$dXe|*NdRhatk!+|`B*Qw8}rBBJ`!zhejuEeh8gd-MZ& zQ+lOCLM-nB z!KgNB^-A*Cm|oC7`c~@sI{RXJ3oYVYTH=1D=MzUKfL~YNfB_W1Cu?hYvYVY1IRy+) zDw!0E95V$Ypw2GN4Q;@35MN4E$H623S%bbaZ}Q%4iyJIJEr~GZCHFk8UdCT%_+%`5 z<9y9DPbfvWXy4>E9OJut<)Oo88)m2dDpBC4}9&%~JE!$22$aT2HNJX^$ zIy|(|uLl><15@(`IXNQy;FrTUz2$ahEbGlLt{RVD12L)@mR%trUh5f6OYU0L$3lQV zUvHn`Idp6hbV3CjOM_jOk&l>WdZfrm>gqPQq}Unw6)D(#x!objs)uoSF$=l0r86uUv1y;B zj_d%8$hoy z^o4b0_D`mJCu8qPHWh~L++BF<&Q!5-AX{lw6A9BC&QE*3WFGjZBQtY4f@5ydd4EhF zo>zl8_YQ4~K|F!OnU$D*{XX~DT=$MtAlB`Jp65h-3ktA|Nq|!@L&S)lCTnefp68Dh?5|jaG|XX$K6MFC&by%H%&;8{#g# z8zFsJFVvrI^8e!>4FGYRq-o$Ue_nhTGc`8{ejT+Gr=8<5^Q_qS3CZ#Gsa7E;l=F$e zxi{5cLW_dbbA;OrA>D}~7a>VlBo9?Nb~g2kh5kLd_!6;te!kl?`L5dZ%;xdmrn2Jr z&`E`GJmm9kAJz~^yP<^0M&a|RCWN{^=$ z^xU8O(G&=1Z7t;ea%(t4T%nG3jDy}XMT`dq98r?iRJj}8P{L3MK^tEU8qnW$%Z+)1GNLKw?@Tj&gJyky?0JT9Skf2RiGHTqjp{ctnVoUrGn3;F z#*+e%PY|*f;PjKKv>9db$Z@WB^IPQ_LSpZ6GGo z+Bi4pe!ak_-WW4roT}*Z-MGt8A{W-l0@s|b1d?VHO6~qxvLW8=Ud&j-+etM@*v|Uu zFfFwlORfXfjaeXJ{-?ZIBZ@Dr3i^okyF4age3%Q`f^?Kx3e8$2@ zl!<7nQ}k~OdR5Sg%jwo>VG(UGsC?6_>vTTnWE&{0#99vB){Yd8%1<--a+*ubc8|(i zAIG0A0aU8ipg%lfIn9QpWAQ4o$Yv zUMAtX9f`)mkbfj-_vQ11{EzL?D(Jhn`w)Vv1Mv-I=Vu*p`w{ea#Zj(%YNpfoJJi&k zvkB}BwR#^|)f--2D8RdwsopP2>kKSl9tnd3eOwu^p-u4Y8POG8f}Rc>vK zXKF^9XF9ab)B(%j!eEGeFUY)Z9ohl?Rj(}ptpq301IADeA(T*7zY3c`)2Fc$u;^}e(N3VLNqD5MXL&}skmSv4Xh0o+tEc7+G`9fQ09`Y}6`Wnn5j z&wC@E?LhB@w-C|y(DB-Nl;YbTQb0V$S}D{gJH1y9%uV~7d5E}*RSZ^n_$Cr`4s12h z_j1jFsO2{RN2w1W&TjqMNa?uJ-;NSw`Wml&wWMzLt`O%}bToXa{XD{8AOYAI8t2=O zxW-tLqOSRRFa+*%v@9R?(bUOG!^}(0q|`w3LCgdAlXRNxLw?XL*)BFtcXrfkXcB?M zC~F7>pI$zn)-#`&fSI}T25JYauz{2Y5D3kPHlQ9JfZAp+*ZUiF0<5K(nG|lGSIRw) zuf`Dcmk3|=FWv>tcg?Nk6yYwJey+TH?#u?pc%Lio8iBF2B`mTFx(vnK^Bx|mwQP%K3 z;B?L2#UAz!Ep03zI<*8~tm6e0{PuQ6fsv#nYZnQtWu}l%ijndd4OZOAb;_9e^@8{C zo|hL-=JwGvfFmqVaVmYjyIVIWHl8`^s~J4KA%DJslF_iBaMBeN9iQ-LhC{yO_I?}3 zT)w#6$0lsaVT(2bU&^FdA+$)hEKH{F(ZrBv+ef?>=rfC&pUO5rPBv%pCbc!gGNt2=xb@=H@@$2m1SXaDPCSg9 zq2+6l@g-7A&F&SZWn;y7Qi&9zyV7Z3+)?*w*N_PgnbnnU zwF>6;Mdh!LZTUJaL5x<`2Az847BekA?y^U#tHZ#g zxo!d4a{8xh?qm-zUAL^nHu44eAMSJ%1E5~Zw1O7Cliy2EXL6(9$_g8CU2KGQpbd~F zv}Gqv5wXP*kYW99-R&Nuyn7M5wl|DGNjX47s=2vU7Xx8blrWB4P*cn77wY=jhwKmm zVisS9*=IT0o<-NH-f$G?L4<=Z6(@tB?;i4p#as1VE_1O!nZOdqSQ%m}IxnNwk8s_B zu+SRgt1$ur_w1dN2xO{>zP{Obl!~n84M@uVm!D@~7bWHSV~6A2_W*QA9XU}lw#}*n z^bq%)C6{7)c^e#3Qzlo8i@w(~J>*8KgJ z@6ZxjZD5RN1omw`-lb8&TyMd@3;9~7C1bt|-xzVKG8J7GkAU(i_`dY;X)!Mkx4c!m z-)3oHrC^NEMRky{KzI$1-Ox<+4}6qDZ@qa_B~W_tMsLwM!Civx=exH&z7)r`5zixDT|{PmKOe8#Lq3Tn2)@*dEOxnPZTRDjnoYj9aQBi(dw#X( zQ>=hMo|5zNxxRmU-;^E$$s+V80wK9JV#7IH?_R%K#fMHA$MZG^&#Nr+JKSna%V-67 zT7k4}vng8PM#cC0?RqJAGRi_I#E6NBVP!`-1e++T#;z~l4~i!0S_xUJ&a=(0We_@n z7^X{{NjEB7e2;!$%Y|b>N^XSq7a4b9kbe%J1F2~O1cJ#?D3H^EYA2wG(2+)0fh{)szT!?7Ao(|mv$wFTI(9i?1wKmGUXBHWK}bJMxB zI3;Ry(&29Ou;c)uaMQcboi`jNSU=}{x&TZm>ssj>)SS~_fC*4y%4w?>+3tEJ#`Awi zji#o5z{_n3^l%SqNkpxaV6P-wRPD*{cX97n zz&BVqZNKhMAE`{k8M*M%FeYob&_e>?c#nLq2G}0%e=h2^Q+O=g@5?XX*2x)JoN>C> zdi1nYItWm845eBGc(`vm_j^d#SV-WST)$BVlXUcnb0xB@Mb7&GK* zdfKNsJm#UIG5bhWa_ZKYaj|QfRPo;_UpMgmm_F6J40>ho6r7g~`%J~wT7wXr4Anum zpB=_WgTK)K$n4M; zZpMw%c7FjseGN`Af@Qf3s1@Pa-3bU)p~X1)z(HfLmDr^Ht`=Ed_SqwmN<-0TkFGL5 z`r!p&Yijvgx3nRUz%i5)uMfYKX#rl|mV%{-a*wuW%RS(bY{Vi_^EB z{wuD5R}Z-cTPA(2pXiv9U{Qnn)|;miW&W8u{MJ&@7g!oO9C{lW{@Ke|MIFDx3Ky`o zHu%)EgwN0`#oVc>778Xjz9`NlpyR;{WdSJ@VrSG1IzA!qBH_+ty@b?csM6IW35ZWb zG-H8%d*8a%`m#;dIN2kQ>SO6Sbe3xsx1Ke()k)%nB?}WiOvhj)K$Y7yto)o@)rs7n z6!L}9Ba|_8v>M?zN4iJj_M11M>A?%}?q$!yg5OTpGJcoYk=K#Rsw1cT1)Ovg0#O59 zH$9)V4Qq#DdMINZETHvU;ou3M<&_5vKd!NBgemf`CCIryyB^+x@%S8vYo*PX(H{0S zzLP@nF5eLgZ>suc;C8&!><`7+ID(s?YJE{A{ine(83^V;56zjh{A z4{{NWt&xrzsDD3oZ!SRgB}3_=)5BnwmczeM<#Y0UIVB@z_rjo4^jU5t0*r~LP3YV! zcQdNh+2G!$9~+yWem3+eocxV~IOA!ZuG5%1`WL7kDpv6O@_grRg-`eo_U>n}ZmM0*o=z31hKx%Jgi3YFfO<_>yEPzgJ-tcUsj3O;WQ*F|{ zhUH7I{)d?!;|JZz>Rs=XEPUBu8gzOT)N8ct%4TuI8`v*yYWZaxXF|O z)vQ-N)4mj2m1cZ3{yk>gD=#^HG(V=@L^J%du9nMOOTGCZ+<_H7Z>kdj5h0RNr+>`y zGk;p|vtEh#>EBq)pvV%!;;y9`H*2f*EPNf2?z7e6zcaSogx}_@U{K)->qldXq zOVQPt1+_$2JGNNO##7Aoz{Wimi>bKU_k6n6mG{lpD#yW?u|vi$0H_`c9+IsCG+DFG z+m+9I-R{e80R`KU$8^dahA%QN?bp6%%=Pn$jrUehzZse6@GwbVrFw1Uoc^Ap)ZSTj z_Ih?7#W-G1+Mb~Y_|_yFQJrv`@((O(L$?&J4>!aPZ+7Jbu65=v%2~Jo_55~6UnL9I zU1*g$VrFh;Fx3Rp?Gq$-ZHw=EEzxEBhlg2reTwhIMtGo3alx9Y&KZ!bdD+p-roVhS zjTvOo;`0tftIe>~oRn=%<_wKsxZl;A;tt`PuNBmFjV-mcvOYsKAK8tyS0_Js&HySadv?Rc2(;I>32pxLl ztXPCqVp*a8IjE;R7T%9&v|93)j~V`%b>;@s?HW*;*ZM?Vyc+d^UtwM{x)>6V+m927 zQhw_Ay0cA1KnVXplu=&=31)aU>&Fv%!+gAEguLMfe6UU%W6bOD(4N`{LB2VZm`3Fn zhG-D7aJ}t(jfTGCXsThK-GDfJs`t^QK&^K#ZlF1>l*6I?43rV#U0-;xJOB|HH|=uu zm6!M9`!So0J$KMp-r_{P3H^pFBr;UH%U4IULxb;ou0K|JwXX=Zs}?;eT2V<}CR2JNuwuj+#tgL>7}!#Q z%}_nLp{Sqc+dRVt5)uE?P~uVNo^U%YiGYM{V&__a#6pvizzU*K-&TRi5+`K0g6EruxgI5C zV;=}}2S0f@?(>eh6nqXQDP6+x1RYFxL*|x@r`SVD_dZZG^O)ohv5_H5f;Zl#M-uNi zX^L8cYV6MpvbX*I60PzhW?{+g`k|$|$+*{atRe#o0T$rfP$;egB#P-r98@-sj5G3!(@gC`ea7pb+>%a?r5z&sPgQmf)Z6KI{+%{V>9Q zn|I@bQ+gW*UB=*b;`ul9!``FDwg;%GtxX|)AuQyH2h$zLSN{@6V2a{5Y|-E+aAqt2 zqBFti`bpsXuJU1@6rYC?W}6Iclpp?FIdu({zRQFKK#4^kbuQ?POmX$2EF3M};8&Z} z?E0!FA0#uVkSQ`-t^W?Mii_k4rrr_!@5~~t$=Srw{33xxV>ADRCo(xhK4gThE1e(x65O(TXkB$1P zS%L0JQ4QhW+-dK34-O8OzMoxufcY;_OfXKl%a+y<5`r5SstaZV4Gwn6u;IpK*$anJ zGTLgi+SrIUB=!13#omn2t$1UGV(p@m-YZJ$M<;C&96xn9Uo2F2uJ&S z{Q$ntiu!DQT`y$TPq%_j>>vlU{h&Xe$BpCP@a~tnEXCX@9dIAb6H>ugmm7OV;EklM zaf7{;u-yIZYggWHhfF#loTei`Aq3GZ1J`nLA}qhw>y;8-c*zjf{2Ni)NYBTTojN7a z3(r8Po3>|z0ZSloO5q_1zuzw#dZuD+HV*z$JzYwhGSJO7d-afLJo=KiljL56A~T^! z+kLvwEc`XTTM;cT&Jm=$D1cDtTsMprquyp@<_nGLoZ6>1I5S_tSvaJ-RP6`ei|uzX zz%VGouXiEH`8Dq;xxDONa0&Ld)t6JX8y{%Ebi#^_fgw{_pc7bH+z;qA%h4*#rA^mK zRRylNBksI?(QMi&mR3$R$yaZRuA;bV zx##eJ4-ZZ!Sc;6F^5L6!O>|>9@ke##=G5)ZEZmSNE^6xQ8InC)@VnB=Qe03;>3KD$ zwFpYKE1Id`tx|ioS$AmgqM=@2-%wN_^EvZA{=9?c3>$o2xkSG~ zH1F$(7hdRSr+2w!wDkJ!g3s$Yrw6jsHYf99Lt4y* zfI6q?;le^2Bfa(t<>wX@kb&dwK**#xo0E2QH2s_3RN>gKhRPJuT9EVvCeo_MJ zf3)#*Sls`#4(Q@iTLBjA(QN#=4}9S*d{+0Ewsd<`j0pqA!BU=Caj?#niF*@zy;mfg z1GwZxdRducAKb0G>yJslMmE(d9G20V`IgQAm%4rJ=tc94Dd8E#SUZ)rQA;YP9z_6L zI*Zb2V-?S%w(7Y%y}tKzI2yBXc6r&*(RQ?c=>G3?inDDW6KLH~AFPA^ubLQ%PCb~q z&`d~N@X0>1G^}-kK1!z4fUS7o@Xm?;ag#ZY{Pb zHf9&rR}cJ~MTeauk*d^d3HvR}-}@xLO@x9(KVm6xMn%7Od+W6}7e0?;>xd4B@o9bi zYqEUr82$h4yp+q@16a0oM}H#t#+`h;y<^%nt!SjAL|nA;+?Hn&g|iCwYE5P*b-0Lf zFmcz_&(#rA6U7dx<$Vj2hL79zM#8Nef59w!k&MRr{WWkawqNd)FJANy%XfCJN%#Q` zcK*F_n~R9HZ*}MNqkP37jB9qHvG8hx%z#ej;&gaGxEv$0VjuopXSiKUB^?SS*VIpv zNon=@B;B>HU%S&{jg}2F%fSCqwC<}1@MqnE)KChR{Fxoc@=VpXrimNX9-PJX1k!9y z1+>e?$(J8){P{xvExz=%;o+o^Wxd0|TjZA& zjizF~l|Y)b*?g`g;DP6ihdH77G8}hjQr1P7x=r@rYb@)nk>nuZyqe8%EVg6W%P8tH zQ5dCr+XyZJOyv9GzoFk0%{*-ODjcrZS`d%MuI>8b&+78rNTmtJ*WU_5RpKrU8RSpb#t@qK z*)5?Fq@Jbk82aX~Um+mKXhfQ>?_>a|8Uk>0oL;YzrnmM18kuUSaL+o)tG6<3@*4*S zpc?VnH69&VZ;RMhpdSwduYStT1OuqmUqf;0Ckj(1g{g-}9AhBh>#>R!x=iU==>Gxf CvIrRf literal 0 HcmV?d00001 diff --git a/docs/assets/images/roads.png b/docs/assets/images/roads.png new file mode 100644 index 0000000000000000000000000000000000000000..af99a1b28f9c33ecf268228c0cc535aaf4ffdc15 GIT binary patch literal 289186 zcmV)hK%>8jP)7K6v)Q??8F8iDVPw zy#h{^0s#k+6ha7Vi6_(fo7)>#7N^Bv^I|lFh`sB|qFk@n8kC=?@wprT+f%5V_& zsF*aM!hqn~b`hmru9n;T7le}tnO24K(W)V$6K+6S!0zDQt^Esoi`gpA$9XZ}f#15fp>O+K9 z1On$tx?}VJk+ibfppUDjJFD6gQW1a%^UcYX;1Y=%iJ1g6M&dShPI}N0h&i|-O)b*m zY-Y){t135=n^0E`QJQ4~AGqmTYm{d<8jV&}SCm_sodj?VFU!mG)ftk z2k-pWW-;|HZ{n8Tz8T2o8CA6-yHSj`7*y|qQ3e9%834?_^WvXgxq9d8OfKw@X4nh-y=MY@u+D|j8@EPa7Eu2XJ<|1D8kGDAb@}v0a8rm~3`(U918c4O;1gp)2*RwjCc(C8R*Pk| zT!1i<@*Eg|46#JOm}M$YRgo)=K2Hfke|may^TEgN+&kXBa7A<~D)oUBrGyq4fEkHN zi{pM#FPo+=hudkI6X@U>fD9Q$KmZatMbT=AvFn;u*RGWI5#3_7D#jb23m0%W+DXlr zTa}82AOMO0Fd#H1N8h_~wV|i@uWPPoi|P2c3{=!=H%hY@RCJS(ll4cC=6%-4T%8;#Xu|w z49Jl<5_@7mMhF@dNvfhEL4uB`s@s#u)v8)-?Ox(ALbauFvuUDIqDYLA7#i=_&Q(pb zn2g3%-IRk#QEs@NShP|Wzymn>|A8M800aO;K%|f0N5DkZB30MktExML($tm8^9S}M|TZ{L0I?U!Es=HAxur@#D#i~Cy;TLG^$0>*W{a_wQ6R>2d)N= z&QYa4u+l`pD7{u8^ozyfgCvce%K)|qNi6XQkBbG6tTEFXriv#DOpY z`bd$HoW#o2y>w_JDqrR{_MIi2Lhf7kwWqkwbRE1`I_rBTWsEhw?{uQtzR&YfmTdtS z!6(cHl^{li%t`{P00@k__d{Nu-~QKyIx@69t%|Epf8lU8lTc|}^geZ9i{UuU%C6}w zkx_23{9rLZ+}zlI>&@ApeEqiGxccOCpWm45&yHs=z3@W2JpAJ4AARn*2de5lq-9y8 zO^dG0jJXg)GMmqLzIVjqu3r-SMG6&OFMjFA z%Hd!z7$T9jrm89;5@wViiavC0*EbC?1F#4%A)^Ecs6ZJ=6C4lI$tdlrsS>|ADe84w ztxPf6Shm$!#(nG=U?XVR%kvP4JW}3(^%NZ07o%t zmNW?2(EDYMHg$$Q^nf*kDmN0l=~@iVB`M%5-~aV1S0=N?`Fb6cDu;s$S+;|a$C&uw ztpq&9Uu!hc(IC%5Jg@4*YP}kdCXtaa zDF>Tv-S+L1Ep_hW_xq@B99AYomyizHxgMvnzv(kE?Q<6?EN6QuK%CAFLRc zaY*XI{_v5D+2z7hM(fnnf`Ui@fD%c9Vy`eDh=4FsBoj#ykcyEgAO%4Uk|6_f@492> zW}%Bkxnq-yeIT?Hm^F7q1_S^Z&^y1Z+o?^2#d#mLw=RX=YBdyA2mt^&rVI(QXX=^O zNQ|IkNRbPpQlo`s1)TWsQas422xxIbW2Nfe}Ya*}F%wj~~Qs-7-Q#Q*x zfA)u$w`QyMWUa36Kk}6Zt_9Q_SKN2(1A|1Z+mQV2|Kh*9eCe5|pLy=aL)UNLJN)`L z{@~(8`;$NM@oW1d6P&IwH~sm^i^XJozA|aPl@$YRQV`9g5Vd$fMBxY`R#9+nHoG_4 zSl9g>2zETYP-Gj^>DlS*@bcA5C#Q35hjoKC8*c7y`Ox&zQDPVZ$1a4<`>D`Z>d zo7N73BSlszLx}zQG}LDnObVv*hx}{`0ld(!b*1mYZ== zj}KpQU|(R!UN+Gcuox?0T*#l#vE29ywdnijL!;^L+2@4WNg-}}4&&7Hfqo_ylrU;FF7 zdiCn%EX#;!y;>t-43Z>?)|#1P6htCY90LL^D-F?N=3@37rm@hJ=%^69h~ojK zv29Zgv)KVtlaz8ipQia`P-AVEDroZeBq+?uF&-u~XT%R5!;PnI(6OS5$|nOsf=CCmEc`~xS; z7GWJqq@C@-&HduaP|^g}mMTC&BoQWHj9!7)7!gE37%7rrG>D{`5gbw!B$1SaNcz4# za&8v7Sd=?9+3$lws{*r;UMVdMEDz8ur&&&9SrnrJRN_Tz4I;up69IGE z%;w8CH+OKosET}Ibb4}fwtHb`xvHEO(q$hMquSiw0u^;`nxEHM0}0JkK_FR8=pH9xrEVbK?m`V*sVo=wqWf1puE`U<|r} z?+rwy$QhhYZ~sZjcMI!|&drsl|I^Cn3Erv0{bhf?wKG{STh|svaZxFa-TnH`*B-hy zoZp`wRr_)0Cl9Lezxw^>BdVvKdi)cgc;f81{oZ%qxO?}N2Op9ze&On%XpCqRhB^*x zvf)%xhghu^%jKMXN65e|z}A?ycUf9I|HAkF(Leg1m&;Y~eV!*5FYf=$SAP0Oe&n-S z>!K+5BN6_b03ZMX;75XYX_B^WZ;V24EYLiZg+V#kn2c`Ud4Ko9*5S$F z{@%6I(|UjZA?6HK3JO^qlOu@$fTBS(u?3*j@yPHfYrJY(U&e= z_MIzByIP%{pB-#(ZS{RRoLm)*41EMmXgN}dJz#IGGNgj{u4`t~J4LAlsP6jlXe-Ny z!GqSOt?I?>baR|-jO=Q9N8r>3368Z4I{1&#KYZC1p}=QUMhh8AyPTB}oz#2;P%`)&$`D{_No3 zt;<(8=kw!rwYqrWY7EKwS+%iw5tWS~>#jzn^0G9kZDJj`^P!HR2M~owV53KZEY*X= zmRco58iiHt+SPH_oDYUHn;&d#Z=N2V7x_lt)7I97hB}yqj zjLyb@O1nhOm-oJD`}c-vfA5ShKlz_DyjAG#Dw7755Tc2}>`Vr?-u%`B0an;Mf6Q0Oeh zdUY1X32_^p$qP~g&t$9xqnwXXgc+E{+C%}(&d%%QYIk#cZ)ZPvuY?q#1yA+y{Ps(w zIiIc0w;%X|89vHj#7jmhsy?WuT`kU!j;8bDNZsXYdzUU>z@y_gA^0SDJC=0T2X41xO+)M$hb1tJ`*!ShZZ7W+_At$0xH3 zm#$}7>4FgI-nrCTVRv$PXFRYQBYWrl*B*Q5$_p=i=12aJlaum9P1{`i;w;%Ba0s;*ov=7-f}vY%!{R0dJ8U}TAmLZpCg4=nYkSXe=&6g+aqIv*A!<^Dh67nD z5;KrMgeuR<;QMAhHPEb4SH_v%A}T^_M=W zxK3cBNH26^(OLyqSJmw7tXi*8xM`Z-{_WrT+V6d>?K&d0xwUoU#*J5A`Tn)5m(QnX zP16J)vn>CqpZck?(Yi{k9d&&V+L3lZ9Y93ZAQmJ6A)Br{kDbTf zLx>SVhujQu_WiPJm&I@}TUE(mk`=?Icg}T5nwvCn!3T~Zu#eGdtALj0^Ln+~+1%aV z-D3~HRw=E};re)S`{j*t)wn9%`lJ~>5+Q+z8L2>B(7g{a^br($XqVNzX~E2u)-uGiH%u^&lK4vz+92J9ue?d{EV)i5hzEvS)5gjoax2zA@8i=66anq`=# zda+ouWaV%>GWf{GBrygMPOWlXJv}>o>hYUr$M=eanrg8;d+(9!gY#v5XF;yKP8&DR zYixVTND^?$H!L9Ozzp~7U}peD7BwIM36T)71*gy{b|iv=0$MPMXaTii26Tcw1A(Lp zNTKVRgT6nH&KKo&lI^>w(Wti2e@Agxh50AwIink6dXuJanwwm+S( zZ?!?J8ehzdF)Y`oFAm4*m3PmtKKf-l`dAN{fI}38D2M_*6r4##k_DRM^LMww!KkZaMMGei5Mq2}G<22@ypZm8H5= zU>4IV#<;(;E5g&W`w~_H=bKx0SPt&onqJ)bq@f+}pl;7QKF&wHu2!VVQE?%mF$i_K z@(el-NOBMb6pUW_=}Ya&i`!#&>)!m*Q~!Rit`XU;K8xM4GQM?P({@{v!I0{EZ@>7| zL;L5mX}R;jotfD212&(qU}O_u@IU;c-(FVc#=}oN^UQOpl^4JBz1M#5$DjH1<`+Kq zkgMY6_!?6lQ7NFVZRh9HYPBYyx88c|H~#rQYntYf#~yy>lg~VO^MSL|)4%g~{`Rl_ z>R)^A+2`JQ=e=)#``d56`F56Nf9r4kt?_sxga80aX%G|f+_? zzU#Eghs9psk~T@2;(T@IgeZ^spGG|_|n|V3en6JG`HuG}acWdX@CP__VJJ$zhBF&LOz@TOyecKJv za&tTZNP<{xtfiou)7h<;3VSwR&juHsO*WoTW&lxXASYD|jm=U3-E@sm1T8T{JUX9( z?*JlFP>O+~51n&;wO;joH!5< zz3=*IbiOFJlWgBbg;qt5r~*epGz2OJ4z6QylR@fz-F54}tBoPwyYYA%)F^^wbN~#X zfvvCw0FEuGx+o&Y^=x|TdoIhta<$&rcrde!A<=Qb33z!i-ruK0P~4M;MUTE&rQ8di$-{>nET3 z^rMenYrFH;UVq_RfBJ`i^FRD6k3PCJED~}GMG2sQ2mp%+03iYjA`t>1iAW4F_LNym zYW@DLm$tTzHn3c^!@-`l8xm7N-MTJf5DF@RWw#FOqBz2+2thz1SV}b}1g2g!!TBqf zE~SY+I{vV(jyE^0_l+T&n9bERxw!jq2&jx(_lL{+I4eyE5WN`}7t$mTiHi}@mB<;O z28v2muzX{2@7otP-Fvr>E`RLToW0hw0$<0~L7FPZAuo!0aazV%4i#{BG+zxbJ=9Rv zMdFAAh9O;dYOs0zpZ;HeaQ{F({K#iM^{FQ^>%RG?-#R|}{!f1SiR+hk3|X6Pgs4c+ z^=>&`RO>p?cClQZ93O3NPm-}Ojzdslm*HwMr4MrP% zC(i4#+_q+<^?<=fK@bFFKnEBABY=RQh($>W42qyMB1`X2PtWg^1sN@{1@!_ai%mn zGNeR#PJHjZ?*nPYC}b!xDc(6bPcR}xKn95dfB;CyF?QYh{N#R~vev!GdNj_K>#FUP z#G#>~(kSQv9FgT{g`Lt(@6UF3NAr25Xy|>yVwBM=9AZ#LAtJ{>1R4Q}N*e{Z@IIY7HhP3%evH4JHCYB+Ky%O(98f~2}Ddgyk_tA@E3`&Vn-aydel`t`( z5P%g(0F^K^dQ?G30b3LxX#4iQbJO5lS?(m+zKeu!%_(0D6&j zwK!Lb`>xg|%Lf-3Q=tx!K{QAPoC5=4r}Ro-+IKV8)yRfa9x>b8xZ%1KNeKoZ0brw~ zck8xUR_k?<4vY<*o4QC=4|no>lJQ$F{mvj4w8i-&{NqAN}Fm2M6^tpM2)wN3R_o-g)JvR}T)~`Ah%KbI*M2ruIaF0v{1TjuM%p zQUm~`6d{TTGYd1ZO0?~|3dtQDytBJE=-kqWkmp-jx(!meAVP7mKEs5Qvgm#5e8cP! z7(_S#uwoBIQfg9tRSyP*QnFYbC27!#P;^`Q$#`!yYZF_JhGWu-!Pnig?v_cWUGE^I zMLx141)|XnkTU_z3KTV}`r!Q5H!g35cRsv(^<%%{vj=J+=_}iw`@Xh$Hl7S;$G4mN zZ(Q8SbW*%|?`-p-ryVJzm}!eanRKX&$$R$>DY^Rm^NZ)d^Zrv$KmPR7PjvP2n_vI^ z-EIBUQ#;qLZdx;pL2Fd5_p{S!wXTb__(<9piCFD-uW!gvozB{22Elt1=K>Cl=EH`Fh=55HD{}P zuMhM2yjm3d&m|jAfGMLRCD=>nRcDk^O!5&zL1GrXb#R&~Bw|Eh5oQ4fgpV+wSK>p0V5qCbPj|Z1vb$1>m#^%)r4Ii>uXv3+JP8Hk&r1!6l_io0Q)Bz}{FBI54wP zgdhr(QM#?$?X9h9xw6p4^_}C}FHeS`a(#DN@#x0z!qYapfH5sZFa}i80y>ot4x%@m z^8up}14gTYrKmY*jwFDh01QY1s01W}2XsIRFd+tzrf(0NKNlbJV$-C13>FMBuw$o4 zp(xjd7$wz-HAVv~#YV-dKCjkOqTpOii+z)gLG`3!3&I<<+}i``zyXOrHMubB{iD`!8K?vMBAB%jeEcSXw zZSP!YE4LnRZ7M^v*@;aQOZ*`(5-{{}kd+(baW$VIa$PNKCN{(1a6H_Dpr+I5_U33l zKg+UwYx_dqBcSShy{b;M7LCceYDZf|o(<8J$QgrSB0y)mgX6dUA^{_wr(UBA9VtKH4F8cn1>si9l)${Tl-JCc=W(@xc}}O@4xo)cR%^5-RGXWnJ0O0pn!y7HCr`RotR`inHWt?Usv^N zIy?LBi_ic1um97kst0B9)vx}gU;Kq%+S%E4&L16}gb+Z$Sl#!%QaBtA%0c1!ZaJS> z%UipMx<;hQ@LK3LQag#_7|+k=@0x@O)74yG+X%kM*J`h!BCAF>7YFK8MfX5(t zh+r&&>KJMfFKU1+27n|e3Baun^|GFd8_*gD001BWNkl~BMOG-loeD#gQMnje&>}knN8QTV(-~x<0(-^@MOud zifp|`1s(ekQ7KZ!xqt`fQwk!?B7%g71OUPjL=b~Q2T~KQ=kxmleL!uCJq}~5M%EBZ zXDtWsgl*Tad{}7fqB!BK%=QoxM2(0nkvR$o5F!E!0H6Xzq!kbdk$B~o^ZPG{^}CxB ztU`Cxn0)`Kjfdkyua&K?4{N1%!+N z&@qyTAwh***WBy-QxdSr$RxX{GgbfuK_UVQL*E63I=49hB&3;pt)fV?TAetzLZm)q zgYk|@#K+#+ysbgO0D%y?t~&&r4~KMebWmoKJliLGk#ySo79a!80gxyHw1Azp@$m57 zES1o~c(8AhjM*27Qe54B_dD#)w>FA<_t#e+_%Ww;sod_x3%cmUKqelFBCor(P7pMA zaW!4dZ+%cb|NQ;vcb|Cb<4=A3>N~gI`}Vh=H_-p$Pk!#98<({PW)Bdwh7dbV#1arm zgoP0RkRXIsAs{3q#%R^{)22QUs!ReQf-xhbN4=vg8yugVvWmlT*}FD!ZxidhcfChe z>^V=;z3r{#?9>`sEzSnxV!D`VHQXFuR-o&8CbCFUn9XPVd)GjQB8joKYNl;BcU?aj zk7mtjkq;*61qq3$gq2~5173aj@*nICtKN4jyt@71v(8LhGpFVr$C+T2Xm@h^t!tC4 zOa`yLx4!<&Pr3Xu>Lk>QZgFlYMhcP`$~MGKdLEpf!$13tKgzQ4=RWr=_~h$<^bKv# ze&tubFfNkldW~8u!_ISL6!?g>dR;H)i`lwfzWCyI?%lh)v9Yn3FZcH@Jp1f(!{Nvn zyIQUh(FZ3I0U*ung$ujZD(Cvy`SHePE?9~9ve?MeT?r!q>f>rv-_~gzyi-^zxG*d( zIUmvtB2QQKp^r-o;yKu)G-la0yF))og*ptUH)3Zph3M>ep`jRo7?HpvOjbAmB+rUvMatf31twNLlh*m>B{-q2T>Y~5n!z( zRiM~w35pp7PzXQ)5DTJaRDl6w)Wo2b>)ZQXcY-X&j!m+QIu(tAA^?aW41L!V=sYPz zFgIz}H2^NLF~n**yPsIST*tv^C&`EuiC_%c_bN||x|y}jX9Vf^G11Tb+rUPKFYyqkDH}dlx@z1~)r3 z306=Aj7r5sgRZJ7&C;Y$>-ucf9R+LwCr1bRcmMU9f*a3%{+a7HFTVBmz3)8#Z#Ihf zGe7Z#2Oqo|e5Vu}CC)b}(HinTh=A56grK!@u_Y8>B(OzZde^S2lip29H8z8FT^ISb za5)-WX*-^-j>nUNA+&vi3L>-Xee@iCDAH_uGCDiEpC!t*RX!LTo-R^58WfxC{cx1D z?TPbCYfaz9t<7s7h0>YxE^^mY)23T&?GIAlQCEX&dW+mYHS>@BqJ2yW&^Cgn0XQ!D0@f|A}Y;2l*yzF|1 zk=5pRUpV}|uYLEq=f3#J!w(=MtNAZQr(CQIsP15k)G*z|7Vv7Qes0Gae6|?|RoN>_mEFlGF}CvOziN9W!*R z>NvTwVj>6P{Zbyc6W?b2F8z_yE<<2_|cqXw&WuPDj0yn)J6ByOt3 zvF}$&VnwUgOBZRpy|?PR);S;i{?1-TdFW%?bx}f)=z=qeP16(@m5>H)F;S?92_$G@ zM6a=j>Ue(p3k{+t3kmD!bWa2rz(ppL5Si7g!t?2^zD+oifFmuW z01!kN0T6*ekUfZ-&rcX)q$D3*AS@MFVF|vqNpNmW$^-e??93!qqAv3trAiS507L`? z1V8~q1V9lG00dB|i3k9hwEzwDN*1r4eE6+V(VINIKkI#Z`H_$R#MxX~HNv1QDFo>u z))E`fkqj%tNJf!WU?6DmiX#c500;sQk`CYmI#dQRLl%j(?+=|jgDBdJOtOnQ5sg5I zpb$lv`>sP&nJs|9i;(F+ksSb-hXwv6|1$ z4)%7oG-2PHh~p$n(;S1(K*j(%#8y$St@m!}<9snc+#Fr$*ZJ1Qc)32V>iNb-o~f>y zeQ5lN>q+qP*5ywx<0vG^)T?MH8YN_H(zdNl<@ofLsK(^fwoneP-MuIO`#=7@{RH7HK^2RoK{rcPY9{-V_mcj1I>)C9P zDN-!LT$B?g#meYRJE~SKo*vuZ``uTS+WFLHpI$fTU;p~IuU^>w#h>|9symG!5HtV? zD-%ank4iO3e9FPdeN0yB1>qIHFzyvNkm`)5eBVI5HHXJX@C?( zfE(8zy8a9!7(3K<7gfd@fKZ7g65-hOEh6SN2hiSeo)yBecWb2`Vs~_SXD}${^W~K* z*FpeP#(A$a9UUDG2W9jD1=7SUm$Ndr8(Z5aXG=6@Jl^1#A(SHIxkc%U0WO!vhex*` zxPJBYU|FVn7(8s2MWfjwpfNhQZn-+? z{d_VRpPbGvUA^K0dMWPR=fD5=f9r{l{m3IvU%GT@>#f&bdHvOwuU)p0BEd0JVtHYCJ5icP$ReWI8)Gsb+{y zeAP6hh)72t6063;?EK_TnqX5ehT{vp%Zhv`95{wDPZ46&UVG(xFa2l#@n7EGve7$Z7$x*wWfW*b-a8;llgx!!SM6$5RaH%Z%#28`4@887 zN@3g9SFc~(+#Ga$9l3L^wW;cx<;G+a<0MOVyaR2+vbop!b7jOk8J7D+zPn!akge=FlTi!2lHoN0iO~%IVg36g# z2sI~&ED*ZBA;Kapg_TyBa{)mRgY)YogZ28XUY{3P-qdkxb1yFkRlA%or%IzRbWPkG z?+o&Rv2^#&yQ17^Qm!k%F}cK?A|^-*R3vIw>yxIQTbqPl6lTMG9J(eoI9*Rg@s-`l z?YF-p>vu2jUbuH3t~~M+GQ80laZ;;bET$k4FeHXn>+>wrr^mA^mv2Vkh*76S-KB58 z-Tjw;_ka4)FMRfq#~$3?-u&KoUwGs7m%jYPAN}03pGYl>Zxn>CZSph&0HsV(43yGc zbY1LS*9GTNlaY`x+XSr%KCY&-<1EjcHf~NXjYqq_>$K6Jcv-C$)glP5>xP+w_ld#H z&B0=JkXTu*&WFSOz-3vCB*sKr??ahpBJu3(!1*f4sPDth?)Bg@O@%;++$hs4b_cg^ zZ*EUIa4|{8oBOHr=kLBOi#M)Z97Db*>E6A=Hd>-FSBqPjo10~Kb^F2F_xs_chhZ{0 zS)C)e;b3@rvbcQtCeeU!f}F5;#ttb&B|*&hzIX7ie)k7AAAkIrXP^4;?&5=WB@qwSI@ho7O=lw@ zYi-GBg`imKNan3{%hbXL=fmn`{J~(DmQ_KRcCsC!HiE93GD>9SS4t%UvS1`TROBO7 zo8|;*adLidYkTedbY54WqppgwxUW~URkJc%YulYpZ`IU6Q$zm2(IE@CRzVD z$*wb`Sv%p3r~))vOUGd}nVJB3E5+&gpPo%;lf|lOu-)EVU%MLXHD@B=2tPuOVZpeV z&L1*Z_JdY>O$bDCf)xf9!p~O^>gM6*R{!E+g)kfp9&=VU&ILuD|BfI}z(aSK>Tku;45KoY_EB5*0loF3oZ-WcBd@aXX;o~=#OxK&Y4nVk^vTJI8vSYm__ zisJlieD}r^8^_1fB0dR$hE=lo%c?jeB#NvoHwh50t||>PAYt3 zW)JJpo4u@kdMbK5pN)neD}@WHmNrtX;#dmh?%lb4`SPXJyll7nJ_z;@XRTFLg4SLn zw?91nm;d6AU;4}!KK{Z}WjX!HkN!GK=qq3R+}3(qqLJXOsq!?9lroL;0Z7U~pi*5f zO;edzDIq`#N93EjQc`)(QjxK>)WFWSvteD-Dp8}^SZIYxOlR||sjahdglqkLIyp>Y zUM|OJwpKN9yEVW-X_Qx$NtH$l)-5N~(@0ZQH%ZcoqaI;Gq=|sBpil~H&n_P6ZZvnH zw6NQ1r`2e6{L{_#_+ZjBZg^??v(V1Z?7pOv`s{YAX}WUlod?y&zwjFmXOq&cuJ7&M z{b2vnrH@5Pr|~4QWh)FG;wWOQE3+z$n=IY8zVoxuH2U-_zt-JMfAoVtzqtGUKmEPm z737ixO*M0_)Daq6wc8ybm1zQrL`Ug-R!k-n?_6Ei0KkldXszk?@@v;G&E}&lR~Mt> zNP|>VRn_jsW8hM2LmX=)^Uiy3?pzua)j}!V>upyBh7k38!|`~We&0TrVH?^6k)w;3dUTiDgaA>GafjzcbuZArrNZ zgYNjt@q#Uuk}h>MzOZuOR1IAz$8iMX-kWQ9ZMvFps=RZ>Ga^uRx+M0C+Wtg zlC|fB>;@+y)SkS-niwL|*7^CW2!wHx;KBXBh*G6u$xO5PayqS*=ndDd3Ce>PQVHj0 zfV0{1Aw$VL$nzUgNMwgh9O|k(v2NP!rN)~1ydLzg19X5C3bH;pW)2`gAV~m%zySP_ zz>d))F$q9qLbT2=nj#QOc0J+g{OD>CZb=1IU6Md1;X&G< zJV&0DXAF)7p%7k?C9EM-$Szjte6=j9ISLua8HCVOa|koSN+2akCrXBa635I4%0xuK z;Ekz;5J{2(3uhsU5)Q!!Ln4&rjL6t>%&q}MA3*73G#PJfZ!A|!A)+i9Dr%V~c;v;KA$a*kN5X>hL?7F#C1fGYib=Kkvu<}o}Z8Ai&?wZ ze&XpTASh;H@4Poc*zx%M-FM!7;rUN?TD{qH{O`Z>XJ7o%XWo1F?azPeOMmeDfAk;x z=5N0K<{Q8I)i2lH)YeSqv#Kg%C3~H8Ha*l)Q>-rX&M`rHl}*+f_&}ajB)Zo6+2p(^ z7N+q;Bm^O#cP>klOP96+l%&jbb`)od8406KYX~j@ud*zzo8`Ux@9$pODyy?l+%!;;CxUD$CGn zw{_BO9I*(@j+_)Ak%$38000D}z#KvVVh7#_$Ls-EFj0UNuQ+8>hrY_zeEIN=Z(iFe zfy}{$UfX*)>O2EVfT|rU4hq2&ScDLeJj8X-g^^6!vyUPtsc6cJ&=hOE_29vSH|`_G z`x>}*W+5;jf{fy%G@H)=?ZhBNG6B1TZl8;7xFi4Cd_Q-jy3` z?|$%3)>`ZJcPEo7Npl&gauu{{x7(d4@{{@dhbQmeeERCi;e6PC#v0L>l5xSfw64z6 z-uT>aZ(NJxtg6qJ#eozM$zGIQVH$#o5*Q!e{(rlAi9RW~vvK27PH$OA5SG54ps^ck z!+-fN{?99yu6^PYFLm1ecW>Qlce)#!n^~4!jK)&v)vD>XH>WeRe{`a=sN2s}oE;uN zT3?sQX0v~3a(1q@TN?}k^13k}+_^pIx3_n;jt@_C9Jlhk-|v%zd-v|X^UkeTUU^v} zU0j^J^UhnJ`|L|qu^bM!zVXL@_R`B=zV+VwU;6r2m(8lQrDqPz3T1?W{et~yI@!-! zYbJEt?R5r$Btt+Uq_HLh6DyjGPB9os%+B_@Ll8X=%5lXkB=i}4WloCnJc~iP+AUA! zXK!5E$`|8R)c<&V`PY}F#bQ4;cbe(jtt>2S9@$~M@hrDCi`phi47+O@GBz=QW(W)( zyg+8;2EbWo7S(7{EdTs3AFit1&wurE4wpap?vGt@@jJi$sg|y|F4Kfb`s1@=S*gl! zq$22J$tA;P?;d7{R@4b>7AT_=v0!9?rIcu#J6d>Ty@rkWg zQS7Svq^Qo~6tvdG%4s?1wsx!1Cy53w$I}DPl^3lz-_ubCUEt6(=A<$2ciL;C<5rri zclsTmsCI#cbGA~T2oR7EiID(+0Rwa3z{rlh^Ts(7LJ)uwsK&y_-h0)RodKA|!`I#N zr<=v^0kAb#+bqhOLzKjANy51KqPRa>9^ANbn7KPpa_;{Z9X46?UKebVHksPZ^40ak{g< zQOwFe{i8qs>aTtM{{4fSH=lfT@F>sHnj3@Ww zr0;pKw!Y^%G}gKhq*9GFaims@NvdVNT41mO0;1H(Ca4sJ^C1d;AP9hFra7-xrwMq? ztBaF2wugFlI;Hkaef5h(iMzNP)%T#juVZ_@XrjT#8+EzFF3PNx#VwT!7X>dFh{-ZK zVnF~17SUN#E$fTY*5CX7*}Lzl?rSzx}VjGwj(^)JiT$n#D?v zXL42hx&pIG*?6s&Qc3Hgz)a}8tdq2gReGwskpK6ngWM@y0U{<<=QRK0t1v>%2i~g0~VW0wiSIKYSz@ zg>(#yvL4mVlmw?qTCNOuwZ66;0wDXMoUh8I&}(tFqht#lL#R&A-n)Da=Ch(%Zgx7` zX_nR&jAM}OLM@32LjVFm24DteU<4#!V20qlF{XCj69OTybU_9IaVFCa7*!qId-oeV zn@QmObQUV6d{23EJ(yUAr#&@B4TD>55Nc#~~WZPhe3iTnNb z^}1rEWZ+`HdgSd?3Qk(PGTuNZa#8v58~5J*(azTT*}QJ=-0bf>v#iwF=}E7Xx6{^p z@4Ua7*B^iG#h<VzvCjmw)ZShj-q)b=x{Zh=i6P!6Pk-<>x;C z$>YQO^Yi(yf91<>zwugKn<#485QI{z<)SQB*REX?O1%2h*M8?8{;o0At3P>lJh`}h z=~A%v?%g{#u3eW>NWx+^8*c25ruA_5^7hrsi)L=P5s~uNV-N~i@{;{{G`^Q*>&$EI z?$9`Ey$=MD*47z92C%UbqqCD>>wdSjm=`JH3HDKh z1y}s=qUk>V5|YN{Sy#>#jF8N-CQNQtyzSI_lJ&JxXoUzd3$)Y(vVb0gAYcT8;DGJ2 zIxn3$JkG!I7q?r(?&p8y2SP{y z;Xoe073Gs@vAK0w$QVHcMgRl`1VBav1R!7m;F%j|SBvFEq!_?|q}}OfX}4~?^`KP3 zNX~fz4#XhQp`9*g$LGgUtaTK3+ue5BlC0PQ1yUH928C1(D~Bh`)qCr$ozZ=DW#^`I zjuZs~=WQefIc^x5C^3PRZ#rQ-y7Ov6MQxb|Po`T>ilk$m6>MG54Wv$5ioLaUut5RE zQsKSB15J^4jZluLsp?5>76N@MkEfHVAeCqBG|omBBS00Xn`AqL83ZP-??3qI$3HQ6 zaQ|S?epbm|0J5Gu6BDp-0cs*fA%hRzdjLQbNC?1yj07Rrx~ZJ^NF3NJEs-#yRI^l} zYODF955H^6qwUR|lM9pdo?5%~OzC5U9K9m&2o^9fkV9=CX*jAqIB!W9_A_wvRw9xp z;Q*e&1?Ro-&IH$>YXkrUP%6=B&je+>Kp9116+XhCgp8t?0IhX`h&cdw-~hlrIPf-@ zgn`&bJ)E&9d+B=rU4x%A=uii0^|B% zH&TP92}&vF%c>sN#c?E@(7mj^K|sQ0J^leO;7_Zl z^xEF`wHw!;die0@=RbSv>eVYsVyl%L9vxh}cKPuqpLpwMZ>$!p2lpRcyLR*7=wz@l ztelAwy)hg-xc9-+H*Y-g_>I5#<3GN%yE~mNTAeP*==}UVNs|7ccXD>p>9;@m;wOu8 z`NJRn;M%oodwY9LRlW9;zkU3%$8W!P`=u9O`tG;B^VP3@{k7NM{`{~0D#ld$g@uZg z2o5Mj5lIRayV-brKhFmtw9~8~Kp;hp10-p^6_T|^YnRS0%GE`ut(A<*Wdx9_NRmi_ z`+y8sDA|B7Y%woqr|8dnE#XRUMTCQO>%25oC$_|MV+vz+X*Mysq+8pO&b<$8Nn!?y zt*inWhJb;98QBon5Spr)7N%~;VWZ(mbQDHR-}AgkBwby4A;xj;gy`%nPYt73#;I0Qke-C7qi4BVUjM_Ja&(>zv*@Pq*+3uNIPp%79yvc1W$eMQFhEo`4T(sA zz=P2R8$bp?i)avQW9MZ#W-iy)J9SZxF2-9MJ9TBOB^O$G=Q3eNjEL2P2d_W*vG&3K zqxIf1$Za18MS>!--m?fS90<<=t@%65OeCX734w?p6bA3As&w8mu_unBSfh?8p#bcP zEUKEt`*+^?;bWJFP0jPBwR!#1KH3tPg9ij=^negRSk#WAIta_)gAJjmiwp3}wQd$i zIs|q;1P%-y!Bg~giQ2e%@84P~YKm7mx;OoEf_h0+jTVMLxSL#q$ zDh(Gdc=i-grYQz*gIi3-`+45>A&j6^HhogLm&Vm0U_&C2AxZbb%#WaA{(N;IBrvEr?*7t;K)jM|=& zAqYx<6DG&9VRDQ}EC4`&C3FJacyeTe^RRjMLH*6Y{_b#Z=L=u@%@04^fBh%lj>Y^R z|JT0`e7e?;%UKL|&3g{PM2Jd6MNRSF-@C-yD*p`;7a(`C5o41GK zQMR>tE!U|qfEK`cr9|T!!y$MP#}WHN`&Ag9kU)#%yo~x=q%voN1aJTjSV1xZp$05IMa%%u=b(@YN!?mYR#4JE~gAKYGFTlXG~&(nNQs{w&vSe~BV z+T7uyC~Vbk=UV|ZLnM@TjspNiWP>rreuM)9AOI>Qg+M_RX~7)Ivhd!p1P2g{EXQ1v zMuY$j;xdBC{aZim>P0J0&ZnFYpU>8x15AMf00aaE;Zb^2mPO^*1x67FnsRjxq1@NS9Ff$l{CX(#x!ka=%6A5-rC@X`JCYc~h z>k1j!D8kjUN#kunZSUCzgE9!22CpFmM2`r7gs2FB&a4mEaQ&z|d69`Mfx5ch=9(%Z=f+G#Sk1F3Y60ovOt!=iogjm zJ~+JHYR3!~5t5`8$6e=Qgp7l#j1!8Z7#mmAO_|~vN^V895G#j$3&<7BPAd zAS8&u0VG;e_Ox!w!^!Ga-djJP==H&FFYnm%GIcUeTbL(-i@*SsQE-5@XbQ8xzdXI5 zD9Uf%6oVn64#pA5K!L&0%Fyu$*z?s(=gUbGr}*K~nItWR4BmKOMT#Z)rdj9+%3^$Y z@ZpnBT{}Ly-|41JQzH$Kwz6bLV&wgFy11X_%QQ>w-?_NF_jCxlsEm-BFk%!AxUTEQ z7$s$vH-l=Bp?bTc-}M*t18^NGrySDR~~i`qJa*&yRh=bl3TVX&rExAeM~EC;X7HXcHT>pOv)%qV(MroNhqy#j;QO# z7+Vwird|=aM2m7U$&!|ZC?p1KEL1)aVj_Yd7XSo+ zWRMVmz!5gc4T3YK379aoDvLT%TU*)ZKl9w(_doo_n?EZT7frPYwn=sS+SSLNf9|Qv zSJrjn0+)aWSx}IKzNpTs`mEEHh^8u=;oypv9q`J!8gMn5+--HD`IOezo)nnZCUm=- zW!*H5i4*O;0rUs~nGp~f0NtbgUv6x6>!uDNv|61s?O03BOYez+P$~d#gCP-w5>P9t zWaEqj?=hU7UsO$%BPX*#GRkIzRx>#q-w&Ukm@a!15}^Kbt0 z&TF?4P&aN~+q*Vg-`ZdwP3Dt>M|V!{-nHjrGb@uUx9xOz_3D+Yk8Q4Rq)~h^KYw(* zzr1@gzjqc72cQ2Z|INhLYHu6w9!~`kvqNwI4#5#Ha`4s);qJWu))PRJi~P;k;&u*x?X&hEVRXIldz70v7Z`lXji513?Oz)?hT z+i}!*3W&zmz$W;H&_s$AaR{!JwjSJnxUsbX7#53ZudSD}^I(<{1t|a+b=;1!wqs$e zk9}7uC8b~p);7T#4nb?l%n0ngn@%Up+#3vzPR`dhc9XcvY!}5N<7OnFTv5MsEsk5v zUPj;?IFn{cSj^vAE+4H82kmytc|TtiWo4E{S(Yo~O{>#h6-5*!&W2t$QG$x8HkEGW z+BT)D%QP-0)Az1jdiwj{egB=?`@7d3d;U|eTz}%}B#!F3h7iSZZfZ|NNbFo8r3Y?= z^5^F#Rb967woskv9A10<&Rf5{_nZImZ&9Sb_g6oSwfNoN`Jy*7>7y)>&dm`efRgAX zSnC_(&2)Cb#Cf|lUo3{}TL2PRVo(qSuq0Yd=Wlj<$)ME`|9TAo{+NFZ|&|4H@A9mBAj<11)$&n zz!(BBfgnZ%WrfFciuw>}p%eqlG#*6QPvY)!HfL_EpNFut)}(qTOShR35J(^+G9ZIs=NWvY z$orDWWr@1=%QvrGxiXtB093cPp>@mJ5Ewl$vj<{C1ON{N42-Bn2+YP=2O(fstX7lh zxZUbH=hpgbd7KHx;24Bh0Z0|46+n3s><6jV(-B_Yy}sH%{{H{*ht-{nqz;m85k^s} z0wXA}+)!gXpzX2}DqfOJ2mR?}-fOj8RYSx^a#O3?rbQP27yrY5yZ*^%e>pnC4-PH_ z0g)&22%dunAJ{{dzB|6>;b~6^2Oe1`lx4OQp&z!Hiowf7R zrB;2Z6cR)#N08PUByMVxWi4Y207)U8^*#jeEr&n?g+K;&P!xV4T^yTSAc6EjF%v7m z`RScD9!EG%Q*n4=v+l<>EMs)&SkC_zR-C|SiqkPps#OUOhJf-kG3QX+Wgy^kWD|&_ZN!;>)giXrm_Cu(Q%r# z8HDqMLPjdC8)uE5FXo*d#TqiP8`IF*I?tn`p0!%$?YF)=IW5X*`?=>n^R4fG&&SEv z{{DY77<9E%9E1>&X&eHph@3A2*T`m7Oc%@faD9C?U)5Gd>DD{%pMU>Hx1RgtOE+#l z`Pz?v@$=VT`{)1sAGK1i0(rAk%0?FlW8;nUH*PUm`E?~F$FJKz4n zgNNt4JCE(`+(^>y(@MB%0MQj#Q% zpa>xVc!vy%FhXfilq8)H zN;Qfk>7-GiI5YL_R-TSd-Icu?)zS2|-~Zmp+mBK&``vV2p9VCEN@{0HSGS{7I~0zE zjOM=9-FCeyz&RNpL|hA~Swq^dwRrNCm!AF7EANla@MKbWTlvs9S3|Hupb}aN-INyD zF&9TCx3{*bGjL3ci_v(s6oR*i+l?LT%#dgTH^brjqy3SjcBCbeH#H+FfmX+Y8OoxL zHMi*0)fDZw!BM*owNa0q}9j0oUXfwK4S=ZmZ{0Xl% z8*CRL9W4=bTPK-uhR6i71Xn5vu~t&3-~$+T-ZOI6N~8?dEP`FmCnw#u?zXe}e6c8N z8D{}yZEP1KBJ$q(U<82>9D>X8#F$zu>4T5s`0VsFPP$q9YFXdAe%GhEuz0fLe zD%Nq<>a+uM61U0%bzEIcUUh!j?XFL!t2j=PX8_oE|;>#FGaHM^Z*nIta3Vcy7M=@BdcBy;r{Y%H0o6{^;NR!GHhHe*5w3 z>*QhWZ}vAuhIayl5St0+Mc0SjirAb^P(5sS0a*RNjLI60fE zD3w}G79$&MlJ$~wxR_Cr^o3MqJ-rwopPhzRUpqR#SnllXZ13)DZ*O0^v?nMOg?seq zaDV?`K3@dyowapUl+`o@2VOHn;FT1M1&vLaa zn>5)*(PktEmZ=6N4usf{aEK|07L)d#nS(%^Xpks^XOxA75~)YNi)Fa9yZii$PZg$k z;}^HsN8L_;cTe}$Fw;Fj>8cVZqqDQ|SurV>hYM3Jj?X@fbok^ao`2!_7uJXEPCK2< z?nyN(i_?C;?JcyD4YoO93gkc-6c&jQMFuqgJU?wT7vqkxLfN^tUBaKsJL;$U10PAgtId7_q zN%3B1ZGHc!x&GL55Rzi#$dYryAuQSTa)t$|2%I1`93cWT1`HZ1!-*mS<`95@B?1Op z14^IuVvO3q^N)WI@9sZHv?dIQfx!juy$itwB~|do`PFQGOf>5bMBYZ@s>R$2-T~hx zQQI(czDiQj@3tNtUc}KLiUG+KD;tT}+M?Ud%Ch#J5e1@fjsYn!5E29MM<5^qVqj#1 zm_o`Q0UOv6BZVlH6wHY&4-`%^MdORIGkiK-d#2)!5j~@Z%Z6&}r3CN=_(Fn7v`n-{ z5Z-evqPni)GxYRQCU?cfQ&QisW!HS01$*kLUyk9-jeWDRmHKa z%4%Su$F@KA&c3dob8+yl5bu zSMpE);>Rav&6mFN>qTMz`metAi5D*a##cWb>?BcMBAeO>B;sYTv(aR{v9tZ)B74NQq9Kt!dr$K5`xdFrar_lC)AW z0Wizp2s{B2kVL`&jEI0_oh|FSTvgutey6V%Td_h(L8g)5@O-ZgLPVL{4SFx)@n{E2Ua`;TTgz5jt*)2FWRH-Kv$d zEvK)1`jh|gzxoIN>i_zG@aXg|1Of&CMhJ+E#0bHdvMguLRYf^ZVvHh+6X|?aSB}E2 z!XZf`mGQxyUmWgUT044lktORW8j?*@`!sGhrpz*Jj7JniQ4}S{dKGB~0gMb7I4}o9 zV6N(BDx+BHHYovMMF=vGgsiEXJb}^Kd*$T4tsb~yS-4JT`xB~tb>Ui~eR6W2IEp3g_CV%loAmy4>?9SRxy z;3mtXwCkG2Hl-p=R;xwc5*u5C!^2}Gx~bl)3z20lA8MVL+8#<=b#-fX(Im-QYtaA2 zoi}zat-b%tw@3RA>ha7p%3&v@eN0=|uHJm|=F?h7J~%{AS}8=qL3LVd z08tRC0pY3jXWxAFz4ym2zw)(KD|_{|?~PCI|4;wp?}0y!rAN;Yn1gMqi`DY9*Y917 z7ybSgsYI)m^~j)rkpY2$nGphkSxok`RL+*myq!_x7sbe-Q@UFe@uNrK=*Zl^#y;SU+~-^3%`U*x4RL8bdJXon(}($mhVGVS((C z6(R?&mc<#P_b%^rHe6_AEQ3&FOh?#@{Wt5`{r(`ocW{2~=`YLHwHi_rn8-@T&=_k@ z9n45}qGSW3mJ1L<5ab0m;AK-93rD3n$+9bimpBam>3{dXy!hFdU;fokKX|nNlb`$) z9dB<)Z$_a}z*%FRr(|pAiM>m^X^c9Fk}S5yj3<-P#e6niJh=OCG8*-|d6q=GTN`4NQshaXjD(azDJg_RBGc5)84gWd&bplxz|>8ZXMLp-K}>5FpPcROU9B3M zrY+}zK?DY7V8Fo4!LzS|FGZ42l7m19MtZM2iO?d7jBNx?PVWCOwhuSEba>H-){V~A zvo)<7z1475yMSP9HIAvtHKjU2APxe6A`C)c(bOoAA&f_-kqF*ain!bDMmlRenIKRm zLTTX|V`>Hu;Eb(;Z-juVF6w&K?R1J_skLTi?}H#&HC3mrowev<0@c*Dju}N2C%UPF zF+!)U(d4MV(OK22$<%c7y%3}|OA|<UlL~9CRXgBiRjs8#A$C1YD#FhpiTIbo_8u zJ6ylEUYlw$nxs$^7mu{;7ADU(ALFDiFiX>pv9(g9H8GgwYE+i9ERD;u>UP#T`MNV= zK5w#4yJm|~`-iXH{?U)`|Nm6Mcd)J3br|-w*53Q;r=QzjZ|IEx2?8L&UO|wmj-(km ziXzLFVvQALVk`M06DOl+tQpJpIF?0;q9kfmDUzbt#SXBb5QPAN_wed{@80`vJN=xm z?Y2UBG?UTqcgLL%pS$(gQ%`;4sVBbr?|$RgdYv3>4i=@5Wj>kBc3MqY6qO9KEbEg@ zwI(4G>j@Yc0N4XFfI}=7!^=T{RSliq3XmX0!^!M$RBdhLPk#Hdw&{t}x1T2lDf*LlabN& zVzO9FX5~E3=X2+(xtTcBh!QYBR7gS~GCD+KOks7=%u?__#0XLasb_Xz7#t%Y5g-W> z#9`KKw9`11gvg$~W$=sIR&`yJMOAC(J&^z*Ol8Wlh@)5vsiY(X?@XXr8w;}Uu_*QB zRv6hy@W>-?3K}ba@E6bC7^}He5O|_t7A}75-4CvbH=p5!i(j`jfS14o2#8E% zP}D+|?OwRMdm~gWSEr41O^Ik$TqQYW+hN;LArm?8ac}?HiPQbCE0l-bQWMBg?9j;Bn4~>rLZ1Xhtqkrd~)^5wd?D>bvxT0Y`@rRuMEf3-nc#Pp77jYR@&4gov|gL zF3O1{5QtHjgkctlhSmZxVu2o=rQphq$tVBjnK;{c$2;Hf+W8-R`3s-_B5*8i(Wj z@4ouf=8Z|5Y~25b2YX8m1AcFKWi&jvc>Ypd7RQfmoH=>q+}Y#Dj`pi!rX&dT$c&7{ z0+^UVlVuXb8Gu8WA{b(Y;GNGWvl}SAHLZUCcv&w*5E+gGYdg4DY<<^Ee$eTJS9Zro z?sy-zZY?0IotMHY2F`P+_XN*@x>2$LGOMij?1g0TntTWjX5|Hzhu(G5^psceypI0$ zum8@YZ-3W)uRpVSZS&jT{O%j>Iq}E?w?-(vt3XaI!|tBjKAcXC-apinAuMLD)#{u% zx8CW7X(qEQCYBN;8wcJSqifa{!8tM-twCehc?PgZ+WR_C5$^R7H^oN;+qm8355kNXl8^ zRSZIV+zY`3COUR>T{U_i`S^EUygIBXa8w8}eAB&0|IIIaU^FiN*9Uyz30(4 zo+%dM|NM=Q?e0x~>)-xjGd9mX_xuBIeDu#g_54@9bsj|!=-L1F%RheCiPkeuK8G*9 z@)?Cn384Z+Wan&Mq1FyX-s*{+o0m_Yyr-PD+Rb&XbL|i2#Wq2rL`GzstEy5*iRrJ< zaIgr(22$X>nJ?yX*ywfE#-qi2I#05cL>PpzHaPT{3RED&2$XW{ z!8*khV1!OpmCl+`ncq~jKRtY@m|W^-Y|#=7BfY$HI&A!Bu)XWNA`dW5-+?lE_UuUnLPSI= zOAfP%0r7EwUM;dYV)PCI7T@3waLuQppM4CQ1p4}&xe<67s1_Kn{0MNX!cVI&<- z%X)`#mc?Nl#Z}>}Ja0EMM9%Ytb2r&>EHA_h6m%}4+03zJel{;u~q zTLs?wT@`J_nAePd(K)ayR>5~Z969AD29kXL*&z_ltaLyqS`I#P{ z&k{AB`DX8&h3?Kl@s%f^-rgUdJblNh6L%gv)_e8U%R9T5uUz}KHq;pPX?NI$#DX5qwp-Y76~T;Bpk55J6TMc4sLJVq}hj2mu|{L8_EYfYZ#eHI3f-L83YPY0Ldt%@fgDxe#m%75&=8_ zcqTL$F`^?+-~}+%fVBV$V-+=m4}bJ)Pd;;9Mse+?%d7mq{;LluYm&I};opCv66*AA ztB>5h(Fz;C@!Nm9zd!rTAOEv2e(Bp^{LT}<^eeyi>@(N?{Nv97PzICV{=a|X>2E#% z{L|mW3s=5kD(h@%{Q|I-A_(PLs5(VGbU0B_1upG2?sGCO$LdsqbP31Y1rwsno)D>`VN9{3~|~NA}A}dOD)g%^Sus9rCn2j#?gIOn#mo_Cd?#b5gtz_y0B7{sy$=2yS z45Vj~SCj+|a)lJR=FxP%hY0K=@L995Oc($;6b_LA(6M5spiZn?fXG1<)A?R)%dFWd zau)>6Fl>>CfCV55B*7w7ay;G-L#(RlY<}47re!(lc2Xg6cXzkj=_W~{b$w%Jyu5Ko zrNv@VHk*l%byW{h)YIW%tCh8ziPd=;2HQ7w=hM=GO|mRY*AMn*r_XMb_0$^Ei2M17 zH{p(?Ih@~i&)xUlcZb*M%P+q0+7EtE zR@dJCwo|8%wh8#miCYL0gru%qtJRv#CQ><+4$%PucmkFP0@(wD1M&zA3+B~A*W>7v zQfcjK$2pP$jtB+%YC5|X#noaq?RM8F$e8*+cy<0?Kl16fzxzi{o;`Nu+DqSi`pb{M z|7{Q6bGP&?S%9}eLdIN&NL!(bP!(Z{ z1W6-ZYBzcal~g{82#^7TvP6;r1CjLB8e$K?2ngWeAE1&_1tN))w2{SO3Ixs=>#bQ# zigHowT5EPr#PLc|*HWT|im3v@L;^TOr=-!sdIsqTJUU0UN8?c3ci-8~P4nr$eeUpZ z5Jdb-|MEwp*nIzmr{4FrxBRF7^p&e)4b9-6e&B%zZaw{Pe&Z8?Y<}{;y!-b)`k5y# zUi`VA|GC|32fz2xXV{syz5e)5|LE)f=wly#=UX1Y8#iAe4%u4|Iba1y#65zntOvvC z)uokiI4F;f+0~USE3jf$AW)z>>>EX4mB;Zqa*UDfIS;yt#wW8c`O~zD?OUd57stTclP#Ljb$mDLS+O200AN)vBM|`n2jLI zT3W(b5<%zrEC@srMWgZX$i|V)8^h&|dqE_N`8)_>DFS0Oqe&uPqv>og-s<+7Nz&Qh8|tcFTizJ#j&DDE$7px&;O6;8TA`ojd9}Q8?_i2) zcdcSsvQJx?(N&`2h$4w8`^W-n^adOelDJ^4vYQJ$T1$w|)Eh7r*(H zkN<~%`*V^8RXyrA<8qn@NiWV;NTl9M#6XaAwlbzrf%9B5SZg^9682IEzqkE^cBeU- z`B{;E`g1SNir~)s-f+j=Cx+wcQ{R5!@`YDU9cw@K*qy7ZdB2^E4i={3wbi4ZrJ#UN z7L`^~A|VqH5+ZtL@4WDU01nV00Wc#=K=k0vA}=p^oCrSBXqRPuCIGPQn(&Rrz(~cKN0dph}k?X}`OQ^gqW?9w~ zszbr@qR9U9hd&|0rAOZKkjL20+o0Q5VRLHm|=XMP2K>*0r?)AYoKN6p`=%AVC2T z00J-o!r$W}FCE(`h#SqU)oh1RfPl`sovW|r}y|pg z-`V3!uU&cN(TDHD>swcWBO)MKBWcI%bz-eT%6A7BR#t++FkkK7t7PVVB~T$NMM0p% zV6Yv8*lwoZede=w-@kP2>dmFzJ#n~#sNyWB^&pn7;B4FT~%fwBm_!^N(!OK31=x5ah~VRB+iQwVs6b8+(b_K^)H(H>ZoOmDN@fweqz3r7)0c( z2G8gN_F-*#QC9{`AhDaJ0AwiM9n0VSgHJE@kG;4h9G1avJcpW0uw0%Z=7|dQVvi9)ZRO#q}EOwJ(vyCX7BqiUHjTMUa6|iLl3|A zb@!jz+Sz^Olju<_YMzA}>-nkFB z@VF4f;0+o=Ve7K4t}~AmuEx2Lk)Prdid$)!e=m^xR1w`e^g0SV6t`N6@JAXIyYvm-|y z@R(KB3I!yrKsBGvWM~dY`$t#L3P=~TQUw4|Os0oI%Bq59YlSEzsjRP}IB~TEFA@F` z@42d~;b^$MwRPjh)?hfOtJ<^w$q&6X&cZNKtyV9JJEM__E@?WMo`n{PBaYyb1V{wISyUhkOoX7J@N?f&uSUc9-O z{OT_}bo;5}zy6yapU>=H|L326>X}zQ^VE~S{6GDRZ+z+bFZ}K2-}bb5HD zzuE=XxV^K>7ywuhC13>z$QiR@m|wf`!ja?Y_Rjv1<$I(|r690DC|bq5GIh~tsxZPT zUtHOI`t)tl?(S$~^#LWjWoaDO2g9pMO_DS$7eNxNb=t?B4=PxD%8QpT3#V3|8`o!<3IX=dTyS6>NBIsGylu4{Hz(zq{mLXE8?Ig z2Ta}ygorRA4#*4OAJWd}MKKr-w}7fJYaSHQYnz9k|NJ+OtljzWL+?L(>g3hSn=d@~ z%--(hAAkGz3=@-FZUjE>PT z8-;>cI6y}LOiW%fq6cs1dGU&;iQx4{il?YTxt>=XhBw8o5zVowQgEwwwhfx(NJnJC8Uh!KD8?k_NO^@0 zNuUGfFo;_5|M8n2dFjI8WD#ab^N|P7ec+w<{ozNRe(vgKj^>wt=G}LkI`!}V>(@rZ z#ZSC#^`HHV*WV~{^TyyWKKfOvhyUsq-+QbVfX{nyT_MQiYj#UttB3@fP?mUAPU?~b>DX=Ui+RRN|4yTt+-4a~CzSl_332GOmX0k%nOG{!j zJVe)RHBZFBs=dSV<8GNz6%-)Kwu64i9(2 zfQ+fyNj4vE&t@;I_C+F^S6?em9DDmhgK86`Rc@wQi!5Br)T*;Q$v2I!ldwOT6i1Jp zFxHR~&I|SmC^E(t_0;iP1cj77cG-MB4MJ6$8UUA8){I6eVg$(`fr$|q_=kujk#NqX zX`IhzN}vjGG~BJLX&i#Hi##88d+GIS7w@?1;meov6DMvb0oJ3|T-C-}rvh-Us;fK< z1$Yw#09ZR+Be-@qsLYHg7>~{9(66qnGtVMPb)i?g$JzKxSD);4tEC2whx73?K6?6% z9IQdu&9$qImZ6j?VBp$WV~t0aU=wmOiZn-TyPx~QbKiOC>O0=^*x8MxPkri-H}}8$ zEC2kTG?|YstpW>2!U_bC&Y`maEQC;m2;hyWN5capMV6)q2fJVW)-zvy?n>6(ICu88 zdv3q?je-+s?+x0UlzmO5jujHWNPn#*&H5t6N|y1M55K+#f?oKUiDy!TwA5Z(g&X(3JlDKKLLNCx+@RNi6 z%k6G5nU%}Sw@KA3ZS8ykSO!8ZX44=lr}Mq#?g>{%%~rQ47FVyG-`H50&SstNx)hl< zoTLd0JD)A0paU!rfZ-pp&av|-C{)S=IBTtQw%%5XN&5YRgMR;Lmab1{CQX|_7O1w~ zSm%rp#>0fCM%E!>N^y!w2(f~QJsUP&f(zmb8vpTk{`xylZKCWn($1}CZ+-dYS0>&R zSl@MOsUhQ+u6TAT%75^>2ac$v_2H=#w|Pe-ytRcCRF~CouoK5Ji2|lkdntELm5c6d z$})(AV$Y=@ZM0>Zwwp(zaLE|yJd!};N=6F^9?(01pctiPZ%k!fiD0B~l01S%aNZdy z#bQ1~1SwE!+ia{8_^TH_cVtP6YTi)G({VHF9@BxEn5k+745C^%=~M4qkhm~TCquu~ zKc-ad!J%YpJz#*CIFHsZ9L!M8kc=J~l0vFrG#np0cG7!k3$ZM6dMmGF^((C9o8m6=|bY{zqmTE~;l zS(P3`*~>Lhpg>yf3dfoP0gSA5N+g1)@`81E>C)g2KlQ{N_dfKt`|tYZlb?U~{MUc> zzkAp5rdnw=1VtD$El18v_Gp=bEQneJ&U1BecsL!G+nbY@Ubu0vTgA=QJKp%96@2#0 z(NG4Pmu|fJ{pa%O%@02Qrn~Pr8KAUP<;UCDZ^c#)l&ArVi5i$_-yg&-0 zup5SL6=dF%^`5~?BJv1cI3R}zfQ&2w(Sx_Mym-aaMDR+Zan6B4A&|9263F`Icg5&? zX#~47=$(7qg~tU+MrY6xlC7({-1PoX$zBp4SF&duc&<^R_Z}IfVBq5LaI@2vqtU$I zyT^-6WHc$=xDhQk{x{ZoqCQl|U+`zQ?x7DA+Hk2waA+Gwem1TqtY zKn6xY0EWLONjUb-SPv{okQ4;S2(I3l%=Y`st(~2nmDS^lx@9S(3_W@z4T1sCJ7qi$ z^`zobKtbMzEEJ~-QY9l9NiP`V*i&m(MF0M`|LEG5pDbXpuu|LE&)UD2a!8%tTBWSsSkk8o?}3UZ3XNHu_C2JnJC5;@EBd47|~ zRh4TbOKH>v=}_wVY?9|isG!+QX5&et?UL4fILN`S*L94ftgoUNip3-jBPmnwf_8hA zIU!lmJQnyosEB$-h=?}Z52M?j>_ zf`Zb)aFLIw5=hcoUS3|e1^_}tB`E+9fP_c@%mAJ}6FLt{231+5aq6A*#xQ8)%Da3z z-3^o_su%g_=&=*?sg*J#5!QB|>j4OBty7{aMOv1NFvQ7pFAif}yH*pL4KX~Zdfj8j z+UacE?lrA-#fTOWq_eGP7u`k=45^`i<`dWP$bf(#0g1txXmh~w9`mh2u*;a z!^0#k_I9tHJbss=&Ujo-=d=EDYcM)oSzQH=m_x*1JQ*UHMk_-^20{P^Kmb4hKwt($ zLFBw=?>(~=f`mXf91OR^m>B^eOye~{E$4)152R5r5&@38jiUe&yl3yhc>x%zAX7ohLDyOl`-5umz3I+3Z$Hzm zOMNhcBPSnKt)mrE>F0-|&2}pegWzy~76tt@IwD0ISTY!(+JgfoCDWp+h%AdDuXc-K zk_IiKeG<2_tOFbvgNPzf5dgw}!vKiL2#n|e&?5j62=>g*dRG%#rJQ&3JkSm^sL;l+*x4I>@5NWIUEf>edS(6S$&<%dS9)pME{l9VnQd)expL`zq|~Y7#~*(1 zzT-!G0AnKU4M`C=YmDC?FJ8;SR^a;0tYp1qP}>dkEF4@53GPnuBE_XhaV->w;#S<< zrMSC$DTUy{-QC@#xVyv6bN~0w+ioC)kuFlC@i5Z_~qilGT~2O_f4uT zwXBs@NL8REd`8SKB{a9;^E0YsUoc1bSIy<8xT!MNhatGBr2}Ae1<$ zJvIys3@DwDK+qljKih0^$H>2AbFRzQrlFxTw$Djeq~|nnu!JH=VE`;%;1}3=#VB+I z^wi|tW{g%em}DT35jQN3SG^!wMX%BI0c@`4b31)-WZ~T{D*cLV#Qj8_6!~tW{wfcL z+x9u<_o>T~r5Hgp7&R`ZLa&nku2T}dAh~r@%6;j3HxRR82 zVhboc-&PE<#zK28_5CiN#`PXjc!b<DZ zfayOUWNe4;@yIwC><*q1+|>*afjySNa<6^n#K=_;Tg*0mPZ{`OFBS)X!$l0m=l(KQ ze#V4NmYmAKDjOd_kCFMDA_mmN3-kC=vUag%0u1KPmMBiF zS>&-?TcRmweD8}@-N(qSr+AnBG&Uo0BD8Tr3WY!f#HcV4|0w?p%(wthTzvRckQ9X^ z#-gfc9X%%hTL1Xn*3mReFllfY3=B&g96Wr$7i4R(buB&)N0sk-ygEOBT5q<&{{pg$ zP)QEqVH%{kZJum>K#Z`_?l$P-qqbpkmtyyMm8iM3M91M zLKA+FFAodGPC%jMHH7|NLl{K?#^&gew!+IDTGDzAMXh3D=@XFUxuuseHm8W; zaOEUZN}#u@_smHSiQ{vctol-~?jG3uDMKarE^hR`Qvahf#fMb@T=g}LGW2B73n`C~6J@^*#-MCu>Y-{$w(M`*-*{6S1|xHLFUnvnF@Prk zbFdRY0i>b!v=@<!M^88tKd8Xov~=1;NFl|a z9U1qtfDY^@jL^#Jw7Qz&NA##WG5fM?z&tu0K~1?S^t{O|xT4}pvM^aG`ew{uL9K(E zKv&S=WU$K?!QT1jsf*!`v;^|cr#uD?0(jL&X#$zByxrGD~bnuFood& zDUKxACv8<{zf$r>Z8!g;x8|Cz5Z_HFi9>*4CXjX)iCrJRz7m`XcBdUtik zuUYfT_%+c_xt=BVo`TuD8H|HExloQ00zUrR+9imrO44T~Tke_bajrQV)szH_4*2|R z#4DItv}e?)S>GvAC+&`brwhH9h}*!(%%0HTUV#t%8*{pl+QX#^EOuvXB=Y zVc0&>v&N3}JYvh*3IXz%cSHDu9+u>+zsq?#bS~fTe3b+Fx zjDN63KsbDm+Gi$w2t8`09NaRhaTtr-FMmxcv^(`b{MNyutLmZ_f~oz?zxz(|*3hKY zR$3}8zLRPRl;u^9#3k?K-B8GnRm)qZZYPhGD1adhmOpsmV2k4@5VSvF6<!%X!^bmCVsCyu?V>g%|(JyA7M=FfZUcv!%qZ0lN9 zu<3m@4AqQyI?IYde_Wh+p4wu4A8*!T+YiBZ8_Ua2ci7||*IAw~*=|l;u1Vr!g*lnz zkAo%L4S4tK&j+t|jWdn^_Rju2%_onfc2p*{@5CfFWC^v;CNrF{xm^hWw8z381Um(`qlR4TzLncB#he+VNAGXC|YAt%ygD&i@})e*52 z08LFad1KcLO|azGcRd`|cY@uU;@bnoXWSroW$L{mgfkS_0{ zK-E}KtM2nA_`@5efeZE;Ukt*hosq{1pmn7vURw9H^?+P1&$X%F&u3?Lk-s1AlY1Pu zK%vREQ(`YA!OML+-9VWf@DOI}v~i z5C>|90?^&?`pmTc+V0n}PZe+s#FD4uqfsD`z=V$WZXz>@R(3s9DJApTerZU+5Jp3#h4)rk5*g1sExhyYbm~YuI<4EX5P$<+i5AX1DLz>(V zmvqk0)>p~w%Gr6cjD!fUR<3u9D}X=_72dZK$rM z9sM|RxiWs(M`WvT;L&KI<`>=R^5y#&@Ya)jrhYX1%x+Lr38~tVWNUmFF5!7np;R20 zJX{^Rd=fp>A!gEJ{D)XAA`TEyIsh$V&yP=l_Jev(eH(P}a()mX%EYmtfVAbt^O9s` zhrYoPiJ)}?;LCwH{swGO7zAzRW)o4uG{FFXaUE(g1@kdcYpmEOJOK{}ilpQF1zTIC zux7c}orLa3LA#>#d8f^#*2ebc6cQ3`h8VeYiY9u_<O^nj+NA5?@Xv{aUY=Up8g&nxKb87-rGy>Fe=c;Db~MeYEMUicFU-{`2qE*jnqH zNRe`%lZo84?ds6=r}5;N_vKV!c2eD!baIdD>RppK4TOQ**O$c1h5pKxb5gg}M>b{0 z%k5|leZE{)#QP1uy>Ws0SZfnGxhfO$F^(ZUxKyUfY1g1pKk1s9xU6u>U$gfoQ&a{{f9JHO_()*5 zPx}96N-Iqce~v_iw}Cb3We)Cg<9GIF2wcr)g`Q!`6s7ayG=pey>MP2OGChFshB#ox z>Mh-VbY{liC{=Xo2Fj={kn5BFYS*;8ftiyA-(x3H&zmkDAz3Qltw;0gqosy6)7RM} z&}aSNzasu|PeoWv0D>Vc2Gk#z)2h26$&O>jMr|4(j--R?ar10Fp$y$xZY})|tLy%Q ze?zqxS*|gnY*L*tf$+}aTlYkRw$qvf(KnTw3%p!g0hXQwfqGP0%|=uI%(^=8l3?tOQ+H-2Xir9JNmKeJmF z{3V=u8{czxoV1WsmY4av7s(F#t@Rbv#rW7P{`eMBC?*~n8cA`&avvLrzm65&$=`Fp zq@n4E7lOD&ZzdazgAxsw_KPYrCSq4{Vpkw?%W3zaIQomk-{RY&BJDBtb7obGkUI75 z_W^A0PAhG-&}}`d)3%ML+w1HvZ5(Vk5}w%K*pBp-3#kkuS;E63keJyL?y6ZkCyeeKAX}W zLsQ^AaKw=p7p0wH55t?M&j?GxDhi~8vG<1+qetw+R`o}yH8lglh{3}GU}%ct2KnjG z#e)GSh=a%4_;mY9uuG=`^Z1zkK75U%>(NFV%Q^3(=RD{**LOMeFjo3~Yvs z@+*3;2WhYU`87AkWiN!)=djGnr~N+XnY{76{lj-^=xO_~!gnr&rbSWi1JyE5!>x4L zx$_&O#F>@sVD#l0gi)LVllE9joRr99*Y~^_Nk<|~IkjT(_(egDVPvMvCfalnq@D~#AAUVDiPH#ZoOE)Vmp9F`48iico z4+ujRltPvPeiQlc0Rn*4_KMosZ>!Ruzi@tT@tM&Qcd4cYARGXlL_(1R(fJJx=>HxV zVUgz>obbzQHf1@)wTK$BRL?ZIx~e|6+hDGQhK?X*RF@_XV2qVVDV{7hUP~~^G-VsK z@g*#Gu^kf#)2KO~B!&=)Wx##4lmsZE4f3p1Q+3roO~M z8B0Wq{1cke&3!qw^})SUS6KbGPKA4Ds2v&c4h8Up?9?Cxe++*u8Z8|Gyi{IRL|ubo zPLR7X>MJD!K;a;t-Y|4f7EKz%VvA3@006zmG%!0}3=f+QmZs?JMi(gpqJToC_>dAJ zj*Dd~wZY7lxz4M(IYjzd`nP|SD;0S^1=sc!Q|mNXYumX5O~b2`}mY2sy$!Dh>b7tsJAWNrXC8?Xm+FB!mcL(^heIUOH%`8lNdT&A)R|QA4 z7bXsm=_+$Nc5WFvnS^4d zu!wYV4B|uHw)b?@vu^b zWR#Ih&CTSlcuipD%`{w~P2i=YN3B1ixEM&4{*#V7aDki!p>DDGX}k>FpllTs3=K4@ zmrmSjwO>i&Mem1@nPQMqtHAKmU(L=?)-ayfL)z@Tzj|!MLj?R>c}cC^yR4@$( z?k87Qsad@wu9Ln~99I>g>V^W*=L1!^YMVaVOKi;aP*lxnH#XKC6~QvrQT++#T&>cj$*;U-vMF83X>>ysrbSXDGWdWXzmuwR1rLkCILJGOgs=K zJ_}N_en?))6S%ZwOw4mKrwaE8g`OgE6FCGPMnZMC`-EyUu9Jeps5=gs4{dVfN-t#} zH9LN>m|9CfM|fE;H$CT%#dIy*Q(>ZcR8$U!J-e3zYInf_9L;hVb`1%yIr`tQ9~oAH zU;OABM3xCmkqNsfk;6VBUt1H1ws$-ls&e|@o zrkhKChrp>ME#)K{(q1GO4#y1dN|K}?1UHEo4Ln|L8-dqP?okc>jI2M4b#7Lx#~>HW zo-o)loUqHHaO!`i6P+ z9t!%@k?TmhfdRUfHh6aW1s;BeC0#LL`e`cUWG5Cn(!KfNX(kS{-Y(LlmlQ<4<3dD!Hw;u2hyuguwHHkcs|`qQr3&NPtjXV$L$D1o0qE4|CJ= zdiweM#eSv7X&JZ8lE=aiOmI2bT4V9sXna#6zr%Xu_!`7xyS?RHxaxdr=yEu7<3(GA zQ0$i`J$$sdylhSK-0N=5;q6TSfmv{bKOHhNAxOlK^Xb6x7*D&+{N+y>+V zc)Tk!MerXWOkXvQKi(v`g4rV5%TRdC@w8vAE9^WZ2PL6yK@LN}!pm%QVNAAd`OpP| zDxOr?=ypYEA*2@B9m2J;>eCecn*bQ%hbG2N3+ukck@*-u{0Qw6U)OmrvwBN-^GC8 zvak60r@Dd7@6S3t#7k&5`C5!mJ;k(~Pc|%jUZpr8b@*v*9AzAz?DG-<(_$!;VkT$*cxf~Y zwY0P`wG?cl-@sAhq(2s`Upa#(4;(jWH?89SDoiH29?;HD#}&(|d|O-kmA_gN<1h~> zJj^%y_qV3n72_&>w>TGzIi>7!xW+Oj7u=%&5b{m8*J1Y)VA6lWwkArt_@*vaA#F>4Fxqe{Zq6tD}E z*tHo{#65Db;#G$4eFhSK&tLm|is+=?DqqmYB}<{o-g^z{OU&f48*$S8aT=p!U5~}| z-Bc>aTsP(U3r>A#TG-9XsVU7(t2>)>y9U=sBSR6Os)S+a+9!vJ!J{gdKUjOHH%C|Y zM%U|?*(Jh02IPohIi~oJW^xAg{P^s*NlHDv?~~+y+pE{CEf3SFq}e*JeL`+56{KL! z{!cA0f5*NjG7TsRI#2xg6>Zo;)KVH<9|AteFt+ zjO;)lW!Rh0@D$oMiMkLsva4NMHD8S!1d|E=60jCj&3;V!$F`-jKamfHFKQ9)U$EDF z1u`axQ8tzy8<_!1C2tB924rXp#<&=KG1hU*c^k?+|H6$~+4wa4z23HE2kHKvzjmSZ zDasL|!+2SR2Dwr#RmIEihW!?n2jB>T3tYe2o@yk)NSqDEwUN~tcPLH3Knk$awi@W+ zz4X@8F_kdR7w-2LEfR0)HjRip~OT{WEWOoC#P_DX(lz#SpdmgrgBZGzv$Rm_xB^%o-!gnpM@>wN!b=kMsw{?Gb zl6#i&uxVAdbE%56G`23$$mz~guX6Oq2o69%hzEj#!zcMgY|4YoF~Hm5eL+#bCaGtU z5u`E1=yP}rasSn@jVhWQW;9l5FH3$j69-aJ1PflM#_xuj`}r&%-WJxPRX2d?y^j|$ z^EMSrt!oQ1KNiq)GEOhMw@W(5%&cNSRJ5PRMfshJ?K!Wcx&~k{vm(XRx(l*D%tu#f zle&q}>PlKu+zVPt&}ajb5n#pj!#TzYwT{8UP0cs|2BqUn*rdA;60%K@86q+bc_FR37HXBMnIU?Jh&q~JL6}W3?+vAyRf}EXL{kP( zV3kXZw1A}PpwPr;?X2$^X@7`{2r&V_@O_uB5FoAI>&3wV;@ zv5C6_qEf z$qF60&`}R`1WN|smroWOf_x-jW!rzWJtxGThxuLLjuQY3PsjBbzpOp*0CaBy;6eUV z*V!RWyT#bUbA@>-{}@0}b+LyQp}+wmybECX2kJ0YMCeJ0RFL;470bBipRFvnQed&V zO=u`C!ktiM;TYQlWQRj8UE=3%9U?>d2s=hu`WUJ-_Sr|Q_caA!;nSN`eV0dEI+#OVhhi9u(F^Q(=6b@N1B2*8M1-M3JBePQ>7dUBZjk`ATR zu3OIwkfaxwYzxwUyVW+9D{U|J=f$6(VvnOh=76QbqN?E)hbagQ=z4EBUk{;6#Xuo~ zhZ6yWNMpz&|LUc~qGO5z7xz&oU!{%7?JoZTQqsd>F$gM1B#`Gk-ku31LkmLZ_k=k< zgH2YE%)IQiT1wU=&qu_02}3Xw5X_yh(oO}8qmNivXr_iZ7;P{eMkTCw%2q^??hRFG zuOBRM7yYi8|NiH1Cuz_KZY(+hfLdAvugmh2_c-qleZe<^E$yal7M2F0XrbuvnHA0I zf5kzzIFm_SE!Gh-+R>?Gm@l~oBZ+ko)FC;@yn8lt~^k%^Jjf$b;C$0=o;Ud z7~6XK#FN!*T-(jbj7}*5|6F~S`1<<7YkCLt_ z^Ze${%kYN*V}uk4IX+D*exF1b4HS+H(j+OMp!WyRfZC*!Fa)w_OV!HnbT!HyzH3evm;i@`?rP@H(Yv5gebGltk`mc)5# z{IIGG#%NI?R7j_hf?3L848~LfFZD&;N>5iwS-tcyq_21?{=493 z!|S*x&|o^MC`i=sLliQs1&pRR3|4n75Iz^-T>(07!6N{~0sg&It~%Mq)YMZaQ^wfX z0;B_Yg`7-vhzhFVvXb7wnheq^BNg=E&P`N%ypWI|@wh>A1wuV-OEr3|sf@?3gJL$8 zJrxvWa;QPSt(9@nVd;^P{iVa;{Q)t336w~~GB^9=&&=bjq+;m35er{-wsFy>CB^;IOAB1I-0fAcs@Y_s*BVn zIvwZeFk!c#;gxep1eQb5YQH2$Y zI~X!AUX(^ja)9l`!lW=7z=_4qpXy<5lD{rYyHEj-Nbed@mb?H20Q zqox6s5+94xDAa0$muxZNon1_57_KIK_kMewwcnTV__-JvT`55KRRT}_*J1oCDwJ)u z5mX7iQeCGQ6c0A}Gzk9F2-AQRF>WSJ(*E)Xez1=W|MyQa;4kg=x>9raDpg3%gR^eU zk^QJ4P1k60V2t;Z z)#AXYFzuhw8R8%stC43})0uO+=soq|W`89AsPt+2CiMeKI=%@v&k1+KA0{0CPsv2) zAW<+w6*6`96bF;c49T(;SJs*)KZ0@Cqeo^>Z;C8}yG$B*(04k;K6cA;aPb=bswFcJ zzO{IX63nU!KIn8KQbr}D0E1jfi90_IN)AZQW~jiyMv~O9d=5js*-;u>^&EH=7;n7_ zjD-4aEc!XFOw0k70&VESJM~QVXN`FQqh!)#sLAO1z`XHEC3c3 z_`>6XAt(nWD4M4J4Z%m`QyKg_5gbTe`|U@YPMs1z6KqOFD*P2g&Z6jAztb8@rpgEO93eRK1TRWLQA z=7-LaMn;KL<|j*2gD9&8B?4n*>l8D{5q&M;-4C1viP`g)GcTs(;SH!ubnl$9tD+{X zumxlp^UK3zqLQFi*&J*0LBVH5;Tb*+oX2Y80pHij%2ahcx{{9*!ta6E0IkUtC1WTmG+7h=9%#+(X#dD#-a_3@ce;Q8{*!2@?8PJ0aLwFp{T5Q`>*Q^{eOu}Es#*J(-tk_? z;q1OQ`HCqRx7%0oqa@3(>oMMr%;)7&ihRxOFUG^n@mr$4UnPC4?@QM@cq2d@2SaYyy>7@Zv5+XSYsW(-@?Q> zGET?NFDt9~b1RKS%6PU2I1oUL>f4}5Tsg}*)BiiSahS;#{?ksxv`xGAZn%#^Ii^Zf z7K{)H>m7{{+}9KjLk1y;_rf6iV}-$IO`?hs9RL65aLvCY} zCP;nPK*RTS6UafU)dATCl`~f=*e(YDdHs`QGBi9KPGJwPP-6|1Ybin+AD zK55!JeZ%5yqOidx$o{xrBENBR1W-`%()aSB?ft`gU()wQ#7~Wdwj>iE9$hyeEU!xx z=&7}Add4KLp}tqhrf9AC*P4T$JNV>RFt-wtl-arP{>!CnS*YtQo*5W|2mh^fLBz6% zF&HMoa2^@aKg&s*+KEi^Bh%B*W!B`vxsb1j0{>b9mxaa(9@l#i2xM+I`M!03 zEmhAm{5;dPQs+}@YU+IZ9cBXwzxzSk`D>da-`glO8E9_Xt^L_%rQY^wM)cPJcBl98>dbcwfgaQSLk6q%WA`-)e8uuJ?9J(&cB zxRIGejuSfIK@i3an%ngU;3Fw{#8^iYk%o)cwl0&BGB37S&2sDI(Wd-iN7mK{cv|SJ z_~k@fX`#U4XSCG4uI)}~)VJ!GPJ9QMDcM9m2OF>ytY73bF$q1Im55LwivV>6yrz%i z#%hPpx%rHaQrpAuwNCc76g0Z_cl6$`W7Zg-sRCZ5XtD~(JpyH&#+>*yXFV=<3hFS* z=WWAE2+)&PSh&OVTAh^{;x)uZ2+NB=s2pFM?MZ!d7phzp{zr>Jq0+6{VW>6^h7W`_ z--)UWWJxea6c65~K>mUTNYnbC&i3CstVGzF`tgB9t+(@8@69aP@0xF;e+I+GzLVot z!y<`8@1*_^a0RN26Y@xFhtA`ZV^*oLl(u&2>8q8sNOI?}7Y$D)aI_<9A)2DgQEF0z z!BU9;5#&2*sPdGfj?K?HM=$m&--tgklj2Pk0YL=85&%#f^0#uhYGiJ?`2>?O_o{V= z-Q{}TzgA*fNt0$nn-4>w6M|*FCax8D=NHbj=wF$7)Xi;7i?REoWt;FMxC)I85el+# zi<1CI0pq9kYzJ6PhHeZTTEe8g(J~Th`f7E_#g9w<;`W=pLwkGp{}xA^%Ebj`1R2Dr zz|^8Zq5{WGbnZzH5!ZvR;mf5KK|wzC@7GK=LcZ$XRvK$oiGC`gKY0M>1hK71wL&4< zK8BaQ!$;fu!tYD2=C?b3x0ls>cWhC0+;mDgFN*`hwo&)hu|C!g4!c3*FPkn4YZvtm z?Wg+hw;Q%iyT|9g_buZs7ZSov*8>f!jw4>{*8;39PrD24m&@OkmagCKJKj6H;5J_R zc`DkEitT(yZUHA**RK?W=;tlxZyoP9`+CqdC?`>b9 zrx?w5A?CTa;T^A5-~(#%$HKkAK`VW?(}RN>{r5RKyQbX~Y&wjN`!+j5JI`ckex?CL ztLwJ;@EN5QelKtKp8onDsT@2k408Wc`_)^7(62bTc>LZl3LYYuK4s*P32-Zta+SJ#ggYB=z^s$;_CKjd~! z+ofe+Au^H>M31yf!0Zn@MNb3+Koda{3zHW2zY@d)0Zd$}@^HcdwO>VOu0ZK4;Q8vQ zsjF&ZI&N#;WO){dB(e+)Wuh@N0Kp%1Bt}&$SlarJC%BJpUh#_x%Ct7$k!z%$I$1h@ z8^7yvCjuS>F1iR_1pXV0KlUIXJvcsGoZ12yl1Eadrr3J0(eb`%tVG%qQrr`qR1qBfA38>ZHBDd&EHjg`f$~) zPJB72Ir`0nTSrU#6m#0s#@gDMsE?+nTYL0c-pYjG%A0=kYU{~@>+Ehu)~T$ZIbqPL zvDLYVTbV?gcX{=t09~@YjGlWKmzFwT6!gjZNVft*|ah^R!A2>lySr*4a=mRkdrql(cdo8BoR%x|yWr zS$E&*o~Fu|o#8|-V5(@mYS_4jI?La^uXVhqW4?7E@z|t$?sd*Ub!<|sEhjY%?YpGs z9`|13e9u|JkBPz_H&aqy?wcmEyv`ykTF#c)Ze#-XA9L<||Q#f_ti>o4_IP+rLH<+ViEW#zPC?WM2Mdbx2|jn!}L z=4KCijrv)?WtaH<>HNJ?H6~FI=3jXD6szx6Ej9J6-^0?hU<0>Y)t*byW_*7M@Ks|I+oXER>?=}Q+px*V%(NiyvB));Z3qe4BSdqE$wZ@(@(Y3*%K z7oA75dx_AeCBo82iD9m?xm{&AR?b8A#;As*a%)+3c;K zxdGxcW&HN`LrY_;M##H{llUt=%^W2OWtA5v{CxA+>o5OqG;SW2q~xyO2Nyt&?Hd0o zJLoogu8I);>+AM>zIb@J`5s%IU46ezGf|*I%aljooI{50Igmue%$mFE)qm(jm-35{ zlX%9-DRQO37HPza>3SEj0)j_;OB&G8wFhI_r{Z5Pf*~G207U5aN65qOe@BEJrRt6f z8)c>v4-OmWqf(Le0L(*{Pn)L99uKN_heqA7y|v3JJFukdzl^H3qLyC zS60>?hay>9Pw&Wm?`nD4&V9~XZW5T*-|iap?avU%A3C3Ny^q4}{Emt7^}W07+TXa6 zWwU6$im8g6s-HszoceYxrx+@G5loe>Z@-Q$qh(8K-mmD} zDw+F}E%xum=9ilarToqt-VJ7MDw30TdDiU5iZ!zG+sYx!>w?t^rUgZ{?}sbHb1~$5 z*|w$19px$lYlo5>lzqMeTF(>uLJkvaP8w}DYAtRyHJ@??+TTmuUjN;+dFeSGHWdQ} z2`zVnNdsMtNC;pMD8l58P(s({qwaK5ni@F|y^Kf6fT(*#0Mx=sIG)ip?~;a%NFu;@ z!&!LI|3*}@+Rk?o5gY)>xu84`fL$$lmt+B}Ye$aSEgCPNk#=}^h9L`O74DjsMB%pCwyBfY|WjNkB+)E>iJPi)ARQiteWpK9sFOK zxl;2lyIUtE1wyiIy*{E}_w^MfYumJCS}(Sm-wkfx%(_O48gxHC7Vb9NK=!4G1mOJs z4vKLsJ76rs@&Refl{o=uIR5Gc?`ZzWVaSolR98;SAWA3)Rvadc#&6rOG9V?nZ7j9_ z`?n(H4~9i4s$Wr^zqEhmGrOpNYqSXNcRDqGK0mJ@&01Hzl=bv&+I6n|(%!)7XlcgO zGy8oR83Tq;9Qt*z+9II`K+WEGiU`!+PhyNI=sHEZ4TS8-5?vW z<7vbCqvs&Vt+C9q9XIi=qYOjkij1|WM}$lQHC7-6pN(pcYsRf?%RVEu0L*Y!sejwu zleJ5MP_47O^+*Tj#1Asg)gSYn*~ho4^5utEQ?hm^k0vx+HbS% zgsw*e&{$h7Y+QU?UC-J&?w|2>?Jwc(-=EO*AEqB39)5$rV+y+GB71LR=OPDP32a=B zUylo&$G$&&jTOAQ&}e_@!*4q%UuZv@+rb`t%PRwL9YK=kS#hM*H;kIN@8}yzKdowC*)kyuWs{q$GUNDU|!t(g9wuI`@8V z+5U4^%dDu1nf#YANdQl~?#q8Lu zJcjoEs^nmSIJIz=(v3rhi$N0ov~VZnD5u^cb<1khCAw#_-}&fGP<1;yOKnz8;P*(o z9d?x%HYQMj9~gR=Wf7k5#@2iXjFbCgQeXO;kTA#Io>GO;ZZ7;@w{(0a#Ns{0Gk6Ir zocYmquoFWu#%c8s|M&CUF3lvwKpr&#d zT|KOe<;lD}If3$SKZ=G!W`^AXgtA1IxN-Za>imP#it9PYtmH-B#Yax zP5&OfXA_t5&$Z6h*2lCc3lZHK4gfOe6ELCYJ`!elZkBsv+0!?oo(`kQ;&}cu2Ug)Uy7emU~mkRP# zM;WR9ZCy31@6&rnhWVmmw}{T@RT!U*l`Mcj#y9^ss<7eR$5bKodQ%%S0cI2;`RRH8 za-{K--}}`{Pd$?F4oyib6IZ<5MYa>0Qe2c787%~gA*vG(ap0$Z^s$Rtf)ne?!VxjV z@!b6NKXje)S19+8K_y+3dP7^uyz8fGmk;$iTMB%8qsXiHLG`Ap2=D zSVfG!z(zFW!`n`bSMG9$`=c6bWz0Oe?*o3V((BC+JCEI;UfjQfDwI`CNF{!@KnNtN zr{;zOu2r&By3+4h*8s&TzDVh25 zWtn+woFqGKF+kJoqHfAReK9|jgnj}*n|+tpFstps&)H)}edcoQs-HSguR-S)p|3~? z#{L=~_$>=t9tJ2uZ2<^0&!=Fgh~#z0fT0J#Mgl%+tZ(%}CSH0P#+xn}bv5~E6ywFd zr67SZ!<{w$t3pHfFQFBXSmP!`PBbwR^ab^WJt6%Mh%zK{%L2{Jl+;JtcATIZQw*`@F2W!lCG#M3pDU9E-5lWo=gvzmx?Z zZ;T6Xo8kP5Kf_n55U+fTOXWjgq#>O<+VNndK-3&?7+U%Q(A2>>0l>?IOXKtfiE5Ye z%+Mfx>wg%pP81ybwd+Vb0anjp+t)gJ{)HStbqP0oC8|slGNzu2KOohQ``A-Nua+VD zO}3`n9T5m9rk`dW5!?kaR09Wa@k$1@&oDiik}b<2+M1ft1(KzlMl2r^RlRfQ~0CuzMJ7GSAnMGoK-ti|5E7s}mpBlkqOiv$7-fe`$F>pBl`v27eFpNYVt8BQW zGuhc&Eas1MMUJfb*V69t4~zecw(#rynVWAf-#xYU6@31_ne#!%E!SxX?T#GkoDEI8 zTw27!qc0eQ^Km;u<;42GmkSMqHZ79;4-``Dm-HB^v^qXtJ z^DCD3`*U;QgcusR8WWF()?TX`Gmhi^b`!WmlX{cvFN`N z)+l!ZPZm?~w`uE7+>=>`v}0pZYN6459j8BXWMnH3`+N%9Pjq>?9E4i@S8kZ7xS3>*=VBD^G}k-Dh3B_G)ZL4wOkbk&a6@> zA8J~KS|Y>yUzuGY4wW-$(i7kc#j{2p7ndDP?EYa{b|4kLWJUmk6vNj~Nrq#1RctsR zw=~nQV7Yh_L|?&n_wW%1V~+Z6=NUs7#(jF8>d^W2|Har@HMH49SvW}X;!xZjio3hJ zySuv1p<^9OQwa^AD|TF(<4li846ftNR|UTkgw z&n^VH=7cjxV7-AlfEcAp2L%9`;Gi1361I4f93~GQ6)i>uHOXV6K?XJ4 zQQBzx(7u~u*O$kIPwxid#pTM5|JmbF(etKSu;ar$ z!ee+8Y@gM)L6}Hb+}PwfYJ~&rf`&23b2C=;V8zs-3M=1QOS9Q zM}H>a*{RYWOjA9R3Tr>zmWCqbI=BKvZPvdQN1tpoWmZI~nIeAl!b z#&{vYzu$^$3xiICoa)>{FS%AAIkzL1{3w=JtThI+MmDZVHPS=8Rsyb>(S!ud3uzey z&F%Y2zdcL0@Hq{Qh_#8lD43Y!uZK~>6~AXKw@z0=e86;uLBr-9EY#_f9_YiIg0`^q zYdAp|`t1A)dATsD;e-VJh%l>Z;?noql&P91fZm5LxTsxse+SRf4*&a?sU_Fpc-#_> zT+HY&VPfZ`9x01a97m;H_w&0!gnmu~pgx01L1np(jus0t%t!H4`{N-cq;R|@NiYCA zoFH|cOCP}&APb;?rx6EaNn8hoUf*$|kiT42dH7tUx5vUpUriMfViKgmeCBM;Fg%%e zx8m=|T$!?u^5R+vpzdpqNYtid3p!#Y-D&p=Ir(BYwn;fG7%0g(rK?V>WUNMSU;jY!UbEx$p<56o7vSD`3bGhya` z0XlGHEjt;~zu0+b2)Ybr?;M?L$|S`bMjt3+uaK(au5U0!!bQ+Lv|6d3ZpM&^(rwB{ z$19eKtDOp_fIIVqQW%kXtt6@1%KjP}_(me#c#N_TPdgL?ILsS+vuW_)00B;3(zDJm z;;ERD*crI%Mi_&N3;wI5cBG{4AR=GE{Mb@M7ez%(YRrW=&w~4uFGta~eVk%KIyFn_ zjvIl%Z)7z741gpqbq&yJqWRhW`qR8W70E_a!=I9G3!TuFVI! z-?P|}oRWUDo?xsfa%EC6-lP^MGei+l<7r@)P-If6X{jXUtkh;n%n}(v{d?KEoQjkY zEevhkMn(zCj)fIKnnIk?q*V3*#IBU3H!cagXk}zT6FgZiirE<`-B0V_Fgevs*>J|#> zvwEWz`$zq~_e-w!)cFvxZNhKlaLky;rZ3U2Hl{$ z3fbkP=e7O)LfCx@o+N)?r@KG5Kd!FV9j(Sps2y#;I&muVlX{y`HWQxKI7>6ABe^*n z)+}9bauHOZY1k&91=G%HNpMq_kTevXI-3SQuQq309v}AX7&*-P1pW+ted-i_izDCY z2$Gw1t8|R?382`igHi%MIM`jduNug>QP+wSGH5h%(}5}_Gtv95;u9^^&PgLE-J<}B zNFY(fZ!3=847?N9+@&02?jY9=!t+_p01y{ zHGj-$KCnG!Q@DmLwbcNZW%YaBvYMU@-|$H5oCrb4VuA#EtUia=u+< zvkr9Uvg&N;3BUh2t&@vU*qfAsbo=eblg^61Pd4v0cCOD~Zr$)12f5Ep6b1ZwObLAn z2I=CSq&IOx3!jo~nJBFXp5)_FIJhe9p``moQAXyDP*cdYty1rf%yU{B8?rEBPdu{6$;5v3I>j$Jcp`cP6 z9Q#2j#Ck1ZaN7pIAk2UmOTuKKQlqn}Hz*r64pay2n z$;4>1*Abj5jZ%}WIErhAKLHbZ6qC}VvpogA1g&yjF)ZRS7SK;7t@Yt|ZVo&SCr2PE zZ84(wKM0iQgOmmX-ADrn2y&v?Tyl<}b1Mvt*$cyeS7V~#%yo5u;h+?#K?|Fr?4d9f zY1ONSJ7pmWG~?N7K%Drcr;oS~iAHddJY^+jZT*LG5Ie68;gs^F6>%x`tt`?c>DR39 zQ$eH7oX!<{KD659M@;jQ2Bq}oHfTh4zowIZPSD-)J>NYQ=xO+6@@1@P_*r%5ni?CZ z9zv$1x$bf(YX0I6m3q}xCeG`Xm8a8aoM=j{6A`5ZNm@(d27FU=ZZi~mCUnHc;~r5x zy24S@rKb3elh8HH2KdLIlUR4UB{CKsfn3!7gnsW2AhW*M&emWwL;i+kCg) zG@8RfoecBeb9bE>&yQZSBBAfEoo+kZk|fQuX9`Pe=g?jM^J^+PkWyiX zkmJe>#mZA?P*M4J@TO2NL)>7xhxa8281b0#Fl1$V1T^-o7%M(=6&3oHK~D*Hm2iPp z(xW1%yL~;kVFvpo1k84=+LPf zVYk)EDyp`#{zUJNm|k6e3rSNQZZzy%qN$@(a5&O9cCRc2yetF3$5MDY0F3f6GGRE@ z2iRsiy{B|!1$m6$YoQod#c5a4Cdq>NqFnZU(w+^e@zJ;r8u(w!8-mb9zACTtlO5QY z5@~AJjAkjqpQpm~;Zn>gnICYNivyzG!?BRVpuJW^ae%FRGD7lxbj4)oYl5EN<(AJw z(B;@cd%|`gEW9Nk3Sx0h_JL7yR$bAerMI=qr)0h!x1wRCvlUV1a`@5DwlcqqP&P}^ zE;ZVMt42A9nO5G6h%w9NWbUg*I6FxS-*cam27^jrTfQDA3NAy0VxC#lVr<+LRwrL38Wk`(-@^3=Jy68AzHf>WZufc$v#C z=_~18Ml?(35yVawY5wb+lv18bAu8wSTFLJM! z@-~0^ZKvyb>ltHHL_j3?e6=eB((Cp2Md zHkw~k*nc*EoVQp5T)v{+4&NUH3AAV36ATg&_wC>kK zT^NGI$c!Ftm5dkuPA9iJc?P2RAX_FvAm>+QJXnHq}VodF0E zy(&DmDK)CK;n503N?^w8Ph4GD!Dk*0P-|V)=j*J4pR%8G?D^DyqVzt-ZYpwFf)Urr zu!R32kZp9k*|8XSlTH+W92~Stgkk5W=Sdi2anh{G-wY44lQzne9IZ8J)>u~aJ;QN# zmwGe%DrNJfKW-?ASX9K%=S<%a@rI9O*)yTgw=685`J7$2=Qx;P!2(brT!2|RcGCmr zS_M2=S^xJ zyY}P(^|V!!5fJoqBF?ue+bE;Wut!4nTlg9Uw!}G*r-5&3Ms9gZi0}M4x+@=!V{2=& zOi{l(&2E+~4xWmVqg1L%-V_N|+I)hn_Y*=cvOGnEo$vUJ;aMVWgkt%EN7afMG8`XA zma~hCVv%=e%f$x%^}@0v$iorfL$dO9Z#V!Y!kT-g4L!1Y0n&5uYh>W%P^!%G<|*H8 z+wb>RMPZNI=|!kMNpryKui4w=(J5YQ*O#}({wEMkPSIMI`|W-{@bWtJAI7_2Z84XX z^*#8f#S{x!@a@%)rTve5rk{QeonC8F%ZhK1qdDC79AOD%~3DR{`=-cx+M3}>=S&3xc$ zfk$8cfX-8PWv#@ZSQOy9VctjJck}m2TFNmEWGtAgEm?fLTEl~8*ZBRkp}J#k7Fnhm z9!e6oN+eFLkA6TZhrxWKv;~+;M-7Y({uaSaJgqYm@pK@( z?0Vnsa?$cX-?xI1HI!qDjY1=AyGu8KMMY?w5a2W4*)fJ*nQ{z{i9R6n-~;C#gEMbI zFR!4$SI*iFZ36xyfVvexH!QncC(n;*`LBKNWg>@6WfoF|e`YtoBa)6?kw0#jgNARQ zk{U>m#}dkcC1QfyVjc(I;!~u5ymM71vYqV>UVe1X)54x{xR+)`u*+(L}WLTRMA>h6mpC71P&5=No#+5Dteh9 ze|vI!sRN>Fjctcq%*&CfrteptxplvN&F_EgOi@;uCHZ~|Xbt^yHS%eu(Ekb!BI18H z1nGYQFRBgj3y3@qVTi3d>l6mPb$LJwY^O$kJ0TAjek8FOyH0W`A}`}6W@m@~84E34ISF|^ zGfRWL40s^*^5Sajdpo@+Mcwcsv5cQ$|!=So=t-evLM2b?I;au;8Tn* zzhk;O&a&T@2Y?%*Hwo|ic0~a%ClyLZ#2L%^7#ABHE4Jh%%Ip*g5hbSzZr(vDVo!#C z%-xWFzecyu&?uzU@N{s!xm zPHl~Zw#&^mvBj!_-ZpeJ=}TaV-PLfr+fiEpFA5%Pq@03cSQ{9dl43+GN<55A0uX2p zdqt+sbRqBt+zD7+J%l6g73-ue6n<^zq?ORXr1e7h6R>>MT)KPCy~8HFZrs6uwp&DoSCUZa@F zS%%+zBFuZ(9|ZH-5ciiOXGw|bPA4L1zUF75=7>a-BWBB`25P)$CI5NGI|S*-6+c{?X|t{pxdoUGlOuX>!9 zPD(TQVQPbvxO#M-@JftLR~ZT%`TUY%D5SB+%egBa2qQlLo8HeUdKhHAWs7Gr9{af?{H#iRie7j$ zk_ZNeQD|RBUTOw{F30P}D*ecMFH9hXj;f6&`UX8;URIk2YF1?Zc07)gjV>`s@;!UI z+F#ChNMC2X?9##Bj`4<|>mdx0tG9>k*9x}x?Pa|SGczM0zx&PEx6Rqm3#Xmc9>}Cq zW6vc<|I0z-^TU?st4`=$c4){Ah)?Y9)(a!#$_o0Ag|FcM9{CV_qGZ->IkpVxd8Zb; zSuA=k6MIW>BNKT6ji_zE4`Pr9KkuKPpTl7YU**4F^6k8bKYWrwPK-e(MTsb8h(Cg! zuFVy(uBAUAAVcUNe<89yV1)S~H^*RS7tKEc# z{M`}$SMrde5*o<4+U2sofh7Im1Ha^$j+&=2?yOko^)jSE`05Q~-}cMDxRHmgzV~D& z;7L(_kyz9BrLDf_uS3;|8F^B0)-a#hQA=>6wcdOx9`nFb`43`~rZ>W+;zZ*_R}81YnZt&o zmq#Lz;Es6qTC|AvEI9X-M##4Eh_Ox=6I_ZmT^+`i2{o*ySWfmZ-m6p)11vL>d9{4{U?^ZSCKL$~?vvHAt}+gv{~3@l2&rJQMMBg5D$)GtM(kL1$@Hx$yI60#zDU> z&X6+(vqXIcF32JY>lnxvOA#dv3qU-E55U+CvSk~L0pzK}5QHVBVrF^`XQ3sAO*JTE zpL??stt2tI@*4sRfo9#t3?du?T);{L%{l?ZfRh61l<-!nUoQ)PPI1)4goq9h8+u$H zc=T4Ba6YNAnh5`$d5T^^-x`0|N3opfMWmF%>Jd}&=>KUMBsYi&!0bi5B)ucN~WQEcV1Pqp{H6! zPbWn$HP4qlLMn(76r%r1FnX_sQHAh*x4rj315o#6XXwq(9h#x{%bmA%w)g8#s$@{Y zemngow91lZ*Wc>)KCQR)xch!4778sy1VXIq?v^^qf{t$g9%>&H2Dz@bvO`>u^ewKV z5i8^6cEij9A2)H-3jB8vMe8N+{APt0Yi%($$^+ z!oo39Wmpwv$A+DM$lJX##>@dtw}~`!CDMZs5xa9;6sp8(n#gdL;XjRIE{Gt|i0&hDlN~o(;hTx`VR<1T47~Xrno0H%!quf#@JVzF9pr!qMuw}YM)ou2+p*@MS zpv#uUup$DmY<}J&UU!C(1=p{JcmF%)w>Yb9;-YY;B9jvX{wNoKIRLe z8Zk8lO>NWBH@HiTZ<6~ZD@^hJZx&z%@2m=T!|f-*hwIzloL8IYQ=}ekJOA)ctHT!l ztd>}GASI&N6ed5Nh4UI}@%n1kY@(Ga=6w2Ey;cpu&g6&WCNAs?TN_ly_C7>OYr?`t z+BHQPucwPB5MuuTtP9=daM{j8_^p2{o$B=}9EY(M-}C6k`gtBKs2a5K$@e2F5RWRE z$)kd){61NBuSJXj;kC3ii;cCRK-7n_rURX{+sF4Parx)M+9JJ~5K7;4542ZuB3Sja zbb71|iw5*c)$mgbC-eri0?ijseeQ$~R^~(QbKM}@?N=E^uW@G2%kQt@&pTX1zOzMQ zH*2$RYANKR!a|)Fb1HoAL)q_FPjwhzE1&zRzma-oudBONuHBC_O4->PIMW-Ky?@o- ze}z5{28G!B1|AK(C+)mE&c3fsp3d79iFsb-_54crJJ;9OU;VqF#P-vp*FWU%d2Z{# ztnI zwIg2kK-TCB9aX?)A$vkXp9~>g&nC`RlxGYST)GG!QO^elp4NZLk%in`K8v#R2;Kbo zwPPaqu<$8lwvsRsu^A*$5M1^(h< zP}*s7G@@K_@85_PQ%Enmi7Ec{C~KU`;3@|@Zu#%$UK;Rm+8PCZ6m3fem3zIC92q1Y0I zr3tb*I7)fhT>=uLBNfwRf?qUo@M*1N3X0m$87V;4_A5k+3LXH(E5C>oif{pfDzQuX zlFj^2HyY2^f?n_Vj9)js*nY3)j(O|2`0~L(qw^0z!AAfEMM9hjVP;GN26RaaX91!h z(Ai-0LzyFPgWIjI>ws+z)rV#@Zlu|nQu+^+ucrbLd5BOEyPte&39g!|iC&WRQlDmyZYsF)Nhb6v|U8YC)UGSqIYz%*-RgY)ahG zP#puRQxXStspN-B?%)aoMo;jMtUOK7HU$n%hG7zB5|50ZYq zG_>E+(j4gc_eYnO+brEsPs4i1;+yVz05CyG>q0j)^X{XLT?gXDMI*_DaNs{uaS<^- zJb4ijp5U7jV$;VZqxL{mh!5U!t=z z=(F=KCYUkK^MP(+51Xwk=K}%0jz@bb!hvHZdfA76gsNsg7m_d4f{0yvJwig>dK!CM zy86=&_JF884PEz+pseP@;f3fS^Cp+)4o99Y_uXN8?(LwT{RyAg3WPnV;+K}Z&wdZR zj;R$?^KAtALP8JMKB*O%E-3asjzYcCdZF#D^9CaCliLEpC+C*NMLRwtuT^@1vwgQ0 zYHxG@jhvU4lWYh_8caaZT?%@miri6^!~7LawEQt|KdF!U?~XS*H$&e0;q=HvLY^kZ z2HqZvx;-GgjM5?~8&ehzm~m12Z3INwdUeR*Q(Q`z@(SW#SCLr|BY(1cZ@G$!^kLLo z>I>e($17oG-US}{9D8bUp9#^n1DMcrN-(iuhKwZHkYmTG4-;h^P#N380DYKKKR!IY z6^DwFnldc#(EhTe)ukDW^vJ7>yuXY)oC)+nbf;yWEG7A7yIEl00D4%zAl-J7zF1X? z8z&>ggvSYxg@6!^@|HZY5HuBspu7})EGDR5ijxaKL4~y&3O6`4_%4R|wH9g=yWW5l z3>eK=qAe_AEa;>D#(O($-z-q}*ugvAWHrpT4S)L9T_1|knPaRZ7=)&28z zGTgbR7Mklij|{$+!-`AFB1ed~u>JD%@;bAuGl4i)F5)~x(WD-E9|eI)O%boV?!MRJ zX$g*?!Xtcf#|scKf7Dx3)emUru+1@bSRGu`EOcZ$URkjqUGeJ|eMar^ZO1x}P(*Q@ z{$IeRDU*h4 zC@}KIa_yo^cGm3))%3Z6`t<$X0#@g!gI!YlG z;wAcsexBQJ>*i!3IVvpQbnI5|%g4u={j7f8b>Cg!Sl{6P_u$|Tv}^LPIYfp(%WAtf z5BIQh3CbFFynso>wXUbtj4dU=Q0X8b+(w8S=HoQq6h=v+ zLFfAkHoHlTtr|y*MQ@3Wzv{i>$BvvVayHo4LV}sFOsGa(kN--5UdGK$&rfIQThL(9X<5q4X{OD* zBTuyYo`!6-cQGIlz&3{#lVD*kwDl!0klcK$`Sv$5cQyk9oY*@tFhkyd3{!cSP3U>-goJ=^l8Kh9j-D+t(3O+8W!hP_-w6EE19rMVmPM3@h8f zmh;a@Q?i&v1sk%#Qh68;D=#T{1KryUd%DzVhFUyYb|y*|$wGX5q~|`a4f>H^kODW= znJNnq29DqwDI84*uBIRvTgqsiVESu#pXCZqK(eMH0;+hWwU)nlKYwwWmM2@*y-agiyw-R^SaBA|j_{4pHv z%$O1&$tX2^@XKxDpJyg+p%1TeL2jc?XAOn9JDG4PfD&`9wG)38m1Y`~UydxU?b5p& z%F@}&u$wWA88s(ZuBtrT;PUbS(UvD$DaZ$0<^UJc`)JLv%|SlNadSp=(ssR=*b+^h zitJntv?J;;XDp;_Y>fpXL4i(ATyeLgohF?w`5zA|q%Dpk^WuvFPEY7D$hUh!Ax#9T z7dgEr_eNDmu7bW)L1(uWB8ZLuaUPG)##9UW-wK1=b_V=82aid4MG&1w4_WrzR-Y@L{KL~iN^g%+7 zrY3jC-tO%}Uha+DHV=WH<0ToRW4DFw3v9aDSruv}QyD*E!C(WBtiuo7zY`$XR2eC& zL15~IzLAlH-_y!Z2KC(twskQY-I+ufBH_(WLF1hOHpZ*u-uAGs)mP>$TJ>2?C;m5o z++WdhL5}v0I-Cv16*8w(C`V_SWcg7({^lpf&i`wUi6|j>8px6la%3ZIP1K%CUlND135w+>UY1TE=bJpC0gU-Y zeN0G(G8}Xc^069%B*|=J$j&Yw8&(6@l@!MFtgKmkr^BgcH!sN4_8BOfd%I8aaJqxD zhAv9oGxB(n+b3C#MR^6bggd_nF2701P`2q7qQa-8s2K2rR)=KQ#dKVId4Spp8t~jg zeb3;u>Q54XcntHIvUSVFl?*0Kb$qln>exUm1JNNaj+%Hj-D^Hf>l~fW=t>vZ5yOGD zbu?d5g7SaO_?)S9djAEMgJUD`En8Qn&ywQG!Bi+ol(W)5X1p9kiY>vCKV;(QXIV%C z9Iqk|i#u@r8QlJ8mUOkxxN0CXEGbmBsmqiZFVBvm zDJc|*#Hn2}VbZyHGm|8@_Ghj2?5r+H_M(!wvFGg+xHvt2&4F*XD6y94S0w0rG9QES zUPk_!HnEnQl$8+rckZ35MO!mC*ht90RvrnI5?QR6A>*-n;d@hBU_XoTRltG(-mp}m zRT+gTrmA(?3e}4%;gitn_OA(ed5Y0mMZrFFdo}(%(+RfB0C$LAmfo}bm?|a>{__s} z4l^rKAqWg%^i6@A4{J1s_cJrs;>K!QbhQxtVat@9BzTeKAtdfbX;DEZdbfhgY}S#p z*Rfxqv4!m02)}RS-w$I3-?V7+1tXd=OZ>Ks~hW8{Ss=I=2nx*iA{HY;xiU*;#;t#*eH+F!*>pt*o&x zgzEG6`9hRG`%v!3j9dP=%kSLoSLmX6-P|el?rCJ+)2}H9pBYVny$J)CXH8a3) zWjecx&NuWHQB*s@n&Wcd?X>g#x^Ce4Z;CL#K;O|xS>%x#n(O!7WGOxpC>rFYb(W+M zSo`)bCAc1YjS8Z8(zXCp^=lE)!+-VuF0V~6!eqbfw4o?PL!-c_8iS{kP)b97=jEk= zNUS))LJPqJ#LgK~M**xEqcax-5|E^SoGUp2DC4Ozh#|qnu<$bp+$dRIUw4D5xe4f1 zK$9{z@ME{gEA$`6?V6CXL~ju{?gd z5;bORdUUZRyKtFLM>|hW!8)z>NTjASE#j$1kxi zL}Odid!&);QePCZRhh5&?VViiiq!hVhZNzhzzg!a@C)K|S$L9Ln3xNLAb!_q73pj3WZQKq#8QU3gav_G)huoZn*5BM$kqtO? z94I7TV-glHDsP%+^g2Adgg|e)ffZ z$)FJNt%=Asppo1zj&)*TD(&v`a-yx|SP39*&v3+~JJ4chp=5buBOypF^$L?i?IZDR ztjqj~uPDKJzn{0-_a1>OW_rVfhZG$d#EKsTEbNx?t0?(+&YFZarpqXybSFJjho!Ck zo`uDIO_<3y|G6EWV)q;EHyct<7yvdR5 zn_6|O{K=k?Xx?5I_ZT7n_MBF}{aOa^FBNvJ!6_jot0{lWQtJfowI^+O5SjIVu?hBR z$CIYVU36PD?^9;>a+ zvGtFJ+Yf~%KYA_B+er&#ubKFWtU7Iz39kux0#Xi6_LY3Da%;P}z5p-(!%f>NHnR7n zMXnn}vw+8+7e?eSBWBMFe>9zhw{<5Y+GQ-TkPPHYqHeEQykwbE0C-+B639!D^DRde zz!`T-ON}R;U%#6ukoe_Fdv^v%;q`I5O?Q}Uk}(C{r}Cm?=HijUkU>0uXJ#(8+JC9w zsexasNq+44S8aKbaMRzbO_50Oq&bS&&8E4NIoh=?<8&mV%vH_%@59%!6C?^rmw|vz z2{#}XRz=U+!_TKvd=WtRspBvJ5&;Zpn3N~@q<0)f{4ou4(jG)Z0fR|F#l_j`C4UYe zm=pMi#F@VL`_7BGv9K%fWxsjPufYER(XB7wja&4wGi2{7Eix1WdAn}ve10>sgD(2z z6v>V}+%|WR;nh@iGQL9;R7a(7`Mc~2`;JE^ee0T=+UN6gO^}#P)9?8@U3rY!g@47j zRZA~ZEoNkZl4cb3YxK&3Vb7fL_*)tPikU^kT*uzLOi7bZ>)@#+m?#Rg+R^XaYI1uX z4XxwZcbX1MS$|hc0+xMj^6#XHf4+ z7qFrWpXhsFKyb)O|I_fUsYT}^Omv9~+{tO$4$5n~9JtHXm3Qy&w>`<|W&V%7_GT7z zrv8tAQcV3t`~p23e0Sa^9;0i5gD{Gjnahp%V)(wfxjM7Dxth(kY&~C!JucaahFE(L z#fz3CXKc@0j-F3>_v~Oq8iE9oNhqGC;$a8}!?7k014f~$H-l}pjAYFZX-aYiw0Sv> z(+4LxlsCa!7rxg^ONMWkzwehe3p^^aO?z)ol|F?+{N8nVkoH_5Yhv#hz-iQhrw36! zlKaj-aas32)Iz#@z0ZeYivC&Wot){h1z&+TSf@kZywnQ#yTn5rbuO*V+rL_1C>PoM z`OtrTs+sxW16ndjr&<{E_d-bM+WN;6IZ5RY8bHG6s}>geObJ}VJrtl*nMPQ81Uw~$ zptP(kf_oSm3lz@3MK#Z+`RO0d!Kt?eeEeV&HTw_A78T!_ytfS<@^z^~{#$J-yCeXN zs{R;Y#5wciV+E%jGa8<5v55sRR?Y!er>xlLLh<=ejF8{fFEpkFRe_5rZB^ zASwy?jfokKRL>JVlgL<3U!e`Fo(k9{A#wrv(6C=Ii2EjUxmdE@CgOY*iD^Fy{dXDd z=O*@8qsHx2u@drh4SvEihW2m-*E$DoF4iV${Mo-h&+I)E2s3?`N9Yl%TVX8-r6s>O z&n@EjH}BWJ*7sPlr$go;O6YX;rKkT?+um|e&%UK<*RG2?`gav~u6`CxE;livdi_dz z1a}fYU7jhN0VSQ#tKbOwR5%Lg2OBrE$!B2(yPWeA;5*+hi9#KSSb1@D~3Urj_voH znTcA7ll)E+Tms^VfMc2nNp*m9p*!6}Ii(OZ5dHVkhi?-I$`;-=F*2x|{tUjq+#pJ# zsQnZG!e-^J#ZhgY<_VjpQ%IQSPmv1<+4Fs_C<xt5*3fhHDc zjJi6y+xtb1?`22sm%OjKs>p;q{uIw>xeMN=k1MSMLH@XWbadH`Y;2^$%KK?oVR(_& z>VSxFk|yz_*dJuAUcQ-!Kw&rLxcCSvJi!sen$3c0Gz2H0X_clE`X7sSjgN}7HMKK3 zZ#(bTM-b!hw}T=N^*jD92;Q6K2a&Tej|XJWky#ey4N4`W_?$euR;YCQyn_uTGY z5bHI#ZuZmZ_#Uqg_e%xYX!Cr);OiJn)XrQ!J#chkLNO|gpR5qaTA4hcN}{EY5OfGp z3dk~E8E%4+@BhS(`YSc@h8?AyW0Z*En<5gGH9&3<>6ic{ML|Cv$8U;X3erMF?;p<%Ua9~pek7uSp9)H3^Qt)(7hmK(Nd*WIzRm<)06o)%Jub> zc4@b2fNC+n2vu&-dB$_`EpIaN=S|l)nh1VZy9Szno7> zM3?huA8$%C9Y5$X*=(-b&rXwTo7M=~^U*ua_y?RXGamqf`KGbugSaFJ?XE%UjmyA^ zEbiZ!KKx_45Wo;y?S!D_)0RFLKg0NlcA4s8*F!L?Tf}Ogkag$oune>yR zxI~`#NXOy#&M>eN#UA|lWDfKsI%q3zFZorC+vj4h(P}4OUKZ5)xx`F{#hz~5KA&&A zUp_<3`aBPs<;a7M-=0si(q|SA>c~Uhy9Nq@4djB~AMQcFHiXXnin{my%^TRoM4Afn z1h5ka;bfo|9yuk;O?+#n-fPk9`cp8a89UZtTy#^`U8Q&)^%+2lohFWNtw2E4`sHR} zO1W-v?ehx#oLeyqhq~=3IEl7Jt`MR~_bYhT_c;~0K-n?ylouHAW@xFV@e@T`E`ayVgOigcR=V-u*-kTmZ zNGMB!`_ncLJrm{Y-|w0YjAAGwEj;5aq)-F9qAa|06(}=3Y}J7h%{fp)E}9iBn&g-hlh5Og0@kDXFYDK}y&Kc0<<*~@~ zA>!ZrvfaK3j@VbNPX@s7|ZS0ZU5Xe@~9AxxI z8dpDNVJ5yf96L29#faP-3>-``S4R^VyW}d$y@W7G^Kk)=!de?!2_@J!nO`nVC}Jui z`kF%5?EUaWqBi96CZ%!9^lkoT_U+Z|k*fdgF#mn0DA?+KVZn+#2+9W?z}9r?>*;w; za(hX6z7+9!5b-n2H_9#&3bl2)TiM|4mR6>9^4*(@9uq$d?8DN?_ei2H#FANaYM4up4^eEW{OxNig9!DX3tm(xs1J z;Dj!|W7himJUyo1tZWcfJMjpOBN+kqg%<4MQc5tt&_&DP+DOk8B$|P{w zEp)pZoYsfW%z)QVb%svfe#Rj}gxCdKa#o}UB!so%i6o2L!8yYiU(Q&l1Z~a5X=o%V zd=nGV0dpLNG2*JJI3B$$(neJz{}vBUl`Udz>{qevEl&jUor`vd9$PSgFsfval7|o< zY%GIySOsgrgpB-|yZV|I`_dGIB*_2Jbk==M|L@-(qb8t?kd85tMv#zB=?0PR?v{p; z(p}OGQqmyZT>{c6-Q6*+eXrl+a|`yzd#`$)=Xo5cTBM41^)l9frYC$3kNP4=WkYUX zZ{Ca@s>6ruUlup?Ub+{i#RIb8f2V_Kkca5(L*A!S54rd#JJI<`>{}$hE=!W(IRicN z@iA&^2ln|46qYA5CUKBrJ)R#{W_UbSsADs6J_c&fG{5ZAX2-LU4fORtxK^m8XQ$(s zWQ;|Pr$zN2r!%s2+)b&&&dYj~`FS`qiLFH=3z$hM}xBs}|;JI6)xT$Oe9S0e!=3?w8_gwg$gex1C=nc`t$5S{gf((33TDSZzH zQ9|x0+*dq=!+zA5!@~Rh$LBG6?J9O;?t8f{m3qF9l`jX@FYsG9s_SEmeaB zs7ERk6pF!9GmB#-yeT(6?vbU6QB!`pJeX!!*`isJs8un0@e`ALThkTAL< zmY@NMLI6luoqKp-U+rbO(Lt*?mrfEK!$bn=yAdwOVSWr8D zIk+~xOUHA1hx@;yGTs4N!JEJLn3PwWHwLY`*+1{}{;ZI^T(H20tN7f{lTx~RWZpOL zjvLQ5ta&`jRi@W4`rKUVe;vN`A$jv)pXKAjt>Jao^;tW8P7n6Ht&b3FAa{8094(C- zD*r&I@P>d|v4z|#+giMK&%Ye)U8}FTZy95+{r0)<3OOarDqb+v%E#^393b$+A@;)| zV|#~aJfQP`^@9jJkF*m>99F(cr)k{$?2r4_RZu%d7zq!+3Pk=0K;|)#066t)N}vPD zN&l$kVNkJJ^~~}@NkKQr^xxuQ>6mJeSZ3f0n2h%NWUJp!&9TXO9rgpA*Sv3H5KKN_ z^p?!8xV~A35T>_ieu=JUgcH8bu6F0WD{hQywDeB8kmd+Np{r?lNuL>y6#0!ywdJT^ zCJx);stiq0a*(=w{a87gsrIz9BgK*H1~s`9Y8I`)g{+8x(%abp0Cg%ITcbS;oK(*I z~%&Z>xedvoT@^M4R=Ieb-+mWQH4AK~nzpjC=Ej?$X)ER%I zPHOD7Rh!KS&x8-x&ddsezgSX%mG8s5b~JVN{w`*O7UHY8%b)~N_zOd9(H3*AWb~9i zDePJfq$-e9q9#hSb{p~!A}hCe``lJo2Uhq~nh(dA-5d!uRlz=5C04|Kubs4T`?kF} zdmyuXINLpyTNozb#nQ6`f|KRF3se6oHyBB5g0DkQ63wS=Pp z6y>kdWXYj{h7jloOE~#OLLzjav59Fxs3S*y!oa=mD<2_ooJO~~jBS;_e>@aGqr=?T z;?nnT|A|MFgAbtxwC5?7>vYxrVYi zVTHRkH9p_bcSi(W(71h$Qu#GZ#6fSq(F8GNP(&p!xW1xM<&L0;LP)HMjYSnb7q(JuM{E^WHApg-^qtGH+J}`SzkuJ8sVrT8?7n8A_Vtf4^^26$P$C zUhWlrU))}vWm#H(*VlR-{lX(;Y4^H1%PNt6S?G8=t=REiSM)wl?I>&QyzTqh@wgGw zalLa-Nx{d9JkD`|cPntlntOYE3K#Z-KlJaA(<)~0dt7X%_%7PiQFv`_9$L4oJ&#{{ z{DQ$#vs*TM$y3LJ^0*@~%YwxqW)6dIQse%;0|LPBG0adT2Hq?H@ZU_ix?Rtchw!f4 z(2b*r$ID0{L&2W4kN;IcgqX)T zBp?)nuA`0kAg!M0=cGsG>j!~VIO{8ELY|{J3#&E=|f>7ZwOeAoWc5@ z*+7E~ppwo5cfV5uVUV*48#RJI(+`U>7*DykrWP!H8Ix&TVMdQSSE|&}Z*$pqvfnaV z{$jOSZGSqIwJ;>pq(iiNeBIF8lXSgwn9jH@wd`o&`l91gQ_Ap`Jkgkno7l1T6Y0Y@ zhk!rtlx&802;B>GE0pAw6=n{CE<{DM|I{V}3QUEmp~65&#NLlC0>s($agsOb zCrU7{xwUhN(|6Z+TjB%=Xe(Yg2H>2D^ijs1b(DsNFiaG3;XOqoBDMjx*{UWy&|7W! z-E^~f)mk&YvN~#h3kxp|@hWm@!E-}+gVpm zK_RpGvUhaUFai6QUd#Evkm7f!+3r_y=qG%pa-{{Ib0fUB(Bmsa044@B4nPs844SJ2 z5_$eN&=v|0&cKLh-M3+XA>Ci&_}?|Ye`ofmNzSSrx*?{>V0rvQyna>9Lhvsy0kke< zPF>*WiO*8I56XBWi@8-str&#gj~_7q1#S=vyIjbQ9)Ral!n_R~PnOo6W@kq1;bpLU z>|Z**#kDKX^Y0Yf&-<4yz04(~?Gv%G-H-4(URqxMxxw#W;D}oqp;t=sN$c(Ebg_Qo z4*~f63gLK1b=!=-{-N(RW5=S60s;X0yW@Ha6Xx-JK#DEk(5jbS%0-Y?k(#u0D0DX& z@rX@E7TIse)BNHeGM>c;yBa)C7&vWmIe*B84{?PCm}kMKO1w@KYBW5cTqUlk&;(&b zW32%V4GL~3AT(&SlhP4Q0~!BKJlw$C)efBzdoDT0{1r=Qo?m-}oywULd%8Z}jqGW3u>==y9L=s?f`LMYh)tVJ7G9 zs{0V$P~}r5%lh~Yn;#^1-XB@?UxJcje8ywl5z>)TsOjpcv8b_` zL-DDl4%TnG{h!^>{3j6Xn9qmy7{ou~cGpbz0;2tub3!1Ih7c1czvxL`6sLfUP{|RM zZ{dG~;gOULKfEK_KTCWF{r{&}|Mi6WXA5kHhe7t{x-~E|Umr;Bx<19BRsSL4(yi31&Y;O~4jg{~C9mt%V5a(qwWpyNeUFQw3I503wYwSE8RK;Av^2>(o)MB)Apg`!C_4s$m`WZ% zm^pHi7vtH4AIsZNzNYD$wOIp?j6`5pj_NO}`&kU=tDjxO02Bxc5{Tdr5~%_5Y=HA% zvb>d3%0dmDxIbZ%DG_P_KWjK!i#HANXbF%}EUGER#jx zc_@UEJDOB`q*IDIb@C%9x8RB#!v03`oxv03+TBBMZ|@gH9|@1UqsDgM;~n(dWsjF< zH=&1>4o~>V1V8&qsrMb6R3$1s!51toCJl|0{I!@ta_~_Wqq_!7#b>Gs#xS-?rk3fn zn9oeN!#Vs{#YbU3W6e#bobN~`)>MTynde_)v)C)6jsjP@tWbE7Y4kEKJxEFvBHB}i z)-jh=Y1)sK(#c$mO1sE_SR$R(xv5MwuuDDIZoF~sa2GH{#ivNjWKpsp*?){7a8Rco z*Ceq^Dy>ar+ssdOH&;m!%dUT0`o5P*Gh_drHvEw#-;9q|qgze(RVu(E3YSPcpAH1in~w{wjzIQ~tSQueH;hEbgFP)Y}3Ko{M4p6o{y z8Wu|X94W-dR5(x}I7!Ap@KI=L7&RP=oi!iTAv7{{7C+h(PIx z1}jr&hJSDt56B$zIO#|Xg21K! zDS9K<(da7e2p%n-dP8^hU;2mFrKzU^w`5qtH; z*=^OMboOe_?w5}HaS}i2b9V|1z7N0c=KPNac-em zsu0&anEh1*S={1}^WY%r|E24{;Z0VdnMm>!9*fB-9J~f)^Q;Djm(+Tn`l5?>d|;Ir zvZ5s%5wGOw6E)+IP@dawmoLp{UELIxJ-Ug9Yi~Ydk4b+#v2lBI(qU|Ft(yLGV82tV z4Yt;$?(4ndtmykG>alo@n``)j?}Yoe{X{|KSti$7tM~R)dtc$RtYrFiGA+!{PouiJ_4UrxU(ptU->%#J2)_UIw7Rd$ z%X2Y9J%*on00*(`dz?;9iI7fUDhdNMOsZ)xbEZ=vXQ-Ac&+gQYgO)^^*L8FXlPJ*{ z7(B)6HV(yu;>w710p4^%xlL&OCM{iq88rfHvJ$~T;Gp(OQB)*i@izj{f#COsIj!xw z{4as*$1(i)N<@(Jytv_w$L6 zENi{&FJwEcZ{+HAaB8)!!gpUrI-cOpYcmTES@-dU_z=-uR#zO+_pBbx zo?gdC+)HWNKY;!%&(H}H-+Kq2ji7KE_RQU)%tKrB9#*B$_d#i#->5#vIx1rc#3TZ% z)TG~fQfdE-L{STkmxAVfn?-04m>|jA%NlLGGZ|!8nY&}!KkivzPZfGV$y4w3d0jUS z+EVpj_Dn35Ec$JKbz2(jwN`w7*1(c?Xyo$EfNMl$ZVg_VP;*-BF?n)P<*`X~OSJqM z)fkeoo$(t7*OMGdF*;qhs`hDJ`v#I8L#;|?cfBu4#KI6TI}pIm#*V`S2Z50w?0knD z0gein69A%r8DQ!HlpPaiFArC{js7TY+LPZCCb_jHx*w<$>H^(qrCYXZ){bw73#ElD zK3PX(o@iifqcgar;*?iZIEtMsz^>o^`!y#c9q;sukN}(Ca$9sX)Ze5Fm_ZuN*J5oL zJelD8*NKQkHAk$JhfxO63UewyX@r2Kh`MZo!B%P=oM zxOV9MMl(T{#e=>O&I?sZIGi=}k8CQ5Vsp&WZWCR+g-p5ru2<~lDroW0|I zMbUz`Bj^}aooc*eeoaH=nlt+}8|C23Z5hTf_U%_|1N@YC{NSo` z-MFT4{jM}XAzln5E_?(g2V$CtCW--ZzQ}~Jl4JMy)f5Pk9jRI;`F4~g;>vtv7zt1Y zV;ph>iqJsmrEp&X*k%c4*^n?@0+_jvBRS>NkTmd{;)#A%6_g?+@h2kgDc@CpwCoLE zkGo~@A>cc(>$a-zx17aTe&OC)-> zw%i*QJGZUoNtDg*oAG`8`JiHbpun<7X`Vz~%do{Ncj+Q-&gW07;g!q9XdyGmO4v4f zRp4OoP1z*t3fdvMhj-UG%wy0%H(yFm5k!3Di1f^yaSG4s~d&5g48Ws6Yg@=u(Azmz@AGh^UQpS!!P)QT0N{;0+K>9|6W zSkwNW4lnknQ?h+-T4+xNeUEypg9W@kaeW%k zMp#kD81?Tj2v6D`-$<+ZNz4K@!0%YOd$9bvseu1wh!o7SGxREi_q7ZbIiS~`Z-|>9 z|MxVT6H7>V6oz%0Bj5N-6+-)n`+aEHftTmiG5O&;&EuV5)P4EAZ#@NSvkCGP@pkwGA zCKtp|M}uQAZ?Gll*qUG_Fz||7fc@j-lHP~@!+K$}Fie`;%GWDL-SM;dL7d123!Wl2Lk9rKf$ylGATiMb99o&&Y5JDY+q?dYq(E6j zkHbp%@LMV$+c@O_rRYpY;#vs_e-#XI2w;+p9r%tHC|kZ@VH_zg9%p>Wjp~}EYFeqL zHY5DdyPhFJZ2H0TunnQ1KTOGfINCKUO4}XJSk=VY~+I&!v904XS2BCF~o#HFVoeCNwmg(y~=k z9wQ=`+R3BUjdy8inEQZtUA$ZNy=mGJa`ShGV#`9mywHp)pz|`gQ}uUT$Yw!fMeI~{ z$&6VTgI)>Qp|9N+sPQ*D7Ya{h`f?znzhFFri=7SH6qFcU!J(o4Tdnfzh-D(Y+4O;z zvzV+F_u7}U0U@849=8=e-42JF?#1EbP048f>;0Jev^ZMKAf)cjKu160sdESOwzhAw z2D3K7zP*mKQIf9nHwX3isSBw4sM5boAz_r?h4(fd{cfb=J2A)yc1$DSu>X`}bNcq@iOU4Xk6djgm|@^tVO0aB zAIs81AkE6gjgZAlOShJ}pU2Ee#om?iMbbNL3`ltNOJ{X?bps2>j=Q#*yD?d#nhE_D zCsY=I7XBw^H#QFQ|7u!}&(1SoKIAn1i#q00md_7 z#S}DB3IvW6mhmw8N|$7iX~yFzvW_W@wb+PCG`%q2?tavpg}v7Dr(ErEiR;k6L<+`T z4jYBcjaT@TQP5SqdD;*#HJsd<>;i*0QdjY^QY3N-5A8?jS%G|Ixyro*4PmrCYwuh@_EkV z45JlWmen5faHWy;D%u-(CjZc%Fuk2~wAk~H^;)KokF-KEGDDuqB^*nOhA~(z*5kwL zU}lMDZ~jk5M5cucM#LJ4&3{mu|CBI?560x>1gztDU}@}C`$zKk#9EH)!bmmTYuLz~ zj4#%mg}kHLozMR31-N`t`0eAIn-FMJ&WuSO^?it zMZw5q4c^7Tt`TvoXmcKG7HPsVq)vQqE?%5|XIMC!wio@7WLB|g6^Y45q?x1DR^6*Z zkQcwr6y#(>ZVh<-6Nwp+kOSqC&=$#}{R~B2zc3P}jx7TTBC+=duModaSC)>Jkgoki z=~)4#HISAeFvxhPFQH=*w2VDEKKm`+lBk4(xd0)Cy?ibL`-|AlOW}ZJrEL2`THTBh zu(0=g>cdvWd~XiXX?G}x9SH=4SnQ4(?8OR&Ro-Kn#mbI$i$W7o@tgfvOYKi>+F<*c zg!(N;TX00($K^CD_}t=md-KI6rS~mD8JdcI+T@%^jE3Rz5vVTJHBKTN69@P&J&Z{% zJisrBc+z~!p%jEB5E7{aMpzO|9wQI4%f8PO|LOgg%~kk5DtdvTn3$DIQ;#X#i1gT| znB4c7bnQXt<+!6lO*T3ror?v2YwvyhPg1Dqw6kaJe)T@xI=%R$1-7=@Q>_2emC6pg zL5H2OG^p9vld#)7FYmElMAjSR>REY&0_#5I!m%{Hvw^aRn3p*t>X zuL*r2J?+n@n8hZG_==xI8%(#`^i!3#4hao{vWr1&UUwsaO-5>Kvc4^jBn5oWCr0Cn zkiD|M!HETQ0$BlpR}0(YMOk%>TpyT^ms*^hJ@R;vsVm+cqr{?%S`;gjKwd|Og=v8C zxJ}GL*1=>@uoXwsWbpeQBzpfuzAri3elqVhEx)FPqd?y(L_3`(&3(v*Ip0q!`ow>{ zAHwdqU4M2HxH%K>-*xc1Ekgd&&kBHYn*nHW`-!Mp`A719ZgnCV^I&#G2Om7KQ%zfP4WKl{a(mh2ezdX+v@?%5;pbl z8wSqpNBIg&TQ9nhmX)&i*~JXkHwV$PKjl9JUHkk)Wy9!!|E64$Q!DCOluj(JTi8{q z8hni(De(YR72|y;@MbV?sJYFSSlNErepFs_m(gl}6p7SW#as?w%%2j+9iZwh786|g z)xw#5IDB4~H^S`y#O?O( z0vuY?&5KUWZ-z2}n+eoaQETQt`Q_%OR%lY_Yv|cm6 zO$l z!(X|OgSkY3h+3NA8R8aA{8q+Dl`g2N|7zN0`gfL6(H{bvzJ%#Q2L+4?N9D60aXvG> zqQY6fT?%Wjt(rItM$tEOruaGAc8&A9cQ$TZcO`hrrOH#DP+h(nNQ-*4GlqBn5RGSZ zZC%mRJ`Sa9Z;so#*a}M+h@oI>{(S|1wEv%h!5E#=WAAV7OE%3N#_V=TR6Ln8QZz;2e!#f7Ph9)4EMbGINK;Tiax6X>c9d3 z5CzFU=MO0oSd0(7_^9@A74|Z$J&QrDn6;bM13ug%RKxTGSfBwT1DNP~Ni@gIck36N z>rM7W60W3oks@>a+;L5L)U+!vw#MwjTkv$6Z_=x|x4}wzaddzWpQ8A%4b}fm)-#?- z!mi9aUMgQE^7h1jvFP95wX8i}YTLD3_G`C4tgz72#Gdco$GI3ib{W_1593vQ%1Q+%T51ESRjoO#4xm1+On%o z3AesUHEH5^^~^ti{)e-pdZ<^dlO<Ej<&t~PLW7BUp(R*pq@>a@k^x4I9vrn|Ov<+YjT@)^Ozep;+tRKd}_D}fi z>W2UIA3@Q;5{M!I8Vfj9DOZtRLDQ-PYKUE2w z?FCka`f=D|(pZv-87Fk9eB!4#J|CvUFbw^uwX#@_<3J`A)&L-ZqDt;bCdf-2IJQk| zYt0lX{vnPb2%8E0(;%;zTp}+G5;mKDC2Ol%)x=b)Jk8{}D7Wk3=5QI3Jr3X07xa4g zu5H(}Im@r8_pp@WHv7wW+rQfgfrMYXEnY6`sf1O^=7J?)rDjXZSE-R zuFTFrU~r?Q6`Erjs;_h@?p63Y-O|cD!PU|omz$kea!P*MB3(=vXB`}=0HQaxxswrdKq5c9_b8><`s3Vv%dcC+>)a_tm9GGokq=wNtk`=INUZRM$5 z;)0W?Y~~Z46aiH1)ncBr9@XxvV>{h-?yjf3`>3r`y+;dkbJypEC4`r~2)vwBf6b)_ zJKy`a`VM==_2G^|B!Ng6#}Hq*3qphg4Szp5y?|#MNS~A^0dp7tM!aBqi)GMM@~|ob?=?_nGVsd<}Ls(75I}ho}EIZ1mCNx<2KD z?){T?2mE+^y%#R_($(=25hywFbihUFv)`B9c0U{AyW8>jtzczlMh~mkhMO+`n#Q+Av1O`0>llQEor}j**`3^}B zC1bKeMUb>mMt%ZoL4mlc)SVz8yB^&wlclwo4oKF5*rDbkJ6$UBn4~} z9ERFnrZW9c7cQ7^j%UW0HOG-uF)wfX&ErBF>1v}eW&V6) z%g-*5u=pu1UPa8HWK%0S<|ynW`-2kb96i0fzwu$_yPBn?&7!Z;yzb}4_F4SjdNOZU zVBhR(*$0jJ$d7%|410$420j(iTw#dzXVlch8AU`8X=pJcB~A4gNTCe|e6VR3>+=iG zo!%Z@5|=`%CHop4HPsUOxHj6NhfPTI2f8aDQVh^}_VQU&$u9^PUSL`5LF4764kCprQm-0TdV#7!<}s^#%5elX z1TQ=VI;tAahh%6Q%L(!i?&{|zFxx(+?cU@B=w(#`-pg%?*U9_f`7g1(x}4nowNT`; zFkS7D3BSAN8rLVvZiD}tp3B_48i>6rbSWLfbzd|f=Rt`-LXvHE?+Lc!q{ z`IvCOn{%rZ5vF;PI1-1Hgh7_1)*TxcS=qjGvr4)(bQ6lbdiPbI>>M!25P}a_WUVMw zgq-9uvAni_xPQ!k*-PDxCezK7lj#46$n!mKifYR*#M9yM4tQA&_fw`lZ1WP6P|qEH z??u7yxP!*2qXroiL?8cB7Qrv=(yiQ!Tmvlvk^PBq5-a~~g}nD0w*M62;ro>|V=Und zZF`-N^!p@BzI|-@YNF=Zu!O*}MsuClhT}MU6!HoxnfkD7L2m}NH zI1GaeQ^(wrFyys~ja%9ZiC+7?Wd%?Zq2>vTQ3J%N@c{@kmY6t7H&mJatZQs%x}ike z7?bL>0Af&Jo`by}5g;YIB36NpGj&PG1>b0y$QJxIaqPC@aeq)O4Vl5+$&1RUJoXYuyK=p!Pk4v+&xey5{e-Z*#5N0v(%{rFiNLQIC;eACZbN zK}4#2Bw(VnZ*g&^Flok^_SeF4mSxf}tQ5}veG8wDZHu3@O_5|}bydui&rb#?7!X1i znkH7p-ccG4y&`Etx#%KLyjbR3teSFttb5&u(4-$<3a@^tRfOxl=LthF_^HAZ7SPI$ zE$eyq$ZK8q@_uP&@1{;|>6CG@g*0gXy$o}^u3Dqons1Qla<5w>&sfSVJr%saD3GV{ zJv#4^jBb6LWu$CQLR})yn^5xYz$@vsr(ZEf3n{LuXHrc0I_H$N>_8MA{bjtK^$NHA#q$@9Q*ejtn|WF%2l07g&{GW~ct zH&^LlMe_nP<~zAsO|mx%z-w_C%KF*wRY|`UTZNX|l#ccF7`|%AwHmzi%0F_NE{OEA z4WY|vDdA}4JKKr>mLD_XeJ*!QU;KbXK0S0%9xe2|fX>qPv?{-Q(s6RMQ26g`qi+O3 zsC2S=+SG4)+#yu}azT(-!Jc`c&~AbSIWxkc=(f2qP5OvJuz%>{Iua_1%EtZdlH-%1 zknC*{EB|He1a_s2>^D3fIwUvVgLtnSd|~4 z%l{67aAFaBC>5Ouk^v6Vx~li|c&Te1CsXPDLD%QW{Hgb~hRS{*{GiV!F;X%(ao<@$ z;UFLc#EQ&HAK5jwJ6%)~WI~bFH5DryIDyCcN2~7D;)cy637<=suaocb1pH_Kd-?X7 z)UIj&as*L*-a)XUyl(^DvPWz>v-O{NJQ!+JRkgo<*(DK%{uL|zvUP1l@L6|9^NV_@ z${VMFF%y1GIqRsQ95RAWfrI1BX`cG~pBTkVa5nO^6Q{`=iJJCe{}gF93hA(Ue7dal z$Uwuw0p+T4R9St6b%}+&LBfw0EmV4^l^gVx*V=uDNG^A(TQY2HbZ~Uf$NF=)&*ws5 zlrSU`obGBrtAp~@Q3^c}PlQd35m%U>fxs@^>_oS%vC(Un8FSeDzz)%JX@y zx$nh8Fk`J31p;kbf|oKY=(XQhjIsT)^m5P`{p%M>qZGSAhNPWQ*%AX2LBi~W+{UGj zDREd(U#nFb$mRN;&Jjg<&NJ=O(`OboH3>MlBxA0XnSKIDjWF zAQQrs>F0+c48Q=q0<-?MQgH#e^JbMJ*O{)q5|KBjI%P^Y*y?j?GZ0k)t7d3t9P9X0 zrs?sv#>@48`M&)#g-@22d;fh~VKSA3n$4HtLB{T!D-)ee`)-<&EVY3erxGVyl*ih+ zwUX?L#J6Fe+|~YCL=12@3tKG3eD%fnHTvEMi9NC)Myz?&}?X zW+>2MS5FJAdX*%TW2*Ukt1sn4>*ILe<7v}na=P8iJ|<#Ax-@UUIW~4%{nkHY^b>Ch zP?u7udhm|q3yLBZh&LPsBafulLex@##?j^9le493A5DWL+JK^9Yc(Eg{_wt5)_K;7aah_+Cvop<52;fsBy%9f?wgFK-rOdGfLaeqoplAWg_TO z)XbnSI6dXW__(0&V8o*X5tQN4g8?}mAs}cc7DS9Fu(H%+X%=a-yy7wN{pXS(>Pb_h zdX;jlPlBwpwpI4+&kMCezMGShu;Z)L>6A)6?|%!Y2pdjRjL*K_XXf@BxNM*kCkt*t zgQGJgG&fGFKi&;*_a?aP-lh4k(EMS!-imfQf-~U;R(UVZqWvM^4Xb3M!`Lbuz8jPP zbl3y!r+_#wtv zmWaew%Nx0y^t0E52Q$oCilLB3A|$byuJ%;Wuk`E%@7_2W9) zRCSi&zcLkQTOJ?z%0k{)m^QfHDrWMwSpf59`{83>NGsdnUB_+$-kVM72))GJ_!5in z)kq5L7WQ;%&+W`H`!)dGN|)?i(>a`OX5Zm=!B@8InS}jOPQCO3x)y}XkJQkR0ID*q zku!8TAO%2Q!b~$~2vUpt_U3WPIKjA*69Ju(w{3hLov$Q>Al%2h5 z%DW2tZ;UOaoFw5eLK~w0%fQ03?tY($978 z#+13*XAa}&gngTYCR>JVnoR168;SfRekuCQTtX!w`+Er-_jIQA7cUVMiU z<^0JXGJhEVdSsLvwlEf9#Qx)eB~R)$F!sJ!A}BZ!;>5G#V-dlspln{AOc}9?yQa&!hTyv={ zBS1}yN-0vVV49j!>m39FhEVl`Nz^?~iFp{Nc-a{Seg<{X8AsxpWG>$4RcKxIAYzwx zja)3R zA4l4}uMZYcRQgg?qmYNNzP;V@SUfff7Lj(b*h%j?{uJ?g?&#Q7-;!qY9eRlAP?$VP zB};{IyUV~-n3qq@K~%+}r{F?J(f(q$>(sCqAvvGqXo+&kCz2$Z&stm`MhU(Frarwd zq~;Ax%0u)Z&5_H8g@c$#aHyah=}XyHAwv%jJJrT>UTZTA!sl8|y$)ZZ`V%sJEBUll z^DVz!ZER?pu?b;JmCTh(!HUa@>5CpyE*A-UjJ$zP?K z0-61#GjX_Obl-|VnWhy~nNa}|Zx2aS?4aRTEc)MJmoNe6Ir24b=bhyo{q|efxq%;`&Ms$k;rG$y2ICC zd+*S`{Tz;7x$JmbkInD!rb)ztUjW4*UP#mKIx?y_2_9b=A8`2aZ*lN)d zg56b_!F$;`lZk=%B?KXpp5awb6j#Oy2vP?6<$ypkVkQREqGO$YNURu=I7n1DD6?WD zaezEwfB};0b%>OeGN)y{W#*2D5L%y+lqGc^*rz_mtmt5w_|ZpJl2eFUfth+`JM8(oIHG|6#+KznjYyK;wq*cEn2V{;@oU+H&*+bFH7iYB7X=4dHms7F z1kH4;U!oa`bX6#%0wkkTXG^BKMM3(ZOv<5gN|q{vhQo#ds@lk@LwL5KIGUm2?-(7l zm$I+X_ZJtpHwPwo*TiemfHKU66vl78`AA|ON6_V`rtcj%5>C#}NKcGGFmsR2?%?<3YEaI!zoYs3|oP zOD`=R5uyEFRnL`% zPL~qHOx_kZh5T($CYTtqT`x_{ZYW z1}iM}{Twy@sN3SXU-5Z`ps*?B@m9_sjc!(NOU}U>Aap_JklGA_f5b0DgWr$Ob5}LszeDfBrA zK@v$;ntPOQ;nXf)bDEZpbGWZ%Tp71YWl|($W@HXx0%|3Eiu)R=Vz$z7ky(JZBT~x{ zuLHI=(iXEEx7YI&_@v(K!)I?Smx3;77jDMci~CtYB<07a=HO$ZRQD; z#U05>IxgBifSNF9-fwm9AjDYuAOGO#zZCbt&k&ujzPA0n=+2d#N3R*-rqbg*MkB$u0^3xCogE@^LGa$@-(>h?XW?0Tw)rkRg zbaB3wIM>p`m9^Hre(UGIDdf{NYgr117A=f(S0UzI6u2|kv0_F_f~6Sw6Wl9Wk2Y0{ zas-cEgyOy#4mr%ZrT+Xt5xP8eEk;|`0K70n_Js;m?zV8*(4wuDuxKUa6Qb(Me*oK|ky`0mtU&%^x>7k;V=fRjRIHo5k1n@4Gof{2(aZbGSzlB$>&0XY?|YH6jPN$ckOOBdT;VHcKJU-(%>6(;P1)K^EhHJUP!;v=~L})wEj{48F}G@YGB0 zwyga%q8Prj(3xQGd+2X0$tOb~@hDd=% zc7~wW?T$Nx2?OEd^H*C;@vxX~P&l0^Ae0Um2@Q?J0tp91q67s%03cC-j0P1XB8R(B zq!;z6U=I^OhXoDL zhoFQ2NL&oj7p0D@`b_#o()_=aSUvap+rs__TP4RvDoA9zX zN71qUu(?9!X#E(>c$lu){+AIO&lHHi;R16hv1_d4asI74+Suq8Q%Y0L4; z<%@5}`N6WSn~w8MbBwPeJkV`b(AnwkSih;`3&-HQGIAtQY6Fq0{7H$l)aR9|Iv0Lv zn@|O9ldwDu0GKl(I!`zb_~o%$ zV3cuxJRlepi3AxY1dD@$ga`L}n~J13oH>ar@~wSOw!vQW?I}2 z{chnW-a4ESYJodd=>K~D98qfXe4Pk%KL1mKXFS)yQ1L!}uEVk)%emQ~mvk{_|G9^X;2s8m_QzcIIo-$m-E_og+QU@M z{o>rI%rSH_HzD!J$12o^`cEF94w8#&+QwO}us0Q~m^H#){B!MhV2HxXZ-GpS$zgoW zRmNc|KRu4uxR&|eE+8CXKan3&p$NPrI1WVwj1nY9_p!uUG`^ss%=l-5D(7*lCBt{c zbQ)+;*fGPXMjc3;z*bsG^h!BED)J*@yeFDz)Cj?_2<9Ya@1+Zpp^x$dLPl{~H~SBC z3?;TAUqKpv{h9ZkR1@!Te_WY(xl+`BIxy~Vx+$^_+e?TM^x40s^tr4?KjC%L%@TV$ z>!Ey;e7Q22Q6RKO35@lq7tk#y=UL32piL3dKTMKMW#$tX%#6hNVj-<$SfJE&pSu|% zSv$FEQSP!xA5wB+Ifz97{x;K4f03}DM)j-A>afwN#la57TS@pqSHRV6w!>AYtd)yw z%r$=sh#Dv%0uTd$Q2=6ZQ8ihiY)XJIvN(ncB9W$|DE{eQG=Bh_?L{xi`rgXw$qcon z#=-gT58+PpluTyR3og85FK3c0Fc;s$f07hJK4W1qwL&Uqd zrQ@1Z|HGFfd|Rw{fJ&v$e<7k^n*4g|uU?P79{27>c!Yr;8Gy*Sejv!Z0LUgGC@!|u z05zbO*h!`wryWdWB{BdGut-*=emARIK2@bD|H0NCW^`RQ_?s#IxoyEFT65Q8RY>^* zc}%kow{#81--LUc&wuN#`N^^fh=H!}Q2sLKeHLEF?~U~Xu%iLcz)1MQI6#r$G#;8X z;e!R2geIVYc%Z^As~;LPZvMez=BU9AOXIPM=&BhP9H1aadpEq-X7|C)jSI)VQxc!9 zSzCT%G`AHd(Rsj{a=};erID2W&w0;#uAi&tVt@Aj?Y-7_<&+Xog>h$O=(r2XGO-TTa77k@eul`S z7Lbk}D^VLpn|N0iaSR=cJ2

    JmwQX#UYnKTy>`kR?+?m_mG6>FI4ibV67f3tIv8o zuBOA0gK4P&$3_o}m^c+89*e>3rE;r&S8as;*9%RHs!J|c^~=&a@wz#l*6(7_f=n1Q zxs+)lB26K2JQN*jb^7bKp+WxO`!p`PqMoMggrkd_A^BM!01TT5B^?PN0#L$9!@_|G zrk_9pC>WUysgo`r(41M)Gmlg*XaPEiuk4=}tYE@(ib<=7K}Z61YttBrK>`%UBMX$t z!;+`08=d4A5+!0JLTHA7kZ8(&B%`#FF_|7rZZjl`5PN)~?pM|uBd_}(LaWVpKXZ-5 zyhd=3*LQX#Z+BHQAGXn#IJf=!lqdhXZY43=B;V^Td>1v+m6&Z%*|-#w5J)?Y>VKQ- zopid^{S9+y#xxIR!vly*boZ!hb9E9nP?qqS#EyaUBN?l@NrO~fsH3l%OAc7r#xA=K zxeE5ZGPRx*-&q~6siYHn*viq7JZCOahXAC&0Eij@3l*3HeI|?STo(y>XIoyk_kFgd zs+7$N1Qe7H%R#UyHK#^X%xvX^G}|t`a&W8qc#t^f?===| z)U-A0Qhqh|3a!)S?YQ}8HkT=0R_#2J)bOgWC;_WM5uQsEUBMJ~5JmnY(JYM9m$cl) zLVB8`vonZ@73`GX21SqXk(`pVwHuTl39m&xb3V6Pq|;3qaB z775^%1z0y-)w}cRN^#$1f&MfbF{Rh0ImE1S zPl<2?xlOY*C)3H7+HWJSGTXPOzuij+ylb9f`w{lfs-EidW@t3nW8wpql2f}DIR*>} zeTHI&l7m3xrmLI{N7J1ekRQGDM@XP=PnWx~9XOntSMg=Cy^~`5fJZG!| zgLxt*WZ9la4(GV0GB?d?BY2_2Q!?DMLM7{be;zu z(IMKAvt4r;-Efe5O>1k?}^4qQYU7=i)8!h&FdVlc2`VnOPFAScwfFgJwSFF7cMM>>sl z_q3I%>=!+5A(^C-j5ecpZ=c*MEz1z~us2h{hH?$s_qtDn-CQHIdKsd-<<#)yE}fnG<7I zdKpG5aubtmFew}>8$gLma)K4k3~R16<|p-5=T@+kon`Sb(1w2#k51kX#bn@x*(JGBUrmPS#$ zyRH94n{bCPZJz!{3MtD}zKg;!HW%BV_-yk2b>RozL^`%pGGoj#T!9F%$&jJz>Gmzd z;|1ZvpjOzOqZ2l#|dfuzwqt5av!|miR0Xxj1ih6d1g(pNIQY_X9Yp)|xi6}ADz*6z7*rW-p z9JFu{2AQ>VKD?Jw#2e1?KGr?=@3zyg)s=R|7jIuYlLwGO7!}t()ggXE-oY6u0sMMI zQefI#R`a+#Zc!;-Boh(ms{f*#uu*W8W#(lihk;&8`qp)JM{64&^NSig?yP1Q zr%&6Fo#3cOu3L~51gbJHGj;9TVZYtx(B9IKVa`THrwinZn=Ep9)1!_QA8D~p!frgY zpePVy*mRd7y()CR*u->qa>4pc<+6^1p*Ie!Cs|=gC^vu@MvU(h#`#^8x2L_nc%yv4 z&fpuVb$B;60A}0p!{3tkQGVT!<#0M8reK+ghI^Z6sE>*wPRHnREoH}0)aSlw@wjz0 z@4U9dXD43u)%9p)X8Y~ZGI<@j)cKd4>@FFp#B8fx9(0CAb4)=iU&(E0Ke7G|RJM=< zT=WhS5(rWVfuUU_HTl1!7~#>sfZm;~04Qs=34m_->heHjj1|TQ3;=pa!ay%} z;bA%TLBF8QHtll_B=)hB-4;Wv65$4$nv_V}Y_>J4=6BKWZ8H+D!)Gu9mx|xZtp-vl zORhGbh@KXS{W%y7jL#kFKboA^*e{v4i!$%u&X3RG(B`%=Er;{rvx2)5wkumN9^zFy z&QHubCX7Tc_J%5%Td$2Ca=AQ|CPj&Th-Grzul$SSiBRtKgEe1l+jtiEd}Q+@Ly>3E z_C7oq^J((_cNJ>%;dzW|#QaFl3ZjCrqyb87cFTA9Qh<7Co*p(hyhMF22lzVNSgh|& zfzI5OB&*My|1sAnIxcb9`FNS7Qo{f5UE(@Gk zjn*WbaZKRW+#tZ$bsNIwmm z0GZ;d!}XSrH(wdr?YYrunu=zu1cJS2H0thkWze>y{K8B>=kKm-my5^kN1xt4?haT= zUTkrN2?o=nWHSvYdTEB8%Vz z0RLUdqr*k9K)R&VA2?A#P-G-g36Wj)+nT9h25%F0a5XD=^BXFl1yTtN5v&l5M%t#5yLHS$%*XU_5y z6jOS4dq>!ht+WFBir;!YYFch3aC-Yp-T(ES`#@*@$^2Db5vvUr9t;VifaPBgIksK3 zJ)SS+8a<9AzMgwHFXVb&bFtWQ@h%A|s4n&4GkJX5ME}AOPBfm6IS&L)_$gPTG1+wI zS@l%ne6^oH(3dIcIi>U6g(^EB{J*D-xT6)t~TqY5-BWF5|t_cz;${aW;9=gMJf~A>6 z@wmBJHNjvo4Bc~AMDi16CmTr07e)@phQ6e{ku`TlX?B}JNMlXGu{3J*Y}nfnBF3o% zMk08`rYYb!7%8|wY$GM3$jHV7ghNb-EKWH|Lsj@Nw22b{xs!}vOGY1((Jd7nsJkL| z)MDnS8E~^ZL*ppCwYXa=>3gcvetFX7kuEU3hLa^B(-keJBZ?{V(brAAo@U=IiPk{3 zy+KcY{t!^*B9L>M37bdhg_Os=!JBclJ=+T<=_j;vwBvZ9Q_d+3*C?J8yzze3ES~AG zu*FN|zTGZMUSw1I^)@3aa_9bypl$aGM`r5-8J=ie>>q+|dgfSReqQ z<~IGL5GDb_vN^~n{sMp!{}Kw59%)F+A5KGOy0PE?_IP*?Sz}FQ%4Ser9ItVQ8&HW)t5U%(9ZIMs8FCJzI zk_it8rIJ1DNq^;W&GoRo+n?!c4BvR>0CPrhOMIF~o-a037 z)SXc=9i~q?zt=BKP;aL$YY&O{C^(y~um8B)(Er+UJ{ZQ6LTMps?Oty1gPVVXbeE0H zoRnrqLJG#H4KCUPkn~64gE00cZtm>PFZ1UJX`AiM*nN&o?++~v^+lZyeh|L0YV$w3 zW~g*bzs^{_*UGMUC(d7Te&X{~ZzsjUJSfaA%j3=Ed;&k_4tcoF3`z)gVoZ zLyisa21s?XJqKWbkQkKe34oa{4C~k7C^SdF39QFX6up*kX*;)?mN_7sYfmIN0n8!S zMk(5I{>i9R!(poK62k#hYox%W?MShR2pCb&AX97%CXGCS7cwZ0&h^)w&2hViEUJ+p z&N7)>7`|UrzvG#^~3IENBTYG_jM{^xF)BTdC-&!06-)#)c zb-aJNpQcJ{=N1fqCOub4Uaae2&JOE~P^$SULIJ{^{KN?Uh~#*~-!$O)LvUYje!0B- z2TpVtB32>A%Vpo&-b3F&tVOt``uRSMR%tz?zu5FB-x;{ompIqy_;OgLYd-4YVFUp-d6r$Qr=Ey)Sd?OyPQ==I?0tH#>?E8n$1v19SO!2z8&9o`yK|BN0+B?XBZ zUvuOH)&sb`1NG!7V}hBvnUvKcv2`MygToG0IAxj5u%Rjl^aB;DLI5KGqD_h639!p2 ze6SupnGj}BRXhL0JE~6wTQ-{DSlqz=1LiIrEiJ*(zVbH>8Xh%mXma;}@ZNI`z^6KAJPEdxc#Xdo&cS3kDAb=oNDL@?<#t74( zD}PXC-}iDW7Y zbKOY*(EQH6%bnV`T9yvqp>LzcxoY0#7Q06yAJ*z!aHl5oaU{qOdr|sLJN>!m<-xwts_*7$FMgj@qADXR2#5fH(8|-kq-$${sa&J0m^@*|Cqbjr*>si8>Ly#mwwLWz2A6z z7>am%{MgMEU}9VPZ#3Fpv80|4>#Ll{Vy)F)^^(oa zjg2CbjpGW*q@xxC;>I?w?c;u4L%!Axwt_xEXkUa2C>mT1*{BrPEQbrt%|1PngeeC< z#Ps&DCHPmhS1<0beEidSIJ}whcCeO{M_Km%s;A;ouO6?SZt#XXMdZe5QvWHKdGu4R zXqXsya1px`o6Ww6)<;%F6hl4aML0i6Q}%wggj`wAz;|oGw2!4UX~DHaoGBHT?)H9K zMb*TXQ$zY@*Ij3h9e=kMI2*;C7H^N2mREewE_O!SAMPdZjUN4+_SH!>&Ct0txKIFn z5w>f$sHZ0Jv#Oltvc{VC_V!=Imh;_9BS^!t-M$b3bZN+f05tv@T@2y|6wd_K;93H)j{<%qpB7_KQznDP1h)i6hF3);- zLvg9n4>fV|Y5o4O^)zhL1*?x)0apG*ormo`S%Kwc?A`&vUE0pAMU{8`kDD6}NBulk%?fYz2>4&V+|J+?e)5g3-$1%tS#R+Z1Ou)xbI@wC7qQH= z_zU;&HN%VHvLX~HiZHKfo974US9L^O-fN~vL+dz*7eh7l1>;tFW%+Ys1M+*rIXg!K z@s9`FBO~7Kt19=>kG(qn&CAiRE}}DO$u}%Bulv?b&o|>edYCx*p1U3Sjg<97$CEeMc4YLvRyTRp` z=@;|~xE#ZIb$=(h^)A7*){#g*t&21ZrG4p?f)}5>X6F}EhDYeD1fI{=Y0!~)WR&hz znZ@-jw0#u+pg&UQCgwcHmE|C#*A(gMVcX3&BqWz{Z!XVh!((jBU@J4ce*FnB{O9ZU zGCYenahhr5O4}kIAy`{fa`7LZ{P<3@B_Ti|Ff}>7cps0?zPo49;Z#1iLMwi?E_U_m zu{T3j>shP;rwpRm7BSo|6~Mq3`KJdTg|T3H!n zIAO)x-ratgS(mbZeks7niU|&+3PJ#5rOiA0x!-h;?)4`7HHpkbpr)(Jk_hSP_zpy( zWp!jyn2Q^i4o5F<>j|Bavp&i09rta?uO0@B6i(-dD8`ID_vNx4^P`njpND7>n+X(m zNhL%T7WnCc^jVO_9yyw(e&zhaIxH{peDldF%=My6zwf3~N^>E#kFQpZ?{yXvtRs zX&ra*S?_&!5+(o5bEFuhL3)GFOB?!%fso#QoyuYRd{DQ?TBs z6A>Y$HIS^MLL1IT-{hU}V%t>f@Q~zWxkv8XL6|B;;a0Ch4B1xZ_1xN1_uMKB^fNLt zOfCf=j4%K&42*{hgy8`(v4|{8&=!@aKO@op1AHJ7@PHYbt>yrSNW;%NQ}%`tE^E(* zRxINC#u*-?jjk>ZD$y)p(sOhi$sK#)*h_ldhh9}l(h{@;>~4`o(tQ>4idIRplfwUB zGM`edE{pac+XyzVhkwI0OdS%LA)JQh2&WTXCquZyFZo$(mUb z6w+hlUA&{E1^+KuE=~cVT|&Fs@OR7#t#ipo!{r%GS3=xc5pk#lyy2(f&v?}V5CB#- z7NAHPjCa-yF6U>UD2*TJ6}P=+K31VSh2V<*ug65mCL=j(XDu3Lbj#9(c&JX0o4ua1 z-FYEqWqcfot4&TvGWpDhw2N=8b?2VfDc@$3@Wx_%Qc!pIo&20MkP(S8>^Sju=?*5%GZjLnFixyEaB`vC;F@>$spvhQ#a#x5ukzjS( zFT6R^o^A^*e>>1rW}U1uZHYYf*Ph}z>LFa>O+27#^M`K?c;=i^J_bUUI>AB^U^W0d7QJ0YvZ6hY zNH81-3j)G`0JN5$60K;84U?xLt5OjOk|J^WZ20PICF}8e=xX_X6D=~n9eI0vw|Si` z63+e`ea3|>PVlW>@3GK7{`6xIj%Drpdl?!_mmOHZwwU26y!5odzERsSTbgH7@F``rim>3^82)iFf98K|{YQ zJ8qU#r-O^BUjK@6H9KS~$dqR?MZm`~1d&o9@VX$xFN_40+L_(djOD<|Fb##& zx@Yl%QTTvi3_xU9ys+we!z`6zPf$>%2ms6`>)PeDFYEJzPo1Ml1jxu%3Of;gLyP?N z;vXDcBJ~$iac&uy2r?O25=c`4t@1_Ogi}j~o0;BE72m^2mrWrH(UNL$R^?Ydur!G; z*Y5{Ptkc!irFmjVI52eK7*^Qu7Z|PGt!&>Dw|;abmb9-Zw%Cas9@WTkT49AUGBX2J zg=wQ-V(Q1p%eg4Ln)+u9(>RDx<37!K4TW$MCvXvS=sCOX)mtXemzBBR{K$B)vU!YE zt=Y@d#p@1QQ-5jHK3Ei|tv}v+yON(PltCGdZ+WO(={NN)pFMenD!Q>AZz$qctbFBW zn=0GDF|i}zSkd3?H+}1Uvvl^l;m%)A=YgRTlybK!3OOQ?g)Zf%j z8nz`1gR+6kLd^i=MU;3LgtR!FQq?mKW^$p$v%^kpIZQ2rWgVA4qDp-ZeI&hCm)>7? zH)gGf1Z;OaEI+cUU`H*m1327%y~cK5h_?E^pk1$Xp*=HKTl>;x*Q&jkPsK&gjYt57 z$B2XmU8(4v2Uo&5a-s?1Kx*Uv)U+J@9YR^LC%U1qjlbMgTGZwCseRkl4z3(90X=CZ zIO%tcPy~nwLmm0<7d{_&2_AyNBf?Ms$iR^)GN3R(AQ2_{D=sP_nKA(u!kQ_6UikQ1 zf8+O^rR06D=7vY+!|3+WjmmMy*-|gNs^2Na`|6A3!j5ZnDo@kSm#dv{=Z!%T)O>K` ztSu+=Sf zzL^-k-aeB>qm$E<<;LV?Lr>iJ^D^1TL)9QqG*<>r0xyJ~)qhZLp6fVR(k6FH9A>)q zg+BlPl|eYk#jF#`DMkDIY|vFA2R4xzt0s??2LMU`ED~Ybgi%#53O}x#^$`>n*5-Uw zIlW!+_OW*`c}QAZtz6%n-^oHV0&P|t$lSi)Uy8*u1zhLrguXVIJFA^SGw6OlZbv_y zWcoO`HL&*2NIqH`=^2P&)zSEp%Hfy$3VPCIAbRP8uQ)Sq`$7qHv<9#I|1Mei zjJ4j)&Nf}xT=&p1_^t&9w~bJ=-yimdNIq7#BvR=uhkT!tA7ah?f;Sal>Gbz}1n22d zWNGZ1_3P_6gq+C7xaUgDsTku(q&$qEv%A8&Per1^J#T<-4p8Ax(wo24mht;wsYW}c z%BCz!84renyLL8Zx~(n0V+ecUB0v&KfQ;b9B?#l@l9FR>Cz2hbpSD`k|8q_7eO=Wc4I78M>{{9gaOprr`#cHVeKJes)oOwQe>UE1_=KB_lvR@>tmFIlUpM(<;@o2Rc>Ukp zz4Am77=OvDL{M7%AOOC}COXlhd8%j<*$M9T{3sFr!?5FzJ4IX`767)^wxy;oBvltg z4+kp{G0MW%=7B&U06PRw26(^nlFW1>E0tiKX+XdH=Z*iN+zY9lUZ4CT35j~rpwl{UAsw}isyU`w_iMeOYXcw#OY=mKYYMX@P@)E!OF$o>xeq0z< z0*Z)K%?$YoYJyYE=6E^Z(9t{x2v zr@S`K=XDH4{f2HGbX)xI<5k7ySLq%kAAb)$?gm`apjGl6S7{yB(JULw46n`(0xpam z8q*dXYwf%kSSH%FZD++MMNeV!Kf7e!QP6M+wG@gvw~F=j>PyZt-M*vYRMf{l&)<(e zbQ_Z~-4?s{j}Zn<=wVVnO(m^WZdFFBG}hY|X*0*fR;tnt>AZJC(Qq%9rgN7wIUR?V zW4~8FQ{FnZ{=JL#KQ{6;G5@rIpbn>1@%cGfq&CyidSUwBVZ=g7XEv=k_e#D{tO_$} zA!bldsmL2Z4ZsB;06=7AX>5IN&5~`Ss{vsyVM0P)dT-!Mi-D2OO23j-0F zAXn^IGHFlVC2@aWzOO$;D1P!M7IR4Q-%W&0WyZsLGJU|=U449|(c?4;;p?_D^c(*S zEug%_XYdU8WcFTPaz`ET%m`oFIE8fP;wWM7%0u+<+TA_70+xTeAh3XT5fCw?&*q_P z^H?oNb^?zmd-tkxle2KTsK^~T|JASxf40DS*7{0MYHz}`(BV_ahWJjgLtV=}&Rmom zeo%d{Y_*58e}O?%X$?1ysxP<&=Q2Hr-=wFYOe2z5Q5a>}uVKpxKug8B^n>ja|CK#^ zN$_4o-OwXPBrwJDjp4&@d`ood1cgKU?&#mDSJzV%aZKVD)4}*>)!NTLvUT;nAg@f| zMUlaKq&{~BMQ(z`kuV-6?D1#XKPG0FV%yr&QbfKY%GWU2fM5h;$mHkl>&d3@*D+a) zL_d~*>LJ5wL?SX)_fGCz zBBIx9%3%s^_Sil;>qQ#r+XEPy8F0lSBGOM^zk*vsmTTUd8_`VhPH>b6%Ep4;KyfUh z1>*5ZDalaSg0hi#^vkRfFZ2zJT5cLN{yseO@ZZoMJ9u>bKKK^3$(37jutm=xU2)))2clMES83{EZ z=B%s1WW^0KHI}JHkvk>H$=9C=hFR+9RBpcwCHy^z<-N0XG_&tR-z*os>h|v+Bh=&f zGJ9pm-ISS}zR|y>+;434)>r~spDEQ(t!!H#o~=lDnO3)WY31DYoPWDj%)g!abmgbg zKBKQOp==eA zjm)$;_xC2vcbP0Rjn?o&{qRQxkCYvYp?WxZfBP*QY<}qfCPL zAm6Yt<8h46_jwa4L%p0hO>&{!33)X6-^&^i28>z?d`dBFLE4`~2D^H^f36pi$Z^Vu z$TO8;@WVbCli|iz4w@K5g#vBtGcwae5{hVFV~!-z8BiX!=6n7c(05Y_R^azoYbfsB z$i)lJW46HwqmID98m83bl-5n3-uh7GQJi=^j#!>G$!?G%t_kXfkdOot`WL>?dCnhe zE%R4=ufb{r!*mzPZ8lJ1S`*Y`3MYO|Bm2B>E@+%Be zPPO%XVb_Dpuu3y4VA1DCrmCPnYndVxN0s zm5%QpmI>)hdgw5&)<&5IGf0{^>{G$aM~T}Fe}n}d~zDQA-A)= z^T|g{hbui`e>%lM|8a8XX#aej!vJr*x(jTKh&r{zwq4Dd-4`*f7OSs1{hjAwI_$4m z&T~a}UDpQxTL)58oNo?)Mj{7ZM;|MHd-JXg=-b%tG;7y5u9}uErzyYBJDVulC1f6T zPX8dvi$o!iA;uwOC}ND+r$mq#1X33P&~<>zBGj0`nZai(dKCS|@#^tQz1_Dp`0ax8H*MPXQS+;lakN-KG?L}=uD-#_+{w)z+~>w6zeG1l&C zbKa91eLJzjE_t`d_3EQ9<6_*YL~D&R9xEfN_gM&}_n>>_ayGQ-`e=0J=x&J-nfK!R zVg_{-j_hag2!#dn{EWBE;qpEVHu+WQnum2-Z!QOIrkbOQi#b%2U=nY&zSp-bhe$0H zus+{m@&7p)vF~%-Mts}0+jKN)+&b~~wTC!3<28vAu(N@m zHQZ(HDbxY27V8!z)m|yUfx`4XMv)U=Ma^55aC>Hdy#`E}{S!5YNLSu%(P*G!L zk$v0ZX^-=euAnFpHWTSzAU#4pR-0PAy1x?`1k8y6(7>VrGEHvwPsJC1QL^F8lw>q=k2|aB1RE#?PnLhSX`XpcLW1zf)#( zxQ6Apnrw9r{{E3%QBh&ID(ZRSlvMxe-kF+3KW(w0IQeQUQ`q?=^7Z45kH|iKUU~@2+7g1oTm_%RiWU zu>17hwDId%nSTcGNiTobv)uqLsO36iq-%$j*9xtEN5hfs;XgST#QYB~#cGSKd;aW& z*4t8`BX92G`{~;^NU}Wt9A2%w@*lz(YSzcfC^fBK|t76L8;0xkw;e)}<8 zPuqLY3A^l_7VBggr1N!LvS-PYlxmUq4iH10C{6O0l=x1CVB*6Qc;q-xAo(|)E`S_L zT_WMU8p+o5yw*mc)C}G5+y)m@SLQMZ*%Gpw1C_^W%6$CmT5tbTOuaTV5EW?6JI`1v zk#Zp8>g0d3X2pL%I9Efm zw4uP7n{3bUj1Sclpjou#61u1_4*h=O7I3imR&IOexT*r{7q-M!*E?Ds0mayInxLw= z4t@!l85D(ugZWRo>=?5D&U)oSr8ZjZQen++aj0q+a3*8p-c!oI=%F6R!^;I`kUwwK z=i4fJlelX>u+n!SeA@N2zH3yI&@Hdl*Ms|ytIw#Jx@O^6>;0jl|IS>;NpG&4vlem}b($6$6zwl=7o2U+nSxS(|5HwkerSemtNt zF1#u)Te|vJ{$$3{sMT|8@`C-?@auuW^^TG6Y2fV}0^`0(jV%wp%!P1pBYTXEm>wTLO-QNodw{+~ckP~_SG@Go@Z$p*jyYXA%Y zC`FxeUZHBmtA8smeRm`qz{o7Bo<|zPO=%Co#gJhNS<^*G6U#MJ%UEam?3Q0uL`5$@ z#F8{F-EI#INnWqaJsuwWpLQyW+AP&_8QuIHvPIWbF)OL$-NK{$WBK3Qs}ZH9@HvmM zCTtmK7|ew5U;~_L(c0wYwR)<#94XW&^kvz#)FnaI-f|zYpW_t#?X0U#w9Q>eZas%q zHWu5Rx_dA2OaV3;)t10ls}#bwzkgp-;xje%woN40r&G2EbB2b7B5pcFZ;a!m_X#!Q zc6RDF{>9Q{qkY!|K$)Xz&1F}ypHQ{+%sS3S8*9)TmfcNt+W$OB-A=|c)SJbv<5D;D zvT<8TbSafK*+EDfX*LD`{VyRkg=ylzQRt#5iG$eRBvSZ*6;#=*Xbq)q& z5lrDe%cD&oM53}Kps$U)|6ft%NVdl1)wGDEX1t=5vp@d%CsKxpiUort&$QPOIs%yrtgFDoPv^mZNxC)_!pr zO6Y$QD864_>G;0=-{nX@Vc9`eqrK6I$v>L{n=Yq zntl7bK_#7lyC02?UaNkpetXY!gjgKYMXpD$=VWu)k2}m)->Ujj+VRoLvrBRd_<$y@ z?2q*v-Dhf|21h1lJtQjY_5O9Fk4aXaLv%4N@Ym%8ER_2$_S89KDz3w-Z^tt}|`$~j;#Y{_|C~WdSw`3Fmg2En$;(-FG z;qZS{fly))6@Qa4&D?ZFLl>3_LOR;zt;;$Uf|$-W{|OaDEl&#m4v4u5WnF^+Q7g-} zl73sKq5E5ASr5H{?d#(K&O&2~YejnT9QFpW5`cspRbm0tTP9@RuQwL))`ol;ZF^^Th9evA}%418U z&vD+3oGV@SF&*03yBt5>Nj}&#*FOIJESc0eOjDU9a=pZdz5v}vi@SCwwvYy)pcvL* z)Emutt~whhF@!RuFP@I(rI@6R<>$p~W!(d^8Shf1;5fbIH1IPfxG@|G zfl0#`-${on1B+4@1V`w{$&fr!l~WRb491#Cq1xe6ebnx5zvvF%QnjVh4`7*+gqQq|y z4h=O8V=J!kTu{}CT6la|&@+VoZr|{qUJl!NN*mjrhYNS4uy`$lw z8~WN-`to!52M31+R%Ufl{T;38m#GLjy2~OJ(lk=iPsY0G@(>dML>q;T2!yI(qG1Bv z$YB@;9q~*%wT_HBg`v1LS&FdGwX*G?{%2IN0vw(j2Zge7bi?3Im@o1GYqGCzSFYQ3 zjG7yKr_6^$N?mfP#{BP|aTGLDXOEs8v_6>m0=<+$zYt~%|? zpv|{9qleE+uF%VDT^)S?J39@b&e!xX8=)k@xBMli?l32%O*G4iOJS$LyKOl`@L)gZ ze_DWu!vk28KJR=l_E(pd>6UH-3H?qg(gN;sg;xCcw|?L(bUX~H ze(39+u3`^m^gPd@^^~jEc@qifO4zqr1}c2Tg;1tKXn|}fIJk?E?EZH?Q*YOoj0{mq z7P{k31QkB9I)JdJND3ZAC*ew3WP}cFBwtv}w8oRg z_4}hs&y7@GlEKntXF3-4+A|Ntd>rP}kRpxg5=z3GVB59|V47R)GkW4^j{iKLV9X(a zC9VkD?kMdPK|XcSLo7CJatUr5)mWWyG9Wf^R?WGbHSVfDdL$-Fg;)l=ktA#LpL4?Dx%_(XAWK7VFb zrY;fp>?h%YRx^b9|H{d^PUurg8pGdtjd5HobW6fx9x;4di6y3(8>-#Rz(%f8U-^@j zkl(t5`4{VM+udNOWxLCEAPzd#>N1!sUEJ+*hQaRyv+Xl|`dixfiQlxD_hSr;)5G;b zw_;sr@3`YQ7sUB=jz^4JibTD)Ui)AEVbTVukTWj`^m=lilGvFmh*G@Yv@_Q<7J?N; z{C%3ELhxxVj)^TIPPd@I;>PUrL@T~J`>_ax102zb-X#sMhhiY%q=7&<674PoLV+Am zj0~t|duoD=bt#fI-#IC-cu-XRXpi~JIs!e%^-%i8K)V4*AQ%jgCxth)wVj*}rR}`@ zB6*oIhRE1u5WhWG+3S_O%Lw32ED9Lc$eMpsxEJo zs{l&c8>Y25mnpRn$DRPYn3vd_ z+R%~xXF=0e5H|f{`X_?rbT2E*${gI4c6kI%V3tx1`A?Q$p3}QuLO2D;pbw z^TRtfZDbEXpf~SH`U@jN{siM$eT@M7Si}SsBjv|0U zyNhJ(%zwbY5ua#-KwHU`;twmg9ZOBN#}x*jEw&r9$avZ9fslMe-RAs4X+uCAS?U95 z`>F4ekjFdCpMCFwLAnxU;X`(x)vLzkwbf{tYUn}L4fR%IA&E-p^qee8g6_`@UOl1P zJ7W?nEuQD-fOm}b#vQ%dTtm}IGDlJ3QSIRz?-iB3vac#N-urIU@82uvZviIkl(Zda zQnl%9xy*lt{&mw*R(i=aohQ~=J&{Ld)Z}V0H`@Du03AW%zO~g$vop=QE;Nw{R8^Ht z^F4d^ojG@PcIjYNLL4`ob;3Z309n8bco7B>fe#=80ia=GUEC6A(*ei~>*qp)pmS*|O545CjRFw=9B+m>J<$);EJ6KY6~h{f3+FyywEDYp=fa z^Ur^AXC|9Pqt#SIM& zV1-auc5|9t?slmt`gvA{CY|XnZ)^;VNju$L9um(^2W4+~qO5z%OFMd-qa;k)t#mxz z>TUGmC~CD-QJ18b(#H14G^$c;O-iSzV&@UHLREX)*D$zp;plCN7Y=eC~y z$%`|odhotGeN8XF_~NB2FaOqWe(BJ@y;9kTl+<;gh`ncEQB<*=*l8(N6q3d{ia;WQ z2r)nq1k3D15WyfDA}2TT*EIkF5D5GO1guRk zo^7{^JkF+`v~kRgAP^#jT9K>rD8zhJG~+otxLOZRgr<fitU_bt2I@4S0;LE{|K)+(_kHw^ zRyRId=Ow`oG5bndbWy;{J2z2W8kgzud$95HeA9$MCo3X~7bRYph-RZ0EkUKg1xk#@ zqN*GxRjtyrQCC@(jrZ)?apA(*v=Lid#bM;EEz7d5?e5)s&YoNC%awwvi>*pCD4s-nuX z#f3So0LXdtUK|iIh?1br%+Fuic;e;3M;`fdXL<3hSKhq({u}@Hzq_xC=L3JCH4|SM z(sOT>uO7z-ANeB7g;00~sBJl1(-O$}XKddfQEV*EiMyLxd#I?I>#2&U>-_;a1v=i)?!NuV zzD6_7v#C--#G1r=3&4sL2zzD_Bt=MA`wBQDh!F!o0kJHO1Q8UnBD8?x{_t$tP?Ldc zq)TBCp;n{}gCJ_>S(64p1R_BKgb$#jz*Th(qQwjTimIx9ZcjTqO3co7VuP;v+w$sa5rr);)`R!_0mGgMyaM0?r*i4-~8*pzHt6RXi^0A$N%<^g2;GZG88}h z@%KjK{=FZ&uhU&9Yaon3Kog^QBUQfky6wHw4AgLnvj;y0GrK00Qy4~&ut4EPRdq(( z8vB@3+Y5`3hK~0FP@=I+GMcph?mI8X&6STm^vH?x*PeL%(XW5*jw1(DE4VTljDm0{ zMfS7#W6}o}+PsGzR^D~{oMPg=aYB|*?7(Jm0Nu&}klYkm=m}iCKbeu!C z-CbR~(rTsFmx@FyWU)qT_RiW$n3FV}Ol_1div)lOLIMIJ03ZMY3?P7BfB^&n03i}B zARc^P#H7cyC8UP3p1;q;yg+buG1MzVfjEDV56M~Hlrb#dw50C&9I&oHPltjb6 z^w!fK{N(*@`|rQ?-jDXi8^3ts2RH8yKXd1DR9)OQr$5qo%Y3RrOt9KkZbn^X^aoW`;A~0z>r*#W4Vg#YuR-;f=RF5yd_ht)#q=xVfR0M=p*eIn7DK~ zXs3*@R3M%}lz_MwQM1d$GHJMJIdg{qL@4Wq%BR7dSB07Hj#5e!;TQ}W! z#5sQKhmU>xJKxq?ojP^u8{ha(L16yqkN(Z<{OoW1w_p48!w=8RE)nW4eC~^gg2YJf zd*A=N!Ep2b2Odfr9RcGk>OiB^$j(TWufJ}4N1K5jPGSDgCwzNlTv<(FB(ZZovqON( zM)z%HSQ^&XUMQe8dm(b5tOc3o?Qj0w3(c9G_k8R#Cr)g>^ukmB?CW>lep5@TEBQEg z+{#>M(wl`SsG-D*6XQLn>XDjb*l1ABdYJ!H+U1o!bL`npNMF0>$fJMBB7h*tx zf1q6D*;`*zpq;p^C>Xp63=st;FeX4CVFm`HLhul3W6M&JAXI6hgHZSTy&#ON=bD`g zO|L`aG-+TMLAKuxFO1ymSeWe_89z?LVah7E|GuzzS9JP|2o#q}_G@>x-kIv`S zh1QH;U$YCdw<5$y_VTr(`}VJ#ICl2H{v!yQrDm?`$`wV)GEspuDp3?NyRs^s^QaAl zF@>=eSzBM%1V*vc*`A$C7tddw=`JA(5(K)Va0aP^6j~@kK*Z|&>DO;OeDLU-7jHgtM_CmnBtdqTt#u+9()7~h<2T-L@YH)37nXN9 zQgMjIywmZ978bpa_1ZF`Y1obQ0J7FPBfdG|d{lpVb9l81D58ZJKDMo~At83F~wrzR) z@#81{)$jem>#x6_W!Yno{qV8J9^1EX-|zg+zu4++{y%^9m!JQ_=fUHH_dm=I2}MAZ zmT!Oio73s&!G|7FItZiKIUuD_EQm8wWovKR-aD;852i4G=;PepKD92;Nz760Y-WeH zz5?9$E=KCGFargYde1DC5DOV63xEBsXLLM&|3jZTdvf%{@Bhtj{pN=jXX{pk!W1>; zAPAyHGR=pR!P-KD-1yRT<8&vDk>jG$bBlXhbGscj3MLb$mA6C=ptjYxoQ_B=h)&WK z)ZMZy(njQ5KF#{<3+FPWd=l&Fq;G9GH{add*ofm+5X?BM06=Rk0?Yy+|G=|&00v@2 z`2Yx%*_br7JFPH@O=P@Ce>^Z@V6Clc>m36k0U>LsLtl~6N+By`=SrhVX{zfQm989< z37tS$RgQ%Afh^6A#^Y$K7}ANP-G`z0=MQnW_sH&$Qd&;!^k0m5YICw9=i$G;Sw5lvZWE zw%L1kVVfQe0R6UhbID6}ZR6z5or@RFtnJu-ATWt@6_8abu-0YeMpgBTtS}}p8nu=n zG+{vTb(M;ka?loVhc&w&hmj$J}|9DvK?v8bKt>h1HLYyp0p!B?!9~U z(#x}LOhTDoSv-4oV|6&cy#JA*-}|5c;>U5+x$mAMiyi&)OK-gP_M89wkH5OO94-bi z6_%6+Kyj={fd~R1GK&NBfWqj7y$BnOM2w(eB2P6#=Aa_fiVbm~MToQE;9{fU$I}fb z6|)3U2ufS$khHBG2!bF0k{|-25CEZQ0IgI2zyN|swHr3O6E9Uc=_u(kDuv$Pg!|PQ7-+ zjn|)k|MJS78=Yz9*)*aulxgqE`&s|o{7eu>Dl6)75v=UJ_0q|@V9^atv~sb|K&?x{PH{Ryz}Uzj~+R4 z-|zVFhcBGDRFw9oKY9!pyc1*KJKz3Ro=-pVz$XYPh(cx%5Umt28?LkUH*N2oW}pXC zoW1^D>8xaqLlfzm@;skZ1CT+eYr=LIEdVJ%rO_~ZrO^x5YMx%D{%`%x9fuCg+0q%4Op0P!_N^bq2Id-+@L==8+mRp5&h1)ZrW=0@%r9YcO0-VsJhODQ9PzWjR6gb93F*Ygd@b z)?rn$h-hs@z_UjHr4;~+ctlYe0D-+{_S=?LDqD?4quRU5)rGC1G%2bwP8&fO0ul%+ zr41!1&Z9Mmo`_KxSctR$dJ!jJqPVPCnRGI(|Lo8IVt()4x7>2~Vzc@F>u()@?I-`_ z3v)LgtRc@XU0geG^Bt1zxt1?|>#?_ob?d(S?yrW!=bn7}Q=ho&&JS%5RgSAyez7^c z)Eo46?>f+(nLB;v3@IXQ6eh0LQP7>4nJLOG$6JEKP<4hqJ=fV*`>Hp%&}>CT5iZW} zt}BcpBWS%7{D96qPZAT_swj(b<#I2j1zUquf)0&PNGhzeIzTCSf+rNTjP)w!Yf z(rRrp!JJUTGV8!pd6^n1#+RG%Fwaf{kK<5mvBey1_24;^ceJ96q?`%H{IV zf!p(B}#^_~M`b>7V}I@BYg? z&t7=p`CtF_U!R?y%c`=`Y@^WKci;Ps|M;ICe&~J>0Fdu~_uG?k@8h4mFNiddASyzQ zV8Ejho2|cTx87}rdN9TL!ykwC%A~Hqa^9P6Y;6oDo2|Ai%r>>|Cg~FD2v8{kYbzuH z44hBiI(F^nFCO2v`@o%d9eLxq(?5Uu(Ledqe=@%qI~%ZI#K|_UUWos`LKuuD6H?4{ZiPvP3=8BgX0P1=QP*?R7rL5`+ zkqwlL$6F?#*-qQJ3RT!_EM`JU72^`P$^){kuP3 z-h1HsJ8%8aEr(CMdiI@{p1OV;e&OL=P@f-e4Gtc@xi;E{JAe63^;h40_9ORy>gF47 zx_a*1vyVUV;79Mc^Y-nDDe>qVf3dW)n>J^+HvN^$!!+&2X{-$7`LwDmLJ-Hn!a`>< zT`S5yayaSn(&8>6m{#jmRYcL!OnV3W07wKZfC2=esmK&+Mz%?!f{@2qe~|StG~>$l zCuQ82Epiu{W~ibxh`Q-KPbM8jce~jVX?BZbos)$ z2&*J$=EcI(FRwoPR{yRCzH;ccTUIZxKmMb~_U@)nKXS7tJJW8ftZ2q5p$0+100b2h zhyXB=2snXK*duvFZ1}S*iHDZQ)T^*&sf7drl$h8kasboe=zOE0dcC6E*#>}B?czr2 z9V=r@5P}def&j9702l$iHq63=%K4hPBBI)jruA8+Jh~mRS=OqdH33;KN+c9O5dmN! z1OP-3VL|w>1V9k8_4Su`tju1yR4gyQY0##RIfa!$`Z|~W&v$vVeFYaS$ z3P7MyYG>HSG_CS;C*S+Y;=E}!y3V#PU#VAi-_YzXS%^Iap2QI_1PB3$A#f;JHoYb? z1%f>1G~I5QHwWhga~4EWWVF$w4aIS!wVr9u1SZKx_OT!S^uCWhv}gCBAm|{fciuUs zH0|HFPb>AwPk!=?U;O-E{^ehS`0;pLmc`e;_O(Yo_u1{cc6R4yXPVtFefcZD{m*{u zi=Y2I0t52*zxSQ3t=0SQzpvd%DxWK*v3oMLnDhpD@Z1B_MV zr}cO|%_=>!~{XBsC-sbd6^?Q zMOHYs)fB~shMZ+oEuaJul$NrXG+W_h)JLd{W&~f9lQ=TKQdcE|4&&KLUU}=4QX<04 zq!0x}EFx$P+9&|Aw)V`O);{Nb?VVB@l=6U}RhXn%Sx)n!c8-)HQoiPP*yuJoQ4lao zU0M?)S|^o7&jvA8M*ZxGmmhufi5qXaeb=G=*WY&i)r(hNdgAdW4Zr%?+qLg)Uucbn zqm9w{z%55EZ^7UEmp3GsyY0?9=H}Y#tCya8;^~Jz{^5__wJS6Qjz*6TMx)UfimbV? za3D!$$J3#c+(aJH6-7zF-j{VfCbE%fxk7hZ3t2u15;q+7lVqjaUSSU9184yh1AxjD zRYnvzhfrBR9gJ2BUo>Yr)7m=;*SGvn(Hu8SVFsfbOgEvtNX)Xx6 zMPBr_uBNeFnoIKOsMjmgbgsX;#x*d_{m1|FTlatYU+lf%L$$XrJo{=jS$pI&hqmv~ zCTdniMMbaOjCI%)3{fRSfwh*{Yp9JBA>>^4^3iIY4aD18PFvSxnMqr_TeG_;XnKqp zQ^W)y5GlR%htsp|uG!cuW@dINWk!=JC`F`6DG?!3Mul1hB!B`0^Z`M%mJvwA0XhUJ ztAVF0Sw3vXhZ^yUrbd=elwk%C)JOmb!ongTf{K(<-g|8{16ylBfMw9@zr3&zm(xZZ z&l80rItXHK4S^9Tog4J}=UVM#xK*{&#Q>YA0F@^S6==75q?m?(-AGC(#OUDm3~@+?Vb!f?R^Y3U|;F|93Y9jPD?5bx{S z7T#7G)!N!dGwi;mIeS{o!Meed&u|Xti2j`}$X3dFACsBQb$` z@r4(D`SQzO{pzp3_4Zre{o(ij`#<>CMV0^IAO7oSo_Kt=+wtDAufF%a?~KP=cinxP z(!MuZPa9F5R|*?(*!0CDs4jHXMuadbl2yQ^w>n7_BwBaFV1Xr3 zMme4!Iq#8u^W>@iqd$G2IlFS-!=IW=rY}GF>}0(8KmMH(z77Lo zwze*m5~BowCzJ6^w_W7LXgJut_t07|3*si4#N&k#ep^0753h zs?1nynkM7%C{0t(bBM%<&T{1)XcNS7+-P1~Ul&r^gkFTSVqXWC#ahjEca;T!C}XI0 zm4K;ju)gYk_}KGTuJmud_12xc<`3Mo_rlf7&pq=56#ctzTe;(wo!2g`^*2ZR4;`3U zTDZD7diI55$By?ucHie_<`!!=1}uL0+;a!_E`RZnJ7QDfE3f<+>gK}YL6G?{Sajax zSD5~>`b zV9T)%imX2vu7xor?Wi{zWY%})xA#XySqgaFY0rcdw8LhKkpdo%){E*&(yCBby}`8I zy?$-Ih~j8wrjbq7%E@@9wa{$sD9T7&c=G+r|JPrC`_LVC?L2(*?845Yue^Qf6KH5N z-y8T*CNm4$I`b<@x>QyMC=J4ZVY<3?DoSZIc5`#Pl?sNFkrxyMtph~T+Gu4IYGMQc z0z^=tly`urL@b~~fxPTh{v0Z&c>7FaPm#MQHi8ur0uTTQ%dY?+A|QJ28ANLh{|K?J zxANkIQWe2s7<5@kX>Ec?e1M<;%hBWt(s*vRJJ`zIl(aKWvI?gj0>UIzI@S}#Cx;uy zcFeYY4&d7&dNi$*xkJ&+KC2W3kx6IDit>Urp;pykc*z)B)m56#D4JmmyjaK1dj(*~ zL`oBj3ql03;5`V0l)V1R(X}h+Amc7tWl!JiPgiJC^ob_s%d5#3FT7RppqpW0xuA#24bM(JGr}o&j~h-XRK-pm-u6!Xyp{ zgT8luW&8H6&0ba2yZ0VAeR(r!&ICc=okIa66!r)}z@(%s3t`(xlgVV1B#DDI60u-a zyV`M-q;a#=ACA!kwewbl0X%bH6#61Cm`3e5Zo3)*f}-$OuWY^Y$~*79cX8YH>-OzC zeBj`XX#NxHPP65zx}7wQ1N3Z^uk5wn@RXHtcW$vi)Il^SK$A(|kXxKx4yl9G9Zz(Y zr$2h)rK9Ih-*WFAH{5o^`4eZ4J^$i-aP6ZX>TFw?Ys@Wg)<%*p12X&2=tdlcAW&sc zXZ2{S9BxR_PmP;NwbtGjnXAi@iG!e7*QkRC6^`?9?O|bYZxnA+WIkOZ2SE@D z7kR!G##~mV37g(EomVDOwY5q&!m#aFS?7pA8&71}RiQBf2CJ7hUV8qO2R`}0;X?;R z5I_V#DJqI0NfQ=E0Owgm5RsG?Mgs5-K7io0Mv$r~Cck{~h1Iod`}gl9Em2}fJBHc> zS^$0R8=->fY0S5aFdsD;o3XvfL2Ku18Bwt@h*wu)0H zC$GM?uELp*+<#{;uYUH#PxfsOe)BiKvNkM(G%dW-szTe-#h``R`uSJe;iTQDMO@+!a*UlkAV2o$0iJHxHb89o3=FWLd zI*yZ~sI(5!*4(A_anhWP!jOf91pyE|f*>%FR8_&=HX6xfI!cn*Vu+|ju(m8hN!mfcS1xT`xir0eE<1Jd>fGGIo_#Ajb}lY1&iDG| z@pmp=I(M#3k4sV-x`8Sp^=!)p1;B#icMP6}8H& z(QM2Extce7{f(uCeZ9?cabY*178H>X(Et`6^1x_zHXjeGavVoN+H5dj>Dhsv=9P86 z(`tuCaaDzZ=DH$5Tjh1#BQ;ThXQHx>7-AM>>pIYSzOx*vZq3nVpI?7_?eSl{w)>Xr zKKjr-=P#}P@`<0A(S^_6HGkwfQ0Gwx~w1^D)8=aZ>!i7sawjEJADQ!gtJ$n--we?EXn_K4=meY$D zFU)s$HlwaDxRP-u!;(oP(x76PN^!#Ye%mx$X-qsH(E5!axcc&21}%ZpeV$ccC)d>5Z2Z!4I%|%;pzzrH=~q5pE!2%!r8O89J%R+ z8*gZ}TSy8Kg~2l`9e59b+A|X>$D$E6f-OOzC<83j*4FBK$BrI5`p%)lhgVj11YywZ zG)#b%&6FV)>n#V!#l|~z|9EQjV5(-XzsENgEI4#7-|WS)>W$XJI1ve>Xdwuf0A_>8 z3ak^*6%Kc-D9J2#PQ3!}2-j&|vfCY15lxJUfX9HvMtPnuw91&_`swzjs z`T6;4*RGLLAT&EOXRV)1voMI`#!NpG9X1qc06_o(5cVL9;EANJ3-9YzBNelAk`0~ZgPILK&!#6H0EH;}> zXNz;^&%S^1L_W!`+r8u7+itw>`lP0d7N$tSpjR7{n7|RHz4hidzVSC7`^3Y$_Z)fQ zrT0C#d+t4S@${K@Uw`r6{Qg%~79t!Bet!JSc^x#3X?Rc`B#Z(?1U76*LmX)&H7(0a ztrpi+%zi#eW`JtPTm9i$Gg+F9xz$*RqLh?kA0ULNDleJGN+Du)VD%&{-fRRT6ECW=ral6YZjeO-B{f;4S*Nk!vPK|Yx2EGkM14&OR{@rOTtsk5-- zo`>&5qn>^Gwc(X_AGv$}hPk2(n{mX0vK&G@!S3AhEv^=og8sHO1RIx5{*7+ z;(3-P3prl|k!!buNtRisy>FmuDHB<%%ffh{1YtLfQvvVnSgBI{glz^+T1iWxKKAb0 zmoA-6l1K-Ua~y;bVBi@EqoTA*Cs|$*g;Ct7i$dzW6$f>h$0>N3vM-I+-I=-FyRP$| znyq%6B+96w%18kKBcSqiv31N2P9$0nGc|wkUYpEPsKD9LmDMniVYbm|Cq-2$-ANle z6)iGKe{#IG89@8lC(oZfs~-5wBe~R%Klj|yw)R&axx3p6GH=F3VM63;8oOx|HnuLl z)C@NpsXl+Pyy3_rnOkNZm44*dBA`YE;=Qjx3g^b&PLUjlC4wYQs(xr=W+6aOWfbybbhQ;}%%d1_AwPRCU2zx0=ahGEUR9 zLM?*EL{X3`6#yEf09BZkwK8E**LhW{AgHV#PVCDsA6vUx6jRkqXAd2`e%o@Zkp`1V zxw$ra|M-dFXmjtrg&ix&?YG_7QlSbaThmic>C$-QWJq&4;$(nX^v>O*(zD6vFjdB|un7ZOg2u=| z(oT{rTdT^e3k%U;07|c<=?rOG*4Iqn*RG9b+AG=Aw_4pGjM)alfznne^Q!V-LjVPe zt@Dl%jgavmq}1x#rB)+kpSyB`p${6Ssxn`Bu?k$MC{ke%#5!suppx;>`qFfovnFV~ zcWL;8pFKYu4ZrY(&o$f2ufOr`>#x7|@W*fXyk7(NNHb$OHKwGmR0`G`@ zBMt*&ilUkpwFIeY&8o({YR*E`%sti4LG1!mQkGowQ&lMLZ>^r!fV15tFHwJ-i3SYp z@{a9;zHYa7n;>KnZ6fDAkp?6bWEKP@P=ts=9=y}edQlh<2mzB|S#CNwolV!IYOO5p z>G#&lx~Em%Z6wB%tF3b$1igTB-gyx(EJ(^QgNT4&UQYMyUs_#XQ#fzE(xC~GNSP2Y zCW@mtynOA#b$eINoxQkY`wd{46={pgi(%g(A4V{W@#3j>zqvA>xU8F(i#rb7JHbi6 zc)wnMzu~7*5|1k1&uMOHf3vxxcEVsiXHf!0Su#Y-O%GVQttd(WTGltU?vM(~a_Tu_ z9*Y|!F*K7DtmKmdM9MPX>h;z)wzP?ZFd2-B zZn%D7$IdQ5=4I09q=ye5Rw@Ea0YdMg+nvwKLK#8?VNBD8%O>O1w^eyQRc2%8X7}Hd z2i>?C*gUs`VG`li@LJl5D_4_lC+SXaJ7ry#azO`>P1LI|^-jKz4}R{88`IvCFFbq4 z9XH-{^X^7~7&gTy0PFKsbK{ zA`+r7v-cn#!7GB==HgwmnM@|5G)+owAgU-#;;=y!Fq43`7Q>|B1*T=G!?1Gp=&=)T zy?gq?<^Iyb?(6p*S(saDB++y{-CV!+-mzm@*1vA=(w;pF2M=y*wjd;-T9C?((Uqj# z4#Os~2VXZ$L=eAsV*T6SeL0@H>BvX#eD~t9v*#||^`Q@Ug7k%_eth$x_E$dtF?{;D zAMC$z?$o)H?bd>I6oiQYgi+{f4pa(`+DW>xcDA-#yLQcOY}#gXcN8^63c&$Vec{}d z9ozP8tWV}a=LSaKlpu7jis7!za*REYaD7u}PqzoG7(#B;} zo&Xd#wR8*z3FHi#$l@y7p~tMU)*#3-i<3RREr`|JFCOMc_z{#;2aAx2pZCg zGzxlP2(e~Sq5(jGD8Q=f$E{%_g;*_IyRw;22T4kujzI=jNj@#gvH}2YjL{(}WmG6E zVHguB5mAIJMQg@SCjGLCtR>XSI#*jS7%>L`P!!oMx7~F7*vU?72ZRluBp5V}nGJBk zNEAvxgp2RK`8U_^S{(OcracRL?kOU!a4i^J9iBhI=vs3NtG&`mvb=JAyR%T%ZaCf~ z%|Jn%%&{~|m+NpNFGnm*rP^ghW$nYrBr$1IgJgNuPl6zyOhOX|n%b>~Qt^0P0V&Jk z#W-)KV{3xewYAY}ubnE(;Nzco$h+zDPkw9HirTe1-nFwSG6J%J36u(hsOwxj9!nf` zMbJy0wwjZPRVvV2>+(`iUkQXQG^%v>K;lNbQH)0oqS=}B>iYS(6#`*xRb9ukuJh*W<6pkK_26f}=py*Vt1oPBUjFg}_wC-XIJ>+!oQ{~QR5+>!FnK%gy|is! zu3YQyJ@_@%zG=wXBf4T>t3p^%gnccp1gO$9$nw5-B@%~05XbRkoO_3X4w=1mb(F;8 z@o49+9apYiF+rrX0s;V@B>z8Ga2l)mc^!uR zobxRI%36Etx9A#qWpMNt%Ri=;qZq$tuL zMF6LXVq3PPXtP#IGDS+H$RUTrbym)DXYPLQyZ_hcdCuv`NWb*=bFSdvTdl@uGHf)G z!cA*!y3il?<5mMGO5#?P4W%x-QLEkRZtV2F{FRq(?WK=> z`dMjJufBHS@Y0#12M%9(@Aa+Qum98k=I`TQ{P;%?KQucU?}lL5D-dH$+-$at(sflU zq%@&Bx35KUh$0$|d1mIIR>GVESFJ{zkN3B>_GY?=suJerR-7kADJfmm6-&?>2}_1C zVdY#-NX$4IWo1z|nzr3E&JRRNWuiM&g-Ph6nW7li=fulY8xS<07#gKmryf!uK;3=u~ojv2K(FN!8YKe)5b>2 zrx6yt$```yK_Mw{>;ZrjA)r28WGigF{f7v{D?r z00ReW)p%5Rr)rT*Tv3PM4RRc*B+}H5p|^AO=*m)ED#n@V<@==32-+K{Cwm*ay)~9V zs>y`4&uuh4J$<}%q4eIwOKIakQEbyRvBp$Y zjuOOeH%uv^Js2pR3P!=iEn^$ZtaVa(^YYJboqKKT3%~WHW>dfV!VBBC&;R!CoD%r( z$ibF#V*p4SNuxdE>TYj0c4a4t6O;7QPP)EV2r3OlQg1cGeoL#|tIRIk_h3Nhq>$o{xzjO`<3= zy}f;7G?4`MMqwP=EYForm{}>$;5DkzczE#O^4hKSMq`>td8h(TP*Z9T?C({LW{fBZ zL;%7pEW&J!$%`z{GaK1PGbW9-s{{ezNVC~gq_mD}Cx8mIWmMz5HtEcp=dXPChc6?g zD=UZZzyHkg^7PKu-un8@t@X8c-#vf$;DJwk;;BO`v)zs%RRv#2s1bocX%z{ewuy*B zQQ|zY)5zB7GWb`|UHSTVUOV;B<0l_{_{Lgq*!TCGKC-{N`@)a^;>jnD;;;RKe{%ML z1FfcAT3DT%IRIiOqoORTx-11k8fzaW%~o{u*or{t_lAu|v)gSLsu5~-MV$`?xEXgg zHhRlT$86N{fs{^(A`SxJCi$k9{qB?^s`hqvio8zZZY$}4K(Dto9PQ4`HWwC`2BR{s z$Bj;e825X%riP_hDP7f72x!u&np^7|@ZImfp_}^YXP#)ArT5>s^n-7I^Pm0mf83ba zuVhnn0l`Mp?dWz(EAk_DydGLt9!UCX3fdD(^04PMLP$R=# zA|L=La2EoSwK1U`3`Tps5rXbaFUHfSp>YsxLIlDdBq-E~Sd4Rnpa~2GSB<>O2EE%W z%l77n@5Q!}Wfd_Lc@}(?#456ABT6C@8Kaa&AXEZI2+@!U-aGH=l7+DtPZnoq`n}#@ zSb^zgtV^MGyWMI;B7-dN8vo%IBN`3ITU$Ggv}H|%NW#HdiejB*8HlZY(8h~YS{YZDt1HWEx7LmB zut>lH%_wa(l&lW=&igTvSBMA%0>B`GAdsf%)XcPvqrsrRKkO4y6i0D<8~})v05w}( z&p65}GOc0ezw(!Vb^X@v>ftjht0#^hJJ@N&?_PNO@(1tTTD#O}sNeg&FWi6M(IW3# z&58t(C3s;WKqAecNgJgshyo!JPyiB2QtZ7SWYu?n@Qd?rUw``JUpR8??Dbpwr0wdF z&Igy?|G^Lc9RJ6E`JK(%H^+lfo;wtcUIv_$EWtZzwi-xPfPP+W>}-GNLOwq?-)S!7 z6BrMfFrJ@TXf&F;yX%ATog=4bHn;Z1BT15(*mUbc6GcjSvfe@FpfQ?sfBLgaS8wb+ z^W4WyoIZNtl}kVVs~0}|+*7~vJ5T5CW+gj1hTw@StDH&@o5sgB06|ukOwjChhgsGe zjZv$#*ll6_8hmJ1aymfPV=^%(9P{05Ziegk2qY#R^D$2Wx z!j(=qx4MoE#IaRMjFH%A39j9=&6!TIzf(FC-Eb6xj`IElT?sNC47bJ8{9LO$qpM2o z?a}Pwfx`K+YT9@)ZZ&n(K-CR^${=E>ea$R3YIsi~8c+v802C1K%euS`zK4D>vd3%- zYRIi=1!0CdZmO&-fA;g6-~Zv|XFmP0dmlM{?&p{O;>-W`kN^4axAg6L`-*jg`L<0` zh&t1|dr6~ppKYyHdhqs*zdZBcJ=ZVG{PfX?T(NagPu5yShB0aI|>Uy@KV?&H!TD;GosHWSEPNxwPw3YGr#*gzq!0Jg;4sC0as~k5f}jo0EB?yE*2)OP$@)0 zR2mflg}Sg-*HuN@-r4B=+b@5`dHe9ApIAD0PvylnlB~=J!yWwDyKXS(5Bj6waO@lt z8f()eNsKmtViXRC{j$o-aedqS|$+&;tnKREk{rJ(NDR2+PH&fZ!xomW>CU&Lj zw3pJj9oX;g-%-|8^#D}aYT4gG7wyF^-xDy6t#q#j>E7RRaG>}z;PgxR3QP>QDT$C zDy6JVo6RYJh%f;(!J#N^jb*OOdLyrT;+Lko_vr-lYN)A^=T+J;l@zS$;+5hQgfoO%1g?eBf-oB!wk`d_wTGp+jh&h?OQHXC(3(;QA>V~@1vPC8S+b@dykA2@yW zQgvYQgcTXzc}HhA+A;ShzH{VbAzq~@W;H||_g zX3(9L+iSxE2cCZS{n3wpa%p!zo?SR`?8H%>$ms`X_IlyMo9C~+d+zXD@rCEp6DtEO zvDH2iaJe5;8P~PX8(KrCjm5~C+LitNy+MB%MG2x7&w;&CU?QwahcL~MDCK;eD>Ovh zZYDcBy+$(45*YG;ds8!=VXpz9CCUi~KtT~?5kV0QK@{3JZO2KAnW~zDAQ8>X%>^ds z0V&A}&NBGg*M4yM%K9UZJh^i4;C=TUE$h+SZ@+)(;(NQ>w?FaR(@%cnu~s{7q&hE# zArx_>g@dqwAPE5z2N3b3Jd%I{AVN}vN&%rDc=p~aL>4~(*7=uy@ya-dgGU~mKX79C z;7JuVKr8&S?_5bbu{Jugk=Dc_-U%}>1E2(vIJV9O8yQ#ojoTZ8-sHop*Lr)KPd$16 zQ%{~w(~;E^R}N~o8OKg@T4#|a3+TY)0ZTw>HJe#h#Zk8^j8W5ZG((su(k!*-0X)ya>u+uTgTMQ` zoyaZB>Z;miC=dZrp%@GZ!GX_(rPWv=6E&vHA&k_W^XH>)?h^b3ufxjX>)l!LtVxMM$KXfdd2|tkL2fk+UX9C_h}g zHh*;a#>V>5L#KtUb4p<>0wRG(06d^W2_kTp^(GDmC6M++70Osc@5=kHEzYF~VeQV= z!ph;AY!!^F0ZUI+$@Pe^){2ZSO_Ui;)~3pe$4cq6swGJ9%;FFMnS=Wk?;Y1Qf<#(1 zP!eGsMRA&@qy!r^rkqV$X?(<3Vy>I%oO57|%3L0GrY>K1-~Qp{bav+K6KCIhZ|ytZ z`1-&6-~aKHnKXSF#+$wEOD5Xw&dJX1gmGc@(36bG#cSt|-+S_dn;Y{BN3?^<#ye4c zy_<4x>^p~_cXkD|=Fl7MUR;=8*xDJl+f-GlQ>ykKCrrS(CEmJ?)CcDu3WzH;jLDR&pvnf>?2FT?V9C!|CvoT8)TN?q^rJDfcO1r>?1RU%QBdfd9 zt#LLQj50LcxOH%trCX0wMwc0U`qV zAQFI-QObybt37}yLP16ZL=->{5&|G9MHqZV=!^~s)$NTNt%YQ3fA7$tlk6gd6fs8B zA}s6yJzxN05CK5#t?>XbLC?Msa1d1!RT@SS?4N(_2PY2ChX8lBCTAXcoJ~WhDQu+* z7C^YF$`N=6kWD7*qtR|0*|e#$YT$ze!8nP1Q72#xUx)B!cV!KqF{G5)QR1 z%Q{m{(aogSS6sJA1(3R#&T!DyMisMd&t1BKKl%CA?7>ryfAq0Smo~oom4Ejy{`em* zb!(LmQjmPGJ;`p_bTXO@Cz;I7+_N};{PwN2&eHtVUTzx2be-gkQQ^Piq|1D z04RXq891PTC7qCpNm&4j8l7yyH*fV`fBnkUYda@TJ#_rU!2>JHgZ|E~8&|JfdWT*1 z_@fUz_UHp?0@kqB1jtCj;)Ab+8GpqhXcP^i02Dz$&IKHhfDus=1ejH*RcxAAOQL-! zxAu45ugabF^y0ghwr_2Oe%{#VaS^m0%LExe&y${O!BLr`ON9ZA3ZP`ts8cYWHL9c@)2|0%nDLEW(Y|d z_xpqSh2<=FAd$5#7DY;t0zfZNi8vxeb_hHf3 zx~j6tIF3wR)dv#}SlsdKI>TLR3;hyaL!BtQrV5>OmMZLKehL6-NsQ|+yto!Qw% zW13|NQPQqzA+mr7z<`Y40G)^j0b&E700|KR5rF{EI|d|$21&_Xi~v9kC_;otD2Ob= zOu~Sm06{`c$`Muo<<9QyW*f%YV0rm?U1_5_-YF5SloAYp0WdH!vj-6h)?gy!J(a+< zk#Sq^pMT{$r;Z$`oxZW*9(e5IwOF7ILMlRl9D+yj22m@ISXB8S%Lb%;QeDEP>E(9vXAP^LS4>hyX8nyBQH7cL95*5XHZhUF9b|NLRu1oJdJ5eRJuCCd) zK9Ca+K6m=T2hP2D^}FBw5C8PP{n$)vyR9ozi*^yaysCSsD<6DO;L6hR-p*k8)V&vX zhMl<+HYEAhyD)jL5$B@(_|NMOfO5(VeHvMt9*$}7!f?tEQYE$!Bn!dQ`%)t<8Z z&1Sr{&dug=P}5F`Lm9XbE(K}<2OyvbP_t+Nt8LT94Xw@khI#9)OBde0Y?Ace`yW_6 zbl7USeXD=|jknnijvt*m`|#0|M^_avqGPEz1Rw!mh5*7MfQU+21nmPdBce8l;BtU~ zO3(r;4!}Mrga$a

    B@#mN)k{&q>&}$<*#Bo?W>=n1wgq+q-tB!1e9i1C_O}>LRdL z8kI&s1VkH0gtW6e*xcA%yM3qEAM}UA{%CUK(EUda-*a$vWp8`<+N-Z_Z-4OkV~bBc zaX7UF)VuRD@$TjwVB2aQw$aphGM;3kcDo&=>1dp_+tXUdF0cz86(BKy17w958O3!# zZ-VEI{c8&c7q$oWn{V%b^V?UReEM^bJbM3LFMIjtubW6e_lYM~SKFObfJh+{ z2#Syhh=2&fuOJF2L1F}iy97~)K(qil7qn8swbp^Ctg6vyv~8#|3c8(TkyKNst_eT` z60-*iKmsHHfB+yUjABC2PJESM5xZOOpZoqjM-OJDxxJU1didFjwS*R7(`#Qz0RXXy zh=qNP;>%)GWCN{`2&blIonxaD0y01lJaYw7`cQaZF?;sG2UnLlV(>0wr~xXYeXD8v zds(OjAlKvwNdX#b0x73D7jMWf-Wc8U$gdr}_tA6bum0#qfA$Ce=$@v&IGDS zEpKgB?QU?c-%L&mA23P8tTlEf`C3+<>$ay{-YH!!#tSw;#bCG&(O18AetWO_%&-4i ztdnnl?Jw`Wr~ldK=S`h<<5eIeoz@}t07W%+J_iV-K$r>9XzQFXvqJE`L<-hI?L5#l zOH7IZLsfX;&`fQoJ*_Y%43o)*O@>hfy&cnTp9s_npaK`p<=*Fk3zixQkxW)NQgIY_ zv}t&z@p$shZ`|DL?;kpH@bIxC3kR0Awl;5Ezj^V4_g5C@AG+`4y{8X#n`l&pQXrrR zlR^RZz9xkN?7btUmD0kzWG=lM^Zuu@8uB~exsy{Yb@J9ql+cDL2-3d3kTQ6}zo zr@ZF?Qo5o)*sENwH3)=88qam-U5=@l_Kxx}8I+?@P5wXp0kNsAs7J#pa2EH z19}06;02IL18M+d7DBBQi2w%_0ff5{1mSOx05aYM2!bSl0-6OwV67Oh0s7~`k+A!ATk6&7GNa!PXs|EXzz_<@7k)y;k$P(zj$PMaWFA^<$*(I zo^)WuHx#DM76ncSl+jjvAVCZ;9__hm9LF&*O?79y1A>H6F>yc-5D+{fgRrmwqt*sO zuvWXeWU2CeP);_dQYa>QBWW?`91367gzQ7@Axwh0yjH*Q?s)FtV~>6GlUF|+{P;&- z`^eeqnMdrj-f8->AxR@jCX=Cq(l(7(YEsr4yLz>RNM(yu!ysgk3Eubrc;{nz7!y!mg5kh2wWjDk}wAZ zRLT%2X0}>aF0%%rM3t2fJnvmgz>@++ks^v?9qE)HA`HXP?IazM^4Xv;)Z#?(h zBM;njVr6LogD3B-u0cvdg@Aw(AczE!AP@ovBmf{0P$qKDJLfx%wm2jp5EArEKBy27 zMH(tJu!I&Cy1v%m_?f2Ld2QmU`&%=Q)U@byvoadDcW(k~Km=eG&)|s!71XY>)*|9K z&%6u9M$BCL(j#2Fvi05Xy%yV*Q>Pv~`{<)PTl=rR{PLi8=~K_2eCp8?`S4Dp25IVc z_cj+67u&6w&CTBa{&->WaN6j44FbFUpfB*{;DIx-30FUSu z*2C?ajR=sU!LVFjJQ5%Ruz^WH0RjL61_6f>m?VHgQX(LNM2biY1F(n?!v7DW2m%VB zAOIkP5X3Ej4qv=h zpFHtQ({{E$e7)?wH`T^oj*XSiVE0TdOtQDP{^sKR()M;SHA7jxlg1}z<{ubWWmY(2 z+Lhnz4c?rYTC67BsqSJ?2f}FqTe{uhu>5EL%a=d*8^3ev%&~VaTv)sL-e*6%bo!(! z`%ZBxT(XE#jQ}7N1U!-;ibxPfLIS}Mg0(hq8Cft!CV3gcg7+OHKmrtlq~h4dQBz|A z5XR#>Q8FO%^`zNqAM%Pl1`gi2s;+DAJPQhI8+8W5I&RE-@WIWWzW7RP+wFGe(I-CM z?zFadhHJNPoPX;V^NWqoeCDG^k1Rww02ktGOU9^}9WZ-90b~Fc2m)Rp05B;O5dbuC z%q-sf*rx1|*pg@f7IZ;5Pa=?DNT|{+EL3^5zy8x$Z;s0-o_@GJcc#Kl2`!Ei-0R%} zZ$UsLu&`hN2uOkuf&{I}2X|Lhmm*wCJuX*Z@+zMGIa9`hm3A0omQ0;W!dVqZEUu8*7Iy^Qv(zZ z9$cC9s!`7`%q=%svz4Fw^RNB<^|v?fd-(BZpM7LwZS9p8zSFdOU;Nyo)ANhAxl}pp z*u6BDbdjvA@D+0(O0f7bCfgq6x z2?LQ*WPm{g;r~MdfC3-_0U!th5(TiaoJ@vQ zRT>jnlQbLCD6y*)g~Y0e#d#>$Kq2;<-+S$yi+dmY_-~v#xOnI4jW=HT>&gBN1HD5B znvXtw?D+BJNj4Dnq(X21I$`h7p*U`I-oH53dSPLDp+zGoZYnJHGnzj6>(V+|3Ak!! zxc$NW?A+$os5@nAH?h&dylS@R=1@oDNr+`uWe_ z{EuIM<+p$Pcc*9L7k>2Z*p|d@>|ZY5D*0V<^wlJ!9tNF)F0Z3Jo)={_HPUEgGNyLq_4HNYg)%B#)XfCl9G(y`iU8$TG1{L1RFrNz|~Cy#-uZ(d)&@YXwf`?o*+=_ej~=*Y^-^mw?hl~>9k zgir@x+u#i%12UojGNK4L0agl((TE6us1@9WXteQ_5Jwae6a;jv3a^5o6^>LLHKe5c zO7G53TS;$!qT}g@rxs6p)hsIiph%6{q&b+T~^=U6@_EdF#3|t&Oe5SH5yrz={O)Mu{HLE;oN14{^9MS!_pv^ZSB*ePC8ajwG_HKLZv-_(L=h+o-~w~- z=t@`DrPh?DiLqK30ML5?Qko*~K~Y4goM)>vphs{5HDCY`0631ulfbn*b^F-o)$HLMD*eZM1D@>atIjbPPm! zK1^Gt2sxO>tvlJDef6bg^S~EB`_Z{(ymcr4Y$8C8|2WSr?Y-+ccYU;oaeZz8=AC3;+J%pHjT&VTl|=cf<-`~T;gNwoNDpM4&v z_w8@}<;sEh`RDIVZLu)3%ns^0x3Tpi-ie}A1ev`E6M`azKuQ_!1CdO!o_7;%14A%T zqwt}2B@&ToDYU3aQ$wpJaL9`-(mQ~qFQ(#XS=om7=xSG0&ebeJ2=>{7--K=wqKcdHnQ!r%t?cZvB;?f8(B0jk6COdg#o-nDWaPFA$;D zikXu}gbIA{WmzY2Yi4?xs1ZdS1lt?-ZG^+oPF0PU4lI9obMIgM>mSXpeDukW{pR!x z{_+>EzVpkkJ$6$6{^!qtyR$ngqV9>Q`Hwg_Fs@^jC@1T+Tc7Fx)*ii97^5+uy$D9C zQ{>fnJPur0tCc2Zj-tr9P}LqlBbr9qwl-!F&9R6_bOM!t0}LSK9g6^hB85sJprE)^ z*TdfS-fsWFM<0LrrC0BL@T~WU6a^*$0w4esK@<=S9%>>KL10vcmg2HJx2ev;p+ z!c8Jjl(G*9s+hzeswg*+YHcWr;v|VW+v^!Dha#2x`_V<49?q9$7-ssn2Z$JLfndrpfcDBE#2$20``??LiscyGdsDV8)F^jB|;If#l-tYgz zN6wzy-MRJRi(fx}wDbHY9!nxxm|dw0?}CeC>p27uiV_qI97H@3Y0|(Lf&}))(0JS{ ziXKpnTB1gqNhvKlN{E_1C>CLk>H<+h?Ruzp1qv>wEzLVtN=4rB?(W{ztJmIt@6z=f zYYU494jnnMcwptwkt5S{Q=>_J`SOQ1*VgV_{L#}-KlI7x9-rx^6eKl~)V`{#5Cq7e z)*gI-47DhXKnxP#UBUn&z##-?HpVdXWHLce?RFat*ODurXxG)jDhaG6-b`4db7Y|% zOXYi4_tt*4I9u+HA)b4r**POP!(@eOym9L$QE3e+q7ZylSL|zmkY)Wz-kh)j2TJBwPaNpRlU{YfBu;D7t$KfU*!Pd@S3)3fd9;=3Qb|IW`_Y4)3+f2!#3 zJb3SEYZ7MBT9sAlT+Qrlq~TYvk+uPJT`?KU2+j|Oqn%!__}-7++#ALpdFBge9yryuXkeuep}ndGTSV<)E(783hR{#Z(7| z)Gi`e=D=K&0;M2G0ED6}s?sTCZIm<{9i>d|o%K_IUa$r!0USaA!O5i1#uyzDBA@^; zqEnb5l(%lJ9XfV$cc-7WrqV{Y_Q0S46bJ#32*IxeftnNulQ1aML|O!p5dcsG?m|WY z6cG>s0ED|31OS9l1W`b#fKYN64F(&H23BQlqXS7Y52BbwYt0-4Jdp?r3IZTP1Y$sp z;($>4ga=ZBrcU~(001BWNkl+S2?@$|~EgZDpl-xX>EPu_WGUO-N}{9 zH$VN{ryhTNWov!+rJsExiHk=byszDyYS=EYO`2`ek`%)~ zaaE6tY8W{8-nTmk12l)D;rhnr#VhOAuC4X@1Cdx!lTa8&r1lUisHPD+${LY?fKeQE zJDu6N+3r+#YPLHwJG;C(J<0utYd3D({BZ5|TJ7DhJsE%G?BngU*-hKUFzcqxVw@#O z;v_I3S_%Yp@U?e}2oV7Q?-CXf5DCn|1w_Rx*=S-+G}WE*s`NTjAvV>t@v)L1Y81@a z8F3yXY+J7Dy{o&oUOKSA8^aLIJk*{#MKmLrFbm$keLXAIjR^|Td#)?*gBRgOD`D|k zsX>1~iU1@-tgN11-zaqw=~P!3Do{1IHaFp0-+J@RsmC9A_(7}m^$$P1diC7K?GK)K z;J#0O>|=49b~}kO&ed5IM<7AiAq1_AcoRG-rCCVNAPAs{AOlJeVMYJ}AR=Q(5OeQ#hlBNInq(8-o;j>c!+U07MI;gs1qna|009(= z0kJ3s#3Pj<#!0BrV;8Dh=l|l^f-_28xH7)y+5c*+rwXVIkO`u&X7<1-p#~UQOGWMn zlMR~`-o@S4F%d(Ql(|il2*a4LMnpkC3@lE9C#67uh{|$IlrxM*ldWddo%EeDR8(Ws z#}ai8c#Kwt@(x7#RCVL?UvHM(S)iP zU3}--8!vCSRR0hE(Y@8^B3BbPTub2pWeGmOH7&~n@!$9TJkMLddg`2WX68(XVHlVh z21XDOMIec&*u@|gY_Yr9Bv&+>&407my%Gy*q*yj z$kvI(iqtC1EqEA&F3FaU)Fz%78rRp=pPA`OUy|nxXQX_RWzn)G}xWJdr*fB+8J zI?fq6v$+E%g%?@V$bH0ZrcT2U2un1Wa4GnJ3G@}&S07;bGL$<&kBLX-8i)h&qp(jwW%d>1Dh?1==VEzxyvs(d-K>x3@g2*{f*hf{Uv{Teqngc*2>_{c4p?g z)5XD|)3a@DN-w`Wb>QGk|Imi@>$aW0W2dpMxw3p<-@)0LDHP-YQ{&=FdF}YRvEhMY ztfW^iRaAW?aZb-o&Dz}Ni2)$PoN?|XvjjmxFrfox2Mz!cK_C*LKwx8XK!?au2&n`B zBcYNq48kamgD_Hp2m!$&Gk|d}69SzD5}rZMjj$FG*cjbvrOkS4W@bufoo0RBlXk

    WJlCl6WtYCbR4yDncJi^u?ta%h->_@vc<80VCFnHiPG{ozlBija zkIppLYu0AltLB_a@NM$O=yWdIO@h}bv{Y#2cRF$#3ju|yW=n9u-e2hOo@h)fniftCnP z%5JN5%$G^l4okXPE_z%e>x26O9MU9(NQv9Tfx?R9q7-QKLf|`{W=pk+VpVlJ!Qj9)!^o0zW0aKS3_4== z01(gtYCr=H1Szl*IA^G%SelzZG%zr}QuBrf*O5@b=o|_m^DI|N0y@Xq+T1x!0;EFc zawOSlVXg!1)M9;kYHn(NF-wwQxxQ$jvupSE^Uu4ewOo1P@dpnd`_(5ta{cC!4P{Cx zotm3?&ZkCLa3@a9Zr%A-RMq24Q}MvMC!RfXa-umk+dTK&3r5$hA74AxZFgoSXAbRu zChsi{4TM8OC6a2X)?Tis?T#@9OU3Hut=l$i+#DBTom;Sqtpy82dOw1x!%A|pCr2Y-aj>>OKTjW$~A>=j8T>2;dT6=a8CwaEm5&T~>CXK;Yp z*j_hH(~K=BK~bpUP>rtYyJXLf!M*~a(OK71vYYJ7vs?(3rKYdCiYS&Mc2)rkAOx@s znlT4<42nSlGJpkOKnuW*tz+w$9Wx>+C4tCU0T2+gWKC=koJD2OHxy`Ne38e{$QSpu zrk@`yc}r=ZKk}+Vb<|i8(lgHCfunb@4V-0x5U4oxDn3t`E}58Y9y~OaW@>!>*`sUL_77Iem9j~3VXirOa(Qa{ zj1sq(bA|wf5?lZ%j4_&f78Ao+ZnQQiP{mS6 z>dnr*yzRU#GgHlKc_Z-vf(O6=%pib$1c}6exx<9f0y82Yp|x3(c7i|wA_1aM=%jT7 z4iOm10BHxtI%1MY4p4yc(HT!A_4<*(&y$8gC13oExYBwcS*0cTsvJI z2s>@nS3QfQGGuaNJmsM#WCg4MkkJ5YK+TS&@LbLSItaQ+Ho35TWME)?Wmydmtrx-v z7S^DYzR~asL;`k>9kU}sA=ubn5ctme+CXM{?QF`a70ab!xcQ}*kNoQH->+S>`|2y- z8W*Eyp1FVD-g{rQYx}Er?inb=CC|2&k4#U$Fua-;YVF)?=^NSp=u3O&SMcPSOoi2L zJGO7!v`(t9wlu$Q@AD^*JilQ)-oCYe%Z6$cGLh2Sudnd_gHwk6dLuh=W^T{Lm#Z|z#_6#BDc9gU?L$UYi7&r955mgp&&v8V0OUPv9%^A0tAtz)b8j`tKDif zv#bZ;1VI$4YPm$jLa;GfNz_>`d;;NwA}Kr}rKh|&dPO+0YG`<{uMjCuIGuGpiNFSc z9nUpeP2cm|?Ovf!j-#rSk<|)OG7z8xFbo=i9SC3n=l~oe16lyb>;Ty~mt{E-MR6>o z$TNeeh@E6Z%)sQpH|SdojkP{y5v-(3`&!d443_D`NU_}R}~KRoE`bg5eKZJJ7uXmaIhbCb^}$?W*L)ty9i z(h#Gurg6FFoI(a9L!N~QZJ@BxYfDc^DTzP`LO^4kK#``oQl5|!fR&QQXaHbWbe5fU z2!Mo$4Cr1#B&F{IQf_i>G$O^a6nSE9;lPH?t7oU{gMFLWmW>4|0muO$uwn)V!)P5@ z1_!|SN095h*X;@+nSsdjy;x8HED;DWXG%ci+GfTO(<_)+2#CO1rFxCV(ZJVPGpLj{ zE3c110wDYm126zEG6MrJ00S}r12D34tN{_7^`X(6KftZygH>^QYCay?<_})jG-U(6 zk`B4cz)@ULR0eAVwv=bO?fOc6vf3Z@x?Z`oQF?)4qn%btfpO?0vj;$o3}68rI3X#p z86vni(#_7PTKz;{|46GP1_o9O^4SSvK#IUwB2oYd4E!emK;*3Jc!~f5beQSZO7|d! z^F~L5{kv-Q^wG!mzx+bF`=U2&J-?4__rAOCVKe{!4_sb};z&dUy)#oU^~|&%j6VDj z%q@$CX^5~mJi2-N`P<5sQlr(Hm^{7rrANEnskdIUrxd4SgPwU3^HO^XX zv=rof5|On|0h}?mS{*EuDuuXED8_LZD20R^__D8BCSoBt%X%ar?IwQUlL&;6LEwjB z==;79$n1n5uo|3^#K`PyPDDbGu?=JLR;yJk7HhTo$mm)^&shbm00|KpEPw@Y4hVo4 z9e@LLjE=!EJ3z43bbAQ^7K=rtRGwP_o?s`y5Hm7a@GN*1J;%|WT$;Njy-T*wLEAo z5h`PJH*Gn{n(bP3ps!f!Us_I@BD4UeQSn>hN37;dS-6A zaq7fEqqU-W8bot!^+>fm^5U~c#zr>mx#&V6-Wqp;=#Q*lwpBxN0#PSha?vCkfaYbXEwK z0uXGLCqfYrAR-WGoeQNDN@s|z00bmUm@?#2$~3XP1k%iElap{k7z`HIqQk|NLtD-o zUtDN=Y9R7g0h5Ca$N>VdWCq9D0i*Pt18X%PNGSk7=f)b=xnq!_UlhUzmWardv*-b3 zN#4_%fh3Z%2GNBASyHdlJMF0)vU0hwQK}+?Kqdx200)19%)kha(IGfSMsUcC&M`7_ z?m=_@^mCz`>o1Apr)O86b%}}2X_=DYkiZB?KQ1yelX0=EZCEZ3A_#V53`-F>M+kzM z0T6%@0TBV2$g(p!Lr*BeywN@47Z!Ux>Z_bPF*ECjLpOc-59>Bu_?CBFkaT+w-t|JG z@$#GBHQHbG%kio>s&sqpy$7Fu?6G4@^IHc;&MA+GZ9C77iv@DHI5#ylb9!dstR z>$ZVC7py(B|FPABRn`o~SE7{Vm}>UJuv92?y5`X*4?XyYmtT9u+ji`{cy@O7@yG5T z8?CHcGZ^?}a~>KR0}$PwL1OtQi0GWtT03K$vq%v5$~m2;JqD|FUMv;;FpQ!wjDt`q z6qbMi46s3Ph_2IVl7Mcf9r{II^$QAw1ZHQPan3kvwa%l!D-{Z9ny_JOj3DW(mA(LU zD=SNdV$^8VgRoF6RGk$73Q@uT;~1C$7@5%lFd#EJ2FL7>;1yY(I|sh!6Oq**IV50W zLtqiWfpDNK3IMC9>)GY*(xLX;zP_Sp+5W=ni&Z#aSV&n&4de9eEDE$P2WyCl&}Tr4 znw8Ve6304oo-oc#cRNSpu!y!&iigw0N%Ey4hF(~(OZAhr#_Z~~YZeyUQ8X$=e`bS5 z=9+1?ckkY(pFHUD{wm+sJ(D@QwFH;Z+=b;l)I-usl;!OFCRW0E49wi~uzu#~V^zOdiQ&ZQnRVy9dWA<5sG=wk zTM4;P=m#OVfKYhKn!J-H&0e?R`@ScKd^JKCJ9q^f$OLL&bf5qTfB_8v3zWc~;Luu4 z(COvVX*NsBmtKDum7POEvX+IA&Vdl<*a164hXRNYKsY0umBL8@l=qV5l_Qn@JkO|5 zSi9Jqt`4vI`b`foj9&VNJ;VKL4m~q<) zxOvw_yGs2s%c;Jk>+`3ZO9zv5amR&QH=n(Rxhp9R1J1g&UaxI53t92~)ls~z-R`2E ztd@h5lf9q*^0D)FU2*m~J7#954jy>sf}I=B-ZCP=EHBgt2gahH&jC5K)*551vknOb z2}$4wO6v^RrD?m{>qtqCU8Qe8NRQcBYrtv-Cj=l`0E_5|xYKSZMcrPv5LT@TJsC+w z%*MDJkR?$N1Zk33YmK($Vl~eVp|sWt;TxMV=gYOZ{{HI1(&FgITIUErA$R}?hyV=0 zmK~sDbO7v-0URR(FcKh;vDRqE%z}v6M;i+U1Wlk3tV3{!7FeK>q9^oHZ}~`b{$Qmb zTW+8*wnv47jy94FA7bb)D?56{G^>1gL0l) z1~#taaB*htNNu@!|Gh6wo$)qoeqFh569sWxEyRVG8MD-xOeaa(T5WXBd6p-wG->2n zBgtyHZd%T|y=GX9*Kgdob=x_cH*H#51;z|8Cp3T-9I`W>uaa)Pn>4a4bq)jtffp5` zC=Ah$+oe*_XqiThiTfIjt^;Fj<{SV7LinC9qzHV~=lg+FfMgM^<6LVkgi6!g7!HF# zDa8yzl0&q>4)b2x&2tb!B3YwRK5gY(B5F=Tzf^tbcGK-zs;l|>@QbDzCe`$1&42K-VQdYYu z;pE(+b`H@9*2EG)5up=?rS5b)aXirLBtGQE&ZOB%&o2lu9H}9&5piUV^}H;%i_0rV zhewO;P8%SSVleQ>9D5zJO^;%ZIfqd((87+Nz%);OB1)S z+?btRZZ+F)y<*L4FMm~`C;@d4$X>TyEJh~pA?1V_un~eJ`Dr)TIVWke-a5X1)9BK2 zi)}$bC5j?1bY6g-Cm3X|b&_`SJT-|ygkGwyB+7$x3AK%v42|fCb`Ekr&5N6hW;%5l10$ zP%e!Emw-bdeCsmfav=kD$WAdZqd_uAR-j@_2wtGPJYQO_9Sx!^NmXCp`3Nx)G6OR^ zHq4e^0S3Sc0VDvC9SiLO6uvLH)0huEURpX?hygh+m&Z=c9PJw^k{5pOhrd60yts4c z>t40zyveDVr=EFXW?|BT4uips8_wQ+(Wdp|1C7P{OV2-h^61{>g)>_>t-1Pj7q3}0 zc=F`zLw|Vo^u$!EyBjw5Uvb6m3oqQ7W?7y?ClM+dRAJ@jfB$BC{^)tz&YfG}^LD-A ztn*$qHCub&!QV|!@4NKXTQ1(cxxW&Sh0`bJ?!WiZ3-?^|+ACg{q^ak5)>=d~xmKP~ zQuLC}H~;->j_pMkU9kPUZBbZ^f>lJt?|tuwhYlZnr9*M(MKOXb?U_H zUw2ufS%2_>``H->qMMkwSWc5pRPbMW`K6a!yhjSkvh={=BTqf{^uB$E;;3}N?u%Z1 z>E+{V*9l8R?x8>2d+&X}y6m-=Y}>wdWMm9jKK;}Sk3aFu)mQ!b&Yim-dg!62o_gYn zH@yCWi*{+7M^Us`TYCJ-$6k8rg}H_Kk+HGu=Wf6FRTnGaF>@4zzAv3ljLwOrq6jf` z)-z5bl2p#wMRH5M_L1iDA>Y@T98uNtfCil_pFY|8)!mQd#KMfRh+qkfU_q=NMb1RSD}q16~Q{G(o8Q*&+Q)`jk~>e6b^W5h;23Laj6`3 zlO}>S(5}@_RVss>PFN~#s@3taC-?1r`E;ij42`bqTNPgNnhWA6(ApZ!?Ph0rsWvw= zfB4XWUbk`fmNnb9t{)w(^i@KoY`4>yn{7Vx+~LE==SJ3S*|cT*`1;Ljh9j5Sq~4pG znOJE~weot34*fDKDwR15RpeDF#o^xxKYMEs^O>?bt$IgKdB2XSE z4}}O2h*>j}fJhQ)-4tHa*|sl6qi8$@rob0M8SR_}1R+2G5CXCTc8u&0kw_2&7>zOq z*%r8R>hKdo1yhRUO9u{C$JY1!s`ZMV7Zv@W5{AegKme?aam{)?j93NTC<-Pg<`F|{ zJb^I@kE97gk3k6$ND+{fK+KRcTSXpNpN$|wn>RYiWL&WAt}GX~0meiEfdGIRnAx#m zW&j{UB0xk3(90}J@`TOvri5;@ITc4zU^(zcGGmrn)2qkJFCISr!|xv$9^P^OuAOVv zZ8>&)_POU@PSSMejvc#pt(U^2t(8aadt`a`K&8C+&TFq+Jv>IF_P%`hyZ`6*soC1- z=y<)pWKA;)+&})~-|pDCYj$cnh{|4Edi?39Z@&4~#=^2Q>Vr4_&Gwy_jf}59d~ELi z2kw64;h%e|@ehChi3@j~!@1qN_rRC_*Ein&uIoPZ(T@TmGxvH4A_8+9MOmIa`|Okd z^3VUH+ikt+&2Rkhhi~+}Fz^RGzxrSQ`fraNJL;^y?Y3J+$3_+w=6>{_KX~DV=RWnR zPj=dkpZ)ZXZm&~YX*&$17a+QFC4R$|ulv9a*IS$a=a2vM2S5BzL4JS#K%Vi+N^^MC z=v7x;{qYZc#JTJn-~94J58umRKKbcSTy@ozopyfLFMo6Aop;@M<451}mTSNM^{?M` z*DpW!`Op5@8?RPUoSvEd*DwFu<4-(3GPWv=f_A%YwcWLI*9YJK!Qr7*QYZo=rHdlp zXzq10W>2Xif^QulIKi2c>HPG;*_ngYYO&V!Cl=}GiN)i`=RDQFZqvDVYT=A?MC=GG zF%c^i#AKYv)3oRNWs?{QTIXj{JwaYbYE|eDlZzDw&T15iHjCY4s#K+g#TlI=a53;l z0@bG=mQq#9@znf25c5pz`$K*(YF#CFQLE$s%fI|+Z2X+H8%ECCdG7R?`N_%Y)nluM zSCzvcFq)>Or)$fL3v;vcbJM+U%UR8A5kxUsJGOdj-)KC(b)Y(2T&dTRm2C0UVsmDx z+nCmRKBuQqBnW(;lm|g5ONByTb)di6Ux*{6{MzKv!-tQb zK0V?AV*IznrbR+cpx(=2ZWAtg!I7#sLyK_P+?f`mY+KzV3Eq{bPWXp@-S8Ecs{U;uYvCDhezJlE|GToAvyp-n0Y#+YurnNhkpcSug;hbPj+CQ6M4!I(Ci> zdBD~P)a~|6(w+Bwii5SD7zc=!ThmRwf5Ta0_uX^+_Mbj;{)KPZ^XkjeJUMjmc(rff z>@91F^~~w1=bm^<*V`M`)h~a2ckNJrL|Yp@{|CRg`?tTp=M7h1`KC9$88rOj_PdVk zJFsWh&JVorU4#9_R=2UZy!@Nr-S?Y&9*PU26H|@1yzPef-tboz<^KIg?tkF!eS06t zlet|x*8k1tKUu9*pMU20uiSLY+u!+~58e1-l1k@VYon9`=YlYF&iu{a{Fi5+d1_#w z+SgaU@x~9GfBvq%{*iVo{lXW%_}F8Qgi(0)RabuYbD!ySTHpEZxA*OP`SYLu-1_zF zlB5g35C7rGZ{G5w%U=72&wcLG%x0jkQmqz$^{ZdqcI(Xy`0-DC^1|I0wK}~&Jp9;? ze)uED{C{u#?%7*6f9>mE`pNCzw=Um(;qI?~^{Z*(e*W{je*TMJ-|)Wozvn&gzUii~ z{^Tb=`OIfO{g$^~3*f%;?_c}PZ-29U&qeRO{<^;Y{xfIJ{OqScJ96;QyWjQhx4-or zzVxFY%JR&CVKgWi1+W9HSz<`!cUF?+g_VgD6Q@p|oS$1>Xh5NV^2`XbOaP4mTpA#Ai-ef=9q4rp6&RD9~W<3Ih`6T2^d{m$LzFE1}Y z^~AHa#ab8!VHA(A8DBd-R`{b*tJ!QcYH6yCHGozMKk%xBLbcE*jHsWQnwXf_*R3yR z^;&`4=C!4fRiaV}hsQRO7(YGLt!M4!W)Hd8?NO_vd%fJ)oJnilLCigYCf5Sw_?iu) zqpODp#}IL5X8QPvBQw(zLYPY~-nnJd+R>3}9FWP|)^vzdflM4rDVJ-9{D|r+*~rjV zN&VI#k|A*nLRh*SZlhGzOJ!=!|G7FB8LF7nA zk`h8l$pn%hL|}HEVnwG}qqQQPu38eLJOVH_6U2chlt52P0?gCQWQL6e5QIV^c}hBw zgGjSvxw$yIs#xtcauDSJAVJ^0(ak$`(3e=xTIGWZ7`5$Mktb;;gp$JVrVEYUvFbp1 zcBT)p3kH_LJ{_V~~$8AOBM{r-b5 z9MBiP=FiXHaZat)@jVp>-ogDZ9@+P-a>->E>^^_1t*!iY^V+d;u&rt1@BR9>x8M2e zojWgl&81gtS$|e*xrtdGE8Mbvb+O=Cc9T=HU;FxPr>AS1&Uw{S&mSHe-}1lz?WXy~ z`t;1?!F?}0@#sCooxE4O{x9Eo%{6a4a`f1L|EGU>&vn;-x2+< zGczCfzzt)oM_zr&#lQUJoo{^OU)=D%8%pIqDgD3w+rNGM@y9EbvJmv?Pk(Cr_U*Ud z@ssDCd+z=3f8T3gdzt5{PPcRKeGh-@J3qeolFR<_AHI-fX}K6R8!O-V#@8Qu@WC5y zc;8#Dy;dpZ0GrMBZMWTe&pr42?dSjgUGIL|x4(VM?YIBP4^(dSM?U=VYp%KWj@$42 z?LGIt_qxBl=9)Kt_y2tB=Rd#m)1Us#HE(`XnkCo1^X(|`umA3Ec3pUZV`sE^_L*nD z_aEOANdNl3{*T4!Od(P`$Br)Q@p=X>3BbYyJZ`i)_s zU-+d$sZy;*nNE9IhR0`T5SYLSw#0%!ArX^xm|AvhBVr<#roB_fPNOP&!Fu1T0t+RC zvngUX&6XUl_@S*g7Nqi+6=EpRFZhL|+tWJpeeiv;uvjmZR!eVK_(PL3op1f$JBCI# zUwFxDNQu2KJ~w&d#Q2)kaa?RQd(CF2+co9#z?QSOmCJq*`bfU?l#q~{+?Z~fb(R}BWPWaT%f{6kHVmA#d0=QDkYvzW zv_fzMz{@L#OI5$Il2$9@9u1HXK)K`0vSmkzM8XmXwgS=mfn8pi5z=L876#?e9|RX5 zga`uAGUSdkAOmC_B-W)Sw>r;_={m#60Wv%86stKvVzP?hGEgEt3og&Hwh+dX*5+L$ zP#|<$&2GDAb4wruNr3^O50W)>obGr4BgLVWxt`%-bxo=?qtSTht8s7!9joGXqUwPcqlg_N$u)F z)h1_NuJ(mF_J8T-Kd5l*^2@JWH9RIzoH%monWuk0HrhLXYyUap>td>(IdT6v8`pvh zYZ^{AdjEO*efwWNBcL?4YV7Py<2$!+y!?_~XtmCb@0b7Z$g|)7!JT1gX!}L4ec-XD zYK_*XKKr>+sZxx?GpCMy?>o0$wDa6Er;lY>_Y&3E1P%lF;zm)pKlS97zw&SAp1Vy5Vg$$b7r*?)Ew|o${d+$8@sEGxmRrC1i(lM%)m3kJ=ns#U zOVuxa@xSlifB23&es<%HA9~BRZ@T%GZ`^t3Pe1j^Phb5PZ(LlQf5&z2UbkW0SH6Ce z7y2m3Iagb%ed%Anbo}tK?|<+6tNMmzpn7RS%F`BW_1^SMZEC7kTk6iw)DXS?>cIL9 zZB1Jasbx&G1 zjk4%R>y;{^BTq@T8B(5RE7~+jnw9!e92bc^Ya|1(NsMidj#aJA1p3Rhwl+S}kms+v z|Di*B4^Hpgv*+Ah=Rf@D)2EK^-??@5>tDMkE=09@V{UHY#HlkY_0H7vlCd%>R0oGf z!nly-c`t3XdNZB&ymZlEd2svLYd5bSs+MS=>eXu#z4kFMlRmd%R$e+(@2cUQ+fOZb z28PeEP)&7gF|>pz42g^&m25((@@{tK#N^!U!UKnU)|o9^Hm_f|zFMwyTeW6AfANJU zb-FUt@9#Q)GEOWU^w{z^tHDK^42Ttknil?5i1e z%2%H6JMuwl2KGH|T@+PIr7`U~wf3=U-*C4Z_VtZeC#^1cs>GCPn>rK>0zm>Xpk_<~ zb8DP62)VE>H(4#wbJad*wR0thffWM-Fd_gj0Be&m10j+SQV1kOW={yV);X{aoO5A; z+sP8TD!CyCU80@l$By&g{0%m@I+IDw*2EY8o*|J6r7mSyQb{I@Uqp8CP}zc+E_^v6E-kw5>l zKLds@e({TsKKjUazVn^iZ@=T|XP$Ze6<6q7A3A*Kh8u2p^(B}1fAZs>{N&$nx%rxF zuKE1uJ{x*IF)z%`ef7&|b zzU^1P`sH8$^?%)e;P7vLbI+x(e(k#PO?UtHx7WY#FR#D;-QW24o9?*dC!hY*XW#hd zYbPd7U3bIvtH;-T^VVBZlLDa>vfJ){>0iHe^x)BN-Fn-W^_v}p?H0Uz@bu}a$$G1~ zv{H8(L&Jf4}SJAd|kvApTBH(cJ)_Q3}qfxPy~8{ab6=O@`Zq`?(CudF^IgoW$)~v2>KX?6ETSf~32+>`v9W9oF#!52SzfOvNXVJNw z!2kfWWI#m6AOsZw9Z=S6E&^&}P3RShg+aE;T0}r3MluWrKmrKo66aE6lte-TfpkVH z3H8R5wu?gP$QvuDfe2HZHXHR?qd8}7(^EDK(f8QdJnQBdY!Z@?=`=1DOMSB0nR7OlSP`l#D6>hGwGv*(D^`!q&^K@W^<|g7?V^h=n>ao7 z$OFIbuhwq(z?P-C=cygY+-^H(oRh?+VsgeVC&f+uqZgFP0wm5O}^iO{H!>#9R z{ipx$zr~f(OZ$)B@~s~pKRH+KA1hW@rPfYP9xoPx&wu9Ae{t1Szq<36-@Wx)H{S4} z3wG}O<}J7EJ9uE*dFMX!+;ca62-=K;g-@BjUm|LrT*y4|~XBG^-> zjyIdlYp=cb{qMiN+E@9)-~Yoy4?g_kAOBEm^M$|vq63b?z&dmN_19l^+2!SOwb$$2 zbMHMjef_IfUwzdV{_gL8ZK#@r?@$3m^LMhu-myYrp)JfBW^_ zcYWq_pS$wvKWny{Z-4hY2Zx5g@Wn5#8XfNTx?vceJaPKlw|%=_Yu<9pZN3*BJ5qc4 z>8V~SEb8h&arOA<@JKa`V&4y%^;WZ9>-F-Jr%pEN^=7MHjO6<9RqNNSE>}u}1AW!L zBF@Y$rg;|$2?>etj~o+N>pT&qJx4B&{JhaT>~NV>H7aeE7^1bHHG%a5nwgs{^~Jf) zGNTJ|MNlZ%v(5shNR9cqy&E>1b?8Vlj{1}ms#1OY`6G`%eC)h)uiCl$lBb_P{>Vc= z`^3lIaqgyJMY&^(#MW73t+8xaXbas`H@iu@lRBiR=tqUjQ(ZEy=%zB&H__9j*pMVe>f`fW#M^vLMNhWk?+Xe8|{GXWzJ18M>T2#Au1IL|vt_xPz( zFTQl*ztPoe2eRd!u zT5GIzQm8b~<1k3_lm!N1s55O1GeeeSQ5bL8viWUqeJdekdFm-81Ubi+*#a}9Qd%Vi zSjiRzD_}vGH=0w%uBd-T@< zE$cG(d7wG5GIOHdNV>Ya!aSu~H`}qFS1JfYe+0NpLLiZK!~!*Em?U1(it7hTxuyzm zsTMclyrGg4s5~Vl5LptLpLZyXgg|0GZrd=BsA441tQ&+-LSPd_>zr*NamV_o%2E`h zC%phwfJEf`70;_!i^`)$Ybi-OLV6&&y>JbKk3@h7z>JPTlL80Yn2eE)HP$g$r_iBI zNSRJj*EXs46ldp8`(DM`z}Q%zby|7KD|KPDclg+`Tgf8^+)$M5;| z)t3yNf1yP)X_ibW6uF8a<0&^XGbjGf@Bi}R(Wy^;>90pORHD{$x?;Zg>AzdQ?u^fW z<#YWT2Jg9V_m6+{%TRUa@_nk*XUMKBO+?LwkKKCfhd%h>Kiz%rkAL)|TR-^0Yp!|Q zEBjyh`q#gnB|7l)Z-2+Nw|)Gh0E$5}u#g<5?Js}%D=)uzaD04Sxm-ZZlC*vD#MD6l z(BJ&+XU~28xqtK7FF*O%)4#v#m&HQizFiOe9R}S9EKI;dB6De zFMs%>JFd9$ivRYN|KhCnrL<}Ct6%*4UBCa`+R@Q3ed&vpN;yvA$y1Zx{?51O7UsV3 z^>1Hs<(1$6=YPKEkAJ-VQ@6kKo$ubg`?0_O`)?Wp-95dxe&|D2Uvte*e)5yw-Tm9Y z`rK{Tyz81c(Vze97miPyc-vdAe(!ZR2x4o^J@?%I`#?`DbUj#>%*R$^_GK3x z8z^;}(Q?=3*Bw0#1A~`Z?$O{`V&gPh>6~N+Mn_6J0Tze>`m=iCT29zF^(IaIrkcwYJ@k3i*Py*7H1Ttz!me zA*6MdokQVRx-88Qe1U;PkA%$9&QE`O$45W*!L?(um0TB{-6|gGFL3_klru|1VZc33UK7Y z)a6?Bm8nPaxj7E>Y&{*__$JF`W1LP?trP7!nwwEPlP0TZln1^-;rrCp9ax(h;|gJy z2Ywc{0%3(~YMW$`*BmEc;eubcmCV^t{mTaRvOTP9|2NigIXZEL)@I0-n$-r_Fw+}E|>Q% zebd%L4vsy0{Pf}Z^Iw1Y?O*z2q@wSB|6iYa^5}I}eej|S-;(beI&gH~o@f5}{L>Fz zaL(CZ{lCBV^pnqi?|c9Jv5$Y`vdb<;vUlHk=P!Q#>rz;~@x~8)^tKPhu}d?O3T42r z9C+~`zWJ?YL*MZ)KPr~OR%@}MMx{fB!728V9BC-E z2HLOc=D~umV;JaOd$FIZ8pjR@2yt%u1S**sYZysLQs}_EMu4Biu9&O3tc9@Lj*e@) z%(AE2yTe1T)2sy&ig^{qt5c^>jI0|ycJk!t+V#je0eJ~IXPJc7dM;`m>gpLhd78)8 zY)Lxp)6M$N@4ip!o*S?K*yJgB?|pZ_;j-?xy=i*@hJXqF6aOb*00!3J9D-$z(m2Ud z6sTQ{V9BD*xDXZ!xgwH45rC7RO~6@e{*Y@;l+^O{{K*X$zwy`%4-Q>sp~s@Kf*A~3 zX^nK2868N?0xb#$Fkn*yjaWA=_#~>07R@i#@BZT-XQmg=IqQ;*>$b05GaM(&kL-Mnr4 z79!9NjCP(31Soch!l7UXlxE~iPOu1+$>P&->nLQ?x-*9^A$G+=#Tl=*0uCu(4Xgcw zjA4e^O0%60H|O%>hOHw;DKa(=Oc!{?PHW-BLxDe=P|`Bt@P;=z=mth|$m}ep4pYwq zn`LP`b7^W#r`4Qax1oQ2;ndRdQhlXW$`^-vyDE8Rz2JF9lAk2RHV{%Urp9G}C`Cnx zoYq;Ry`n-0{6f^WD~;9ErKxsC6JX$b#ayoJ`S~!H_q?1`AyFu0&i9H+6`O5~Qss(r zwKlW7GFR!UWEu4Jj#=ZeBSd6Ofs&I`hsQT=e&+dO|L50Fy!GuL8{4tt;L!um{_$rw zT)y_QORA?Po>h^kR{i1-lgnc|Aj7`tmH3`VU%u$=kCm0*KS3@%(cy z{@@2c8{2rsCqMOt-~3|N?%jX6>&{>F_4c&t(SiLheeD}x85{4p?uK_=@rHL43InUP z)khwE^lSg{&8x1y`tzUrY_(iU?|k>W_uaee)1SWm`s?4fG`~=9wEp&sUu5gv|Ni&iaKjBh z``N$#`nPv}{F8t4?)Tl$>?~zEdFJV7e)-FvFV3Gvt6Ub8ii2mKeaQuvy|vUcynajX zN&~0o;)U6%xl5e=yKrLK{HLJm7L2JipQpsu{B$e#Y{8(`CShR-Sf69uYc~v*+1?2 z&8PqRqH3Y(+mzTa0{|l;0Wz{>_B@p<7J_`vAsDtm6m=4b)xw1adF_ROXh)u@mxji@l(HF%MQZbU^)1cHTSG6JN_*kuMdMeIyWytHk{+R0PL`}zibRj94h z>Px5dejIr9&`YZMT&Jl`ri2id6Khihk!B)GAFYn)b^r`>2`RYxtKc|0r`o!YIq6)Y?qDr|g-<4R1pxRweOUo@c zw|LydwGI7i`ifN)0`sbY=IC^^|JAm1W3M~w0uA1?&po(ygg1@%`Uu6)^F3@dR)r!) z2WYBY-u&!B(pH5+F<Y2 zjT^N!LJ0Ocj-lCX38hw6R!2rggCJ+EZPaR#M0a<$6tuXoz%0R*8C6(9_OgZ5`CQST zo<4Q@E zYxN^Ny|SH%e16ndej3-4cC8cFd|&jh8Jw6rRjCdjm3-BupzJb_0Du}RE3cM{E#b+< zI#w$qii!tLuH605-m!tREgnl|o^sA1338+y~?TU3ZB0~bfk=8n22!Q?NMZNFksVAR!acO0_ zn3sR|g->kXx()%1F#sThU}i*QW+8+zhM56C2thz#0SquXlm;*ZVrF;yXFhYo`#-RD zY#mA^q_oaD2g((d%URcAYzUbMsh!g{ZPk`08!IQf@_L|>gCsF+x3sEVd92jGrCb{E z124*INfy`Jjj$-%Q5^UqrP63@5=Nsuk=P6c<+btZi?!2F6^reKR#fQQS{}T>aFv~4 zOYDSWZP5^T!byQniOlnp{Rf^tW5@cbsZ(p$Zb>?rB`#^LtSlXl;}e_4%A7TA$FT{N z^hh`&Cx!B4(Hii4Fs|viNdlu*Cdm?~&KPS2g7Q@0d!h6d5jh7$vJ+*5zO$qqXf%oG zSk4?}f$sszh1pev5FiZvA`wXs3MFr0VRHM$@A$*Rv-duF@`|fI&^5B|nP(r*7IuI5 zx@{ZAhw2Np#&o;cu6JZJAE<#!SEXA9-T780@AZve!R3<^wS6x=dC>&}Th{mXmCLMKN@*m!T3=Y_lAp$1VbA*h$}mT4N3w-&lg#i z`d)!;QJdV#O7`Hxj~qI<|I1&zeapsmN=g8**0$U2QmMqu0Fb6>mSu=YM9f?&mOukI zNNj9f66ORT8tXp&*I&5l<`0jLZ*d5Yt>sKffi@sZO16oX*e>a0F={Nw?PZ&_av}Bg zl;d_bd#X__t*iEJu*E)A>W>qVWr>j53vp>>7KGN?eM zx9d5-=uFN9T^&`9ME~#ad%4jnTzbh{=T1eBK77yHuikpjj_&_$K73ham;?cBK@+&uB4;cwWUOx zfsh<0%S=(4#geL};*hnB0*Oc|m8OZ#QUHg{LLfLM0Xj3*TIGAb?*l-VWjW}ukP9m- zg|40`&N|wZyZcE>V;ur8v!|pr#&n{BGhL*tXHZku=Jl zdi<&B=@UUdz2eFX&NyR3Ayi~jo5YGFNk7fl5AvDrNNfkZoUR^hFTCPQ*MhahHE&e; z9^)JU0SY{N@`1RMDpm5mE~)ZJ3Irh`IAJmfWRNCpDcezdGM~>fYZg~pecipqFl@J4 z=08DL=%S#=7$D`1ra%?I0HM~|%xZ07bf7XZb$VcY2b+*wY0s;34?KBr+xoM2Zrkzb zlgA!?{112Baf`>xc`T4a00+Rxj0k{C2$@dfxRYeDvsS)F3C$gph5?MhAm|SKKDI>x zzGUY?L-E4O%wFzHmV#t*c6P(X?>sim14HLC7A!G~j)Rz-B2r5ZQs;*S4spHb7WeZ6XKla$}B<)=Lj%x@du=>njfBD7_d}!_34GtWDcAN-l zfgN&+u%bIBljbC(OTuOXOra1qqqdhXv*_+*)voH9GVJTPR0e_3k_eGBK)kX#?H~o9 zVqp-eh(I9NaSDk9Yoj z=Z@mr-+I1hQ*t%rTBcKL$@B7{wBbc(sUWuq%sZE|Q`UJxq2+{x)7p8mlw}!W1{k#( z3qu1VosI?%VxvRV%Pg&_6S61#EQ`{to-bjVB|6ImeveX~F&QEOg0+U(5imPP2t=5s ziSj%_D1>nAk|YsAl&nduORW<@uF*-VeFNYH*0Es@b2+266e8(Fijy##)meLK6&E{h zInz(>S#+Z+7~*4I9gEeamI}d?<))mP&RWNn+{PLyOiT~UvHXRxwq9Zo}V|`3PJ%+P&z+~drC#cw}6l@71D&_T|T zbE3o05sp|3Hd2sMzOo>b6t#9OKa^x8q#h(bW)f1cvB^?I3c{jx(xE>!z3|{ek6izb z>vo*6-C1}4{r5lg&_jFo?tSEuM||IR&VBW(Urp0=^XARg+H0@9wtt{M>U8eD=kDL% z`MdS&#=rH=Z!776rO$r)zkc9-A6z#!4yc7l5MzeO+D4Wxw;NMgv=DHopwM&D8WWq$ zNa3?!Ia}qH5P>c2%1yfeGUB z;^Oloqt%J&m4SiHq2J4v2&_P6eAhv$(Ws4JsKR3Fj=JL!pJwg0iL=|M9Qu zUU}z5Z+P?EYP4(DZ{Ku&v|~KJ_nue(?u$QKS%|;$Pd}&*4czvBz30@?N1uQ4x9`5@ zQr4!sQW4aiIQqiI@nM2OZ6$1_<*;{i&E)>$-X}WHd(}JNzgllU_sj#rox0`yZ}Dy0 zr+TSqmGqXE+aUa0(Gy;y)zrE*EGdvO0T$MJAlPxDZQ^->NhKm7#L~<10p!BM@^TZD z>||CzNstfFvL+2x=vZ6VE>{(UZ8ZeA0w7su02zUi1R(%0u#-YqXPwoE0L%)?rg;IHGbw&A}ANW#`P7?wEX9agedU|zfN|lEq9{%%R7EjE=>n?iB z@W@ykMX&6AuD*2qg7f-zZ0{=XkLb7V=QxMG+eCWuY zU~oHyC17BZjsage@E~G43<|~;3WYuf-vSFk0I0R|&_ggnbh31=*`CaoRJl@4I?3Yf zQg3ybFwamVRk09cEUaVCLvS&2oTV$R*3{aO!I|T$rRo|i_LxiwC_eSd)WgrbeAd>@ zXPt4@gAeb2X3t}HeE&8dBVhw%0ssaEU;qYW00+Rp4uOFkFe5l2Ql$1`?S%9pPD~*j zF8k}rC=YbfIli*=BAWSP4x1}YR>kqNFW!Hwv1aTd>jIX}V#FLt7HkNNB$C3D%re!| zT3+>)LLzHDm-?hVNWmo%nAxEshu}b*o?U$Cp~tU(=li#A-UbZ+`mg`mY&Li8+V$Xr z4@xN;jmB5M`qlpa{*4A|H+TN#=#gWgm-~mWf72%k20rttzrFbb zH*VdymPEo_x2E2T=30%@Hd_{)6nsyyNLre8;D;rV3vDPePqffaRh8vHnC}VE`iMGl zfgk837NXN?%^ITxhLzF)iF}rlABLH3q7(=eWGn5{FWC0cYBiXc$<}PW5=vtk`Tz!< z0v9+kEHay7sPYJjF?C~?+R3t)^IC1_?%rZei6BSNAzV6n^0Cd^#$R}Kc699QK=lZe z$d=F%BN!>^HSHvwt2d74^0M7X!=P7U7hxbtyhce9!V#J@ZLF>?byq8ki%Y#d16n)Q z3Ax4Pg=12PVzJ!aJ8ZH2uW8eJMzuoi6zxl%8+O7ya8x^$*mB5*26$f1xS zI%=jJDeMNePRN>d4mdz$2Pu#xl4t{FP*Pjh5R?Ue*oiEQ&~N~@04#_)2$q--t#NHH zFeD(3JSnQyf{jU2Fbu6JAptvMY{p=uU{4W~ z6D9?#!5VNHoh8UZKaF*}4eEt`cGrV&&PCU5+Bw#2>AibiY^+XPaNh8?&80wf3ZdVQ z+S2#Ir2=9}8KJen+L7{0Y3hnWj?%V>mPNX%K)1PQi=!+v4Nr9m4)U&Wus!xM784gBmhj>K}w_cd{7kaI2N)T zglmwy2y^ISfTfw~XV-6D^ZY9_!=q<~vPY64as-YT!6|_#MY6bj)c4!@yfPZBlg0_> z&{?+DI%}QHm@@*Kq;YRgZ==@g?j8{2DZVVKV{ZCL}FRJTx? zMsu;+Q%rg77yjG*7ro(zv(7%}(9y}4_C9>Y>l)*IwO#ig`|tn#{~SFq{f%$`Q}>#o zzy0EEb0?p9<%K)1xOluPRAoQRqLwvrsT@Rc)@q1M2dz}JA^+k;ZDOIi?Ywub-?sLF zhaP%m&%K_(y*E(YBO8=0&fK!!R6lPW@A2_WoPSZtfcrhoUY zqx~b-yzZj6_(gpDsXdb?4qSH0=GUJ)s-Wcw!`3njl0LE)5DQ8PwFTCUnZYE({UU+!sG*(Q0siyz|}{p4I$6HlSLqo?uLndo<%;#R-pE!owPTwKFV9dE zoU7!DzK~9{CjzSt+gcpYSOZd&i^XoloO4AaWw=Qs!EynX>Zcy(&WY~s%E6O%!_KR9 z(3=SWOu&-UzP5>lrXN_RJ35KeB#v4ugCm2hjb^oX%u@r-mVkY9De%h5(ksKGz59`zl@T9ZW_k+cS z6$H;{WEKMbFevHFIZKFsx!mI%NU0c%gUq-n%!`@XljU-Lc2)g9-+J)PZ+qX4v$nqc z^1(v~o_Naz*(GNe{@1@fGB*B(58m|g$>|vmJanDAfAxdm!T7RE*0}a^Q7Q?_X=_P4 z1U5>^pwUjWDoodd-`&65JNDKKF28i&%g6RT^Vn5aY`E%*zE1rJXC2ldQGsQ~$}X?e z`uorDaTBBKm|5pQP{H#QkY<-TMs%SdG^S;3z1f(rl*(xWg=()u4_pzM2qOdwfWW5F znj?`qHUhf?zh4Mt!7^LRmYoA+Kp=b#v(tqzV3#55i6e){$3|ynPH)<@aaoR-EFu>N zn0T)3;uRaOuFRk0G|EXT6>v5b zfCMw(iOH90tNV-j0zglxxW+-KoddEARtmw!5t=kzZMUa$q0Ou-R|W{+^r^`;Ln9>p zy)PWR^onbiSK~BuLExFJ<$GCed9t@B-)J{HtaOK)o2khHlWG^po~QTC?%wn2&h6tn zwrqaj!2>TnzvqYFyG?RUfIvn@U<8K@zyQDiz)XMuK;Qs?n8*d}fUyl&t2K@*iaZy& zxaE>gZ?(F(*l4F>XzWau-L+P8c-TLBY-)7vrG|4(pv8!}0~Uy-BE`UlW6QwgqYx2w zvGLJLatUw~p(!{eAT}vd!jK`s!d&aoho67%4Y#fv-{^Us)_P%K;nrJkz4zXGgCIC{ z>eSJrN4IX>Iy5x&#V>xbQmK65OP^y2ioCmizw7xud%yX$ZwSFe?azPa#w#z|-c>P` zB9)5;XKb?;bsAJIjtmTss(eX9=tMqsLC0j8I<3xv42^S~%XNb;vhjn!BSLVj(09gJ zy%?vn)}SZ53dJtRK4R4ZIcy^lSt`JMZR!z-r%J`*iMeoW+go+6TMJ-}zzCNH+9n!S zg~;VX|I z)R{$yj~v@OzM*GfVRoQ@jgX#YXN}cHXIZLsYEA4oah&?T=lfooXhA-a$3Ue@CCRk2 z(mC1PHK+|Gu~AZyL=;w=NJx9)XLIS zPwkm};iZ|m+2!*uy>vNhoji7UthadfIei;9=W?Q%L*@jhre=atF<&g|SSw_0VyC=B z4E@tjUiG`Kyz;8+8mqi#_g~`r-kaVx;^X{awOhKfR3(v1WXQ7%t!me1&IUDDE$R+P zh@$67Bm-=iQHde}8q+dnrM5cVRqoOn3)Oz@Ja9#1B5WfV0tB>;)*Mi5jaH&B7Y-6h z%Pw=NF*?(kV~4%!*I)RCvo2h}T5msa|5L?+z3JvRluNNE z4eC-9fm9$QIpYL^LKXnX#Hbvo)H0A!*i^ibtnSb1hZS@Z94qu+tb(coL?M|GkDYkF z)i_kj7m<4kr8SO2;~b-LV3d+3%cO8gveKxZs+3h`yzcIGI*X++hY!Ad{)HDDIx-== zQmJbwin4qz4>k=wdwS~7&_MUelha!_p9gWJ5g z554m8-e-RJ{ST8}^*IC<4B!YDfdLo*m;nG0i5Y;AfqCv^9YFBUqEp{Bl$beP|AO@p3cECu zGd^0$+_rWZc$F~q$#*s*p$RfVT9{29eR%JC-+S};*gDViTCLW~%F0JS`q5pxb_GFj z=+L3>eCInmckW!je*HiG<3IlNr$1e{epE>^7U8r!3IG5g07*naRPMg>{uiIy`>k(& z1BB&l@pFIk{;S`1?z*+r&{s<{wc2Vj*uP4;)95_Q3XwzL|@C-ZruBUqTO3Ca!h4~O}p^zzzz2zf$ZqSncBt98O* zW?Yaj4C%}xl0rB^j)Wl05qW`!lcx`iukSl}@Zdn-sORO`5db0r03%rhjigsr=Yl|K zlL=DHl38>*QMo%}0*s@O&jCBRM2<_{ggpH*eVW;463CH}$S} z-#pM)c=XW+`zrRmZ>$biYNzHq#p=2z9)CImS2ywNwx8V{6q?aO@31$}tvOz9F1Kb* zFRt5qW}Mi`iK)JFuB#*x8%I$6*)M0J#JAo$4?5rfn}y z8G}{71g(}=E^P_DwcrOX$C)LzJ|H{J5Un7=#<#{GCTY4L6%jBG9X~8ODybT3~mvFv3iX4n0bAnq`@Dh7brDz!q|z04G@IeR+E7c%_(2;#N<0 zx6Jo}OWU>irRif)Z7%O~S1DI4=A$HCsI}S&SNcYJhsG!voLngU_)&zKIcE-y z$=}~~SG(SP%Nt+6d1FPYIy()nD@$d*Qj9z8LJ$Z91t1u~31;7s$I=tzvUpyY+0M#K zwsoZ7b7V*JeV6*hJ_Z6300Ji__e8B@g|G;&yHH%?I5f^OS;yM*MG|#<57V?>TRl;& z=IV7SmDiW@p>vH!Yep!WFO`l=OpdSH#?Awlo)Ci5#o5We?ye)prnYUpfTN;TS>!D+ zf=2_7y|A+T=@Vyf-?(k##s?qTx9_DV{^f_a2)*pP5SbXkAuxhNa0qA-01y!X2!H?q zmO1WCTOre*;;u)*p-mv+;lQH^!j|yCM;K5B761d3+HYcIC1p!=;#}?D>^}z zI*wzu4h*7W2BR@HY#j|n9d%3=*4%v>-ufm z&mbZIsMTtB-g)OoKlafq&5-ES)YNZ&^P76Te&dZd?%cVP$N^h$bZGza*{QiVzUd0U z4E)yTK6TwY-hNR&kF8p#x3X!&*m=SqSg~n4bU-dkQZlj_6s40{+yaOijp-nV#$s33 zTDIMUg$xo0sT7D-B4Z~$t?jIH!dKm4F|V!g{DDs9Kt+T^h68h|IsK?I^Cn}FdtJW& zyfo-C!Xd`wJTe79%c8Zoc(7UyYD@7@-#U*9Nt_8^T5>>=QL?pGx6))m;tEM;MJ3D) zq_Ge}l5{8>5jpEgk<%tRdTjst%>$=Sof;e6lJ~nf6YS72J7*aTL&lJ<*5*B5bvo@* zsVXUOmR44l#y51odU)@;bz94Yp{PZTdgghhe7@-UUOQ@7mjSvHCy$+R#+Lti$FC2c zQg46fd#Yu*>rcPmwy|={HEZ)cIXPDgO8t#Sv(!_G$tV|KOSMxkDCH}~Rbgh9XJ^xl zww`mz@nZ|phK>2@xPF@a#OoShVg#2Dq(GaKkVehbrMb|T`B253 zj_T<8%6t~r3n5iXf$vKTJT~;-BQKwI_U7Z0rz(}2#vSf&QMuN2b>dZdF`HUpMTW zAA0PnkL_K3Tcut0I6xK*$Ow$U01Uv)0DwpcjDQHQ zLB|eJT0;aBp!RU#;ehyZ{AtTF7IuVj{Hfv22v=qw2UkZcG^z-!QgYyS1^H(vIJb4N#q$3{06g8n4( zEELkvi#+W}D+cKZGgM3xv#34WiWUn6-&k3xtg$xF5E`@^QePohN6b+)W9%|J>8VPt zSTrn^-xsHbWeNafte>5XrXTlsCF*dg?@h9@)B1Tsh9LtMXeFT~N*3l14-S-1PRwsy zcP6uN&Z0eBZm*}JbU}s|M91*$>5u>dPi4@{&3eXw`?fg^3F3V{$eL>uhd(W za{t20N_D8Gv6_V3?YO_4aHU-D@9vyD@v7FaZu5EjUY;5s*%k_6bfcpi3+?RK>D)aJ z9NfNR`}Oa<`hmOl?0x3{z3v@yq&pg{R10B$oMakL=gW?D{?v3Q&5BNx!eV!js}%AT z$r{b5m1TWv z0QNu$zt^d9PfUfn^*d1NIDcj#yXW^Wtsgt{s%y`lot=8-iD#nL^!3+Ykn^=*Hi-`N zq4W(4Xhl#Ay9z!YgmR z^}-ka+0P_6(h!g!AOZpdhzQ8{0DvH%fFOVX5J&)^Jl0yFuG#pV^^1QU>46}Wer{p^ z!&bEmu1!>*zxevCM;A}MeP-{$I~+7B4j42GFoOsHpab$k4h>TzsJgjfu|TB?D$<$t zL+f((K8ZtbOXteKsI}GA=bwJ@$A0)TH|)O^lmY|?P=jYc1QhTDphXmbVuAN~FGh=q zcixylm;nJ1KmWPU{?t$Z9?#JjMO zPLVcVNK{-{8;1f=5*OKc%h#DvVOesc*#(LiBBdiCa3WfZ8DA)_y%f=CkU@L?`>A;o z2ISERppX-)6oWy(wSFdT!g%Ogtr^f#yHb?oxveV!aY-yeSS1mpQPS^?1S3>|(nyHR z;4QObBz8V8s+~A7N!;GrD8RQ+MJg~#8?6GA0D+JkQnkK*esN*<##%l*ebDHJ=W=7~ zLaPh?;m*wDVWbIyw5Tm;r;IpX1ttO@TiNBSmzH+T{EIJq(dlCkJoE$LizlA=;s@^A z^Pzi|iouy?Bj2?!Yx8D*kgHga#+9>?qPeobIO$E#))y|Gn3|kyxAvTQXLWk!08orU zlsTWX8Q0Nczw>X89lGaJAN%;T&zyVbJ750HPw$&=^AfF%|AX_3!PlR9a&_h0J$E0v=k7zmg?Ouo5CPB$0*E41 zhIAuph8Tkd6hJ~IVMO*eLRvP-a@Y?^odjvqDtPGG4s+;&5Sa%LBT5*C!8-@BeP#!(ckt!7hGb4shq zN>x?;e0gzc`qH~wyO)j{l>mD}k4jY#fBA(A$4{((=(c-r*t_@1mtTMJdWeeXrGuwMw%Qifh!)mp(%R5CU&R6p=+;F!yF>7S~pbMluf^2xNJ&k)&og%)6bv zT6L6ZTIWD{9U>yLun3fSRpdFMeBt;0a$@1ZJMVfVAN8Mo=HGwl{=LTzwVTPfzx|zq zduOXWX*8xh@%7F1yn>1LzR{rSbX^n=FJ5|c&+dKbJ1Z-rq&debt{^b!WbVSvUj48C z^`G8$^u9+QdF0vW&%O1=<3Il+2lh^uO6DCKYo8;YK0!eApnR72ofrK50Xe4HX~@FSIC0I zLhK2|*$^>sy?pcSeEY3t;)gKb-1VReCxsQEagOoLH@|G%^33$a#(LIl%y}Ovm58A8 z6_NLxhk-boJDa!Lt=@1Pq%8y#4+^8a=mpVEr_;WCVY}U)GJz>8uC2u&n_ry1bY{EV z*o6=pr9f)W;C1t>FI{=_LjIxK?me_;-;*!D_S852><|Cf&qgq?mBqgS--Q4IfB*u3 z00Mvj0)W7T1eOXSPX(kh9qT9};)jAd`V z^(ca9U4Rm$<$7FRN~8MHwVlNypN8a+hf*0WVoE#C>OR!Ycpn6#F!sX%E8QTi9kK{k z6^Rd{P{)xE!*XkDd8#ve?aF9r>HUB)kVW(&!ptJJvO7qlaj_C5RE#RZCio^OF|ikP zAc!0wAd)4M3-mkfiM7>CL5n>pU1(z)aW@-!q}V$`j6?`Y39|JikWbP$%PVIwirfF_ zfB2X0d+_J)y6gMame*f={x5F7t^J|*9SW#dm*=9eE^|FKvjj##h}SpQi4$A6#rdX* z#`(D4Y0vnoy|O$KO27oUV+=bgoV&gOfAq(Hb>#4o2Oj*$w_ZAR>crQ6`iJ%(UcgR7 zd5(aQ!aPxx&vVDxhuyl&IJ+)>;G`Cb07Il2utowxWh+or$FU2;XwWNBwLKt9uhG;b z(P-ceHc&ao{j{kab2b)`rZzDMdFKEHkr5dX5EXy|ArbTfp6l7!$+F7({Y|B*J$0FB-g@Whr{7puJbLf@@7);=PrmumnRj0K*`ND?efuWs zYJg-37z9OxMUYS_(gfgL8Z=^TXfenD=tVIjuy-L~;ClJS+r{>&X6pOA(A@Qq3MWN0 zf$^U4%-O$EdVQkXUf<{irsG_oRP4M5WI!f#S_4WA;?tzjALoo30N9D4Sg=Ien46hj zT^R;JDu~u1vjnM4o59YyH8fF|&`cX;F=j!pTVHC6YY?MY^hxpidAe0!8u=5HHL|p$f7Dej7w5_#)JuTk!4$*R%D1#`0UwtKmQLt z-)eUd0TqgPWyrG^V8oKZff!_sfZmUH2A6`sco#Gq^MP)&Faxr*2#s*2R3UzljW>l$ zVFm%ELk98;ObCb!Oz6VmTGKBlk-f4ynA-QK#QVqjz_W9XgqRE~Mk$MC)9S!hMNm}A zu?XoXZbm^@Q;Lk>PyEb%_kHC2sjIKN_~%Css!u#}Uo~Ezopx*M7ovDV>E^KX&Bp$1SO5XDiJ53XIi zxNrYbufH)fGga0H02L5{a)Rv9cnR|o!?=}KymD>)_*ae#1n>Xgebe*ZZ@u#J%db59 z$RqdOdDjhyIbrR&B0>-p01*L1Bq0*G z+PJK^v~TbJYghVO$DRQoWI)iFb>mPs4Yfu?w>Y=Z+ul|>EFpg4rOR(!%)jrR58kl% z;FB-C{4B zatLwce3kECI{emKmvh%Pc&|N&;sasDC5hEa zimD8vhQrWd=p?#uWqE6Rt;l!mXglDniIu8{)o9DtRhl%yw3~6THRcl1u~paB%lE_!+vNun@xH#WAc4S`?nd!-i+itr(&+{lsjL~^fkR}8pfQTiaB~c)R;JqJh?wo5h zqpF07?k>WV#R;JJhSs68Bc&|cEF1423!#almN89KF|+b4mc4_a$eP_eX~q}Bz-?x% zx_7x?F^o+Vgovi7Ys-}e)a(P3*^v1?` z>A>BV$#W^A{|8?=dG^|UANlB!Blo=d z(&_VOzVW_0+DG^8N({AIc6III)b#G&5L?|n+v6QiBjhYGPN27I*Ca7kx!zoXB$=(9 zP~?NAT;J&nPK)37*cblthMR8s;KLt&@!MzLKKay7{@{T<(>_6|swhgQ2rH>abyhZ7 zGeLKkwK^seuDsMB0f-hV1q$!$(1au^%eL}tEea#{L8CnnT4%*-Ui65=G@foIGoJHN zw(6yDp0#ebn)4#YIWOc81wattJ%|cLiJ-8c5&*llc6nm5G0u0!_1J;K^Ovq&c=q@=!&pA^*`Kg(fLJ10W{2+~C5R%z z00N$XL*y8vhHgbFL-)~RMHeVA|Ten5p2APP}?=kc90e=!tGc2J}p$F00cy@tSz{1Q5v}XolFoGbiw%`e+B5&>Z~mfk zn@RzKAR>H^0DuT0!rz9>B!E^5B2txZKsH?cRvheDpO-K&QK$lLdT z3Bt79(g0a+D~hT-A53)j0d}-Wgp6}&OxKnQz!_6`zcJ`7H`C^5EbXZq7$Z~`QG`Vp znHi~K9A3YEX7B!`^JlN@-+QaLHbRU-0v-_%6$r58o(C&y@5FK1PUn)S11P=WMIBV5 zzRXSU7S5swytUwUU7`16qR^wyZM`)polk$~3x9g(rd#j(=mW&fm;U-ypP&BZqx%xX znThGa;A-XaU3-t7I=yx1@P~$F#;PA;7OH$>{?5d|`J-nK9=-R&AN|;K$KO5k_Ba0iPaa#Er~|2s%BY}&n1dVp$~D`wy0cW< zAjHVI()kkD5E?QyDNE?zBNpnaZ|kijj*9|XojFl7&adTpk2p-@=}vRrb1@h%lXfg% zZO}-jJ)0nmYv%v~;d>BC6o?WJ01}02FxrSCxW0aQeqplL+iFA~CS6ikp%zB4LY@^s zynH49>#v{O*%{t^^U<4cI<&UFef*_oS2r$v=CeN&MUtdo>oF1oiU1-J12KpP1{4LN z#f2C)bvscB3bR-t1_E{*A_cZzZl2D!-fkt_$C-4`2UOSwp|+YYchk#UVg>{^Ic)ZaBDnWjsBz+t!RK1<)q4 z6l4lBB7EoV%ZCr%eD%`RJ$nuo5dQTWE6==g`GMQ--Mg^+D=)lq_T4xBkKg!3s(T~` zQNj0!0Dy=95yF2)1O&ljt>04xf$MEv_-1IfP}O5Mxv>9X4yS67K-sgWU%BPjo|A8% zSvqukjT1RHEkrD&$Q!5)mYOpoj*txkB6>zdW+|O3J^LVt1CuzX8H^wTf+!Yp-i=cl z=Q~%&z4cggOpfbJgVfIT28B*1yR-Yk)}mF-LV~re@YjFi&maBRr;Z(+ee#LFYNhVs z2k%^*>llTut|vMZd0si^!zl3#%$h|3RRk4@0ssVOU4L`?-N~u;U{K7??DsB2Vi6J- z#bKk&cC_KzjY&{{!Wf~l2n+)3 zMTAYrUiz1>oIG;l!FNudKXl*@v2DTzGckJ+CenxqQZZ)3(RHOvBbp+NJlp>0LZgLi zYx&arLFOurwW|w-$~zR%Oa^sWi$3wz`Ty|MXQO!L{SQC1@5tUu=hmNn{JFV_tsnWp zgA-{IU@$JWuWwzy@#cHaUo5-b+iLHlv&%FKA=YIaS*>Yk>+RM9_k{U_s!OQW|tN-WZKmlPF?uy4@wqZk#Q%=eG#BIZ5y5~L&y26NPyz_W%<=MgZW?)QS zxXGy{kwBTyc|jx~Bp^g0Fa!obiLitR1)2Z=AOJ~3K~$he6c9ln@5fhHUfs8U-`Yw! zJH4AI0Ek&MsFG=ia7UoNd|_+X{DEv(Ois^L7(f24^T$stKXm7Pdlr@+KmOX;vnL+= z^`8x7$P9>t-v#nFhzR~Oi0HtfVQ<;kH1>TNow$1GThp`6QQb+W?o225)eH)&3ujN< zd~DY{@1CDnJj%gz3GIqQ0Zrhvlv>6b@<6;%ViXa9Ez$Z>%_E0}5F#cZ%`}?V&_V{} zT+tY50Dfch+Uuk3t6HhOdk$5F9}TNszi70lW)}8Rm{OE@ZLCNw*c)~J%YXEzpZdX{ zIC^CI__I$c96WgcExQ*dk|-b%6l4YgLL>$fKoJ2fkSu!544MeASXq6i-Dx?i+s)mI zTAn?k5F-0pVTGz@pKbT9$DyvP+Jw>e&bG6z(Q33NTY=GH>tbiyZC&c>GOH|f7vsgF z1vZTY0V?na6qHs1L%r>*X~O;9_SEDd(j6TnMOmW?m_tp8NFD@vmR&50b?_3$lWF4+ zb0A;=m>Jli_b!Z3nd;0tuN=H#&)RBlasCK!$FmV+0fzuc8UTeYONms1=sNJ9gX6!%^|(HCD_dG(dQ{M;|zKGzx06^a3359^c7!w#8jkmg;U^rgi?yW5?EnL44F78?? zUG0@}sIsaiHT^sP`&ULIx&4k??!EWct*zD9UVHi7GvE2CAN$1N0}DX}#)y~FyV`kM z)!wt9(v@?itA#`vB9efNViRH7Flnf@hq`uU?R~4!#G+2H%+^j1R^RBha0jLvd*6?y z!%T$6IghK?UmEo{MZ~dcHYSN;P@!jJ&w%hA0*$DV4Wbed0gu3lKthg(*H&KLvuDrF zrp(RmB^3%Mo(XjYs)u@O`O1aa>4V$r+4RI*5H@mezW(av=ij*e(4F_~nO}PR_-kk1 zJ@MGD{X&R+009vAPl*Wprvw0qyfA3?PQp4#c#PS}OXr`Ro^K4QRx)vWV{)Gr(&#Rp zJ8|sBg|infOf4RDW-6Cv?L(k|&;?irlq;WuFG)BsT5EDu+ejrd9stFjY%@?v*$LLT62pxwk8(~C#;kw@ZdbufW9}L_=msx zXP^ARpFDDS;`nplFxY$G{#*7gPKHVlfq(!=fEW=31%$zCU29?l%?{Z4+KvXJl}59{ zE^5Y00I72fXyaJCWD2XI9OU^48fgTO?AQQC;} zrFVortx6WGd&74d9qtd^M0ZbU+Tuh&h&YV(c5f`y-rV-T_xpc7HMj4`EjJ&#<=`mG z-gx!I$rs-|vb6iZ`0V?#(MzH7WnC|CUOIZ)ZC6*zBsnB@AqbN=E;VG;Xw6nTVOW@G z9LMI|nXTQ6?=!F)lwv)~?0QxY2Lt_u$Nv1tO%FWy$PYjF!dqwGdHNTA;^@9vXNz7@ z1yN&0smhjpV)AWNWdsH4^cTqfQSHuqCk|ZEdoT5$+DfaValpM9B$9d zO}Rl!nKY|h+Md9ub#-<0zy0=~Xtn#E``&-=`wwrdt$gF_&t2a*{qgU=``+7+BpOIr zBnEWC-U|bw7c47R*cudo0c*>wER!IPs1Z`4St$T*z=VnkiIg9gRQ7!TV!3m=mGTZx zr@J3e;RG`x81Fr9Y`r-iY?gU$f~KN0j62L)PzeAFyoW#mC=`W2NM5iOumqw}c^+N9 z_U+xfm$o-}VPU_b$ot57rHlnV$jd8R>#OrKhqpJ%-3$AjqY{Fzzjo=l*DpSF=e>L8 z7au?V+S#)wAN#dm46)DTMLhfs{2pe8zYRf@6Tv|FS|XdKoKb%A;`yhi=NtVpiMqEo zCJ$Iv0r^W8zH|7<)Ws_or#pW0>m4wwNbTns=BCM0qC>> zL!!V&;@SaXIT);6&bF3gWhdG(DH)9O!I;}qyHz^Zp4wM%QbU9~b^>0U=NiEw`C-xe z<^T4NKJi08cJzj+7oK~{;NXG#Z{52%87S5WN*O@%EM5eW5H%r*WOX${P*D&eKvnH* z?OaM5iB_#fx`@!Q)_N&C_XhnH7E8oYY~m!2!nCeA%k1W6Uznz*rza*S5LwEB>n{(k zo}OWv9KDRFjOZywk?i4irX4JLauk z|J|ucQ)WdrF2kTvTUS?wb6!}3gd_nWgdtXTI5Rub+pJpY62T-HvMQ_H*tr_PC>?~_ zkODvlY>1n}8n7DX=S`CJ2Da7O9h%7~Y&nL?7Rr!Nw6;-x=}XUKMRdnq_Z~jF3rzX^ zbI-he;?-mOZv5F#{|Hy7g5Z3S55uIdLY^xc`H7-i}NV=-k`uqyD94YPNT- zwYs$q7&y%b-O1)XLJd*1S0j(rU;zL8pa0&08*lsA5B=CP&wl6hTTgxB;i+T$<7Plv zu7hMc2p}KrU?rXDJyuUT2ni9O0&)ZqfOe8Q&YUgS`c~Sp^1jP=lbx9J}b)mEusH%G0YBh!% z4loVV$$n9+Zd8Br#n;l--uJ!#_M30Jac5`aThG6^xv_f3opZO{I+Kt!PzzWQhroy+ zgkDf76Gm~(ZjcQtUj!iqaTJBka!|Wm3V0zlaKw{F9tYZv;qPG{}Cemodi$-9D5ZiUqj@YDd#FbdGY)=r|08dkp!Ka8xsed zm{7yz3vV4dG<9Y9+RW0?8rqqSYYveDM6b{(tc6SV4uI)<9Cg{Vt4ePRgHIYh5ehGpaP|M>Sm z`GbG&#=|qmpZ&Uq!GrhTws&zV(x?;=DbMV@FbFCIUMo=ASntOQRG@WHW~0#xsDXe- zh&6Sc3#+o@zmWXQr$0Rr zHpl(9m@g@<3P(XF-O5;a*YxC#t}sR<4)Q#|fUsjL7Z|m+_0G|oceBR}=kq3@D~e&4=N{?Jc6^TLT!C%^vv54I1^!%Qo+E&<&(3A{=nx_i?Iib{msO@INTNoO?^wGtH#0lv72YdAk803t8IpK3aOfkE3U%IW8ONMu z;#?G%Mp-*!w15M)0*oL4Ab^U(s&a7@1BmsdQo>@5(UEE9IXh@xTPwcw=g;I-_X8jL z=-vbKRh1oo;f3p~=RR=Xk$djGAvRS&h2l!U0(b-lL_lId>&04Ei)D0-)^cv04|Ss% zcN<|xGx@r9Qj6l!IcA=2b+GKmyv@UNb+Nr!&oy^Fq{Ar$gJ_&(Ja_2@lFfd9yVIGk z>!96Pa89EN7*GHJ830fK08x-oA)v4WWCZa%y1M+*o;^#OYj$bz5K-h@#B5Mkj* ziQ^DZlOhz$Py={U$cQY!0>XwoYqo|9sJ2~x)s;Wc5bwn^3iONkzy2S8?~_09=_5DH9)I>p4a0{%c;~*Q=}-Xz z3!oPk5FsQY@J5N&re+=k3xQ;LKg(8IT|XN4m;;c8RxM++GNH9$KDLNL8p1G0n+*W1 zC=@XOT7*EvivZY|Hr>vN!IigX+S41uxV86gKRI1e5V;0cKBCGqvW{x*jmDP&LKgJP?H+3t)1z%!+e;v8Z$~YthHq|vbGY>AOs*uLopBM7n9*=8z2;$ zifaLC3$>GirDhLo#W`nP6$VOE>TML52vtGB8q$EvW*9D26^V)7Iz5CMYXlCZ_Dhno? z%|NPhaIJRNbWpHO(qv+1aA9UX5LI1YuI8pbsMKs(3m6ZY>oWSMzxl8BAHDVAM?dlE z8|UA8@L{2qS{7DsOa5 zq$*n}g@6Jeh`O|L?!wly&#i!-z5n~}o||7Nvg-NgUK#GJ+;U6z_S>gI3dkvxoTvh{ zh=Rfb079TNDlPBPf|@})(vC&FmRUf&C}nEf?+o7H(IlvlV)SyIRj(_Nl*|4PzVG75eS742*isx_RjhK>e{RO z_U~R>sg{-wB8J|_AfaGcRI5dG&AX}YMzuZqLYEot|l zmmnazeDUo=hZe6cugokSb<(b+;W_l40ENW~SRp~BJZUHBSyEqV$)sGXhnM~MYQWo( zD%)vTSy$FrODLw>=q|LT7J#(%el#w2Lm-}ofe;8iiik%+VrDr7#G@u6*76DWUfru8-0Eh^HqR2;Zz1sNpc=g>*+#T83bobqLr&E#% zY*SY*HP$+DDlFZ4QC}5b8J(o@JgUTj1ri~wD?*7Cu?eb;^>fWeP>!m}iCq8<079&Z z00EeV*_BmqedEHeJ*{iY7rUJq@eQdP0tS?4s1Thdqm?G55Ll$v6c-sPr3FWEt4FGz z@1Vl2^*~W-sXZ>!mtVd5(znmwe#eLIxZ{?p9>4bL>!(hgxaF23AGmkdY_doo|%G&6KXa4Nyp3P5w_|Q~SS!YI>LmACL!aCycGbX02Eb&a{K&v<5Vk^Ath=3ph00_ctU0qq-?e9c;j71AJA3xzzxwsh1d=g}_0~DZ%tWY-eh&h|cOiTi z!gmRvc=2cgUsL2-F%MLJ^3wTlOw9&^G7h`9HYN^w4vgZ97fu~MymaO2^33854q6Ud z9wKYOGXpXZ3yK5uLLNy3r>l$k=xQ~-Kz=!)Vbe&c!hTPjv~{wWOzqa~X={QSJWJty zS>}~SQ|4}>I~(c*!GNFud#Sw?3PM9{%86dv{I6 z28At)C51vzySl7$Z)+4sSSjUzK^zNvZK_rmwzjrHGs(VfR5u7i(#CV3bYxuxz(EvR z>qsf*2tXqm5ENh$Pvm1>t=3;IHZR7yQLFvQ(%ogFQ>#GRNY^fnrLLVvo!2WhFZ;R< zgH9UHp^9r?p%xEP79c(hjWVX*+`QOKgM3gon{!Dr%M1cFAt=&_3cw2#*RGx3vv2C% zb7v0jyV0nwxKw};*>Uc;WDmmZy<=fp=26tFa!^WYznL@!UUtaFq3#UJQIIxDpY*cU zAN|{JP0bv==k5#d+nLtB=kz;s&SQ4Nz;cCN0zy6?s$FYC2+nw>o=kO+!rF?!;k{nr0& z8b|KA|6@UHpML5|9zXvppZmCSeE}^%)^1L9L(cQssRCQVQ2-jmGca=ipg~zwURaEY z%EBpal`h1waNL>P!=y&}a#3yrhjB2~ZOjYUox#=G4;VNKCK`=-gpgDSOyZqDO-fL) z7iTR48eH%j=Y0nc9lUmJ?bX*#tX+TiqmSJAf%n}I zD>NPyms+t0<3%Ab03*By0SJi%(Rx?8VpI_nt-Ki+@m7qcEl@)>TzydCihE+PgirqQ*?rnqZ?Vb|ON8C^8!N zjDem0_T21((G7ysSp}e2yg<%07R-iO`rrKbfA)z_{oH|li?4nA`Tow;k9_!^!-u8= zl@p9TkIQmcRRto3CQ>?eo}6_G!B(|K9h!KYuT0KKZ+o;jdpp~gAVTerjpjegDIE1e$^SjbxZ-n{kvhlWtuq&n9g(&R=^w=`_kB zHl`g%4fd5W0w77yO7uL}+VkMb^6NJon;7Q9%^lb7>}#ZpRmlJt=;)9CpC?XV#=Af8 zsUwFQkN<}!^WJN}`VW5`Y+oY*N|rANK~)x`IGNPplCyzEjiOix1OWl424Y`>2{e0a zZLh9(;vn`uXm@ro(l}o(?G`eIdbSfE0O0=UO2z9;We`lYn!CIYfI?;w1VT&rUF_L= zuarijs^VsAs@Knm6e;NScfRn&<3_b^zvZsOH|)7~_1)KBe|By4@+Ths_+57#jY5ke z219n4(w6N(Tp3IHGic@PEwLp9r-QEyZXqGmMHnFv{FuhA*+EaF6Y(cnOo3Z$^9 zD)Wug{gu}yyV&Qcbn!kNbpaHjsh!}J>&L6{U^wVEl4dr}gCHtPi>LsIkU$U+0;4^9 zW=}>0ov`|UiGuHNU$3h`%xkT^_g8=Y^mEU-y-Jp>Vo6qYLzZo9FowXyU<`O-2Ztd% zGa)$eJhWjj3`2k!!eA3RnQXxpqZqe=c^!n>x+k3B-3;84OtH1;X zC#Hh!-r0I>dhL3!u<#~j0zl)Lh1}Nml~!xKvAnux@qUCRGXp_|=JVfv{l(YTA9?FN z2lh;T<>WIje(%}O{_dx!>MIfk>)8P^5s*eAWEMmcAOQj)5dsDcUIAJPyl5?`-Bwgx zzIf(a^E35+7S!6e)Y`|G0;HYGS56%|c=Y=6>fGJ~o+68ZhtRS{44id}KuHO1oJ7>$ zU0+_hb~Apx)|~DaYO^m8O{bmx5=^GenXF<4P#Od(geue_*#t%RN1I7q?G83)X7{iJ z2n~@GI1&NDLU4pM?2m(A{FT3X_ai_0rkiiNbm8oa&pmPLEsOWxcLHTwWG6IL9D>ox zS1uo0>ourYQ51&>2_#WU5?;Cfy#q(}>dNlk+55q_m5M!ARtgVRlpr7=ihwWzBOwuL zMM^1yKzxII*Im%dNPWd z!_juV84kxoVNw(W+HtYP(hZC&avy|~X|g9x8vWjmp&(Q>00bylc2?KlXt$f)-E80f zHv{XUsx)b46chmw)Qs#P^PUyAl!OEv1iStI*+5eKt#zZ>~G&x4E6>5ZRbNf=-C_&k>0yDI0)ickmY9a)yw_|lB+(&fl|lgtMFKz%SOHZcfUE($R#j1K4hC!W zBz2W;w)O$&VYXDcEdU?VY%{(IgnGlP7MEEMjGC<14tS0jv=xg)iclc|3y28&B#w4^ zy*Q~A1?wPXrq^CS^VnlwbIrT&yzSOw2Ntegy71a7k8f^$_XocJowpvjKS>&hl>ng9 zEEbdp02Dw01V90Ve$z=32{(HjplTgJ`WWV0PPRF23KvVb^N&MRRctpmtyf}?!v z^}+g!od$IMbUOclP9^{eQJ2=?wbhf}tuyD%Mmx{TFieC=E5i&oAd3*9upkJtXAsbu z(mX4-HrD|9C9m9k;?65?$euknqcVWXvlnt(+m~Cdd}Dca&*B3JO=cDni{?vDoqz6? z)%V`})`gk&S5BThbMDnY__d!8B?DkUMgl|z6c7Ob5dlH~1V9lIK@e0TglH-70170q zTVZ+m(wT41&(```khX5EwNJ1Lk-8VIzP5Py*!7k5#l8DclsJtXf(uCkLkfHrnlZ@6 zrOVId`AT~to#es#R))cJW9lYM_F9?{)A1B}VQs(!7G%ggHiSy*RY5zun>td%(Qs;J z4@*?pU^L{iz-(OP<55=hs$w{*`1Akx-0gSVcmMtO1X>>d_LCc{mnJ8|n~v|9pRdnM z))j&)eLzvG*-}v{dSrA!puM$mQ1g|#eC37xNA=3m?sWSOgmx6v1e}%9q)EkW%Zf$l z22=nDEC>Q3!Yo3FNZ^9v^6<)If!WPLg7n1f-gjkgvEYDB-@;hy7%DKRhNFu}n|Z-O zFk4IJK~%Gq?CfkP4aTI-5_82c9_Q=hygS*R4TFwgb2Q3Ytr|P9Ifg;x+$e~K8ygp+ zI4W|PnmVc|a%_b`gn$r<7_=2z`JuIzd^^BMD+q#};qZK@Rh640*{7p6>vDJ4Uta0{ z>7RZ69S{HH{{3(2cDJ8;`YZR{z3=WfPp4)WW3_z!jmhbx(MkYiXD7E+oJ0+ja+F=0 zoJ`XC%yTbZncH($+?vy26r!UluPo>=hCup*_3`NX>{P0~+gj_kTl;JEg?_2U)K+(^ zU;CZEz4!k2-FNrVlTSXiyK&|x{>A&}C!6SZC`KumR*41V}rnfS3SC;QxaFC~yNKFhS+rARCX$9JNa7 z^;#So2ig%a5d(l{<-8IW(mH^=N^q2Ky*^lfq0@k_pGoH*)JX@B5OrxSUS9c*Eti}d zBdFb-0f_Pr0hLk#A~CZzRODlANQAXXyf=B~Lld`JX{{#fJE!(89NAfI%+H??Qi$Z( z3)#)Bi=9@vvAnux@d1P;GYg4D^Ochqzx(p?`|i7UcB1~(lP51-J^$PP>&H`Fi7=5M z0wMx{fR}%Uh#({gD8M2hK%fA1Ma0MkTwpiC^3vrq-=3YR_p>nV+?up+VwDOFFI_#o zaQNWT%EsP3d(kVjN^zvTkwkpFRiUDuPkruc1K&A+t$l&Z;+&I27_P_1ESFAFwiD6{{$3a93^RE z|K0;f4j&r!`>#jMQ+dM1A1xe6p&CJiu?LE>sc)T?`JJ)V@kcFMtlGip) z&+nsb?5Eqe*fJC#(%u-%vWi&&pw_6ALJ$!KV08n6h+`HI5iZsEQn~g-Eg5Z(hhgpL z?4Gxc?To|3>AsgtQLJ2`7_;$J!L7VgQBEBPt|H|rJ<@Uhyp?&63~u)>H5~& zfF=S=6naIQ?A{0ayW`l1Rj9D#rQ7u)kVM>#ho# ztph@4G+HkG7NCo0q7mN&fZfp*3u~;hK+V+CL*55~08#)TVGO{41!E~ z!_Cd?Km7h*9zJl-fdj`E-!!$cvib7!&#y0^|LKoBvapaDw6We7hfP4|0R)xf3KVNV zg#Vu)2!I#%BG$Wco?G!z5+`Xwg37V-N(m7IqOfwF*b8YLKwc#{%C}x0tiRA{K-bTt z^AGBz14xLvv=**@)(Mbd4o1;L0)==6b!8L^Tnc z=W9!AFWr389c$O(x!Gd^07y=}pxxTKIMFUQme=+yK7i0>YrFVPG`4!R6(%kIhWc&ZrmF56h_mQx>H4aR3qBF6+dA->Rd;Oi)PMv@F;SX3)6e#D4(8SAEHxX!JvX*7bf&<6g zY0r_gNkxF{JuA`-B7lO1fjx|wy_S}y2*EP173EcQ;$5xYKIkP>;4ZD~{{2^9K#t$_ zz=K{#U;O$vZada^E%Y9%U2Qivw5t>;U-boN^Ht>?BMdgqTF zT&zF-jc;wOoc_h1|5)9C5hkgIA`uWFGBY9q2!ID(|J2&j>b^ZUYp5v>#am~)gWl!Q z@Y;B=(yRs36Eiz&gJSHPjfvga9}rTN$BWliPCobY*-O_-N7GXajYeytHPuWTX_Pk7 zdM!=DR0By6)zc&_ttchR2n##UM2^5CAc_V6VPp_g1fETx5P`i{8rfG$VGx80R8`7& zRE@J@kmucD*4-Jg69O0w29+IWQ_pS!a4`~Ug#?|SDW_uYQ$t7p$X@!V7Ie(>P?-*HpvvYnl+gn6PJt!-Wc z@?qQ{YJk+TaY^Ki$rl!<^U@D62cY2W+KcmD)&_0%{2u^KLa>R*3C`7977DaWI$g1s!;ZMS9sJwd|0 zYtg~dDOMm5fP?~0s06A&KtsyxiHa=S8ur)gwT8Drv$>B^53}Xc?En^mZZ(sG0MH#> zcd{jD1Dda=huLcYRKh@|P$?oF6az9y>53puuP+aN@Av4~loJo&13(2J0G@ymJOU#iqIGsS80L9y zv~HxeB#w!Q*^?;EngjsYqjkgrO6vgfD#1~{_4;7_g-!#yem0$dKqnnQg{VsF@#R;) zp2S>~V?}YZHKQo;P6Gvmnn4`fq#mBX_r1ikmz+)7VF>N4Pz5UQK!?MY&QbU-savGD8gdK8Cr|h!f;e%SzfuaEJxO5-WJXl z-g$8%LLgBTcFMxBIAtIRFilOP70t}HgAj~S#%QIr(TYd`fL5V`Fd)(j27Sr$!Faq| z+Cf=zRp=~tm8-I%KhB4FZnLcD4+eQYCXgr!k~FN<;?6{SaW{e-8{BM%)txF_7$Tub7lozyp0FPorfwwgtSCg{Y;B%!Iw@hIEO zvu@@5!6Uc6^4j&ihi>&4F$bD3&;x@zO1h)%wOSYgbG?=H#@nJ0Qul&I{sjv{tztp(4=rMtT6i_eM*WcLBYjg=Tt)y#^2j56FU^ z!7;K2@M4N8c;nLg-~HVe7xx{1)2(;!+kaqXb?uc`u4TP1Km5-3+07)3fCNNqnr5S}-Y0=04;2co0Vg()Bax`~y0f03<|JT92>1_Gnx~X4X1M;x==@Y?O-2%92(> zK8*FHE9cUhan9PxN4g#d4TV}O57fWD^4zhbw{BdIW~L9Z2%r)aplWmT!gR;3Ev?Ki z+)vmN5J9$R9)056ORsM}eAip{%}xH}(@&o|{nBTC_fyLC081nRQ2+!&zz6~ehzNiJ z;6n z*WKLSxYp}#I%kQK$|)3L1VkcDN+GiYaD)ut2|a-*g@gfNVx9NiS({r|k^-%X#S?&8;%KZ~tmPJ*S z9Hv+?MSH_n)Vj~+V`M-wcR<@sx8Ue=0lI&o_fHi6;F zl{dcr&A&%AI&t&OM~>cFjKf-eq9{f{LIf-bq5(ocVH^T@l7v8`*et)!vgs{_W;&_Q zm7G}L_{C3s`uHvP-T&Z2!@=gazx59X4%FZKeYX{Z)poO{hI+AXyyL`8Z+-UZXD(fQ?dai|54`_fMx*zRIo};z#$c4$UXrxa_)tFb`Eb~7 z%xIl5SfC2XUb%90-=3o)5(IuY+UoAEC<+2qpP$>u;(CKsz^t^rIO)`qJs`d}TK3!% zfIuzQlLNvCAf(AT=fyKQGEh49Ts!mn)|bBgOp;FDarYgEkL|yB`O?YnzPQ`#e)NY9 z-g49JVg+0VxLa1|fo(lL9z~N*m{Bnr3l6}CfW+caL=h`=!q)q|EV6M%0BIE0<0L>u z3_xgs3AJVo%pmO1T3{fpb%2FUahz?P>90ON(S)v_N#-9k$%G&h>e4wpfARkr6R14TDh}rs4{r{^rgrhY#Mgxg5_-9cBf*C$6tt{`99lkHT{;YpZK{0b5(6%U9O2!a0G#crYq6QMx@bJ2iEn*_w^xRO?`(RZ}KppsKQ2 zQFOamx7XX++~{_9T$LrUPGcPyj6#!yX%2)r(GtYhFz6Tz>_11gD)k()JPQW4w2!R-Z5I{hU037%L1vJSp zyYBrKcoV4Uq%l|c+Q}ELKKi96AAIngH{W{V#Zxa|IQ_&!ckR9P)`Ln}DMq1Dt;vPq zaCrKlsla#w{-O$(=A zKC|@3xdRJ_?!5C}6B0vl;qtl9fBy3i-S_ZqZ@wc*XgJzDb?W)GmCaUT`o6c`H#ylD z47Vyj$jg4SH5CUlfWA9e@-hTaq1s!E7ZHSo9iSDqt{?+CFyma#o>~9;*IsMX_uqcU zZ8HnAs~gvze)gM{>mR@Q=zsTpCy)blCFp@GV1)*~66X*YjCd3;s8pazPB9yAz1CZKezJvK zKaa1?xU^0wMGBOW-QFgkFROx`geD198U|6I zpmN*W-BXJThqqVaxtXI3LZld2u-e?bFg@v3uPx0l+^47mAdGC$eCeqRFPvI?_dRzl z&UC)`#1qSFS3mtrACGA)k^y)CWI;egK@cFN9kX}=1SG;6M3GAo!VCr!Ra}kh+T&p3 zjngOR=bM|uDxN%=c5Yr>x0{>0ub+EerSaz04m&J!Ta3$AquIV;qTQLEO6pBfkv26G zHHIVKAB-crF&qsyHaFHbR)^z(2`EW|&O}pbFdFN%cz$kXetxD=i#0N#HvtOz(P%sx z=Y)|lHG+u1C{mh`$SHC{{r>o3#eMIsXV2aP7^Biodp}NnJ5^b>l^bP);ds>B z&C8sJ{XVL4Yv+x***!~FN40c1D_v2zEFYKExUe~6ggQvWB&pZx^;Rvd1wj-=u~ym` zoz`N6fGCLLln`9y0bOBB>kz)#Wp{ z-FD!A{^Y+@2*@ZmK!sQ-r9B%&O(H~&*(wUWQ{u#P^=E(ad$-+rM3AN?7UyP9Y;5(C zG(>U?7DRyrz!89e8Uk8kgMt8VoG)3og&YTZCXA*roc`2r{Ap)u|9yAemA29^e*Mc0 zwe{m4xGRXYb+(Nj)m6{y6VXPEPl`RlhelcyN9& z*s#@T@8Y4}?wFmu=bqc6i29=)9YGMJX*>hO-TrmQBLowheYJQGp|k9IV~+s}WGYb3 zsn=dxdg{s3VK8&&?GGM2G<)gF&eP9)MfA?Q9=Y}K(Z!Au;xM2P*^Wj_j905NkAtI8 zI-T3163DDCxf1c@B?-bXiWs1tup$(6OMpZ?S*A{Zm&0A2tDMBoM#K&^D;y>~#Ql?o6^9AOm# zn95`-6>n|8&UbgtpMG{UTEDooHgE|93!^MBWO`Xq#0@m@-nqSdCT1EDwQFG#8bn=G zRd?9ykITa1Amg=-vezF|?jfyPyMz`WKM2$wP-R{&9jAJ0h+89z%5Qae*1wkVWLli)E;=QfBw-rd`nH@uKd*p0B z=w3PX$`gP67k_Ms(2Fnwc_dquMHI9|lu^J^0XsyE5Qvk_&DFpE{9oRA_c5h|$;pKz zo_AhbSA-FIDM1uSh#Ub3r~zO_Y!HcEnUyQ0-BMBu^?a?lcx^TN&ENmq+wQ#oq5Ix) zef9dum!3K_13&uk?cRGG#M8~FDEm3m#`eloOOJ=#Y#k<52h!{vp;rPZRZ;eOgRLk{ zJtRqep%mp6b_W9mWIT3A&y(If``Q=&;J0hz-8OM8hy&Bu-l-}tL}P(Ug=u}FQ=(tm z?T*15y5rurfB3&QHQRSPeI7sY%*$bN@LlhG)Yj~>~-f8UY*?)aIL-&tP0cF$YyN@|hgl5{*ZvA;juE$p`QV+0eMy|ri- zsVH6Pb*=OzQh9A@`PpYrtuBq)&3$*?dDlc|ZgYL(*=L^_j@Lf;!w($4r45*eHUO_R zh9oY_Rs^pVwx}m3OwbvW1V$N+hSrrq7zBn$A$rXgl30z4wc+@U`Pl>8E6JX@0xZY^A_xL#Et@bl zI`ND}$?Qp!4uk-?3hdC^b7z(=oxVC)-tBF!)M~&1Nt|NT3ggCs#kuxmE1Kw3UInU2 z5@vlr?2d=M-Le|>daIl3m-@r)qR68#T3pyaJu|yF-;biS*_e!zHmV>nah%qHpz_5y zA5?ZE$_iAK9ibb?p^CzoMR`_QCqY=#DiP7%A%aq*02Etq{f_llE4#&9AX@g`I~J#s zu-&XrHqt4rBk&*~?5&{FMzhnv6oxo1R(ATQ_w7A;@oc%ca1)Yt9)XlGx^mWf<5@Y! zRb`8!8s~YDmmuUB%hKjW-tP_jgTeC3>e~9M35@lOpo5?mMD=!Os#a?m9fc-NlQ<3o zt#lX$^;#Sxsdjr!1prXjGTsfb_ z;lYDPQ8Wnb?ri<}U;oit?m00vJ(H$Wz)cg>99KGICk2W^j*w#jK^g*K= zwA%_Bu~}5X^tYdW{cBIY_OADQ;LxF&uYL2e-Tt-jf7>nl+j@R_);l1v6mW*+_2mom z(~a>EI-L{DF_IFgK%5p-Xl>Qs-d(DXu`&*s@PO2Fiuofl}?GoiPceo@drQpk>htA9Qd6_zxn8QUwZA|{odbB zPRs*&5tWS{iwzSZEdqoPF@vj0z%n%AoYENg2E9N1v(IFCe)qj^4dT!`oM`O@^8N9O zb7KS((R^ekP>l;WytcWO75>__)$Y!K$Q(L!?AVc;rzd8wURiqb+mDsy*2jM4LyLRc z0=ZT|Lc*F@3zu28g24*23(XP1bZ6YR2oA}D^WG9rpbQ}rP#lJ7oCI34XK{`I5fB0J z1^_`|6h#3#66Zm@D7L_WM(KbGU!#1y^?GmR`KdPU*r{axzOXheaD%cQac%Q*X$1%c z#5r44h4+>eMxpWSlOz$5EYHSSW{mdY2tZ><>we|PB^`803=A(~4zP`2m+rRYjz-I&uzye;- zF*2Yq01G(>%o-?GDnT;HIP7*$pZ?x6r=MT%k906Qk?gHYLwPqnlT7cOZq81aBoH9- z%zm`fT^o+GUa#tRZLeGH?hO0=uGV&OPy0DXOF2(+q`Y9ZDY z)ySj*+OieRsQkF>?)KM5qiz~fvsMd(y7QV;62>*s%5i0@ys`zeH#!P~R8x#lWTPv2 zvFTl=$SD#OK-QtIHEL6}sKpM%IZ}WqUP!4l&}mgwNrHu485FOz+Ouod!aegx1;IKI zP}(TxtO1Q4Sp)!y6d(eU_aXvH8OLm$Eem_`;-xd^-bfqmgNKg2@WSaUd+&MRhko!!!zl2+`pduhPxYpH z^KG})>eK8Rq+%x(s!GVBDC8J91_4riz!HT(!25iZuUg;L)Q-b_r04$VPyVY{&4)km zgC&=beeJ)+rvK3&dBjx1*+wVQAq!_b-WsoyDM<HoL{wdzPw5HKg;mp{9XCX~2KGcAKphSaLEFx$DNcn&o zX+5gh3U^Mu@xmYe@n=8#nMdQaiJAb2S&+bs^-_^G1YuP|7yy6=sQ@&J$u0ll|Mn}} zy8|*|qtzUZop+H5h;isSBQWGA4b@1GO6~{s*mBTF7V5Rmv7<*jokkSUr3)9HJ^8rC z(a(PT$L8j1#Gb7d0SG)nq%mMu4oBC)EL*NZb;x6~J?uF`uZf90c#XP|G}0&r5p*1& z(n!FJEC?tFhzJ0PCqRCl@+0=P=QgN6)B?%UsJ_+^K^IRxv4hp*vVw>zOX*S z03gaS;??C<)WXO_!fb7sSyw0}o}Kr$-RyYJ0FsxLB9#>*1RxAU6Qfkl?`-X!I=J`5 z&T2Y8dz1wkkeQ8<-QLwO*xuaO*mvOV!gUr#1s2U09zXlyYa8!*>pgRmjYl7Ue0^*A z)1Uf;aTy6AFryQ&Oddd(K$*yS6o|bKHaCYay>$BdXJ5{GWvy0==aOKeUTe+mpF6y7 zda7Lm?_p5bonhYX`$4zruJ3T(+gv_f*`0B|9Yk(n-_+qF`wr~iH#s@ksMR84@_d+$ zy6ndwC5y9e&}vN?m1Y^1l`>&7iaW|g9#8^e;=<;+%|IAjMNG&kU|j`u6KK?uyZ$KK zsQf_08kHt-Ck`e;CHde=Hd-&sE>dZ>Ws`RkO@xcW2AH z;nX}paHW=XHkTVy(}#gTM6(cS<=Gho@s61Vkp7t<3W#R`5EcP|G)=8@>zkWZStUv1 z`t^+yCvJ)2WIQTO5RJx`nGwC^Vtwt}#fukL*S2zN9LJlh+q+w9u^Iit|NZBoE}V6z zUOxMGfBiS#|Ni&B_1?RF_LD#Nkq`guPIvV5cfbAHzw@i-&z<>;|MPGD=zss?IE}rx zm#)70xxfF5?|=XM_w74TW^oYJ2jd|tQ2lf(z3 zbm5af|8L)X=Yw}Y^tMZzYtKLTmE(*0p?lsu)97?iE9XlfN%6}1srE!L*xjCvRr#20*2B2e36Nlu7Y#KKJEUUq7Ff0MtOKnIIu0 z-Vd!W0+lL=@^LP{tR-ZWfV1A(P9yrrM<1D-_UGPs?%LI*fTsTCM}Lw4T*claAfvL{ zfB>-s!eA7zcn}L-+9MPM-R-jrhEzLjG`bnB}$+%M5soiB}Z5Cs%Ru9 zRM_l}2Zi_o#48435>-p;wI~7S(Rzb~UKE2-8UX;232tBzMo(e zDllLA*4dX|+j#iiyJsfrU;fs2Hny+*_Amd8av6yMAOT@uM)U%XL6o_CW%>CRUO9E@ zY_FG1bY}MNJ=CgAO;67+9A6AtMvSnN&8s_GD_2MTb<5-4Xt2KC-&`A4Bib`LebeEY zg~fDsKAM=-X~O}Oh~i52RuLEgV75*Q!4e1}B&7oJ8ZZpPIzv!a3|c!uCQ?CUq8La! zFXF*lL`>s2VU$tkb35?Tv(gtR5iw9{pqqhi8zo$AX5)2R4wNbgDz>G!p4fDn)1Bs| zcwu(h01~;IS-ukV#FJib9h3WdTnw;E+WR!~8Ye2B#P#mBqG>C*G%#PVH zcmYs4AktM;39!~!WW8*-qg9%XWnurJVO}J0-FYHJ0ML!5@0> zg$rl@;?Mv3BR~GJBZrR?p$YA$|NXB$_|V(-A2>$R05VKoC>Jh(1LO!eB=kTdgi3_i zIRe`sEennV)lQQ`1$Tb=SO4(f(c9nqL+^j}!s_GS`rNzk+xN}~?+j7LrHvRW1Q%Cl zEvJ_Aizq4SWDJLMu2y&UOzX#IMeO9PUnbH3IQq`<*rshGQBr= z_mBMQP$FwOY}%y{ym;%gK(PWu7bIcgs|tM)2F_I_G9-cGeCuOB@y-vu?~dR9-QPU@ z%J<&&j`#fHFZ`ThHd@(|8CYq_t8o%1&JrOA3VWvr5EWAJ-@f$JW?$ZN&t0VB(U`5{ ziAg=mMF0tb5V!(%5QM-80#FuEm2P8gXZhN-3+G?#?w+~xEz|FL_*O1FF$XU7Oa5>NOMtVG|O%AJJZi``AI)au;cRbea(Xm`iOzn36m`JF zm5lOyts1VRp&>OJrPB_y1FAUq*5emnd3F81yWhNbar&{xPHt>o{k32J5w3cXZrM`h zg$U3%hgVNuKKblRODpR-h-PMI_AJg%Otd?l=IqRLElLpGAeT$mR<5sJ$;Z8F&@Fpg zl5N@YdaG3&J+^S*;PGbd`0UIHKxU`}3sDu2MPL*Gi{KGK5u!uuz*?vTI1NacfHgv( zP%{#P_iPyfRiJdLbR8)Xh^#~&6#z3-)@PL;R=&?tATj`YM+(x&wBo3(lsLbg=Q~Bd z>)ptpH6X~q7He^{*_aH1*m`l^(G4K6iLPH-%g4?+d&{kdmzG~Va&+JIYpYX}3vn`0 z79<>mQBt~6(Bcgei-3p&Dg_Hfk4Wr{R*7R__F?3+!4eeP2({8To0GGil=A_R5iU`x zP=U3(qw%u$NZ5>$X%n{)@wa~S*MI9be|@smWMP8v+}Vr&`Apqvjpks~ z)y4u;;1lEoMUYCs909meL7st9`*E}flS*tgx~$*H4C zDeG+EVv47FmBS?Z$jAO;DJ|AvQCV#yj;pD55I}2vX^5Z*d2y~LSoX%Fjc&oJsnFK+ z@NKuxzx}qu&wTwG%a_mp(l7t~9k<^s-dB}VW7|K|eEy;tVhYKHlhn4WEh*Ac*n=ArgUv4hbP4m6XfP zZRebOdjGdy+k36`qTjEA@!lJ2Re-<&I|K`$7EL~2)Q}e&MZPlVUp#Usy7iV>qpPD0 zp6=ADevxhXMl`x_`gl4rdBr5wxZr~`lovZ$c_nykHBLuy9bH-Yte*|@s$x(e49uud zi=xz8s~90Bh9U$6Ay5zoWiUwSRBXQ}3y?T%)oLA7EQ>;^N?P@-WC#UhYik$2J=v;u z@_J+DMQP)hQlpg8CW@Dq&XMsf0RV_7c=g^3t8-Bl#l~0>77+jtkxIOx5P~oB;0F?h zDtWWk1g&*CheTRRkx&RYD9aTsm(W+G9~m7xhH<-6DuTK1zNgMUyMEUzZf&*Fdp`d_ z@PoJiAFnElz3ug~*Ym4uTR%K^>GJ$?RBIkRcDmW>j7?0AblPzerwJ*SJ3D*pD~oF@ z%e%b-oXdT;$ajzJ-}i!3#|}+2eReLk%Z+BSwy`-qbraBx+PWH}Mg&4oR#78hgh&km z0ct=F7#LYlBCJ#h#SvHp0#bz#q*7EMi&R5wfTUg$Z&Gp27zsKo{azKiswE&384#!J z4Aj%OlO%04Qu@s-+pO{~Y7rqLGnXNvq?R<}sLo=5jCBzj5-ttu`tn}hXG`XqYfr3i zoE@J`3~|3-q{(=ijFlxYtBov>dKS={voS&lG6c$z7{N$L4Axjt)w`(7x|fXKL~Sw7 z)JDfW5_3Z65ONJ!&AGB%8w{@ySdrGq_*{2THe0Rty!-$9@Sp#grAQQ&smT4Kk3D|( z=f6;^*H%`SZ@&4a$Dero#V>vF8{had&z}9k-~H`hzvazuzUuVV01njr;Hh)}^yzaV;uhQhEA2j=c}_qn*S)9r<+vD-1~u&XNdqDT-C1D5?(T~xNt zUpTw((DDAzjEo=il_0sDzCzsbiCx*1cfRZ6m9&FElo){CsS}M~c;k!v+pUlP?Z0jB zZvWyhyzXVU%=Gi@nTtCg`P5hTvJ_Dh=)d^%_|L!UrB6Tbz|z9m_x<5JqX<>xp@$y& z#3w#+{q@&xZ*O0@viSb@zwf~ZA6#Ew71ew1{ql`B-uRApyo1$b-u%g5e&V4=o~Sh& zwOSG-@i5P7^~NwOQ4I)M6DtD%Dw`x~R8^M7diB+F*Il#!$ibS$EveQvt~@i?UYVU3 zX}fxNt1FczQ39u49Y=8pjKafgM_?N?ZlouSiA-Fe;nMrwAnOmh3ImahL@gPksy-kG z0u9THc=^X-&Y^~!PA%TeEBWyPUp+_Jlfmq-S*PM zd)@7e7dE@yEJ>r8{nHau6U|obc@yIkd0zO!=UK6~yt=ZqT9tWhJVF`On}?1bK7QuV z=vX}ljl55!D0|NhyH9sUe80CRJeoEROES*31_l^dR8$oetP&}q0s=6K5;KXSl9non zY6&bV0+glRT=tR8@2SRtB>qwHa_yFfBM1K{?u!i zmRG*};N$Oj=kK07_tY1^bocMR$VvO|96}FqfN#cDHty8|}{ePBuDmGuLU6PEYn}hJ?xBdy6vB0X}uf1;er(bjZnG@sBKE3_7fA#4o#=riH-?{hh+ZVtbw6_bKmYxozVWC2mm6=nT38^2M<0FU%U}NTZMWUF zy}kX&Bagi6UBBOIwX8K?``Xt(_ql)hgFpC#nVD$-M3QHpee$!P`^<}8avN)Cwi-b> zPLf`4;9LX(NfZ+qLR3(bCaunBY|~J1D0~_r^3cM-VRx`MzqNWUred^{0O#4TKa5^E zHacFf)eUK{w;{M!mJ;KUIIY>F@|^XD!>lNU^Spl%c{?H#yVw~+fTT!>gh)uB$|8b5 zWDs1xTZu86IG1*6ZY05k0HefYK2(r2YK>xdz1)7b9d%2f0!Hhtkw8tA%H^f` z@1}8gbR@oXes$)+4OKE%ntA|bP&9;Kl*I@dMNkD0K~YjARZ@^rSqYp$s|o;tj3@>G z1tf(?BnrWntUU~s5hNr+B77bxsS=1Gi~y{oG>&V=B&tPTtV$TDFMz%JDh$hN=q*GX z5Y#yriE3bv2GnQ}j!aWLj_RH#G;z1<6SHw?bk?3`4Wl%OIBp>tUIqTj5ggTYdNxR@qQU)0(o zb7T@>{lEu4@SgX)Cr#5NsflQo<@elk&%(mxMx#y!-t?w7is1kG?hjmj?e%4u?b|o` zn%BGvz#x($eD-r+zi@eNd#As)x!r7!oH})C|NhoU$24jqjdUcA5h);+0AkR2pE37_ z*`{-9D6Q8fcL)AE4?gkT@16UJSH59veCpo&{#AMJ?Z5fU#JLe~0T9ZI^UoYTIeGEi z#Us;a$i!+$&?&?uH7nLi3EbV=yU=VKFwh<3jEyv%B|A}aZOBS3TWd#e`1ucIMV+EX zRaK`?Pt5K&cieU)A10sp_-ChQqCbA$e|gXEe{Owi<@f%dU;Q6nc=}(y@B=hSq}f}4 z=B}I1O#bDE-uaQg`Jiz`03@<7KmU=Bd}MuneRFg3jyvvn>s#Ln03!Uhx4r#U|AB}= zJz^fJ-S@uh9Y6bXKjUIT13*v)Z;W-$aut|^vlK#Q9SxzhaXq%3P*|TEhY^XO3@zml zHV3_he7KUvzTJwG#BOZvCo-r&q(1bgrsKdg+-)OTwSyo<6_^zfc%&f?3uP64o+yI| zD4+t0fFJ@9kW~NzZADIv7Rq@cA*WbeY8_eaWu>c+i%=wGdt+^lfahjL$H$^Zo#$qohYpXo>JfQkH4;l6$_j>x!C~aY(6Ef9ySx4a zpI@4pN_RK6D`?l|ZY!u=sa67HEs+Zq8wCphDgdG=LaL++Dxnk>L)MZ5RnTA^h*kg! zXaKFM4NRqIo@kCC1V(ViM5vAf0UJw^rI?J1ToT7I0CE`ihf4-aWR}W@yr_m1=i)GF z)kg@Uy}fP-Wl~G5112p(AV_?{V=k#inZEU z;zmUrAfgqPT$KqU4$fdo@Vu%Dd)?iOoqEWIc6{oZ3Me43)=-V3QmU*T$G!g2Fk4E~ zR;cQuBm2urt&6_(&2N`wc+=0mDT-ndRh6x+%?lTv6Afq1oEjbJc-AXdHqT$Y+-!EP zzWP+Xma;+>7!AGm{eOD>jW2F>Cf7Fyi&wTT&0mQlX*DQuHD?kcHco3P#Hs1DT1kR& z%!*mFmDJNVVQrB4?x6b1zxw!({P?S{yY2<|+;exH?f%-Y{^yznl**{6`uQuD<_=C@ zxqSKHW^W=i<1iNT8k8X3>q5NCgg?W3Bi9(U%_j z{(?d)1Zp&rAZx$%>n}1e{pnBt>+w_R@BY@$z32BnIV=Xh_S?U3-*@Ie{V$IjW9w1* zuHX2vY<=bX4}9*A{^;Fk45}KHZ+_#O_uhN&4L95nLU{1O2Y>(fe}Dh}{f|8I=zHJ$ ze}D3mpQzXC_&g0LLxka9{PFwmyz8ZtQzP5mtt5@B;8oSRNJV^=rD+s=;Sx$mYMVP< zlp1OSxCRmtptA}xG?+yu=g{TQj~v9Y3&XN3N)7=)s%mfFT&>qDs=+ujsu_?|;~b!2 z!C@~`0aa85BI8_4HbSz3R0d^4G?5aqC~=mC9%~jzBA2FAkD160 z=z7g<#i`AP>ce=&Ep?>Uc;Z0>@Tk@udS^Vd0tQB{rje7_f6JfIeLaDvpIaP1^`AJMVTwuyK}!?~E2&xl1V&T=78C(d z0AE!cg0n6%R#gz$Ibtal6rP7h!HQ4`+B4MvJbN^dSW`EU07nQeGKsa$80(xd27RcC zYOnGe20W>1U@pARI21}Dnw^|WdcE$}=EhQ)h2g*#c`i~J z%hnRAI)?xyOGyOQ)O@MVSXO=b@uyz>+Sk4C)*HWa-~G=%^MeEXrfU%y2n39Pd%a$( z)7k6qHd+a*09nLX#c8lc3;}~=gTd4v!N{jUmeegX20wNi~kA3uG^YioXeCIp!Jb%q=Ui-0+eeBq=qwjwA zdt0scZ~yk&I4FP^1P~^uKK^%qxo>9d;L-hxA+Dty0+O@F@bg0HoL1Gas)nNzt&NSX zC~6w4i8u~GhOEKB1*&&eRRUL)F~(WfUwPR35IGk|HgNyo;nwCxx4+x6HdZ@iDSZ$D zQcBatjEOsBEGUpMaZl_K#y;eHWvUwJAu2^_2UJSc^OYp7y` zoWe#*8_h=2?MVoeWoQR70Si2T2)P%6MwPd@YHm8G2r?!PqNIT6KU?N0m1i36i!%{YzG zMAk&-pIh15+}_;WSX{i6=fnN`r;Z+-ot+&U9jkRZajOwo6F^Fkpez~~Rh@B8zyN~{ zY>Ns@FCkPUC1FKP1Ge1WTYIVz?Txm=#@?W7j>O}~qO?;mRbtV^ga$-N#ULYyA_o;w z5mjFW4#7DaJFChF630#?2#A6z5+JE!1-dQe5CkMLni{A%Y*?x}lSDQ)hL98~u=*_P z4zf)!1JII0NC_E3t|8M<;&^*{qBEZ7*~ZqINHsAz));AT?{&8~d!**@p_$QMO|e(sQ1dd$ao|w|0BJh&v$&Ye7PYTwm2-Vh{u-yhz6X}+t{ zMvQ^Fzxf+4Ow$8@^*5jPVeeyq^Y&*SU0+&Sz4_+35B>LtpSzG5xBc^Px~UDrN4|ES z4TBH=#UG0;35*8(`q#ht`Okm;`0?Z0+uQT=3m^R8hbAV*U;p|yy!~yzbIUC^8-uC} z00f8%|Md^wbIYwaOz$6$5?iY`5S^+;FdTw&AX-+{U}Jr8W_+aI>ouDr01+z%5hM)k zU1W@*JTDB`G-?Efs_-p7UzQ~jf`tBHWA0F6b!Dp&pJXASJ{lnx6FI>|q6vuFNXC1w zAjTLZQbaITiOL}TyeNF7KrvA&!I*%KErJUg`_hI?bigEALq9q;mUTCwyke>=^)%V* zLZf*msUJ{R%Xxqommd=m01*{cR%HND5CFB-s%lw!YppOKYHU%0ccyME@SyJi03ZNK zL_t)sE&^FO=w)j_VRU?anCWonM#l~sTVGyXd*FMIeD~p}XZD|HH^&bgIDG8bQRg6p zvb)<~UEV=$z2L?}4}JgKz4zUH?R5u_ADuaQJmiIBo>?^^h)uB82U`vj+1gloWNsS3(hn|Ihp%~Y5h6CVK(&e~atVrp z27?R`MA%DE1x4Th))Ih#ctUi}5|OF`0zXfMi~*twV6&>a6@$1mYS*I?hYd@qv#~Q4 zkwwd*>J?S5^h1WsM44*oy>BFSsLgrNi4%?l^*yP0aZf|#I zfC9&l9UAGFZtn_0QRU_M=&Yd@LZX5SW$AY}cPw$P>wM)K4?Xt8 z`O%332M?XB)tk*mJBs2sO5!L@lC)k+;~3ML_#mQ8s8yu|NC2do)O2s4=%_WCY;Ai~ zP8<-cBP9g|3<@ET2ares6%>p?W-tZ_Q3RMZGHQ*K1@wF6?(Ww1=HlM&W?7*J+#1d^ z%E6=8ojQHphyLs{J~R#0%CPYZzx1*=9r@I!{*6O?NplE!or|o@yfY_N7{=EtFx0gsTy)67%4r6pcK_A zjTsH75-Jf8s)DLA5}~uKQh8?8AQ}Qx6$+}WX){ezz_=u`Ic)SVSCvv+Br0;lRZ-C>sDL67Ae5>*rDS3)rnR^gn`Q*5Gl{bfRRU*Ou{X%J zOYWOUP0U_;fL>M8D8YbSLOBp$0C+nyH4~X=YiA=L_GbXMXyp zUS+I)`&(c8=GVS@4Q)_3k-URk^Slg)2{VhdUGdj@|ge>ppk)L-#-MROMaL2x_`{>En2Oa~sB*Gd3Si zj<~^axe|)g)=$6gR#Tmiisje6{3W0N)MrngIQ3(%ex(nJ;3AibNC*KDt+fD9RTcd^ z<9(GRNeBTzt;O$t?^};Q@x2$^e63KJn3!xd$IFrkYM`+SAO^sKIa|4MasTAVpxYlC zn++1PIwgn3R9uz5PzX`tq9`IV@E?*A6aYjJ`0~OthmUp^7FG^S-@;1h3IQ$(9|WVM zCX6fsC%1ejSBfJF*6xx^KMiKUh#DcHEG92bW2f=f0H7ELG=yU+DD ze$Z^y2YEC;b#q)h%9IA9xVV0fnE{l=t9nr{>Qy<8qb$n+z!>8_$58^HRkfC?Pe5ZDgG#B2eRmHP4FO ztlX<4V=Q+D8;BA|78MK{sSvy^ha3v1*V;4F(}O{OcYBKrG@DIj9QF!CICcE6wblCi zrRnL3&9$BBsgs6AK@wIb6BKqfw;!FFZuz{{>*LtOfyxKt42v2QBil5J^Wl!MIoaO! z-g2BIdtDkCJt2gZcuR>v8$pTUQDA%LN|aRI+fL^o7%F{mQH!}w)a>r%_uTV^=gvRd z?XFKxwQqgl^)I>Y)@Pr7`m_JzGo<=!Z~bNF?6D{A-`HH-*jl;$j+dW4bHnJ^A!A4S z8G)&xje{~;G?A^i>UMWFH@DW;_SRN**VlHsz1^jy^HCHPd2pufY%6$<6C1^mfVD~U z%+=T4e%FoneDQ&EXP*jrFSUs5NdccnNY1i}Dos_%qJrjRN~K)TyC@wL2;8ithEjpoSJJr`M@Jz`qDQ)^x=;h6N`ZNY>ZJ=L^OuVvPhCdL=aI# zhzJp@s$f6->%ab!eRHG7P8}Q>X(-xyeYDK2qYh{yf&d<%VCgR{U)(o6-s=s<$L0hQ zRtFe?F4ZC@=^bs=%r?iR04hzfwJR$#nK3T3qt**Jwb4G>8HD27GJwux#Q4ywKLd#jH% z+EK4G6H~XwwPPOZ!2&LAToh4NR%KQ%QnFN{-dYnyE`)$c96%L_AV?peWFL8-Cdp`& zHaB;+&tF`;|A8k~*Yer@S55Cbdf?#U{RbusKit?_TU*~)ymWbWX{lLHZhqmlXHFk( zG|V$kpZo5&7jC-ot{2>T^zJWy=8;FAc+c*UuFA&8!+TPu&svIo>A%h4a zSz~NuO=8dydQcU{%5xPsXiyYX7i)?|(Tehw#c#IK!Q9mN!opgxV-x$Y8E`{vEBA^9 z5j}!eU=dM41p=TrP80%QKoA7vfPsxMHK16*imDO_hLVGcI>yzliHr~lkb*-(VbKsL zXq^TqvZ6Q0dc(3`_@O|krBU#eGp@|5P->A$C^4e+*zprZmana?2uoz0C07(xZ0(5? zhg65l%g-G>b^r)L_r7F#acgGglrv+(QQ&~KLbJ2E@$mFiqbeF%9*>O9R$hTX5eW>b zi=8dA9b*Q&-T7M6+AEaju~b;I(n4R*|eVL=&NKf z(1#y-d|~0z=|Ephr`1U*h(+xLW z^R=&kb7}GHOK!bxq#ip3OGY_l)u62Qf|^=$*0}}=JCYE3=*lb%E1{%5mBh1aEB$lN zJh!v4COiN$s5et*W|L&1-nJtXjoG<_^;UCy+AggQKl9mVpE-YiSPl%egyIT30X8*- zVt0Hz+VGzZ&(Xss;YQPPUR0IgULeAP>TD~wnGuiED z;}iP z@AIM>42JUQPdz#^dg6{By=ig%!Z*Hg|BY82dEJlRoLXP`3?YaVF2Xz?WLY0T!Jq=M zB9JlGxi~gNDwTRh?*fBY&!!NpR3Zm0$U|xhlFKWXAGr45s4!e!Ek^fUt?9m8lYlW= z1PF*;l|@7q0UZJvLka;<5LFd~9gDNBjhL`HK_E+L)N4SD2_pg|1&10LG%5xGA%sve zc(e+ro-5BjaA5H+Lgvz0)9(#>d&8=bvQT6P4$h&nF;O-W{FW$`;lk4$Z@YrQ_}q7gyMB8VichMWPgCKukhJpaV8 zQwLYKcL67pbk1w2LSZmLfmVv70a#a8FON;8{XUP59T(Fm)%EuH;fJ3+`@@Bm<&DFK z_MJL4_p;lsbu`ehms-^jy4yS6hmo;Pci07%cDq&NMP8Q9rS(ReY${?!NzfSU&{_lo z3JRq{C1OP!C;^qFUms?>pw^m}FKK+d6NF7V`p6TP|LGs^z5T9N9zTBU%U`)WRO`R~ zt3T_sj07Dy4&@-*7#1s{&~6=Q*Csg+k-=_v!^FIo@6|`9)r=rcs7Bz0v?}tA)s5#a zT)sGe$?t5UKxJZWv>N0nY1YqNeSNJt^XL<+-+ScojV)oc9QCTQJ5w7wJU#jHJFmL- z#sl|#{hLoe{>*EC{H~eNg@tDi9c|5DUOGJY5)~t6 z$QnGWh((MUjQ}FBfj}BSD&Ydu6N*7aL{$|51t5%sjYp|a5#xj!4Xnk82*C@Rs3Tqz z$&0PC!;Qyk9oWgk_|$DtdfHQq4dBxH6%_zfg&^uh%D|cmy` zT1z~rC~IXC0aN>jPd>i69pCX|x3(u*cmL~mcGu^B@9l3KZILgtG%>+v2mvt+2fYx2 zf&hX5Dj$IqSJK5*bV9}+aNJ`aI|TCxVk*(%Fc z_VzAL&WOyUGMdIWb_1^k$&O6^{q$mz4!jp zCtt9>zRr@p6j`xe%CeHMHpg0Xk^u<}`g;`Vkc+rA$=Fhy6pf7rM|o8& z8@pYVL-cdtC%XOZOA9}|IDf7PJ&43hy*+yJ_~}!71Ag|0dn@aEeZM_5Q9C|4an;eQ z+BHkAer4n0*Y5q+T`zvYRVM}qrs2}F`E@tkerav-k;fh%>|~SUlUbf^ZEaLl*=pBk zW~MJ)x>&0vn_KI1bF-~hYiDQMSK%eMy!7yaL%ZG8!tdBb;xr{{STlms0!=^wp#`a;AbDk8A2d{v>+^OB@V2!LuZ%r8E3_-K3K^74Uw zw<%b)nE(et5u@OkNKg@&fJuXJDO`XCL?8q*78C-Dh#HJSq2jP2V2omFHmDYXk_kbA zja%S-%!6X{>A}XM^$zalFfnyol%B4r6Aa9O1~!2rsRJ0HGSDE{Oduw0n~QJF^I$nL4{dB!Ju(~MCe5sK$y8IgJ|q*r{0)FQx|XnR4@efRaJ0V z)MD326H9_pT4e$T4gg|^07*bu0FXcl!59NoHMEfuaaomHn>)VJ-JPK|bzuZ?&P2=t z033pIc67AfZo5XCmRFyfn3x!5GB$EpxFKK#Jw~O%*24Mk-1>rRA9;A;*zuby?-ZSJ zPDD`&6=J7lv9-N@d15l!>F@L_sMQYuj8q(yLNgtSjYAovj@ehyN3>)y#AV-9)9@2<&_I>ee3IIrmgB`C^v_@Yt1w=KzSi?dp52&EJB|3 zf-m!76}ft=H705REE!7%1U<7SjvS<*IZ$bAf)E8C%CNW7y-=$;A24!-RQ9j5*@PY_Y zV(a6jq%0i(u)$?4Lhdoj7%4L4y#&-bR0C zYo}IEr>CcqG`?{0+}FSHl{;>~`uX|1a&l_W_fr#x5o*G*f&;WH&#M$lA|YUrKtO~98pHEc zh^ocKXAU3jEH13hPT!1Rg)#g?07e8tB474+3Bl} zG2pNYgR&%RDxZ^vsu*x6RfUK=s}hnE07h0~bXZpa)}qmlJZ1_8At8y7gnWwAs5D{&($ed5$t z+rHcZsev?Gt#L9|(fPp7BSIoFVvSmXA)4G8@V-!xm6gSM!z5{an1!*i{Q$8K1w<}~ z#=GA0XNM2o^oqM)wYOb-`#WElo(XS!-H$|2ItWHRNCnzkUVpMPHa;wxt@eIY>JB%+ zN`DZ?$s9#(&ty#+MPhMJWTnjJYjIu;vUYm7<_-uuK;0Xx8WycQtAaJos6|3X5JEE6pd(gCTuBKo66OX5 z-gGaoF^Khqv_6Ne8hURn9KZ{5GRx#jA$pdPsb z_9#JBfQ%1H&LIX41%V+jB4jNY3lozgFMq}DiUNSB1c0buVQBsQ=KSNQ4(=QFs=c1; z%w3h)dSwJqVzGuJ(X=GUY!M9COs-N_Ny<=_WsYRibi5YNfkvX4=N;BA5kwrLnfy72GgwX5t^1RsG+##C;uW8zznwshE_Iq2I z5vN+VS~M~3qNK?3ZGb3_ryJ=(;T9`^Eye69tPi)JJv?{hu}6D{j$MxlRFWei`6l={ ziG5LC+1`ET@R5U8<}-{t9668bq9_C*aqV=(FjyU;bbYmz=Q)~Yy?#jPz&+o*_~4U^ zSDij~^Nq)!eDtgLf8(>Sf9+kTkIzIl#LoDNeV|%8QmcX3`*)gcOh>geWKi5~b?dDjNuf00G%5+Y2|x zgP_~4lp_{8fe-?rB?L&%q)cyX*34@E`ukVk_kErnyw17rT4RimSx81HSR)H0!6XnF zMJ{9lB2mgNFP{y9fV?EqaXcPXn%;}jS=Odd)erp9|JuF%(wE%$nscW%9)9?~%P*h0 z>4q18O#_u7C&E);;PBy}Y~Oyt`nsB)*^!jV$S--F4F^+Uun#e8)S z1z|jRC0w%^G8Lo#K&Y^E5=Di0<4y{v_(`MUtKR}r}q{w-LyxE#mtd>qLX1!6i(jWD@M0pfNy4DKE zC&y=J$EO+sarN9_<=h$%`x}&q9h+`_`)@z=*yE2KIlTAs7gWcZN=gY{0C`)8=SfYB zmOTO?c!`<_h*2wX^3?Hr?)k=h-uo^<2S5M_fWT5fSykQDlaEeCE;f37Jy*>wdVC?1 z0t6TW$%@%nA#&wCa=-~-oheR>%(FwOrL0HcJg{U+JZv!cq(CF%T2z-Hh{$_KL`)ul z5dqFZ3vT2L% zcDoAZ!)Sp-t>6??>U{w$B3TD3jqsJopIbRB6gnU3V2;K7=l=8IZem{c(#r!)-~0Ce z+g&^KoX$zH(DE|} zAGqnJotIv`6Me2_A~BVWQuyOXAKA5Q&(i79)*XA+2CIcUpL36SMogkU001BWNkl*EvaYvt_pex`^)cy=rR(12tINl63ZjM1=*y%$1|fbB~@S11f?55Cg?V z0~0$6P2ng25bdXnvp=al_P&z(Mc^c+Dg zh{o!TnVq{XYP7~1t%k?)#M1e*t4mAAj&7Vgd)>8{U$%eeg_HHl+RDFu@I%$%u&z;u zN`}Uu%7;0F^p?0N6@iix1v_BUN=6|XNzA?^Ul5db)o8rrz$@Q++mlD1Z703g{MxUM zPfiF#LBQk%3hyle6M|6EIje+JG6V(yM1-Tq4*$_dKlq`$-Vf*iJp6(HmI9oHLEbsR zgA*5Qo!Myj`(+f*>`p|O6G?Om2tW`hivgj~ZYV@unP%>6;j9NCRJ~SNU_wtL;thbV zLeRog!n#C7MBWpzV`g9iVE8YH42+JPv(`ECUI>AJBqU0$n5ig=G|#2bo!+o4J%X8- zn2JnweYI^f&+HN0?54UgHVP@t@>+E!4rjfqNg0+tm!=#Jk5|muI56jyYLl}U6kuh@ z&K2MS14hWfsZ)VaSPfYgC_rKiUY1#^q-*zZrniFH7$+C0Af~7(!(J&cLMrveA(rlyCS)QMtTV7skHl`}o31E{I z4uq6S6)a2Dy#3BkUUJ~-SHI##KmOi{LNc-|PMBe$x8RcMlyt+P(g!8|N3s4?X+b13&!Q zmaU`ryz8yQHK+su(GUQbHB$f}Q57i27g~Tpk?1WmmzuSISF-) zjwFtt{^tOwyzvk5WW2?P$uYS!d8?BlI5t^7Xl12kFOD1#-%z(%eND!gcFdU}q?d6aD zkGt-;<2`^5&;u|40!suEXzO~ocI?OFQ6bSUcM7V^hZ8%z4nY<|mXZl5@YDd%f$Lfy z>Tt{=j!Nf2RO&OvOp<5s2Sjazo0Qmm{zzhfg2+tFYfSx=#=RGJHpb(6V z$U*`DJL`+mY7?xlb<;E_FI%ng*7#(v)9bdo0<@MY3~+k3nItQdQ{(9{Z?zUAw!GIw zWFl<0kJRF`aUhq^H^*l#EWKBua6T2R1%tI~qhxXOw&tUc96Yf16+WvdGD2!E*?}v$ zu(l*FqEMGEZ+8aPn;-o6$?kxUpIWcCW?%k_S6sMf?%zNEcTYTe-}~Nu+kuNV^*g7X z?T4Wr4U^F*Go~hWm?Ye+&R4^_FZ+lqLC`aDJRMa>d7AqXNJa@-8Y7h!fs~CfnwCnX zX}2gxt!8cU%$a(sd8-gevd zTQ)Zp5>j7csX>t|R@RPPuw&=q@y__fbU)wlL61zH7Imd&0C70l=(N|iZQg{AB>_8< zMzi2XD_&V{H)`9f(TtS5(L2`9o*N&VNCwgL*d^pDggqhp-X-Uk&(tR>y`fmxdi`^U z`d|C{Lqf$jzvMdS=^mc7FH_NmF1*TYv~|JvLq`@=M9sw zJ`XE~JVikm1_65#sDObP5I{%;D2P0w&`LGpx*!yuJr)ifLZDbH?>#$;OyMX1!1mMS z*#{dH)5&#X)0L{VyAY8h!q>n3_OmOU$?1i;nXMD!o5#mzCa0#Gt!7kFjV2#Ha`NPv zW1a5$Q%^l!iNY6Marwo&wrw7Z6{iH*Mz4MO3$N|2CaWg~fo!3u5C{Q2^j-p4g`=W$ zg^#poR1uZREh#Nf)5vCosK6kx6cTmCinuYM@4Np?XO>RC^{sE1nHm!ykpi#?3?KkB z=RPfb7V4@N0Wg*Y2LS@Yi4!M2c-J3(_`~l9w16Id0Ra#I^E{aulj+jqY5Td0FIr$z zv0`#HtM;8HRf5PATH!*pW57X--BHFCA}~=-l1)55wY4aJ z1R??e127;W`~v<0ATbd$NMQsE7Q{>d%s|ZSi2<5FRd+@L=StE08<6ZLu{=|_{TOTg6$ z2Ox*lDE`Sq-@o?e{f|F!c=M(g2{H4d2cEs}yN~YMfB8#Zc3|mz=b7i8{Na!8d+S@@ zeD#&P!L29(0s?PC@awMvz!8djzmgKl>tRI+SY%c5)w4$SfQ?7A#~y;Bz-f$_?ie78-mVNQ-cg408dj zm9=Hx7;aSSMGkpR^+uy~ewY=#zLhFM;Y}dRyr}*cSK6|$f`u^wGk_3)SUSs|l+cZ+ zYCtO?Sz0fxV53MY?>#$;OyMYC#EqxRvkx?Ds+-H&%;mDVyOd$+9lrl#Uu(_Qrsk%n zCTGK-!X9nmi-OKCb&elDHXN<>hi6nUyz~Xz_gpYHQEx=3q)jyzxlL7EpWk}L|NQj7 ze*eKU1yAI@0w@HP%8nwzr~}Ut`MTg#;(3qCK^?tgPF>(ohgife_biLLrU|WH{?Y?s z)L&XU^_Jgy?ZV7dnG{hp4g_mU-PTM^1=2ym!jJlCHgr)GHJc6Zh4*%OW%0v*^!^Wg z;C2utfCFFv0U#Ivw32Qpd#7#h$owQ)a7&$%;vHCDa8h_tYAA%&(l(HSX4ET4_EQjH zox?htdR(8*bM3sRa>P88JW!Ym@W_N97ywZMAOHg(05SkEF|ZH_0t5py0|`U~AZAbO z5g8GgAf_Vq&o6 zdNw+^Wq#9>Ph<<*uS8X~RH7)6SqbWNPS%^kQ8^gWSmOZtDtgZ{DX^=n;0TwO%Rx_n z>EG|`w9~2Cx&4=4QXijCQLR$11_-_N?wONE?)~-`|M74B+!pJtDkq~gTaEyISz7Or zLFI)T4*QLUk&wq4qIfVq;RQ9BCX+HRDJ9{7JrI%g?5xx*Lne0hS~Uu*-Cn<0n;s2!W zFMHv>!^h4ZJ9+BFsmI^>_FH$%g^@xjB4)#mg-C^9vQi7KPrC-X~h*MYgfLa&q&QiS_ktc5)y2&@(%7EI^r%kqb8* z6>aN>o|U&1@)%T06mm2iurHd8(3T@tmQ!OhgTb&UTv(}DQduENho18&QoeLi6a~f< zMd=+$A&m}*7=-{7#Ec9=DCHqmVWbQiBH@6v^x6=4wmu39M*#qCJYAlBuvx=S2Jz&j zSl^k0$!v+=d4z?sxh>K(>uhYa*Vfn9SBJxaEt4eO*t&IU=g!Ibt&MsE0ShAoNlN-$ z3+Jqr(fG`kYya=h-us{T9Ua0{PSrrm01{npY?*DAIk!9ByH*sI(-Wh@i}PzNts8IX zXgbav^v)BKwsNG3{^m%&@pV@f>51iYXa29Zy?&}$RZ63aP98q}_kaJnH{JGzeV6Yc z;ZC1De$O}WJ%0F%R>AN5&hPHrxrG@{o;vc!e{$CyA9y!F!DtZx5sAThDu6jl#;}~N z=At|Un4H__7iJ-v*q1@z1O|#YT zq6KdSfDpoY)>0Dy0x*Dc-jQQw6o|+GETvQ^kpTrU6Ojc3DFhLXMk%mL(|n`d16EVh z)6MZlchFA;kPmU|{PwBIdTE!ty;DBW=B+6OMYy49SyV9y0n zElz#v!1agu%Gu@a%K4?!$8Wyr>X+Q`0xb%1eI=a`BoUk^YZ--+$^baPzAbv>k|JLe zs+SBD@(c^f$~mwCAPS6;Dv(0y0!|N$iD02eltP zn%w)NW7l4F-6i`j`o@>PxVHMlhwge4*Go9^sj$`_ zlu2$p1cWrbX{^^j=UpzyG~#KE4TFI|H%w308fs(JE^OW_FdQc55_>`^#kN(Cb}KQ) zn0ij7sN}BK?myXV)v{4kiFQaaeSUfPm2Z46_wd4NUc6=d=BJOGJ^1X;iqX=We&uBg zGm}9O0U@xHa-gI|ZzO1EbMo!M=u{lkio!&Vx(Kn?*@%qptZ&TEZABS-3Q8w+5P=|a ziB^Rxdn>D_r#7|P>*>tY0q+d~IPY1okcK2XpXRP>c|@eViVk9s} zF{(Ft%hvk*mio+ewcA})Qneam%tBzOL;x;}G}xpB)f`*6`t#p9_}5?j`AAG=PDj$! zu(xAYz2nUib`R`iaL6 zmnxTB%+`Y2e*M}!Iks|k@g2AQ%4D;mm3i*5qo4cCzkT-y5B$yF{mo@pUPNgB>0kb~ zv(bP3>)v$lz4u+P=fazAzCj2$dFt>-|HlX3|AF_QC_y-8@16Ia9FddIjB7#eslVuk zM;f(~H7~Wr80LOC)tc=E;iLEM~X;*C-fFM7m!FS z*cA#vpiJ|kR;e?v0HL%_vn8|wv^(e%X3c&ie|qv2>#sS%(@RtSL*1^_(`%Ix^gom+qYv*n$8 zu5lbH6##ey$1ZQT&&Uol#UFtk{^toZymD;1X6{9cSci}ZxU0Sb*d^9l1X@x`AbZL5~3gp+;SHnu(L35N< zOf)TnT7NXOoTkNcU>FGEpecN8IE*B8`p0JH>dWT_Gt)bas(T)c^3!>q1$rV7n<~+) z=NzyE5jdZoU4Cp~>-f2)l`WgDcKNI&@$8W!U;f7ZmHOP(H@tLmZt~da;|Cx4sm#(> zzVzljyS51=#5@QF0uuDfh`?J{6zgfeY-G)qQEj~GML8Pw1p6|}#+p-FSEa5OPD&Lx zDxDpL#`&_hbpF`He5=#VXQvO44*&%*d1OFI$XU_LTo-ley(CwWGITH?;Jhe^DGZDt zTMWB48%|D)dkexeJjQ6M9))))y9^PvR)uqAQ6dVX14N|fF#`aic%B3)Sq7+L6KcbR zmYmY0Ljdawu0+nW@SfJ5^ve&?jkj7s z7!p7lMWR+UgMLR#{k$@_+Ejxe2A@?!jX7CcY0kdz;S+;*fBZ`$IqpbSM83J{-t@Yw ze(Cz1_y6GdU;o2bF1+}q?5RT^`-^Yic=@Go{?#iUdiw0t42LdJGBf`TBR#)ZYEA`+omjzrXL2J-xyDXFvOo zz&O8o8+pF*#+&BmHaVA_T{`)ZkKXZt58f_R>8U7f!Ngh{9T*Q(=AK7TlLcg_&@DBa zdadg@*cy!Q%cR7_BgMxim5pOb;^C0SUTDX4~e(m||DM68g7V3gnh5`;_vxw0U~ zT898=w6Ud?QZmyh84dt6=YhPH zKw40*x4LcH{HZfbn-_MMwj!gkrB3pL2cA0k^!drjUE8-`xM_B(UWw8{x^(8$iKEA| zY@kA#ogc3@)Xe0>_WAkA@fJ|YzO00rTv6s}U<`m@kie2b0Z0Z9SOAbKlO#D4gn60O z8}$o?HYFE;tQD3?76pOuuH8Ou!rWTRU|Owd?*)Ja6jDh*0$>0}0AO@b`{yq{er8R) z=$flG&y3&q&AZd&^+kTe^)I~S;@w&m zC{~nAxa3GzY;LXX3`fh6Zo0DCm>AD|N;WI=v`9u{t%+u9#*uNPJV^4Md}^dEi|+E; z>B;%#MlYY8+D|?N6dt?>W)L1IExNhy31x{T`??fC;rl4jlFLg^&ZDzvM;g*rt?C>~ zGlsz!>DV%X&)8=SC?%GTin2fyT5Dji&JvM8A*B+}15~I2G!+wQ0|X^|rO8By))hW7 zjzBT<+EeB7gA*+nl+2Y~rP*AFpztOB&(D0mS#h(|_10K5&H6^6KyalGO&ppS8S^Y5 zUkX7&P*kZp^3El(k)cy;E4A?hBVB*{hyQc2%SOk>_FsAZj;k-9J8)p@{STh`-=Dqv zs+(RuHEyrnf8p7+GavipH*b6Oi*LAe->3fNn_Dh;!SDR$wzs|WpI6dS34hJrng8~d zTORu1{nGY-{nnRGPc#t#Sd^uE+dF>u_y6GcUvR}G$BrHP)TjQ!S%1;q{ZAi!=H)Mc z#VcOEs7L^qvoW_zz1vMB#(bD5<^o&b!i;62nS33B?GqB{w|Qhzn-D+`*~s z*9~opR8=YEi;)z_d|X8$DGCsEX(lbz9S1rH2qch^LQ8=tGJq^pIvu7;8l^OO&`O^^ zbt+4<-Me=ThlBO@N?Bw=5FlwOkcH7oDG5k`ERh8QfKW==!mY1&KKe(0632}Xe((dW z$!4|LTwhH_U8~S+-#)AKz|lsYtqTE0hf-=!go2~USF1@BsqTOr2cEPoiM$Ua3UWn0 zoSGV2ZEr{uS#L5w{_M%}?t6Z^bJwL8?Z3EDpUy_<`7`HF9C^0CacBY%09=5al+vxIW64ge-u$ z8nj|>nnpXfQP_@FL6*{3Ym<_yDEs|E*968}6`Fb!)ub}kQxNLq<-=0vQd+^yMs-6VuynxcTN*V`61#{i!D&AN5ynxc&vZcTEbhT&q}{6-ESP$@{+Z zy-1H0X=JK37Cuk=^-9=TU7nhrc3uiqacryy1c6*gQL;;V!}W>z@r`adH?`kWfT%n> zkHn}5C@DIb?Mmec6jEKvD9t)07c2oV@Rog^q8rtNtQr_{ie*zqQ%;2?d+-^#92iic zC$`>!Kq)2v{}4bR0w4e)V<>{E4zvNrlASVSDpHiTC=nJ-4JDT~)&Vt* z*%D3d{mXy**|&c1l%nvG?elMV)m4u_dhg3#b=|>J*+Sph@XpU4S?<+h{koekx$e@P-}%Pfo5yRff9=aBnhlib zy!Fg)eDj;%``-6nbLEvsj~@QSpa1!lS6=ZOZ+OE!-}?5w_ulvEzxs5g8lE_D=nwDs zgS$R*M;r?fzAOtOk06+#TB-I2Sy-I_UnpKMhZ&-Zk557xIkJyCd)!V`Na zmg1U9ijfdi5DkEO;e-l=BP6GZHJ}hGm&$1w1-cdlahjx25U(t++;;<;xZOGans=fZ2Q*t=uvCh}#oSq~%a!Fob140$4F<0xY1 zoV8jTA_hQa2_Og%KmZV8!BmhdyS?MpI@_XAuU!a2mXM(&1Q%=5-)N6|-C8xy%c9;G z*QSahEDA!2N(;{xzyUBaB1>T9p!Qdv`(8WIx4!ySTDZHv{FRB8f9r3(6kHiVAcZHN zN-0L^`Y1nT0$YrdMk^ZTL#eh|yCtekmuwhoSxI1e!|W`oQJ!a&pcZ@4(mK%g-13Rd z^RuT;F7DjEpGiCG)4cC|%HV-Tqc*Ko)e|T!lBBcIS(=!r4hQMX^mbcBEcBV>=O$*R zjvY*=HW@wwGRV(`A=lGHHv|P-?bb3-rDhSG~sSsE;I- z&`dU|L^=qJE0f_c*HNQ%l1NIWft&zqq<6lQQMl2i*{S{H14QM(5fBT_z@ws_mK~`) zu|ldz86~5(mlh0K(q%@{+nVvhu2hUb3QMZWXvUk!OGICgD~X8(GoS;HLI40WAp$Xx z^~_!hC8T7=Py|(NOaKH9oib!1MCZ%GsM7gJDeOFxFFnwx$hAJjQ_Kkvq=9jO!_>-Uc zYBag!gMV=Sn|}LaBVC!FYu)}^x14?MnTPKG{$+bFc*E;{d1|T!0!mjB`Zxaeo8R}o z+poCf1xY{o$WX#`pq|e@rz&n$xnXz$-n#yA>hc7XFmCF#eEiS;yi%#Z|NVEWNPt2hlMh|JS{sf! zh@&7xEuqnv93Pvh)@mrBu)Vw(N&xSyj3BoeARw@0kVF!Eo(x;9>XDO&Ds>aoWVJCr zOeeqcrGt+@(m^?`0<-_(nF}tgOpJ{-%~WF(FQ08sO)L-#p_GtDO2foimIX>nDP36t zfKr-4001L00E0kq5^{jD%+ucBWUWEYwrZ8#g}0_6v%DY2YS?L~{cfvP8w`p{ZK_h6 z@FW2PN368+V2KL=55R&ESR)w+l~4S`mkU*U?X9mFblUfS`<^}9Td%$KDsJxbN?-3#Y87KNAx+#$lc$I!ZZRtnaGf>u5BhDl$eYDzU3g_TI1IC*&I zuFZ!IAKJI~g+-=-g3^w1yN)tT)6sZqo5DIu$qW+J;@P89Q*pn)F+DX;z6z+%u01)u zX=2c=J^j?`-FN?RcI$-~UGbucsj2qL(o;|TEFGSI$;}teOqzNavn>M+)~(eVPD0Sz z@T`n7(iMYBfD@CAUbo%r4deQFUJ3vsgdt}UT&RJF>aEF6hi0etdkPShXGcJur3Xs# zcILWLc~1(tDrKmJEg`eQ=U$Z=YofZbE;&(Apk*~HE4sSbhp`AWdhg4^dgsUz0wFU3 z05dR=FU#DPB>+^yC^ z&@*K?m(~`(_5G*6{>A%WcI|an?7N^lYF~Zr!um%1m2W62`cYgHk?_YQM6~Fn$UzwV2 zf&@a&Z1Vcs-tfWq-+9?Zm->=^{@~BQ@ULGOo0>dy_{jTif8X^lz6KGFoj82wo$tQm z&iBNzR2oo#l!83i%xTi58n2XnkfIe=D_OsL?6EqmPfmv?SG#gzXIb5j@kHvZ(mEcw z(zfeOGwh|6Xspboi2@L*m!h<4lyX{FG`X%wW9F2c)H(`v_{3vR{N#ZLf9uV+jWz2^ zf-SS67$TQNkra6%gk~QI)LEX4Mtue!8m*-8&JKs^us8bJ*S>zwx9*GM>Z@kf%V~w#m9%By6(wY#%3Ii~gArU$;L{&Pz-*Wj<=Hl6G3JN5{mVebDC|d-bgcw z8=C<`Wvcx_8da-~to51F4B!A5St1$az;WeI|LSw$*xYMwdDW>yhkyRSkFU6F`^#>= zNO)Fc1X`(_b9ryLRBesc&Y!R0^w@YjC{~!KqG+!b+RMQEvBF9#G8rX>Z)e$vt#27Q z83#tl#j_`;=PHYfr*`eQI7_s`7GROt^QB*7E`3>RHMS^)-bpRSR@Y9cpzFP@SEs|E zW~p4+I5a&we)3p%ys`J(lKs2S-95GElFP2VYV%BMd2#XKpZ;iV`QY!q^YzosRxL78 z6op+PTndP>i3c@%YY_wWIXMM5WsCK%8Ag-gV0EUQ$tQSC%?P%0%j90teVs>i3 z_W`2v;60G@=#jFrSGb-so>(zel!(Cf2SqRA0%TQS#6>B~jj7s5aS_OBl2xMCHW!8% zXtLxBTiCMnB>}S_0z!d+V9UbVoIPnJ!XS`J7bOKUsG1-MkkO%4hPAYg!Iy!~iqas; z{vmh%p=MpJ4>_E?v^1M2Y*uP9{^+rPDXk5|KnOh=rj@v%Ra|6FN>i^_hogQN36$2k zLYs*lNXRR%r5q$2m_n$s=67r%xQMvujH?5xzKKxBu<)|N6_Xc;ywBzd%X=Z*7@) zp9yeTKFrgR(XlO+(NUTuoz9xIWi<}tII=}~&pqGzr+@fNuQ&9b0uvMQ?u)kn+8bYc z<>l8%40@eTr4q!knwy(3GLl$Ts*XZ>C@l3nk>M#J!lYb_YFrcpqfrnU1hB>Oxy6Nr zsU&Y#$8mA_*={eL9zRfxFJPV-O_!BR_ zcJFo9>_qR;O2O6yl;xw|U~zobpF4GWp|P(&SPmLRQ8vdWF3UW54AOkOa4Prx`Z#B< z?WuG{Sw%kYe0`8S zU8z(gH0zDJbEDPHv5D#C$z$sm?!4aSGmjiv|KI<4PjhnS=IgKCxiEd|`0=BMe)h~$ z58QRf9orW+dEYPHVteCYqtW!XI@a9otc*fwi_YSi=c?66o2Z`@6O;3R5rPH+EwIRw z_S%`LxmvfI%uXL59{@_vo`8uZE6B^9<)IFlSus_W42A1kS(Ln9r%(fFQpXE^U` zs0_2HIB{Ks6 zBGU7ik}^w*M53z1RV`#$WKznwRxO-tO>IAXV(`zO|L&=?ewfr+v%7`>>q#%SWu+2@ zVdO2_)T8y9-OkP9K3y7hp54E<_3=OX?}P4&EFtR^_kR7}A|1T*ciuTUISmp(W?7Mh zK?490ED!=|$ATpYfzCT66@xu`{K%jE*&n~}eeVVIfF6(l8~_U-0TKWlY61mp3~}U> z)ssKnGVQc%pIu&@UAU~k?V$G#Mgm)hY)L?>5{>nHNfgwC(g30)CzL=Xt#j6UDP=XN z3PN)HcYps++qdt1@y)MjOw3x6x%K3IU?k_mPRVp(mbbjcIbRfI7)HBx?JSBS41*{Ntt|mKih?}1 zM8=o^eCBAVLPIVpV@7-VLLTEs?1Ocv#6y>o18 zrgGxM$?aQTAbFE_JI*5~kOjK(R`QxAd z(#+-qzj5m|4}9;jryu?9JKuiGt{pY+yC?}*AxmfTe&^g+ORb!5&ra`aZ!A?>X;HXp zb!(`1WLXGGkRprTg0?=k1k9zvQKSGiLCLM<3ok9Tzajb2*wB9|e z^hls~S#@^uf-DhXC1fa)th2g)W_qgH8}{escUiBAL+2DaDM$)t0m#BLIxiea&&UW? z_?qxl0TLl+TJhYqe%KqPN;OS17Q}Uw$l%!vTl%ahEE7p20UpT_5fcC-fEGfckOab$ za1?|U6V;?(bY563yg+T8wgr0ySoLT(p3c`Etk?2h%9V*%>ai;_U3f9V2Oj^DWC(%) z5s64CC8c!EDW!xE0Dy?h?7g?n=B`MK%$80Gsijf^fTfD|CXaUf9GEWlAD`Y*hA>JQ&@TbV7}v@1M~Ra#&9kFO4U!*{;@ zo#T@egzS8-1Lau)le0yr0${;XG6FFpBC%ukr%#{!(1-85>#h%g@Bki=00@8tumAy! zPDla;tTb^*8761)-l5rP=nXd3y1cOSrh>Lg-Rg^@L}+u5Xl&u5sDda#pa+Nlhb=gd z*8Mu`!~T7qz4vc;=l9I#-g9S-S69|xc}A8kc>voO>=;ZaNy>tTm9CaHX;Q!>DS;*| zny#!iT_sHmESfUd1{*wKWJ~gZWewIWT}gMI&pq>b-}4T?VekDsy;8~_wEcXTlpq2H z5t&Z2<4eD@x%(%d|Kh#_NAG*b{VwmlaPriXKX@+2uzz{+p$Fczve;Yb=G!}Kb@as6 za&tH=r<3YSU;6Vu{_Ou1;?xj#W|DWj;~h^w^$d`__1?F?^umiN7ZX}8;*o$V6=&@^@42jZlz%4TlTgo<)I#)-sYJQ*ZOlIM-Va6BpMR;Qn( zttyCGOMr^9+SE4kr0E>WYI8Wg(&@SDs~ao(j~ndsRhI$cTA(0Rib4V)YAEWW3YD^g zPzP^}X=jZVl7#&3&LzM`pY_`NtaBzA?M*JPZJarBkwSrzHrm7PEQ(o+YIzV$=zz2n>8{QgVNJo1lz@o&%1N{G8IA;Xz7 ziNt!iv)b)o_3FmTzPpB_bupX7E^|wHdQ8#x8iVlx8Z-%-c_Be%beh?!oNT434hNfa zbF((dVzdfp$QqR}-3imp%$CK}cjxa$GUKZ~k#am57&8@__S*X_=c}717nd6sF0CCq zbZ_u;YV%s+$=7$j{u;9@#M*qFFkX1xOMGkf9AmhOI0W@_Oo_1$r`f< zYuA7>lh-(yR@ZC4Z5W6NVyoTUC&EeQ>M&m0xVV3LVQYJLZs|ZBj3S3RhNGYmFru<3 zhsZH<0Mrn(G&wd%Kq%O3f%mSho$t-e@9x&^-o7MjsZl^kjIZOgDytaPkQ$04LbyRi zRMjX92&z^nflZT^%^JqQh`5llTHzwty3}Zunvvr6E7Ohdb=t*XBKhoxZU4T~)nX^~ z+^MgJvPzN!KwZ}Wk|Z(4s44(rW+GMfH-rENnChyIl{ZAr8D>>N-s+4>1nTtXj%@Dm zpMB-YmtSAs7=>XW3YR9$5D|T7q>i;rO|deceDMAgKmM`1>dDk%;_G2*i4=eJ?eEo7 z^NAn-$=*z7JelV0rh;mzQe%xW2?#0#C8|TTmVKyFXV08F{cHc?pMK^uzYL0?2na|3 zWd#c>Auu8tz*x~VR*BzSzxd4JOk7;-z3}Sgx#hcTeiNJa$VOrldr=&YA?^X0ub4b+6T%Oseyju08qmi>vFy*~R^Hi~ANAm*(eZpMC1PAN%14bE8CM z6{=}bInyW$84kyP^hbaA;!DpQzvHGm@4D^oyH6Oyzw}F=X*K)5`k8;ayR&!c;^n8G zdgk1jbD#WMpStOTi*KMowpo)^y^({mx=kKWFxCpC_ycvBnu?Ji-Pu4^Z5gI57F^`I<0deZ6_SK%s)Y>wt zPqP{4IzA@OB#cO*D2A)ev=|JwJF~Z%tgk*W>twWB)|+V}nVZS8{?)bDmiP58Tv|VJ z@U9Tr>@rV2YWMjU*1r1n$J_nRyB@fEd3pb9FI_wN+{to$;gdgpd|`gKle8(!c4k(h zb40bT#}>raPsST{wVkF?6q2WliJft_ku~Vm*Iqif|M1T4WO4sN(FB}|utsG8K^Rdf zDu>7_EDBgnAsK~4Vi4I=tSg4sH!dDLeB}DtXl7bBz`O~7ssbP)0P#OkAtnZij|6p=Rea@3w$`TY$W1S;R(CncW}bWL z%6FfBbz`eoTOaIfPlQ~n*=S@m+qWlfTYlfWkFU%TNfC-+X5sxb#43dF{BtL-UL3yX zJs;}L_FR^EF+M7rkXb8rGz!b14&Ee=*u+>f6EjYqef_ha{i9$0m45;VNB{){1XdVf z1-yxop)?Ir zOqwLP!KBtUa+ebf+k9s*ec_ceTZ8Gn_r3G!l@FXQpF-D;Pmzv-r%6X&e6 zfW{b!V674r#5F{UVmzJfsYK^&RRuP--RT>ff*rA|>o~2aQG-OyT(g72)Xy$-Uw`fN{OnOgC}CljWacSL947lmZnAS!Bz6PKheNvyTR2`sTwcB+wMOoC$=HQqa4 zX-$!vk;2x=V&ktmt!hwcYvIGDckk4cVhVcZwXdbt5ui5!1Q3y`5|OHk2mm4i5md{n zs)J9g)hMKzIZFsZymi(l*|-uiEl|rOowU)ZB)z)2d*Q{8MeQ@GZ;^=-+t3k8#Fg+s8SLk zjUq)cO%iJzPp4yJ>0=-JC`bSW6i@)Huwn(`tq&|hWRzUghE^>quU>e;Qn|cu;oOC* zvx|qayj7U{D?j4I3m5ESS(i3RG_pk0WfgpxCP-5NTGo_iJp+^2q}85b*F1B6^_k~i z?eyozlVW#w_wa%J_rL4DR%(i3cW=Cf8`OrN##lfHgDpjEoPsycghyU=WOxZv9 z2Y=@+cfPeMBnCZj;9%mit*zYhmJHFO=Ao*8^eGa4k2#2BuvNC!C;UjNu$x4 zPRgS6N!rNrR+8pqlAu&obsb7YO=|L_(@0x}6_^qitLx`Fo#t>jou56x)U>wgBN$4E zLJB|$HwZyVeek34II37@Ma3F!<*lYPW4*h+{nG4wJ{ed2?#g5w6oJ@-6)<&WnvM2! zI&5S@I#H+)D-qtHq~buLO60uQS`)bZ-~H|vg1z|zAO1V#-uSVve__6dPyfXGo!v{5 zC?YX1lnAviw+|j{Zf*`qmqY`2M2xy5XXaYXMHnLlVHP;iBq|hQz!a2$%U4bwxg~q` z)C(&sZ!=~&#IAJ-P&!zO#pcGd3ybFZ#@6iY%1nD-S%zvlo>teAbSggUw)Ssstt~9h zpTBVZ*wH&hELj$gbu^{7oHU<(;q=4bc)r#x21^ixk{R_?y*!0pGE z_ASmqnAK8bM20A7fJ~?5MwDG+YCv19nHU=zYuihUo!#Ni!t$XY7M!Rugh_-|p#)-u z6*7^G5Lq3QILpo&31M$Mxi*<>%rDMdUEP{rI6~ASYQQ)UNEIMuh^mM9D0PfJ#twOc9n4S;PfrU?ThAe5Ex-Zi?|+FBj|I@3j1|;Lg&AZ2z7Kmyrs3 z?$lp6GWsTFCL&dhF*38NiU^392!H}nVvq=h#K4M#nMp)Kl#pbpO&U>5|K|m|Pq0U0zx2u3fpXbKljS1)k8O(xaqb# zUpsaBnP;B((EESrzB_NRVQRE8ma9;KpejC8i`kWR1er8z1jT4lFjJOUAB)7~sp%v(F-C~TN~5*wm-_wL zt*zULX2@Vp47f(%f_;^HsPdedZFIFzWwanLN*>v(`2Tu zY@^W_4tGV-@6C-yp1{V6#>%n+B*Y2^Knj8wfhdg4f+il>_Ne;Y7a#5|-TA;nAAS9$ zliz*h%Rm0n_q^rAvb7__K~+f;10zyQM%NY=c)lYqkeDnV%`{xMx#bPGv7NJDhj?V zsw?1a@o6(#9*u{ybF-(HTi)CriuASFUdE+kaaO4Wbs< z5s^qq6v>b>2@n+#8bw1C2obSm|nLM9qOysf;g zBMX#`aHba1qL=XA_N9%r)3@BZRF>P@JDaZY_D*kxT~ zrlV=GHyZCg{e$ObXInAG5cHOtZqC!LDl^#wD~IY@)~;{FsI6xA*s+_OOT72Ytg43V zt*z6}RK~cv7Gsi5ch+!Llyy)dVjpAWeH0}IQ8c8jW-m1z0s&=+J5|`8jD|D)#f|my zz{)KlLJ-IVRS+!Rq{ILO1RzG47SpmS*ihcc(lnvKNz63vtnEBAw~&rTQ$pL>ep&cN zvzetib7oDWuIsE}qgNKEU?o;Clo?8@hB(w>Y+gniIe+^3*S_<_^M`M{^S*c7^X-Qp zeddWr|J85&!)`kmGZLu@mNhXjA&!T;7iRi#_1gNrmA6})7sc*$I$}1#Yo|5ik{oaf zE3gU{f*L}yC&L)4P-nxP;@GhR+dDh`+2y@S zS;uHBH8Mk5K}tddv5<>Mgq(m~P$EDD>Y1W*Y7GxZlNepAwG4EKTB->%0|mGOAp!zb zVkIVG6;cI23?gDuK*az8j)>@+PXGWQ07*naR4_zhG+J*-NNottmk^_-8BN%Jwb=N6 zt5FT6vAz6$+dDC)AXL+Hr~e`$i@&C-092Kk0jMefeUm^V#ln}quAOs+IJF6bCgUjt zjYiWtE2732fK<6I6=K+c9g}51MS>w%MqP~eb~cY4I#7&<1~F}RIPKVEwyd1mtO)Ka zUw{6k*H-U&=RJ4c{g%fb`TmvjCqMGRyYD@5Bxh9##2TYl#HuRlx&*~2-WXO@K=B3w z$f#iM04VV*FmQ zQ)@|vVPqKhV26+fIo4WR!yTfaZ zMoyB&(C+v5MbRouTqXn~VxR_ZAOH#`kgC>oRmYl`(!^S4jTn?<-RS(4@9bOYZme&0 zy9df?YE0Je&oDa`OO!^5Y@#ZltS|}&2p}j}fruo@%Nmh#arvMA`NO9#tiSjDA6Q(N z|I4p_Y5nTy-}vu-(U?8xo-t5i#MF`%oeXx)&GgIb*Ejd=e+MWh3d7+xG!(_8*PYFh zHgP7JL6*ej>&BzKm6f^6 zSFXY|lB|{f?bP3b5r@oeuB_g~@{~9ynO{$7FiE5xwgd)aZj3JO= zD;`BrWiHRNrn62&3Bm-ZsisOq#tJ(nBLJc@tJT1cY+XzemVQ6Kdhztip(7^iDH?2> z9&S>Z)lK=I{@ouOzV()mef(qBu55ni(XaK};phMEClm6HRiamo#2RB=Ruk_lP#_{z zQN;~J1h4^7BmmL)Xnf=V5X7d`kZDZ88CRjaYG||Dtw!U`gvyKFr&f@nIK4hFlbYAjm|>xfv0BnCv!b?rltZoA*_FH9%p#>Td@>D=7H z%*-4Si3l^tP)I#U6Uwp%+eFleK$CeNDcDFlu)TQPC82(m_`zZF^=nc;(gKW<;DimdN3TbZI`vF zJX_;hjeI=XZa347_4UQYl_)uxb_faBB{T|Q0xm~;8!=Y5-g?J{3+D*7(dvxHWuw(^ zHfK~5AeEphiZ`$lfee^#fHJ_O1P~Mig2w1;WdmbDVjwO!64oSmuDvCSHmgYor^ajF zYv#pZTDO#-08n?FaU@MfW8U;e-sd-0byEB%CaCLYaEHSCbOI;F0<@Z z6&i_@R70iAVB^U~;vj&Eb*3e?;b@|-2fJ%`-F4IXb0-fUzB$BZRU^$C(~97_d9U-^ zzw?EYr#J6^-v@8G<-m8p{n+N}`A`1nL&pxy8}*DpBy3347v;FBC#r!6`Uc!UL;x8O zga8Ohspa{e`r&l6 zQ`eWy4m8qNo5MC_ywv@wKnKFF}!+v!u~%bbV0+G0W)s+68O9VIEKF+5Uk%Ukrf- zk(>`w0EUr58883?AZ5HkiIhkMK_wD|NfTqr^7_{BwfTkKcp|=NwHqsGmMfqjsD)+% zfP!)@928JuCBKq_kOaybE(rYgTdC~!V!Z`l#JObi)aMF z$4VtyN)i`OpL^`idu}~@YJB{T_iqh7oE5D*txl}5J2=ZU?6zk{gOHh7XIcgkW{d5X zp}Z<^ZS6vTHs9LW9goMIUN=_WMj?ojS5pWF)kNTmP`Rx0>Zz;W{N}4mi}$_vy&vAU za`5$6uRiq@-|MXAa-)+~a4SPGgtwtKEi8JI3wVG`aNmDb^>*h)G?+s)ouC$6k2dgbCHT1UKzh*TATs^b5PNEu2PPe-HiAk7lzk|>;K zU6RC5%4DGmjf9{YSwXDCo;WCrDpZWGn4%+POG;AsIGmYjPA6e$@puq5hKdqNJ~s|w zb6EbffAKrV?|kRSKk>txYu6tB+SeE78h`)iKh0r6u?7Vq5v^-KEy{6>wXvjc0zhDZ z-XMxMkPwsv5ZoY+W187!D^C$NEN=~mug}gmFTZ?_SQ^bN%d?%qcrd6tvj@}W{&B^@ zX2{H5Jsj0Tw$yOlUe<4CIYM1crv|p!o=uxQm-TihVQXgsvh7Z9cDBE}wcaq(su+Y= zN2x_(3^E)}d=2j<_(%jc(K<;|nX4ZzSo%2arOp9S7UCi@EXF5?Rk_Q7&AQG#A ziN4s_JbC1%gRS)7<4?YF=;-m;g*hL}%a_+Dqv_4Z=DQuUzOmiwE>#n>TOILAW^nn+ zi@xHeg#$D5>7?8oO-B+T2;O%id&A{^!jTT_U*sL zC3D8MYwv+7hS6a6>cU+2`r7rSeTO6Eirl5S>`CQ!c88ai_V@DKz3}`i$M3j1#(3rG zxx8uiA6&d}@%(6SVr?$L;09&9iHN}jVkiIth?EEffK{q$0%KsEHJUIbNDZuQvbVlA zte)DMc4Xa_ulL*8)=*Z5-NG#|96gd|8NG7x5vc+Z0U#m;pb9`$@i!5XhyonMN39yI zG)UYXj+xSSb5^1yHB3Yhs0Rh&07POX0u=fNw(Oj-(btg5Qhjap!tvwBu3gzp+_Dcb zgefS^8vROj>ELa@`}>bxxHNe0gAXh&?tAPT-wI*!iH|>YV6kISs??xB97OBdPwKi5 z4XUE50Eif%8&o~OEDm4*Nz{k;u%3DIqcq=KjrC1r+T(kRgfs9IwTxe(M?uNbVYpPA{mhr@B=x^r{K zBqTntsE|<@1*%HyH&fESYH;mGZ5j|I@EMR%!acgCE>k+x-5w9=Z3f+a7%1 zy`6>^8CV-ct;QTNvusI*gPqrU{n6_B#{PrvR+$%{B#BJQtAo*nRy!RHFw;HU?(CZu zb(GSjNfc28VyG8qcsRIz_~6R_{BM6pDIt^YJFw5D_Q~)4;Er4Gc0Kx898cE&^5HKYzxAz;fA^^$`_u#Pe(#Ah=g#F>uddlTu$fY9 zQ0$R1Q9*WFsFv8OW2$6IRA(<-dE)Wwd3wh?@4x@>&9l!u^YSY%J$3og_x|30`oZNT zld!5c;>7@@zTIwh+6$L1p1b|lg`z6=MoG7OB!pa|Y2-;_!nt!N53DSmI&=2$k=v7e zw(>Sj8&nK7cFwmtAg)H^QLC|#=G_=5Np*X0ZDZ@o^1g*UYgp^ZR6qp~045?3h+>ow zJpLvN+i-0!rW6UGP+w8a8nu*3&Aw)XXj+=K!zxc-Yv)O=9n(ENrn!L+>l+*N{F$#C zAprCy01AadRq_9##A-=7#wwtIiFK^UMWwLwvn#$PC|fp$6$n58M?j$lFi;C9R2i`> zhJ@0vugg)R={l{JbFJyr0hFd{*o-Ds6?u1TihAaM_&2}*p&$9w9e3Qly1M@S^Us_( ze)L1{y*HsLP!oG&LFCJNQdW}?DpgTc07L+o2tqZKNpg;kpdb&53Qp2)VtR>5h$dxm zwJ0t(8f>fEXJ^y#-lYqtpR#tmf3aJY)o`!kw5P5cU6b;Tw{~w*8QW$`93*8;nVfY= z+Jb4Ey|nhocb@b}4jsOw-RWOjU7epz-*)Hz#MZ`YQBI0!L1bezyW7)Ho5VG;Jd0Ws z#a@gRz$A`{0ajsV+sHdvmhbJ2>Z+cdox8ypqbdNinj5UOoB)i7AQDuCnG7*0Ap$~7 zhR6^AGv3^Ojm;>_%xEv{U%E|Vw<<|MN#=;*W35nP{6CZd28a}Zk_r%+1qePARXM5a z0nyI>1N}1W?G04?LZ^9?N}D(+PlYQet2Ur1)POvwR#GL9GC@g|6(sBf*|hzGmri~0 ztKYfrhaNn3^Bpfe|LnIP{_21K>%TnHwHmkctoD9tOeV2`kXbe)gTd~rz5d?n`o{9g zyBJHc%8jd)w$`^_?e+8RjnHWy?soQ9UIe9aRz&OIiDA?B5y4p8ej{%g_G8FMRy)!P(TX0a;@2r+MnqBz^JaCvLyJGnr1d zwm8f8&(GZiNy?%i6lJk9-rH@q+djCN`IRapF_H_Lqv`dz#r)#svokY`S+Z!TtKy7B z6?Td1(RjC**5k><*ph7xC;$S8n7~X#j2npX1|k3~Rx4H{Vy$(W805$dJGdBJ49<}z zdBrq3S8hJtZ@ZmIobYm$E~ovuMx#YPc=am@TY3`!A_AbQ_-m>PKvkh+H8sMb-ph12 z*{-ExXMtpPc7Iih3MI~3LqH&k5r7(KMv|x|1SLdJF&?is8`@})uO{7gdvCZmH@~>C zKA27?X=>ScV~ut5%Cmc={rA87=bhdi?|Aov#QK%5eC_aoUz19zO{=Q3oRTJkK{Xu*71L}sT?!wH5NeGCF+>JR-V4EWyEENxZ)1IP zIxX6r_Uz1TnxMM(@Z8)MlKTc{Dy2o)$uEyJ=BE2}6#KrH;)xVVt!m9NWQXC*Q7 z8rne;BCvx%LR5vq2$2u~Wq_bW0I2|xStM3fHLk0PN?=o_jcKb%>$}%m`Tpss-)r9r zX(?4O6EP*gDoscRwV+7wAXR{r7)lBPGywuDsjOviMw47&jc37lTYf-LN#1Ws5Ft zD*K=UWe~A36hR(&(#l-++H0?@ZLU7|!qZFpmKWydAA9t%TaVqkG`swP4}SPFzxK<& z_OE`;kpAhP{Mmcn`9tgL*S_-QFXwKN)c(Ey>?8d-jHgq>t#X?77qcl=5qn&(n3ym; z)0E(SV3(l?8_`r(u5a!QyN^C{=EB<6-2Rn!-S^xB5j_nQf}|8m7!=f8$wDFNyHEgR5gkr6;N~pO8@~1wKmK0PL_14 zvT!b}uAZKqHJh7PmzO`vPz%6MrP?0vUD(_>*=QF1o)eY9ZYiuWCa`qp1>NJ zG&3fX5LCReHBi^pc(`}H(Z*=9(`Yu^%|(qlQ=7;Eh#Ex!Wq_0`Hc^!&l7V3+XpCWE zZBQ+ylilDeYq%_`BsJ}By1H>*XwvT-EGIK_{o7O<#6h_b3JL}s#3>R{A_6FC43-_D z5(KJIU|jpz7tVkAFCV@2E%zM1>%KE*FMaRZU;3%P_0S!+-IO`8R79C18C7*)YG_Oh zm~=GQJ>6;Vu5S$Xtvo>JX(Z9w+RDel&hE8Nw>#P^d%Z(!nrw3)0suBnA|Oh_sm5#`U+lJ5?z{Kh#||&Q_S*Uj&prbke)z+0zvH$8mb^t&*{kYn!{M0&2l9&-&u7_E znk|)O*6FMm+W-RF^757E_8sV5xpMW$p|_AMs3zs)CE}2zwkRrVyQ!O3X)-m8v1PTV zJzp2CssM-x01>e=2~;)4P}XJT zE9YFAh660s&AElaeZ_fN%pFW>OW202mZwtm~RE>Gy0o*14IR6X!zo z#OJ7ZEa94Y`#pa@M5Y!PhF%zXQ4d-UY6TI-!neE+)kF>nJ z|H#n;%Liw@pF}^=SdmtUg|CXl@%Gl%a5!dT$RtUcrD;aO8q`;@uImuQ``B!>78aIN z=-TQkh-28$<31mbpIcJ;JTC!285|l(nLPBUe+o*jZ7}<0$hQV~St#Sh?CCzrv zm>lE)3lKmAh8n0P1xzJc5e$?W)-Y5H=Ay25CzDNyMV8pQtf!M|Zf<{B^VIJOZO_ge zC@1}P^MFdiR+WN)6$B{2f;0+&jIk=QW@SWJYvK){+UI}x$B%3bhxdQr0hi4_{=LUz zarS3_=11nbeT^ZtQu}e*;G!xOmNX%S#dNfHF;8}PcFU!u2f(@Ngj5Y%Ul)VndaEP5 zgN?cQL(mRUUttu1t&IVOZ3xjB*J-uRojY^#)fZc>{MOr!B#z2*Z{NPTz2OdXk~bC} zdHAo=tg*Dba@Sq=U0c0AEz6@vkFKq)ZfssYe*Ez6?)B+(&}uc4q#a{JVWFgIp#<^( z=XPd1+Do#+$E&-8vz^9@#sj9g{PfFb9{%PNS>Au!+uw8e$l>$n*Pi(PQA}F9^f{8)7R8RV7l867+@`;tk9OFa!f4Cc^})kq`lm zY$6OmRzoTk2$jie6^okp&P*>o-EYLry`r)5F7Dq3+n}iQ{TDx%CV7%%B0@yW9714b zeG}e9L;#2gQB{zrd|>r4nif-o}x5rwif&X7?hD4>WE zB}9?E#7-OOjM2GHyDw0MQNy*Cdj35gl0cMcG|o+ud?|{rmTQZ#gH6b>#8$04NkC zj1mI-l4Mwk%DlJGU7MA1t(HnezSAA_{YYhWUwve}^f>T>CS#R|isGcotlFJkn$`$) zY?4a7I&@BJ8V=gM_FANZrhwuUvPf8%UkW1DiHVYtkuh7?GB3;01|Jj|VK6#wwnnnF zy0WrTmM%@R@rfxDM~VnTAXJ(%Qd(&SDga9sKuLis%t~odW@y9WV6f=&K_#nodv;`W zD^g;jY>?+Bis3&KLQyCRg@TmEps)xtAOHjeJLs*Iwi89HDIkQ6^|jHF(W0Ob>PgKE zigS(nRCgmC9hpIj0fV3y&;lSBKuEwaGDE2}5=xo(w2mU(EQ)|yzjtcsEC25k*WG-} zRo7p2a`xi0Pd)X(-G}e~;8oxd0~;+a40Qs5Ll8uX2vEtO+c}q*_WDLKK5?6lDx`)I z0*PUkvh4Ko3u&eX13xjbpSgh;Avx;`tu?a0(OX=) zsCB$;dS7rl$*QE{Uav4wLPmRUwF0HXV6a}~8-xB@vsq1&kr0|98h`}^Km;uSDz1C) zlGx|Pg>L6;C7nXvqOz%>m{VuZee>H-kea^#qYq4OY0b`_d+n8@?Ajl_@1_GY^;%k_ zNjUn-GuIv3H$Qiw-Wu%=h9;>BRI}<9q>2y4%Emj}wpY)bI(6l~JBrSvf`&xT_Ikr= zrM0xQF*Uiv#B~m+O~NceJPQj3LH5FknuVA>A_B6!kDYVg2Sr-zNU4ZW0T4>iAPPJH zd(s{?0x0$=mw;eZR!UGrXpW!Xpw22~V-03p0jP>=vY2!H^9gNq^+LJ>F@;m+ooQjkO@ zANCNLLlMOY=n0Z6-KAr?xbXVe*!JFLHZe96LA9GRsB;6o?L&2m=BT2lg&FZDK(R!85Z!;P(aR zoOgl9MDI(qiU0^CXb}RBz@C&xg8+(s8cHCrDk~)@%&Buazwq)%!mHgP+i?T7t^gWS zZ1BZ5za@f|N(C-M#1H}ihzR~8xJ*P)0099&M3@->1W`Z`(HLW$8xDse5=D{LT7b*4 z6ow>8wALJ07!)ZYO{hR11Qr&hNU6fxO--?(R%DuKQcbJzFdu@-$h6MQ_5S4ZU)_7) zhU;#;d9%Irvmbrq-n*_nuy2djZhW$mm+gMu&AkQE+N1a%0mYX$->-)#a9$ zot{dw^z4~)uJp!4-aAqp*v3(0bYyf?6lLBolrowkV6>$(CLS3XYc*S18xJ8Ml4vAS zBuaa&9U^FoLogh~L^#Nod%d|hMFN%Qerj@e2!`2M2T7U*b^r_@077t?AP8#0!gh4z zin7z|tT*aS?|9HFnvIrs0KK6E@g28gp*>3C46EZ+UhQ)m9}yMKSzJs&!F@S5YtXJ3B(>5qNvhTCtL zfxKOf>L4PvMC~o-LWC+ph>;PwKj>V@((Y!rtc_elIw2}Sgg_&rK)Jp#TW!S7N(gDa zy442+@;(enu?WO*`mJw%cVS`q?vLCzF+LSVaR@#x6X@WAd5-F9QAyH=}@#_70lCJ+f0fPJ6>P>>T4B=E(s>uizev@CgK z%lMG}V2G$H3#-dt`pUPf)tOsvxpU{v9T(2c9(nOOS8V*kFFZ6h8n@Ta?AeyhUp%vS z&%u7T-5YF}$au%K>R48*zj5@%TW`DN&7<$`-f^>mU9OD!{s{n`Ce>cAtky;ajD$$wgR{OgQ36EFUPM?}I54vhmoS3TN^28orHM3x5Ho=XU{BhkK>;m34HgJ2 zr6mM~Id#tD7hY;5yw(|HyRO656@XJ1Vtn?suQNlV(I6sbMnt|0|0{5rh=2egfe14L z01+`l2tjL&h|c?>C_)J8|3}U{TRKG4T1O_*Izm7IRH#58cmV(+ii`*8<%6P{jR%)B z8{=t34~n6Q#tLT!7JvHGYcCvm?}1M|lvLEue*C>!T0Z*7{b?GOSI@LY(v8k)8EjUq zA|(o=NTLKI%}PQDAfONseefa>$7z<-wMl_VIB1l`r3M(V=1fhtj#NLJ7Z zFtQe}YH8i&Lz{ORRmGuq?##=Bjn}qKm_}`Kb=_`uF|AEh>XRx?LF1wjD@g@js((X4dL~5D21KBJhHtKj>eq*NS#` z*egea7z9g5gc^hc=UNv?zFKdsEO)YW+&O09w33vib(Wuh{z$Vi{+ZAGlX`u`dr9KV zc~3+lhzQn|abyUAh|1Dx9T6!J5D^Yc6nee2UT5{+|M4H)eDgIQfB3=IUVX9J7!j@t zXF|ECu3!Nm3K9;C95{#;m84Noc3E)|LY$1EN!B{cYa9N@KRT7h+dg#refwtioH=#& zm6u;%T0VQ<{kP2Q$@cBS3$yQGNC+YL{z$8aC@Asx_?8pzzJ1`}{tI)<&F0S7Y_|n= z^CQj1=rDI7sL|2sBxwx#C87USUa{)5ZChT8Urn^wZtfK&vnrqBu^7lpEGOT``w2QA2@m9)t8?C z;RkQK>drf_Z#Cfj+==D2izd-glEg{HsMJ6lL##!SK!6~~EW#p0CQh<6trBXDDue(M z&dr|QzGHfAWnpS+vMdjSvZ4x9B`Ajo07_x%tteIsF!%z&RWsk)cx&$5E1?+f-L=z@ zTAW`+Z)){Pla4@CV^isrHf}beN;VA9@BbfP_-}sspYNX8W38`MWA@>1zxger;X}9G zoJ5g#dB3}{v9^K`OeEDT(poVKp>ppNLLIDVFgAC>M4%?ert6J{*Ww9~i4e5{rNt6@s$Qv@ zg}L*?Vc|+ilDe}T$8oKZt!^yjMJLNrmy?c)tkF;6+Uhb%sQ3V=9FP-HfC3N%2{}U6 zv5uI0Kn|FBNP~(Wf9&YVW6?toKD_T>{p5-FUVQ$gYj2pm?Y8MqEF|QKH3TLUWdxMB zEDRB0W>BXQgRF0vQl%H2><$tWFusq3gFp#T1Sy-f)*!cK4k84gf=|7TH`co^Jpa-o zkN*7R#5Ny5tC$&yly#m(Ok@Cn01&v_Yu9T{W+@7X0LB=tsmOaKLZz9@?mz!;|LMQ{ zm%qMy|9BDBfvfBrLIuzO&;tOX_TFn@MUjTMTEo(9TB`*!k2ZiXHiBg5FZRCh7eCfC z^MPCMJbd-eW5>=Oee=zWb8r6IfB$oPclgYNa=^`6MR;Jy0mJe_H#YTtK13ZHdMB|SC9Kq&v5sR2V}(Pn+~Ugc+uwa5t&H7r>rI<$i$8k& z+n;^pqtnw_uRD9-z*Kj*wzP85v9DAbag-4o#iUsgB0~TO0RWJ+)=843Nks&-*1>xS z{>+Pdsqs__j zCQ7lqa4u3TY@HjXSqumv1m_%)2GSsCRKgyE!(q2@Mevp<$EQZeMlAt@AR-}ZLZgHf zD`a4=iOZtj>uzWx0^T!@j_+_*rE$Yr@{W=u^WFh^Knv&qEkFQdVZXjUkC->>6=P6> zRSK0-Mw_y*+Qe~`49g-(@sDe@ z^r4@-==S;I96$Ta z`FefljW^xAbN9rlv+up~+B5TWZ+`N@8+Pv;PfcQn8|L2yB4SMNbTyiwasd^)oP9b#J%otq&3m&=ZGXo0s_DQfG7eIAczQDf^dnj4D+G2 zHce7(vYUCmyfl*LYn@)a<5p=M@|Y4U zJo46e@;q;~S^z*qAp~X?5k({bM5L4w5oRVLL}X?GKma20-VgGjwWaq#X&uF}bB>v# zC}NQ$PKXEqM8r84d@#zyajcXA5dS$T(|btxvvta`&E{y>_owuc~w;cnT7sq=2!YX67KSv^hwKVr5K(0wNro z&tfvvZLgeaFCN$28>?pu^!nN$NF}LHQd&3FdR%Mvtv+?W`}~VXZ@c}@AP{G1tyx=L zT}~5y;J}X6rP;)AXML_1Zf05JgaRdi${2%MduF1@=u|ukYY2LMrR~a)nrwP{tIiU~ z9+-_$NfaqW4i?3U6lsie7tf@LX|`&s%d6v4+ZnRJhA<&WI1m76t(@xvTBR8zk!O$w5grEttP?&lH2lmY5#I}p)a;;k+ zq$6+L(C7q61g*EMC{sWZoFK3wuZZI2*S_&w;OZ^6+`M$JJCA)k*_sOQkZ&fwYc90)QuE0f)%5XHV_k zz3bxni@SHtlqG1Bve1{l_@z&O=5zb@9{?Z#EDHPd)6c$f^o=-4w(r<+>un$4;J^Qa z@0WS8d)KZ9KKdXCoIZ8x>8GDA%kuU+K6LFhhfPEv9w*- z%+#sVr(b{N#l`a{|Jg5o=8FA0wQ6TcFO=<#<&9QlPj>@MoK#ydxANMSompA~7JKpR zbhT2?vYJv+2#Ny%5QqXGL4->X5CuR0ML-Y{0OTJrv-h4k0H8KXDH0JE0x69Wh{U5R z0|`q?l8KFt=?5bkk%zE((k;9?nhjUly=2>+YT}yp;byDe!q?w@tkdbVS}gz|q7Z_J z5D@@~2wldP;bkI1m$8WVuC&%U7nqe&CW@SM%xogVEFb^~T4|*eUlN#*wAP9U0qGJ% z0Px;J@Jg|88N7{D!%(eOuaeFnGKNfsj#{g{-w@S-R4C5h1O#CKI6|iH+&^`zWB5MxiXL zicW|sgmvJIB@rYBaiQ-+j^rZ~DP@F}u+o$SZw=&WT-f3K#>(k_XCaLtiKAjzSSv*- zY1SMa+akK5DqD}fb?W&eugov6Zr`;>6!r(50|$2BeAD6aRxEC_vv#occ%&<-t~hJsi28#~ z9kKUinpV@S+37l?>#kJI>e!%M-0YpGR$3b?Fg?9bgiPc~hkWQvq@5ciX_dV$^I@cc z39N`iSlKB4{;{Js+;rQvosG4n!5c@;r0Lp+?i!7#s8?EnW5guVRbM&|7F38*6#$)6 zAsD41wrz#oPWw!?TJwIal5Jr&T4@#!-~m}AXu_41xhNtDE;3o8HtvOx)EB<+#ZN!_ znSJ|b0Et;vS66@U_kOS0Y8<%YiqY}WYp%KaYhU{sB3^U#wg2XS|2Kc|dw;lN$BzH- zCx1FKGozFe37>fA<5SZUq>+O?a^(3Jk34txJvXP-5;!$#I?G0xHDQfCm2Mcv0AP{9 z+hS0hLA{a2BU;9cX+}wP=xkAnikcXip)KAz{@y=4`68eaD`amE{v}ymjW? z;~&2BmfLRISF7|j^u*f!CRfttV9?2GetF}>mTgTJTw#Za`9KsUT170x0Ywyo5!A}UP)5`worpwdO&FY^A-1&_LtW}}s?rX)7HXB8V% zGQ{?2JO6Sk8LYPZ(Uy;xsq2TZ5yvsU@!sRzZnxEHi3k8V=Kw%!4FDp7h)O9DVP+yi z#1H}ziAWIk-dk&#*@ZwvT5IpUh-hO12YDYDrQy6Y=7|Bv%>-1bI-kOIm3iE2RN}*|S(53Li>M;H{k;pYHdDws29DSWXdAgbX+lG|DJc zOvVa0rBUkyB<2ty8zn>lAU<%RbP;5;)4kB|UJQOC)uEooP;%L~iK<5F1Z2~oDre5k zpPyfy-myzXv1fbq=qp!WHFI#^7B1I@orUiDMXdoV<2|l|Nth6n2CV}q&xn{X>)2Fn z&b@XHq9-S&>$RrRqz!0A3N(pEPzpU@?(Igqv$%Knt|KqLa@{o_aKU&?JQIpis6jx) z0XSn=qzqsOgKkk2N<{+TeOawk#i=b5yNaI6hr?gc3HOnRGYY;>nmW@B?c&9u>RoTknW*ETk%CwC7AU53)L7t)~9mtQ^JZo|m< z*vPn=ySU7Qc;EhNV`P=YHEI*qCjuF=mH@F)Lf%R41yQBm8$=S<1KwC)d$(3=u#DGh z+d0HUTG#aYH4x7%&Cng_1f zU#VoI$g_Xp#pm9B`>nh0xh}|D5~pPu)vH^K9t|!fm6W!dB*1KigTm16o@Q7_NeqoQ zD%)8yF9u0@U=ISCEDqm1_V!axzl$(=`05+3IB;O${P~Ns^CynIvuo$bop&DEyQ^tb z(QB`J*Nv0X`wi=Qjq2F2A5|+YQ`v^7KrjRlAwfl?IlzAnQ2<#$SlIh;2>=k0B85aC zA|Qx>B+S7%YlGJ&3c-3`=3Yw1Sea%LRf&^08h8~HX&6%XjGcSAl?>L}1Dd$oOkd~X zcJKj@y!CDGL$lcoA&7``4gicXh$tceKtuq*%=A9=-dpFGg8+z#bIu1(N{a{)g%AWl z8|}SU%7_RdMp2}d1`q&LNC?3HD0m-20AZs5z$@ZPS~XOyW|NU=3TPWbprE2ke~8aK z`}T9s9l!5m52sn<^_QMqTRizYzxgZG%uDDf6Brx=BLISc0EEEowE+&nIw?z6+S0n* z@z5AihA}uI+B&s;ZFSS-9LH(y3aCW7ZTj=p&4%9&Pc ztSrj@p!?o?r*FCWc2ZP?p%7Rrt1HFHQ*-Z~JazRo2iG^378mBWj88uFi8}^^3r16H zssUoa1Vp>i)oK;*2Ta}zc-A2p5QH#b-dI_BtJ!J|ZLQhZB_Tsl0W6XSVG(5rLl~^B zp35?Hg*0l@+B5=~FMa7NpZV+~`}gew1QD5?o&6X8;y3QQ@4gEc&X0_?9)0xFyLatw zciMmc7k~M^?|uI(U;4_CBS*gewXffK=bf9In|t=|dHCU<8yg=JL{#+CpZ)CgnN#=O zdt*L47bU?5N#n^#O(xN}bqp#ea?GB+C*q=9&GXeP%WNUusw^E#(lJ2I;6+Iw$(`#J z;lzohXP!N#&G?mvuG>GeojsjBId}Bvt7+msc-xg%U$s4r^KSQy(hF&7vnX3Qmv0;Y z071>A0f9t71Vjjs2o7jK%<1ch%bZW z9*`kLN!Zq_RZ9sgLhh^XX*d7sNIYEc<}iLYj2-5*SCkf?d;J>#)Mz$1FaU%Q5K(Il z0DKt$gbYsj6hNgCO1m@C~gW+ha`R=jfWnpi)@fKkE z;g5c{cjnO8vN(MLZuGqVp7ID}58^Y+_sUwP$~=V#CT+K)>{rAU5$1eHyx4!dl|J}b^TU-0vZ+`Q$pZo0Xx8IRlA0_6wBd@&l^2?uk z_&z&aU|2Ir2(D5|wpT0Dd0Fb%`jDe24gn=-4gLORp0}e&jG@vxXDQ3-NtQBlKQDU& z?WMt}=9e~}fBwYUYI)7I*YDeVMXT97H@k4^z4zLii(9wUK6KlGR%|9EC8M-&#*_KSt1|+iU0_*00NI)crAS9l^ z`yzO21xpX?*ho-$f27$6rV^&&%fG=i;ZqcQy=!NgPfK=06z2T-)J4xYBldY z5iv7dCL$pOW)>0eeF#A*g$T|&=N%Enajdnr-dkI0V|)lA0s!hVYi+gK5E1@IAP^a& zwMIY?W)9waW+6lZ@UGxswT5~vMmDX=fyj(`7^;Yh5>=9TQOnEzhd(;H&>r6X;9dRp z`m;ZMZ2NfapZ?;fvIvW!hXgDl2nvx1hyjoZQ3Qe@2X@}OF!VeK(jVmOv4-`v%|izc zFI-&NwSC4~FDedPlw~(B+ddRVQ=BC1F)wWJLYF8+Vp5QpL~9eg9}I_pqLgyhmiaK! zD%Lub!&qaa(Uk)iXmrc&VK4#GUa6ma{*B2kdk4dyNbT9V_3ys+#sBShe}l?RE;n($ zKhyvKAOJ~3K~&nS7n-qTkpOZjVWZz)?RG4wsM_?Rfl{TaN!%=k0mLYZMn)%0q)0IW zARFLRNi5=lhQngMaGRm@wdzDY+f_K_35WMQMVHwr$@zdv@-ME4MChyd{iw zSZg)5f}jt5RKDLUZn^mbPd@qMeKQAFR=NkTKDfBCu)5N1*0*_U<}WT5MSJ_U$=TB< z$Hw*2^6{Bn2NE;BxzX9Vdj}J5wl`bNiIs)L?c27zbK>aeWOH)cmWiny&XX-&q#W?Z z{M;L((<94W9veRZp&^KZmNWwgkc0#X`vBeLl{1Y>s~AMh)(#ytzVO8_Kk~?@_RZ`g z#Nhqn;?lFvKKt3vd}j9S?C1aE=Wo9Gma;7Gf8f5U>8Zc|o4@|suYdj5fBk>>vp@U4 zzw_4zT*dAqQ)ChO$`)okoFx`~7; z&P$hT%z!}x$EM;+-|Meiw+YzOajCSkz7SE`GyodbR)*Gqj#Q#M{od2hy!qDa8wd8^ zc<9i~wryM2*VoUUo;`ndR(!u%FCThnZ<;JmjiqZBhLer!W8Ew&1_S^J0fdp6MMNor z_pyKg2#NrRfB;@X@IK-oA^;$W04Rt8$N&t$j52VA_aza7NxUduIwn92!Hb2m+OsYmSwgqk%*c7B^>yY;8_4cm_>w@(tyAm z5Yb!)0EM&8xhRUf_bdVcT5F}0wYFBN10pkrz|L7=F~-DkOhhQa?45PaJ7!iO1nj-l z3hMO~JdM_`h;$3JEq$q@8Uyu<(wMQwpLp%ncQ4#@=k3!|qeq_p={v8!`2YN;Kl0^< z0*|PeSwsL75h4VEppXQRMVQ4)5OD%!ufJ+-hsbg8^-3!r_$`yWtqnrTL=eKT*Wa|Z z$kMDtDQ$0LVsdjR z-5i=@TZhg(_tM*|8|BQ*Rd2n0d~!?)e^(YtO%+riK?VMv43;mY~puw7|ZDy^)W z_ZHR{dwH&-EK2K0RTH(Wi?VbyNgHueMMS`W2q*?6M%Dn%M0RQAWRgm^(;Xk#TFtf= zRx!mQL7>zs5Zd8jeRFeZq*WaZ27r`ijU=fnihV%Gkfez#d+TfS)r3Zyt+l1KmtS}z zjT&jvY&1u=Y~A+!^UvON>-F2V?fT0<|Er(>( z-j7dh+4lK=|8GD0xzD}z<~v(pt1nzUd*cVLADbFyP}X8m*hmHDjk&p3C$^3+Z2F1G z10Xd91oBD)Gm}IpLO9TRxUzgU)-k&*PNtG<;tOB=@~0ntm*>O$bD#P7uYUEbsOZ3h5=+TZ=%lOto*8*aLGYHG5Q)E3Tfo;-1WV|6z8 z_xA0JK6uOCJ==DzE)@03sH#r^Fd!1(B>*525D}0;07U=N@P;xEKTZ_YGz9Z zpgn`u5khkGoeMvB=Ivy3_g#10dhE>;Kl{;-e&g3Zw{MS*&}xZ+1war}A?<14L!mJd z5kLpPECK=oV$0qjUmp(FtCiS$sb*u%+O&62hLSWQa0nhij53i)oaMnFuh;8&KCmt? z%3+!%QI@v59TQ2Ud3AA4T!>X7PQ|9;eXuS!DOMZ0F%r!!ZRFBI(@e7(=wzc)E-ba% z-Llo39BGU|a8Lf^hr{05?j4gKzyF@?_2%i!-2q3zj8PjI6J(5K5B796}mZfAIH@fAZl^L!dOR5Yc0g z{ouZP?lwC9!k>Tj(~o@WmDgYR*nF^4_`NX_T0zszqejdr%oPSnp?bL-_?U*8OQ0d6UVN- z{@Nr?zVY>Me)5sezVynG2Oheg(UvwB)*?os1nyjzdtuwI9Sh5Ta&jMF%zyy|HOeI{ z8aaf18cDymQuKSZN^4kDYK@(bKmPd4%+9N?IygGg0FYsxzxVE`WA7X@D!K8-TXyZ) zv$VMQ(o3%{FSV~ceATtr9jaF2*>h)KdFA;yQa9dk!j*hp39o4x6=-OlNNQJketybGm{P(egu2$4g+DAL+QL4t~?(_Lk7QD!vx3VG?TcIMuzKrb&` zHhDYN4|&A6If_SK|GF}f_nwH9*3Nq$JZj~<^&Ak9lwuJEFWdF_**`gpJHAN&3j)wugV{ni5`74!o~fk`PJ(%iC- z261MjR3Z#i0(cP?Rw&B(a#(D1JM*oPYQL9{wzgH0NoMls1wdGY83gcsD%PebiZo5F zwIPI}C{a^TVtr8*z0~NjW*tJnAPSWP5eRb&=X2XTeC__T7f!YZLG%>pN}MD~rJ|yg zL3^tdWov8QZ+z|Vt~hYuqxar({@j__lczuZ;KzUX?eA}y9J%4f-SZb;4ff(leYksf ztGhNo?B}x=);dEoz2n+#d#=Z5%!h;}0ni*!n2=aeVCiY&mX^;?PmiBHeR_I&TdXsI z)R-EJwXWUnE(#VSBhB;YFOIghRZpp!Ob>+bQ#p7>s)KDuYu-UGX5#>Z-}A9-eR z;oQvLJr^&mOit}sURoX-8$ks>d-AD!?s=#?=wEl^)m{dkb76xL6RN=7bMw#b+PPz8 z5ho{h0ci$eAy6tnAQTi&Y(;Vm<;L1V94CcMn`8UdH`-tR@?ZS!zxwU5@fHCRQsCen z8yz8O=e$x10c|01OsEh51VUN%nQfM4fD{~~j$b}{?2rDhKly|I^N)vK0i}`ZO{dtQma*`+kHr?b+4_Hf)ta0LPMy914;l4;)}8zLMWZfy)7rFCq0K#r%y7#!NZ4F z*2=VU2u!ov?LGV4i$D44GuyWxICSu)nY~v`PgUmT!pZlJcRLI39Dmu`&em;HzwmSS zU31MfL_omH%S*Lt)@nA2ydOd^N_*!kl^QTx?^GPK!nMuiM!goJ%8Sxl&Ig_Y6t=W( z5O4@;=%fdLwaS!OlmL;6iIhiCsqPHhaaDouf$MLr$L0F+>iN_4%yzon`sAHdJy>lv z=et9EqiCAhy*5cKI?ebQ7!-c&%XvSlVA*H zs|OCfe&&r2e((d|e*W3J?>gS^>i56%<&S;vp=NZk-nq0q=RBk$%bTFLHYeb^hfmzw zP?@N2X-GIg?En%|5|~CEUA=K}d1+;Tw>^6J9@K6drbPQ~+S?m#fN8tEd}nvB?9TVP zi^g<8GiGD~Ks6Y#-W_jTSv$0L?%d^5r{B~cES@`eHS@idl{Je#MxKnOZ5!5B58b?Z zRdsyu`05MaeLisL4*RQzkL~VF<_0Uy78lN4Jaq7Yp*TP6yz=UcXV3309=v~JdwSy3 zF`LP`3$L|R_1;Gx@8_1k{0CUf$gMYcl) zfA)=Y&prG6FMr}!)()$W+2{?g~a@YSu|`ryGkkKb|c zsXOoM_kC4|tJf}Ey!6KY{_cApI&t~(<-6}W{lEin9(2o>Uw-*_fA?RUyyK33xBF|q z`gcMIpZ)A-FJHRsZSk>>{q-Mz$6J2oZ~ofcLa)>DbBn|O>3{gU`=d!rT(z}mFpj~r zbr{9AnI9~T_h!}>opN3&XR>N(ee>qrATw!#lbv}Jrq?gJIGJBI*Y>sts}D4^*)KMsR!~ERtYMMFjEI~h=?{qtC%#QothLU0=A^333;^A3x2h^c6p@sYF(%70 zL`)&{%C1FXz}pl^L6ayE;ST}F7F86ut?EwKB2@~h$jihmNqe24^O*$~BZDG>RYetL zEM7Rb|Cdj_F&y0SlOOuv+1IZ={f#d?bpOiR-*$YlXXbhxR2KuGE5Mp2M50_Z5jKhp z0xA}OK$*3^e&hAycO1HO{_62N?$uZrn}_5@7!k>!u|`!yq5@k>AqF&n2+Ta5?)B%~ z?%t+1#lmoDv@z6lPe(48qdF#Ca+6&ij*3G2f@$Y%Z+m;9B=we=NUc7$xdj-~|<07|6 zIId=!qw(_blct<6{6RxYAiX4*w6$4MQ*UhF>~scOTVZ+OPUn`DrvNv`lbbF>m)YI% zey=}QcIHJ20mtIVSTrP%Bvw3L&$*dRXWsV?96TNqW%-bqQi8TkMP32`0hUG9*3-A z153xj7zM*hNJc;jKqL}Gi|k3NYBZgW5+dcDrKKYw(D%Oc+E<=dH1R+FKmYj?pZKNU{H@>mC%^rhn>#nY z^u*`?;cxuyBB_7 z+p!dJhg0|9j|aOZ#sC_k#V@xS|@AEuY)!2r9r*9Ay2>=vGRFa4>25u7;NzR}sSCdJ%=XwLzv=st{kWxs_ z=BhXy&+@!PG|b>_Zis@=e&~GWzdcnJ$A0p|KbL|$`PI*dYW;8h%7;ld=6XfH7$CYP zfIwz_hgk&@VynO)sA2&Of&jKxuDy2R#NqR2FP%7XUurY!ipX6R22>B`z#VhYw{FQJ*|6Xfe?20*YggQ-TdaQjc$M5X8pFoq%^CiXpxKpDH1uG zIor+L;KKQv&pq?K#rai2|M0sWR)o)g^^2EoT@8tU;p4w>;>fWmGkp=sPt!(olxCCY>_aD z7M&j2PF@TmXOT&O&>1Cd!mO!AUYneBHmwgFIMM{Qu4imVz$E52ge-H$fM_xXFohnu zovoV>O_Z6sSakEvk+sF0DOQ7G(u^-t9QU$fcYD0F zawH+PoXA)-P7-;W7kQz|oLb?;p7W%vNkr<4|Hj7l&;R_-OG^Lr*MIvr{+EC7Yk&LK9{2!*S zAp})*&Ux=uHHFyg^b8qQ1iZ~CD61G_R9QKxa^|fH*Rxrtn=7QMu2s}pZ^#3XDtYUD zR74&`LWVbcTce zASG;CZ(L6S1R`Jn5EVqR02WX|o9j1TKYD!i;)Tn{kKQe*G$s#f5C9N~KuHxuQ4l3+ zM1&;CT4LeQw%%glO;yd>dQ#**rlzV!))F92tGY873fLqF=tk2D&>$Hi1O!53O>QX% z%?;&sU0=I??ZEQl+Tnv|UVrtq^RJ)0`>rRS`u0N)J^a@D9?DJD?vMKpvNY+~N}5}{ z+ZRWp>&B)2AS*40(99-rHcOnyc$XCptum&p%w5qL?bpWivTTS9xlt7fLAt$R-kGzm z$Kn)x5>!Gp5V)?|NoXrWrme!_(kf7nRI*wIr(^*MP!t$2A+d8HZRkTW8|}^7QPwHO zRXewEP|*uW%QL_x&x?!(()M3}ZR_b*UM^M_jvc%E@|hdYJ^96-{piE*c;GH4K2R5yv}*Ir&6=4pna>7I8_|eBL&Pc>Nseel#+R=@cl7w-jrFjyatz4` zkf$f_E z5lC!&Bx8IhCPg$wRyahBts#l2o;4$1F>Me^y;A_pZe5)ICY3oT{lW{4D3K#%Q+%{Dm zT9X$<;7~Kt!m5Ebg^}=dw0k4Bsh#d>J6Y_Nh9FTMv-#u?vOC~=tDpRXFW~oo@cAUQ zfWVIs8B3Os00;ntHAOaL$QTu=V-qAMVE_;jBI@`1bzK`{LI|pAtu@9lb8KU$=nxuJ zKq9gp2@zFQQVO5~%H9y7rWm{3-ri_tj8g?`G9rs$I-LOsI-k!bQ&AlbhKM+=>v5ZI zY*qjHvrnEp`QS%C@_|=hI{W;$zIoTl`~&Y_%S>YhK@*X8cFCB&&7D9C7y$%?Kpdz+ zRFUfDt#gMCFJHZS{m9xW;I5%8U_eAsNgQK}EFviVL2rMu@4X8#E8bJ-TifpRS~8gl00+P0V1;m)|fPk zN^jU_kd3X)n9^V{%xuRX&+*1M9Nao#GWz?Ep@a$g5>`FxfQUDivI zCAO{@C^|*M%79EHKKCG+mbkg}RfAVBa?!m_% z3Qc_eo6ipX>=Pe<->?7&qLHj`TDX>ABg6`L!O_8v@2W6bG$v~sv{??wiD!Tel9A+u zmSuG1`g2E*t=+m6S5}T983DseL{=0)6%m}l5E=q;mPUIU0NWzFnH%=IM>zJqn`_!+ z9SYS%Et(|EAjV*R?fQ*QKW`z}PFV{FP(f6HPF{Lr9Z;z1qRjVpcb)fQ=USNO)DVn} z?!|hGr0x`MHkk~D3uN;)Kw=M&J6C4jN@`M!L}&;^nK=+Cp{CRVF#sb$RZY5iIosSX zY*uu;bzqa1d2dc_DOdn?65FJ{ZRGsL%jeEr98V?>+0PsfuplX{sHbAJVF-GTHuh$D9FtdozkEkl#ri4n)crpZl zXbb>^*orWsSVGVQoJ5%b=H`~R_nK~J2tdNXtN^Cpn{(ECU!;_nlQ9+$RAFa2M%Vk~ zzyH&+Sbg}BM|)-YjVHdjyZyo^{`>pq`;r?Z2m}N=pHkk$8Ymje){-;1vmI-409I)B zM%S{OVjC@Wi)=B^dXYqgV@hq?HX)>x7&t2m>wVqSEaJUq7U!~#?KlLVrTxjx$!xRR zFJefOS?qL{kUB|B0!_j}+9rU@mhxdX z$l!Q1)#Q{-N`R0_vMG^4dt2Mq&Vy>B80HqbA%?Bp3A(PeJ)ka8x7%NxTUcwO+1;;K z4jeLuX0yq3Hd$I(x_agEp~FXRT)%m6VQJ^q&E@$nz$}Da#@6InBe}Shtx@kQUw{3L z^P{)?*h5F}IB@2b7ccza`Hww*--GuZgmy&Cq&Dwh(A^+=O*;kdSm>2`DH5$SfVOSW z=N%$pXaFMz>!_Oohqya!&K+2u-@MTb2M3L@3MMfKkTDh%0KpJ7P30{af~J|aaVIOJ zsUgc2ot+oSLQFn4WTW%y91$20XRy3@`TAgaX{VWV=7+VWMAUFZG=(oLnGCHaF~%xj zUAH!$Z>3BeP^T!PP;YA7Uz{)3Z(LqGcqEAp(ExSw)iacJ@+1n3kfhG?u!DOGJf-5<@*&uwgMOeT~0 z`60)2`mWQn$>iqEo3FqA`qJXUBky@Q#7F?7p;Kllv63H8Y9)DJB=P_NAOJ~3K~xi> zsDeQ-Dx?89p|lnh?X=>Xqy6i%{Vfk|VUpq28_2RODF(EARjk<9&amjtIr6zLr!n}! z;Wy5k|KpQ?iWjaw)wHuZRLnv@f{KO+fMSfoVy!h~S@^a(G))S|T2&1pmSs_vWe72Z z761@YRhbzPoXwr_nJzk zhe|4HEFp5#nP9D^QK>DbTnu6+)B)R7%s>cLGXet@pydqz4u(XaV?)8T)24ojzh;LTk9td%{9}j zO>+}H&myv2ZOq!$?apWa?A!Og^^pf3e4w4}e(g*DWwE>c*xT3U@>$0Uh!D7z+aOih zwR6LMYGpi{q6!cLr~sn?TQb7YdfStrWU9QgJ2&X8U!3HA06>671QUyM87Boo zRAGsPXb44P)V9Ac2tlh#^L*GuAxi=&v=apeg(BQX{?ddF` z0qcpJbGZQntSE{|NTh&KeVZHrS|cFS*lcmwv{+@9QPJ6sbwkx|6fZ#D8U$7mRRsWR z4G|iHDYb1oV`&gmS!R3t+ub}zPHmmYbbGyJ>xN0ZLIz+3RFzd3G$9J00D?eQRBqh3 zv9-DRt#3UY+Hm5;iRI-5!(i( zg*0>6dJ{EPv++(fyI$3o5T}+f_r_a;qAALB7K2#dTcUC?*bbHhbOpr7?KJQDQSH9@ z%=DS(uj2V@--@Z3HPaNC3>va{8z4(+nkJ=`-{$kgsjiy95s1hdRSh9zSymK9jFFjB zN+JS3LPXx>x$ijRSvAB60E!wyBb8Ji|Wo7)~_rFEsuBQFWxy&qd z%Ei6WwqR0h3Bj4%+m5q2OBARTM$_5u>gwu^Ygkm^*qw%=cAIuH=v+34sy4&k@>!xa&rs(EPYy$@}M#+Nl06B|kTL_X3mrf!&l%U)= z6o*JaDoErJiB$!eQG}z$8dD_W$rr{INJb?YPK8CI$ta@=pei5$s;H!7QN06_7G;+E zq%z&!y58@WWN|OOzB_No{H;xr3(O8_W+59b4PIcFkGLGGT2I zy>tEPRLkCq^Ya(Z-DL5nPTm)zoiVMxI_>0Q+uqDN zc59R*JGmPU{@$m)o-f_??)QFpX}g(3km%M2kAq%-gWNA=FyXPwdkryKxI`4qVE)4 z0%VR&XaYBC5HM#gj4ch3!3Z*Ls;jg8tEW$_UOaz(d10;BTWx}G5|Q-=0VKf>As~{W z+YlkfI>lO~A>=Hhy}hkGb9Ge}`JmG|;N4KAWcI2KfD{;@1#J-`A|ooI2Ar>|>Zxyi z>*9qAcb+^&L<hJ zQkt$FT)A@PYOlBC{a|r^ZQ4u|G(<>BpgczD~tD75}^`!RJwPC+* z_5qA_oi^a%BPSK}?>zrvQ>TTw6-#d8*48`U@y@GPuio{hd%pSnGmpRbz2AN2xp%$o zzK*M>qe}{-HpUiuRNnoSXRdzjudcuQgMaPRefM9xeE$1SeeuXr_1HTX=km>h#co%$ ziL7TjK&%OW&s3A%z2(wvzf7IJh6&I+1=gy?598dt{;2b z{ckx{P1mdO^=f*fZMFl@c>e&8SfZ-4%dcmFh=yYw_Ut?R03TTwCAqCr(@+q!Ps#KBr?j1gr{ z0)RvokpLisV2ttJGczK_7y*EY5K&bLZCMPB@ccfN>0T;>rG01}7EY!YIdxx8>))$G>Z_}Z=UfB5v59)9E_Z-4vS zpMUm+YZqUB+?^-Fm+ zS66YkU^-=4b~@IW5W{pjt=eid8aZdP+{YMuy-wS<#%2o(s~0X_@AsF=Vy>>)<+&gm z2UVCviJ~gvMKb4ldA^8tA*KW}@utd5<0z4cMX%x_dyyik7sv!H11AlNfQZ%_XV_zM z8k{s%5-B5qf>E%MV1_fuz@oK)4lp&-(f%f3@Q$i_=3HrQe{TNp{%&h+VXbw}sVc`7 zBp?LTne*Y+jcd!x3#sABs98O5EJbqOvjU6M?QQYU+TmLp8_z!T?A@pD>J(*Y+m~K= z@zKW~``VYE_^F@%$Y=iFKl;UA_}Q;K@fRQaiN`nBFYN7JQ)F^oaf{!2{^}RM@#^Cr z`5X7Y$d6l7sjK8Aj@q|qO<94sCM#9mY0Wve)sD2TLJ9eIIbKzwXks1+CEa* zv@)$4Hk1##So((BHiEOmru8a?u@0ai-Eg|Kv;O+=!-uwRjuw}WGnDEI20#&mghZeu zND8E?NCL_+%u<{YM#Nan_Pz6U#e=z(B3no)2hEKwfQUILvb?d=f{(FacR{WuVTF`fSd?&65|a3 z%&O^RHfB!VI%MPo6$f_R|Mg#f>MajE{^+A0nvJWk{KXTePjr6jqxXB$8c~ae&G?W$ClR4TpV^q`>3x zerOx-9g^SNspl7tj7AlbpIbPPMB5PR&{*%3l#CI<5ZM~;+2?059Ign!!Q6@lx$pJfUGe`y^ssf-OB{WPBwP9#8OO~Xbj;rZD0vCBX z+8_72^Mkn+oAt-zxVU(5Yipm>d23ZgBzmV=mH?~Wy&F4xoz-8|Vb|`56p@w&rBk{? zN>aLp?if0xJET)OXFwVT0qO4U?#`hR5Rl&Uy!-PUy!&AP19LLJb+5YC_Y!VQOV{Re zJYE0xcVi6egf#2t25dn;F@+Wrb$xLYuC>)RdN|5`$dFiRuD{>8>v(N=^YP!nVkdmJ z`Z5K_TlN(E=y(?1d|h}9+)13CXt^{h1M{6XcM3hiM^mspL$TWlSy6kT=l=|t?W#my z4~5SkmL4~@cLNqw|6c zL37D89~=>`MEVd7W&P|Et7F^euHTZB?alosC#$o1<){xKsYOM-Y-IT-&{5`}Z?9RT zQT6v+IX!S92KJ~mrf$F<9*dLY!cA?}qI$Z`NcNq$9HKPh7HX6dNb-nKbok{P)0i2U zGUHC!-?L&0SN*VIsHgxU@yJo)*u#8;na0yTQHhOVitfzvY z_!IBHRLt{C8~g3oFHW9+e(Cs8@j>8ao?R5ajsEev780R_nqY=L4S)t!AGQ%w6DZ

    x#_JFtMG%lnYIi9>osnV(c>hzf<~fNaiD!S8!u_LYnz)QE*9>N0@mijq?6Gb zSB3Elq-pqJ*ZJj#c-i!k->E{rep#Kc50`E}v{9lKf^xrSnbXq$0r)xA6K%p&%EJ^% zoh53jJ%>n{SPjrxwsy(D(UAyEn5L&iIVHB^9cbE|Tdn>;MQc~Pq+VjcQ;A)S_I6G^ z`%BfK3AH3`587~3idP`l>JnL1RYk@5nbx|?+j^C$#s&r!IYi0<$|S(hyj?n<|p=hwRR_?m*w31OTi1%g%kn1;%v^a?w;*+Xe55OlL`aO6rN8-X%*QK5nw zCVWC?GVK;8Sy`|vH=6uT|3R4ciuCvRCJiN4T$TXs&F#-z{c$wU=XUIVRl;K0SmEv4 z2Eaz&M_}aMRdY?JnNZBI2a-GOr}>9I#wjZjz+M{lA?w>kmnA2L$96wamxT|Nv^6HI zzY`b%Z}AwJk^t1`P&92YvzaQmcWb}Z*&m2u#1+@jdOZtOY-IK(L6;FJWpSFqH3VK8`8yD1H?h@1YdfyV(TNjn4!_| zH4$JSqmSj+05OWVI5o03;dTms&=kJzqK-;94xIi8kiY=~S>8g4Q;4BMrc1`;XM;uk zAyUeHI@t(IDN6#r`m;RA%Nc@Hrm!FwSdqXp$<8 zwK#^HsnaV+_u=w|E%C$ywY7D(`99T*bXE1BFMWgOZbD z(M6lr{#t)r>!#alna17Nq&r-zv{ugE*(9*}+{YlA0@J`K>l>2@A=YH7dB18Ux5wc7 zSf#Vn+oG}3>m4YFi^xIA>??t6k-wma;*qBwV!eL)l**v8_HFQhRWHN1b^ywpk3b1f z1)!ivp~x}Oe;pwHVWA1Sd8u1wZ3TVKA~$MhK*63-iyi-WWE56a z0rna_@KTRh{<(N`;4N=Z|81e}I~zMu^aeFS*izCHIIB4=h7s#Sbo}bW!cLcAtK0d~ zapLpYu(MN^$pEn=k0(nj`gOHm<9tUD_Ur#Cg4?`|KOt||SC455RUH}_tw^cdVQ}N_MkH4ZT zouB?3@)eCJ9T3pcknLyr!AzyxHoW2G@W7Dkdz(YyyQshMz}Mz>gChNVffmbML}86N z+O~x?l<%9{1g@H5V>N(53EiZEE~ge-k&3wh!@y1RS2-@z=WT!})U^kLzJ!PrG7w8>#)|h4ci-(k1|u zVSE<6LVQU2^d80`Yh?S_N7j~iv1keSxO2gz;;8nx$o&OgAO3{u(Q%HUpv;=_8oL`Sq6-wgUNO)AXXuK(%@KU&JJUR^F zTuz6nz_U305{j21l707D{#7H`Fq_<%{MeP;N}=<6f^_Pirp=GF3wfA;lym(SpS(0OYq(EJ+fy1UM4ZgTK(0DE<;l&d*KUCZPAR zxZue}zU8FmLQBB;&7FWSGh1cgbvU@;x)cA1^A2d6{g15kp3K6{95!GjdVN%`&7KPv zg->XBIyjxZTyNf|=RWPddjIJ{h_9&rH(*y4@Ele3w8Q>FU5f??;XosnLb8obQs^10 z#ssd8p%t-k*oiQa{roV>hvc0A8PWdF>}69J+y5anVW-h(*# zs1;=-(Z)`}+ygEhhm?KP7|1xr{}Dy32;=yV|yBLL=0NzH>yt$5mHiXlqw z-_GlJ*Mo92+)%-$R(PZKo-kC~KMRpK)>?bl-l7pH40s4se3Z5T1c}(+UssbMpAK;)>GjTzv^gv&%@Yby+)7%_SK zd$Wrr?9Z|J0^4NP)|G)oj_<>;0&GL|>)pENr2gi^0-rSSkFKc$sua4MSSWSAq9E2J zSkU*N=Y*)T0!~|uh+p^Jix>W}UabY3CF;DJ>92JHe{Okr8Ke;MD=jE%2ns^%ibfQt z6bzzL1e<}zU;grjxySuC8i?UaWF&C_LM+<%ov&>Yrt8fvyTdet@f&(2sj2TnWeB7J z!_myt-PlY3M&=;ups!m)$TobpRhZ#ECkOMwi|4o=$1y=UoF&#m1|<-y^6`sbSVC3c z)s}0K!15c(KGb7>isK^-Pp);majiv@6&6hLgtcdB%%Jksu>I<2$~A*V)^-f;bHryorsfz<2M)T97Zb?AfFa4qP42B z3?`JWKJxG1diZd^?R8=nTYO9)Z}`uAy74BN!}ANpvoRdt_9`wFdFuIc>>Kzrn0w^@ z5cqoW+Mc?uN*YJ{=PeF`K(mrG9W7Sm@$>5>J{Z-; z!|2ZRHTRn3uEY02c;?tavNzoC;zCzxY)o))Pnve0 zM+I0AhdnJ=!VDdmK)E<+QDzc^eTgjQ;HEIp7zfgY=CkMr7er_E;NmJONkNJIMu3jT z`}^~kO-9DT=u#RbUnrH~`fA5|bh<+L5jD8)-sE>-nSFXK6gO^F_^;S2`{wf>Suxkw z5DKryip5R8-J?knm(7TCQA1{l*mfq|@;8>Mh!_VZ-GUk`oz1?Li+8@Q^LhJszKafw zSz6su*v(m(g9Yo<$OPlVdKE^Et>XBAK{omfQm_w~0F62KLin*MFX?=;x3aE{s2$W> z)a9SzwBTM;yRv~0S_X=(NnBPU4624hB>hgtqR>`%?(q;}b&D)(f|K}#4&_3c`)9n3 z+wXNAUj+ro_;@zt+=N3%?dInYJ^{iX8GFhEB-~zIzV|k%j)7im`{T-^7w79b296h} zJcC$)Yt2Q4npOsILRFl0uCVLF&_I2RQ``NqmFVM;tmwluWc@jRo`y~GaPPF{XJiF< z|KRqpM5V2!zP(kXZJCT^BLF7CpaP*{yS??y3Altop9n^u>>VZxS5kQH$+dS+4?{}+lF4&P-&EY$uIGdkrT+u&_7?BTiA9ba&%uo4csb%B!sWs7+xP{e_OdlJ&anv3B{k zb}&ttJ-5|+b+A*bU)p1tAE?hQQO=X8ShZLylJiNb2B=u8oH)WIKy;$VFe{J3i5~>K z9^P?j{G*rlIU7que!?>@pHXxEXHysekvjxUJaS`9swg&(k_2M?;ovdyRBu&@!7s7 z3V6K>e4P+>d{b6G6hb_U1TpBF;$xfCR8Hp2_0b z6lefDTpH3=*S2wj75PPrPk<8V4X0KD0;L&fCUS3d=-Srqb*myk3?{S)G%`3oJKvXh zRNkp%kI7!`WypD2-mc#`()hGH{7+WwL2cw=zUoD5+0oM{L^oC4L%O=nG;yR z$7>f-VLmvi&hiQCOOc(QJ`{8}e1BUjt2L57xi0WrT{XUoE_^9ipDNX-WB5zg7IJX! zCTdrl717+1c~b3p=o#a&En;PTB?S~=AIXQ38Q0YuPTV3)ch&V*I>$$m145QqRi|mw z=CWGKMzlVA{8b(HIGW-8VnayhdteQq%H}P`lpvNeAvW=PIJoMi@ZGz;TgQ$AWFp#& z`R`=DKL2>xfBmQOa(Q!-y$YW)ZU*?O;lG}DUe9;lQ9QR#`k!;hk1HDa-s}$s{OzrJ zIdDS6Ng%=CAU2Wdi|@lPZtB+rI+}t)5aliU6fJDmhRCxEXU(JnlfC?GBhGzooMM4wMg8(`ug0XJO;}vFTI~+!`Gu^B@Ei z%Qdrj7LIc4g2oN+hj?KX13%B}zP!hFyLYssbN2@aw?NphOc^=~$Fv7Q6Mu4OPK^S&|Z%EDE#IemenF18;`arxt)>GD~UwjspA z@zT@sO!Lh&soM6o$jDwHFOn5{TD*+!H{ zvIxG;J5mXN8gS}O3a1a{BPIJ8RR>)-dj5$oES}qV5*FY5%d|57H>?t9%jeLT0a@MH zX!W~)U=Q5a{&+uT^+usQpM{jIt@VDEqSNbW#;B@x*WL=JU;h4VmKDh-fJ-o{Fl z6E@U;ql$cQ}&j;jwygYflTYuedJ%9LV zsdB1_P-B(rd(-(S`?_WPd?FUGKfm~L_~Z4o$_4)M=_G`D;(^kZJIKq%q z=goj;$92W#OGOpwTo>whPH|f=Y_jTg#GuG=7T6wnc9b5Uh8Z1~bgBE<>%ZB-s!j61 zqfukfxybEqXa4A-5sw*l#?jf*JF zb7;yJX{akGm`j{PmNb%%Fj?E^dH4-Q)9zY!x(dbfPZ(d1V&U>q)6!W(hBcRC8X@-G zL&S-opf--=^jNuCs|F+3k^?b>7-vt>#;K)Iux(q9Dm#8aqgb^?tF>|C{DY@6m_ZXe zWE_!!nhFu@#Dzg_R>vZ^uUh9n9SqM=2x+Vg$*2n%`&uL=$sxmTGmhy{E#UoB9*tmm z;`?gag>$!)6wNYR8yCEB8Or>wIS=Bqi}WG}#j&ig^XbdqO!AG5!iEMytH*9*z*b-3 z7T^ilZb^M5TPt{@1v2M zOE1`taFwz5U5~%#=1pRRsMla7P<p2LQqI2^?PemB!Ak(5y9`|D)Kq<9`cj`o_ZJr{g~nU5v)jkb5>c z)Vlz`x%#$#P1~qxYHzeVujX-Q^LwOWQ^<>ET{Icg6;(FoX0H1k9NJ!9t!9^qUfyIH zQ^{(Ul*S9t>r`lbulsd2q`iQacbHOpFO@Z7W6qV%GjBj-FUaq%5kV~BEQ%Ax#qxKA zKoUUCg2NfR#ObR!PFrNdf-tc=8~~v|i6G+VgWKNxAgt!kwZm|L`N_YfRZLPBfy5ou zmhD+g!E&12F4`%4{%y+=OUuhRPppzTb-)R{Vvmr`=d+edI0#_)BH;DS*g28dV+^*) zU)4sUVf)XbUfcIpeEe0SS3?YuZz&NGJ|37To7$#cE1GcQ2;xLVN&sv1kQjyO!quz! zNuNf=d=!`bw-s_Xo4B60&0mS&8N*B~h7*xF38D1Bn-@3=O>(7y)1WBY#=8r>74;x>hwD(cd%S)2xO1sA zH=j?O#N1vXxexlD?s~kYSU6)y=y*XUScH*_2?}t5bZWqYN>^@94WH~0vz5!K8`=os z2t)c;$-$%VCw3#D&OL=D=}NM@%WcY>16%$i?$B)5A5t!e3%o)YjBiWPOIBDU(2(9(*^Lkm&d`LgB@j{ zn>bLEZ}2(S>E|#R}xQgCUwCgT;ox`w7DKX-6-_gN#+z$7l6j`KXK7V zOI`MdhrH8rsc!Dm)3BB&FjD+&kS+qw&!1ANGee{w%9hUe;|5j0LLK${3yaF!zTBlj zU~O*dp4U-11f;Do8$8QvHLF_ILR5kSAn7kw7%{F8Tl$AYpU35+I4k8}Y3v>C-VeLR zxet~CJG3Z%T8=|oToMM+QX7b&&3Gfa7$(0nCB_o>HP6=C_zoLKzn9-n`F@HK$X%G4 zI%e?@3ON)mW@E6xy~TeAJ;pVNr;C$m<@c=I@LzO*ZFu{d{$4p_i)z`@FT?ftIOQXn ztr)>Hf97Fepm*pdr1G-We^mJJmnIjU6|B&M-Xr|f?Th$n8&o_;TU`U>swK(zc0CX$ z_O$uZ&mMT>8X~dkON|)(7K_kSjrG%kC`VTkriobzvu%EsG+yFw1}s!&V{f}#?M?6f zp{N21|9=JSBA)lYn~&TrUN?dsqA+svF+n6y@wII}G+z+5G6r}1L(B{oSC(>_fY(cv zP#-oW3%Tn^twoFR99_C;At>gs?XVx{G{f;*DGgL}<0=?G3bRH-7R%#-%Jw zO-a_cklP{<)Dv*KEIZtyebLw-oH9H;30=&~$I{gNMTW z$zr8}(Cfk|#YME2g5J>Ejrv{bT%YH4bQxdIzT7@5#3Qp`~NAt65dE+o5dZAgY7!T6I zSlAwoo{nR%+MrZej{nQ)vT(rw7g z?dk;B>t6wOA7W^6B>dwxSk_#KZl^D?=bjE{O0jH(+ERQm>);#uU z=|2Rtllq|(wx~L2SScsq$c*I@y)oiG6HHM-CkwTVt;3!Dhsl@uYX+6|yQvTgp}_NX z3eku4&c_S??VQ#{@CN}cNsd|C>lDq@0w?T<)^6;Q*-x@qHy#Z#C!?O{jz7{DLCN24 z15BsHb_^SBc@#7nM1IPkdSyhQc9Gah&d^G$mG*!w(;ed-PnA6F%9wudW-!mobU#bV zifs+mj``&fSm$fdL&gs}7$ZY65b)cwCt-2cRbr(F+&X%?hm-V@D#Nu(18mF8K z94xC4k5&hhD+fu+5Zvw|01YvQ1!zXjFvZl<%F5gF=s1-~D=l^=X|#k0budcTUbMn7 zV|9f>xurrFV$3$;!DyCzZJo0<+PK+q8`t?X9hW_;!EoO4d}_#`{Lxr=PA#j`b^8kL z)LUiH&O?f+lB@FyF@AM9V%R)AqUjO`6#^s_ zGF;idPULW8b+CGTXx4ssf3`tI#mDoX<{}Dzt}BJ7Mn;yo!Pk5D@_mW2y~EYY0||Y2 zB1xhvH1rj_3>SbB8LAoEKB-l&KhoUdeIrw~xeht4(@u*y&*zmMwD&vvy6pQbH`)2k z6b5fD{7=)iB$D3IQKf%i(*Aksimapa_H>N@t?PF9_ogobjFl_T?v=-y{!r|6Tn%o)+bHQ>zX)-goTci>c`@ok>y6fs{#*4=>Yt8WnG~1HJ z4^ggSTq!uRHX3hPzui$6OWSvgF4wO7d^0yoDH?Fvw|>!?J5(}Ie0_g>HDbY6c2ee= zf-)=A;8V`t@#lC}MGUBYQ}w*UF7{OYrref2oTcn4e%a5N)xrrw+8l>ktDZ#t**hT@t%wNDhPL|HX=$_dE9{2y9UQQ zuxXuw<%f)WXXmluXfxNm{FvxJXbzsP`nN`BYg^8c>kSl_U#ef@=-zwfXq{1r-oi1R zcO8HG*|XrLN4wc~8@{JRVxGn&#L0YpYDy*7muveuEo(hZ>5a)x;JwKd|jwhcBS zs9#v~>Ipe>^nMGy8uN;ggCi|vh+qwX)nucIUU??++DIy;NXFH?iT79dPM`GTfqH5^ z=T2BX&7Bb2cP%!RcjZW*lCuy*OHFw)>x9>-{}oq~4O4~B%~`tHyE}r4VAI_nlj}#! z__CXEMm-uCqg&Ljiqzoo@Df-EUFH<$t13D3fE$tr$F;CZ*5aMo$Hq9DeO}M)kh~1f zxWK1~+-}mf699jR1rb#`h`f%REb=@3s;KO|@b}CW`lergTI5~Z?7chAze%d%nS`a1 zqwBq=fejJuSW@2QS>0S~<01b0)A5_>`WzXUx=UVKQ-DT8UMeaP0VVVQrif-*LEj$h zhlVBhJ)c%=xGBiSkC)x{apat_R7l+X5^hsdR6`g19Bu!3pii z8KcU?Y8HcPQ%~yriKM8%4&`;`keJxh%P(LIF|Rn=^f6y+1ay2 zF+bC?Tm|b5Xq-p4ESawY?ST0sC2B_ww}LW9YiKY25}LvM2r)TvuKN|pHXpiU2p2wj z?{O1tc*BG@|GjL&e=sjbJJ%crU)Wf1!j(YO*Y|4)2y}ehobP!#x#>$lg0LF!OfgBzuwNkhq|{h)VKW#ai6SP5<0c1qGB-xMSnb^V4Dl!l$nW zdv*2G$;n0Q?yY2m)?<5rah73+*V#ys!tOK&D!FjO)3$Nb-OzMD{fEB_yZ0T*!xI}f zFD40icaJ9^+&zqqUz(pVyXC}r)liXD6G)l5rtl8H3Q4sLvBgd?4wQEaf%)?yv{K=y z@V0>?@&9e7_ZEtc^@V%;0NEtf+DPI-2pFY_2&g!jH2;LGj8%U#?dyiFF15A&-dN7T z7W81LkEZ1bSjE~9;$_?v=yZiQ4iwGOUN_LN>hIi{Ezykk1^^Z|q(3H{i(T_*1pQK? z$>mT@!fyR&oOHYL64oj`2j4M`Nf%*nM^|&+hD}uu(o!8V7;Ef z;ewK(wzudcWWubf72^sKahDLt6a&A13U{@xkAXne>*sr=Pv`0zMkWqTK4-^C_RYB5 z^%TX4y&lxQsl6Q(eOMOW@VtXhP3Pc7nO9SicL5Kx*yC3GP}{0mmk{MnXG>*}{FpKo zQ%QR}B;T-Zh1E<;n$I%YJvnBH9+vBUTa^3R_x$ux%w_QGuH$w_LCoi`{_9QPjqm?d zN?akC`z)YH&MXp2DM~(7ErNP`dXW6y7z^yw|1Vo4W1>bdR0sy7q@EBAGT6?@hy+~q zDPn|V_8ktZ8>*E1oRWt>`mT4IcyWAS`GvZ9TluSejYl^R%7px8k`sU8{=RKOkjxUq z+@wOPm|T6IU#DZ#(Qy~&BszNpzF!&?y*&?$*?hU>@3@7}VYfs?YB_P@IGjLCHfnC4 zQ-8a0d^R4hx@~QnG5&DDrMqk_aO%$?Km)p{9kLg7YERUW3k<$MHGa z@xp~y|1{vSBAb=^%4wzv+9oTp+6z4AaG_wf$)=d9(sK(q2I8te7IYH!-2La$!5pv2~c~ad18iLjKw#$D}8Vrqm zy(=pu^luWF;2lF38V8*6!jaG|?krV}dzm^XL`#R&xpC5r< zJ4^7T+LQKiv)}9Vg^**w&7x@Q@1V8QC`D8V8`Da4`3OhJ6w7$GMdv)cI?V)*$svO} zp!JMC)PH*^L@#?zv_-G`jqUpP83Lbn?@xCwULK8$6&7=NImAI}wWWHoxIvj*Axjuv zdCM%jXc>YsAW$Eos8XBINOMM4EsZ&Mu3D{f0<*u;l;0yuGpvaGf)Z`7u!@;r-s_4c zEn;gV@aH)eCOv%#|5KGUtP(zrWVpI~M0A~aZvX@eS~Z56ImDj)cK zmOcT=4!n#proM%X>>t}bZdyB^IW9w)m^IR9QKl(Rzu%(-UJmD7HF6g6B_ z&?O_M6A6gV{?Ni2Wbr#M`F2c;I|)=j3Tb{$-a2A6w_kg>C4-QL}1tREly5SHL4bF_+Y z#PFiiwMD=`eMY1#vdN*cm5mKOU0r)dXMNA@WL0fXr?+tm3JMji=br-}Gik~d)(^+te}DJ!<4EvZt;rL} z2|wH4^z?b5=a)qK_toFycoGPIp%es@k(B9jP>cU(6a7|TkXq1p=06|($n`;Q0WQzY9D#RpE|2xD{K}u7>Ty|0bhYq;PlX^mjg2APu z2lz(Y5>z2cdRkPTF_Ytc^NR)N^0sEy^QkOVzc^9UGC0NeGM3?2(QWUN5bzR1=+9J& zSDym}v&T&>8*9}Y(rQCn)M#Me8FqYND3Y_r){~$&XC4Zn$IR7)QhA#fKL&h(ywKUE zTCc+cul->n$Is7mWN@d~+PlryuItJ6e-q8xj-CF`G!*SL|H=y0ju-{R4%u+N$d7H5 z73uQwCFwl0lu0sz*|SKQ9;t65dhd+`A0vd#;pM--_g%Q(h5n}B-t6Fcvu`S!k+0Ew zB)nhYi3ul0pvf@D$=1WO8RNoLObuY8`!?~u+QQsJ+CB;};0_rpT|e)mCViXnv)DF% zGg%|N%v^q)Tn<`Kb#}IK%FY%`Ki^{_J1h@z}FCf~rh zCXZ3cu)tn3A?9np0NGnI1WKfA+)%0ws`+bMA%rq0$G1k$K5LRg%WE0Ux9}kbgny&s z-}yju|Ngw=-O`!o+Wbi)Xtpr(VZGbF<#i`UY<0E$X$q-P?B5jRoyaX)HN91zOrrT# zk6I9whV7NL-Q)VX31?AFr?cER83G5_pp1Rrkdy|}r+i!l+d@D$b?k@iz0%fr)17D?q zp`j6W^}b)8O#aA*AWUgI1<~7vQ6N%zj^3SD(PrhWVQ`n^+cI+Ff`sZ4Drm znb~(PTwx-F3&!FB%`z5Y&TtmjTS7z1H$VbhpoSVikT=vqkL0+0J^Q&oY`WA)$ABif zPa@7gvJY8nTE@k!g)ZZJq$xV0jojC$vPg&8w5(=v?aB-P-BmF6x=?9n98)W3}27P^#4c&M0%d@jE););id)0P#^~w$O&e??NW}q5q(-=e0 zk;?JPU+Rb_ZY>nUX)P6(URI(MH$ISIYqRAKMj|7q^B4^Su?BgXJj=1%i5zVqG)THG z)|i3m_mNOW#0*Tgea|a@6L1H1CCiTM#K|2VgLRUEju=9NnBM;bp-c1DezFFYcx9VPMx_8loiF)P4`p|d^%}WYPBX3s#+zNkU)FuIt#)f(xCZb7XK5K7iJ*; zRmluj8VEoMmR!i7i$>u!tD=50e(ICsn5$#Fvc6(yDEze}b?9v`IXSN7;Bs;jRrMPQ zrMbD{+4h!?w-3le&Q2Wy0&{HXQnM4?H^rG%l`Inn+-kZydSm(XZQt1BP-EL*TY@n8 z`bz^kg<=G<0vh$Zi=$4Ga?xrR#n{rbh{$7S}Xne76G9RI8Sn2WY2<0n|>NSm~i zQGg)V7@nZ<;*A?0FBgShYwRgT7O-|784Y&{rK>DU0x&h%ZGc8MC(K4yi$+x4AFs~+ z&Bz?1kDggq3X@p|6^KwXj8Pi?DE!>tKV5o+sUv`_6Dd0OSE99pEwlWAISL8{!m8q_$PiAZRa#0VHT0BYs3gRVGU`Ld+@bLSFy z*I?qpVa)f9BQv-vb`Eua=Zp;nHm(f!T4I_0395!|l{e!J)~rLu?j+pB{A~ z`9!9_xC(jsa*+_yC__%h_-PKTeWg1tZ6;1yqc|P5#WF7mgL>DCkzP=U_?JQRVHr!EP{|Kg>I<>Q(;s~N z6M^@mxxRmbeFq9E`opM8$_f-MRLxyBqz}GtjT3`4HrAH?ZSrc_<{wO)rNqA!alPZ0 ziJBh@H5CsckU^A}0idNIB&0x_BX2hTd|1NqrfTXnsO$gsv!MWI2tzj^Ziw*LrOz+Zn~*_Xa)>waf`oiRL9t{*_X8Ui7F5T9cV^V5dCB|!_ zT_@x)&4Ri~^7T^4r3`ziZ0Kf3XCbbhxq7RsD@H~_Mue3TIA7EnS~=5n6QtgPYs0rbB$tWT z%FEm6%%`_NUdG2$11}jSXJ-s^ANEQL;ya&vomeVi?EX95+$W<2b%7id)cn#%Nj&Y2 z>`i>D)Vlm9q0cXTZLFsA?#i>oC4KBb*=|g?-%4 zFPFvwH3K0cW};I`e%kSA>YO#!Sz66yWvL{S=Bpe`kc)2G=PH}NYIs$8TscUDlsK75^_RWDHC}O@1G@#i}Mes zEi=5$IocWt-WTIz>*@_y#c_Ksmd-9yxP2Qftcu;=+$t%Nd8xl7jh{has1RUg6*~sj zyJR)0y)d$ZK3j_c4jsUEHB?I)09;cflB!3*bXeyc=&a&>q)Ep*PnGLpab-VuuColB}`yXj*rPGyX z3Br=1<>D>nW{BT!jpf_ozqRF5E49@6u~~FKKi@$3Cp5t6Qm40~uke?}L8u>_oGIJ8 z7mDI7Wb4}U&p6kuVAu2K+Y4j(GAL2+@jKkkT-P44&sH%uBt7L!lk01LnP!}odgfPV zCI-vNSgV1Lld4}&3r{mLgSzHw$tPds)c@+8aW z43428kRzI*MrOf?*hK<&`dngtiP*uy-e;`Mm%^*Qq-hcFV)E>xObBs8z&E_{nK;ua z(_M4+ToCYWY~LV-m&JAYX8YgDyN$qWcX&$Q?u8k9zerwm>>nh5x?YO4@)a$_nG%0H z;?bxv;U6!2Yx!0=doe-MpU|)n*Ua9W{PX3D_=JBzJHZ=FRDR zNcl=QE>{^f-Uf|aCJOF~jO_xXYQDw91*j3siEEB?0XVz?u}Y}d6*UxJBFaqAIc4$> zLvYn5I1frey1-i8q%ul$-H^Fhk4DsY?}Q8Pdv-`o5e^H8agdt3=|maJMj;`hR-e%zbUKyJ$UGzo2lq5P6DYU-x+)X}=H>%+3}0t#zOS z+{L$^x~RNu8MW0ZAw`QC0z`h#%qp`*1^6IQ_ne>wb)f|TrfA;>XUI5kOby)5f2&_4 zb1Tc7mzwc=L&7IwnM)pIt=+kPRw(2`6TrxKT^?BRW*~`xiwvFN4jpmA+lU4R$3Kow$ z(5xy8-ns8lSUX%U@CthE&c-4a^nP0DRTw>UtRnluY3Gt$-c5~rGO^(HJb(Gn4}sw45e!=jAE?DeI(>+6cd?_tVeCVrIwV5lPC2dR?8O_R4x05Hb^T{!sj za>3VbZ8lsULJhWWc4;pvDD-Vbz8%k0`@UW?u}_@b|DHcnwaz#BQ(079xkIab3#u~c zP;JnMNA6JTTt%Hm`c2X>+|YGv!zgF=Y4&r|Em7orrRtc zVq@#sFPcL8@aAnJt0HG**R#wyE}x3)*zZn-f%{wm51an?4o-m=!^!+@e|oqlpZ>k+ zd{7W`bvAb98K_MUkdxBI!{Jxbn8);`h^8J4#|g0lxtXA%gKU{?t8j67C6MVaz*boF zd;ZyF$ga$q^Vj)7H~`%2Vq5hB(DEFYfJbq3#K6w4oc0BvStvaLeA|?``!Ge;4?B^+@z;{KDY# zU9$0Wy=O%w(~1!o*n2C#C4uWB8cLkam}y99TZUMTkO3_P0Vq+a5ox?WAm9)qQj$^w zs3N~YnEx~hZ`(*S)}tmMAk_2ki7NaAvHDi#HlGjz`p!oTDkU{CD#fBN$Sd1Umq4_YW{reC)ByW zU?&Q%#1;r6($s$yTXut#qOY}LvWxk+K~?h9$cI2COG=DG&w=C;!pCwwR_upSMBOqT zlOp8OQaO1GfOxod3ZNDNfzkw#a!7)gNHlJM9qCj89tLo&U}hv;5N9^^yWgdW8Avy1 zd)8Pru17t)vOjW~{D4|oDwN(xT1b?5_y7dW|HIT-HpSIN+q!X=MuLY%g9dj9jRt~y zkl^kT+!}XxcemgU;lIpBXEfjaW)3HV=Xlulc5VEgY|cQlIJT^ZlTomrItVn)>lR5F;T6608kBMsR$Y~r?u>mZxof_5~AZM3a6dfkIJLR3#`jg zW&%tNd|VWuWSuhm@Sk_WGMtEXnv!mrdCKh`hDrk%b^bT{hj8#++P&Z3-scSEm+jT} zzkfWw;cXwxZ`9$NR4g(xl*mHa!xfdHMS{d=k>nS;f~JPwF8wdBL!iEQZ+NeY4N%{s zZoKc&-=QLbwnZ_OJfeZeT;>x(ta{%@y}yZ2M>oZ~4~EL1@9^YgM^`gdZk%dr@zNC^ z{*nT?l@m$kaAr1<@hK4^rZOOW)tXMB2NUtA{+p>mH{q{J%$~o{b`qqFt1c_!mMZJ6RR)=~8jq*l7Q;CnYsPSAhUT z5NQz&0*Dl(=~7?nUY~;T!!f~=i2ciy5JqHmw5{5Mp%dVQ>}mVDaFIsZ2p_pV=0`-6 zP(i(d7~Yxdmvcjs2@j-t^{FYuv3QWpaW0ayQYe}36z}qH|D3s)Dw^pWAAet8?R~3! z5!l{`SrB_(&qdwyiZW&Y-9~^)JHN+FzPE}0>%z=|VSVX88h(*a_OsP-%H0N=fe&|^ zmpzYnIr!u;RXX3%r+6O$%-YO+fO5-tDFXZA>PB>aV9%-gTHbVl;rsdtzaprSCjPI5 zNMfGgB2HFX5P&RL4S5O`83G{#(2$f9_)*3g@oq|y`Rq`4y(*3o0LJJ**)G~3HB_Ac z69n&lZ>#IiL?r$!=aM6)1Ow0u0Zf2IAZZB~0D*uM1Ry6bMnHg=eqU0QZ4lmeY2w)q z2>ZRWYjW9{(T=zCXs40~btu)fzmKn@Vw*55kqmozJp6Q%1AAzPuZhlv8YXG=;?>yI zSacI9$m()p3^8F)A-%HW0| zQz4@O-@2F{$=81~8hwY0rYb9{3OzCl0g@e!P8+W3MQv(^ZV>uTjnj;= zz>PmnMjoKL>c&L_R~FM<_IyDdOFx9%Ud&iJajvcBedM49poh;u)=~JP2sG;1v1n-F zPe|i^I5G>0+h%vNu4)AUh;xz+Az@Uy>MnTdPsgS7g~6wUw`q0oP`7t_`Hus(@Eq=c z*6LS?ILzb4h!z@dE{lpAi%lWz8*&@GsJ{|jd4ZHhbJ zcC;$`$MD6K2^j}0OFx(xwpq7hzfy_e(%H%9eO#uHVYn?6c(r`&=P_6(KqcgIzOaBX z-fNp~DCq9u_Bx!~uK76vmyJrKgR=6<@qQ(TgorU-n5*s7@<)@$R^r-{`nPuy48vd3 z$`qLSmFQiItS!nir+!ws5K8bRQYam$e7wyl)g!$lNhM-pYBGV34=gQs5s{_%q9N-L z1bo$>_^oBxn9#FWL*%s((Z4<7-+d*A^gvBWD5`t45L<*Ly2282^XG-I(S-M6Zzo#c z);)1dInB7FKiirzL4ph6&x&#E2*6z0INaD89gK==SP^epE08@NW|$e@K67whnQd&7M1FK^P_tpU<$ZwTefwW^VE>@-aCk$+vNEq;v2D-LekV0PPF_}; znapUc{;&G~M*%gbd6la_^P1(4Z^_kEPb}vFut>>KP5_IZblpG`Vl$RCe85(!H+yiJ zGQQv1Y7$Lu7uAZ$uP|w$m2kM+7!Ww{NNYtb1wsV_IJGSQ#g@yvnc`>gcyHU@jVufP zfGzg>eP>zSg4HMd?0Ni8r{7~UPoU@Yg07D9-8&C^X5a6f@#f9HilZROc;~T{)8da) z%N&8P>+RdG1B4$`KE3`Uv@(3zjS&BrZkNEJ{|(L5?{;EQ-ik{AyftJFDPqdQYm5f` zq9R266B}tsn~k8PbdD2wWZ?WU6MlNVM^Q)#J9AV1jCg~GQYnz6XyGS+RM}OMC~=~2 zV|)D!@7cG+*2P=g)Z|waZ8G6B7oRSLJQ)y!6ub9k%+lD_I$DNlve;N5nN^k^cRbh_ zrV;qCt{Bq3^*GbIUjhw0+T`f@J0||{+>hC{=`gVHV|2v)Juj­Vz7j@O8vGB2;z z)k?yKAt561(7Q&K7S{r*`_Sd-?PwFozP~?&D@iDpUHn@ za0lxb{`T)}ys~evp}Ms6b!V*=?k}xhJmTHVcU!>xIJ5X;dyq)t(3a1epCzR&HJWXt zUTi&PR@Cic$?b4;^|Q?SCy(E2K~i?lco&4N=jX?dH>aC9DS36Qc6P%`0`EHxHd>W; zIcK>pB)f&TnVperCMNN@p!!2<4eQ^klY|Xn#wMA?{>gvdM-U z#?hNCA`jNh|NA`oYEcy)GJu#!E{wphh%Wd0D_JbUvK%&@F~2haz0x>RojmgJ(fXxn z9o-e${aPfVD!D=cStH`4u#nNdsSE;O9GZ8N%!qru47HMQl)a)gp#4S7O&fDdN2Uja zGZ~{sTO8Z*bxe264FUxO)*?3)Y8djrrgtNuF{M79A?!yv`*&+ zoZG%nVFxvMil3hP3N{5OKm8rk5Lv#M4Llp!4--l&(t4LoJ{DI#q4tpyQfKBPvK{c)A(p;1~r}Gdn4OthhqRxfB<5AY)}oiu;c_Y7ps(J z&ZWK6KeX5R9X}HnYPF!R<`U-oE$j9ZxYMbL=(;>aefWeZG-$=^DI8K!h{@!mmY^?! zaTncqaBO(vqQJJ#te9v2>D4H8;Pq!bs3%mvLA-N|`P8E*|Hr>?sqtSx9=ha%M_3aW z@L8fX96pQyp`isLKv+1vX_IU1Bm9>ylZ*?J$l&!x6D1g87qH9Qs|rPF^W#051py`8z~8Y3M7F zVxC-*xtZrnN!o6-HrDIgoE&y9fDAJ@$wym~4xlw53j||R0uY!0x-5~Y&iq+;4It|h9Z*UjoZyjlCSc*q!$ux0*hN;Hv>PevmKZb62O z9$gqY2C+vE#VjmGm4)E`43coR^e&wywl=g_&vfi{wdV9Y`_S+!3GYl!MV*eKZ&DU*QT9KQ=Q>BO1P!`f#JE_0`T7#QO5z#!HBWdl zDN|0W&uu3V`<6?38E66VEDO-%7W;nIt6R5a~5s7%dx>`x2=DgZgUq)nDy`t6r zq~@_Qp29Y6_s1%AB9;&ZK2l>fFzF8wV#tBdr|GIjwr^0&QDU9?TqB=-j3T?YUn+)O zH}RgYOAhU?f7V&?K0SpPJq~X+h>-cQ{`uN0EAOj_LuZRf%QPA97P9@#=dJ9@N*s23 zzXh8oT;0CAo;)n@`RxnOzJKO8ZZ_Do2pf#Mk1QS*AZPR0ILf(G#WZQP38T(wD%q>+ zc4*gFa3PXHqAd9kq%CECvYAFt#S6*t6I-`-N!OY-Kh|my4cS^kFws#90kQD_w=Y8z z_{#^I`lo}t##X%gdK(FvfR5ClH5#dzbrgOr0EhvI-p31J)cQG(_V0{0NEXC*nc90c zEi0n2YkKYpyFI+4?mHi(ejR!mneps@op#*(bamyKZld_(P!(;vEI5N6h1MxC_TWsh zNn<%T#nzIMUPH@LvUC*^M1}~WNdf+Mifw2XZfPA|{Xa2ruIwSuwvw~f^3C_>;NbJU zj!S}AMcs(}f zZWMbbaEsjMh2vXYi@LckIQ|vyOoaOgmwsY-^0Xnh|L@5#&pEe|=k`YH>U%*ybC)%z zEM8lo{gKeGY+$h+LHFxS2d6y8jP2Zrl6B+9x#>7>25w$n9#!?w)glCD5QsuZN?nSN z*PZs`e%$s|LVCn=i{8;a369nPRx0FZ(a#?&ROrJKjkV#oMx zpq;NW6&%vFD71}a5GDp00*l~xWW`EU=XoMGNA9b6qMjxj=NFeABulw?=hZd_=%{3K z@bw2xY-DWwaT*>le;kYMF5mkiuq(297wYe)osk<>EbdKFD3AB?i&vZ1rR=^`4TQ1v zClc}D$8S$}A<&0ix&*^df&1kYj(zuHmp+SB?eOUvVG<2!apA<&sYoO%ZVpS(+z3FD zoR@92ilCEtLvB|!nkcJ&$#(0{m&b;y9ZXGBRFG^j{zsZEoAHpzE+o~e*(JIW{rsy! zH{VfP7Z(H2ziP6pFVJKA|4{h)>wHHTFFo&iox7xP5Z_A%|19~{48X#woo z#x12!j+z4#69Ieiq(2_!!WZAvTC~8@F~wn$wULJZs|5g8tFCGRMU#3ZuyOE{vLHat zQMp=dHHW_5)=#AWKKtJ6?;}BIu=tfwJ*K4N*NYCY!{c+AxqQJy)1HV<;pu<$aJ2`0n1Ei`_g%YD2OeG*zjL(h)T3ncoNT3} z3Z~N@#$-M`YWkCEt7XFIQCUsn1*9<@RVFsvTcg2e`VTgWjWCC-35J;HsjRlI9NyS$ zw#TzmF=tLU>1j?|ayL|{orLZ0mQ7~(43=rz3CYU7pK|Ly`dEgn#K$V=lbLa4$PM>_IcLg_uHJ+3w6nq!=)1*9?RHG-u=QR;x5fJbV zBQTN2TbLn!3C4D$hby^gF#01c1 zK@YMP&dLXFGoFhWvUc?<{%Ju5qoFb(uHz3=n#f06Ykc-SoO$^bPSF6}Sze#It9viO zLX=BhRb`Ee4@N>l2AO{zfS?$rC{i?A10X2y^j5;Poj3V>`}Q!yXTCblBU?Psr(M_k zv*RU+Do2~Q&Fgc*%ikb0YWPiiXv$-CWzGB5P}t*a4xV@i!DXaaripa|5;mWwW{%$^#ILUvV_Kr3<(lQG_+g4jAg|~;+Aqu;;5{w=EazDK*CR~p{_T*3qjRKH!eaw?C?WT7xZ%I*g< z>ud|PC?8Jyz5n^*<-I+sye$-&VZp127dRz2aP%DQA`m)lpQ5Ss#iI~1o9oZpk!xla zskIzhynNx2)RC=p*sKebY*=l~bc1hv1sYw5%W~SAu#2ZSVYFS#RL|C#f~t8A>t==|n^zedz- zLC=6^xy~z67@P^ZbTq0u8DE%~u>PoZF=cjN0ILb~9o_u&^oG~-JSy&Yl2!4(^EF+{ zv+uDZ1Vh(={Nt@27BfMxlw>1%Ve-IFbzAjl>0e@mC2sZAEN}$;f{<0XB6hejJWGaz z{}o0;YmXzK~|<|QwyRj`Zjlm&jvG052l z$qF>IEIKiaH~V;YK-|UJkbS!!i_i*uj;DyR&o9(r595TR@p<;`U7HjotQifCwNCi~ zSC5V&J+BU)Th7;G8(;eWA#&f)#}9D>!b^km*V|3M*)?-*dLR6nuzM{?YNDO?=x`Jeq#M_MplIz zvhgEn((!!(m>wWdLJ$QNP>O&vjLkg7`lbG(&rqn(8x9|1RzVi#6$$oa`o<_p!5!}vJ2O9Y2YTo<|(|IO4ir8Q&+pka}(ChiU z-S0Z3K-BBVT5DLlJC;1-9)~0yHBUld#M0AAeHr+zsHl|FdF`^@=k|NLrB3$aW2*&8 z&30Ot)|`3^CtGsR{rhFp?379Ot#^5VAA^0P79;g0+e2zbr)_O@oZ3B;fE z)?rOxdVmz~=$dA;E&n@tUDt1;+8@~1QA0YKdDQHTdba$ISyiAuqn}j_Jx8%PL}9&` z{nrm*gv>^GZeepqc(zv$=h2Jo#&SSteEa+qvxlLFL?bA zSoiE4p1!R`rXQt@f>x+p#tkO z0v2(+d=M2E0%Gxsmdx0;N5NcGrKI{8rX`^4Cch~EBKEURUNc-=tz+ojdQ{I=o1eM# z0`EGpwL5u1(E{Inzm9A03vdAxJUl#es$i~2R4jhfPmUYQaeXHZ3K>(>Rgc9f^t#M7 zlg^#CWG?&d&XB@0xC#J~BLK+%qnN^04XRDD6s4FwvFYB{yJ*w9k*%2i(T+*>ou5Ct zWsbZcurq)9zW1EU%lorF5|dt4_T_Yn6T2*SNwp)TDVd)@ZvXe)-OJa%RUZruj;IB_ z{$?XZ#P2xY%r`A>>}+_wty>-N2;FXBCFeX}bRXVrDxc{er%Ql7pp9VCtG}Z(P}31A zLRTA^(mT<09pf`0=pzbu99ViOuO83 z{C$M-2SOosV3ZO z&1J)b@e%S0Iv$5wspZUH@V=(lneHfX1$iks9C)DTlWCSPbGByn{LCja=TZZh8l}#3 zmRBJxiEvM+(?OP|MI{}7Yu0?D{jg?&J5{FwTQ7-H4)`Z^?_{|Cx*^c_)+W;64Hdyl z<-I*|RkrBQ9O_c@*qw6u4pn6hCR5utps3|@_l%8DZIi)Y9o<8}jXNT)Uj z7e$8SN6NX%@=Eg(a!JtM<F#)n4 z8RB#^e;5yzuh$*wh-z=g8})Z}H@O;A2~5^^cRan0D#N<_y`IG2N42i~%=fQIpxAov z-`!`Zzn23;Vk&Mh3BYA*V%+W{RR$uVDfc98a4EcJ6}iIOSWm&jI>{Ys9Q_kFX$&1_ z4j(WFR>UDvWo*9M`Ho%t8aA-oB&Q<)d!dH$mtCBHaO%D|0#-D`Red9Alki{IcN5Zm z=^q&Aef!@?*(K}&ZL!I3^h3bgisx2uN(npLCr_6>g}~>(bP3{a4@cutXn01Rzc)@B z#1>d$+^pJE`n^0_+>fJ1ssDuqoLRwp3eP*AzA|OovM}q-C>K$EQBgLV;sRE37$8;x zQ^InIEO^)bpT;H*%J+}yZm&}GI zyooEEHD(hfXK$NHoD8h-{x6wmzC8Z(p|ZHobyvu2p0NABqgJkBtk)(!`)q@jjlHW( zvdJdw9WEhFO*du~ph{{`dGVgT+7NTwq-iCY1o=u-MDKPD2V3hNqN1T__k7od6=Tca z>*GbEmzRQV?@20g|4ZNJ$;n^W1uyfk$5Gg31?&j+P(tC@uVvoX-TdYWee1>|SqVIe z@2>COO|Q01ygHgkvRDm+Ly)yPCL&Z9(*n4F#4<_h zb;;_rs!eW`Wjl3kxr=av`Ys&z3SZx{d!x6R$=TeXguo*+h2CW+vA=oER@Bdz0egdJ z??`Rq<~L%n_IQ;-OLVWYX8kMbpFgPd9oIQ^?ygr9_&<$P-}%6|R!?3-_Y71v`Zhfr zeh5j1B;*CISV6GrJPItHD%Gida(kX#bZk{bzo_}%0`_@dv|iJCQGQb-S4+k=)>Us4h#;&cE2gZ zst9;l3lV@iKlEPqEt=rc2NCf2TvUve(>!pGlj2Vi0pZ)@uF6wv+2zZk{Bd}FYzorX zMChV`99l%0>L8G%M%77&Kz^m3)!N7I9`c++@mH&afGd$&EOvV{d(3Q-Pe>ax7xvzd zM?JRLOU4*+v#0g~Tb@u6@wX@}-y8U9?;4W0_rXDN zx2>wWTZPx+m$}!=zPqm1R}?Ej!YtoIUVZ1V&jlyQrrVCAgcZWUS;CW{l4azQ@12bN z;RNS#^XJFlEqguXgBrB>ZQ?qonVP6lY|D5=o{|B($Z^GGA^XnAXO-pR@~!PemIMR6<5S zXdY@AUnpa1+`4y_#gnk({F>BUG20?s=l`s2=Vl(tri}ya`af3zn_K~6e7E`hs>!9aEvz*fiD_Sl ze!?1^>f;)P!F=XR$JI~&GIVfBk$)7H7yU@JMN(5rwlin=UMQBLt=kgwZm36#&#bMF zEZI%Y9&BnV%f+vFM3seENh^_OnbPyEh4dh*5viW1;Gz{VUs&LAGh&7sJ~{T>dcCtU z?D@Oj5O5*>n$`~WdF^}Ws@o#q!I&2|T;~Gk+P%F^THRedRQX=^olcjyyv`vRZSVLT zlLYSe!qFt5)?95;{eL__F1c4%tQ;X-3-^?5G!zoi(;gLdwmjT6)#!*8x+A zJI|!e(KOr|f9r?O6z5~{Ns|C$iVUkoARa>bu}ajj9XBwYJchg)MeF0t-IKE*sY>?Pg-iFIEf5Cdw6)_45k+|bX-eCSA>t2=D zfz@Q(ovRtoJKuATmthh->Vt&WDSf$rR-rA9n^!-bCi#ku7$HZt} zvG$c2YbAK9Hy_C*v&B|_>>;sUxd{A60^1Sj4?OwzD+hZtKqJdX|S38+szK&J-0hVmQpCQxZpV z$L@IPkayA+GrqQZJXd7qxw^ok5iwy-FabAP75M+HZ||{b;k#%lN^no5Ff`E<)L`FrPESBdg z;-TlI(?To(8yK(i?Lc+^lu->?|D<=g~ma8b4@12fm%mh`&$=+(d}OtvslG zVd76{u;B@KoyCrf&B%iSE2MdE1k$?9)3uy0jTOo~$UjndC%HE3Km9qqd29z5MABB@ML8r4}Yk znZG*%N_z&@>eAAPyhy4%t;o}w0?jfFA?ZemY{`tYW{oTGA1cRZ)CGGhXrLE;d60q= z5q<@}T*7uFP3rKg(My1Vr}`>+V(sqNUHUs7t2s5^H+$4?M`0Q7-x5Au9oRK|o3O#f zCo6K!OV&s6jpO^|bDY+6c7Wkb z_G9^QA);lr86sx{QBGI3il{>Sv}Id!^P;V1o}2ID`osh#hzvwPMgTxe{(4w;b9)(h z(oFp}#$n(#jg#={>F8ny>mC}o7bS(oU=tNeKpK9A8J5W)Ea??8aEgrpo-fkdp}L$p zFaw#P4QPyZFSJIb6Z=G)t5)>r>y-F>y4}L;GirI#YD#-$J>}>>X**0u11n^s2nl7I z@hEGW9%ZA%XrZ&%lm{)DAb&*L9_o$Bx#1*LJn+>Q(YGoPZ*Fcx>D=kpGxT(IUaX4& z5IUXzcNvaL&{@Pt2A4@UtRN*~1bl?~ zsUZON9QH0urj(IOaErp>Kr^VU$-Y&DHJIuL!2m*~8q!xJ7W72oT@lCb z{e2CqXMelzVyQ7gAHz*`<5H#}1d^PpA(66`K{)75nM~C{KoD~d8F?|e9CohSfsoSY z94nRDj?CZh*d#6!ow1sTbQQ2-^Pq5>)`Lg4)7N2FGyj)HysbBC*vl+=j;Z3tpISHt zvfsx=T}d(7YvE0u0*ja0z>ZU)>_`%r9`j3)b*_t;jT0gp9-Dr!cW%p%xueHGF?TRi zd&Y+SG^kyZQ(R7;=h0uClgiEW{3}vbOWjs8ZQLRWKbYpn9#Qkn$8v0lH9Eu+KDrcA zOXGFBXqQy^U24-tG%~cm+IRO5hV>TT?sqoExB7ClUeR}#H~aF`5O|%wXD2jMvG}rm znJaudwQ>u$B3|8uCKrp|Z!JP$JMH36jqUx1eJP8_#Fpbi)s+=Z&KB}CtHk*m8?uLr z-hCOSe9-ouF-;)>H%)=%+F$7`?__kB_tlBFWH6%0*y6pmhQZu|kAtmo=v= znEB(27O#c0l{D_3;jVh`G=!axoF}p(ael&wi2wxM#;KMU3fN!I9iPL9i=LYug^Z7) zPiq1fey6+by^q!vV`5NQj7kJ%03?%}sb>J+&pYJ={`yT)HSs0vt<6C**-MExa`9FB2Hk%hXcJHY(Z+J$Smp_}^AQ_c1o*`uoJed1rf*NLbBLiIpuj0CV!W-Bwciu8Hh5(F^5G+U z2kbcTZCXi=b@SR1zo>2;mn6C4xU|8K^e}Z^sFD&yTDeR0?GG zm-(OkoKG*P8u@be23$?+8oZ0U*}v%1;!6VH;1vL|8j3WdDXlDLWMy>WJ3fMHL}GCI z&{vGX)@F^mwEeIQ#%>o~**#O+&3X|r#TDByY`}kT@f6&l01zD+`ahBYP~k6v`lRZ( z9Ury0v1F`ddS-~lmy`|@LDXJG2r5`jQySSApa}}K)8r$Sz0%^kK+_=zYUQ_6_Kwmr zRnx?l!>!W(TP>HJ$PH!?&h3AC3i4l_HahbBu&2gXP`=2bPZ6gJCM^7??p=W?$u^bF zWx-VmC`2qS#f0O4DiJGfRXH`0)53pG<;)uPx6-pH8&oIsoX!WNRc(+0mynE6zCI+D zPV@dQZbz+FPNHS1{=}tOHe38Iq?JjIZ#0ejUrg6u{)sk`EP4^*Mw7a)6PdkbV7+G4 z|3H1!-;SlwfA?}AW0^%Vy_+S7ZH@D=OJ-6>&?3H#jAm-B$*n=8r(pt;nMGn3S(t%; z`4VB^1A?U4%@B9ORk`qxSHp+Xiakc`eNU=tJ{X=t-C$^VlpBvjZnOP9zmFUu@NoH` zLnH!jrrR&JyN!nWU0)tL-JG1DE8hR+?-`@)%!4{>Pk|6=enw7m-rX_UU&C=HTf+kJ z)PW9W?v!dT8sd+~J8-DF;ftk{+f~==^F=3|{AVbBzcpV>>cxyl{mEipPQR52aPD)j#Fj+*OPPj96>85LGIh4o|LF9-v!SKWz zf?S2z{BEpGUSy}k zdHdqx!ofu{r!+^VFv_l{XSxo5SVB|!m&m_vKvGm@B=D;i0_hSWX%UNRn6+9g zj!BD0TMGN#s*zo(o_2X{h45m8sE4hE1hO;$83ho0DM9ar#=^t|K}}C)TIw5{G|3$< z5fxxWHMUzAvkaA$(G;yjBaqQT)B^dw`$g+v5tHY!;oCvhC@~qa#*^$MCfK|EH zN*xLHNo#sdK#3vj<$`LJW7^KMnv11@{y6nSvAI!c9+}H=s6l7@>5YC7z>VWpX;5bWD@9pm6gpPfA!^aJH9m+a=_ZIjUDIvGF#pUGz3oiHR zbiBlgzb-Q*vsd%QV~M%`!X)Mq>zeB$86_>~@yz zI=$XCKm%dEA9KH*IbjF<<`I7y66i-3TA<Y2AUpQ@@EaF$k7qqK^X z{pPENU=C1)KMepa)g^KZ!D!g470l^b7$-I;(DO47-(?VHk&=xf@6-xBKT7dUj!5R&W zC;O7?a0Ke7tM0&;y5Rd;s!^q0e)yz|M69$ zW3Gb0iuO3oG6+_5Jd}90)S5}mT%^nZR2g-XV7zqVpNa5>56uXwKLgb_wn;ID~-BC_(&=j~0Mf45)9ij168d#1Vm#S~8cak_gR3&=W+^3O63gm=QS*eiNSLx`m^e+PH0xg0D83G79`g|`jq z4}8aV4xRZzRn@G=rCFITPh5nn-U*Uh!T%z0Bx8`DkXKVYCcW}UhHSHR{ft|NMHVr= zv!+^4FH|y=QHdKPQ5r{Da=;FNfKEgN25W`Teof^?CSfqF67Yx#ap}k9`n`4Y8BVYm zIhk(nJ-ri2==uJl>C_u|6i&g|y?#CMa_R&}jK3}9!8=qi|90i?#X*%%fvvPs2osG@zD_$UUe=;M1O5|NI++ym;>1CwfhCk<;>MvC!00KDq zCR6%JP|L(lQWb%hD5&s@HLodZ0Z9()q|S%(Zi>NysVT}}HLk+i|6~lg&2-~p!L|UaVYEj$f7cJ|`~LoZk-`fsO=`{e z`W^L6NLuy= z1ZH&6LPJE@jkkJ^2ffq9+1vgP=WZnh@D+B}V^BFEep);A#=^*MXcTN7Z~I0Bc6^*+ zB>o!F4-@y>XKmR9aI;i-8uIFf}zVSt@q9xoXh(aVmX=`*?rD>7WyH zW<~h83fS@PBLKNx4H*pR316=aj;^K!{Nnp^Zcf_-q=?gqVe{sC9~a|dh>BN@ zO2gS4wHF&zEtH-u-wbr)7Uaw1(Fl_jQDxM*Hfsrx^jUqu%IqHcI9;HDfjNUdZRD2ubSM{8H@l zTVMtZNT?ioBqB>SyyZE=EMXfv{XKTU?$N zNtp8IqZ`SN-%aPvK~)5G-+hqpr82hmt!&M=I{`G^mTyC>v69XsoQUQwL+HKJ?mZnX zkNqzb9B``TD>PTU)%iM3L;Nj^`Z0#X&(X5&>L-%t+o{oW>+H*#%CrOYxgqd;HSnb1 z?N63l#SB~!m-LzX`Q=c&KM>Z}>wEutHVX%!y-Y*Tz6(b(UH+|(Mt{KlJA)7z42YzK z&uoCCh`2ktF{Pizy!;)i#OC!b?+*_=P(BchZN$!{$`oO0@iC?kIM;0}MM>(W>GG$I ze7iJnZZ8T>SxiwQ($NYV!z@IPtc241{vGQhrK{HnyJ+uw`6VUp{AVm_Z#1F*@u^w- zx+=n{r|4S->vUxld797{FsGR`5zdacmW0%b>$zWkf;8_WH|@uXrs@;r3Z5gpNE=Jb zQ)kZ16J=Fncif+Kj)w0eT!b6lzqU2aBvC()L)nhP)i@^xr?4-Dc<&S5cE9bTzYSgn za5f3n4O{Ekmcr-xUk`x(YD!ERJv7azP5{w zvISW%qoh{tDLI6e0--Qc5B`acW&)A6g_oqC!?iB~r^gK$%N-)~!mc+-R3aYHg{ZWg zp?~u1czJZiei+Q6;(6e}#=a*Nhpb?VDmleg}bj<(cfa{r2MS6Oo0?obt?%u8Q`8EEV zd(sU=Gfj>)X3~ZAJgK3>uG3!=MqW3BQc4*ek@1xYqsEhu79JP990T@GCWfKUuj10<7hUJ|pT%E-T9*|9-yUI0 zn+BpkoS-T%L*n`!T~7kghm{EG=egx!1v@*t`z`O;nufmXrA3u}?@v61|=+Z)S0SA?C6~tBA8XZ@ol~o7uT;KjKmwUCdGlfItyImF^6d z7KGxku#70U*DXx!_3b31|Di1KVXgbJtGOniGw*w~!F8iud$)HlA|MhH85;U7%0~3P zj+Vt*sSOgKrt5kK@5ye{syr!<&xY&Hou*FqgDDv{i5=DSS*HK%lBCti-!~)yzn2JD zLJdWoy^sC{e~Vt9qyA0EW$*p-`>lKGfXmavdNybvG>MQy+;=;liW)XR{Sd;D>;00$ z(dE#ujpuZr{=I8Fo3 zStJ=_mxE*?QVWFr&*q8-Nj~0nEz0+IBn~ZxAN)2)O+;FTNGu~_N&+lYvB>eMk{hykyeM7v~AVm^#?s1k{+ zDpsm8k@JgsQx(>qlL^!F>f$8+Om-k02r;rFz{#EStDSrC`nqGHtI5@uhW31SyfPbd zvKonDEJRO{6q(~FTKW=eWU}#OK8tUuo_f)(Z8e;>JHO0LlQ?2;O&-L%Wi=1~!st(#qRr)bW;+xr1e(=sms%-Ue zaH!jKh``sB(bPmy0|Ei`$bc}<$YPd6#3Fn|w97bz1-%vnBmE;q58sg8wyblxvl9Sj zQdD$tZMCi2oVc?wbREkocGsi53^T5_#5A@Mz)6V{EsnPrYX9Ba2ESw7nun{; zPR~bl&)2tRvKi64mL)<1^SqhyN+Ltpzu2(C!K4VB00dBq3I7x-1dIUKz0^<#an4A= z?ZG1neh!>uRozWYEL?e{j1c3UMxFa!ddx}02WQ|TLkFrc!J&#nk)@c`kg;$j(~|zT z-x+u3+un-~pTk4qddS1@-@VHqdmN!~(lgrjIv=u2$-DRg)i*TU>T}asfNRtVpYhJb z-A^?04?VYBD(>I1J`~vVXSZ+pDQFQj^!oH9S=!`I%{clWKSb#}_8vx66ukb75MRrT zWQ8^u$eZKPpDY)Cm{Q66Q^_ zopIi_p_?qje@!dDac2rJlhOCCw!I}Nen(u^&fDy@?Ee@uI+NeY+ivCoZ$7z+e1I#I zfQ$PvaHL|u1US7d`T2d%>wk|5p9{QCe!;3?QKDNgk0F4tf%U zRDf--t_cZ>y}VbpLrzP??tEd7~<_6$tnvW4Mym+O}*vDDuyV2857Y zsZ%@G^R#k84SSqN+j-s<>%M27ZGf#)zm6I`Wrz#%sWparl;ULf;9`OP6 zRzJ?hR96GnUCm4A8&}lNx0&!=w~+0z!zFADbPXNM;}$Ds#2^1*?Fif%c%BZ>!4KEr z4(!e7O`>68Wa(eUCzs0=55b$2<>#GN7^_O&`{lpKD%);n$E))R_2Pa<_ppbf8aPw# z@Xx=%XO;JTE=H-@!=}7Y`<80_IF>!Gs3x{h$=41W42DEf00DwDeT(#zJpi5P%?Ld; zjTKL*$|TM-Z1-e6YQ;A2W||4NOeN3pa%RWifsy-JH3o~3J9NZ5!S??FNI|#0j5P>M zM5+i1NF13cvi#Y9^BX_@nIFlTanLF+$K8qUlTSRgZD#xR*WdV!zkcHS>u>nxVbflO%~^s^YMG{Mpan zad>upWnj$yt$QEHc`CQHH$&Edj-g6}cy9)Tn%ESHd{D!wHJMZxe2rmn{^E)25AD2k zb-vNrIW8L>x?+NGU`h?7F=Y%`S3?P-Rs)D@&^kB=g4QSuHUt5c6v+0+Pc?Udj0iR`WqX|ODmRBPSW>2^6=b_Ezdvw^yLe$ zKJtBc-Fo;s(lRzxSq&o7WE0h1gVMODUF{=l;z$}9TH|}0%lPK}d@!bV6mts&Es3kw zT1{ch2mQ@P+|Kj5(a4CzMBtrQVInIUm?(~;{-94phybAQcN7so5KsXWKov!S6i5T2 zV({KrAn~I4`r6XO(znlZrr(vsT2;%4 z2qFNA0E9@027wR>zDofVu2Dv1>s!DyWc1RwVhY7WF`TmZzBF+;JI zG)<~gXI|K`cjC(8)z0*;VV((fJ$j`8ni^`w+%ar?C{;#T;+QLtu`de<8gUlK6IGSD z0M?2z&bcA6Gsb~>k$}nw1_GN zWo>-!!s3g^U+WL@sp;vxd-iYNzI~!QRhPx;az20Q{QQ-(#dvkk?#XxEeb`#}yTAYW zgSS3%`<-_OzwyjBzY$~jkxxDXy4h*9gZDrV8OLRf90kRqa0rwpC}A)?nXIkM6@a{~CZ=bC+Hvli z?P(`e)h=SNMv2fl2dc){x~__%VCE=_thI=!sszYDTA>oV2!% zx^d>p)t6sCzPNnFJDHo^yMNE2?b~({Ss&!onR9FXwR_)t-Jkr`>o2^%RFu+4Y%}9Q zF)A=AeH2sDWJ;hI=DoNTAKEwlV;{S3Zn70YC`YTtLegsH0ZL2*S_CCuB~rK9HLOE$ zssWKz5P(2Yl@JLL;qNGbf-)&9RRPBcY`|C_))(K}IyI=v%YeQ=w(Tu7#(wEf|K!H&4@^#X);E@~EMA$Non2qsoSWU%%sStA z{E7SSyMKLo<^K0PaPq_}7@L{7ZO31Gbuj4PcmMs}iH^1A@|BCvJoVJ4e&~lR@xuK4 zg>&a8Cnh#GHYVDgD_0i|TzAu%iX8pQfD*Aau`zL7hpKiavep=J zRYvFrr;F92+a_B5^?3W<_toj{kr3w4}M_Zo~g5M zoILi-GxyxN=dL^UPESr+OD=f9x;NfLW7ssjW6L(nI3KTc+q|}V8INDO3~>V>1|MNi z#yT=%kqwYh5)rGZYL`Tbf>WqfkuefMW)hLAD%R0Rf-lR82(7h545}(Zga(aPh-7LDCBbW_E`R+Sr*`kW_pUo{IrG*V-}u^>e*8xt zyXkO)bZme@03!wj00dA__*>pPA|^CQmN5cgRRqPlGH1@Oym(^ituqU@kcYwGTl0K;DTrU$z}Y?TDPcBn+soLP3K2zs&>CY^K!Ol4 zA_0&H5VA2*VxrB(r7M>%D7c~=&1|39yKny+ufGYxag_DfhjVi~(u)@~WoD8Yg7*toSKog7^q{}dZbq}S>7g5E_wVhto3gpOs4gTXonPk9 z{^#fKx$}YdKX6+D^7>21=dZl|o_F6eyEW@hc2qN=dXQf(oI`FA#O+o$&1_z*`_S+8 zm+2~nI!G_`=3bY;_j_3_u%d-UFi-&IR`ae9!uN-fw< z(5PXOy1y}z$l)9Jz30Khcib~m)jjrXLjq129oyVf6^I2g=VDSziYi6KwFMusSj$X+ z8XyQN5D)^vcPId$DhL207{OYx1XUJEu)K2q#o4L6%$JRAuWXpk>}|E})XcTZvn&b@ z>PkDUX-1<#5K%NNEiIZT>UO8CNmSVoHX{OGZmh2u198MQj?3EBwWe9yP#i^xAr@bY z_eEWuK6_@fzj^bmH#J+0qRN|%=5RO!fHaCxLsg7z#Fojh0Zfsz+DYj>87zFE7(@jX zNs$pi%GgwIzH#jKTW`5|etB}TwJ})E8k2zCW@}3=U?TDwf>%HwMgS54P(ma`MGPU7 zK9qpMOx_0oLL>nQK@c%!j+D4sK7ZmbcW>>wI;m-P%YnOdqM#c2*!W0lDj_d;Q8{Eu z8`OvrLIh$o0HQ?3xiF~eO{cXN5Qs!A*_cdJc~kkwNrJW!XAKh>&>E$rP*U)$!U_b6 z5g?KXgHmun%m}IwL<6W08A3*|fR>1tm#dA9_0_ed&CRuIka;{V1x#6nD9X0Y?cBL@ z_vF-ck|diOy~V4S&z?Ei@2_r|Ze4$1=MC5I-Zs-s5(pu;Mp3oj?+^Mzp~+{TKWF;- zvAgf;pL(Oy$f`7+p4-~sVtDED#ZyboPP+5Z7M|Ot5a)}F%a<=UCbn+B z`ITIniWX5oO4NcVw_F-32`f@TBvJ!lPzhB51wi2)2%rE6pa2M<@c$qP0YE_wfB|Jt zLS@mQD#pTSw3($$92OR?Y?*GYEiYtQnl(CuL6M|wwpp5We1M=B1c49`1XLst0s(-+ zcaQ`iMF1p1L_kzTB?Ke{2+kL=P0LaNTLC)Hy>RAR&!4#N=9_Q3>&{nRdG+NNzIERn zJ3jH)Lt)gj2p$KK%^2h000Pf}&k+CsAOJ~3K~xfwLQPQ^I|wyLIDT>fC?n2iV7eAjL1Q1AP1^OU5ul1Z#}bnPF*n+?J94_Y*!Ic zfdwK zB0`Ge)R>m2ML;BVt|-c}1c!{ldmC9I5>Z4l#xQ7R43=x_7hh;bSUVm=Ys>yyf{lX! zj!AQc8iJ{O+S3Sa)B+_{LLgKG1pqY&grTnUvdR&a2wm-MlCe!{p)yb@RxnYMuu0-5 zCQzfosw9CV0MtZ|P=lu+NMwyMfKs`9ocGt)*Oyk-)|UF4{jw@m1xtwpR22Z3DN;0@ z&X!KIGc`3aJ=JVB5`wVVTU?mGeCo~9burqrYvRz6xycD^HE?>OlP0NiLKqtx=Vdv} zN6uHZQ>aaJxfh+h^wu}N)@j9dcBiuumpxqD%oi(Q&2~1-%(Srey|wj)D`zhR2o*!+`+6TM$bc0jg2}Q275Q01EG5P(oz@0!0L^ zsv?eArK;T+DU3&hM#BbQ7&e1p(QZ$RnmBEXvIJCQMMg$I^%6qxOh^hMDk7?gfDDER z-vNLKh=SJ;0EqK>WMfxT2yBw>;#&TvUwpEH$-C}*Xv=K+?33U4_P3t=#sBf2?%$o% z#b&c%ioy|^*hByo;MiC!%3zbuxX^%+X!gvrr=EN6?a8gXj@)|d+>R~A+M*ntJ@eMv zZ@xb2_YUmaamQ_k=eBjT$f*pw9b4v`48HPOLsmme?9{N*W5>_FaQsaWxaIJ5_uqNb zwyDg*$WjoZQB_vuI3{eTkws8fsY(X07A+JZ3s1DAVdR!+}imw&(F=OD@Gd|G`IV%nx{tSO3Z;MOWNuzV;XZKI5CX* zc=*B#&#i4P=lK|r-t(RZJDurPyB)A%b_lL6M&r@YTH{nXZkQ;uQNy{QK~iH4VO^C0 zAk7kD=nZ<~e5?vnQ&Uw@R%O}9($R1uwg~E?D9w_sB9Q_rimC_#C=n0=0R&@2d~Vpi zee%^qhYy}Te`(9iw)M@PjWUxon(gVejbYlD7z|xm0AjMaIlgfI%F^=ssFcF17xCi7 zRh6$%1CXi)A_4$aU^a%0Dj*TmBN!}YOp5VPEw-mZWB~vRfIMIzwE_(Xtf&SR5fFe7 zkN^-6R1JdnwRaVg8b@2$Pq(~6kC%K@#Gw3S+mpWw%ZdX%8apwO=?YD@#aRpx_otQbzynw^2*YsLkIWV zbY$=JR75=5IvvN6A8f8$Hj`6Z>srTo%{Ed7CoVRz@0H!n@bs_$cD-=PTFE){92+;x z1fr@@`MOGKNv&5hAPh9p#w{Ou?Ea5Gd}{dwzBzwBphZeiQxy}ucs~}|w5A`&MH)K; z0JVh>6C_Fy$O9<+|D*_j0Eh~I%R9#g3_)GzStD9qUhMTZZocL4=H~j^>e|HQR;D;k zT6y7|2Wt`_0wrZskRU0>yzE=p$8wB+qNZ*C}Qch;!ux+FMZWd zj7Q?DtAnI9%h{Gn;$~+$s1}7!3^h^!KO`wEO66r#I1owWI3^6vfdn?F3Z)OF6S7&_ z>MBKpQAwsDA`oiBE;bMwVnhrGf&e543Zy6iLW;(dhCn0$#2B<*Uz&eyYND))JRilo z_S_N7)KIDt^C(R$C1oBUSPYy*ab)?8*IqvH`b+meaL@Y2%HxlJec%4;9((j3m^i5j zg47IB6~m$!6H{JR9HnGawrN?`q|i!JgH$_5%w=6k@HR5zB3FP;XF^0sHIB@9+|%Gt zLlUR$##WFBKm|or6cLmN4HF|MQ}8}Vs4kp8xpU9%3s)Dm%xuq#%0?MbV&c}uW^v`p z+FPeCo_gzYJ`QozYGmzZvm0e?kK`o)C=rkWCPW00002QmRf!BDdC@?O;@e2Z3sGDV zj~R1t0wDp8fl)d9UxdMV%(v%tC-m<*=en-@zJKepyvy@0-d@{rY{zkvG)bGL>85BX z-AE~j0W_#WDrF@8LL)SQP|=8LG|UtU(t&D_(6kJlwrZ!-(sr1xnIv`FBzEj1j@Q?Y z-~HKt&u_Vx>pJJ~+Q1(`rG7r{9R|215;7+coE#u?0*EOv%v3cqLxiA4s^S2#lVk`W zPQis8>}GDtZbBpsAu4%@%nmm=izc$6y`l^~@FXpA{?c5?icoQxP?yvx`f zWaQ3dS_WYV`)YO8ZPqLl>vVE@dgaR1zE=q~T+EocGJ}Kh9w&1Gk>gzskh=p6fF1N6 zI0zsD;KXncBy`=Xt`wB}JV54sp8wJ>f9_j1hEIL(4?X$RLtp*!H(&kcU#yom|Kp$j z$;+3{hQ1v)X|rCq`EIqj@x|8r&R6TM8?r~PX5;NT z)MWnV8?Surr7!R9PIk^sXS2~;Z@=~V&wu_CpZMexPkm^#dv)EGDp1#+iMzp9Z5Psr zLS+d3kn0%7O-1H?KLBiw^=2L7yQb6W&6_u8vsu$LRt8vU+hq{0QZ=r($;IIY1AGW%m4=g1TbLcY9$23C`>E@ z7_^WYO5dNIogAMWw(X`p+#QB>J1n|kv44EKPPn&!d%ZrLOsfYTxbW0d*B*cTf$1c6 z-Lg($dp=(;SDJ^5yYqH)c6e}WHfhdX+&Mluy0^bS+uGUMIY%7R{Gs)*^YRM^k54a2 zzs|a;Mswn7SRV!A7`8L}%DO)1=u}DH)L3qSs+pYQiw{P6<=(60ot9L}Tzw9V4DP%c zhC4Bwj_S4+ODa-Q@LCy})yeT!ayA5jKn5s70VQaPGISd)Sv4 ztU`nl8O}}@mo7{Lo!+|nElJ}LCqoI_yH_}jNUFuzl8EM$k=c+-$L!{9(ZM~qCHKlH zi4X}>w8io)4<)6EmUQdZ$@Om?{Hs5G@vO~ST38#X2)huQ!W9N_un`#>++mJE1>(#_ zJ&36;VrZeqLs!o4JaTekso5Ejds|5rQyO_e88r8KHXfPw`*&|_Z;$7*CYMd0yYYB* z?UBdc{MMb*we*8mfy%I{VgON>3x`H2WOE0q5StjhWK}Z*aR9M7`hJ+tw~mhwtGXVI z>Y?jWkiOdl;UH0!4EGt4I~hPukx7UourL!-0cpEgj3=YbrcbGnP|dc^*Q5FN_TGGJ zH-vQQ(&Z~xE;b{-uN3PyeZN{+H)t+>-{;)pJ~DrgNPv@>6EQ&9bCwQ}x}Vn`LogZX zQcnxJGLtE}0WgTtM4ZGj!vGKw03zJyZp=*N28BD|04XJ-BoY84zfa+6?!`?caEK5w za4}OQ@hZj;LU9`4*|p@M44rnHezjO_HmjUBrEG@Wspb9GC`7AAKHsTARi1g~vE}CE z*=L>_Pts_dVleUy%EAuV$?<6w>aEExnWwSo}BKT z-^;md*6W=M7t?6IX*)QlR1?W!v22>L7Gq)&0o>gHCx*e*&E3r$05b<-0Pap8!vBNZ zA%k*=4q6a(!epA%#(j=&Twngmue>nde(+!W(eIw`q(AumFWxLw`*p&$94o!w9+ zC)U;axTzI9yLA;}l4?|q0kYzyAKLbCGTM~fg3@|jrjuQwhIqtWrO`NsW^uMyt=Dy3llbZK z7KLv2+^#yEoNm^g6Hna7%QHPZ+}yfx^w#y8ckUbrWas>)-OCSCN--2hW-mf6Am%_2 z2P=^goB)^;!Qo&)+&m`qc~RBoWgS9dpKFPZ>$`Rt zBQqnWSWMLzJg#DL&Eg6-3BibsVm4%hh(rcd*-e;-qH3s{F~Gxp#pm-$E(6S%K@JAs zaECD)gW$#r7>FJ0Mx{7|3C`jmgAFM($r~ans`a>;OefR%G*+>yyzgysyuN#9|LEX& zwOr?%H{H6=Ei-b?r6@CpAnu-XPN^bhEoN%&Pz;=gDmH#Ln%5K9DTUQqPYMO+hA2W9 zq-rQy!${ZwBftp`2OMxSV0+mQAWDYa3%G#Ji`(N#{gJ01ZN?Ilfx0{U@9gcJzy8)6k397F(5n^@ zu}}cHBZt`Lyy@09AMb8W&-ZO>r6cY)?a^v;R6NhO&c!$$IzOeWzxmwapZvz3^)1&; zOvy3mtZB#=>u%N2Ry~=8Sg0Rj@ebw8iPCv}tys=&{a$c9xi!KjEB1TzI31amW0 zb1kMUU}hpWcK}Q*6m`&kv(A0brYUd=A}j{(vaQ---IaoXSTm=lndCBb-KpuSsbn^p zjH-Gzp3f#*J6qe^vpOUvWZ?`l>sJ!A=*qCUb^FaLSNE=8zkd1BLvDeo5~dvCsGZY60c{ps0yy)Ikx^Ro5y-~FGz_$SZbwrYF1S&tj}_|p%6 zliTX(;?YKw6+ zid;=iMr}_{i73D_TUT-4NEd0tx&f5#1BeLkad-TsoDIS(fI0?3b_`v+T(8cm6r0p+ z)-Ay2cF(8KtlHjVZD0bq6C5zWk#iA|7y^J{=!Rh+1_?P)Ri!*+HBBjznuOr)%uIm4 zhrlFaE(T%(Q-SwDPef&?LYnQL9{%S4{>QIh#{-W%`{9p&bbDv_);Hh&#y4JGoZY?l z#PsP8US-IQcMkvLkDhz4 zkJ^*7&1f>YczO52-u8TZG8vC&z01v}jf;*YPncPZ=fpb4Fz)pe1&CTxv$j!~2iiRjr zT*-<8qPq=!m&7BxYD?mdU>eK=adfaloie zm?^ljJBdiK?8waUoP)y6yRJ7-UxutXCTAHW4qIEe^1#;R%hTyxlAsBbk<25f)oQJ3 zJ3BjlKdjg57-LG+csw?>oO9pzF-i>Ft@Bp3S8-XLzTRza#4w2L&bHp4X?H;7p@1?2 z1Ojm>%0eNCTFJv;R=`B$^e%u1fH4rMFWqK+MsAb3uA^8nQ6mkm0P_S8wB3v9DqmVfF=M3$pKW;|$&aGE3U*3K5%{TV;t}rD+6iZK`8!LV_ofeDJ^wfV z`gi*3?CRyFnVtJj{?>p0qd)e;k6g-IP4oDJ5B$mVhyTlOeB)$)74vE=cRu@bf0N#N z=S%BSnWPM-R2f%Y3B(h#icBJFL=l_?UIuCda)86%h4&B<{&GZM60tIXGK;TQr<={P zu2Ru5bY*KcpG~$)(UP5Gr4)<^<_^<}BhaT9zwpuT~ z{_^v0zw_#RKGlMQ{gY>&dG>?Pet0yRe&vOizW$A`o!^^(^1GjY=!)2IPj#42XCb8Z z*``Y4`FPg~!`Zz^@Q~2=tFzT%v4xPsWjx+uRKg>80xCsXp7l5H9_$~SoSZICPM0T( zZnZ8X_15-<^Ltn4+w;kMJf7CoD3#o;R%cy1tQVV`H}CD=JG4^VGIOpHDlvizF*&&t zaU>B4XD?a?^&-TPM-?}L%GvTZc;S@$B6V{<@Enu~&@zaCgq)1X;7VH7o6T%I&3&oU z2rdAF2n2^2*r`_P8pSFwY0;9M zC_2T#sLej8aHu3DXD5bffofoifyJF*up;g;QewCjA}4~E^X8jkOG)|moj3O`?p%NC z`eWDL=Sc9R#_j?HX6uGykOrQR*H)4jC#ZQJqH-|zQdRZP+b|%^9{pc``{iHwjpuyp zk->duoId`(2N$>A`oSN0^3g{x|E>S>AD7;PwIBQ7wZHZQ-~DU<;+uc=^}~o}f-Vei z{K_x=ZMyZXKi=S+hB|vTfpY9MicD2U+?4zy0xC(CZ??f{60--Ew|6WrYh zUaVi9odQ->G3O#2n$aXmbR%~X66atf2Dq6y>|K6e6_c9*aQB>ZDTRn)ieNBP+qOlA zs;Z!tQlk4ng!`C?0Ado&E+MHwRYQbG8HUAjagZuWRkK)Yr#mlx{nksb+&ny4e$U7M ztp^|8h2*o-{)OjXJ3Kgk=-~&RdG?8_9=-a?^{;*X#fz7>zT*?mT)5Z-I$)f@t%`Nv zdg!!@({a583q;~jaB=j@)zM+;@p(EYk{g!rDdf47NPm};LH*;0b1-U~@;(>g5dNTA~h%r{9o%0v7lRC^*hn7)F zw+45!dEF1@sNL#*a09A3f(F&zOo>92QRGqNQRI;z5M_7=>xonVW+5jxy04TBvSRsc zc^YaN%_fuSG^-XX!~hWsmr`8S-85&_BJgn)W=%!FX0xg5QH<&IbTJw=r4%=dF%mgW}-QWpzlbDi`Ar*#nfwDKG^xrc4+DECh-a z+(FK8WKHTDQ0Lej9NygB*}8T6&La;!?p~QC^*~63;FOCU8(KGUV`u=Fi2-GHVgoFt zl(V^!OdtNk=a2r*FZ}K*UG6h#)=BAp=zBl%@BEGTf9ZvrKmXZ(#u_hfjeh(`zgMyO zNB{J>vplJ+YRcK87rTG>4}OZ?dHH|y>HDmjWgCiXAf=-Q3mQo5`^Mg- zy(^b5mC{2O^SM+ZlwwU9H`OHZI7kzumJmR24B0lD&7vEY4?S>sd3GjJ-`zhtIa#%x zx(7!n#&tEic=^67TU(PVHNr`aSF7de>G5K5x>y|E+kfX|aYtggxVLlu!tS}9-L0+N z*=&1zXSYg$P{?zjUZ@BZuIwZ%W;B!nMyO=SeaZdybXHjtdJ_-G_KoGG z2R|^LUCj!I5{M~;Sh>5FHUvM|zcmcQxt;U5x1F6!plD9H36Ev(r2b zF(zl3ZJ+D1D(*9sfl-F;%zQnWrLH$%3?Fs9IZ%y~`o=wj5V%S*jxrG%TdB!}sK8tD zj-Y`I=30~~2$RED&=1|g$(`{|W$evpwqEzei71$pgy3#&8Bo<;wP*Jxj;76wKyBOB z)u^Z*930JNvns`+MFb#^QS#6a-lu7GaC9)4Zu_vhFt+aKOuE-}2F|!Z_1~ah(?k>ct+2Jz2^yWeQ+yCI#Zmh;xV@+Q5%O@Y+{q|2@_^wZW z_`mzPKe+zN&F}i?6QB7vzvGwx`4_(UjdwcCWI)^;{?xzy9smAko~2j*^k>t>kI3kP z!m?R5QWFj%r)J2K3qT>H#DU3%pr=VsU;_Xm5|J1qGn*Oy-v}j2&Utg|=B?dx7sjK> z?K}6XdVF6`^D+PcAOJ~3K~(PC1yc-JMPdxe+)FM_5McoBZgBH=nYq1(Im8%=DCeR@ zi3w0<>igbY>pEI4;XUpkCn6?dIJu(cGz=|O2z6NZ?RvEoDx)-X>tz$J#A+I6zG$;l zdwr&V`MEpKf9bWrlgn2xy#J|39=Wz>nl`Q8zH{@&&DW2Pj`~iu1Xyq#s*1@q4}*YA zK`z2IQDkC+Wg85GBNNQJTymMtwu^hL>v}XAO{Z5Mcwjo4j3-jnQ5C1BhewA8tHo-$ z*xb8&aJawEu*-Wp4?T45+=XiQd^MfLW>nYBgs9G0Bs30k6le$ARKcnMCWjh36R|m* z&B(fL-3@Ki)U&uXrMmXT-J8!#I5IAG_x0k{57g7E84Nbz5V(S;Qf%m#RZX{UUY}0J z5<(2kbh7Id)iLD0&z<_hsGqTxp=9@ zX|Y~{B8F}%C2a0seJdt-+L7&NbGp{s9MDlXAP_sebl<{N3BDL3t80 zcDVg-|BHX`i7T1jdhS2lG*4Eu2T76|nTr}BBnqh*cLnN+WK1#&%#|NUJs|JhorsuO zM3@=>KZIO{lY4jHxpe7D$$oHfym$G5$#lDIGjn84!;sZ9q{N_7GO-gmKtynN100?Q zEv0}trAkPOnyQ%=)f}UgQi#2-Q|Si@6hd$VjEDpvH;^KcSjp57s&ckjwC!0PV|Ti_ zbneo)9_SoYORt*tnGYu@J zv|M(kM&w$0Vh!wl+rpeV_I)YpYFb=D1%gP<*#b#5nx5YNTr7z5V6wTemiw z)oQW0d-vAy(Y@TCY|r8o@4NQ+wMWixZ`BpX6*n~`m})6XA&!VgMI%dPA-JoSWy$Nv zr4A5xsKSgmu#iIg+zq)aY}Kf#ylD!@yx*^0kMT$n9iCOw?MFTB4j_=Zi%=~za^to= zZN~hqw_myT=p#pmN9T4grZjPm#l6ezkXxgk04bqKmFJ=KUCAY;s_n~s=iFeP?Y`pL zCWdR9^BD&%Dyn0*MlCwr#U``p$bbh*f)V*hebUl=;D)6Lb%Iu?BvCT8V&tB4uc|5W zX0y7x|ISlSKXP~f&V1*5+ZHo11dxEl;6x_D-1;GRR&s@^iPK3lF}N2u`03F}agBjP zk{CFbK?2|gCRZY^Vm;~3Hes`=^TF8m>!v;F`|9FHeDd_F-KnaYhTGtx6th{*y?cpK z0>iBk-o*|gCMP$*0T2Kpc7n1g+@b1fmPw3AS)9pL^NtPOXTBL$|)@nyDZ1>hR#+-rn9~xtUCNQXFR|kVp)G=b=;W)Ym{JQ3BwB z(GZQ;lTa`%M1us&CR$(o^H@ zH-306*MH`-zpau2Qls?gk3IR*|L%7VXJ4hGZ~V;NlQ`PBhU#2FT_6e-;i^hX(r2uT z6s^It#G{JaU<>!`X3m397B0+4(vS-rAag3PW=gEJge71Xk@rzk_$GeJ1GJHX7sEN*ax z6mFW(>hi2TLevnvU#+)B=h>pLjb~enB?fXHfujG?ufOrqOW%Cv>2H7fiBB}u?u%dj z`q#hl{B$c$CShl1duw}pGM-jd6Jss0N~v-;cy4NeJFKt-CNXywmJlFbN^vc0r3!Hv zRKd%2d*jxfL?OKPP2qGbb zijbJ=A#=MaE|Hqr*}QB#FQaG^Szv+44QkFJ=A|1t5ICaulBjN+q`xiYruDZxP|ugR zxteKe#2nng%p;+(E3H?jqj7li&2N0@+n##;_17MH=n>}1DGr4;L)VwJQZGQ|)z)ZI zx=kK7x$9%9hT?(GYES2lg=2kX@-q`og;uTlts z%@kIISd7GYHlBmnvek9ny$57XlS1UKTRRlc5GwYj+o;s3v}LEBR^6d5UW-7O-(sH&x}XSnl&i z1df5J#3-i2y4_UM+0cuZd6e^lIe8#1gaykPuyQMrCso)9Ha8RIHHm3ihiD})-@g9l zBiA0dw|}_3y_4#3cBqqt2#_i?=b|g8jzyUnCgc@a#Z)n;QZlhhu&xwTJ4?IxE5H5H z@BH3#r0Ma8AAbK+*JSR$^)G&(+6&r+Z+rFwr{&};Z@xsNwc~u0zxSX2#IuiFc>Yg+ zjgDXbdtq~SbjIn*N0({4Wk?u;w?SPf4iwh|^+-{667LXIfS3lg>^KxYOz|WUHMGrI z5e4E;>>m#|tcPfN~|acDOuqk1%* z?X(>b#=Qo_(aCaka<=&FFTDKh2cLfGiN`NpJpbo^_W9>N|HtD=tSX$Io~+hg(@eK_ zE=?voB(+g(2<{vx@_PVhc7mDfcvLT!%cdR$34;zHLN({Ug=^cc4iE0GS0_QrwMQSi z_Q>VO9)IMKhp(30s&+AW5{r?|aCmq`B<5)939$%ACLt1l$jMot<8ZcIoZG#U>YXmjrY|08)t(G_V8m%t1sb~55p-y(#t=y+Sy?%a$4$wbl23td z=+8oArU}zl2-D-E(`p=9bUcYU7tNS76F0At6sL`CZAz_5%nVm@t16DcT-(xb%CJc> zj;ng;`_=01Xqs2+#dx~Y6|{r(O3rL>BNGA(1rAJ1O5!q#bqdKH1PLJwec7}t0HdZN zcrGoGF+#Z(3=#BBGe1_@17 zMG59k>@asT21LZ&g@u^i;f~^_T1p<&l$e;!y*LW9gP>Z7#aYaQ`xuxL&A~O35pUd1 zw45>dD2^(bF-I%L#v2bma{0B_UU~Gs_GF*B#t7|4&8FILa4URJ^Jcfn_vBBUwGlAJCJi3O-5YzHXdztU8}Yl&0_Ht zbh%sUPyQR<|3lyT*z%n}fB1sYTYvF)FZ1Gb0TqIR z+&#c+fB`3W0tgN`k=wi63B)kCxnv&|3+^RyiJVC@JA_3bZcqmZU^los%xfWMDk8(s z9d9v9$A?Yl?q^Iv`Kw|?t)zwM(x^|6mWI-AsA{M;YC@%r-*UETfB zAN}-vGFG#7+wUKoy>ny#TkqW6KRhk&2AB~%5Q!N|8FFrk)U+oU9B?YxIHWdb2_cAY z&n8zdpTG9-mB+7Lna%6E=JoP8mv!C5Vc1CE*=QWVL(UXZE=X0~4PXgoL=>2W3FJf$ zCCZYNDd;9xTZdeU!izf$tWFLQ&}QAClu;do6akLz^wx`8bh;J&_QBcqW8Zt`I~jEp zPv{D?=KzX2pxck2DV@UQLO8#2H*xja^JUY zON_~ABur|V$N($FS*BgT9#0A+4Y_W(^`loO?Y+ivW_!5s^m_Y35z2@ARYXB9s(n9b z(G=6D8if!*CL-i+stjWx0PgHYcn^`dyIFyQg^64(n-?Mn+)PDC;R+P54Rg>o(F7po z!Ex$(61dc{ic~XLi!dNUI&`3X=hjm=l6Suq@(+-@dmvs`b_wnme!lD!y9sNKbt2n>MS2~KVxcaRc5 zAUMI{032|4xSIhWh6oWmq#e>wgrHG0ac0X57Zx%A>>wvMSAzjW;2`7DOVzX_w~mkR z2-l@Bg>f@IPjPm#2w#5w`tSbU=O26g>5qTs4>q-Y^W_&``No$nUz&dA$9`aUdo<(~ z5dmCG)Wi_MSg!8&x&)XhF$n;3CCV`nvz;6tUEaHV_wK>ge5V^Ijdnw<-PFpULkAls zqg2;{QBF^fhGA1RL9K)!l~koGxmc>l;0T0l98&`iPE2416A11~oROS4lnv>!;=T$N z*bU}HS*;%m)cU>;PLoj+MIf%aT;2WpjE;92zJBBI;?tjAlzB!|30E={Xy*c!rXH;q zn|8T+|D#t=4&Pa?4DdPdmpe1*9MpFrFkS z)KrbI2!ol;RJ90s2tovRhLf4oyO@Z~0e5C{ch#(xi5zgVQdOZ?$>xPB#ngS9X$E5A z%)D@01S*vT@#qG(0Cy(0(h=#=;jOLh@nUf}+nPE=O^6!z3KUs<$SvVM*F2;ct5kvD zAO|@(tM|DOON=SSs_hAJF4g>%>j%I6`_F&vo41b_xgKu~eeSw$du!&d7tYn+`^hIC zdti3&jX(dy2QNN$0S7m}L2thJi(zv!25p^C?QnBJWuh#QZ0u^Rniw;pkTqwAh2+eT zMrh7nvq5Z?=yX~ud+(~N<EuW<^n$0-+8ROBuk+s%eM3JUKmU zM%$~kg?d|k{-@8~{QMWb{()yc_V6Q*ZtqUN`uy{+zVgCj*Dn6>4}EH99{c_zRaDAg zW*m}J>Uv#oRzdm@3sZ1|se=##16j4pLpuz^bUba_VQap-Y;%!1q*{oC$#d@84Z~9v z7~T&Zk%uTl?p2K~c!7i}0nZgM>eZv7yjl+u>*;*gA?^$p0uvFO6l_#GI}a=CPb0NW z^eTb_Q29 zVN+J8r&srO;H$;St(drL?c&92L#ar&#Aq^X)4}b)O-^ z!?3clQeCMZ&*!o{E3mCp?e+z!3J{VI@&Lw|5UglS6r!J=E}2tRPgs(0U?#P!)-jbR z4$EE?=B7U6#cK8Tr7IWSxp`2Jw-m`(lu6x5oQO=bDFQ+jnkrUJtb>G{bKke_#^ml= za;d5+hQP!`OdvHUA_G#a6rmVKlE?XQbMvK!`qM1D`zT*{N_jLaPvON`i>VeRaEviX zaPy|Fa?X9L! zbM2elIDb*DQ>m0w700zl@6DcLYYprI50+JDxsKrZ-aOn(-z=6mg%+%QIR$->9g2+#3u2!o#L{n;OU>s}8X*OMWK|eT~>EJod zrt6Xa@WWsJ;+OCI;SZmxv{#qw7jAz3xuPt`m>WyFj(ka}14K zPV+j&hHj7UpIy7QxO49hCpVszJaG?D2njHP5)=r742n|%1Wl~!7-9?%j?WMvDDE(q zpgL1PB679PJqtZaLF`cb1aCAEs1~BCNi3?N3X;ZNE!$?g2^2G=7FVnD)n=T|Paixg zZ@ziwXFt3D;ul|g?e$mp4i;~{`Ga@gdHZwEpMK{%ubmvXj7{5EU@$9zpyq%MqwRM6 zG^e&n0v(2N*!BVMx||y#%H`GL#bSPWxjH$y?uK2h%W*fE&)T+8u=L}w+o`4|XREc8 z3Ic*!EgZ_skd!-3t-CI_ecLX&*0Snn<&c^>sC!zEUM;Am2E#n zarYvQCQrI%HujfZ9=7!?+rw6|sfmYQUe=jMH_2_6SScguwB2rFqi2zMm!_R9S9f#L z-L{;Ze6G~yYO@XXon2Nhj7hjD2HMyNa_*|h-u{hXSDZgS>LebPxQiKE|!ofzU`Cy7kHZ z$?UKq8`X#qQi4Q;!6a#F({$2I+th^HF!bZF1HH*AN*hPjM2aw}W?=%tF_4K|cqBt~ z9ALHK=quGVk^Mo;r!o@A7-GmWt6;Xv| zb-P+!>>o_FyWM>MfM`>myEl{!`qlEHmZ9r9eL}=7N-066)aKmQz&I97dD2X6^qkug zVIsX-U%i_xKE3<+%{Si;S3&pejhiQjNB8cY9UMNB8@~6ux8Hv2hyUWW8{c~68GiKf z_qVH0(s;I~8{gHYxgOK!HtArkVF?ORlLlSR8sfcUQ*0NT!hl@Q`b>_KgHapu3ohGlSWg zB9g}hk%gW(x^1FtlSHct5yLo&YSZSRmncfr=!Rj_&8n#E24m6?UM^P`m-UA~eE&DU zIeYmVfA;FP{zN&ub?f|>zxXfDKX>C_{`qS+Z(bXR3#-dX7vs3mBoumx1>HeNgOo)O z$!e)%0U|d{DYo0?uHUFiDL!8ujyu~~sX1ngMbk84QTm~jI-ShC+EA)csA}QvL8?;R zJ)EVwrminB>Gqi?h+JJf1d>HEA?~Q*s@}z*vB}se2CMy8hSauAJ1JH*R0tmnnVUTI z;bK^R)ZszPWwolalhQrAu^GH;QBO_QVykAf&fBq2h)qKud47av}~etPfhVlq1{p(Pk1 z6b2mx;EJT0v$m5w$&#%;F_`y&Cxr;ZErNs!lSrd%MBK1Z?c9%m25Q;+sjY4GQQdvw z(qER;9lhe|dPN_MbPijnyEkusUHlmnahF>YiB=CZ$KA%m9aH|qQny}ox`^j_9-+1)+ z(ZSIP+2lMoZ$xv1UtT?~wM?f|RYhPdHjX1HO*>J|0R$+T6O$JMqM5WtTW;68Vdnst zpMCb`*jrR7JN)+TcfS9QXW06BfSDd?x{>XMRy2rNvy=K@lCRDmzCWM& zdbQm@dP(%q!aR%$CU}^Kg8>8s3=o1q5J3l>2#Fv90f3;It9de{Kz1aH6zGIW>B=!| z?c*j(G%0zt?QTnz$+Q(^i9&i70nqm&MYZjUOGvw1_5b~EzW4rnn^(W}ufFus3$w++ zTfeyV%QruG`73w-;xGRE;9w>ko5stq%#9quASU;Z|^^RwAo!sySx7M z>G|WGP`fOO2y=!Mll{Z%A`jX)>9Lh`UFa2tm4) zvELNmFo!gg!P~LSDM#dl2w+95laxfSgV$206D8oaDoI$*{^5u3z4X$Hx9{9OJU$7e zoEGL;Qw!MD^2)>KvzbT&5P^Oe-O;oyKo2C%)D+bO5pWMPSU+yIyA6etZZe(CGt;oE zb@2Q59{lDvAH4Ja?%6NA_RVj9<7&72rysw0=aYB%_DA2>w&&*V-sVxeTP4a03mkub z=$_g}YSbl0lx>&0KwBcYHoGWA)Y9DI5cMRRNJS?@EB7+*j=S5+alIN(kH5;a?*WI0 z!X?bz86Kc&wc6x%97;;btC0{w=o(HqA`n5%7V0$@s6}=pM~=t{QK^kqqDS2+s*(t= zrBIo&LcF4qHS6fk#}CJDdMM2-cZ-W<`P={b&wu#%(X%&ie)qfodb6%?|N3|DzVm*m z^*{foZ=4(-x(z@T)`+od6>c8k0WbjxU_`)+z#||5CEY7ocm2|%h~R3yUM!Axecf*B z(b0|6Ox)q_0umr4=Nt(0APGT@2!@aV!X03#0jNjPG<774WUdy;p@9@&pr$;6+w8j> zeZw)+8D6T7HA-bL?M?TllL?L0f`Ya_xVrOm44)nxc6Tl|htGY@Lkpl{mVin?UKGp%ol$xAcm8=lLK}QsiiWmVzgh~?TaE;I; zP0kEi)e5txb2H1iNF5uD4IV$Z`&Qdtlu{(UsO?Q_4~&{J?TKmusHmut9Lj(v=m8^* zgu4q!2q{7(Q@FSTVA3Wca&AZhAj9fd#%-~!>xh&KCgumC$Kf3Sa!0J2WLdoQWh`ad z0s$o$AUtXL_~Q>>{Nf9D?%Y1Pew}P6oktEN664tKhFuv=H8)KYkg-%!k~Tr8q^502 zH5(bFTG{Tlr4~v=xDbo^JgLyFmT`Ht?3$()`EUQ@$M?_MuYB`QUw-}7PtLY)yzvYE z=GG6YZf3rnUOq~zN3GViYn?xX{Xg17m()ahlvP4QE~-l*2Q;R$s#C*MaL_QtE~a^y zwPz2{em-qCG)he8v!}pGP>dRci5S(vv3gMZacrB(FqF2PL@ik*F+@DUlumabf)bIc zryAMW7;-R0Bmu(*)Q!l{WoXo}Dnvw32=R&%bWJsDS+D!UgBKp250t&pC*S-28*jW_ zUd9Lj00+fML_t*X@yjoN>*ZHo0EUl0c<`&Y-VojVhrj%HfAsuLRp3 z7V)4wc&qO2$)u3%51o#`Yzx^9Zxbn`hRgDE__JENL!`u=In%-Z(bf57f*kB0ZZ>_>%~LZC%@iRJwJ4%rU)6fPx38;ZB@ZPp z95QmKQLES8&YEUVw1GsRUrckVb&{Jp#xRhbi7l{cv?#0$V=1Lgg<#eUH=$>Z+jl;E z?)j(he0t~P`ZY=pZ#E*ADzfAyCq*XA*ti3;6Sl|(5;B}Y&toB3`#4nxhkolK`p;ZaoxtBi0f)%w-y zd@^a4>&@Q&VMVKXmeRtl2#VV%lqMw=L>S;8f)0e!gW(JW5m_RW3J5~R8sk{2OE+26 zP!ILckQ7K18)NBMXCIUG31g-!g-nj@kttonE~iFAA~Cn2tM|t{Kegd(|N6Dv?8fx? zi&tCUt%kka47;6yo4%jy?P;D89nc0ijN9$*(&{pzBD4;gWO8zJXudwb`sDazz8QwG zT8y}U@|4%O^Xb{?^&7MOgQ3(Q87^)quvuQ!dU>7DK|6ssO}+dHY7z#l9&);#fz=3E2qrwy zkG&gG$|70FL{b9r|G4loB1DiOA_=J36E;16emFjp9msAifR@nQp3dDYc&yV+r})+O41|@A&PB{ z+bU7KH5`y9#3Gm^26CIESClfATI*sWN>!0E><~3;+`jYi=fCjmC%11MogPQ1NAk!X zLWrtJQuEkuhhZ#aO1bIUY1d87JR)+=R_bbVQEZvAw#`%}+30X|If;ZyRNJ22yY>9d z8xJ1dA!7Mx)32I;_@@s>9)JB$zx~IrzRvgV{CHii7Hw|V{iI$E%R8!NSAoehv(uY{ z%4WAoIl@|vS#B`;IF>`_Q=tcy3>0Nm-#)(o&V06AOl`Mb?a!X8V~)Ib_GVf88yXM)`mg`v zq#2Ko7Nsmj#LQGPp|w_05h9|s`ffXxQgdo2vnf-!xCY#73V?S0_n@S#s2Yj z7qi9bSd-fj^~!w^k*>{2B)oc(bbw6*rrN!&gA{l(SU>C;b*V?8~(R(t>S z&e`$FHHWsdsYO6S$OJUtcC{SG$BVsmbv23{Htiu&s?iVDSE**=rs3jVb8GWin>?XP zEn+Sz4OAtmdnvW=+LUvapjEfx)z-`9hu5wh-aorMJbKEik|_X+NCL^xMt4#YAq-Oi z$p}OQAOikhB9JFY0x+v)qpE2$8GTYlODIaOwI@sF=JNL2&mA`F$19yZSU5X{OFzMZ$5RkdK4J;=kw*+ r#pb+h$Aka+H$U3D{^EDO`|tk`jukHwsZ&pq00000NkvXXu0mjf!hixp literal 0 HcmV?d00001 diff --git a/docs/assets/images/satellite.png b/docs/assets/images/satellite.png new file mode 100644 index 0000000000000000000000000000000000000000..47ce663b995e04c410ad9c69745bb612183f4019 GIT binary patch literal 292903 zcmXt$-MbyIfxTp}iz+Z0f4!VFqG9dFSCbp6LBs)+zG{;S5Ho<7?;`+DNHFERV>9Kot=H59J zALZ-I_duO_P_t!1Pt>Q&%djI!2K-5KS;9#jpd@88N&d(G=`VpZx-(y2d#P+K*F_%t zGyi*@^qbVQKH@~bw6z?7S=#z;wO1oeuDhb>q?4Fm&UcgVCi8fJZpUZ{PvbF5CBX-l z+vmY8J@HYQ>p{KqHzuwpOik_T5R631S3AM>r-y$lRfNGoipl%rzplqJYRhjknyUS1 zYX(o$lhuppoGSDcm~+qD4zG6Rl7Y^jzwc}ntmtKOI(}Q*!9p@Jcr->L@|3*XqGZm4 zBIjnQNCM_)NwzKcLD${993=i_R9_{}3+`S04iA9~g95OSZ!0YZ^lTgapq#lQ^H8TN z1qbeG5qTc9>rpRx{e@8H>vM*Aj^@Og$#?3F`Ppa`lLGk`&U+)J9hSbYk~SW83B1p^ zq}oRwiOR|FIn<%v4SrFp{7@8py4&mfMN@);`Jg`~x+vT!dr2>TzB~QNd_4X*s)2>- zQU7q~KT#^&Or2lC%TMFq#!_cZ9M31J*htrK1O$hxyFD7*VPCQh;d=l%-B+h*A44YG zv{8yvm)M8>VA)gax8JyGIG=t(yDr-Xjq)a|(C*^)fwZ-?PhE<}Lij+o$gYb$SXYY` z(tC)t1-CZXH|1`o$3-n%sq#ZR_O6V|LE-wF8tE6{ut9sl4)C&LPaV&>LM8uPprggo z@C+J>ymr1*lPFNkQOUVZe=AOGKCrbi^W#UXW3aVg-tEHkUixiV30H)0VYd&h_C|N4 zQ^dFmJuF)^if|XJ*lq8_q;hDcec85yL51&+K;U7h^`=&XK2=p!U&a-%HGJQFU}at@ zCqJ;UDmI9kS-alT)6?me0E0qtCLl90v9zwcx{_^?+=p3p3}sp)zWJm>6d?~^Z%^Lz zrP?dgYU`a?FkIbAU6=Q2t8}c<^}*p_!F{C98Y&0Xz-`-oHCCJppYF6z((4Ly`gV>O zrsh0z&nIBQww#Ez^^UPz)}&;*>Y(Q1QpMh*w4gFML3>_$U!Tj~EU&DylRUA=Ylv@6 zctaQRXg+-Z&1_$2TW&vrJ>eRvrIz}8@mKfG))95t7c?Q-wL0InTtStHaBAaEx3A}D znKHk}Et@Q%9>~0yYE1sUMti5`@V^R{!;jJMte$T({> za)#)D`^sR{DJWDBxEn<`;q`aO#m9Oo4-prmudsH zW+Ivy))ocjkJU%)H>lP*m{D(|kl0uu&=v3*tX@&Z$Qu%AEYuJxw7_oWjCwR2J2-H& z^TW^`d5rZ^>I%o@-Rku7-Ipw04tlCtmGA3YTv0stU;o($7UvP_A3+xKYHDf(Yh^8d zti_F2JmpdfuPMqdzq}G(P0G|Dd{igeTF7UIN-?SA-k-ozTpU;`gZV~j<1KWw0whob zWB}}M++J^Q9t7?qEFxszCLOt?H+x)daB!uC&1Nr!{?WB0prf9p@a*!>(j$u%h(aGm z?itkH=q$m?d;teZ6}Sx!QEa?JLZ)|iWtyd%nVCnWvfL29bYxpIeDeyR^=bhD}|xlu@l7e9ig*AC@L{b^wF zDm<pKcrdLe`Afev`8Mu3?A$x zO_gJU`)LNZY}#Tu*)7Va3}bDAU%&>Q{zNB%Z-FtdLHH=bVS)c>uo3H@7YW=^dvg`} zq46+Zc{H@XUrkMj^$?693wuCtT+*78i+P@B)H5{IFU3SZ^|bu{p`(}y!OpI`Q={da zC}xc`hPZ5SBsRgYsBLGB<+A(lc0+O!ZQvKVAwFcQU+TR)=zW6<14b*o^Mw=Uq*F?j zijnHU6i4Vu(Zhtz(puj5^@JDJR=PyatS$9s<*#&fn>p#AM7j1dm8Qu5gdt{WGe7!^ zSkp9G^6iraCo3ux{J(dhs%6iS^v)l8^eM-1@8N2wVbi;o-ER~*#J)u8w1HuihJ&&L z@6=h`^`|eR7>_yvxgALd4zS{A)aBY-m2zQDQeS+b+yk!cBVUGg9%@$p=|K~Sz+ukJ z0qMAnorQ#UQlsr}Z|&=uL#wf!wYRPRE^Y)>Fy1Q11clAm==}-rw5w9CNt07ytT6%Y0!LijKWIy?YajwMcSKO|kY)>BNX@l;o z6Ur+Wwh)YaC~9M4C52#<(c{hxJCM{dHvBQjiA80E6`nPRZr}#b(S^W0w+u>Lk6xTC7a~E}+A|^0e5>GqAx7X47Bw=wYVe!}eC83gqD9Y0>6u-%c z58r?Om7}kiR9rfhK9ZJ=mPlO@bBSD<8yo9h>mD0JS&O;sj5BMM8M(zpPee{zSWK>G z%Gp`$16}DZl& zOxW1y9a#$(?cypQvFDW@{SqouD$FT2Ni`sfDk&*_XuN%(pC`YrG(rL3&Wm+Gi2!jFY8DN4kYn60RM!;PQL`a+bEwgs2=_??{g z?U}W;wY~x!dVhcS^irByTVz-mQnag~ear9T0DX79;$%|Cz2Lb~;J<)I^ZXBwhapQF z#Sik<4j-=B`*qbQdWopN(6X~O)ls|<)9SpQSE?AlTII4c@O*bVYpbVfCfM-#R$C24 z`v$eOSxe$crsgT30}2WXlY0}=@f%Yqt(JR#|9;Wr%>+~I&6qWlcgUw{wG&(4cNTW0 zjK+<=ZL!*S9=qk&&D_;4U}anuI-6bVo1?Dnpo+JVxIYuzSoc;u(*N1n%oYD;a{fPH z?Z{#-g_afM5@C?2&9Uy>j@T5Z49k?01xXzx-XF&{qoCnwq)Lgyvf_xd5~b7A?u?+6 zPB)a8DPgmErLQKTOI?_6^iGd37qhu4N} z315^e*wSWE`(VS6+rkl2M)VM{Ea-lSGlA#^#i`5kyWaqJT+|Wz&;6S>Wh9J|He5XiHKg)slc$qij`ANT0hJ-FD|VvIbrJ%M|d_S2Y%+)UGnpW50@?@S7ZIu{ptn%^xDC>vVe)~}gtY-zcX zR_~uL18(Z<>kX|GeN?K5xGNi3H4KM}VMe_7huwN+wN(Bh_X{U2{}Apiui1GN*oKqe zMn@lI=1P2_`pRF)&e6W$)I)(5xgaE&KWxrpg&8D?yzJvwKCQRPrH((~({i8y%YlRE?O3QLQN*a zUW|afdfq;+*DD4ay9X1`wu)f3BcXHh+A`#Ia+7X$T*!V`hEpMkcEYAZxM z$Sf*BBD1;C#+Nt1qjZq|1&OShE}!NNZ9pU#!5bbF&rgTNth?AQ7E`I#9&yrBr<$?8y{6KSSN zk1{i5z6~K6LpL!hNaXBJyo;7_nULZ`h()Gce{g3|?4%g{XHgu4{XHdobt{?$cdEdfk_Lzr*rk+y7R} z%3llcU=CMKCb>PEN%J!GYi@7N!<*I^Jt_tJQ0&QT+6`)SdYW?I;84gVR-K@1P0QNn z-Z_l5X!cVp%YGHwslzE7w~$Cg1;Z`jsodjf`>5hu7J{+}Mr1|~Xa9XzRcgy?-upDh zP(8UEV{cMI%!I3YrWKJ@k_N|q{`mg=sf34UMNs|>@;_Jyb|{QDP9Vg7#VA-0aq9)U zGtfmvMF%JT@D^&A+<{?!HzC;*Aovv+<=xjW_4pAB&GO#T;X$fOvS1?Q%q#pA$U8!p zVjtrpm26k_PzkZ}`qg##8@p5y(#!Wyb+|el{Y=5UH2c^3mMLMqxrn6ro0L!Iu=MqL zu$Ope;Bs`_XiMOYQ<|#R*Vngp;u~14O_DCo#nOKk#M^d^_No$giWXwe`!<|1iXU27 z*Dos0{N7`<*<7GwbfGC9M2;z%_tMl5at{d!@$~d;bj&b2L;Ts%(XqAAF3ta7S{L$R zDe~`3KzvxVR@?eiN|Ez=%;c8I(hcW?<=&l?BTs5v+TA2Zy1Kjq0v48oHC>d8WL`zO zHy67>tA@SZeGa+3ydNJOKOfz3_pLGBHz43ik9#Lfkr;-u5sK@Pg`_qeMH~|#uSO#( z)uFzz8&hmx1ReLOu|9~OMWg%!7Baf02Oe zzez8l`?}O`K2O*g4sCU;u@jJ|x*xk?$9*@spjJBEb?=-EpZ$VgKtyMtVNplIzvnw* zKpU;}VZ4ELSXhAW+a5IexIe=0s+W?4wNBWmw^GUT#|(bZSMDmU7H=V*3{2-20NRLGezNO5s96Q0twl0B>hQj0Nj3YLMo}Bm)a(fl zUnzwu-Th!wF7#F>3{j~mFlg2%=AYmZ6LROoL-#QY!0IT@S)ZS@N*!F|yRTF(aP~_u zyE($hqud$^_#;Rpia?}PbH`ygyDExvO_`#^;S?K-PMBF8(T_zyFO?GtX~_P$9>5>uq+c#Y4BM4jxX>%D=cRB~8T(-J4F~1r4 z@kVD*;c0q7tp@mdRy~uOhfmdO4+@pjj1G;~&g;YSQ8~vx=a-L39wya>3JKJUA{e&B zAF*G7jW;kbFg3@xVC2)@C26{&vRQP4SHk~`ffI;}| zKNA+NPt@D*0~uewqeYn+Pwx2K;)=IP6fdK?wE=y!C|r>kyGay_n@m{#_0}DQF1|=5 z@B1_us#nCDpTB8wi7uAdzB=OIvN0$Yzu@DtxwkvdY2#Kb{qxrFKR}+``knJcdV*;m zuE(oYt|H}IdUmGwl|OrK5c#V~HStccdXc3AnZStxCSX8U+I%*kD*_@%qr04efhJ$o zsWvG|HE3NORG|fZe(h=kyCl8$`*wT(N-QN6Cb!eEm{(TDO<1pcekpQ$W3iEomuOos zx@5#OR={{)q}rz5^w`c26jY_zSUeW&fNG(ub=M^o0)6>iTbvKXe?6>EQ_R2NfyrmL z?bId*zs{wd3bkl^5h_rsOzP6}M3k=^z- zb^*I+FJ>oxeS6zLsIz^uK)QALchOv|v!Ik1nt;A~;K1#yrIA4J-d4g=K&^5L^ulMb ze7Re6u|oD2MxjKgx{IXbd=0_6^CbDNUIyOgFHo3+`gIz@g*t&!S6wiyk!fK;bY%Vq z@<5$PmIWP@<=6TZu5Zy>`YHQqxe3`yC5JZbjn?R-INtcw^=oh?mKJoIt800S76iU9 zVtx=(iW7W+|9<+3y*7ISI?v-ZQ&HLbU(`<-^wqA=)Gzqamb`ayf7T8x#4U=P>@AB*bndnP5=8>MEfz08PCvqY zJ*X>YEh+-X+a(?X-N$Fzj4!OqVsmnGfH8I8ufCx?OvoNne7(|O@&E{DHr*B6m~l*P zacc)CucpN{InTJdj)Dl8`^K0V`!%zMs;crEbv{>_+6@u&hAj!}Q~wD*c=|bLyLq8~ zeHE}Z|8-dB%h5J{TkWH&#VVH8`q%UqT0;UOH#!bTOFA}NzRDw-0#;q^Ym7us&^Rx= zuV5+i+gvED8F;CVc?Y#579)_IoA*&V3|ainW7M1N~wR% zG4jgFz^k8dxE%g&c~|aKqd)RzRKEY;7%?llaH=pI)~&D4%E=LvxL?HMAzS*>EcVIB zy>V1?_B?8=s{7UZ>w@ZuI?HB+da{HqT9#PC-;ng)^@ir~)YJ?7@?6(`53B^vI9Kj* z2Q=B(+#IHwTFUnB3fkUYq4#k@%oNRZA5SwFwqZspSFbkG6XqKN z+8Z+5ajvum;?HK5eo%||e&=TP_&6JB5w|$sY*D#&B%^($XtMoXp+Wqz+@b@of-ePx@>Zd2F;zE_Sacl`1|Tun%$8&nWN|?--?$WftS; zRi8h&3W5A`XBl7JrxkZVn2jT zFM;7hUU!(sO+E$rGFQ8E#01=1NLn{rEpJMk0R^Tp?3tTJ}+<2 zHBMiQde)$)VgxR)Lv^CRdh1ZW+ZZr-;SMH{o?ch?$e^IN&NVDvcrgbjj(e+VuFSw? zT{)*DYRu27KGx+Ui?zvzoR+YJVe-ov-WNrsq@)PPjSMe69=xGg0!sWTo+|U2)TEl) z$}XDmO@43!!9Ey^6$y}_uPc^ua>VpmF;%*RgRb6qbZ0ifMguO{^QG=%m{aN-Q9dvE z{XNh;yadjCfWK{WVO@l1iV{T+3?WgX<(Sm+-nyanxE^ZR|2&E@YEWR{)9%O9y2cob zxsegTQ=VSh`1?21(=$a}!0go~ep(klSYE03A|Wd1Uy9L2hi~}tNXsfIz3MZ+C5|o6 z$1JojF7tYhWGGBmg;zvq4h2a%e&*QlclW<6U z?83zSMD>WhcQ&U{z+P#1E|iF`n;Tk<^Kw8qDRsp49CmEzuN?~=p9}q68y&dk)^3Cw zQNMycdJYeQ0DJa+y`NrM*M~64?mNyuEtJ3_Xj`8hazI>+Mx)-Pix*VR*sD56?_RjN z6%(-YFQ?is>;qvT$~-?la(zD5Fkx-d{Sn{S z5VjqZkF4Hp;Zs5p_&zs=Ixj>keUs4hx%P^nYWA|hBOdEp% z6~-|zKT5PkA_-_T%1r4k;uwhcE}V9xR?{z^q}lh5F?tkS}#|2*znEN!A35RgU*2S1?e78SG6W{`=5>HeUB;~&m7Ev_&k8r_Ib!{Y1*YVI%|S(s+u|VE0p4-o$tjf| z{2~@Y$BaKdyz)pB*{4W^x?xKQ{CqUcm!ed^)qgt!zXt1ZGG0a(FCirkR_>FNkO9fc zzN$P=*6kjZvGw6KTOv=`94x{2LglX=eB0QFxoC;Hjkx7Q{#<(x&qs!U@K4JzK*k0w z+hGH}khc`+3%h(?p7@%pCj|H<(>+fBcP>-T4N7JCVZQ?6zKW!$JGv0I9V4Bvu^JHD zx9&*0m*EqmBJIr{5|+E6{S8*csAKf>SZODp1eY9{+`9>WtZo9t %6Guir>yokib ztgYwYqIM`k0T!@0v@cs5tf5$Bh>tk5sYy)bxT2=V2#F8G51ZEbyB^{N;*Y&kt3c4c=b#r)`j zVy^z$#MRO54PC=6;BR#c7}oqJ6$fpKR~KSRu@64aO$M|Add5XF56|xFl`Ftw1-H z>II=r!9jz|U_seTIazEj5c=Jrd>Q-yEPys5#PB&Y%n6x|$r{3B{N$tF`DZyT)jmW~*^jl#p!?Ih(@VJ_6TI+j8`Ebs zc6Bm~X{F#qS5MCdOuhjf>P|o-&K^_!*mshS0T1f#lkg_z40yNX#&4c?`Mnx_WMOhe zsLGP@RTxP4ku7bTgJ}!w*7G9OK8@`OpMYwi{Dcu-({S;ZRZaPWh08)YRWma`m#@3* zE?dPfAM081rAY}TLu6GWtwnj^4U^K!Wxs%wC>}COWdvFi(2_lnSG+zIP{-IP*=~HlK=$*iQ`q{h~0PBkT=FZeGqU@6DQ4z`b>=x$rAOCh_2u z0iq#%Z8C04ibg$tKg#-I^>w9~=rv#@yuiw+vT={)J`^M3#l$%9KxUX9D-q=D=Lhf< zu<+pEK}|#r^Q73OccYMjLSSK6sJDaJuLEd;10gOnG~H&p?1|witLo1r@AZGyk^z5H zYQ9Bnrt3^7rfDqhq^G~|l8}u=5?bSXU^qtBG1l6{r%2>ce(~~_;4t@L}LRmCkpnH+>) zQ<4%AC^*?U91OUP-Q8w|XFaW+3&ejaR#yQTJ254UD@BR*iU&JkgPNvb6v0&eC_J$L zzsX~TKI9vWr-=dnzCf2KCn=e{kiNnVBXCSnM9jE%3ee$Ak;7sCK^C`9a3uMRVaMUs z%zxB7W#P_Y`y89w}Z>B7Rx&?%xMms(`weV)Vtr2 zNVUp9J#d2#=$V1VzbK}{mF9HU0(A>5Yi=-%LH2};1y&b1_(8Y!=bnunLLif)J=GjH zEC`EW-!$Vkm1B*uin4W^uSthk)CvZW>H!!2sKpzb@s*aQ>RL^1xE|VR1bG=Y19$H8 z;G64sv$srBb1E!a?F@I#uNu2+AaTY*?_}o@qsH4{w|sy7KOWpqnnJH-%U*sCk(cLx zDuF-LmU_FI6V$(BcRjc_x8tEJ4)AbnDboB=*1@W;+(h6#({FjB5O_&8ceE&cYh&Xb zV@?Zkiy(g=W`4^9YGK}4F9XLEkCo5md(=AL>K?&(G*-_ISjs~YC8<0BDlmfiqAFreATgC2O`yerMh26Ear9yUzIH#0HJFe%e#z}(M~ z<=4^Hj@em@4Am;=Yi9cwqvIi>ra(y$HC@@<9;b8?Jd$)q8h5k)}9#b0j)!yni+L+(jTJI^dM%fAn z{A*n+Vdl|2lF{>j=4+;*?mr@T?~11@+|K=~Yo1mML+D!!z9Vhh`Na5KSEAUf3U(0C z`-=si@R29!Wj{NBKldgAw)9A}9qs`8walmo>J2Jzb)6YM8DcE3iQoo-jVqj0FR zD^d1J&dy@XJstb8hlu=1H?y!@n=lGPgqggiw#NGo7mZ+PQS6*M?TqK z2h4@|5KASBUo(@7Di;J9gAb~v)jE>xXfwf{0Y(U$9w3_f8Pz6Gf{{?=?;eHSvBsmV zN2yLH9=gH)=iuWqhrI>&$zUa=PIU#n#4h^M?sfmpQ?#)^Pu`c<>YsDn`e!z#z($Ey z3qDQd3CdboS*>WWMkR;B=C+)xh7)hsemxr6jtfbK2~6dH$C_gZ28NE)>)4$%ngbwZht& z1&H$E=|@eecGjcbB4(MI9YSh^>pfvQ4cb{@KXm)Ok6V9MbVqh3*>Sh;zQlWDYkd{y zhiFtvCeE6Sb!QoKH+|nyC}BV(^dXFS44dT69u}hJ69G zOeBM0>m!2=c53)?y%Pok5irXnQdQsXdSbnltotR7PgM2e!+Z8jBmrhyvPi*6u^Gl>+tFyGOyOcYwH?nO2+KFvx1WvsA z#ggt?Onv9 zj(-ny%F%rUF= zn&3ndV2;Hsb>;N;tMvmPv*}&eGw06>f4_i4h3Y$z(e;iKO=0IV>>eyUbUTm8)QMj@ z#0+s{`b7LQExueLz*gncd(3R}xn&{5094r!>^R8rm6w#enXH-Uv@+tx=YKn=w$qIE z8qARrgolufEM0mqeFc)ppGB(7Ckg7m$jnzi_s&2+;b8oMaQ#-r)S(NY;QpA_iD1fd z62T2>EviIT?*M_|*KQ5FK@ZB3YKJV2!eM3t?#4dg|I5f`N?4ceF_k2e1p^P^6PztP zS#Ba;MLH;Js{{1tTQ(TM*cvT|FO9ylX-XdhbtO+p&dZyBIN1-&a&*N$;LG4FGspEXs0X^@>jOi*(@BEilh! zAP@YT)73TeUQjd;gzm?FtSD>v7c75TWZ#2vqtWM%>C#5A8^5osg|WZSuAZ!$^KG+_ zTmA)gDDMWw$CVc4%#C6F8q2G|eFY*G8{%0<@?mHuy>E`+SuAQWx;Cgx z3zkJExR+HI05SbiaiJmm+r&BAco2K$?!Ffvz-!IynON0#q}1i^^poXo*T~DYg{rfT z7GSr5q3Y>B{{HONtsp2>L>@A|>HQG)0DQeN-%JJ@*{4JV%iow zIL?o75-_=)2do;Sx|I$uTd4v&Z^D8FcENL8*CfIHF&AkgH@YYldGrDL0wGc7AtzE3GMIB(pjU}~wXv_?!kCOos%upCs2 zpF1D_HT=K!%FhFHbG_3FAY#D-T}jDFuYArOSplWZ$!_uNY|U0EsMa;61M-= z-=Fs)B8==6Y`DpXRKrAjfb5YWTmTe48^MczBBqS?Joi+z^LUNTtmf(7T!;-b%v!Xd zz#+LepJc-CgecFIp}i@Udv@?jm6rRLAa=4&=ac~U*N@<##qJZ2?t|L6vhF8NJz@CCNZQNzZm(ZIZR!`&(BZ2 zJGC_T#@YYHWm=MlT@rRyrFR!oe%%7y@9XQ+sQF)6SIwbq-VIvWB`*VG}6)eRsDbI2!Fhc-@H3U-A~;*k|@@Az^3TWwW)WWwT0WFA2EUXsgah ze{?cJa;uT!UtJ0YeasDtj0fzMb8D{U6FGod72)N^KVqZc8 z&LEtwD~Z5c;{()PWcZ86SYs-w-`W5B|6eb{b{7(!)j`( zScs{$jYU)IDbDtfABjhg@^_@4q{l5z9hltNNs#&dgQ!p68{S*WIgrwvvK3RdG!rf5 z{gjg|T=rwa-<|~JNK>Wwzu!%qw8}Bo*ogI-xQ&SzocKc9R<+w5ur!J=@h)7my=i=Wd{pvqtw92Z2jmdZ zoQ8#jPeLKBmLDuV-!!7{^!sXy!GR3DpX*;yMijC)DK583^&F`hp6wPu{|R}%_3cT* zKSom0&Tz0lY;dmL6ksmcz4r#^LoMn34CRJPlPeC62jv^x^B`U_#Dzw4(T?_iE7JWx z9_1xNN*Qx6G4@P~4GAOR0fowvwYnp9B@fD4S<*j~+>-N%n24`W0DR(g%=&zk$#w7m zFI@IRoAfM|%>6q$FC%EqKzO-VtbB8!3QG4y6cQFY^&xA(upr@g)|?ED1c5g)a7 z&5O-%ggZl8CIZ3YPUTCHhFUjb8Xd#=5`02deg{i#7z#)zvgblcjgk9>N@7U~mcvJCD=u2BjnQkxGJq%eOfT}rB?I-d`{XG?p zFq;Odut%O-vx>;0ACafX%cXCe)U48KmARxK15b)QZ+^i9Th0*20#8@&F?R#%POHr~ z8wxvUR=*BI?w}DL9O7V|ES7 zpMlOTM=@7@wYi~sQN>6k#v#0dtx7XM9DUW1@K<_w&Y?ZtN6M5{aFV-fe{OY~?7$fN z(RyS;4G4lO@p=XZ21Z5-STC};d)tD3#)Z5a079Rw7PoXkC!;HrN9dC+<}km9yeEd+UhePM?1^ooJ?37KbyJ27 za}{zLZ`0q!qql12;i}JOaazq>MOU(G4iPpK{uK9Z$c0@awvfDbj)hfOF>zTU)s_9v22RMF)<}&W9 zjeUB=aQ74F&IrO@G-=?S5foMJgPK1e9s8!PE+jg7yPI31#yLcMIq+|LTRHWEze4=R z2!Mt!kpTvxqw@e(hDj0Z4nt{Jm~~D8cR|ALCPvwdR*UiBWZ~}>(_}LigAHSLCfJ_O zjUMhTKi}m>ekp;l(r(0uOTpukf`yuNPnFTsWy0hLsv!ML`y?mE4eh=xB!hU_? z%M6ef%+NU1=!k8Qd26wnu6u5fpo!;bd!ZG*zaPkZZz9pab+;>Oe0$)y>0GA{TbnFLFR2CBQ8L_9Z8z`;Mq7ihv>aOfNAitcW?n`O)>iSJ&A;Y$bw#2XnuPua=Jo+6Evi+ zuRl3Cd45pT{pWbgByS_5%s~)Gg+41)N`0-oOj1^q$yFaaV z<>tex%b69!tQ8rkNhj>e^`!z(#Cf3m&jSKywyx1zVgT%3@6LJ;z||Ke(*Nzu zD?E>_4RL4IMizVSSoX|1YOmgI|2O=g`|*!64VT2d(tYmY%%^D}AaU;Dq- zFHUZA_imqA(E+*Q#NAKO(6#2ito`6{y&`3LPMT@{Y&F*`sABj%^>tO%dHT9C?I7RY z9K*9%%r()$Z~J`(-o>g$+}#=q5PGM<2d1AvfW)QgwW2%$J%j2N#5jmYS{93eP3Uha z-dvI@?E_Q_`@#>^dv-3oxo*?f)AOpf22BI^bV2uKm0bhz)p=A+!(-{>blY^>YVN{< zlMZ^s)Bvvmv$jMbY(X9?I$XxYCN<6RH87w1msy+_k=;ONF>Enzx>l4Ix281c=(=a z1|(F9vzA_9^lvIg6o73?Ej`~gH^;aqQ12)b>;08F7**%7kct}(q;pleslH5q2Nm=! zogcr}2G)0%)m{vA4k)IUhSmD*^KxK#-&ab3U|bd5)4IGh#F2K$j4RCPz>`c}a^tai9hz@AO4qR-!03D__SwMqdP8Q;_^nZLWH>UXeicZREqQJRg?55|gT8 z=30F;plHmK%pzYdE zlC1MI-&Tw0o%!8e=Q9$-A;9KwVkS))+iD5S4ySP@H)hpZce2$ArJr{dK}@!Pccsah z*AEmRG$hh17%% zTT#Vrk!yc|^2v4ClQ#-9`nOT$-_VfHiD_<*SojwGcdkOAr{{>xFm@vrO3-Lp&v(_gwHVU@lYV6@D#3j(C@ z`Rmqp$3b7A^%MSeKu5BL>t?X#LZR*uP~uGn7`!@_ezKU`61!Pj4V-hJ+22DIi)GKe z6S%J{^u(oAuPLrst3>f&PZ%*1>Q=_8RRr@Nh|%x$Fok7WV8|=Vp7`kEBY^h24fsIK z&NX0Jwk7?o6IqL2B9BV4877T*377b?MNQg-%$OKV#Jc{d9gkCT$b0 zm2StIxYxj%yQZ}BK4Iy1w!kc4n@)N-^sJmRivIEf%?g+QJnYd0UG03T{@GXG{3tD4 zw}G>=9|YOwDiZn5sGqi7M>ksES!BlZn9mL4+L{|8Vq=4YqJ}jyS%>dKK%Z0+!K`SKcdwzA)o1MFvMkMn(s9>$+6iRrN`@e^6-~lgoW-+2DXYj=iSc7pZA@(U4$c zYVE7}9)A}X(|U@c_~P%MpTHp@%Zg4#GPg+?An4qc$Ie3Fpa)$lV?%%?a;N$PIhm#W zBxYyk+?a>>N2si(vW)sLg)a=%-uXYVd51gpn_b;iVYpii*ljsHI6k5xk>yLWoC)Lvd zt!7sB-YdoPcL#DS{+zCIAUaJ}ahnuVlTOA|4U_zcKKlHnO^QEYLl#cX&i|^r6t94Q zno1;*K0pt=*y{_3p9T=*^Kfv*Pg+3x&ab8EIp1=KHN<>uO~0tiSER?9^(wyo!2J#= zt^A_C5q%|g!F4j^&&srW>US?q$#gT5@5d4?om*`z1lpbeG&-l3V+AwI>iyY2VBN-c zE_~i)-O`W{7#yu#(1(SPhPy$uAQ5=on6E+cC>02FRJi^TqkNI^L7TfN(rv2`)$V?- zDmP!jp(VUZ~H4-hzj8w05`*QYx&vmDeR1Fk)-1G;&4VPQVJ z^r`FL?JIW(^ZS0GOrqCtpY3x|2R9A|{Pn|1+wUo`BDkL9P`-RgzLx;cEv zb;`N1aeDfsQdL|5Hk$S4bSMXmayA{dVsYzeg(8mKeEXonSBp8U3i$!OIzHEb3?)LF^{@%Nd@zx;QQ(V?q4p7!QWLoh>F7kjfX=g|33>r&7J4{ zxs8tJ^ph1ciVYG5q;Z;XW*wR!mLaW)2#JfMG&cjIvEO;(OPuVL-}W;6`bCzk-%Ztm z9R-NHIRE_apu$o`Usivu=rO!l)b|5ul+A}9ig4(y&%a5|WIML=UftCv0g|W236%cY z+Gn_sGO=tc(KHmK+nRs*nljB|#Zj}==#LwY+jJNElO-zA zs#6?jk%hP$QmZc>S-kUWz`Z9ZBO_ykJG{Ah5&NAJKR?A#u#!#upAJyXVKVaI*wNyF z@=qarB7A`no}6J?PHm+^mbuDDkGe|iueGL6UP$DQ|5b~}>UJcI!^8V?Va-&u82VYc z1K3p|L%-#E)c)A(N+S$p4MQy#Kn(aNUd!kmW8w8LoL)}-bBlo6u>ZWPv zOt1S!32VN!F;DMRYJ)D6)@!^s<`-8e8MePxCdwgnsU!wf)q6YigqfBt*M6!3&NN-@ z57q9(yS}%VzdTuhOF+ zi&bJM=8$70hla^vWKKyY7Lr)Z9FxPG&u70^-|PDQ>AJFO)_bqlec#XL^KnmBe7}r8 zJl@mLaQ(|!Iw(yp*o!Eq$R(G)f{GiOut467m*cafj*>7C!uud$xetlYQoIn*Uq$TS z=_8j665U7i`ztW4J7GUuDYN{yh2TYJ8(tpyDv6Vv@vWY>-YwH;DL{Ont=$~tFW;wS z=89>TC08(cZ`?XD`W@I&uH5**&2ir(N1?SWWBB8osxQhob`++afFWJ^?S2`UA;0=e zCnO|vI`G)1AIo7^y?gkGc^Vom&HnnNG33A*h~s^Vku4tj_A^BHTL8uBcyVhg7R0SG z>W9^0?@AfsbQJK=W4QkguYS45ksv4`u1Ie^+uN$mw{;W$vdPQ}%=_fcJRh8Ss}Sq> z+&0Cz*PAku?pe{|atRx>w!U2cN{NN>1jsdoi1Jk zUhE^h{KNsyEFS&Nt+*FT8$Mst~DEI zWk@6+eUSLuqmt;uEV*d78FDW%r?V&t8ATnOF~ZBxJVmCxqpZ|J`zkP9ilC>_iC?eF z$~6~vMclDuSa1GJmdqL48|FXkCoN}D)ME?3(+P_dpZP1F%J=D6=Ld^zB2 ziVE)(7|H%jNxIy}2KCmYgZhgR$&SliQ!Tr*zLWz&d$cxl`eeCOfq|%o5+wHg)vig! z*wGnZH!<1hBR9knzu=!e5pC*RSg2C$^WEMEXp^bTzj!E&y=C@FM?&j=C zNKL}H9wyng5`i5d@|C?00>*K!qjbf6HAk-Y(B8c0-odaZMy*T19ZM7?l#Cd@MM&PP?xSMMT2F71|39*i-e5FkwpP^x_-d3<~phbadS9 zC-)xhbVr`4DA7 zX787BXGo;WCS62gzemXPF*2A?oItXuCC+lqotA z0y6W=bId7LMb9Jl(Z1nW#vcj_4i=e1bhG<99rBW9F6oHdI?A|rjHlm>B*v2-LK~ET zLq|IKV#m_62;l5GF&?CT%G$!BFE*xg@LOr&t5U`c2#D)?!Jd7F6H3^h3N& zG#!ja>Nn_vj~D;6+!hTMSqqE-kQMq!x&rcr`+K%2@UFGM!v*Lj4Gp_aRq2Fhv7_pN zt3;o_)YyDv_R7CjR&&DHKLi(268d<4Z)Y-VmC9laKJFUXPT&u<=t)#~Gbs8v!{wSa zm@~)F?8R>xCP8iS*n;=tfowfBbJ;kL!K?LkG<=?8gG!}{`GpT?6e>qFKr7Qe0{mN; z9RWNs(0AGwT1|@wt;s!FCVPk_rFO`UK&wZ z=b#B9>Rq|yBAj_5rcBy1<{9)TQjnggl*?qJ-Zj8QvodvkeK&VP z>hzu{5ELQ}i-b2{1)q^(TDMeCjD#pBh-pwx#$nRo!_~F5oDeCp#gXXeH;53E|Cv75u?b!@_TRS%U6(&N`&>q^tZVHHRU`k;7g>7Vq#%=4+aBod2diTGBOri^2r zstIS_2}{$#Rge4(r-W0&6@GDp5TJ6r*^<)uA?JaxpNewUrVLIS3yL zgpN+BX<8Yh-J1R0yPL4bY<_s&Dl&J(dR!iec{e#W<|U6V`im*xj@bQQN*6x*?|M4P z8?dy|zqTVy_h3=42*qTo2mj?Vw1PHcwNQBvM}Dt5)dD+t0o|2?rjm~~cMcB^KT-o$ z3;Gd`%ctT(7ZX66^m&4MVa?a?B-4Mssq&UtP8ufuEPJIC)jAwIw^i0l@R<$BbnN90 zZ;s1?A;3jElxLIV2nkb({kzoLX6|QoD(jvHCjx(uzLM(2r{It-oS#F4?xQ_M{qnc! zO9Jzl9&X4do%nZ!pPI}u@ruHPXNi`6trR>@e)W=@DP3iUu@yuU(4K1xhFl_Yz&8JtxaR>g*{mwIK`w3YBCyOQ3*aIuu> z*<)G@6J;G;(h<;!p5?&WT++`+J3|zPa?9dUbJkP7xlbM%u?jg*d&G%chpGVwE$mu* zhQX<8v7;(&mo=aPwRQP;x2t_AH5b_09Qg20Wfn!eUt@@7se=B)DtwAAib9Xc!M-8L z{a0uY9EVLSdbEFC`I1k%;ABpNG?$1Y3`K@>Ev3h`Uf<48i5ks6is_mGV?p~uOln5U zdkpUWi?N{Dz~kYY1GRw$SsF__`N!@2=7y%XPt$!m_@#hF##w8h*hiUz_BWws(#N^( zOGqH{k2XWXwmkboaY5>7ZR#DDX@$mj2XWbAlJrHO>Vj87v{-q5R#AooZB7{WPx9R! z9dixF;dCVVL@H$uX5$33)~rKknwG}RlH?J7=SLgf)L%YTyS5vcurRT`-H%PD7Zk|P zLJ&)(*Q;xixHk+5P-gClvO+eS9a7({+6ZmW>k9OnLrMuo`-}KFl}X`$U@ZpMqTVS2 z`Xs< z4NRZ(l@C~iQY_k??;~~2&rTTI6HfRgDo`<%8^+KRID{bzU3uJDpo=PK$>r+Ux5J_B7KoQ#F!&{GRSgX&?fgcKi9@ZV!MsyeiVEeC>#3RrqH{ zleQO`o|Q(}c2t3JL1K@LJ@3)*H)gWQ(6?gqIqql)a|sIQi9+V*HD8SzDdy$np)Yo< zv=;v8kg;}n`!kMl_qIz0k!)ZKNh+b9io-LI)u3Q;o0R}^keT3Ksc$i%E&yP z<8{sY%#7k-M6PM?#;d@nIj_bY~nkRI!Pn~ z{jvfk&MYjKiMIK+-y&|T8k~@B|z3PGY-Vg-(YV1U%%B_zY zBH#aZ0Tas+Q%FM~-MKu)dyX#w5dWk&+08qrEUPPziKMZWGi z2N*;bxFb&G5MbWe5Dzosg1!bD2mvdSM+ROPKOFAZGjT4bT2nLu7kG{KJGr}4aU_K5~Qi+KYxZJlug)b*5<6!vz(bl#4mr-?K#9m_<1k|Foa2R za+-SCH6A?<@CmisN#3nadd8GW^q&l8XhxUlbuLNVF^15gR-qW$8q)X~vVpw~RkOg^iFGC@fw zG0VGzPe)$gT_5G)KV@NQS-V6j{_7v|XsO4k44hZQPDK{q^PBeH$Fnr*g17#~@=D%) zQ)h_7U!Zl1i$mF!d)aMHK8sT+J|4{Nk?qr7;BJ(%N1;HfTgeDhIa!pQ-KL}&X`}13 zq*cr)AQ@Fo-SrH`mYCM>4L=`k$sAL276kQ0`95wTOu14j%z`0t?t!9Olv;o3Vog3N zptjeG$pJgTIi-Dx20`E~1M9NfkH(p6S8nF%3f~@fs-;2Gj8BS8=k*%vs0ziFN@sI5 z8{U%AsqFQw9!|H%gN`uj9og-l^8xy{(?t=^E1!*$d7_||L_MAd{e@CEai~Cj%|Z^! zA=RDToTWgYUEOMIxi@)SGr_rcJS#+PVhxzN26v08bdbWp!iY-ank47V~K*XpN#HkUR=N#u5^ivRgL{Psv|>ElwfkkwuwAd6@jb}44) z=Xu<+?9OBh*#oAND<$fkONr?XsHHxMBozCsFJ&x%V%pAV`P(!6_90VWpsHf5H&*gu zZ=^6!VD#9wa>%Ii?nK<~Hy0aK57<|Hi6T9!^e1uuoKD>G8$dH$SxDDHaj zBkz!2q4en7?mL`kaO}WS&+^Fy^2@5(0;B33z>Wx{6tg4%borfHEs$6rkev z1V=Lx=25{_!}rARKQWn3jSV(w?zG0?4Cd{QtZTw?&F7oXv)$>KyPRSE|@QJLdX4g=MQ@BY*Y^>8X=(8bwSv**^~IsP6?XffjgbeSs{IQV)jq2 zZVFAD)uFQ5T`AN2RG=WIp#7`^Eujn38$R|nuxDwCPhf(mr!cIg$sHZ3MC7?Nt`-_Z z4+>JQ9ZMdSfjHclYK4)j^Q9?Vbvp1xrHyaw&dvs5gSSW4J$L>Ns)Z~VeOMh?JPig7 z^7cRzYps|OgSs=5Fa?SqRc_y?PD1@<8Y_W=X?vt2bY&}ag^|!A`(-_XU&Ah)M^h55 z+JAzlZjBMTQtMFl3v+O9C~Ny7CmR3Ku~+LACq(QhtHFGeWZN;T78H2kfOEm<#;(CDQP~ zJ|eE@!3>t}Yidc1(2q=|N#f=jf?IzF)Lnx9ia~I7IF&^-n)@4CSXs`_&N%wlnH4sQ zk%SejWm6pK6~Qwx%EeAydhu3Pmfo%kw37@=IflSn$@#xaW-#vBhBp{<#!^y&L=Lcb zmv!BbHecEZQirR>HmctKm?8H!c21P_k1!atynepYgN2}-O^b2EvY=dV##Q)5)#uff zb$XsZSKb@q-}6$>6ghdao6?_a#sc#M2d1}2j{gArP;oB98q`4rE4k7K?RDeNVwg0; z2Z{fIW0n{48S<~HAlpB;g=u&0?(VwQT6rF29Q>&mytym|gsJVn=APe-4f5!{?o(dp z*g|I>pt>8C=QwTD8D{O{8T!lXooBRv0Q|?`u0hC_Mi86T94A`8v|^n;J(HPbdDSE><;ZyA86LEyj8)*w(5b>|DYyOJ>_1D?%P-m6H` z`=)O_AzrxabL++27NN8P6+^_sXm^SkU=knQ#3BBxVy3A{OJI$<)8I{UO$C~xRp55- zs7Ib~!1Xc3UiS(e?~j#Ph04drW7)=fAhkmqEn!oMcHyta)tC-j3%5nv1j`2Zb_PS| zcr<`}sMg9k;F=FcS+5IR=?6dP>+8=A)NauP=l0g0i^geZ7fkk76h=o!=RO4GClw9Y ztj$Cw;NFc6?p&?+yOxHXwX(3L6!Cq59JW9`bv=vUT%D=zY6>VB@S;Ju(wSN)%I9CW zE=fnG62zs}>N&Q&zPcI1batVj9nE^6RiXBB%v{mXZNL|^75Gjj^8gFf)k@&O$YUNx zRhfRLC;^R6LOd1JPZb!7k`}7ixPU}Dm+(U28O*LamMCLSJX+{DicYtY)EYBYYIv+7 zBr00JnE_x3yQ}qE(YrQYTLUci*mQTaplIl_y*t6fe4T&yxdt9C4$YQ70u-FPP^|k^ zy)Jp)y-m6LJYs1mxBbsa{wPvk?`z54Z`w7uy+ec{z(dLcRR<&H0c-aSNw|ATKkuq_ zI~6>i@)pI67*}!p)xc_47)hG_uHXGQF3C*>6Ft~B*o0>IW4)GOHy-)>JMzlIjvyKA zHXC&sToCxKrXF3LJokZg0P)G9_!bkH^J(T@`*?IBamGddSD%1ZgVb$kk5;B*%VYJ< z&!(|miik*UH`a_Vn>ybN|I& zo?bcE_-db1RqDmwQ(2ifwG8SjOu^xE6qkyJb*x;&yzB?;t&r^Ux9^#A26###&^~RJ&ErK)tLs++L{`R z@6L{9{Z#C|q_L}W+h5!RYSFR^;o29agcw*xfz}Yu;5tnXM5F(O$f56D4}D$2Ewbu& z8`N6RP)m)P(7j!Haxc=g>0jXB zD8&P?l&7D1mfq8s*_v5KQDPQy$$$+~(I&|{VIYPFMxYGqoxjS(f@S$kRSk_e;5KUu zD*4T1rs?OQ)3UR(JFbU*sd@@?MY%DR!dyx$HZv1YV-D&Smh6os5bc^C2j(E#(D~_> zgda=#adD&ac0~Q+;vF#+HMK8rVf%mi-?J@f;hn!}o=#>!L8z##91o~_ITfI!QD1W; z=9AC(s$U)8k8BnV1}sebr{-V`j2{=*h3;C+w;diIhs8) z{M1`GDi4ypgja3n4u!uw(o-=5{^;A;osDvP{duAq+F{!op_`ud3o)J|S?OOhW;;6p zA&Oxl_*{7v!0$rkg<>K;E;;Y*4jRw`9W7^OX9OKJ_dkI?jxFmgoE-?9SsuA0*NTqp zfw#+ifq%XesjV0f3l}?#Fs+!Wk`04=5IPDV3?q`)Rj+OE?2U#lt?dqkcBt}4gdO=4 z=rKh7Jkjeeq&3{#ons^;{)4&7L<5s%+E?%t6r6{H{sl2gwE{XGZckZ?-<1 zaGTTNvz_YRO#RZ;y_wLR!JYBFrqGS4bvStb)UIjp*q&ti!p<29L&Dr$2eD#`v6$f9jd76XJquE7378(q zng1HPyRQJkpNp6)Rq?{LN;8-h2IvJop&;Q}8u znM_t0uMVtEPBzhmD>+J$0C{-8=4JGOqnq2^1wAQebrf=mml!Jn8M5O+3TZrKN3-eW zCJ zXIlvj{AS86=_8Kjz#~OZth-YwJ%#H`hIwMPweO~T$`#vmtw3vEd`vpEDmT) zPZD67A6w6yGj+~uHWcuzG)KCKJgsnae&}kR)ag`W3WN+cIMo-18?L`|C}UkHs#{Df zPR{^w+KjD#wzE%whQbqJ8>+IsU3Q+9;*j<@R@l!j2i>cL6*(v_Bvq=;dab*Nnd(z& zcBnR+o0-+bK;)4hS{zQNaYMZP{d*NJMMd!N4{Y!9hrpT_qQ~X<`1vh6%4&z278Jhz z>*sptqb3=W+VBqNuH55uHA@E#;j-h=oi<@&-=jvhx6_SMbIo(!&jmJy#2NMd`m)q7 zTDNwyYYL2RoI5hXAlAHKELGvIlw)rNrk5!VPPvh!G7z1K(5z&RB?XVp-(#fgM;CrKddue$gQv1bR;5#xrn~od#&o;@qzcjiO zkN@L1sUmypp0Ep{6Mcr0u#YxjzIC(+$5I@3b~gG@zqbb9ee3*t$s{sQt%v2`Og7M-w?HKuKHA{59I-aAHIiHxgbO~Yjg8Ndkv9<>Cp{!dGkbfV?6Ebrl!-r^ zK+NmK7bu5V+A{_2Loi%$u>TVUZO|&su5SJ+T_Wv%P-mW+oxAB$(ZUUZX?23`C3VbE zg2E(;HQvQNvk)#!FJuJ1w4^{^UmRO*VTRZj!Ref}4E?DI3JyR(1>}9D) z{wx<>e`3GVm@j+RsTY=Qps`ba{EEHOjUT@12(#3`1al}DRnGYD_Vzv%*0!n)48T5t z86h9Cc7M635Z}$-GQ8i7rrdt6e3E`4`nz{gp|ntMd67q`Hboma>c7D0#>|Rr^QD2n zxrarAAzRTV3==r$Xa%0zqEMIubdEc{RK=j|ffU75mYP9soP5K?ig+fTMP*m`S0O8s zW~@3u1)B^q!zD6qwHA^&zH8?mriN$P5`a#j5_=e7glxtV6i_ICKqXZ|qs+cYEd*P; zMTq?&fFoE7JeF z`8UbK9HX0>m!Z#dKV7h@bF+xY^MavgQh@^yV+#E0R+nNOD@nb8ZvBh~*Y53JL1m6d z08H#jDL@_se_6yXM(nzl)KIA)e-OGe0MveU1CxRnqD**-Q7gtgGMCJbh=^DV zUA7g_68ikVp-22o&)N>@`;zo)8RPnG`rtZ!E_iTlr^a0<2OMeX;#|UpmjQ>rkHxwe zbwrH#o~iwzrVu_(@ae69Ac|u0pDOj01LB6+c0+Ai!3ycPcO7VmHz>e1ydzr6zi-+7 zAV+Owb%a9yi8VGdJu`EEXCcE)_k|ISpA-5D*4AczyDtnJ+UInRaP2Fb?n+1qsa#5{ zUl4AV%c>9Boo?@xd2{T{WA#%YQC3PW=RQB4JlgU;pA=2ME1tIDK2_y0?Vs+m&a<~{ z07GaQ-a~Q>o`>I+dZK^=Ns0RoA7FOQmkuMmXyRjLC`)V0EAP~({+D%>kWp#Md>wM_ z{Cxan(gqb~RuB3h;yGic{Uc;i$($tiAx9#1_BWsQH$cf@RdC zl8&_Y1Iu2e=gy}y#_SF626v_}h=z$P zZY5*{RnImX%JFX6inW%0_n}uLU;=!xhq*Kb{OF|CD7!Q#LT~oMdr2g%sM{6ik7EfN za6#xR&n~(0+7SK)8fx{Y`}FUdkUWB#|I=nTzA{n$`$+vY1maxQ8$kJje`*Vbe5$MS zwHWlNm8Js&{o7w_tkMe+V(=L4h|uO!!?S1g&XO@o;*xCjW6%PzXbi5d38GlW4_sx1C2k>bX9BV z;~3^Zwcl;GYp3F(->pw%#{srv{8__H>o&pY?w>0)Dmvvo^lktF5Qi^sBJYGBF0V)) z<2qWTX#X9!zx52KOBJzVULUTC@D^S{ME&6JtH{vR9^9E-!tWww=XuMF5syGGU4NI3?IM2qSc)BUPJxHX5btpBWPtxSGWtua=6s~Gv#sx zx_vNsJR?qH=TU%44tZ~C`umNcjVJqVoY1o{&~c0bc@Z}=lrbzUVaGyJ^Pv~kzn0~} z)A+WNieak96m<@+4+Rfg>8J-(P(rb6@dtLBhsQg~aA>oR_g+IIb3;A$zU&`w%D`*| zyXTaM2w?8-fm+qu(=)WB@05sWkrH#pqglo8 z4J%8xR7KYJ>N?1U%%Km;(?FKIeZO`gJ2e+8T#Dcwfs!E~L&dSkJg&~D^?L|zvs@?NdEZL@23(dZ3APEXlJsYkUK z?@1nma|x0JQmMDtd$^yTUMNk14`FctvQID_CZg53?PQgh$aymEQ+DUa3-nggiO-;p zA%_8t`h)R^jpraTq^3TPN;?zTeTdyB2~B1ndjxwca6e9gTx984f#1|g4al@kS^@3b z?xPF)Tqu?vl_=Ckoo5ji@)bUA_Dtlt%8v_YsO_$tPZEv!&YfZ4(sIqDleE(m+uliD z_&2^DJXn6o7DNKizZa8Ly{_uNI^7F+9o|*C@$V%M*z1}lWde<*BJH%!$e7)Ur*+Z8 zUO(cxf=Vnjb$uOkVy@Ns_yO*V$=&wf4wrP|zv4cOR}(JhJTL^91j(q)o!x-iBqI)p zdI#Vz!+zpe1CNQ1e`V*h;od($f#|HP3}krqOyJW@TJf&?J>!c2s~?gIz_>h)Qlh-1 zdhR{R93!3kYb8R@koQ^Rm}?I46;kiqXf8?q5x_hDjHZJX75TUK)Aa6N?LimiCFmT{ z9wUG98+V|90X@+OKxegvc>sLGD(M_ZSikKg&FE8K#Tf?ZFo9_P>baZyP_R?yHS0vHUMW#Tp1XsySF+$&1>KK-|bi* z??=BWMG-f;6loKq38N}{;8Vac?U1!%lCAOg7(#SaevW##*GDcu!#BF`YVbbKK0F={ zb1!cxoeuB?{E?yU6);sAZE?ex*Q;H#Ebc)>CM`AC`}rL*L;sum?yZLH^AXxN^=X zqhc;k<^q0bS~AQqrVR007L1i^SvK(!I#pKFF`E|i&#+{f8xw$l98h`pXQ2jM|J-Ps zQ_=fd&;YVv6F6j^pH!)?BQ)AvI;H87O67nk;R5Fx8c80}r5=6S$e2Yu?A?1%$rQF; znrCHC*1hr$RX_XL=no8OwE(>?Bcw9>Py^g_h&te1 z^%X8UJBP!d{;k`Qv(5yEoeCcT2!0_x)h?-j|Fp9f9QYAX$fMv&kBddR&FB{Y^~+C+ zi9gYXgu~t>lDE{!L${xI)i(3bZckJXR{P8i%xwFr2!XuYOzQ~1T4ZHdFOmay$4qQt z>FNCo*VfA9uGcTkTZx>nTpG)jWH2ug?38)Sx#`^(I<^pz6*Gixnh;m#V@0s2tmL>F zO!XUw@Os_2QAZ9AwX(FmKIB!+nynC~T}8eyI)HwY1K#A~$hJx7WO5D+e$^HZ%r>M8 z8tX&C)S^wm)sr2!*wsSA+ zdDP6})nc=YX85_G*%j3fH)kUTIW_M z<;q3`?n|iE|~7Dn|!*X`RqP2`&r{#g($2h zxP(p|3~^GKaLZv+pT%;9Zq@HJTR<5rlpcaY#}YvS0%_0^xLs(UQ2U}MfPxk$ydJV- z80x~p;Ht=Zp7Va5<4YuuvJlVvJ=Ij-`~rx3pK%E{$4ubxqky3;TSin_*})*NM_?ynp%?WwK`PRPBDJE{gA+-MJCDGVy zMUd@ZIQgflPShw_g>ODMZplMYMB2oSy>52>H*hJTIGWBkT8V5_mYF53;Ej511itoq z*D{kpQn99=Oy~sB#xkoo9?pRtKKZ%enUe#GpYv7bA2SRI(QRNL9XggKx^7r5g&e){ z;ShuSH1%R@lU<_Y4#>doOxzZo)yviVGj~#7V`sWK*~H`rwp^*t^x%zpjYroyOeNpj zSh!c3V+ctinvr6PH1(Q2F}*Ii&`qMxEF|Sz%bUSu1W{{pE9ClwCw0-6LTFr{UL0xI z*>W_yf}_KMzX2;CY@b9&9ck7EPRsiy=~qN+_Ugu~EbkX5(REDs$CJxcbV4Uh z>MV&U!=#X*yE6MA7SI7DTR6fdjPhje^n}0zPzjRg6*FP<1o!8 z3Lv;O??{cM@3XOFJcWog>vTE%m;;alNocuI6ZxL@)++<4nZDy!V-3ASd^n4Oms)_E zEw6qfYbOy1mshbOvLl%%p;65vPG%w2ZQkGX}uEo&yp(*%5{gi8zu{Uq`nG!)~;lW1_Q~% zO9h!wZqM?rs`>N@Y=tUVS)?=UcnlO3zZjXHg8hh}=xtoOP? zL8Gg&+xZ;w7G>CTG67PKxR65_c{^t`C83jg?ppiU*x0d;Kj5JA?-4r91IeZc#TmWp z-QC68fTcT#JF@B>EX={dC646PEl$W2=|Pqom9+BclSC413X5j5M2_&>8Q9;z)7a@`o@w2&$~Wirp;7WAFORil zO<}8RHEY^nRm5gd@wH{<7CEh{#6IROjE$C%P~4~g zs2sadIq|3Ux+I|>VYvXtC;QveNa$jQS-dTQOVBJnz;J%Dt7D&b+$r_l`B9)r84j?Y zYJ%m35Xer07X^KjC&}?dfH*s~#o<@aSi|mhNK#q*zSY&gxs18HAG8y8G`9EZuBJ}k zekjEC_MXv+u^Y{3di66{_+f$YGmvuQw{!ekJ53|21FS%<;mDr=dPr7IlY9{&Nn)b! zjQM*Q5(7sUMxXPCZnwm74rb}Efu?`VMQvlqd@x{jdTiXFzW>;!eX_h9*|?!Vq)x7brAedaplf4w z`@W&}1+36*c6X~!OH-47>bd6I&DQF{sbie7Gi1_K?upoE8*c`ES?)>)8}A)>OMC~d z#-BPRk}h)cmUvx;CD^8urm;RCx;M`g8nm|?TtpfA!vCdmV7JfZ(r)K@(JO?VKj*C- z9!?$U!}SYYK4GBU_;x&?thcQ!&$@PF)!aE*uy*(}|2s=FQ#Yt@*cDlv%*W#T)y=Zv zOg{|$>DjNxjBIZCR)4`+79D%5sAo5IIGZ=@GyHy%W0zuC@AswJ+x(~YxjcEQTv^ug zSPuE_UB6hfnT&}xd(7_e<6U4S%?MoE%L?7{6#pWm(u0-HAt($G-_G%IpV2+crQg$W zGLlqkgSibmUYIs}a=NF$%G1j?M0+QaI$#&V#1&oH{4?Pd5*YDn=^~f_Wd$w2Wm9!T z&~9N@;0Ym~A1_8#xc!%mbX(Wh<*%={C~i&&MoQ5>k=>x;dsUKAzSS8pyMGHx7Ju?{ zoWrvNbVN$1Ct|qY*@x~j_N2wvL-#axo4jl5EHMI)#Li_rI1X=54N2MziG;P6g`loD zI}5^8@b?%vnI8}Y#(}96VHHkTmb$K{ri3md(|;~6j+{P#5dXdV7=SO{4Dx(d!rc_B z@f%-X?(TK-th0#|1s>H_k4r3m%pF9Z=Rf z^2t=@T;p!mE=6O@AY?66wLVoLC!bxn(_U?mRr{$b!+u1c7WgoJ0Q3lZyIbQXAad}~sA-@8kNWgP1d=j`?@;a>R&f?$Os!Wf=v)@Vjrp!}vf$wnWjREFNnAue48TP&fpw5AI$My2n*&#&91RMu}!Z8&G`uJ5t}(Qb(R zp1>;`q5Ih{N_N)l}gm7jh2;_kqW_3D{ifaedTNZjG6`k zZ&c9Tx@OUl1AQycTOY704IP!H6BLq@87W3ZZ8I|%_%kpxqL(iHV{B%FvK43nrIjWE zS`12TM4zp;C#~*pOAlKZZN2l*% z+HrfuZ)J)v>=l5UpCYEW3XC1X6@`C*nq zT}ts&7&uiw7_|cGn**V}?9+h9wUMvb5$Z1=%Oau;uh1d!n$U55=C6mTE;)TvoY*gP zpr)d=?B?jgbJ0+{u+isl$9aCHSe8h9eJi^XBxg|iBbr^xrG2wNu(Hy?DiAMn2inP9 zL;ZB*cwtYD*4NV(N!^kQx3dk8G^0>_+`)vQ#noKNs9afozFe-+Tv;gzbW}v=w>1|L ziRQIaHR@M)n)m)>Z9g4cj|&@p09Gh(+|33F@nQ@$S9OuMi#>lmYB-M#p;XL++dvk1i*i_Uhk0uq??Vc&|Qt~7%<#ciM&&U9uTru@907sHlK*o zX3lW$lb=}e^zp(bkPh&l za|s3CO^{S*&K{oryV=4RxRJ6wbX)YPp`Ez;wd%-tX>o>#;#&!|D*+#f zuBqBmlUoBeD$*ohlLx<6@bRrK_Lz7_O#vf>@lum30$XUk){S5{5nANTxMpO z*r=IhGd?j7bGdSg4{qQ5{66Bxwr|MllrGdC$h?7p!smNCKG!cP?^^w2SJ(N4gpi2` z8t)-baA|fa`ezn1+}toC&02=HuoYO{f-d_|IB;U@>cqJcY7qtc^BMHN~sg@Y&M z=D8b#C{`*k6V%bC`)LoL5}(R@5YQ8z3ce#M?}@S8JFeBQ!nZQ>a;EzJh4=1E#7jm6 zg^#KzqL1RMD`w!uX-biH2O*0!V9JXf5dLL(RYWiUZj}x0z9#hP&}WX0w^)JGpuIK| zGN7G-?4#Yfvy_n6QGvohWQG3zH*BMF)-v%c0QI<~(Nk}r+$w)vFOo=>tT z4{eS)WhYWY_nruIbANVt8L~NPQ0$}(KYDOzrcFI+gxMRz{;vj8w{XyUaHhiWh(_Ql zuegBr3x$d;RT}=Ojryq$CuKu{forPIdW;>lBx~#H_`-*rl(yOiw>uco-OJGOSloVt9$KG-$UYYrBXNvJfvaZylcc#l-i=yCmXGGb!lyrld^k z@$vCTlQtI&uKUSr<2msAv3{U)eez4lmJ4*YH+T*s`YH}JddZ(^OI|9KAYQPhdv~XEdNe^+jnF9x8JxomJ!_IAUc`IXg2hwwv;^fI_M!3V1OtsTne4!~5hr!;pp<*URHDj_mNqyJPn%BM zw(Y8@6LhiX5;Stf5GYP+*DQ*Yk^4Kcu|!js{{(3%fF}3$cuIxGTJF&X6#PH*Yq8~2 zRyc*_pgz0eZ8N<)FyK_?zqw3T(F32wvwgSLSAA#2+zE#`tS_=~8SKDsn$YaC`VdGV zn@9vfH5nylgN@gRM+Rxsuo$g;d)Zy^{>A_a2Ck5ye@VxZh&6N)GN-CGXcG)`ruI`p!1t5zt$}@ zDq|NUBwT%IGqRZ#vie$7%dFTB>rXM2E>kpV)^-C6pVyFd*o<6?G{l8gaP&2ja(WGu~Ae(#NqW z_mFvAjn3A=6hC^PiF8xXrJmd;4!|ax0L_-xbUsyyYb)dJUPszougwk?W+@i zJzzQI?nY-`RzRlcEyG5$6k7V_!KE}Rxz$zewY1>d!RZwxHB>rQTqxPh<&h5tGe-@3|48H-L(q*UX&KBPV50V9N z!I+qPXyJ(c62yO+!?Dxl?B5+Qq?j*+3vQnyA>XrR!2=OYI7{$wG64V;3R*`zH*gE> z_D4mVef7K_0Wd!TOau_E!!|!kfe^@llxjgf$s?8h{-@*p`yD%AIk7yVj;-k?^|tV# zj6D1*hQYgev*9s_jzlxv9KHOnnza(?kW!V`aBp}8naVf%2gQe%6tJ5b8^ z>3ASPAsh^25iW&Tv7g!{NruVlLF*GkUYpx_SqB<|k=gQuY(Q5zLfD(<-vgYocNdm+ zZwOs{-{?*7dUTd3-O6#prRYV(jf;~v zY=|`(mZJK3d>n>D8bMxrpla#E_yK2eI^kSe8@K)TNYjUV2X?{YW@}%xrIqzQh&&A{ z{?C^b8X8JL`)Be%prF`Ha_SxHCfsAdZ|?7m68`Y4F$Dfh%kZqur8Jhe)Y2~GX!70H zD?jOJ(RSuVN^S@5#pjX*P3@mtF@$|2*57Z!p$q@-UUdPUz1j>i^jNV9W`0slsxM(@6)V<+d;DE|mr zSM^$tpAQ09xDq*FqvLYd+09vHl-IWadg z1EOyzR57Cqot2qc7qBwL@*CU%vo;CCpT065eW~?=T83ss=-V0Jt66g8od%iez-9>+ zosE$rM}49uV<>7_+G^6@kx=FrKniTK$2m3lCVu7&pl$Bm_I za7kZ(D_j?cpBcchSN`rcJ_oWy)8vWKnn^XG$6vFN7XhTusgk7~;zEdx@S<4wXELu8 z&G|D-80iX8^U8HA2eU$Vn_NQseZM2b-hYN34Ue{bmGkh(xyBIwGo|S7fjjBgzZ(Ot zwNeGHRcQY6qwk~>q~}%wa7-DK0_hIvFf@?uMuX(1<$5k6_Jv~<+^O|-pZ;jzQC?gaZfd?J6^t|)q zU!+=*Q4;=J_}=!@FHu-HlLQ;Ne)E>ZXHa>CBYo;TV)`Emini2wArl|dr2Ru>@;dTa z!1A9`bcY36tr&JWfhhh=UehFl`jjsIJ{l_5Z$(}ST4-G9{?eP&=KN&b6CW=5>?a^8 zx_%mbbV%(w^a|oh+3!rJR*;frcw?{}%H*RRE08B}(Toqcb9%=mHM&bUI5<+73c5!R ze5}Jtu6!{9q;s6B-r4rb_NR-Hy_TW$A#+PL&`JQHM?-^EKAEz=yi^b(p7E^6P|3{8 zY<1h9iL_1gOehT4M={R_Gc}S5yD{K+VEp;5$90ckaqAVqza~)9-Gg)o^J18zLyH89x+O~)YoJbJ&-_kI| zx7l8by*(5EqVsXI+jQmpwWpZpQC>7S=2lE&>Oz8{A-%^{9)@AFHdc&eRdPRJ3@UJC zw6gmAs+z$X*&fvW;slJJ!?a^R=MeLpKAG@@Zw?K8mePSdVFDbYhQYmfKupY=I088e zx%pi?_7C88b$s#jU7P3z9u#9@VL<^G8|XF#UoI{#3Q4jw7^WjlO-<>V<|%8E0%L4( z>c8oJz32J8Dz%l4N>?DioEXB~Gi44cda~;5^U+PF%Tke=JAwk;rMh6twzs<;y)Xb4 zRZ*c(FU6{}*Y*17P*E!lk2TnfgQhqKqau)*$sYUc6(>fR_3wBO zaxz*sd}mjrgAO*z;I<*vG5nZCO-EXMQC{7C;#Of?z?;QJ=vXPiK```B6OR0i22IBB zu#C>{aM8HjybDq3l~Oa6?OkGvfr#Hj57AQ-mLM3ixLa*xm%TL(nh`4e*8zglB+=W+ z$KwjoY;CMjXQOOOkN61EvrBR!AaRbTLVKThly_ljo*q&gBzuU3!xemUSs>mOS8P53byVl*| z?@*~IaJQovGT6?zZq_Wqz;Q|Ho83w~F^VeuSC^^Qj zZ?pp|pXD|Gf)ek*;Npwj@@AJOa~AZ%cFG7)>rAmH+~Oact8$&oH251G4DN?6-PAr$ zsXW19aJ*bsH1ltROjJfuK`Suf4H$z-C()(~JUk63Y(b$NG-K7feBjXCu+l z$+JF!5--w=kS9-@He0C8t$Vcp28kTMYFm8oUd7854~~%T?(PB>SV#;9jIVau|7~Pi zmO1Hg;tPzPE_66Mr+!(|Z2H~Y{Nk`TunyW5gWz{=ekwW$cSQHwy!;gc$@}2QP>A%&Ddq$9;u9o+4mm`tlXs;Qwk|$X+szRrdv+K@UWQ@}`sE zgm(vGUP@{Is}?+{BlB;$4nIX6e(#W<~7ckcstkL1f-!DHcc*j_h^S3O$G6RlFB4f z`A?X{AH6I{Ql=p@G2cP3uHca7R*eqwB<7cwQwev*E$trGD)}ma^kd#1Iy(g?$c!Xk zvA+%5a8dOQtTG4w!mON9SuHKCvjh!1Ke6H!#(4jZ*Ibl8FvlImos?_gL_bTwfIbLN zF4_ETrJB*lr2@P0*`g5no;H(}qaPJTru(J_?xgsDgus@fL(E1hxRRtJpFp6Op@^u^ z$(6&~j9`}ViIAB}Z+tI2R2H;gub_Lq_z6+qEvp6XG`&0H?48LBr+-CpgQlgc@0pXn z?1(SGCJ14J93QJFP!WiJa!8?SE}+7+K+#&TS62sgBCZ$xwUP_d9JIhAtcD-YHG7vI z;;yNwkTpG%ariXp0mfBYCr5{$U?OmZzF7mpUK2oCj;k~MgVN&I%ImqX7zlay>C{~T zP3^vt{wFdK2`_#BqyrF9DSl7^egeUE`nWY2Mn5G0oIyb_8{Z&*f0cL0hzyyC{L)nB zNsYc`JG?UuOh-Sm9?@C__A1ABr zZZv?f^ytR~JAj3~6migaYhGmm6?G*EU%R*JqxNqqqw#?o^UuaohF0qYxN$y(03RW_ zv^t1~uuV&H30mE*DD^I?^>K5nhnp4lf_9QF3%nv-S)C8Wq*c-^JDe}Eaccr9Us#e3N?&hEs`fE5o;Jl%FtZWo{)T2b zgoTa*0Qo9A3spZI|kv_bVxi%jO_aPd(KalUsq_Lwvh5F z#?sP~+Ix}w4tDOv`1EcGfs1#bEJauoz#owjVr}Nq#!fG#bj;{VaL!8=e^QwOROro! z6@%KsXO6kKy(~lB?h@TpTkV)KC*bK~fOyzMvGn^;QyTC2I=3Q=pC1&8G>8(8c=SN# zLpP5Tjj~?Ta}S!~`bB@|2de-(+_$j2?-BJA_IVKaCme*JqC_c4eRl0P&&gMmb#$y^X=depUtSqfcG)aJE?Zjsc7GS zu^q=d{QoZ2=Ott(wE@&-o2}@F$E>z;$j9&Ma4?AFU(H)>$^2#-DHwiy429CYyP>!@ zsTP5$MIIr&+Anu4bHewQ(iL>aeJvPeH47PO^&gzylyZCFJ3NB_{axw&sKvSa%yNUq z6TBF@>PL;kjy#HYS34>u0C#^xh!J zAzCZj{6pu;jHyOG`rP?FjKQcorl&HQ9Ng|RS@mxyhJCD6aK5Yr!Pu$>xtGB@S+J?v zq8*->>sQQ(Vs9wQ{VJ26d*NTjTp0v%A+t5NU+v9hMdG3BJ-@J$q>qQJ@%N!$JFRZP zcw%IG#3bw_4rbk1NAuxAvw2F|t zdX>2ia6||rYfZAb3(2`XD$?{b=-*Nk$UVE^Ph&PFiVKx#>8RaF>756K;C8>h`(J)u z-LZ-h=%_`Zi%5Q+DRKPz9}zZ$)Jr-2Zv%Ra>);Vf0=t=g`?e9zE zoOk<0IUm+O?$0B}Y%93suXOI4@fi(Jb8``D%_q^38tCQvSS;>?1r#O^`MfV(wH~xT z8TRy^V`-mNf|yAQpkG3WlHx*MPXXI6@1cn^PgZxEW1uG}A_on@8#6#DJ4_QJkM(#r zkn;O&{T^>jBv=Zi2^JR=)8uH>L(g!rJAsIAE6nWJ<~Lqa(1Yji@io;jFZW&~ogL-@ zzCaloXap?=*@leNGihRcy}3mndTeqT54TXVoC z7>;77VLtOOXz=QI^N@(n>sQ}kPkC#YBLeq>s}NinU{yXrj@b61<$f?Qri3%s3Q9Imq1KI-|#h7ZG* zKluaB&>nQV{CTnA=RtqfB*{#n>a~r3lanJ>9S869mUbn|TEt(i|0OD>J=VHn6g{tY zYwQ)yFDU2*@)=Zg%-g)()&ukXua!B4Q8rgX=f=?bk-H~)dwVs2Cb{0S5+gOYICqaidsgi1$${qwyh+4d}5rmhFwa?>wGL0Sq8bO?S8dNldXff zf`m$B$R2zr)zao3`my1rqCj+!)O$)%0i&Q7J}%GQS_IG_jJC<$ohnw3V{q`^=E~`) z(Bdyz`1R#w_bSE?&2l?(cng#+{Nq>vy&yfn0ICBy_t`G+O@#N zk$T5cy{<>qeH5GN${~CCM7``{2IJ>Z6@-fsF#!}-2Sfn-al*T_fVJkqaROGReq(X! zIc{M(LH`*=!bczAh-Yo-C3Cjb8qmYmA4)6=6u+zc4oL&g-UNqwuUEd~!Qll|?fRm6 z(_01hyI+;c>6+@O+4Vep4(T16i}x9b6ia~mQ1F=>AMOwO@#1yPPsUQc`$BF0Iz2&7D{k-QJ0YnozKf3^F$Cv65k{ z^W6(otbOd)Uy`g-E$Q9e5XxvA@Tf+=h#R5Xv+D2$5RQW!rvO2!Q7SX{9Nr!{1j(uO*21Hh%-OX--o%0pwXzy^K3ovmoJs|JoXvR>Gv9%&+QVb23 z%78wUyi(>AI4nVeB4lWwzdDKleNP7vNU9e+ELE#FFK(fdBGUHu&}~6Y>|*s!;O$!` zag4zN0<&PmPek5pVaj3(t>ZW{~wnz5^^unBXg$Y%WA@gFUY^$wyIc?}mKt&}U z(A~|D&}2j~H$2HS2Yn~JOmxS}svj5~$5DoZGFc^0eG9{7e`#tzM3@)m6UmbA zNk|Lv(R-d|`Uzq=(h)$&$m zHFAhAGp4S-y*VXA_Y<$Vn0A?IVT^p__#3MMh1CbweDLm`uD}jbSZJp{GG0eaVn2u^ zJ>LtC8JX=X`zyk=r5H@K@Sj`y!E7(D%8dUt`23a#8~YWgpiv|G*}dG`CpWclap;Zn zQ72-Ic}7rCvf35o)-uwigh=+EB-5Gre`_fV{Of%yLqv<=WF6-E%keTt0Kny2^)sny z%cR6EJuWp>V)ke0bX!O~3%!o50M;4*SY$+gaU<}!ug?S6zoMBH9^Xrw-f0L0cTIP9 zvdDjVGuyMXqoMw408|M)M?Pw+Ir@WD9;`FN8(}?uMdgAugGi`4(It?B4Z}wTwTKQi4@Q&i%zhUn1hTL55Ds;z7 zc|FjT>5BUI!|ob^dTHj!p#Y_%i!5*7DBjP(TfYd8i<8TB-;z2zs@L1QqlJ0G8)UQ- z%QnFR%vfr&c2&g^jOO!c+s$bM)$3L$K|L2+J0{buzx8F;xCOki8fXG5ZGMAC&yhdj zE;RcYGHy{1u+=PFp_SZA?kaGoD$^Y|zVM#BjLK_8N2PbZTexC+QbRz?P4LWk&|(AV zXGvHTEC?9kt6F-Fv=C;I!q9<%)d|RLP5uo z7;bsPL9es!3S9rq3g~TkD(`GpEd>58jy|XcD#pntY{;kC)%mF2jE07Wr0INOe^9V} zexR>6aEON12JHd5>a%;HyH>>}>sx_&DX@blW;bU?8#utVd0K6ETy1FX2zlu-x_}X8 z;7q+jI|uG9SYWM5%GL8G&sNb zcf(FN5It>|R^ufRc@6?$roLJRF9sX@UYGRFaz>MI?bdt;@WpT#l$c+pUP;yG3{7W& zLBk#;bSwI!={ zTJZayP;1fb*mnN!ITX_&S(yWnhVi`^C=_9nuO?uwn~m?~#h^0YGr=$pD@h-RM{?}Q zXj49Q_np%NE*tTV1D+s}Te}UMXUh|DbiQ*5$F491Z@{mMkwyw-Ck3I0fFPF*UT6X1;GOfbF$QL? zZP4olY}POf3kzjtScA0*o$D@*U$i7Qw{AVM6q{5e72YtqIWb``7Y2*B;Y56e+nB`P zTmrPl0!58f;k4x0v$F|am#QvDg|zu)eh6T-DFS|m;Y2M6V+M_%*?aE<042X!=QUM2 zjyl^G`>!vkj5tqTq5Ur0{Re^=dyB#R`ZOM)Yk!2&+HAcTrX1oN;WmT2BUNg3Bp6wh zwn&8ek}WOqS2Sxk8ZF^m>}nhJJk>H73e9bMX2Qe1t-;?Xu@ddSG!_}oqmVRFZRRtR zwT9Lg5GA3}zkPlhdd(evfB4K~t8S2R%k=0&Q!(1t9iM#J*LQ}tUYV%$1p}Me|Xig<%^o8Z3lj%|yH7l6m zg%;J=;-SL5Nf+S2i8VzBE(s#;#l>9>dmzX@I%rm2yF+!^onP2>?oj~u`WUPMMztfU z<8(&nMo(W~edniF$7RwZkEY)_GU_o@dJKbN*;S$UOLz)%0rKRa+9Lce#xb)&U@L#8;cpyYLm&L3E9A(fR^%q@;JVGsvDRM9){CzC{6?Oy>mhl>PuERr(3m~Fm?d9O+$(De& z5M6|?0Z0W4DJCu_p!{X*hkR^^YmAtoVYA*qO`v}{W3|guMi4`ia`iPq`|fT}^yO9g zEFcJXHM?aZVn3h2ICPh!c+|nqG|GzKzHqn45T=RKCgsC);q0lPM>{oW8@|i4x1;ue zbkmK*$qp+6d*XDmhQY70OYE-zN`lWxf+SDpbPB1{f}ZxR3I3esQVwK+-;Sjru&6N6 zj8e*RYr!x?{bS{-$>gmXqf<7pjdp<$E9t0lnW;(z-3K8u>tC{_6?{97oXvjgwYFKD zo%|r|eTPY6R`1G$d+e4&*nP!;1T6LF@XP!2#Iq4-`sQMnglc6tkG$^&PA7kqjEG z46q}wg?~6_mFww!m=$jrjg^Rw>?8vmoMwhPeSttKDq%uO+7GL{1_q`uecy-;pJ*%n ze=h*QUcYSZHp_n5h%;LULJf`=>()e>NVY z;DDW=4hd_h5BT(sgd(6a@Mhuat{-b%BIoPX$hr1a@Nr^`0CQP30?5SX332{}^vT3)E8r zy>Gs$O@$iouf|)E5hd-jx@+;RJ@)d;s?i2vvTrT)83n*49OYU?CmVvn6ju2n0E{E^h9c8mzLE%z$8{W zv&5kxVtTNzT1{FM9LwCmP(M|*SMP3%V(aEkLx$z%azbk*P#yc!lmYR~0)ViYV7N4d(;l@Es6u{~#Imu5VRKNr`K3@qW@#BaW@>A<0Qq*I)C3)aAz3n!axwEt3)>E76F>7>&li>MXqT6J5qy3kE*G?eK@>3>EmyLk?h9FVGppi_RY4H59Q_+IVFzTyIx7T zkU8YX>h?9{C&V-6>X+WTuQk3jf~ZSFDP45{n!0 zy#jDB-P~m1-29m&7~uzi@<2uajCbYB(7WK`#BzK%Y%F!yEB*V+@$v3TXKJa}Ajn9F zX^)Fp1KM(H(WAsLz~fp5J$V;0DKLy=W+`{W9m%V2Z_CiqaDCSJnn-v$IG$bC`K9e-jVCy;I&^W z(W*dH$p-5G*iA|52YKLebf83}e_szIaD97N-1klWmaGC+QZfd4Vc9A8r|?5njyl_N zywoW}Lw8!b$Pd5j(9lC)r&c}xwO1`Ttqk(){o6t5%FxLEt*hb@=Y&XAm7BYkwR;nm z+cC@~;eb7Vlm1Y;65(Ajw0_B+LNXZHI(_;ySyr+N$%V4R=7>dQ!kBi2fH1YX9<;c# za3VsMwm;q|1l!!Q9m z7!7hzQiXiy_yz=GaCP?TZGp~Z88|n)Mh(Lm+&eTS3AanY5#lpH;JdV4vEWO=F$GEg z4GRaXNbipA_wWWNG?2hFb}7C!>%_XyKw7&U25S?!07}t3LT+>n4>OLUgS}M&Zf&RD zN;XZOd(FjG(U8F{LC7(LH*s4@0v#y~7S#j-!wt~sN|1)N&m?ylz&$}L@-cK!V9;xt zK`qD*^n&6jc>&)V5t^;4n;OK{5R}hR*VWvCXl+UwevSEHM*wAi`TxXQl9eAEBOE+%%JnWs~_5^nX@dJcw7e$U7>MUgw&3V|Z z5ZWKv|sTjer;J(PRfX1j0n!1t16hY9K7}P|LjwbRHs?PGaIw?-n};4M13yuVdR>5iNlH&YvW;K#%^gga z1rO$p(X&w4gNONEg$^5g{DQYS z%<6fFh!{M<=7q>#)j|gW;;cQor8W1v$M6aqabUgW+(M{jxhf=;rcCi@QR&sY_DV^jq_U)w z*|*D57Tl~NXDfqh7Yr0Yr7PpoO_{}NJx>EZzvPn|n*cLg;83${X1U3#-5t#y3g}j@ zVmQHV$Xx}~GB)%|Y)NS6$JY-O%>IVom|Q|eROvmse@64|mHXHiyw=IundpuarlxiX z5{^^T;W)c#j-SyT4D1O;XL1YkqQEIbge&A7s3FPi5~~1$P{1|mh=c0Cz0Q*EU=7RX zL|6$L{GJ!KA)w1kZ+c?0ac67YG9_haOgeBH zNP0tq9P5S7S+Uj4?#0uq>|TSH5_G6uYOO6rBjg)U5l;%N5By-O%Fc3g=$c%1b}o`% zMHf0TP*E93AR&U!EPNd39jGV-$v4$M6>um!>#nq8a}q1x&d%YJEolZN<-syZZ7?xB zAh=1AkR2YkO(ecO_ymYCnCGLep9h_Rx(#AsxFZBXwx^UB*f|i}RvL*x^*fid5iVtR zMclO|+ma6wWi<aLbvD3K@p(4-6Kj&T;COCC}aQLDqL?Dwrf<{1R zRsJx`fv~o|W~*2Xd{{wg2LJv{cek=G&ihJ8WNT?N|%v{|Ldu# zKYu<*9U)tp#8+E9D%F6>eU0nV?Jiguob&ggZx%Qxx4ab&(~b$V{&f{^LSao{B~NO6 z!nGJPSgSJyl6hU~(5IQCZ%-HUotBS_k_3O&X*i@)Khgat{Dj1;bjopZ?Q-1khR@z4 z%ZcIMp6r3ck|n>PST=bRF&=urCIZl30Rg{+xh%c}@P=8#G^8!7A5yGurppXCmu+or zQC=~@)^2iczaXG+ccySRFL=jpODlY3;-J+4U<9U6a#^HOaUFjg79+zfA({@4gC~kv zLI?Xue7o(w%wk0a`O?_t4^ldrAiUxx=+Vw71HV(V09N*jn8$7plaGbGbE;~7ys%kp zCy@qvv057eP~d!;v5SH(qfxuR1Vpu^T8|@0vOyb**4^@qxw6~~%bbupg<+e%cPFS# z6vIa}X@Zza&|-1g&TZ%t?Tkx_t|;mGJ{SCtFSp3{4?8uLq>e7J^N^D^eG&Hs+ECdP z0ZCT+tcLc8zeKjg%O1yKhBa0Y1A7o*@Rs>AQE~V&WN#`jSbziZ{+@kiiDP1z`;hhl zFgVq=fDYD&3=_gl2~$Y~=FKZq)H4`ZmbrXcqD@Sk$9y*hxa<9e2#Se3AG>7lB6m5W zOUX#_7{W7wiRGX1^}?T^rIZ@PoP&z$dEU)*D7pk}BwC!SXum!BQn8lWPN>?(R`9=$ zJzt5{f*JV-KaTFwrGq6oRf)HIy~cMs|2|MiYonI#0M4umC!lgFOI6zV}T%5faTE{lp`0;(-htp!A3g)BQv0uU^s#yA+|o2>)+3aFV!8(mLw2z(u5<{MxzJjc zkmV4A_FZ0jC@&5J4iAWV3Ufz_A*>H5smaNnc%yjW%L7#*+KIb=B-A)#AAVLukO`zR#{MgGvr#(8O-^8VU;rJs%y-?2 zdILt+6{T>d|2EE}oFlQRzbgr1dZfkTQq$6;6Ld29{*lVqtsf+7`&U;M@ zmd<{2MSWjEbKM}wL)uMWl0VTABt%G!@E_mNWJ9b9lM-XV$4l0ail*SSn!#^$-7$7R#0p~O5J=#1|yLkrw9xXjT9Q@HdzrP@*-Hxu*Vvjd6iFp7yL{n`C zHd)82)Ju~jgO)(TQ^PL%voZ?shl{~`T6+@NT<1K!u0)POPmCR|x!0nk1zqCjfLv#h zWwEzfHXi`3(1h5_T78Tzqwik{%jwPvXEr!7&vEX-a!aZ}KY2*r?90%q5k^7nR?eTh zd0~#@Jv|K8Rd((VD(e-_@ql@LxjGE}C3t;KaXw9L?=vyNE;i4QBS9v7u&*-EM1cDDCD)2m@>%@> zA#wtw_tTHM<$(h=z}LIXSV}w=l+d3-4X;Parc42l;7XQ5z6beJmcs{%spRmA=J=-` zc2stp-q_=6i_;ps8n1BxR1T`0GH*i9o;}N-*G zvx56-etTLii7M;D5E6H^zCslq_N=Aqd_TYFzY z4*&b?rY1m$6ZenRdoHg-z2d|$x5RTI*iE9X$gr=4h^eh>1k&*b6!ug0nLdm!iUI>a z?4%ZxvOFMGn*8IibLaWa|3V%^U}HY8Dk~lQz^e25Ed-cXFG@;=xbeN!yCBK?q{ZZ` z>g|tHH{pjJ5`Sq_SQPqK4^g}CVqPt5g5?LWW;vM6iM;<|dPWNzpPDS0#S{+*finb% z>+;p}P2+AB_epL!_wL?@TWd}`S5^Bgq{`YREo_Utp~jQ0NH3~L@{ekojhGwWcMy

    NM+K!p>qYt5AM#r-v=+^I>xiHShSgM5{1>X%$55#q;4ifU(Pr(KY0sIhT|nOs z4hZ;SO4aoDXBSc9O3XR{+{AX|(d6}R3qB2Li!aZ|-{1tofZMUTH8-|W4K9_?3NDBu z&{S|9%~vgG8vLE<$t#kI!#OdIWBxTf^_us)cC6texD)BxNIdb-?f&L=TM~RIQp*RO z#bcWbz8``nm5qZ7&P@XVv+}qMJqUqhigg?%{RFjZ(f|}+Y;+pDC@;4#%3b!|`BPIL zoo0YBI;kxxihB#V{mUA5pUBZF6fN@sCG15}!2uHGLEhhosB{>vZ#Z~8As@hRH{6`x;O0{O?M@2`MzAASa1W}lNCBode zgg#gk#fSk*x?zvkS*AHw2{ePyS|_@c5}1siE5TdkwPVRivvWJmwHv3c;Zz@$9C;c^ zMp_!&3^@@_5~9(r@0!M6cg^=~YQ%`8?ff-s+RCsk4_f=1(OSGxq6Ry4PRP3}V1}w# zByUS`rYFr^wxr&7gUx$aH8c=3`7@-nW6&MJYuzB~HRvN$?N{)$%7fY7*4AcQ{38AP ziYj^0y#h2Xo3hHBBs0}v_EgJjDhvh#)KyfWjZA?#9u<|BB~IF?aY z-Pq(rIA{*l7Tly*aX1fG?!@w3bA`_>pS2d^33z@dd3BAO8@xRaL146g)2VkJi(|82 z91_)~FD-{0@6tIzY+LFaUF|XCBdNn4#piX@Y_+ehPPA>))>Uc7y=70Eln7vM$AY*J zG6D*CGPv8x-q3Rp5uWYb97P+0crUmHM3nTgR8J>Tn+(3s--|W&j#-8gVz?C3n*{YC7ORsz`U@*ipZm&@k%y$(S70AQr)S-p23% zhU$?HoI0D{W~XgpZc?nK%wg=Y&8Q9!h_#6!_tzm;Pv5Jh*sWx+m9sNhpi>#7S76M* z=A_-U!5is1ydM-F-wnu1Qi|4om=F{$YNDiFM&U53i44wI|hsm zl?4ql0LGet!(pomM1kEIm@R5I+gyf%H^StAdlVc;BU_{{BWX+La)w2r9hnznPmPX_ zmZepFDS@;n+1Dlu_w%CIf?%~rIk~NY9 zX)ncdB%je2FHTC5iGYw+9aH`SJ6E~d+eh@ItemZ#AL~1yd*f!%h>Les?080ybY32K z*9A$dsH*M&i<~1`$l-ipVWCfzleDhBzMgR4_Un${g**L)S0jz{%SlV=KTfma7PfHS zLN@Ep!_yMeZGS7Jbe<&3o8Id4Ok5G+4h5P{yWLRg;6PpQcKF^8J9Gr$*3SnOK+_vu z355{yOHb*l08ZxI{M6#&@)!^|OA=1nbjs`UX)xyEJ$AuCQg0<>pM!YRtu}FMa{id__H50UN3_lu2E$xVC$5dDE^gO6w%q^q!i!G=V zeG?k=1s88H34_IGw>=g71i%6!&gL!bt3xOtmIwXoPOGW}X0`h?06rO!$SOXwuU~4I zaBJRR3PMDt&#!F$AnYf1=>1|*z^F|HV9m;cP?0(aIMl$WVP$1SURNTvxtQ5;AjBlz z(5AZo5ex(SI_mm{S>eI0{!6FZu^iBxwE47v2P`EOpB%ht6tw!!Hi93Ye;;;&=N9iEeC{+(R>E zux#+XDaok^p;E5>Z?c>cE4xf}!wwO-?ubXE2Nb`i3neE%Dq}D^(m*0knR%08LR4y` zy%}`2E19?a*)& zRQ0pZ-pq20M~(UAb?&v7xu!0P*2fj`d66$dpf?_o$At7V9vAn0S*4!=iMrOt*~O9T zB`Fllg||1|z`%&Ac&k^tJs};unrFGQGrSi_oCAVAn4ea_VKnF63THe5yio<{*COYz z46t_sc$nP8fAygpKz^+1vm$38{lGv4V*}C$Hc3XWmoXUd>HA6mO0b=|BEyw|#9>W{ z2OyxWs}u-w{T6Dv#UML}cL6x{P4$svR;8ZgvumS(4|YzwYtA{G5?ShP@aFQm<6AW_jE_4CzL5-yHUMH}xE82ZjT05H!Rh8{uqyx-?!C~3;9ztr z`rp*J>3;y3rOA#0C*{?j%F#bLd=?Ja0pYo-@{wcCJqfP&2Sh(#@J`$LWyWedvOB%E z<6uo3lEp9c)TrcVd(hk*{IZ1BhijYlfZR9=Fo^hDU0Z@yG3KpwN`R1|b!prY8K@MXIFjA;ozQ4IP% z9hokY&uUQzx8e^Jx5RkEz#z9F&$Cb7c+}MTfQJos5S5TASrT>~g7^~1Z13w+THg_g zux&lO-XIf&Rucg|#5y+@txy4fN1Lo+;@Wa4dasM=#$*_QPu72x@0;ElKIBc;i z<8NcGln({0*r{#3HH^9QfclAs!+iY-Ob9k9;?wRGe3*esuZv(N`tcYY1e%JS%T-V) z5mLY$(Gpxk+>*(fgrnw$hTYS;Cil~J2AGLieJ3};Bk7lv?QjJ0)AR)PWv+97yHYkq z8HED0#T7K^73^RDhIkCIkG@D36Jxs+pO@vtdlQD}Sc&vVnHobrg?Zy(7{BWM*467D znQmm>5IyM9;_e~r_dKJ*A>hnmN?T$x<69SYe+B-(7hsiYR<0qDpja#hjl;3piiQ`? zWT4w)#r}<*z80Na_4)JmN@3s*GkCtbZ+3EHito-4v`_LWG8cFS?K2%&lY<=r-l!=> zT@SA-c&P-4Xv?%V+8ifOM`B$6}Z)`cF0LB|SqZU~2F#^_5s{RWW_ zB$D;dh4tJoC^a?z@%jd>Xraia@p`L|cz}n~R}o-`qec zWC`x)({vY%YcU3T;qjdQ4KKgfaj`bOp}R2+)28}zGIQc`^jS{RjX!oo`SSH zKuVUC%)G12T7BZdXp6t==lb}G2p>+tE70r8>Nd>3=2HRD^!!7}w!p(7W%30(fmNgc=Fa_0}uFbVf%PG8z)Kix=0HBxw4bTB95CUic{}EAWr12 z$~k4iQ>HKZ)4pd0Sn^;PW-=3O>Og7+i`9m@wPXIEG8lMn5m#z3Dqar>!~UzEn*IVgJybKffz#vN)eTkX)&GHxz;k~GvdJ2~YV zjG7V_7Q%(_*Mmn85O`Jn-96n~)hpY}`}@UM6E@)8cnT{&*Wkads%h4FiO%}+{q2J2 zZKb0&3=|QLsp%M1+sO!)OkA6sWViZ;j)FPf)Z+JOcc4m&hXz?5bto~w9V97B9w5~$ z*qLOND$qno$sVl}IA|wp6$04@SKTjiI>Q_o9YrwBC0_s}3yMhnL>lQ05kW>AN4ybV zvQ5%)Ds-`}tMo6A(liM`wd{5)*6ije4hibgK-1}CvzPZ1L3SARTalLEOXP5ix3R$o zjvlqlXE^(LtjzYUbUvQt*!8L1!uNUcEU1D|>GvY8EC049j^wV@jL!d@ z%-G&_YH}WcKtrxeX2!|U{%-A5N=XtR@9%s1ns7D6Ryt7+<0ZbzTyBk#jS^Xg-%Zy| z2eYe1ykurh6Q!un>f_KOaw*y4(Di;6-rW3`R|*XPmhIw%qMLN@HX4|p(!j?->$leD zQ&W?-Cwz9@UF2Tl3XCr5$%ec#=vr9MKz5n352*NidGGC3gA9f>oUJDN!@+ig7U+1* zf+9`?tDtc$rM)Y^_c^!vBWgF+%t`hpoIus3FC2m-mQ8=KO18$30VW{KfG;d7mTnp$ zGx?=w(oy*=VA>LxQl53DEbb`$m`oIbdcN+vI!kt_)ahk@ zDeU+IYTL>Hs#oBOzyj~{iRo$3yKN)UXj^^=eoSIKix`LFL*zYFW4-My z@orBM6f!2J6zeiJ21MD)o$mfo!q~q$wu~2Qa)Ys1!xeOINP-!t+CsWxrGS-=1Tq#7 z^f$dvyQ{J6K$zLPs*DADKd_$psl)OMG=t>M&O1YbK+cgHV4NLFH>5XMgQ)DHw%Y_2}@~(dwbv2%)yYV?@ z`Z=7t$s{XZyH-ZW(U1U8(7NiUoT8ocUnp01=uR~Vukq`3lOD*Y4SrMqsY6Kf5Um=t zopW;*d?mo=6v{sbA|7Z(Y_H)Q`RuXqqB#-GQ=j#;TLSG6ndV2IzRr6o$A#Y5+imXc z&rOv+1req3-~2D1NN96KQ3^{_7Ph`WEpSRH zo(X&J5rw;u>Deyw91RLySn-r}WJIM@x0nszA!f)=o`fd3KR5h4(0SlQ@QhmhOe)eA>Vmx zirY0fchJ9ap0%xvPOFjd1M53k#Ah+SCY}IVJx(^bO$&YBQGKq%rz&Lvv~?Qrxph?e zFARY|2Qrf!^VuO0392zl4@cp0OXaZY0MfHi>5LXQihyToo?!#~Z8pL`PACHN9oeWV z4Q z)f_8fN{rs5+|kP^y-)1Z={_f&Sb3zuDp+o4&O7}?I0r{-J)X##s~NidauJ9?0)o@ZlXWZ3IIuagP2gPmhOiSHM93Hb&$V}*!3 zfjapx^gM&$$FU!#@~{3(9JRVGcn^oWtzgr`9|{E`I1!8#``wx{i=5)*&N3%i(tg~D zpQb)Yr@+Eq@VTRf%$$JTp|IETvXN#|Xu}~%P#Hyi^?XIX6-k4hv!WiCiyH6ob4p%q zco$nVZ3}ZH`5TknHd?O^ z+rZ?F%CwdzvGQJm2=7m(+mw+;yX0ZoY(xx)Tc<+5sWca`9U+;?kE&2nj7sYo4p?p? z`-2eP)z5ZuG^o7Is6W?kaqx1X%##!ttxwMrI<5!S5PEw02+~Bs&plyn*EOP95FEOx z$U_`j;a@N=sJBsx8b=@wd3JG*KD)2glGc6vxQmETi0PACH!OM<~O2EET{@j?%446IXoi z))u3Q+4Sro-=-FmN9MfR-fY5~*1(=jlT*$A6`c7$n$A6*$^Vc0qg7L4N*M_gqJ)*h zoLLBwC_;{noI-Ox^JSq-$~lG{E61OlaweH16Ed-k5{t#0=j{G;-;cY$ltSC}xvux& z^?JTOyg9n`>(@yUeMDC(dpt3aEvm$WzN*Z%v`~`)pwjKPl@jCe^%QhjDhUcQ#>mR- za5l;J9dNELtz;c3@nR_CcS`TVLWRF#AMpI-I0tKT;!RCj+-yYZ#bc3ERxj=H9HYuBtAl)Z3**0P=J6ogw)HD&yk?+7d4&CA%jyxEX&E$Q4 zO9txv@Y@lsc##jVE(p=T{r<$@vZ=X}?IattaSA_#`^!PPDP_pNh?IRo&R6^vdF zJDe*{b@&LjIbanS7^u2-ZMZh2APDFhOfrhQKM1*BAN>DO_*QHN=#tt8Ng zk%$VyV7L-Yir`O3m z6$p&y!ya0~jh+2g;Sq?ADQ}B#4+<~x_)(_;8L8vkm?C;I*;}budVo#GkO6sB&*kWP zC$iRNvHl*vuJJIG$%c1J7O40o`GELu7v`TkGvmc~JeTj(3$dLh_wj(gO&7Syv%vwZ z#b3gEaglOsU3B}1{G3%d(&&&D5+YN){&R7Wi)X&&0>KI^0!=Z<|7Mx)JX(((-kaLd ze3c4yNi*B=VQITfaEF_Z5I8VE+`!y1 zO(fzxJb88D1!4wkaw7Qci02rQ%}W+%`LEaXf}ObZKwf)LK!}goXc|GR^L;4;@?kIJ zp3wyxom8LVL=;7NSda@R=urUzRphu5wpO;cvwYh!WlKvxAg+?Pyd=c$#>k3V+E;WIk|Ni~B< zJ9vsU4rkpb@^yPPu-KHDagNV{2<@8Gb>73%tqsAsH;~1=y6LLS`8HF%I)4U{gF?5O z&5>p87})*z@#9O$?P!BwNpU_k;|<#z=;LHl!xVHSLn4`n^q!#tHK4Lg#i*6p11^+5 z^>0hMp_u|CK%tJx~ zIu2Q6>huM6u-?AgkotTtVgSL26FP;F^K8DUhl6z>4k2|i@$lL~1g5vq;*bvHaFpB! zgltA%cJ^7!*ek!ur1&csex0w4$b`aX>iR=Pk0vgRQ$^p9k=r%cVYuZqSog6(3&|N* zk&ksB*^iQ_KK4SF)0yf)n_~kJ8?DU!Bf9@9=brd}2)Z-437Hmi##kQ(x@o7jH)Z3& zF151+-r(7CxA~{HeEh@relJfCPoEdmYNQ5uzD~2Qd{!XV|GGvvawR3Z|E5^AzlheO zJYq%0s?xoP)?cJL!@0e8}poE^f3QCsyGPXNNf~ISL*n z1F6cwHrklcG)wp*ky2kN#~z#x@?m{_J;Gnv+>&T^e3NwqY65>c{azZxSL;cwlP9Z2 zs|g4!0*m~Je&#M{GC;0(_HU-a$pnQvSNMpy66qW2&t8|MnY-uGFZ87eT!(e`PgJD- z>f8bkIh1k^OX_PK@Uj4w8`Cm zimi=pZ|6&edsgGP7nRPQ#n}DsLL;zJjtEoyEm-c}vAJ!sb(d6~9=GT5XcpyQS$MCI z+N^;6wVvHT8jli5D$q_Ww18nhOG0lYPS<7vf5;gSbV&gs-h7bweFXWpSw`#m>oGtk z^Yv=9cK2+mylSl;@~F*PMrN}0#yh`eP2QB=nHkl>(`z^3@3Q*!VZ7R$VWX^zT6`Uq z(g|C{D}zZ`rDwP-GYprxvi%pXopYG~F`M8~t0E?5h!4v?V}a*(M-Nseqv5fRB6vU{ z2j*)PIvW_ea8Hf0>(D|yDjZTp?kqMKCe|2qBCf$ex;@1pYobEQRx<>)dcPo1@2hDv z$kFMaHKtlI(5Fm!rHbY9&22;ZMDVcu`X46eH-26hUZc>wlwt(Dy%*c|mK)lZmj?U0 zyO(|VTi#MhL4~agp)=AV#6z&0Yv#jF-A?V3*I=)QpIj~Vrb;LB)x6~1@1N1-?G^14 z%MZWjP07X~&XkQjY$JZ*JD?uyM;cl5n2+)^5`9nc%&scyd=2)l7#??sejFd`=t|`} z8I9sk`vALcDj0@{{Rw93=2q;G7FH^pu2$?Ms7JSfbs|o^esYCkeO}U7)a@HACTaSQ zQsk-<4+h|>sxPs)p0C`pFisG$yqsZ>>}N~QNhtho?Lqj77r-Klff%T=qHeX@r{+@H z>XkDjtCtd9w+gK*EdVuV zW~Lh?Edw5I7n-=VU?N(nFyzLL8O*C<29P%rcuo?}VviK6LxTa> zuc=8Jo+~7*9=6oszBj++D^;XW`hy9AArDeyb0dT8g==ffz>QiP)ES`8gZ=#bmtaa` z?LDmj&Sa%NM?cA`d_g>0;j$VGb42B-($Vzr$uh_C($WKK>bZ(DliQoB2V)3*HmZvi#lXPZ6MUcWrGcLq+=D zRaR6C)^z_W8?6fF1v6R}wbDZ>npfMwhUfZ)zQf17nq?2=n3x}S=x!JMh z%&h5Y^Lr!sUzMKhIvNnY_^Sb^mw!w<+xLa{`_UH-rI1CQ)HWva17R5+?MprsFQ*3r z!-=a<_GlE$OEAvzX(a;>H|1r69g2!84Pd)CEr}I^cwZ;UA;o~Zc_GeGEE5CRzo)Lu z$2ltIfR2NdIY)i_+k_UXhTd6OxEEiI0^iZutORp&^&w(=XF}jMUh=d)YKQ4=z1lz;#a2_^^9KL4jkN~{vg0V$$aWNjDdWu3iK}f)4w3;8 z*hACBfn+-bEx4j4oaWVJA$Ke$0gp~qEnNRMf+m8pZOeSP4l-P_@U8^{AzU-rkA#i- zpMYcz&}}CyJyxZUgL`m7!4xKJ`S0W79c+_+o{E>}>yN;}GVm#?D+rYX@^YL%d<;_r z?w;o63wR$A=n`PYuW#%1*2qR~RV207O)iiJ$WGEtB@+v*u2+X3=2XRnM?L|R+H=GhK&IaV8in&n_I!FirjqqUbO+(zgwj3zaVz2WQ?)m@E436=0f* zrh9pLUs#oL23-r1fP}z5s15W)z{sZvIf2ioY^`Rk&R`ymJK*2R+ZoX*0#BE}uj}So zn6FPTBUlM8_Fi1h#FCMGMaly!i*pxcf+p%C_vw-Qt9g-4c9W+t0RHj|{q+7=QmX@} zwpg*6hQ=9Uplx7yc&m-H5{sp43hw=i=6e-Mn)@pm_CIWF!`B9{U!cFHE}VfJEDZwu zbyHiQhM(;us|%=+4mMU+X39oI4O@;QFosfCu;(+qL~kV&mR6dOZ`PswhaYtwPVt3gqS`igM@O_{=_rE}v|;#TQJPp(of zPJHth=(eXW1Poi=C#j_`Zpa`%$UcYwnr`Fp}a%WvfN#Kty_Pc)3m%4y=vU&h~xB=$oI5I~*NcefSW1k?Y zkz~5<TPwwiH>JcQ#eHbEF|ln4kM)x+VbzmNHpq+T#MKe^ZskbuS6CVb$z2glHnZ_^ zi?Thh+rQmLzqt#R50;J0|LnT%ElX>hN<1FOqIQR&Ufzt&KThVy0>Bevv`UDs%o9a`x2l3#&$xaZGt4r-ZA@RSXNttaA%sD%@Poq1?aK;lpuT=>lG_rr%#Qse z`IybMLaMl|P+U6`^{WUo&?>0COR_Z#4VFsdsZK5>8g;a7S2v zpcg7T(3VQ^&m~#=a|@|$?q;+bC46w5$|+>v=$59sSSODm@PUtd2tbg?`456b6Yf-&vkiF`N-RfC7FK z3M~Gz7+7lcUWAF%DN{dxUoa}kda#u-kT*dq2a$V+;!TsqcB;}sxx)b3PY#U*E5egK zv>kwS1QYALh?SJ-k-_^KlMfXM)j%;MZ|oZuw%f`KXZB|+0oVuO*QZby;*6-7^|g2^ zz@_a1`rqzrd*prxJB;iRF z6c#>PjD(dk`m@<4`|v-&j#ClGj5$^qDa$nA#j3!;gCW4XY>S<6+hL# zr}Ct*+o^Qt=E+B9Af!8I)t`|LCqfnD39Uakri$i7O z$gz%y9v&@3_Y?o05jELgW;3fz!z=tPOrE;gjt zwx1fDdsFlo>=<4wrPtxh>-NpHY~cvB;^o!UGrKO@!?k-8?o=jq1UMMq9GtzF< zJeQAVUHt8hC+~IlKNo@}(2Sik+O8Gdh`Yw8u3IJ3_vG~X&qv4RXW0ChoD@EHZUpRu zaOUPjU#6P4lW!!mJbQr7qMrD0N0lDUj79d>*sTjii9H!c=gvMJ4r!lIQ&XMvthXID zS^;<7?)%HXdx4|O{9N1a$_>u{6lP<%H8O8Xz+=09KBsr*yCI!dX9oG~BT$luI3$eZ zJ<`xaUPq1Kq4>u`P~t?wh^(84dS984%>=CrA8mcM=*9K zCo^{JBlg90-Yi-}I{Z}34HLWI9Aotrz?sp>?@I|4E=mobJgaaEGYz&kXQFT4oJ-)7 zmC!YH;)fy)PDX#-h&W%w2~qTH9%B}W^{)QP7--uaOp0&`za3m^_W!j2k@gDfV8{$^ zGS1Rz764e$)ZE;c;@3Q(5xff=N2JU^A^g(HRssl;IEDmgz4RIf5+L!rABrB9eJZH+ zze_AqR{I|HfHkoHcK|NxIjIc+p<67_*|>XZLvXx~goFZ1uon|M?r~UjzV6j76%9IFg@BAro|n7gfKVwW2tpc}*pvA@l${M? z)pS$ghULDD^@+mORh_33dlEeCUGS?oSNEeBa9N;FN{mOKRn!$o7RD3u{r43cTiaAr z)faXYpA?q5mvc|c!SUxwPvv6{cH4KEl6(YTumd;)dGyAe)HtMqkAmaK{4Pix0?y?G zRODF^s;QETrcC;Nzj||ioe`HLbWLX??wH7j$KS}`;>;L7e|Gg`_ow^L<`m)=Svv)i zfG+@5;5117TR*exz8IJ5lWufOpf^BpvL#|C@dDF7?uu(`rV)x=!t&*(s1CHNR6)IP zIE*@x?`6$B<)^Z&v1Xg#pkMImk7-%;Ctpa%*c?zpzvO*f6M{H`htqvHf4dL=xJ8078#U*$lEWEWcU^$qSJqcbgdv>93!IutA=S0Xh1=z0pI( zYw%LX9}59+3=;3#c^J)gNE{9Yt^52nN`pCak22yqPke>m63MIXE$T1Evg@k&~?2@@K73zKRm6Yy6qSR!YOwU4w3pW2|xB*rDI$;s{k2WgNiEH#Rkj6VjZ!ifhSNNkj4zOhw8Y9sS}XND$M-o!2rNu#m0f z4J$StUc0854WKFElRZ~J2ss2wC*suIVgExJ8Y*w>$*t+8yD69%Ml9W%6yDZ= zW}qqz(eZ8z@olHBO7hs;$49duQCndVfq``5jbt7EQ(7V` z0b-t=`Dt;`Yr^uO+_v0sqt)_7>*709R(DbSuTSW^X>o0gw)Orb*~zvX2>KSb1mB&HIf`BATH6dKew|xq>n542 zVl$}_##8BqEX7~<8zxJFLtF*;qT=u4-B17&$l7UT-gaz;YEC%?0`6l@U9nQErz26^@A-NJ+H2XoSWtNJaiEpK`p z{ba~jE50~39BiItHk&%XSflx46ZrK~wW1_{`VX@czPTp)PP`hD7ssKFnfsZZR;L{?~KSwq1)K$N7pWhPe#G8Ev`AeVo+H8a> z0-AxN#?1rFhdn$Hoxx(!x8WTHpK^e-zsOAwMj3a2rl8+4n%o3nNUSt8(`5|(48C1b z2}8cVaDlAq;z=xG(rgusGm0APxOo1woQEDq=78i}rl9ked#}^(6WoeF11Ye?v+1$> z28bE8rsj6f?PosZ!*OsN$)apzF(L*j3R5sYXOOEe1!Qx6o@cKQ`l$r77SHKTO($u# zHHBq};YRDY$peYiOs~hK? zgi-IwT;Sqn;!A*t z{h65|_RAZ8UfrE*2K+H_*oP)i2a3d(*QBD1^i6rq&EMj_0Zh|*sa6)@Me~lr1CSEW z$4>td+0pX=Ff}$1X_j7WHvjkU!i&KH}*$cSrl&mLRK%(@Y6+Jdj~;Ar<_uNSZO z)-HrH*r$K}+5A0Hb{7dPyWZ)xq>*@@UViks86~jw_YeN_{Be?T1lyft3_0Li ztPm}S?@%7K4h2mU{6kaa>tVOaL>OquiC3q;3JX_JSd6iU#~`lrH}6pc4*@nLhQE%C zhl6tfbmB%5Sj}(##&Ws+4}fmM3-iAQC6EJNTFFQmzRl<=Q>sceOZDZ}=Iz!+{Uj)u zdnSq_&O^}Rf{ul!vC>ZqwjY5A$=#X(4J>cu!Ompl&a82+Gd$W6Q9HzT>fDF0>Y(NM znOA9qQ{4I6r!V85U)i82PoEin2?E4sT0F)p&&I-^ABBsmJ;Q?kOc2xa;(3pC_r~|{ z+lJVJm^uF7*{QR{cIsgwkC_0LgsY{fFac$ct;`hnK~kI|KzPBD3F5|p__79I!Yz6Z z%1WilZITkv!glhk%WA>UgYDD_dz=w zo0|v>qJ`OWcATK3_C^;$Pw>AoX$3=jCfDlI4kOzHh>o zZ2s5e375bxOB%{d+D0;{lWk2+^G(l0IwU0!=izctQn1e0_x0-MWb0VeZr(xn!O;31 z`WfLkQXKyktSrt;Kp}9T;zKaXQSk5+=kY~TsVBYrBic=d{n{sAyIq`yihg+iC#~_` zB)9vT2$)1+9$78M_?q$_W+qai6Q(B6oGC4D7#9b8c>#Pu&dX@=DkEHh}K_~$4IswXC{M~a}PqBCz)PMijg4(e^kqD zxW0l=;H?(^LosbWgzlFm)-T6NI>MYrdu3Zlf$y!fmN51s7=+Xv&-HyKcLu|LeC-V) zAC`|3M6yGm%<$Y|LUmag*v)U)_DJ>@g@yRsU;jg7^b7_^Hn&Bttr^%EZNzmsDc&Zb znX)o6irIsXcKYY>xAqyq0@ zCqG$VTI@U;dK9INSH|8^g3^oNOOd8Shgw1Q>BghMu%`tg&{6YqEg2Ye88Qlrg|b1B zC(Wc3vTv4~5xzzU9(6fN4^cQKF(UV;KGe@A{Q?i9&HZ97EdG@##fq<+BZVCr4QrcR z?0Z*~ihp@{$|DSz!Fu(K{ zdPCzQt|)bW{25Q~$7Q*Io}QlT*URcF6si4Q4dH8lUI+kh;UNeIQYrg##t-YO_Fq6m zQ6}iZ zZ>#I2TeA3%gjX217U+>BBz7XvrOc zgHr~5omzquef%EOYhA+ow~|2kLTM?ODWsYae1RTzae3=y^`cj6I!>(6wRH?Y)Sdlc zT2eCv19c8OS@IVrx4$b_&hOnAcSvh(arRQ z)s~QkqMb8xYoM?2*om-|;iE1Hoz#Bwm2zjqv7UImmup7I@tgld;ZbfWTzjh)m(wLsKCxvIz~q%dL*5RD6x#gpA7HGRdNtRT9&r!aVx9c4tkKT9) ze{l7KK%m|g$ANH04hoOb*W)ZKEfvbmb0kzyU>NUkEAtp%0qDXHpT^&ri(Xz>Qt>OZ z|9Smgb(1N=v$+=^0>Ctwq-at3d=;>yw0USh^0YPRnkfG? zgjP{jZ)j(yF8s)JCKJaM-$zc4`zA`X~U+T7xBUxxoaLf0A}VnZuyg0_wUXmQRx6Jr7ib28K?BsUkvc%oHO!B~h zRQEsH7W>lL@6EAQ7cgSiaSpc>te9`gPvt;X;B+m*_QzzU3aEP#^+Y6LzWzqdZbZ#( z(lLG%kjT>nJW28I;6LVim-F3-M?FWCJz9Nrv(lWwI0OCx*4f5PWWmmRTqen%sUG}y zU`DMuK!goh6y0F&m7oz>|=ZlSzD;|W&y=sFBLZ9`qxMGcZ3$q-OG;bZv?4dEfAaz@?o}O+DHxqu7gil+Rd|Pk8f4|4kRWpHdgNNKNrY%Im;!nrKMoG^ zkTz#G0#v}vxjgOHog&j8@@a&b{)t4?{Mwq>!0LeJ!7lKXZMipw1Z~8l+S(?IbdT{k zwI4zLU$g3xr@J^{pwk>1}XjEecGfz4{MCEL>nvvM!TUdnZHcv_2b2+e-g{8T9@g8)#5sOn2&5=q)B*gbUv+1%8%Op7Ehn4E`>Ce3|GQ5B z^)hl(%wR=6i*HWs2K9XEg-c4og3{ zy2*DiVvli21pPJ`MClWYaLE@zmL2&paLCFd)9(}7>pvWJSB45 zYJT%flFGn^`G>0J^rxAPOX^AK!GZ=P9r1p~>e)sRi0!@Wrg-H0mLR$<1aS`vmOzgd z%RS0wI|rA)e$&o2cmW|i=(D0W&<;aiDV{N9XFCDs{A^=qSK@Z@a1RWPl>lmUE^?A> zduBh|vDNO~`3*y>VeUhGW*!Z)+{7E?Uv0u7AFVx(sYp2|i&>>B3oo|UPspTSB76m^ zNeIZet98o)hBfgQyGi>~EX|$2!($IOz|tE`vLZJAjy=?v6#lGlNT@yvgc2vfa5;v} z2O}#xsb}yzy2j#E^x~pdF+ovAd^C3z_zD9(Vx;(f0oDsKOQ}xc_{d{69>q5`Qe{4 z_yEx)I)IAB@m7s8^q1Ngvk8p?u_J!Ri05L3P+t!B@Ot;H>}YQP1a)>#1P~Yak9>>U zex0}5<)?B_m@D%nw?p!S)MIC({e_S^Qio}xP*GBvfRF}Swy#UhJ^r~+&rgrNr3n!8 zo?subyt#}$`azD94Wjc%lT$BSzr1qaN{KX${^bhg(ip zPI78PA^)QU3(HA_4|^)IAg`qR(9`ga`UOb|5eT80P{0ishb!|FZ7M%1nL+>`^0(WU z@5A~+KOlR&hi5Ro<|(+BiviS>;Zw|Cjs8@eter#(9d_ z%72>uf1g%BHGLg5T@IouwX#UB`)0V?SQ8C=8I&f^tpgm?rMmt>+<(tUTPT{$<-b>f z=Kq#|UqfkSpZT*mKeK1U7J?kw&!eJ(+=9Gm&#hq`98V$&4r4Iv3T7fj!?FfCanQFT z$s^U+o@dQAl}+Y>=)lUW3pMn;frBimogGU2R9~M*yaD1mM5ORUF(+U{@(Kq>oODU=R@kd^cA_Qw+&rt#_m@K(P`9~`sZdxFiv~5 zZw&FkFoBq!@p%I0h_N*E_wk8FRm^`5zM3}xFdNJ^Twr7*vpWGGN*olktttTW&Nj}} zFX)k+{g<-Rrr=cx2w!Dz7RYL%MM`yobBrdzSrtC44mc>c!&HY%h&$9-{)uA;Z1t zgZXwaetI3b|Boe1UoH3qcosi@I@*r%W!%-y{N{hpyqF~f=|HT~tXu+EtQ=neX>GY` zlw9N{0Fj>lzBJSktxt!!qo+E% z20&I3n+}NjqR-baLj(ndS~S`(o{dzuZ{OQ!y<26EBoG5rPkM6F1wn7-IjoraRRo6G zuyN>|1KBFce%~2YXZqv~xHdNIH6m}qPE6}doreBbqemH8$nF`>tf^ULX#_>Kj;VzK zbdZoLJ!jQ_LIlcDOne$vhem*Zq;4w%G*w1i8-h?~8*8KqpgO~se+3JOGbaw_{ZtlM zAvI$J9iC`8*{Ahx7gSZPrFftqGeID!C$zbFxa<#Lz_?16}$A}J9^LpX+sDH zovrXoXdleXaHcyzO~@Cc%X>uB2d*Bu&(333UxB=JNH&eoC6ai*u+}{5_8FhHiH9(W zvhI~X4pq`+at4J(fx+Pu0hj6JrDahyB2Hhe#8q#;9b5oA^u@)Srs=N-?67AZSP4Tq zlpE}ah7juQZEd~`NNFCcqhNWy+c?9GYpxG8{BY- z-_|5||daPTW4VxK!=wV|TUc64FUI9DTlV=TtxU&Q)V$V7~ZW+Xi)lrb{< z>(|KM4ijWjIYmZJTJMa}xhMDLLnBu%M6T>HBilzA2NRQf;B&IZryw2otI^7hKU=-$ ztB2r5_qiZz+K+B?UibJN!IefBqfEyMYb>cH>0)S>>}Gg`^X z@eZzOf@`7v6IwdJwq5WEjIF(!tuHDFa0LcR0Q`(}j=x@Zw+~Q4qT^#k^pl}TC&DsK z)dfy!PB8$vfp6cvRnGTr-J_I^4m4Nh<1tLey8ue--UhXAY?m3iUBhbM1{g4)y87zm za`H&Q#p8v5LplDNI=Ajm^@ntd^_K&IpVOX3EX)BU=V&Z02(_r>nUQGWtO>PA2?IZM zP?!LcHIt~YxU}S2GgdyznApqdUJ<~ilB$O-)j+_<0FOBDJdpG5gS{DJkop*H*y$?AW=N9Qv%Fnn2kuZievqzbV2u=V}{iRA-Fc!PK8e*?g(X{Sw|yT=0dt*aZR`&Gynlb-$2}qRYX3XTyGIwOXO{F9f$2);m zQ3+qM?3L-e!Z_z_ba8~q%1G!|9FRhK|7bjg&!;qfIX)H;{DQT!XO{(x>2gK^0RiKc zo>Un^VUt_2nE~ZIUdKQ!$Ijlwg-L6dW&e+-^mA#Y2RYbw)FAmsqc0sid1E@Kz?u=P z`m8p<2hx4ztAWf`b;Pr{n9jWYxx84%=O1y1r(#di{<3%SpLay4&~KUun{05U)@EK| zwxUR(+(;u{&g+3(_0TOtx65z7TEE6Ug@0Zp!VB^}vK5bYHNEwkXli`l z1TbATmmk3LE8V;W&k0nN*O`^Q^Ed}3m_6m_;bi~nKNLDDe;Enoc}Pr1Mn5e8k3V5f z(w?-(?+p1N@XPndZ(cLz}dk1qYlem8h3Vf88~*z3xVx#NR>yc$_k}#h;Cjrab14(29S)D5ew7!N&0z7R*evAkCxU zZ~D*bVcVp9fVIVX)gr zn?G{BJ8fuVY6^lZsyld+0dQ_3-80~B1Bz6Tz!?hw5dBg}%Ycg1cYvLjZfdv~ zK642KXUzX%4+>=UD*-~GQg(kx^D=}GdyTyHuLM1NT?s}4#HPQ(LE!y<{rYuiXecIL zj`Qy7;o>_UiBcmJch3#(4VMIQx($>E;!tg^LLaXeM;w=dV;m9x?B0$DJ9~Q;V0%<= z*GWDFRJzE`hRCzsR_016z2vjrEx3RHiDrvSFP+_N?>0B5uqF@2x5oGk-vVo@lRS+L za@Uwa#1gb&6(DzqWSI+6;(tDJCE&=x%#yowuwL*t51T$KtQHF9L}B0WjD*zO3{{uW zf$OTp56H?`zopk$2|Ol+aEmzJujyyg0Uj^W_bp925W>+zn8C%MJL$Ss7NqD>w~9JA zn+JfynHip+c{O<+=8I{_zD$zrH*>aqUAxMKT6Q#5 zo+HF&k7Ql7xa)tir&(2%788*^LtW_OlfAyz>E39V66E3nMoa|&o?GrU4r<9mFkSdb zQ2WDfV--Gp7w}bV-B1e&R|ZtPHr8t1!4Jt3B1<$@sQOp{1cKD5?gwJ`KKY{2ujW`Jgwdf~za+75X2iYh(ux8P8~ zw=6AP2mqv%_c;TH$mPDP>!sx$LQpQPX*CHk;}Ej4w+*$vV`tE{_F@Amb2;e8H|O?I zStV-ct9IKeN%8Ig)j#X6jusAn)n3}(v zJXjeRlDG9Sp zvTwcydTnbk4ZUCer)Y?j7$AXn@L2E*Q4r*MC&tzh%4}%>J2>a%OL>v|TZ^>)ARy+; zb*o4b`$@d#k>hKSyt_-+Y>zx>^CcsuTSxWQhd>{z_s8M6g0txvsvS{K@SNA`U;tdk2(SYFkm2|H%Qho1ybnpIcERRI(ch+mN|f+60uPYRwNAG9z|7E2xKW882)U5uXk;D)W8 zo1fhzC60ul1QM;q+ntEwcuDLp$v0&eVeG|scy;6A;>^w2K%xl=!3<9pqgYq0FFO5g zs{H=2v?SjK{pYOIOBkGFJbdzt9Emff-t)hsDZRgalxs+wM-DM7l+LKcag?rz8W%{y z4rBEg^2RTxl1zl}F_oPS4GZPFQ}6%!H&E_-ce4y_Y~K>1oNM%SVIy%Gi`22A1e>1) zequZbAm+!y(NIBlnxy~qQWWZbqP6sFsu>bm%)7syxBn8Ceq~(#1oDo-xmd?he=u8E z>h0wqIW^j7MC^XI;zpf&b^#6{f9l>+hAeLMXPZjqYDT6#cxxuWbMgZJha%T;K04hD z5RF{r)zIiQ+GV~QZzH-xnZ$(Ypyn~WV>|~bRkFB1ZjHuYpva}Bk&%INf7FAPz)a%%*h>+70UCfL{YBVG;DYnAvLGh(KNzk(7iD?z6jXay zUK{S@)?`VPWd z-k^i-K0X7%D~2GRo>h|<`AsrGjt2ub%&I&^sIz6{By`>KFcyi1$bBaI;^EGgAE7O}4^*-TGzWSnz*ujFmoP={&-C${!&wj?KN>-3nvwIXjc zi2h*^6=RR%7#j(%ZuolAG+JhU{)Q-Lvb<+A*I}#m13xt_%UB7!@39?R#m%WeI_c6T{YLwqoICps$23-H6=3 zesJaK`Qjp$2JD*nY0M`9Y{kg97A){WD9IYu0Up{7x@qfii1TFEm)^P^fq?<#3XFBq z|DoyJKrJ4^Q zXf)cPp8qrsN_?`rM9OV&!JEkSpd=Ccu;!}N5(F{{a@Rj`2qT^ zbW&^@{Wf}QJ)WDd5S07)IyTzMeCvndPiDRLNle~Zi2=;^N&~nE17A(B{vQbnOw;SB z4&$#Z78e$e8S*E5UHuJE+wW~*_lJ|=c>eYP#uBK$!a9KidP>bQT}lSQZ&o8UQ8a(c ztnMmdG$wYYb*e&bVC~oMZzX%uy*Gk zx6x_J)1WF(5u^cPKN-RNvO}le0cLGAKv$v^1lf7-o!#UN<<0|JTB;JHQvz;RzO^yE zGe2s1ZD7-Hm+IFR7ICWOM;q|VXvKcjg1|1A)z=54dy(FpyXnvEOjEr+D(rR(EfUn_ zCL8G)6&@ZC#aLRg6pz}D2SysFW0fP+E2gRE#lis0;AItS*#8-!BG1qCGQgrdXHGhHM*=Lma3W}jWxSWt*Z=ZKn*A!=t0#`JV^jU z7+7!mElf4v>kYh8bEZM2 znbz0xVq!0sQAEHRIYsLscH%sDOXSC?g5@xs0os>(=*9Tsj9;Z^SRxo)>*-|7<(d|?{dP`HPHh2ORDU$O z12BPdgBJ7i2HlsOw)>s@yYORl4H&?AopVpshslv7aO4}j0lB5&g&i82p<;{k^P=7fh}0C-!Avo?c~KSv&H z1(R@OSxpJ_9EJn(F}`Ped(G>7OJTjwfZXxba~67tnbIoo8?w539#o0-9kZyL;D~cF z^Y8qMtb?pm^l~r2a8@i^o8sUGsA=DLi8tgM-VflN>fZ7sLXasv60jH-Dfa zmfshEhkF4K=G81WIJD<09P)cJK z8OKR!DLr~q^n@7aOar(Cwq;p!LV)a;Ot3adS0n>u0{OBjNg2;Q`R@Sap7rG20`6z8 zSYN~L2A>DNj7rud7m(Vc8k)`1L8e6jQ#xKd6}kw)t!Vj8`nJ&mDWdnlN!4e{VaOfs zf(LQ-0MUU4`wvXG9u!GN^KvHpPc@K5K0LfANvt2UQ#_nMEq|TezGBfd2*yI8>mda} zX8zu1N(o906L&zG4Tj%Kd8Har)UjrT%+>KaDq+Mi>lF|RTqcVyy+;_lN&E=t0?3>& z);C21$SJuDDKNY0BR(M%JQ)!=)JB^w02hCdr&Uu>pgaTF)Ke4sGpS185r-Qn>4bTh z{Ag21K5%6H*P2lI!jJU=wTzh8zPZMhVw!A2xP)1};&;i9;Jv{`rsjvI^E8Qz;wD?Xfe*k~Sqa*Ckx>vu z1y*w=@#~xMp%Ojtsk~*jv-3jN%9IO6s3C8b&#f)eV-RFF+Ik{ZZZ@QL;kgR^TJS=v zF~SpjLjtVUnk0DNI@3kuT85or93M^hNumYbGaEj9+^|pY0U2{(Pyoy@!v0k%CjJS;r@K zy^lQzu|>6>)6vy+@>8AOS#JbhjvO~oVP&;Ott`@-s~V=ha9E9{c z56Le2)unGRS$`Cn~U*s$p@~uS8{>#R>v+V3v3R>G@TRu zK2=%o-qe450ncT6TITJp00b0XVVIXbBHr?GVIEqAcw-|IxfT}78zi0(n2WGI&_0Q< z2fdKR`BQ9cGF-Q{6cAWLt0ak+za}r-1AGG{PJ0QL4(fZPk1bMybS_*q_s%e}FO>e4 zm^!|9j^GM^a;fqyOeUiss@BGb*{Z9B{zq1e!Rq7{>1Z$HQZ>0D&iIqiTKN{V=A#kx zf489g{#B<;XQBj*0t9DSgCQ-4GT!R`#A0$A%xih|{(x;byTID3rp4YSQ%QywklqV| zs0fxQcu8lHAD-JE&4Yb)w3zpbDDJDwGzNA*xHH^O-U!Bl=vyxNkB6LJdv92BsJPyb z)|TPdK-AZDHW;wzr`TRlTJChg)i_eGokw0(Rfe6c98^_!u@dfh&97tY?4fseHCi0c z)&;xSDDkgGXjArK(7YGoF5BLL5{*=iw;~x|pUEe8`TK_iOw^q*LV#iSgWbN}zp?u` z-0+4jx9jI7v#iT9CxsuSUZtqB?ur_jJ9vBNSuov>CP|nx?w!N^do~XCok&c$RqM_- zt+XpxAIGbjnk@n8Ha7O-gA_^{S4^9&w|9BNo)}OY3W=jTcOuGvNy1y@SB9OP>(1M8 zu`{iEb~;7QwY7G`*ybT1;T*c|9GW9jQucnw`7JGr%!LW3g}Bk)d78e=859a0h1@#^ zGMsshxusnQ@F7D&nWFl87u?G@bucmWK9i7SJsHtxcZM_%*5cSY$JfUICVPoKZedvz zwYw4HSL+BG1Gw=~a5&p^-zwniSoyh3M4JPQE|Y2d+E{M;+x$Ezw&IB(Yw#;k_g``R zjQ#XZWlV=tmK#lFQiRnCnoeGoYrrbsZ}6C@&J;cQvtrIwQzR9R0R)d^NlLhFmZ=;? z9aIkdDl5xQ9R^L1ff~_AeT{z83E-snV+H&RHa5WD%(w?HDLaKUu(8=2J;9+A^}QFK z9pF53$KSVpAL)m`4;M)8LEXul)bw^$`{`EZqx)xa9Dt^6##{)u-Kv;DJ7gAW6@!1rTmJ<^yCt`;=U0LeD_TIaAMA#q}JW@bxc|e)*ZEYuwwc2|W1H z!f>#jmp&S>d*>&Q_X>N1*WNqCNt_}%UFtrZ0_09+qbjypBu_7VxxFWTu;xx4=ti5veI4ePMsHBm56f~pEc|Xham5`jhpV{fOWsT@;;WQo7fXyE2O|f zrsi}x`}_NYmuaRo*tkoA7cY=^)Z1mcHMO+lt=DY2n<&b_$}KQ_>5826>)^B*#miG@ z@dDCSF@D7^5>nQjZk^!rvki0}RP%U{74@JODhiynXsfYQdxDLs3u=@|^% z_#1L*$eBi6?mU!BpDAR4hiwPR|(4GvtHpO@$D*~3UbIiC=87La0j-lIrV zJC8HctCvK&i!jIZx5PHpd~66;K_X-Yl5rfNc-*?Yip}1yOdFbhn2TURNcTRh5^Ov8pnx z=j=m$i;9Z)`ZB=d`+bwO$PqL6)fy7s!0Mg4)9Z1dGJ?fvhAu|^Tke|zKXpq-2Oq?r z(yI@-?>Bi2t1R|NQO0y`HgF=?ffkaV((H?`rZmY92K%v3Tss?^r0AyQLnc4lRZ)@xj3k3-I2Za3U8F!4Ge zf%o)Q>Q31dg}mu#VN@)VObf z>Jt%G4U<2v;@oT;Zw}!@54&)~yA5D;ab761X0AlCZ1uS)>|+(r7C{t$+)iJMuNYV;T%e_g11u*W|}duuVYL$j^*Gp(RvyqqY|q_x0NZ*){u{c1dNzAt zISkL!(CLkZFWH66hG+^Ou2oqluYxJmm}^Z-&g;dt72xY#CDvs(_!O*1f;FQj<0T9s zB<o(;cX&rRM^P0ZY79ZJrNgHQpom;uMEgEXv11u$6|O(@o~$D9CnTa(t%IDhEtM zQfH$4{D2H=?;4E2dRJ}~f)(f2d^PiU_~e~H(=fq47tw6PulL6%AutU&IS-#HrLN=} z-tJDXlW+Cl*MbYyB5E?k{&)-(vDxAcrovc+5TFEmlCCP4gm6y`j9y`H)4O)Kopzh+ zso~SXw7@2<7PKr*0@uE_;J5va=(L&`Zxmwps<~nWCA_-z1QtSOq$p4d^9u!xBHP4V zRFWAb@+2zN4gx6P1Zz!WpvK2Bt?!7Z3J!k705zC`fojcE zRORV+G!`l(Y~Ob_Qw^S~YuoObn>Eam@}oDMD{_Rx)O%(l*7BzR8I6DPu?aDsEjY0n ziRZ`KjH+xlz`_vFCrVT_geO2ux~<*#Pk)Ng?jrFKcSgVjig6PT1(1>q7m2jPkKSv& z_{dkI;-rukB5SAW2ZCgy{T{C!Px~146xXjSfOh*=@$KnY9(*s%pCT-suk6k1U*&x~ znLhyr5#P^&1G%Q_KF42ZlY-kFt&$PMyx9X7^i#8A1JVY-vaaMJriWYZ)7|Y2(^_1M z$axI->liE13orr|-i>;=XGLwqE1!Mapffm9S_bQ~vArCZf!5I7x}_y1m{(cx7P_kXVls3j;+PLC9H~hAF+C)oz=Xj7}^3UAUeo9fv1uJ4o+3CJaf-k zQIwO9Rh4J)I#ed3tSUp^4X@!1OTam^qv23P(BawJ!Y(c@R*iehk*wdVzi>V7@0cx( zz2oO+2`wg+Rpm7-G+Ug)s)1EmLPkFnTVr?T`8*s$k2Li}B+$3ChT1lW!#{uhI%Oh& z-}|DTyT{M?f-+GQUHiKkp)Iny9wPJNQPFb~85}AZXe!D}mm!7bL$X_upmLQ3OzYHe zA9=_415mfh=JVM2z;%mc(XULvd$?=G6g%OSyOk5%>+%#ACqx!LCD z=ij_}GmI@q$`1nVKQMD>06!jmO9Dn1u{)0Q7c`&kg|AB}JwD$=q@cP;P({P5p3NsQ0oyP1(2 zzZ$Bk7O!7eiC!W9F1u>Vk4srlow*eos=!0kOOoXif8c^D@sH3RBa0U0*Ew82f4&{ziAQskxN{WMo!Tl{1Co8fviPg2aR)72ZI&iQW ziTOi)Vqr5NfgRRpC!ga?xgnN>?g#xlD=KTcHP~Cn$-f&Uep6b*Hg>kr53jS%OJ9X@ zO1?u#;{*+D$1|0#d6|bJfVfoe^h0>Xd#y{v6@~Uci=n!$Xy6Vkg8sY2izKY?m&Aiy z-P?@cpdZfSGj>5JBNZhJtl`}y6*#cf_yCOS#1a%pe;n(p4oVC1tt%x2Qslb99p)Zf z@&E?&pX5-66s7SvdmDVJi9=!%xC$^hL-Qu|bb+_SZw}AM2fB)Cf z7YZ$<4wYHp2-@gNZw&|oO*LoqM^h(@*Y(OThMb`KGg=TxNX_xozU{9+e|bfmZ?hP= zitCEfnVz2Bpg{b36koFJy{KNQhzk>Pa=@BZ0m)}>cSUR=lh%U-*??koV@C)ijzk^~{r9FH`KT*qQ!*6|l z=_^QgZlu4hWNr8KlvO#k#>jR1H`y&LEHL*5ExGOvvOFLm70!kI^Yd#DAfMOPf`b(~ z2NX8G=3g-#sM)(-)luOX3Kvt93`4f=U58AvBG^x7DC%;VD`#OBU=SHz3~)Fkm*C(> z-T0-!X?kT=+2qPA{0d#&QaH$trk?XbK>=8YbE{G_!kQeJ;q6~4rduO7zEcNV<$?9_ z`EalU77tLhLKH;Y(i>e^(`DA<%KjOGkOCL-)p2`W)LJ>(V^F+iIFYlqpd5M zk$Y-3#_;n>Z>W|LoGTK$+gWy&$513N`SCgB!(7DY8&$ri^dN82g4*qTE7rs$nAPz= zDS4p^9zmWoa3s4P?${_GkR~@uy@lJy?A$6nwIP$C;v6S1N);t8zfnW1zF1i+t>}@m z_~u$Wal`wo?#}DoSD6~{oBe6PU?PJ!#2vrp^$_{Fz-<4v4yWFwe#BbN-N|EyRhc+? zYC<$gu*jJ2q25`6>Ra0tE@BaQJZWfg-*8ig0h;%U@spVUV91bFD`( z7fDTU(^nEOR4Jv2n@=nZG@vy#u@H&44#}yiy>>zRy8yu}nCcn3f!SL?^iw0xMNwzN z^h|Q0`P0!Wg8=vj$M{Y+Iow@nIHe&cw9+(l3oW`@Ge1l;wtm0tkDhpH79tbgzWu{5 zim|&HyZg&|cWJGcM4eO@mwia^s?mJ%{-*hhsa6O)A%GyX4=aCQ-;!!_TvY~$WKOd$ z$r%&By0^`3Yyncu#i<6sY-|d$r)Cn)cyJ;=)tw=>`r6@4Xmw!sz0j>#R(6WDCb3Fy zYVd&oFnDGCW_@#2$Ija8UEpCB{%2>KWo^Q3<@eDq&+9R1Gh&V2vLS3VKI#ob9b<4k z@3sw~COF07>vj~`sFAfSl)%)l5CW2TAeUj+gh1H4| zW@jmrk-=aTZO=Oa)-!n3m3n^5HwF}ubdc~1@nL}sAHl6(-58=w2KRvOW}nvD903SF zcx*IGi{l6cYjT(%s3;DUpJunMNDQsiuB?DNk)z`@zAvM60RlrDG5c?DY_?~%Reioz zK2PC?NmhVdd-(eNzi*1UsG&pil>*()}8alRb4; zZF3=PIdX=|@xN!&l`Ti6rtJ46g@&jKtJ#d%BpL(uAzD56c|V|i+7f?^_7k@@;%XZk z#}fmKepEM#A)`VY`7t63nE_V0mO=xLQ$U&=CZ)SMFZbxk@yE+uw#IV%AR?9ZBJ|j; z$|U~RM>%wEtkE_7BE5@Z);{ci2Q3;B3U-KI>I$6^-$~phjmjLWdFB0+s|Rrec*F1| zj=|AW1%+Zy8|(*vP;$@%e8F50)WEklQ)jY)FQ>k(C75#5(4`>5>N#Q04`B_%*kp~) zeFxGOpQ%%BNDLBUc5$f-?E&12l*DKF)C^v%{Ju3Kq@>sbCRx!zk%-{XV~0gS>7 zb-b`mYefPAD+mC6Y#!zZ#F6${eOOn#qF8Ef753)gNznE3BE5wZwPbV9?7uO+ z4@LTp=YqBV;^`tN;dvOXp2v}{0Vs>KN7G^d65#*dOxybqRQKbiXovZ4&NteoKR3a{ z-?lfW<3V7lDQ8HC(#($i^R=%iszImix*9Fzx&k)|Uk|ybGH}@K{O$8EIj{n~57)q( zGeqMlY7C1PCT?wm0$7$!{Z08_%|`GzNR50DJ=4%cvCvZ1u)2{t=n+(Tp8R|vlJdY> z1Lur4PyhbwS9*YOoTj?QNQZmnm|duYP~Y1Wd3B50X%|vpU=%UT&M)qzWe9vLdXV~%b-mhAT&idrLLL)2k&8h__vB+sxsbx zsdf$u>D&k8PUNO+kJmDzb9a@)qhlP$jxxJ7*ae!}>J3IhhCKXn@LQNfePkSoK##1v z3qt}7FkmWC+e|Y)MZQQVX4!j#?nWGv0Te!WO%yTa36xR;|FZQ@i|06LZE zG){j-9HhHZ5lOK-&kJQprDd;#+gu|EcsSS|gD@a_%QYj|1RMM=ynV9Vf*p=vP^7Kx zLZvLXrz4Ah=yTalF>>g5m?SiHEI@S4M^=4kR50vCX4-QJ+?PcWNVk{LhFyK|lZ%D^ zXVpRAKq|n1XPqJ)AoUzI5UpczZ)N(_;l$zF?;gB;+bo0Qn|zNx{Y%DlbZ}<|c{Y!7 z@^Cj&~pDq-{v-b^}7A9^?~qRdfS5gN$98@ zUypMoBR{o0li4{nRHX9&7PHjFT|2>vyp`Ya_O12gJCm}yb;vb0>9=+CwMn!GHRb6E zFSR;e?wJqhOB-7bgy#_cdrH{>g3@X&wCrgud--hK<7U*0(N{|DT4Kj5Q!d$7zoifNA$tI_^sN41XN!L$tsOMH z!*e6p_xXHA?U)>Hi8XPGH(PZy9Tnv68=dCu@zM#U?q?!qJ=0@0G^eBgZf4&*nAE=l zh>xRlD?&pB8_LO?(8Ewl`1nT8GXp7L7o@C3KT>jhJ)YMx7^QP5V->{4S!=lhBf%%I zW~VdXnb>4y^#Ack>p|Ya>ERF#Y%BNyfzJ!4C%3SrGZ0uw5ah(X1S@U`B*6s`mH@aX ze?@*k0v8Qf?Uoi6u7dSGp)oOE;}1esqjg1?K2vq(+u-PCVB|10-`J9|HXOgjci3j_ zdh8mH)Mqp|&q9I@XxmnYwzDJg{vU8bX;;poYwhORb=B1^GXAqWagQ4w;&2Hj$7;UL zRs2cAuTmNgM57x!|2$%q@&=#d8X(22SAIf(ad@ko{OqYs zF?O?A_qtJ)mRuGn#%pS5k_`T=T%H)TsA93*abZJT5N0Bzkq>eki^7sMIEOE1^^MNW zj`g}~ZGtG(_k1pR)XMxO;O#;rd|E+@b0Hm_ik*w!uZSWl6(`MWw87YCKK~@{Q}CcVxK>3M?Ew^t!%~B_E90-#J;JjNU3gtz zigWdx1kDS|J%teghB@L`}sfUcW-sQ{a zhv*9ks+$}%h4E*MbM}HVs&i(lxw*YbpCE$efTZ+}L~`%ab^i^;HS$?3?qj?lnoKu@PWh?IxSwCi)Ln`VzaV^!66UFxDotvcr$wd4)R-zxPRkt!?C9r!OitOb+| zSSsSt%Y(Je-We*X4A{PlfXIImxBBdF)wo?R;4w;@2q^yWY*!Zq1Gc>-6;cW}1Ae;@ zNJTwfX~UZ^^1xtYQTO7?uzTa{+|q@$cC_mR0xOSh1bnkv6}OwKlMOwP)7=dQqO%bJu)2u2`YM)&ksP>8@gnghdt-*76)6+ElA)E93DAUL zKd7sTq(UIk(_G@M8-T5e+#|%x4}jZ2nATyWGk%~(5c4iTlv9y>%+KioN!*p5Z8inGBD%VEh=H6mvHRI)X$x}j<=QbrxT_mX2So1_c8 zS0qk0U$FWEiC)5uxP0u4eEDH}?N{#rbD;OzD&14mI6O$MEDV&nCaQN2^<3nu6mFJJ zXUG@BsKK*si4acMgU2~D&h>EKu+vhtcGA_nNJXO!!(qPUm6r>Hvui$JoT7XH*9=f+ zYo^&Y4-|*(zQV=6=pG{Lgs)f`_zUz8F02)!6iL(vHS*IDtjgirP_TUYqX2(1y-W9l zCry^MwYPTTY<$XFuh3C6*(W#B$O0Kj%Mgj9)`0#(8Lhb9x3tf$f+I37C8`F=^ovd?zj zMo3B7)KJ6_9#^|^iC=nhKYwpPdd$BG4+sO5{G8w^$OR%-K-%iCw*c)z6Yr{s9HL%p zo6H*XZN%ayoQ@}O9MKZC#4EYkruAX*07D8ZZhYjf`{%1)p_7BpMq-UGp`k#;XwyKh zSDhRAGNu!b#PMU@Xn_{fVSkpGy1Uu7rz)?N_vZ8Sa=o{-?z@Vt^AB7yJ~-KnhTTX2&u?-ijT{EGJMmecD|)3#QtN5`>Ew^ z$2?M^)ZhWD)Mlyy>Np+|L zrmw8y;Wg|?@H~jpC=kI`z4k-7;jBo6wL+!+N{U9t)(8@HU<^Q3Ce)mC(dyfSpbwr> zJ3cK*z{K$!iMM*61D^pM4y$oIv!o@#!dVmIa;sx|?TF$f@m}HP*^@@tecnC%*sn&5#l9zW40e2e>qkOT9D~Mv_pK$GKd>sFLaCfh;y$fcq_7vERrEeG|} zi9lEpi~<`c^mrc#VlDzn5kYDH?xOCWN9j4cgB?3+lO=!WGlmv@8zLQ>{|l8C+m$_*rmA&`%e^9x=&_0%-k3`^bU=9`rj zYr&%gx1$mzc(*xFpuBNhbZH=iXa%CGJ8S(B7WeWV)lA%l=BF}#f(9+}rsC7*w!RL3 zHWgy~-y$B#!aJoNW=PTKG!U7$_G?}K5m+4-9Rl1*M|eCrKC2D7heCjEO^P)CHwLla zo0r)tz90L+Rg1c}I9!?FD{QrGT(~|R#l@peuo0Bav4T|py{4=6Hg=c32Vib$p+U?N zx+oq;@I3=ULqfF=gJf>h-u$30g!!+f#eABNusjj5nGJ3|6YTMF8{4dbi72h7^Ba+s zz;6IP;5P+&ZyqrFFQ!q`uClTolXM~A9;7foU&RM7^JXxnwpnhVz*)`Bx7cVt#kZ}< z8=fV8m>YL_R0Y960js+Ha2@zhUfL| zEmIH(kF=F&B&50O0^(hO7Vn8(SJkIq9324tB~ZP<(g*+)vum!~37aDp>UGrH)bfTx zrzhtbX!@5gw%(7ZtkNnQT?A41B;o>qSj)4TF|aeof|9DK`}Gu2Zgs-a{r$_sW3#D; z+ED=Zg;%0P#wis;!KTbRHzNO$%!=*kt1@3j&HyPTNK4BUIvIQm=Jmn=@-F53*UN+1 z15<-k;8{CU_WQCRpO{WNK$HLG$9?>B54H@~VCFTkY*mij02 zP7uQ_E5pI6kZkVKY_WvJ~gMii~+O!}vqyN81zq+)N{~{BS$&Amov`^>3KZY+pfHqe78LMsoHG=>E3TUFC;78EE!UoeLMh8d!C08eX4t$la2 z=->0QQ-8#FnX#+iEBg?f3IF|YubmdJJ7_b0-cB7>a^srY-2Sy5cC=q^Dkn?`aM5X5 zLG(}u9Wi#O=2?U34ZIS@1Oje=9M2JfaI(qw{DGA(`#_*>OvNYtIgC-t%4;CuLLIW* zP8vLv^>1@@EGX)Yd;Npav%a``+guSuaC#I4ZGu{+V%a^@OJX~KZj`KO`+-T(!2B23 z^u@0c0hZ$Dg)M!nUZ*O7y8=T?7SCq=SQ`rlBEZ5@AGZ)Uy{+3t9s62!T7LiEIm zXn;+8ct1KIdT7V!r{M7r8(LfYTZEhK)K$8t zQGlqSi9Ap(=7Kd)`}MyQwM>``pA|{47~o?z?-=n!ucWFqH?+Nd3r1Z@74=UD4pU&u zT7&wAS_k4r9wfYb?r!r0XsVdXiE}bU!N!3XiNLn*?Tq}<&H!#pwZjAKB@)-*19F&6 zO;3lIJ&JJ5ujXSI92^b4KalR2SUnhE12$JZ0BWC9BjTVtU_c{Y`3YZuaiFA3ZeDjA zuge%lS!S#SPS^|r6c7?8`{G6D6m7>J9^iT*X>^_*zty9d-xlRl>0rh*w1QE_%g5Gc zGp#S=mYRtAG=^gQweM24!1w!PTuT)n1V#E=HBb_!`qU@X9tP$RYER9Yt7@s%W+?rh zkKF8i#0}8xqAi~FZOnPR7SUw)p<-k@YK?SmKg6H?HGcTEa^cWUZ^s`VA&iWtt&Pt( zGC7k9mw4Y4BzEN&2NWLCHbVVmo(g~HdQ~WKHcD&&tg9cnz)Jov3&3<37l;$aQbGNt zzCK==G11-Z9})4ovMkb=m6B2m;Ud*}dCi=_%BNv1Osn_;QDT@JRI zqZyGeUTl=ssxyBJb^Mtv_OxT#3OYGDsW}YfbmoBAs=CJ!IX?x3vyN@IQ@;JVy}dXE z-dX=T?RpVgKNCAPnY!Drs3O3mu^Q|6LDqPncfill;Ufn85q8Pfa4K3jO(DaL#Wi?h5TBMtL9tZ z3qs4w!Z&}d-Bw9sATTevGnwk7yDbwc!EJVxI{%h>Xzr2G(UtY8)Q3{q9j(A$Y$8Cu zF&-Q}ZSRf5fnlB!_KudAZrGA@(@g;9+uBuqYBA8fALc>i7aATI_n>b{4JDMGvy*=E z92aQB|HH$BnQw)BIWzD7xisJ(Mbi&xWCzO2fyG{gSsV3le&XOGiDT9mT`B=Z9)>h} z)wuZMug1e8<-SL6MOWfhDOE3n89aK8;f#?4V=>RRivE zu*3BnKo<=$^9J_=W4- znokF>voib&b?rZ7CvIom`>0yK;Rrjdr)c`fnAqTbthR}&Az-H5-Zr%w&4)Ufe-5w= z-E6%og~7WWlSCL%H|DXe9JgbQd9AI^34ym3h*9EWdc$9AxzyVo1!49EcKepEm7w_* zAUpRvoZ1+YPNMwUk~N0vCx7*AksGj9G*LJHWA7S@QgVTO1H=B7yga|c=%e|D@B>}7 zDyb#6YiU2i#f+B$L?@*o#rO)JiyALkqZtb<4Dh6jN)ht!hdj&z$X)y^KcqI_2y204l252SFg^kJQmB*J%2 z*rX&LG*hZUG%o2f z?Ca`xslghL>8O*>S3&a}2pn@y0h0g$z{erLO$W#1mIede`c7dWJq#mvc}p`i}r z^*#rYtCS;g!d;KVbnw#C><~u4&Wcma9XJ=FXD0vrO8-0iE7`NRRRSgOeWN9waLM=) z$>g%;-w+jZd$qOx{=m*X5jcu>`w{1MD5hf;ur08ju3mm^5&8O!~sJdQW@>%@MxZR<|ZGE}k zZ*NcRmm`7`!qh@VJ#qM=ciYqgu%$v_U+<`vm;Kt=-m)x;;eb2?x9=JiH-Hk1+d#OK zb5js92B5nmh#^$of?675UnGtNmS%ENU>4v-^8lZ&5)b1_^7U1lyl?Sp%nNAjnyZMg z_OMNm-QmZBWAt_mxHv>3e}=TQwNL#<)5H#73q}$GpUm2hubGIh+4L&qrW%O@L?mnW zpC-G5`+gU?b!#!wDQdYlut|m784GaStY!4}!t~!|+Ti;9W_kM+j*MuBqdwf~1q#Q& zA&7=&K-EJ7f_0vnOUi||&~9sm&=(rGeHL6*rx(`aN2qqDo`QXyn!nCGa0XZ_d}(dC zEg|s&KSq&!*$h};bAYbCzBHZB0vk8ZvXOry@xuM`G# zAuLDhd_>q_P*`4mx-wWw3WhXE?|1D6NB+_)&AuZ4(*;hJy5PaIe;j;eagXJPfWS!n zgl8o%WsR;y4Tn^&#e|~LwH}QE;_|)nGB0IebswmQAY+CL+l|PRG08RPjgdub&xiEM z%DOp#)>BtbGfRlIw&0$f8c1$hqj>e8E`aV|oi$2N4%Y}`<=QB3v%*W0?pxL`Fm_y_Xfd*4@AS1b(YyTGMAb{P&{MzkdqgMYo4eGO*f%7X_IzYlWdY zmZP+g3$RmDXD<(*E|3|XC>M&JN=^TKTRU$sOsc#r0FLI4Ai-s93pLqW?c+vA-gA>8 zNN!R*M|7a9e~P@|GC7H6w{eZm0X4QW@3GqckVt0R5sZ{AxN@^f&!4@ssHzGP{dY?_ z4td#hs#&aA>?8pY9$tQ7KgU~GrmDDxcUFAcn@`1>&X}Yz}KR?>Z~LU;AjHe-f#f zQ0AR!ZL33_yv^G01~1m=jJ7?SH87;Jt%8$i`YgUqQMd41I*h!i*oDB&RB}!3$G-~E zf!>oFH98W9gh4rH?tIuBn;6I$1-r)Lng1rg8teWYwv7Gj0rK4-jkz-{zP+N7Qc>+m zxR&_q*RR~b3E|qxa^h%4%ff#BoMhD3R=MQH=@>4_j~m-#V>anBwVS{F(Gq41bo(B) zn|{CSRb4ey|Cm~3`cj8;?A)OEMn{44RN4s)}k1$!yY{jOgQ7xaC+!H9oE zBE$*xBGVXB$pq`*sk;vBC_R|fd!Ay5BF1Q6%Eqp_D!}f_cH_Q@Je~V&Uft|9}ws1Ds){Y3jXC)dM&29s%uPs`sFF<(O zI*c>=LEZ!cwzA;o1L=j!qJ2nQsVAzKU=`Qj7WsluT~_w1thu$7V0HKI-RG6SGS>q% z@U0ux??L!H$k6JdT<8|fRm%lPoJ{00l)bhnk!%biLEk|1o}Qu?OXgw8jQo<$j}rO! zeUHSb!Kre?ltXsH-u1P(HxOshUN@`D2H;D(Ik6d4KWVeC8)tps0xHGY$XfB3VRdMN zL=pz1=pya2fz`ER%|3Raw_M0!+$Q)8&R|c8f*kD+Ysyixc>qr${;XAKhnUeLm!5rQ zFZxyqlMqn9Go)4Ey$q=ZZ-tsWc-S0wuewM6^SQcpS&noKg|iPEIHG4aOb1U=X_X80*#pu3t~VImmAVP*IL9RLSfNG`i$ zf2J=s_fS;ZSyE=zgd?@wxnQ1DKoWkpukl$()!s`4-L1$%sto z6=*5(i6A=pb7;pF&10z0FLbJEVJ7ykPcjc2{8P_12j)q zCii^(@s|wdkljnyOVB^8q0p)JR4{@OihDue1pX^3(EU9l1f7M>L@Sa*wmX}ifjw7Q znVkYy8Bsp_HeP_GuH-udYbuCpNlE+Vx~t}KKorRk2Aqn>*V$N=WmZ&8SIrTI4lSWIM)W`RX^%7d|p zpOf3ZuTv>2t*8O;6Tr^qmNvDuT!2}bB5|O?6mD}K-retds}hh2tW9CX)?Ug_FUsYC z*CmZkuew$)b!p4xWnSqXQ+_GW6A_)lzfvl3x6r7U;Mj-M7NCWbO{6H?KiJUr4 zGQV=E3shzC98A3>eg=3FW9qG5Y>0=!-ZvkB)4$L-lClTfY_qzyR7`nfybv0d`2VUz$NWFD0YsKK&Sa{EHd^J|d2>L%+S4t`L^OJyiQ|+g&>f1^>+zk&0r(6;n&`FT3+|LUSlJRTUr2r$7_6LFa;T;7pH`)^;xY z%kfKcU>I%ns^E8Z<-O~~OP}1bs_Ya`2k_T2c%^@l|3&`-tzbmt%CX*M_u7GxcdOd6 zu8p*`bd@w$e;vzj3n6*$0t#RFjPHl>$6Z}2xfAJzz}8O8|M;;VJO4kn*mHuzxE!e! z7+&QE6iY$X*2N|ZsO$P)OGE_)1x2*Ff zq}AnRo<}7s1LfCWQygINO2mn}g$N{Zdr?n#gAVGBwEz|q7fOyic;6VJ4lWnRSxO}M z*XAk?7_8gbyzre8w%L0;#rBvnT@KS}toyHPaBL9#Sya~fe|zg#f$&@=aDFBunm<^Xdd7jtC_Q4EzUIDGh`=0xX`(Y(`FhPfsbKsmp-GKb|8;E72 zmgwBrJG8ny+Sz2rMI-pV8hMWlIoN&W{SZBPAeq%Xxex-Z3SRg5v#gKx7PJ0dG(G!v z^C?M>`m=ZB>L7`L>tWq1TwY&WS(P*eo3yptOOYI_%Vq+E-GS?8>ivj zAk2manW6Bk(z!+dHxz55{91{y^7Aivxgc>b;F=z2Ny3v}ui!>nGMav3-OT|kC9rV^ z<=o!vywQDUCCDV^(J0|eE(x3lQxf?}QBNG_Y~jiL;7VY6mi#UDEn`RjpnDgi)He9=V9@av9@zR;@&x7 zAw8DbqHbqbZ~6tOum^P?tHS!4{Xw3&2vYrtI#u#5GftS56n~td)pHXJ&pu=)B#sXT zq1a}XI*fx9hqUK-sQGkYKL^AlT_0Dc1nI7ke*njUE)oR7>5Q-Dm`^T24b0uOJCWS) zIzml_OAf6x_^4y|jx_Yx-E9#509RhwzCQEO`4COq$H1ofEk|!3{M?opNQZ0a=*Zw! z9kR{AlZEoD;VFeV^{o?axnlO}zV%HT(u^yCgbXvX9jlvKNV_757>#CDYCE1~HJkj_ z>i^wvrPBI(UL|#%7COyChA{E~tJ7+IYb%&IL$5Y_k?NBFW*lnJ{b; z9QPPr0x$*~U=9ubA2=we3S-T{wQi)Q0_6dLxS6F(nO{F=lzI&gu|W00!uT9I5vJW0 z=QdrHmycJ%X+OqO~W!n z<^R!iF78bK|Noy-ro_mn<`9NN36sMda#%SQIpkPKP9ZesGil+?5EgPs63Q{=kaLoG zOC~MzW*KsrL(KU!hu_ohy1suvSJ!3R>-Bs-9{2n0mYm(x)Yy6e0y(v6ykHx!*d*S! zt8IYb)(v?LC?7=zKa~`V{2RvZNccfgubqndnA`6oBYW_2jM)lGe40Bw`3Gf(BV!Lz z_qt>?R{-Ra9RWpv-AAwqKX(mP7_hfOzBSg@FT{Zl`T<2JBa94spfGLGu#c-3jlJ=a)DL4p~zr zHcFgO&&f2Dh2e?uXV++a5D*`C`uiAItPRKzNAgB1Kb{{hVfi78oJCO2U_BP&$a5Mu zuBW-(;TW|&sd+HjKnp#6a0iUHcV<@6_wv65D`o4V|3w|_?p&L^>N>T#t8ve{VLDyd14hMbT|XN^94gOeWYYu>(MITG&wxxvt{*Xr_xB?sSaPBD zse)MhQv>y0Lji=I_1#^M`mDekcc9OqS1O8dVCFisW%Ih*%yyw=3&QGId*X?oWI~Pp zA7?No22<5~uSv;2IId1$pB)PT`)SIk6nNfOgER?hU%eMqG8tUE z$HEw`y}e~SkBKMlkk@xBe+wtnTxQXIktUhUR)n`m+>s8Bdy(?VGE%K5Gxl=3m#tx!FY4+WW{>sg#VB&L_xcr06O)G?1Db#v%Z} z{5NfMIz&hW9xEjFFFVrqgm89KThw7BM)Ie^PREw!?rN`W;#+-k?d4le97I&w2fXP~ ziCqdPxj-}FBIt$R04yOaY*l@TB3X1F3d9&3AkZXI#0q(=1aM~I8dipiMrXTM!rR~{ z2f13gp89e^9x-*H6Xm+FhY%^<4wb2A_&+mytLy71!*u2R7O&j0Y_L&VOY9XlimPNa z(>(6+cHIMwGyummImynh0Yh_tLEj9pxoO4&Ew|(l+B=KhQuWDJ9-_loMcI-b5r z(v=apZJjX#y7}se{)jrSZ8IW zYvFITGur>Itp`OOZdJ-w9UPUrX(3w|w)6MW4+F;nX~&IcLmL70Jo7x=Xh;?QR-FHC zx7-B0u~IX;e=KUNCz3D+uptR1rw|9g(#Moyd0KrpQKXIbuuzjh{3;Ve zy%9RP)kU3PrPOoU{~kmokC$6DC?Gjj)wnzlh}U075LFfZtpY3p zN`5DMb+L+xpS>iSF&^Xa`J&Z*#3zxo=MWaOq#4%bExhMNJTj1{c@Z9z`-#3(y2MXv z*%~G*SB6vs6*uL_A-T{N7Ubc-fpvy8c!O%{;xP!;j1S0OU-C2SF(ZP4(%zLmW5JUH zT|1u8&i|6|e~R6Yt}l~?g-31gN?aju7;FQ}fU@#X;?C3R;)Sri)B7l1oq?d%7ogm+ z)q1)kECn{-WNi2W|E&h7k5I`7EVy%mGK17}IYUDDUE7;6rU$Eor)7f0FUGK(90!5b zP{spDNH$MQ?Dt8P&0^M$7R(cs-G zJ`1kM{1m(6dHFLREDCw|)=BPZT^4n+IWr)#tAq4xR?_;5hM~cjuVRsDf8_*s8ai}g zRhn9EMHqJe8|L}Fm2k~-^o?%(lTig2w^tt0RrS@e@m4No4J*`Uf!Zc;(k1tbgt@R5 zH9&|JZL|CtXX(ox9YnjC8vR3{tht~$Y)b|`JHJV^y@JKd?@l`$xG-=+v2J(r?Exf9 z1=Z5l(iBEF25kF$&CJyMUP^9TOI#i|@kxdaUOp9J+r&apn|s)JpL23H$psg(fH%XA zD;WGj`649GQ?g4-6W)HL#KI&mTIPT-TlNDENW9pGy3p-qmUqFew(Po@gyEy&D3BNS zt2Eepxq?*4=IEPBA1e!T`1V9x^G07QnY=c11imL`8N2#bT!=GTCOA8%#oA1S3B;zVsQiYig4>zmi#op-_FX~XHl^Im(;+||2cx08{ zoy?*SudE;u!34XP8yd-C(J;i#GdDhJ+~VOl3NB~%PJ0Bb{TU{YUx&8Q7|(ePUr8E; zN6SQO^DTz+cf*4bDx6vZVyG?J4M_O_D*|Wwny&LY$nI?S2g}mmnON9DdHkO~@ADT8 zUelXPacN(hmI?X$IK9=WsdvJ0+V1rG=8C+citC*}goQ4EqNiXGn7oQTc`BCHv)uEdHR4@`hQt~5Mi_y)TZzT6gS{& zMQaYTpVZ*)w51)PD5qsy(X+=kBFcCD^UKJA+1 z1eV6;&W)CZru-*i>=We#O0msj;G=~=T7#Go|FFNhEs-L0edMtcWn^t_tvf{+Yz?~| z!VdR0yc>XGGawa*EPzhbNN27+ugegf(pBu?>5*GL0E=qDB>q}(*HvElAA*%t!Q%wt zGLXRPk19|;p^{bT;2ZDooesa@#6iEGBsQ6A_U+Ydx2b0ma)83s36HUI%DFj7nZN7nYhWI;y)s$) zJ0M`=V2B1Z5ILb^^+sa>UZeV?l#K4&wGG$PA}3)KyThsBYw^pY&0864Yh-fz;nv}9 z`?ENjikltS;6Sv&roKj+g$72v>l4qI%G8ZPZ!QqE=~GTpsNJa#6V&C$tGlN_lqlJ3zI=nmP80zg zI_X~4l7)>X_v~lSo=KB-E32A`Y;yOcSz>bbWn?7+hAz9v_*5nlut+R-w0JNK$4)us z`BvXq$C7Km@&lX>`%^H-Rh;OeaW>1>_@&v4&*0cfwHOLmn|>Jb#KdxNv9GUVpkQji zSw3WSik%)lsFeBwj&S0IvV`hENq<<6EmH(iL{2#z?lKn^HZm<206R0Uzu16BjMcs^ zTqXILpFPz5!VikTBt-n1s^JIB?k)J_LwQr%Oqb#MiWjTvq&YAM0vpPtQZKyOQP)PI z=&qruVNU5=EDL)2zS|TntuN?(gt`xzTD5M)f8yLPSw|P@uj=qEAc` z=4w5&$JMp7M1BL0VE`B@CzXOAcCq^r&hN&ph+P6bmlpWZaobGL&?waMr71^IU=k8 zG;mM=YK(mWFg!ouTYq=f>IHChfQsRWe+LG(uL!EQoJjxm%~KjbQW{7j{}dV$Sx_;Zdm&HgjvFDuT$YOy zipV^FUMfX0T6<2%w7gO#uC1Fjd;B`$+~-OG-HN0-{7Tm!h~p3Zbl>3MJs*wvoXg41 z;y}vKqwYhsOu3w~;@g(ROWto&wH7>B?$)F&_4Yh&t15LABulr4F~9+$UvpnNX;N=X z_%kGObyCur;1;$cI;0P`k%h&aZZz%TUfI)GM9C|R``-!Ow0694+U{6 z58dh3NgV&E?D_PCoQ2L#5cS()0~p-p_55kKST@+xaYg%5r6q_pl6t)hQ-=E@d@!rbRxySW3ULsfkGx=11P6YL6Ffc;vN8^)#u;WP5Du-iv?P9Yw>@wd= z95GcS_ZaSVOSq8R2S3Nh-IHC~2m;e>>viPH@XpSTRr}`4jZku+5whpGbIykDJtk-h zRSG|V(CO!M{SaTZpt}D`p3#0`_5hOIlxaSPg~Wvkqi9C;^J^t0fc4%F4)Oa{=|D+S1G5 z!d1=)Gn86)gvX+i0ZL($Y6l38aH*TAbRt~0XR)h`$%x!Ylzn|e$`0dzvIaUZ%W^-DD zhX=tL5slDC{6uwuPW@_y*quiE{*VTS$$1rhI8m227sg zSxv0yZMj-Xv3qFX){@+NDwSGOD)NQK#@&_ECz0?LBZvgxIn$Wuc*M4PzW@G%ik$DR z;BPLo-L! zAi`$afG7;1skIS=6m1wDW$9kNm>49K<=uAAPMML#!`s&()Wx<^&xPN>NcEHV2ArKIH;WZu!?oZIpRQ)zO_HyUr>((oKjX*vLJDU zG>iu&!T;*|#FL*X$|qF$_`vC=f@@u!86$ki6YYMNpE} z`9!z7H4l(yrHu$J|8`^U8mbkhiw~Dug2g~NY!5so7^hTimlO zINh7Fkl1_6@PpON!SL|lv;&iJ_*jRlr;ceAnGT6k=(EYFj#8D*T#`yht< z9kw>W&T6{jVZq=wh&3#FoDq?1xJS%VjJ@X1SaQ!ULSU;Rr^|pIRb{XLfTsCm zp|*zPCzVrg=R+A8k-j3H&RrrniT5k|RY{Xg=3FRfZ)$xdo5A|0xIC4GV*uO;9PHX7 zSEtqpYL^V8%LiTR#8_p|B}yA5)maRhpxGUnqitV*^PfSy$@*oX(&wkker#fDdwcGD zzVHPhT{G}ER_wV1oAid`g}9Gd0*W#k_Je35aZHP}qYVl^!j~G&RQu9Ly)PB*c?w4y zKfC)(cn^?+K^tQW3nN;O)@fjyz$FR*ix42iE8d@^L}~&a2U`W<{x~FQ?YBxv z9T5<`EBu6los0x^V2DBmM6goc8M_919|;`{eH}0Ixb`GO!7j%*VXb$F#>5CButYd$ zO8PfYr$c~JC0hazf%v+gn#3S6w6mheq7Bl#m2yOHwN|sT^gvHNo+qjq&4@08CPWA}B!e5bMGcT1 zuKhPn|D4U{?jJ$YA92Idh{1-4A%DHN?f^TWO0^uVbs1&FQXN0Fw8g-PcLn>->!v`X zB@@_VLb5p{8tf~)y(`&^+%qgKb~@OEA8$?eh(#n@Z=&r|rA6I@%4GXmNsX$JYS&)m}7 z*)D+`BNbLMAkhZm-Sr6g2}WMs+Kxi%z~a0_^4Z(^&>yNLwMrCSc~L0ok`7tH9mGA~ z>ho7HMz2rek7lQ!xDhfEaDkp1@sF?5qIY`<-iV$U`M0ia#9F3H&g1(dh?dk~{o?zL zl?jaK&3l$oPOztak=>$5HS6%*DFcmHBGCnFDN7omt8?d}Z^O2L>WcYLwQs@q^cx46 zV#3^a6*d10qBo^LV=U{woxQSp00{v_6-`IB-~SH1>CTh1Z?YKF3t+1`Qi`zaM0nb#3rTHLp0F#5~TJqE@q1dy>)AVPh#Bz^?UE&zR70c?1{xS9GxmrWRljO#s) zH4)UaBUe%u^uHB$-WY%8myE2xy44+I+#bC73uFlXd8_Yv2J$EyNc^zCV0?=Ve%AYu z`7R&K3b(X9&q7@9!@m8_#Bow|V%QC%8}Q?jX`lomOX@ExO`iPZ;epoAn6?#&my7bSul7!e*TL!b?f*|eSPSrbixj>XGFl%*T0-lVR`yA#hzAo!L7-jxy};dODzi;9 ziB`nivsTN9Dx4qmEa{?)LU7ffKD(jQs}kfXjpV86Y0tJSR^f8wXO==E zL9i$^Rf1p`_hq-ck)5!lNeJYLzwI#qI8sY&vkepfsZ@@bgUwEeN+OTvbudu=XeLK4AZp{yu8TkE0*l zZrvJzGw$>1P~La>TOLJeB8GY-`FEF+^ti+jV7Js;b-TIpgW0NxH$)7a&F8||hwW8s;eT?$y1k$Ih#y?K^hp~iK_S7r(;9bp zSUaY>R0{o79AF?18Ni|{9KM{`wKu(1f{{+)N^vF3dDIE%Dqdbx=QUf}{2%s5XyySr zt(bU_YnEWLOU~a{Fi1lsUw}HugTPZcfQviACBHzT)!f{`*>a0A9g>VRPInfJg~bF> z-cLM0wxgo1=NUKhy4W3$P7{A6JCkWOWHBlzlo!4`SHdN%@%u4_#t-(W@q5SUzip{t zLy!&fN!1ip`hS@qOK)meM*;WLUjY}eCRZ#h{-+&`%vYm}U=7mB>vINX0klLifrxR& zNfjLxW1PPGtJ+l!rT2W@NAq;+CQ(8bTC1P>4Fq1F{LR-V`7#&HfOpt{G0M{Q;O(h7 zLQW3AH*}&-Aw)?d;`=Z3h! z3F*j1Yj0Rsb?bN|T3Q;p?`N9|xExS?4#J|g5BCO|84*QNK@G}PjNdA|FCF%0-s;D- z9j=q_fKZ7kFWD!2-6(qbaEm@xPg7K|FhoF4Oyb7XjhF=%`*L|x;I2|MUUKP@?T4E3 zW1`Trpph2bV566s)n5!R9PgAX-3TqLP5cvl_axv&13>@Yv0`2zv6y~8n3?Mrk{Skn zKb>+nO|dZk?g98S$S*^%U<7dv)^TU~71})~5io8mB<_2!Z6^V6hkCyY_&AuOm0#g{ zrmQfKM~vT|BbPA1(+oT!A?i-jtPm}DEFwXaexIyBo~s2klz+BJVX|10PMBV*Uj{}7 zbtmnnltsoxEDQqE<3aZ9P(I)%{|@_av-$8RLV)(C0A}_>qZ8hwBrazLle7dDs!4D(@+30mGD-f4|Hv? zys5Y&&R1vWvufeZod3!1>j}58i9E`V^)uiTcsXKmu|OIEg`hN4u4`(Jy)3G4o700% zP*a41yz1=j=~Q(bMCHh{L}a4dtQx~jm~UOIS2TezmsB%59!y6 zCf>x!$B0UWDH><8m5nX|mZ)i(tB$F1g_&ydWbx(9#GS}y!=iEg16(fQ>Ce*3z{tqV z1R{D>x8sPfpQ0s)mu|5+<`!FkB5AtLoOkOPQp*|zjO%)L9xF+Kt}0CT=ut3Adj13x zVA0U$QKx!cC6Cvf)p0C9)}d{C+F@sQ;F(^3e(UyJx8^I}=K;mPGuMWt`w8QAro3f? zKyO55x@jJC+!>GB7&{a@zPz!q@mRH|F#e%9+=E@2 zJEFFQHwt(64>!25FaF0v8PPWc;~OECH?j7<8u@p+E7?S#hRyXA^ZY!?P_iL+Os=AV zs9X9&K{gOr-JPGebw7KFuRzdAP-GmK`}B%n2aOoPIE?8jY@_< zjNc<;{b&IfN*>F<0-T|??pgY7r3LrhP(~{lMCes`33db2_beND16~5dZ)I9= zI0ge)fN2VbY0iRr#Q#vqfUKN#q%p{FG3CuYU8GA2F}HG03#MaXpovTvz6~ANY6UP% zppQA4VgNZ19pGc5qro@<)LQ_7BINaPkPL=S`nJcx05l$=$9CE+Piba1un@#nu2h^T zwDn9VaOUk0QMo5g2iEfgO(y*iTu(8AC4^x)Ab@na${KItk*7$MCvv0hhPYYt{M@r2 z;y_~TA+#W%ZL!G_?wZ(0aBLVwl4jPx1F}QSaIQB~7W8&A0in~MFkEc#J1DPC$>5>X zO@4#FyeEKbZ!wTbQggW4Yo-?D*Zh;HYY-k1LAWo}61?$^DaW5V^_;SMFxs5@Ky#bs zV00;cCp@DVkl*e|kaynKvi$(R@xDn>H`DdqnVPIS6$BB;0}eJAP7IUW@frFM+J%`y zK(N+q8V6Hnzn#eB7G)Ka78_RVtNk~&vWupdc6^*!kpF!K_Qt@pC448r&wh%WLmia! zh<;FV7w>|}=A%Qf9zSIBTcITN$Vtc6u~y7sq+l-qGWwD(rT4ft2SDtryx9v4a>eC^ zcERXL!DzneU`94-e` zCN%e+Y0{Lu#x`P*Pm!nEDmHO{6q4y{T>u&yj#+*teE8&7hCIKYF}Jl$Ci>2b>62YKKJ6=mTW!7@^Dil(4s{lz2O~av)Tqr%V;WHr z`+s*5Q}u8^3{su2xd3E%eH{wXHGpau{n0n<2^syx^!UhPUGe-4yaRPEX06Thgj?r( zZ*MCaQ=t!g8$15Z8rWO@wN}H4L9`5Ql)JzD&l0_&wdbx4|f#sc)Oq)dclE8HBISicJz|cV#x&woDkW?xZ&bA2L z9jtY83kqzG$S5-9y+$Nr9%rj!qhb89+~@}tMbHZ}pk+MWG10dOfcRFzk&{)|BX$*T zr8h~dh^4CsP*9%5>3bc8-5~I_H7R}q!h>!LUd1NHBQL*OXTcSU;+{hAlr(dW0;Lh_ zD=xL8OK=y66Nn|E-OuU_EG{P8DtO6GyP{|a-l{&-&4I$WF=iR#cWcnOZeT_`MJjQ> zT%-m2Jg%~Si7j#3cW0Clshn(%o=tb_?_Z+zCj0^6)(T}AtfX-SROoYWP8}>9t}3`^ zMT_)nZUWM;aX``@9^Q`>goqks>li$|FOpUjNZsl16%0c|PrXJlnv5UnYe&<#p?|DJ zah6mwSNFy$buHZKq7AuZ1Hl^*@j}vkrHmW-7)!Jq-jt^YD(34;{~I>81K`fhqcU0? zBC)vQ^ncDA?5&!4=G>g?1NQg3dU3sNm7*lpl4@MJV&;&QO{%$!-Lg;1&gS64P)K%# z4}khIa_eH{W4J?C_I8GV#ZkcFkeCv+*9j<=Uf;u&$c7k+`TFbX>Yr>Xekwda>>N8h ze(uuwD%qK?uL9=Yln}wbOI_iro=rp*pH?5{!C;rC%qQ~h->G2vSGf-M@|O!yZHKcf zpfj`&vU#XKc)0{acf02Q%K|*z3KfLKu$tqlw=@7X?zzJ;1kW*6VZa>@Y_{pb;S023^`qWMkRybAeysEi#@Pu&A7#YkbU7w(u8Jqu)!9{L*Eic#q^px{ zlO|!9j3VUnxtJF&!;h6THQWDNECV~kjnE2wy@qp$T1Ln@80cEsFlvu}>Pa z;>H_tDuOaZP*-Z$f{ddWTak>3PUQ?Xwwykh1oB2;=1hn(N0;;F-|57zjtPQWe=z=E z)Nzqtg9lGk+Jor+fA1N8sGbC`tzvRxfD9|@o=nNwbBv>$uFV;CW5PT4g=y!Jmuh4M zsmU~vScDta>~BlDdo}HGoOaR(>io%~G*C^49*5;>f3})Fn0iw1k_QbVS~Yk=fsI+m zz9l?FsDxe1+3F?B*{`4UfB>o}H8q|KU5G9s#o_@!HR_QHuF|(=)SJR1-=Hi^M zZ)|D7wy%vHcvs&~He9q?00yiCYR&!I67IRdZbi7LRl*%wcPHHFp$*7Jus9z_SDai-3-DMjc}vuneqla*dOolYZ_R&WU*-g=f()Ku#PkunEKld)mNBZP7vKL zg8UT!Pm&#leVh#7Fxo=dWaOCmaG=Rw~4HvFQ660DrMSdhMoL?*OXn zW+*%i_@h;y13&~j!onhiF^SSpS8r)*;_puNBl9d;7*1gz{d;ux8}Qw)li*T>4GZA`3O33uxQcxR;6WE7b6eH4+Qp6O%Nhx zZ`&>ZoqL+Twj2yM6O!Q;0)6A%1mdxBL~qNSw~~@YXkChm#E~_uwH5F)jmX87NOXYR z|8yo=l}R=WfPuVvWJhIyxfbx9+khEV4+iBaZ}lkSi-wzD;fvaf2$kKD8&pK;evQCCr-RW&dZ%Wk>cCU26S zcNTVz`;RFE87K2diLCc_{RKBqTmr-qV)Adi$;`2jEPr!AA{(UCbkewgTZFy0;OU+U4!iFi~#2mVrLu@j)ddIUzuDc+&vA4p03XOkilxjj1oo)()f z5kO}Zbtrt8=qBr6<93$s!tG1;Qm3Nd{ZfnL&c0nTq^#VE97V~=By(mMSzMm{Bfh`4 zRx&EbOAZ+dAcgg)Kr=*m4G4QQe4XG@B^^vUxM&O5bAr-|o`E=!=W9+4hLrKe0sy z^5FEjY%7(3*-jgX7`h-$hif_cr_x2pe8Mw9{hvYrD>(*u-B1MJ^mxzy z&#ByFL^1&a0aFwVw7}~gA3*EXdp+lEuF37EPonspL;&jL@S+np2>u{gIimf9&`$sx z9_UWr!_+0>O^flMs@(lCkTRr3)GFV{pR+4tFavtupo`z1pzhHJkHK&R{BmqvR?pI1Cv;ofrMFlVyf2j-wT=)XNaqj5F&{tC~ zeT(=X_=QDFCO-r4O9Xab#atZojjyOycu+38tD~c9+G1>rb9>JDi==$0GeA1=^gMzq zI)%fD#qQ;75o1mOSG^zwML2TXImaO2}kT1kn7abu&2ZdhP{pFk(hREZ*2*!NZJ)>U%i6*R9z|GBW9SUKjr>=3k1Ky*0(E~7F$kRDJ!Fi ziPJ364+!>bbXGCeLW7Jay2@n&IFoDH!{L@wU0q!+ug~X4ZK}M();#)nlE=5zUV!1< zaF2AN1NQ)T-6Ue4M)kQ`a(4E2AR%EY^KEbMt;>HV$>gZrxWm5vk}Mv#3);2b*^tl9s*|RyhaHEjQIVVL2FO>z zF2y!!dfdK&DmjA||3ElcP@ufKbAHEJ{+{%u5T$iH8^w{4;tN=Oj@R&+8`uM;_sw+!T@vo7@w6zMlAKTlK9b2AX6T2a_y1 zs#h};W!pY|`owEyERo*lO5Td#W!IM4EQn8g!z%{WGT|C6mbzE*ato6I;#X@5YEdgc zIXhQ6d)+S_T$L{3#GpFqWNf8LI_`bc!y;2A7Ld;OwJQJwJ>F&ADD4#a0!1TSb0 zgR@hS*N_?TFf+lZU&nOn2B;5L%=m>%S%Ltxx@e zixmmRuB`s?g?EG3wc|MbM;=*C*1qN61nGq7P=Yqhqat15Da4}?aWi7G9ILuYI(m5sm)eE;>Wf?7_Hd(|t7b<|IHo>eGPFybky8^}JbEeB3ySuos- z>I}b1d<=xwfEBN$%LFP4VDz+zaR z&)t(+FNW2ZO4_(F=4&Vi&WlbJTv~?ixB>7RqxeUVf8kaD#W@xg923nSS6{(+J?er3 zjth`6sPtOOeQlCZQB6}(q6PLP}6~CQUa2%w;)^n;db4?}YWRA8~*7+kSbx z;mXSshkMM!UuS>Sdo_*{bEi|Cq1>!b{X$-AMy%eqISn%_#mDgaa7Y8T+e&K4fECd-ZU+Xw7Tnd(??<;fO{#z)i6#A=hCg$wz-L^HF>)43! zrYY}nfDPtCXhBb$chA<2_V)GxOJK%Fs&T^OS#ZIG?M+QhnON9ltGJE1XImQ10Y?+O zkmcqGKN0>Jy8DB3KOFN8FN)uM#tM-q%@<=x(;-V0DU-oShjL08Mo=3Hb#l8P@t>Mo z`37kRCWl>{`#NVT^^Y72Y*q5Zh-*mr?@hb02ITpWY`FyP=#IGk0v^-wphGzaY0Cvg z(RTcFBgIv)4(WP#etjKmg@H?2Urr_qZziC|kp_TfoRD2u?#gXBQZO|D&)os%IJiKX zV`D^pM$L^V-ANyuMV=hnikej?OM0dWoiyjKv z+W1jX&+K_zdeTOmPv?oHv2li;Y~;#m)=oWeoSM6H_-B3nuHlC|4K+qua>4(9fe#pvf&+OmP{n91X4|+}<>kw<@o@?4YzDl>? zIhp3H=m1npW0R_int34~K6HI*K!G{F*9+bHu5-4$r{PYM2 zi)e0<&DU4+Oc;RP1eo`Kdlk@@+c)1N^s=6opPOq-2g=JQmLf3jn@|;nzQ@(&yKNS> za~J}(3j;1yvi&5XCB`Pz=(YGA;p?uvWu|nUgPD2NgtIrnd}?%KtE@uMtI_&yfIycG zwT>Osw~UXja)@^fW(ni^2d)PuCvyGk#C9UZz7>Rv?iomd7v<`N&9LeOS`o#3F9@nMhea=80{1S7y&36{E40{6XKf0yv$XDldsK4N6 zy>js$@VaWH=m*alNZh#RFxGVNx^*h)z7#jA@dg%s*5K|?0B@HmuaA;I5pUtc7dMtg z`s5kmn(GjVA-nE>D$4&NxJ|PqpxUHaxpi(jI$psj7i^^?XQPEvGW7;0me=RVvKq`9 zNeNTDDugp2EFdiC5!3OmHPqb*{RoGA;$3Ymj=4W%!TXOS&tRmUlowSg;Vmi|r)YLr zs2gTZdOyDRk!l{3?0QXQUH6;8YXl@cE0a7Iy78m7uV?3#;LAFtf6n5n(`r=j0u2Nv z*X>o^<`a~&yS$-dPG4-b3od0u>vn1Vg?FLMkFFRcDYucvoQ9xxiJ^9z@Y6ePae z3X4c&;Xiy*&$cbgDdq#hUvc9!WgmNUbPCA68Mo98f*;`jF5>lYU>@Z?qSSYaeqmA& z63?eh*@lHfh$B7zr&@2&%wvFo^?lw}r`&A`@<5il>?as_!gO@bAFTC9rIz%VEcy?H zGtwDj>guewDRIwgK)6@tZP&xV8ub`bYxqjhg~6~p`6lR=Yj}1@bU??ADVEZaKmxVf zpkD1R%rU-tOAb4J7c^jddf2hRUkRR=Kmb-+8tZ6c$PH4{5J*M0`V8ZGlQ>qtXrz)t zv8HndEFQm!?RHFLNS49&hBVXhuVt$Rl zZ^z#iyXb$nv=SgvPXpgFL{wjDgLVn?7F?=yQ{gB1x=pD8247qKVh9lyEYQcxSuhuW zUY*1p^@q6+dCJ4~=LbQ(nJ)M~I}mQ6ygrEvg~$QN4)#S5iC?W})mL@2lEM=D1)0({ z@dTx6Yg{tjA9dgdvP|5>ua8RVTyYpu5gvxdRUaXDF~(9}*#IT;n|8m*{S;(-yLrqJ z3#hVfi74;pU8|_=&Ps+bSTl5TY3zNRiydtXU6~J1{&z4i$M}*=^xb&qXLTdKB2#e? zyb=#zrfytLo*djo81O(@ig-ow&W#w(8(75OX3HlTI@M`E1#Z9$(?I}a4)fcK;(K>k zd`pB^hXq_mJ3zRfR0BppfS6$Q((H17O~JxTGprW+!-^2k&ssZjpwCc_LF1#i0s;Il z-Fx&FHpF*{VLgWCX_oN)!9-Ex{MIe}+1)2maqOEk#^ybGMB2qxLD%VDm-+NCyxkok zPK$#%Wl@Kkd(D{uApBc%Z~BmV{%A|aRpmrMZv{$P=+M*J_ZA(6m)FbOuC^|FBv>zYv zZ3L)<q-fI(@3pe_P0!{g_md%hL3D1~A{Xvw{@#>wa!PVr$jbESV&5fj zp$%>QwpL!cNf<^O4hLSJM&C3@bCI==v?HAZo%VEhcJ`2sz6HQyTC6YYaW><9US}ya z7y#DO5o2+%S_<9_V3&0{_X`Q>B`Gqjbi1*k4aZudE%nwM%Q^({<%SmIA=kkBcSB-g zvloB>1_l9?GiOi@F_dy605hMhr<990YX>Oq96_AH;`YcLZUohas?b4Y+zIOVRg7^% zc^x}GfWxh6bE<=m1hhcGsDTF(?fX|tl@Q6cbV>LcYe^3sjL$Zbu{-Q$e=Dsib3yHTyjB%j-IjO)iFp@GP-v}B(xaB!l16SFwd*tf8#_5 z0`hQW9VhLYA+xO&1j}|-yTB^i#KIy&f&@pfMk8*C;y#DAYN#~}4!-}j{db>kF$#zQ zV^zvfasw9^q3etFy>n-iAAA+lrD;QAM!maL)+nObUnp_#F&2?n z+uf^R$9`_!DbMY9jTjmorHRC>xjVLoxe0a`m)=QE(ffdgx@Q|FJgl?Nf1L|~+|`sU zI;pa(5BnxU92Lol{BOvMya6@;uJZNk@pyn%5`{fd^f!ug)Ysw7O=?`GNu)wM7@WiT%oO;zLkOdXKvJKLS;m5#x-pyiMt!hv0GkmMKz+-1nPt; zh*>R-ZI=^rA9~crB2Z2hO0@qRXX`R-UONI3=|6vJ-Km7cH5erNy~n)i0)!j83|cYp zV^;_L)6|5^0jyrfK%PThHesmBK{ND-13`?_l1gGd&k8^e(2HK0zblmU(uS0ME|KTv zdU}R?q{Oz%@}sIH-BM&_cPp<-bd_0+1w*py^LW#n+*f;kg&eLqw8a0}{`>c#S;j)2 zt>JXJB1>*wo{>a4?2C5;@Ma(sj=owDNDPJ=FrOK_R@n7W^&c#}d%$)PF&k&^eg-x` z@tlm%;?z11&gp-?-vg8QBXeo%7-Q>*#!G3EOmKulAf0krke0QO*Ov_Blby!4FoJ*& z4w4VJ>YZ~4@nolKBW;Yl1{^_~6VIb~8B$Q60gm0#Faf9BwTPjs#V1O>Tc=-S*PZRl zQKr-BmMMT%yntQ~y$iaV)BQ8f;n5y$Jwrk=+aUafOQD4 z>z6zM<1dVhj8Dh5JVVl3+^N#HUfxA7kN=$;9`5nJ3(%=i^?_P-8j`g zdE!kwFh?Ou7JiR|LG;t!RW1}PKoJ&o0PY+^PEQA+csC+4I0#hOa2nZtK4bQSMr-?w z!v}5FziG4+(A?8tgj?1}*?myns2-)D-ppzf!p=&R2lsRSqZ{s=jf`kySeO{r z#OxHJMxCx+nsf5ln|I&V{4I_DA5CW-59R*;{~=|R80BP?Fp{Md%AUxcDHTOg_K-C8 zeUAw-QcNmq2xTqn$(m%G$OsuRF|sr2VR=eS1c&(>{^YW#X&M z(J2M4v6Z6u1I2qSrG>kVjsWL+xcXT$Yi_*v1oqSGj;hMK7|R0nH} zpAn1f%_gtS&*SaLmR5JhlGvt^stE(-r#xjgLG646wdV0osR%D}oLRl?oYwX4;-(DqyT>P(MX!YG|y^RCcQgu~x<=Rc$>~>t*7{C7S|$gZ%uI7o)HB zR_bG?ngK?Rku>QmW59z0UPXw#AxY<+(}ksFx_xxdi|j%E+-TLKvJv)iZ)!Lka&cFz ze8>&TVK;rqU>ZhT!KN4VSas7`ULvK{=y9lSF9n}nj1J%fz7W{2m}}k^2XPJTFq&Jb zuoJ3f`&U^eUy$vVzXbgLz0t{7ERI*|QwZ%dh6~mOd9?xj8K(-{O=U@cCA$kI^%a_E zxY(xjE^G`>zU0FrgePVd3~olFvecs#&FpU=(>S4f`&-(nf<)nJ$YjsfZ8R-tNm~AD zw3R#HB@)7H_xffP!UV#0ZV}8*CZ$@=Utlcl)_q;AWplE@ho9|{kUL7~a;f~^J+1vo!udl9 z0)JM2-D$e_u6GU30Nv-p`2T?5$eTnx;vi0f$Z`;!_mp zEnK=nRiY7C*~EAKInKn36`u$da)l`s8L53Xd;`}9p7;H_a=7akI(M{D*smINC0ul_ zJefzaP5h|6W)9d~HFc3=2+V#F2~La>Su13L=pYF%!kCNDSb99{&R%Q;$$Mj6Qxk+4 zOVbKuq`V}1>3O5nf-=%=_0pU9!uj@qIANmBo#~8Ff-X0Dq@;n1Iy^T9tX2Yx;RS&*}Pg<9%17 zSekvoB}E+($BmQaj@#Ha2Ko3I$jHY_Jlfy!oIgiqw`_h5IVe(bYVDH#lb%&iwJO|& z<~H?qp!c6n@7m6i*AcQ`2TkQux1CrDHP5*4d=_sRgbhRfG4$KbgI$ zVL(JGjgu?A>_YOy;^N}wAKXnJGVem>_6EAD1ILp)&;6gSF|F2ww>4JRI*123TKDb$a4r!B`4Df&V+wp1s}|u>jvUve5y2 zott8QXNn{Jp66yOT`Y8S%B3?e&p+UM$-v6(F>y`p<~j1=BJfvlIH<76N8f$-2q-L+ z&gg~CX>;fbkOT5+I3m>^G3vCm&z{jp+Zs#A-cRT~Pwaa*D#Dc{{%t(aJ9r>~d z0?cP1vvF`q%?vxP=1;j)*ay{Gx%A7O_GtHjYL#8$zOVUa#RJxM*uyDB^n?53Xn4`U zzw6!Q;85z5w~s&)+=JELoZAo!Wro00@2y3b%Op6qHfuMRJvPSZ+Cs+5)6<4$Y%gKm zy1w$KcLkeG;HVp9kl#&jlF=;Bh-Mmd``=j~xID7~xyiN{d(c4lQ3SPa~~q?sw$Z}p0eLLDI?=gJJg@}a#7#q2#At!(c1XIkI*is$hbK}N zcq(I1+ZAl~qn<*Rx`Jb>69#XbFuIPK?nXk>L#-}7t=U>`X4P&@bZ>SoU(wO8tJ$xqi|Pn}{`6{TJ2;S1#`Bco zlP;$={~e?gQ0j~A?VTu2-N%Y5ywN`Hr)1Z1n6XflF#e}Om9*4~YI~v*bIO_ElCcBv zi>03bEySbL58$3)9(-TMsL)J_zD=0&;zFGwCn`gCc=eg~hHL^v6#OVW*jmQY;Jj;} zQl1$K=5BicZzj%#bcoskU4IYjwVW1EZiv^Pj=aQ2wg-~QQu z5+&3-5G~wHZTWb@{?)DZ;)o@&_4)|u8>}{$><}(x1V6iYe9}wsq2`4K))PCl#EE}$ zo{N7$hpa7Atj5oJA}%HvQ)}o#F6~C0^5M(std`{@0wV2X`Tj92N6SGZbK}l}FJ+ zTzqf$#G*Ix)IYj*GRWYC-|NvXmuB4RHjMzqxn5Eb&;#@ZHhCIJt$96O^+f6a}WVK5v zY8T*vv|_i@$p9LI4-^+hjPt*#NqG^FS{hn>7@7PiHpnH#IZ>3ax`eK!A_`ZM~<#s*|52c0X8`vf`9^YCC4NGj;=-HsvL80dJ z6%7mxBqZgo?LPAF^X}=^tSh{F=g03@O{{IW+gxHYp>z>dDc3m$C(Tb@!G3;|Q66b3 zpBL;O!_WltLu}c=bWTP$4x67W3AI&KRn_g1h61lHlAZyKFTbFmmE~FLN+>jB)1^93 zfu^PA=?gs1_onnRit@Pqn!%?&a(V3bv`My~&QItE7P#X~7N7eVz%)G>?Tc&uQBu=|jz7Ta1 zG(bd_xk|Kv2}w|TK$V~413-2%4tG^6#@XYl{Fdv*!hOTN33@j!7TPxdodzZpzxL+e z{-q`7`Ui+Bx)LWB3tL4!4kqXg6~ z!JvIcrjp^ymC&SNTK1{l{RU|Ka;*~4q9SbW_cPbUjsYRO#uz+}3AvtRdqi;n3P(L4 zvG{i6n~9$AGw@JzL`lRO!oHgXR7d{X$^Tf%md0p4@}=2k$sLK8m%kLPOdT$I13lJ6 zv2qJGwNBdfn7=?YYdL~Pk}T6q62ANvcrcpD)8eCRAgNLxMpYpyez}w8+&6{yg24Ek z=nZaNag?RwZCXev!V`kRk-fX@MWpA4H+Gy0YbB1l1 zrm6YE)h(kM2cw!{6RAFCDE*9I-!*gP>~2L8jtVdQNFqzr2q3W7H*%dsGiaJZonc%J zaA+{qb}Ow_5&BV-^WQ1*cW=d7%0b6Ed-03DX2!U~pN3+4ZXgJCdIJkb#4q zOOybCtDp5AOok8Y<7i`#RJRZEr+e)ljAr=ycX-i*Xn~*gO}9LmgE99}oSYeg`{OY> zkM|RHQ7t(x99{q(w9GB0X}pH#5p8b2?iF3#1c33f?fJT6aAszGVS2i2+J0$zskpPV(}j6< z2MUkyuRjqLw+A!%^3_;I2q;!fNeV6IREH=ILj%(**!zB1Z2#W=pPr$in#bTHY7Smm zm|1U_vYH(}LmATS&aCFL|Ggvs+VV!vyxHBI3O`Czk@m9Yi=~oeo91v_seC64Qe=pMM|DnqL>k6mzWX|DNx2VQ$g3R&70&sis9KxheFXH{*?&9{p+hpqXGwCBKG0?eY1 zeNH}-aGP~__nMFU^xgb#e&vKpk`=;kxJp-lt!@G1i9wD>6J1kv@r(k!I1c_^wLzRk zr35$WRn$MOf~G?OOMurmO*P;z4sqL?R7v&w2XUi(U_?WAZe_|f?UR5L>Op~qjI1IF z6?p@R#N@9pEcA3Y{gptV#3Q%nBNlAiB%)9pNIm382*5JWxq)MEx+-4XMUb0ms4i)2 z(Ql%CUisL0PeB8rq?77&y@8vKgx(J!F+5yfr+OakX!**Wgz^@x3gZ^oXDT;#`x{KJ z?keFQ%b4WKd<2h&sHkWLP|rx;=jXkwF1{jCXLXJZ)||-qMeh<@f88!;3=oNBmb{j{ z)S$NwW$EY4U;U)<&kN7Rc{7s6_4l4_dwlBFb-w{NZEKSs?Z^?SdVPS+&;R_&_DEw~ zjn9meYwzW?rpwJvp!&LQuAB*QF0wivh5xE9l<^PRjEhH~_?RuKeTu~EJ%{1#5SgYN z(Y$lK)bW-$Z)1OoCXDb9qm2VrmkS|}Andq(;6po_3L4AGV)71-tL*|`In8gFyE~i7 z&yB>;L7D*{5(=sligTW)G6VC3Ch-`hq9%{@ii|ph!Z<%Q)9AN-rLrh|jn5Iy2Kl#f za4iafwwK~jp)@}(M_^Y`4(^TW?jtIOS7{dUb^Y-~AkN{9&c+~0d{93-jo^Vg;8$%^ z`Y0(WMXjl>X_daU&JQrv6gDlQnHhqJgv(n`b|=Euy8V6JIF};~yM zS%byJ5M*cNzAnN((o@gW3}MR7g=-zJFR~h@;Vg=!ld`Xw?^N_^@iVz9xRcX!W6rZd z6RS@&ROB5IW|Zil7R`bqljV-!{{&Fg9+JFnolF|4xs;2PxI=Iz7!U41q;@*>u{-me zkU4MMTrx#sB;ykmt=tSj%Go#d?O-}d5i#1?C2IeQr1)sOel3Kqr_IapL1(XPGB@&7 zGHxJ2#_)NkeMa}MVk$Lnkf{3s8AF~h{-VC|Cjk1%*YhZZC(Mme2+3`&3YqumqB1Hc zebe-Ns{U(KPLYUixuA{^D^YF<;u64AJr}eMUy?9ckTHSy8+%hH)p>-Q-dIg}fB;;t z+gWGh+*OqWi=QVS%vha0M*8GjTT3Z6)gg!*K1&h>KDLyFTdCn_gB`ElOd_B2E3RW_ z9q>aYS>s&iB-qFk3cOs(=nQwf+%S%lJjgeG~vInSVZY67v?(3Qw*R}fk zHJvvI0WPF~9QQxx{vG<0EUA9xOeMtu+`j!*My3;uv9wbpXohl$v^uH#4e_=DN~w%N zsP3z{w`OmvtpBO8rWgI>6_OJjy3Y$ZB2hj~G^RRmurT;)iu$vBS^d`_IDaF$bOw)F zE1mRyZ&TjL&H$>pB5C_1hrwUvu$N(t-O(EMpy=H+SqRn2)-Dl^i@PbC?^jA}RMOl> z4%Uqmh1fb{NaSZmt zXYHsQ(>D^AYpGq{@7FhITN^O`(F$1x#(SVeYUPRu2m$}CuRo)q0i&20l>NnAHUE|! zh!|5-lA+u7K6bajoX!RF!+e#4_pAgh)54d!2Kp)*!a~m2%84MiL*H-RuN_N-V_Kgo ztwBS>rlx`|E~5+?Dk&t!t%Qw$&%&PIXU&f}UrD&4A;Tk(Y&Pws4_b1iV-FN1@oIFn zJOwWN<8KARauZQz6*OF;qCv9FtqdpEIvOrZGg#?S#T&+2EeJ!xTxzLehfgTrG5B9s zrc84X+N-1Qh5s@5{wU9mm-GAH%x@~$sR&Ne>*^X@v6}H}nLt#Zt%SMXOQLg-bCsn> zKu}gYxOjK8eX>kIR8f}0BK(7Q!}4n%0m{7Q{VoF@9C!qRG&pTPiGk)@(np^@ z`RdxxK`E~N0!g0+Y$GyXsna!qhvjQY?tiV4zL%tiALT?M&LN=@BPEAN89YIms;7t0 z+r562Tn7l}aGB_!@ zKL6)IoC70@l~d-%n4u0Y!x!lNt?f6hrsigP#u2;%3B>6+lp)It$dk#x?*)CM_zhHX z#pH-pQ94uhI_h_Z^W$dy&7;S=#HZ+7RR3o)ps8q4wFlL2b?~04hYXS=oRaa|gy(BeOag*}5m=C3P)YB$;6IL){U~!{p@5NA13qr7iS&L#4ocI+!ELs+ zbw`WLg=EccrUk=F{nJj)D|{PD-I>bLokzIrtPf{tfeqsF*1`t8JFVbJ9#;$ZI6M-v zoD}dI{>NqNgO^rS;cfMgyL+MKF1_<(uiU6*%oB*gs>PPWhY!!P&(H}hvU(>PT$GLB zU#-9)<^auTF^ij^x4va8`|lj3fBUeo*3{ep_TL{g+U5AM^~HPDRvYW9?$>q$VXuco ztXxQ8MpO*nJBz&gZ9w&Ute)~+6WJ7!w5uX-@6FT4rACHaE{k3zcNXDt$UZ*D}))nk)T zx`@YnN7P4QNPX_NB0kE_@LZN*zk922{xwa_d+9Zu@flvC=i+i@x>>n08SnhRDIhM% za(+EnS}&!xUl(j(QVJOFYt{qpmMUkgZrR$_;zQlbjTIn%9f9zCW`K8&txXP7ru>Wsr7S zCw_i!&rmjT%P72ci`Gzm(vBpa>uRcG-8?cA8foRmuY07vLM~6{6vT(?%8t->V^HwY z5BnX?78&P>J1V&1gB)>@v5l2}1k@~VjF~DtY{rN$?kcgG7rdSW;yWS-jCqpz&?sN3%jEa;t-km9i zA7$PTmYhYHrrt!H_!L{lc$%LftbDgL@B9tN#A<>WGKXCTkEualjl(fE`ceCejCeQ{ z40lAT34yyWXn>8rim;;wAU>jADogEaP`|gJ^x{%sasTw?&Be=Al&C%QOv>sCiw^E2 zp(+<|DbXc0nyW!CY$2Pm|C%)1%xettxx3$rnx=9UfZ7CS6SW-2CJ zX_r6=6kwf=fdhLiCa7K>2vXX5-f9Xz0T*1xL4_Bv+h+lH@183;svTYCvh&Pt_+>TTB4b7JI6&y1Xeqf&4oY9iuD<7Bwm zApESAaV~`WTV2}g?a|X`5n2dF7z9Cd6%IgLW#)B79CxAmk&!blq129=*@@Q##iVRa zXQH28M0l_>p$B^(rIwF&aJl%k_oj)$UXF7h*_>Ta#(t6oIJ7l^XFJk zKFhvxc>4_isUy(FU)*0w7qg2pQvSmR40R_E*1~HCRsF&$G1mB`htgj83yw? zvkl54(>IVU1_+S#9^n#7IKmV;=hTweiO@IF!OZyl^rRpE~TV($)L-=jNj;q}&?^8REg;XNXI9Q@2|K z;5@znhq&z*9(rh_jgcvl{+_rG)LT5{d}A(wGKQ4N)l$D?N$LjXLZzB9T>Oxg%O@Is zj&nrlK5@eLQq$8xBBEVG*(QsvZEUWuiy-EJF+F&XqJkT)BCSmM-YuD3-TeB^HA|5! zd$d1C0$nIkL8`%pc!h6zZ2Yp_SS-{Y{=?1_wft0EL?YgBqfcHm9`qZYTzOy?Z|@xt zK(~8I;Ax4~ffjk`p{4T*U=nPeXK1fXxnz5vT+p;F9~es0>ByCNb**!u(d%}~^tS1oV0WcnMY z?sDVO@B1vdZ)|Kmbi-4dZz0f261g(n_AE&r096Tj=lu^0MdeQoJ9nxLSP2=xz*W2+ zB34kXJ?QA`6~4UM<<_zS;_;dCtuESXpY~d%M0YjCH5r|c0n_fJ_Y0}dz$(~Q$99~F zRaCieM;KuE4fq+DYQn*m;bC*~5wMH?Y#retN8md7K8cqHm7ZmW{W{aQ_Un4IwfV`~ z*qW4@{YPIaotH*zA+%BVui()VyBs){M*3MQGcPI~p zER8fW$@DDy?6b^9!;Ut#Wt1EQMT}(sGY=%#(LJ1|k zqHMHzi@6~rf$BI`s;vK=&3Q472&E)9>Rny9I=ifzNim~X9QAx-C}6@CYI($PHVdz{I-@J z($pRI2g@aw(@->>PMy71^LQx3+JP>Y zG?1KJ7>vH#&XUBB2#jxK!yt`HyGQxRQe)SZ9eVW%eTJb%M?}@Qt~T`>iir(B97Ae& z`iJildEV^|0gFl&d`Gp{0yaw{Zn~Yw4_#efxpPVfeG^Vvju{+?P?{0i*4o;@{ydNC zbOCcs9I1AMJmjmnyVbLP_!P;4;U{Q7fYgDqXi~JejQ^QD-@b3AqgQpSll@{Yn*3iD zfS6D-+fn5E!IHc3o*zBfq)4!xTKnq+od=I5hM*lvC z<_cjM6cZ;U${A{eEbWj~1ACfM2+J}}KjU4BkUV$3e0kaOGC#{ZRwOQzFLQrXt;vqk zvp3{OmS(dHa*66K=9XotojD9=*87%MPf7foZ(g0Yko|{CC$%7qW^T^GA&Guwt}L2J zE-!!Ee%RBhXtIBaQQqkMw5-Eh^PmpCpbzZ7t>Qd+khX71QaGOQQR6uNEoGODXOQ1! zrbk4rdj~u=`EW2dJmNB(@T^cr(3A|OG+6w3*$~ZMBqVg!v&D{qSCeREuPdMnTa?dt zZXX^6|Ll{>jL{GK-!b2mMQl{Jhg1fk1M5Rs>j^HG4k1jn|0`f9kcNifQi|Bj-VC?- z^>Lh_$o>cR3jpEOJ+E@mp0HLnp1~hx`|H66f)8IaUcm9` zDNrb_Yk~rfte%S)sG)B0oyDll?QpXmt_nx%#(C7%dq0j_Klt&xhBS2e>{ZfnDu+PmqOll8&!{$B zKAgvexhB}Qxw+|Hn@98}%jWB#X8aBMfb~eakt{jTnZ6P_;%D8bG;@Jy<*4pdIdu)Y z9fV51$kLQ1masGrC;qRYuZ(|ur9pdWsyS+~pF__pKk)0O^w6fF4($+Qur?W4%Rt#mEJKrdr`<6V&UX+O9=I z2lY^^7ie1-vb8pTXsGh;JG~pDL|Vi`1Y_<(_*^6GhNt?vQ&m+F9~v7CCf2g(nGJzn zUS3a}2Bm0lJJbqX3{=Yc@g5TI{MvQ@HrU_->@#%m`PcBh>HV|5r>IYl+5@g*DloLF zxiEHfbu4#eGGS`5Uz*>aVUl{ZTr+5$+#OLvb^jMx1wJHK;i z?B+ZORK`^j+~AOt)E_sXYv5jce8E}-pGD`vpa83YfRr&KZ6)*(swlngkOtCTT=Vuh z>uV-``ld?YfduuGI2aMQ5#soc3PIiNw`9V*=;$Nl_q}z;E-*w$f7fVRS`yo+w}du{ zZlBnf#0nf0>ZbZGLeCEb=9t*}ALsRJJGsOO5}H+z<5xr=IEa$4u;&^tx|iW6$`;21GJ;3! z$65S2br(h*>A5aJH61)R1vpvy_!KeB;5e)8b3#o~`?wdabNv844f40WoXxI7I(()g=K)ZX;Ujz0@m@L|Z$|j;{IuQvgTf3oSmUz- zr?E(4`*@9eYBBXgQd(JQQB2@wO&Q{x?MEU4Sxv#pBF^#|!*Zm80 zR&sio9zL+CoajI>mK|4v39>8)guEOtQfs!?TtfJ8^QV@npv85zl)@voA5dmk_yuor zWrk`pFG>lH2c;bwgc(6)rO(AXHiGto{*Z>K-cS%tDlRw~?{G?V2Sc-?K4*YzXewE4 zhz_y`$-==0nATTA{}8^)8F$tkM!Ck^KYa`>T*!0ej!(#$baGJ<_`Gn^1B}_=6umfc z-wXlF^GeXf%FIn$KampPI)EMzDLI*73IslDRb1ca0%o;}Yw{QRo}-XZAv)EEvfC;P zxw&J#(P;%QOk5%*^gn~C`goG)4#)dGICD_B^30P4Xlg-08t30s??mUjS`jA;iUjbi z!5``_r5o#j5ea6LLQK*lf^n1Cyf)I(qLWs@Y+C!{{!C2t&sJi@c!1XCTwd;LSdmXI z_%F3btV=ic;^a9#ePkid+G%E;*n6%OA1W{dR{z(~05^I2nCFDni6W2P|yyxgXH6_BYJo zMFyCQ`1KD$S+S_GC?3p0=n*`Etb;u4ZRpDTKj3cOFv`md{jiW-zH zAZS1e&^aA{u+Qqs825pD4A^etZBsmsGwHPTUtJ5oel7c>V*sD_C`UD2*F&!;Mk*r|zT)0Ib}f zg=7_$&TE$c4=GgSb`vYprq8znG1`-76y-&jUs$fWJ1t|(fyYt(t*@K^1B*$mgNZ2M zlI+)w&m9FDsEP1Yy}yzuf9nVJq;WVnATcd}+ddnco5Qw`FjN+{@Ec>+q24N7OIG|d zEcXmIa13V?wA4?RE~KqeYHhL_CvItmtp-&e7nb_5|I2%N2LFyV64VgdUAq zpSo|%tHy?wT0c8H?%4ACt4b7W%Gb>NsC|alBb0rH)hzI~Gj>|0+Qm@|KG#y2>rch* zd8Eo`XLFg}P(FcIxZsc{*!JD>_*x6Afjtt!Jk&hj)yX*Sh+yldISqfk5N8uK`!IEN zV#T=cn~628KA^UY0VEe>N3s$wU5Zx^G0bk>YLr=^ZH?xcG}ZsxFio^9qYQD99|-9i zr!|EJX}vHZcc0`-dSs=JpojkaTsAeWvCt6R*tRi##$J4(f3`K2f2hE+^g5E$O~>*Y z-@iJ?xpRd6&hc-?MqoLjC}_9M2q+35kA7pF<@zZeQ3_!#nO*r+$|S397UZZAaq!3f zwj#W%KHxYJ`P58N7j=&JDxiR1Aq0ogRM0Va!R1w2okfR^rlN(}4p@%5ro!DBT0n`0 zM=tW{A{~GDmwLgBteX{|OEeS{83|e#f@&0dYwZmCk9)w*$VfYgo$%=L>cp5@n@{>% z&#FMxsCHbEdT&7|eYh;<`FRknJ?{zso!*p3JcnGh|2uNC+}7GQ=;Ccln2^lR21Km< zaZfigef4S=#rTbX&`5RWoSGy4lx8M*=2=Dx)^je~+tQ<3{^B2jnKq;|LF z$|OUV6)PJp{?#fZ%Z2c{;vRYz^5?{SkrFoaUWpF9Xf)=d^Dl*wIVRk?S>h>Nnc3v`&J{4Zn(u5@;u+|Cc%Yr*tc zXN^oVxK6jp5ine;+qPH2QGvGhCx9Rld73&)VTIylrPO#^ZHnYNJ94Kd-wp!Q3yHBi zp`(u!a4|L?h#Q@p#c7C!y>YwA`Q+u7aZb+f7lIlGM@lHPP)1jh_Nw?|81JxyO68Cl zc479C@P30gr(&*LQXsRcEn4poF-X9EGj?;H$-c~^t225tFT?LX^H5$XpgKtEj^C_m zElV@}nxw@eQ$D|9)U{=vfpSSF;}8r@0r}u!LRDgY{`dQ&7uu8rxtBbT@U@%Iu3wL< z@FmK^2Cx>glHawzKZ{=P^?ncifM9xNfC6c}=e10{41|CLNNRIH5;@ipTs`=wW4fof zd}I2$SkqcD|1z7ODMB;gqRDv(=UG!d7ETCpL?Vvde!7U>v(xB9i(LET5zcPkT1cu=zKD!_JbDW_ zq08z%hM${U@N)9qP@Qa^iS1$03+w zdB%c9Z07LV-`2||@1jLYyb+u+ZxjpU;&EA5TOPDmno{_qDF^K}&dY}KOJpz?X8m1C zTDgwD0ejcfr#sOC+Y08h-G^dESem7N=v@Fd&7!N*iQnQBW+N4)E;;;;G}~=|rz#n% z?hSH>Y$}H;$AB)Ee(}I5jvRP#gW14 zGWk*|JW$sFZKgE7zwTJElF8-Emzg4>po&;J{3-BV#1)IDW_QuMwuhtJG_GhxcdANf zMVIpqgiO4HCK-hwR4O20K!T15qjBquu4&;t8*MJgvX_@(-4`vLB(^i_Uu&CZPC}YQK$ty6>_wS0dSog2fWZA+J#u=<^A<<_y;uCr$Tn01)Ktty|his9dPQF*H6ML1s zdj~Ja_cD(ZH9k$#r;~Sx%Nq&@6B7z3q&aaI?9l!pzGKYRG1so!hT%Ls<`-t}HCiPZ z=E3lgXqFZx+l8k?$xg0w-_h7&#-7W6JsLM^#7GS5%^ss{>s!{t^;@1Q>5jSutQS5i zyyIK*M%ud1_3gPL%{Ro+CV4WWUxegL`oLJ%yr8<-Z`;V~tSiHC-52AFzD1|b-_CFz zoLu?`G%YE#cCwRk?o%5NiWwHlA_q9dL%WZamh26)J+y0fR(+S`2lUvIoURKRmiV7S6T`hXh+Zw zlVCN|hQH(XiufEA_f@K!sU4_~J`)!7?sKhc+Fmm$uNj^g0Z*$X+>VS)@PF^F?#U9f z;(qF9(0?OxsOctf@zA6@=GT!?awf>5mmeK~_Zs6489zQ>96e~{q&(W`1E-rD*GpzS zz)U&pbO|o|aRkaP#Fc@>2On+>u=UIbAR^$Y%}W`Y57ZP+O0fQ!VUkiMw?~$n24f_cA2S_^`5{zCi^qT#|zvQIbjF;j=2`)QwpP9;$vJEOci-|K#l&KEUsv1 zfA03#3`*Yzxmtey{3)Fs>Hun}Js5aRxu>Foy5m+wp$zrh`Nj@=M?LCwD*Ynt_l)v- z+-qAQj=;e+tbq42Bjyu(S(*gJd?jQQoRZZZ)i<&6uNepTdx!Z2vB^DO0|=)a_d*5n zRkal4PuH4M!6`M9QQy=wLZe+6|2;PLgT2w%7}nCZ(zX+SC9sLUR{43RuUiXPb(!)9 zh$vt}Oauq%p@;9)@{69;2n#xxZ!Bn_NAqyM?wUd9D=9sMe^~YB_wTo(+a`Gu6a`2(@^$~Tv1;+Gyjq^ zmu5j)PI}(vaM?91%*VR+g#LNqy%CFf+COG%ER!kbeqKSYaMZTNzM1#{1X1BpE=NAy ziAWe7WsXXiT*bbI_{@>~Pbf7yq)wZJVw%i$->|FVKrF*L=wXjxASZwfUJ;kWJW5Y= zo-$5`RuCKjDkyN^K?;~*+q^_#Fy|DElXGS2%8sX7VP!Qm602l#7nD4yWI2p6_e^n=oF_|0^MED&rJI?QK_p{H06Dk`~x9pxLCJ z{N+Qs5vQ#CuUL$i$}za%W_gmc!#9=YcIZ5S$q+Z@SaDHG-JhX*N(U3$7cO9D<12~| zA)ffTKQ?pQt4Ja7wgPn~C9ky=#)z8T0(iP1JhJXF$H^}!q#O#fv zaZFAvMZ*z4N*r~lWx0tPuj)S;%gZuX^(2^C6KMwP3}e5y&Jxu6a8&(eI2X^_$M{~*NLo+XrV$E zYwDv4{Jx2`ra8_0S8z(92k91J9_4~|)svLg6?|m!obdjPL%0cr+j*w@+CYpB$L2^= zjoo@MQww2Vx@<$py;FV5*?3|_Vlm9+skGYoz3UbxRE+K`e*{K8j+DZ)2T#;Xef8|w z_0CCnwWhGcx>*lULul?uCV<;3z6)@UgpPN0cJBH3uTnut`ep5i8Y|pK83)2FQ>+RX zt+?4HKO&qY4a8?(!I%uiJ16dcy|Yw3U~?f^|IMG4=vZrN=;jKYYkxPJoy3=YHq7E_ zzR<2hy31U|M&VX>CH-=WlBroKr8tMl5gA51<0gP1ptvzHj}=I=)!3=~46d_bMGuG$cJQDtblKLGiY}Y}yy|lSPNWj=xF; znCqa(M(E}feg2S#$7^9uav7?w99)e=>j4a5x~4l}p=Vqg#GVwYTvu9wJ<+Nd#hJr= zlf&L=`^5!!mDU`xzCA608$v)~g2A9~eVzM|e`A-2`!leJCyLLNpOjzz#e(*Nb+*@cHI^S_Tsa#&ZVB9OqqqGN#<#8oD{04k}-sFZgNkPiH z{(T%qJOUX5=7$5rQ}b6;#1h+API|1_1m-eBeg+Y~I@Iph{p58IR=a`*7&!jEWokej zwSx`2FolnCV~`hAgzZ|Ho8c5pAU=FxC*;DyI9xm*)D=;(Lh#=17DlV3jQsc^a`prngu5;Ku79pBwc>URcJ$g3=mNC>CNUqweowro+>r?TgiVmyaT_vll ziY7+BGibVyr^Xv)sCxQs!+!F#(1IC<#2U7;o;IeQ#oRg7Q6cF-IQRR{kH(N-?=eK~t%in%OGb|Q zT^<|#VhFdavtf6uR>l&93{2G!@R4X}Y>ut?Ts)uVjQGGx@M-ybPfIk(C_8lh4RT%K z5`@${E8bfJpL-I7zZfoa%aM_hKTPIn-OeJ^j|;h99Ye$FZxeOt;cEfmhjyrCc9oTv zZ?4O4uJ??$Llchpu0qae+^c*-s{7~GV$#-wYrPV22qN}rTlrEeB60^x0(lsLJcn1z z!|UA1|AcTLOp3D)B;>V5SIB+)%C-g_PD#&-f2)i+#0?gv9p3$&Yvqr%2N@AS;kTPR z3cQ4Ob!Dvzk^qdUp;`kR>?0#Rz5i~%U#8-(+VHH)l2%h`>87`NV0IWA`UQPdHU-#V-Y78|dn zne7tr{-BKW$kapj`#ENqRFsq*EACg|bxk8AbKTex8RoeK*FYzuxB&XEy&BUy&0GnQ zBG*O}nwSEfBy_Q$3q%_OG8LVbvTnqY<>kdRL*F(u?T&sa=a1$0ycOwrscuuRJ&V(J0VM3L!Ct+4sbfjMSiu~gZO~1#f1b028M(r zKmr;KamW^Q0IrYN<_qVR3c2EME|e~80`)Q^y-f;9LkjUFP*YjL`iHfLUB+6fDC^3YB*bu9?d zKVoY1@cGUF8ax16qZ{S3v`mu!PId}aFrQkGhGei{0@j)O99ocgQ|{M?!5pzyB4~OP zm>cjYQxRr-CdAi={lc^t(e@{~^1rd7#20O{vRqt2XF1O;wz*sH2RpMzYH<6z zQzVaGyr)79tvz168=)`ThW5HtDR(x=YqvuD*tH`0sU-+AbtP7lEtBAkkgG637&)tP zF*&flE4^s(Ju-UKE@EqgwvB13-|- zTw{xA{l{8|aV=nZa4Ga4?Zx4j`sk*4QaVVtR-3neU(WCmrKeM=l8NGP%`IOy`H|24 z4(+b@@$_Yn?0AFA$Ty%`(?&+*JfO^)gSKRp?BzO*-Pr`g-lLKGG_o!dd-0E9w~D(j zvg>D1I9j+g)*gY{yJ45Ocm0ZN_24}@Ps9fsaQ;NbDPWPVbvClNQe54E{bh-+)HFMS zfaZ5vdUpYJY4;J&tv|y`CLSJT3!2Zc!rU*!ZqU<;rq|qwPFX0jRbIcZ=3U0F8+0C< zf&0!Dq5qc!@atRp#$OZku2!3d^Xc9nMm>il_>pzwktZS>znKZ|uuH~YQl4~IO~06_ zNJP2Z8}Q43^Q!hD3IH8_)ulZYQmRwwLc(d{m+oqbpk5~JzGvh8o;2NpopXH)2*U-iNHpBdtC8(dk{f% zdMKdet)`{+mO?N*;`jwriyrRoaBIi^ZHn;nnx7f0RHcPpm2C?vzt_?5eaUuubv$pp zu8aqxCx7Yyd8qi*yfK1=rs#I(KQa!|@ z%AVjxzNp_bGc&aHM%u<)G{0t2XHIitqe-u1SB24Ko0ZYLB(0V8H**_5vv7H!UrFD}6nR462t z8#jb4*5~5*K+#u=W7Ee7AB&DPZw|TT zDOKvhgzDf#aM#1yFV(#JLX@b@ssWsxTV_&J0e@~;wPLA8WEl-Jvw_ymIPYD92R~~(=?#b zOQEX*hMzT<=bj|g+vfRY)&8$xn}c-ZhrGOKhyO>@x%e~P|NnoYOu1Mt)j|$MO(`Qe z<&Y(1rJ@k!l;k*aK2t2jP)y44il`h5qs%dxP!oz+4k44}I1F?6J^TD_-#_5GZe;Jh zU$5u$@wng3GqS8Oh`8!_+>pz^EzeH$XhcirWE^NCze%^U`1a53j8ja3hjMdG{KE5# z`LA5Y5RG6BST)Avxp5QjL}4Y#^KUPq=g5R8OrMNPi*!Q=-fE;`wz zW=BYN=70JN0=QGa!x9dMt|@$Zb~;@JR^3cwOF2oD6No@(!Df4GT+%0UEWtzP-xxu*>8uEn9(6$NKgbb>6v>JFUjW_O8EO8 z7r%r#2-42_iqBHoLC+mF)i!%PHpezsySbd1(Ah#xw~7+|;&>cKcXfGn+)wN2OJ?RN%a6i%+$yu+k7dMKaJXsl39!{`m<+(>hrtf8cK$nx()+53^j z-lvBSAd=NfCRZuuHUnS%=rrsZ}1{JBLBOE)mV=S_WfS)cz?P>|N=rVCI* zPJU_KYX3^#%3z}%FaoA^$1>{K?VRw%pZr4qxv5NZ8}%jvtpOs@dG1dA?|uNi@|nDX z;t%u3&!5l8r%fM|he3Qjnj2|6#!UYfqRQ%@{`K1##b^0H!e9pKrcU+?iztELtL|D^ z2{z%iSUx*yn1~H3KOMLsZ(%-KO{Vz3iJW7 z3d>S8W~zBK7}PikL*bje=k9b@+GX6b=vi97oqpX>em^(474sR3V<`SQiFl?|;xbt> z6DduCnEYu|Qxk@s;nc%Q+MX;5&9YWE+c@Ium*e<*o$FteNxU!{a$;eb#%ShBrK|V> z(Ws^>|Zq5yXS?ou^ZBi z8@Do-c`~%S$6+f;sb9q?S+@1RZ$Z>IsDOJzi`rWPbTVNrj<9qc;^?j~TsfxCP=WT{ zyPkf|dUeT4suquoLVFjS0zQfr34~6P{sKwKS55>ZyhRKnK%W8ucM;m}iGUE(x_d zKc+8#l+WBmEUzVb?#q(D)Q{`OQVYM$Q(6+W^pe%TcwH-YPr_*G)N$ZBTp#Cb&TlS7 z>kf`nqlL4v$B^zA2UJcjyoOYK5hgMlow^&@`w*nyJ*mAnka*{T3i>?^o;LbMxunGP zLM!&;=b(6{uyxl`Z#w%k;8OMvxuL$caM?ra14DtEnH+Q;YjHJLcR9@Jt5vtEkv+-6 zLrr(NQFugFBXni{SF6CC|J=nDXCeMu9-S!FSP!wvI=>zbS2*CLZA3! zlX#K%EdR12SJ}Yy7aJ|I_0Ol_dpDmXd+Z5WiaZjgc-eKZZ3oBST~w4c=>;>S3vw0u)j3ZWg{jpt_do;aFY!P1n`Pm}d}D1>kj z-2a@#1wck!3;GJ4QF%1>y+-uTE}E<%PW~6^VBNXV%SYBXxHG%X^l|p>xk+}2Yrd%^ z=~~Q#h-)61pI27&Q`w$XGe34ncf}B`k7{Uk6UsPwQo9AM8@LRp!A~yTmBn4#_lwFI zYPQYatm<=L$H=KAk{=4JOeT8vBASrJqj#XYxG zZI;7c52TPy2tTlbS3ww8SRfXq_fI6{;Di07PPM_1(^%Pu-Uj)eTi{4h>S4a3TJJqG z-P-z~D@Zx3!YWSwP0uRi@H{;OpQhed9S;iR-DGS|3RmY7s5A>{t&8&BJz!;|(Z%d< zB+>9L_7!h-@Bi)-59&yvOx~Uq_)inyu8d<WR)v~d6o z^nHCHGbWSNy6-k#XqcWZ2iP^Lk{UO5>)mxn~}pZvvFzwXe?dt6nx=x0x&7##9kR)d&d zZE<`4;XHEIjJQ4Gec@t|)>Ee)7wOhvb0hb+N#jKvimtY4A~JXEJ&kYiynuaF(1HqW z)i{gJC2zBPS>Xv&f~T|o4g|<6ANBBH6^O-m)y*IcMpbrZ%cB zo=KqqWVWT}8hi>1ziro>5a{5nhdm^2r=4M_5>bx(o)K+x$cI_gMdC5?`s#QQ-59!c z9THdbpbqan<_6obZ$iB6z1Yc$qY=rG~3daHb;>< z!6%G_o3KOcVXN$#^{-Dgjyv9V+>uJHIQK}|(9jm$dNUR!i%hz-^3UqdmH(uXBf@?U zN4~#~;Cu6Eiy=?Ohy8MAcN==2@p>2Pf194My7VHI>iD+z+f*GN4>H6?FkxI9fyzbt$`oyI7 z$1yw3Iv)g?_Im6ay5@@t1L9%1cw@^W{0(r7laO>@y1s0)zGqW=+kY%ek|Bx@X6$!o zf{}JKCkr#@w3?8>2dK&DdqFiUepeDR5Q*y;)v*uly=_4gFf}OZ7mlAB*-GU0R{0Zj zF$7GWF?x-5a)#`%b8DDrv*E`myHiiD`qnBI=5}*+0e4NgL5N{yW@h&iUXVVw;{4bK(Z6?(9&l7R z{XJLEG8*+k(A?^z;OXIDG*FL;D3bA*Z7*2i2S=?f%p8TKcAK^$%0MQ1UtnpyfgOs2 zA*90j7(?9{I~0d5=`(fN^d#w@yzd;X2+!d_AjfXE(W*a%!jA8glG225QlRmVA0;^| z=SQ9^9ErKZ@H0#rKf?p(_B)C4M|Vb$I`f@(p7P8P!4Uz=lcOk~2Y)^ilHUN-sw-@ERXM#Vn_sp}TE=~yY9!lF_d0|2HR1C_6aqNLT#L8}!TRU28%h1-k zhCt}7&gO!ewul1dzYT^>O?Xfk{qJCoHu}Tjq-5f~$c#6abT*bJh94Shrhgv6gl(G7 zoPULM3>)^h@(&4-IMbQ9F@M%M4PxoSLQ!_e_YVPS*=4C%Rai13PqRbqXKB&2@WqhR z<^$%fiJz}`W_(#CD-tu&Jlh6!ilIfgJCV^*?i0D#Ee)R?z5iz7B)ap9(n_>7bxP93 zPQ5H%)auY^!T8dgUX4kk0ZS%Vt-hUFd4`V{s2Au1Z7<<6V!8z>e`aWPT#cgIa_A7i z{MOcO>V{OHRJki}@s?I=*~0vDv{cA~v0_xKiuacy zwL&e$go_t-H%Ioajc%?SIvEzuY2R9&n125gvxEjwmEMFAn>_Y)nTuNu+tidYIg)e1Ye*%Fe^oo`kgB+5$4k!wt@`dXWPV%G-* zzUlk5tsyu0-&g8v4Rc`niT;vD8P>UF7ZU|C;LuJi;j_@iI#&nl%T@<%)7yo5hr7G*5s8|N4LTi6aUboQMa`&j(5X{{GL>RB+Srw zdxGjNVJ{}}@x%!9F}dl~T^wFoDBfB3WpxR!ZkGWEhr&OB*K6pI^U=Jo<*jb@inLLs zJfG#H8Lm|?7#7)bv}-Vxw;vKttL(N6l;lS^74P&h!N+2mH=GTz02F=EUHvNabd1S? zZ*HpGHFk##vHUmD`*!g?q2(;|G3t7l)R|6~D&6q)cqkM@xfL>t%nV289vDS|@|~F| zL-aMx&W532@+DUOHpub=z6l2bG!fhrho>fojk+W~;@{IW9MW%8=mCb%HQa^Pra zTL>+MjQ(k!gE29HB83lGkMsnn)Z7rM76IlbjjBF3^--%KseO_{;QqX8<{gnH9tBI$9~t0mKy4}$+bDC zIZWn9eYD-C%J>{s&xyE0{rppR8H`JgqUtZ=J1zfrL1tlKRe^s6Yj_}+#-Qvz?Z7!g zwvVlaL;CfwYp4uymFy< ziZ?`C$Ik&;OYeI9i)Vt%=fI_jS&%>Yx0AkFSIBs_Pxjf>lm1l}Ts@~E3jKtsuX?&9 zJ^$2^5eYB92{Fa7-I|1-{|P?-p%>y^b-1l5TbCptU z)pb_I)p|}WqDiaMO`iW?Mt!|EC|zH}m2Pl#G3bQW^l{wj!hxfNH-dsLs1&O3VQ8 zR4}Xm-9MnJhH!e71!S_3<{c4A_A1B_`qPQ%)_|IU5)E)SFCHsh)xmcIWh^j3$-Mxa ze#UrKbtN7;&&!)Ddp0?0b#w7r9Wn;K-Dt79mwZTvQ>0WTMN)0Jc668A2dB@W_3kdDx&LHk^j&xW;NQpzU6qq}7~(jmZ3ka3 z{CqRPM^lbp6jE+izH1B2IT78E0O0b1hH@-}LGVA_tF0M)ZTw8{3Ca6C6PSwV-2z%2(udOra$jwY;+mD-x+kP1k7 zhz~#e*;H9&7zN4S_o}^&n;Z!9IQqKhmW504-WRXXnjMiAA|c$Fjh;hNVJZ~^>PGh{ zlAQT=YzcnlSpnw5pK2jY?xk^vdTWG^Di;f>mIN(T8 z)jWSC&lgSf?RFyY=))aMGkt4acvTIIX#4lvhjCgVnNB-ERJ!}o@~pMpS25<-hr}!q z$QYTt3aMA4WoQSywkSQDyA$`8AWpab>0nVN9YG9RYdwVimw(ntWwQU7yO@It=Pj@1 z=dMafsV#Kove*4!YxFc9TBJmjjDD|g7V|TcZHGqT^iUztl!vG1TDt60rG5=+pBt8D z@wn)5yE>AG54FXSAOe`>d;+4O|DCd8-RcqplIg_ZN@sGCr^G%f$z$Vju(9yyl7**s zs#&>1SV%aN5@>uGmsSnY0(|mwh4Tr{s3`6L9ZVxp$Q09+`T1WynoVdpL7oTDV%o(+ z{QUgX0i6yG7?{1@x%HblLALed-b*9sYw65DQ}V_1$VgtG$obS-+vD2`L~h26ymf_o zutWVe_!b5HP*Bk7pT6Vx->#+FeeV7+X^4p~$-Zz1ftd6}{AAdKrrWMn>23zr4cQZ; zOD-kDno8w?ey_SMll|^ttjYMw;BD%=x_3GnI;*R__131%nDc4*bpac&#+e@;lK?#b z;0#A{l;n+%;gvSJBA0jduwZ1q^Lva!yV#Y3l;3$bvuvtNPQHjgQfMhZ;D3~PLukFV z^AV*B?HLp_KQ?zj@MmMl(uQJKC$Q#1-V9AOVME{_VXA8AH?^eTFwu=1KsLsmGd)2x zS+?0s-Tdgdu*;qV$?vfY@hBO=)9?qoRcp-*d0py;&M7Llgnk&VHc-xCb*Urlwwr&c!y+ z5(x?d#aLRt$@V-x+FMNQx6cE;b*l+ohZR|Kx3(bHM^@q#&ac)TH)zpo5SZ>yyNS%$ z)pQE|&wD=G{glrB-KJNro{&}FKEm(Fp;r3RkIqc@m$bve{xqS2_lt0ZV~35CJu+7a z5ff86zKc*)-Y}ZwEp3!jt&o+G?Hxg_?8Gtov^D+`Oe(R#Q$qEUE5Acp_<(R+G@z|i2AK%{^6tGnjp z8doOa(5KT8?+M@if1H#J%dg@G{4#s0Arq%1D0uZW`p(}d$PBjt18bfa$&etmWKH>r zN7+d_gCk%jEszuR2F2RwG!;%ui=9Z zVrDQwfIuPakXg`D>|o0p_Ls2NQTF=C5|)_#pJ2CIYyKZiX#RV>zE&b<@$!U!atDK| z*n9oy@dmjiEXgcw1VY`hzxu)Z**&`9GYbo36U!4;Cj=2P>{wM&7nIM+6j)`k?@`zM zeSB2@irBxMl?tt}E>)6)ThHINx{hEIm|9m>G@v3m$*nUfa26{D9ewReyKvZIdG`7r z{_t6TVM(pG)OUR|eh$Xl>JnwjdU|{b_f7^c&%!&h7&1@8fs({K^>7;th2AMFy`*6* z6@e1L{W(HIU64j}|0a7|t1i0KrhR6T-axW9-yI{P19N9n)7q7B7GG0gdz^|0Y}#Dq9E}nH$jfuiPg$2V3u+_Fn-R%85aeymW0HUGB-5 zkYCZ^bEyUe4AynI=9{XU6S;}gL&2}FDJ03Zmd(!3_qk9sHMIX}dRySSoVdZ*H1*j> zLx;3#yrAsH5$$47TYzJ@hmYqDeamH4BhTh9AO0^3(CtUJz++^HCb60OqImR%gR?rc z@vptX`cqx<0{ZuVQogX8wPJJa(8PyiR2%xvWmkJRm2H=)xausT)MouEO>=hLS`c8W zgduF(!EQq|5v2#At^YdWWm?{McDS&R8_)hgg&RoOYOZ@OgCJC)aA#1bgJOj`ig3?$3VI8>P?5 zgx;MO-nQ@#_2Nw0?ov(AnDjzuf|AA)DPSC(gdPVtnfVa5 z=xy|O&@B4{x`3~i*G2QXw!w2{U{hw`ZxttT3TYRyS^}95w7sq%xy%9lI~ti6AyJ3o zi{{@!x3Jhvf6^4$lnC&7+c(Ij%ZJ&`i@sL9&;cSaWDN&5+RO(xe{sJ+=Qpf=b6l-n zpg4GGZ6#VN)F;HtYqODeh_lxoeid~M4VYs2T7@qb!v0hhcAl=Gfq{ndyKv{^3aZ2A z$6C`pYK%pj=cg|of#za&C0}v@#Epm#``lEYUO?xAxX19D??8Z-J7dZH-GX*v*aMVF z@8T^@qmgTSjW7>J)s2!CZ(lJ@`Agg-y`kR(7$1;c#N+RFa%M6^mVcH?zbEtx$VAzx zYiOTAO>-E1J_VHOfVn>#wf{!Ua_Ts>9Xj>bO4UqaxsHxfVY5GfHgsQikHq+}jdJRS7 za}iz*8V0Qlk6J^4-)ZA#!{-hV8|E5+2EEhN(5&;Hv4;4<%swk?o$!sdzR2?OvyR}~ z7TUP9xx6{SFms*Ch%7}6LmtTlc0iV{B+thV#D@hXy^N_64D!7mAcc`Kk6HknIuaui zA>&0CD<-0vun0sBCIU4cX#E&k-6~={kP!ihqRf*&aW#bNIOGcuw`IWLQS0edquLJd z3vb>)dFvE%R6U<$U>veJ_<+DY^LTxYS^p5f%Xgi2-NP}rwSI-cK}EgbTujfeG&>$a zvxvf4e;NlXeY4j)9|WHqP`Nkx^JMsaCgmlr-0znuD>Fkk~E{ zs*k^5Qfz{}19HE;;4^E9L%rsTHo;yS^ME-3jNEe+DG78iPcM$DTrckZ!6~AAeAeCF z{msR+Cq-(T!=fv^**@IV9L;bvoGjYaglf5W0(S(4C_Z$HV4t^d0W^Triy>Ymv1=3< zmCeL!`n2v>&;b)rTGX-;KkytXs?>rq_^aaR7CIx9gO96*YWw!;iXeTcfrO-j1{sDrH|Zc2`NV{}^%$PKjun;b4M~ zd8A}Z9XgIHSE2MwLp1Cqd5cT{HoGIg90Ic~>^?W;r#`23)n`YV&y&DgD1Tya;wUC) zX$9sDn7nzd=$=s4^`QtL{g=9XXn^Cui>?F?A7poFif3%?|ln^@iXhj$dI*>7Tx#Ca-5Q{R=j|wM3sK4zhnF^c;PdS(y^Aj8o(-82Lvf?a^Yckwpk9o_LTk#h zSXEE7@-*wr&czxg#614m9?#{)*61Vu#jQSD+#81ruj+$G_}tF5G)GcNdbL8VXWC_a zv8oP-JkjFpx4B^5OW}|1PG`lHEuTPQ@1i!6H-Bau>#x@B!CiCZAtFJL=zUDE$qt=C ziHqdLowFWegw`o;N6JLN0ZCdP!V+DwI$G+Nal6k5-D7bFEek8))NOqXzHKQ4alXb| z$~yrHDXA5JK%h>m3G&JijoXv}gDG@3H#xbIFk=SVl{cp>$_LzK42&iAWoBdyP+t^! z`FpR!^zpI*W^s0Ht+l&1d~TyO2Q#mA5v_*=zlKQ@_7knVpa28%*AJdGj42>3A}+kR z!W?#~r2&BXxiaD|w6qzO=+QETOz-5@g~|B>7WH?CWR#t$Y5M09XR*AiYUgM*{G3bO zDwd=dJx-mzL|a4=Xg+s;c%XWal>5y^PSf-4H3jn{G7jkbtj{!d4JI}%{~k)2)>h-h zSo-aHX|>YR?66#7Vxj;JEkpkpR{w%5W^c|iN^%fVmrqg6-|ba>4RE$taH_9kPZ81f zLU#)bp%nNcZUrldO!A^8U>-!?h0$l+=y%x5gk9SEZ_^zgpXU@+XqDJz{>t(X^gi%h zV%t3dsdxiIw>_@e-ny5)u+2OTQhyg#@(CxWSJ=()qtp=; z6|J>G=WnUtVJ>vtqjqQX&#?M%Zf2>KmCa1gb(#gkS5dJ9Hn}r1ar5jB-5E_|Gr9dw z;I`q?JbdQf%+~PrQK@j&OjwmTQFUqECUkb1YGY4Yn+l#e3cP!t8Y_?6>{sQsRL1Sx z3o-Xl?=h#5MP}{IZUuQ;dQ6Z~Kk7?~(xR5R(tL12YpAZ9`I)_zxS9TKo6Ob6uu6qE zq22dNf)z-FkM54k!Q3u?8rJ;e+wChSAh#=K58{%Y!_q`_V^bt=VZ2$Ahza?Osi_g8 zLuj|v0BjLthBIC`L#Sqm!PW041jI2nPgR(sG|E_Zj-&o*IV_REY(@6!KxjZhr*kq1FibrhyYNH4E+46;Kz zKnc&*hCt0Z?7^$9+6!eaF2(;GBrj)yOg+7z0EH|69a298c4)wHmR5?>Yaxvl*{p}A zQA5MLxosyJXM^k4PZ}7$pqPmK%O_KmK2C-D*4gZ^$FhdTqJrIj`(AtqedDWDNAvZ8 zO~u1p8y`O?lq+jkNj-YtWpP{y%n}sNi_kUX^u=GLlmLM%S~|9^>_)NKCt+H7;5Uk= zgpCaV3plpa0UYT**;C>=i`=zM9clMC!GR&0;e|_*g;N#jcro1aj7(dcm7iXute&8+ zIH`!3OwWh*3fD>b)IKL~i3WB-TXl6U^%?0_u1dmz;%`B<#<;xSFH2amhJWd}m4tXz zV$xgylnAS<+sa5NIJ!kvPO+*B3Pcch{QcF^6Ev6?)7k8^Mht~%T|tDESOX z%Q@5>K3{wS>}Ufu>>l$jmB%-+mWt!u)g_cNVaW`FAGOkzS^`HO@%XoUuKMmXX#KWG zd1HouAn$OmcVQ}$-!Yt>9PS;o$)hhTZiJO71coOZrqg)&gJaFV90n>IG;-sCg}~f-K|o+jIN5}3M_}|A z@uLos#<}~AL~uwPHa4gFaQWY&H}qm=+~wuSKw3rj1GnG%o|K=}(4v*v!jt)Y=VPU% z2x68LoG?};mFClJg3lW6Is>S~F5%JkLe~yqqDjx*ycFIZHY7XwMyGBE-+BGS2>7ep z(Z>a?(0u68$|;Gv@MgENG22C3NHLQyUi5nRr#j19SpAwPT)J0+YE@|<riTz+GyYOP<}cdSaSasQ3!V#|CVXt zN;!dgf0oJgFZ|_4&HQ|u^oGS^8LGOlM7ChFFC_}WUgKE%e!J7|F-Ln-wv5+tP zyU_EZW9*I5&7QZ4j`w`^Eu@6a_lujG_vX4u95Pf}FtyVABh5#&g?*$jUy|(SD7)EE z8$4WCfE0nkS+Z1&82L){z>Gu#`{|Y5UUREn95UK&R{J3F+66~TR#n~n`0esK>bplK zQN}S!jMO~SH1A`;Ji;1{%mrNS-R0<3Kj3+>8Czsl*lQhbSrw`nrJew3c9K&0Z}Rav zh8ukD8I>Nji#@QY{Cj;cbQqD%RJ>jIElp{#a>_|%6)3?t0fF3@zhjS;6-W?Dg)Tg5 znQ+tmMq93{A0!CK;9B7{S9u00pJ(7anGuQFrZ9ErR2kw#N>6ZgV)ws)$vf;$A&p);{3xMpe@C)PVOyH< zWN=71tlsMVeP9HmF2~ncH5iiXoEFDQe{m^W)u`Lgim^z39co?2UG&hZ4|v0v@^GJd zk5L86l%SX4W6?9kq=e+6sShEZm(9K{{xa=VeKr$+*13)mpA?`>->>`K-G4WNaMVup zN-Ugj^zH8WdxyTg_BGIRX8D7QbEZ3Ee0KJ-YYOc*R&X|Zy(7HNq9n!SFQH{sBoD60 zrYSRA+7nQjDzv9nt}l0AN-t?a^YCZDnK@x6EntGm&zU*Rk2NqT%)t~CJff-AzHIZV zd(xs8gA#;vUtoyOt>OXqD$}QmyCFr~!^&fp&pG{o{*>9_Gno4*FU5)IpG(tp&1md1 zvZukL6vsnnjk<$=c%&VR?PjE()WJyHv~$un}ESgvXc1Zp!i&jBuWx7kbicI z+9!n5_dHx-W_kV<@RdK`M&&|Tx3EyWgB@i})Vo!*H>mL~6zx!D1k1Z$)`q1GyA^e~ z6|Z7-*Ek#Ng>g)qQ0~;TnUd0DJ87m@HV1{nW?I76yH|ex99WF+cn6ANkW-*=eD~q{ z%@yv*(hYad@TI3X{N~r2;5T!{pR*YA6jh4Kd+7Z5+UOFumdV9~#P;gs#KJ8qTtuq4 z15PU2Bi>@R?>GfqArt&H3)6uw(RLqSGRYawJ%@uOnLxaGbQKs8uEl0S*)xuD_mvE` z|6IxHv=kbdoQ(1g3kgZ|q`&m{4Rzr8k0cUBPC_4GUO?$PSg(dT0m@?`R2Xg~e+93m zrg_d{5O&xubJZ+mCK{(=SGK*RP1O%;l6Wf;UMo+C!05x z;b`-hDax?AVO_a?7x+dz0M`3%fw(K$1QO>ji*yV5ZA^)~Z}*MW72QXb_kCdAz(2Ul z)}FCd;)K={7$wC`*dJ4V#-iAZ1=SHK4JIb<$BxH^Da@^<7>Bh6e*}UbMWiDQWQZU4 zUKZVDAS#oSa5lWq70*5|;CJdXFXVik2-oVVKX&5sE`x(YfToXpMV{Z19rS};^LakOc3EmOdb1O3H#T81G&tR^cF%@@BQAObhW1XFyFo?dT89%ZxIXStoVEyeY?8aI5 z9|F+l+R#7f2xGC}3{L1CKAD5h3yzSK?4csDU(p~LutfM*P3F7flAD@1gIqYq^kuIP zf_E8uz> zf2r|Fvc{GiD`rM|2Q!C7HW8-Nt!rx3wKR?uZr{1K)*Pp|o%m3RX8*&IJ8eGnQ}0fw zcZ)iUyD>d21ffnoloy^~UIt+-q2@~{qFCk`cAZ!ZP%$wv>Jn5(ZM)Y4ZR9~Wve_q2 zY?(y-SvyhVM7%uL8j}}g7xVt*_nG$nn7~3+e6&J|Tk~VuTgJ3oh0y&+wNSaE8?&}lRZpp- zt~WwUd3x1Ao-#NkNPLfuekeukhbDW%9)9Z7_+0K;BV&ZUAJ-~LjyPQH+@-#xExggH zyTbgw)AgvM;3>HL{w>D+1%k;CmBuq%i|><-dMWF}8C!+^Dk)AKas5Z`mgduO>b{6m zF)+8xQ-pG;1Cy-amqZ=b812X(T|BxYCb2p@5Og# zLOij-K+m?Az~jQXpJwDZ2Fzm|* z!JnFgktXJ<*pmk8!^2aVIC12ghd9GshaQOBe25d;BK;Aw7!p3gPqVmU%6CBUhkCmo zb)c!6TQ_qOeAAUZl~yk@<;W^l;zSvTqM|tU2LeCg>}u%8m~yAu6En2mc3{QwoZk%G zp{M#+A!S-nc^5FI-~Rak+Hvb{4*ujc7tY_*XGNf6%O_Wwopg$?#2FULX;ND9q>z+6M$;3)i)#Ua}I8g^8x+Aeyc=tIgx$oti{rN^L^i?v5DF8 z4jpcfM;QBaY2DBJe{43FJ#^N`j?>?vWgTzeKci2_jGeKoNHN(T^RA`HRA>S#crQ}) zxTA~#^7Iy&9P$=E9t4VqRb-+p7@@v>vVfFpTV=tq8dZwjIUjk~L=*XnQk-URc*>K0 z+6MpB;Q(*WN`4H#wz=`xst3xT*CX|^u<(|IhokN=oe$4cr+1LsFiZcGt+dFq!{qa=SW)SkVB}8{g9+ z(fIAOmpwt{eYbKuzkT}#A)Un>1qvW2)Qm=JN4RFJk`e)Z^dqT_+30#Ub*S5N#((R3 z0h;+(%7 zUh2TK9~BK?Jf~3yGpa)Q5y;vG%-&VW=I^-*$n{%fA41DsSH^BVBxnQK^`x`* zF}A(FJutkZboN+I2jh@K!rSE4nc!9!2G90Y+O=3EM1#GA{nhcUc`8DYpI!bv`;6Cp zBG?|W^!8!>?v_s0C7YSm5{MxQrk5#O9uREF?Yv#SLiexZeZ=@bGyc`q26 znAip9Gy`L&iiq7G>KrSq2afI})-k``{Ex(RFuiK}%_na3z=eqbt^24Fv%(N+VOy6) zJKz8><6((;r5Buo^}mXOx60hI_N4Qi!bTxa!o9&vz?I}phw|Mi^a{kk!v<8y#`YI9 z#dbAkiI|b)_+C4wMdqF!5^jT4kscqlqy^4%+8y3P3qU>4Zj8D4)eoe$7Tpy%yzcDT zT+i-`K#LyVe*oX}a!M2b>O`7S4~3AH2jjci5RIp#_5xUNW(0$OA00 zFw@cvUrXx=qV`FXYBsYEs8797IVso_vgAKBZE0$CeP*EiVbjk~mv`qjC*6GHHKu+l zBV<_W+{47xU3xjvl^N=0(jP?l#3K-g?u_U^mVao8d2}E)WBg7&XL7Qj+SHd5Jhb@d z(C5G`>92SmzP#bEi35m~H~l!~e@eVZDegHmtDWPTn$lhy1={?G|tIuBK<+R|>8>0>6I#q7wM z`SWMBE<4{@q9vJCSXN^0kV|StA2R-gHZ_53*A0dJy3)kM#Tk@9>pO$4m>)+|w5GYeJdR(2(LiSCbjpbV$)!VyKS&=hykXuc`G54z`(Q+mE~O zJh@?gk$#Ad<9ouTAcR|}sG zv_|pK`bkU8o$x>O~65> z`hrT=;}j7K5fay(`S&{Xdn+!Fo?#`wQ|Zv4@W-Tm>C%v*%S72kIwo+ zcR_(P(bRNm=(~+ak9lfp7BkPHr{bvH111;U*uXi{d&*Iu@gi&grJ%r`_HFE zZc}*vWR+xmfkX~Wy3EH`iTV--3^HN&ft-eA^7dEnzJ6s#ste>yto@O&^WiKNvsmq3 zK@ zh%*$%oyvDcy!JIe%@?BULwC+2y{Q=`n-rgD{=nA4YZC`mt=*0-^ zw3&@~nfeR;uCVYt?&IKK7E|ffb7mmwef6=wAFM4*Gu8>%3N%5PT|F+AB%8%7R)ZhC855toT&ozm;-Vb5G5@QtFR--te76dIq@XCZ-IV;H4kFU&vI3_* zTDHHdpy}&j^n2%y35Fo=g5*6->wK5WE*w$Mwqkpev{7=S?JT!`lUu)dz24N+G%X)) zI1tB!VHfeC|6rhFt@R6MO^KPhfJMAmoDvURh|8NBFN!;o;?UrrXa4R!WbxRJ zRQiIg{-9R+W7*mYdykzcME6emPdgR&np&6{T@@9&=}53LjSPdPn$T)w-#1@$6dn&- zzULrWkT`gG@7^;%%N;wW2WwAeLmS0Vgu?}EwyCKl3oDrE%`)2iLfh5K%G_kTtxuNR znXHS7r8;ZFwV9n0wD^6+UmbPVTTjl^q%Q`srq+HX?=kN^UZV1RW96H#szefY!+&$8 zzTWe-R8%AQwUeZA2oAFT9}%{CVX}yxFcI^s(AQG}-qtr10vKoP#)=?V zdF8!EFTIk$9d3*iSA$va0BUY~Nwmu2!O+jzdJ7?t*x z_xKsbDecDjSXB)?HWu}USPT7~R!4NxGtqr{va$OcHTX{9cSh-nGToW_gcEgyJ!}5N(uNl`vEn%xQJZw$92vFXyhi)}YCatY81>qv{X0PE;Q8VSY)m zNmJP7Ms2V~S^)X;p7K44Ht-oLDA?!>->_L*v01y%`_TI$a7AJ+9|WDMvhJsHK~4YA zP>15Zf~yvf`S0y%?)0NR82w-`D9r(I9RH8ky6Sa-e0K}e$LE8pZxqMnyiA7%t-4`p zNeQV36@fu^tH5>vk7WMH4CYia2=%&8Zd|NTifAtxB^wjxTqwY~7e4K3)m?#n|3z4R zh72T;2F`tyq&4gaC|Hw4YAAVLI>ee23Cdgl=9kX=~cYR{NJW=qmOO~|z zuk?vAwbZyyMRvFP_yuZ1B9rj{Xgc?Jru+Z@kHnOiE?1@$i^@u}QX!FrvQSozIWOm& z&u6hvO^PKsbr3Fuax9FHDKbeWmQ!LejF2}DmD=`xy`Im<<9-Lc zA4f!e@mYTUh<9H3KH*q25SGT%OX>W!lJv2x3r|0IeQUp0A`khEN!S_n*M*266w!YR zCjDvV29Bkb1HrDir$PJ9sHiM;S+A6X%V}O5N#Uvm4?x@T0k)<3_0e>AVoYiV+k zNtgLnN-xttv3o~a{*0Oj&GddV2}>RfRg#1cnhJf7D{@T&jXVe&Wy#vW89czqX4Q`A z?%V{zw~icdEm1l`iNRwr%1sY!e!X%|JsjUq9pD~B5f#$dn8@Aeideh+nyZN@I>dg@ zi}Y-6%4*M~?!7D!W;?VrKf>tmzbD?FkRWnFJHr2Lxj8L(Ef{D0Qr93)fJZ1=Q3(G# z@~7qQ*sLL&^3)aT(b3Z3=(Q2MG3g)GURUM>IBrXGOFkIBrW@~42fj;aybZYQZ6K%D z8A!9rpoQxT>aKpw6V;bS3N4cuMcfuSY{|yuly7T{ zG=w?Jy~=^`g}E-*@e|vnAxkOq=;AP$_=}WIujh!ji+2{Bsq}C^U0|fIlLbLcCjFb6 z0B)DLF1Aw^M--(z^WhtoL%I*V8xdHCe5`wA$Z28qjn!Fwvy=MK1JdN!I) z<~PCT31r*k5!!wce1v-1Z7nw9ltq$O}iTmL5sQEvP@w#k_PG2->JjhEjAR`jtg2m~4 z&SF7Zd1rPPgsd-H({A=M7u5JLo~Lwok{@tav<+8Btk(}jec|!kSP!Frw|g^~{xrR& zm&FR>6jmm4=DleZ!ovK~lMd$vPtqY#-R!lq`F+)-Lz1I}{ms&zxnNp1+cALKcY+Ra z6lmT8I1JKA@|P6p(e*a!Pxp{sQmMxgd2E5)++4HFxqJN%r9~}mo?jAprA#m3a`?`M zuLgPqtj_h^>knivjuw`dp2+^z-@gxYk3jmZzZ!tV~D3PlN)O^0B)Cb#o(fcQflkgTljY z3k%YceIS~aC~JS!Cr{coW#@rx<6yOYFr6>sM@&pjOy7siD8v=8H!O{M$14hThD9-e z{_nY&Lybbk*a8yqt$86N+d(5F9Gm9$ueNTdca|7A+3>FD2XstrK;Y|UMK1=#Gbh%g zSF$>ub#p%Dz%K2l3OQm!WTVYQeYIC4;?M73+S#{3pUZ2~^``o2w^G75>uX?Mf_RB- zT*#WOWdQyopyn#h48x)irF@`z-rKf3>Wg#Us$7kir>WRkh56uW+S?S^vI7Oyr8*v8 z+RE1n2{Y6#E%f{iKkx6A+AeeC*h+0;38yNj2zP*dMS!Q_BPo;EV!B1r^Zjkjl$A3ciWJNGa*K_hG~VSVVd)W+PQ&eqwq=GfV# zpA-2qR6D&wKfkMI5ah(5Ohc`f$>g0B024_R0`9_N;04h4%#C-jUyN7)@GRah^2<|L zz6uQdR@KCw(7AMgcK}FHA~jaU$Sj+8rk)DQY?_tT=^dC9;*CO4qNdh(J_y{&YVDVk zWbeov{nwM}ST_8#v^ilfLZm;qpvaY8Q{l?}K|7MIs!{C}bOB<#RQoaMw_z*pon<2x zH}mh}b~o7?xl3dtA_L$9f2s74xhomPRV8>94?MNH40oRlpG>Z$fdbrau0k$Vf@I0E zv@%#9uB=-t^a#6jvCFscnu9W0$*Ev$aQ-t4RGCNJm|V2q}x-<#!9Z}#%rewUhi zeD6Tyds3#K@saE@#;hb@$HM<7hRxvA$sq=sTHK@u(C-~D<`S+UOl7#@>30;4_Dvw>(*EuWmVb5*&tq@aJ!liGd#m! zbj{buAIU2_IkmWm#+$fRntLZ0I-YDu37-2ip1Opg^Zm0s*Q~Y4TV0AfQKPN`HcRb~ zC+&k~7axeKKGlC7ZDeGJY;F`?6|b8W@Iqsdw^916{ZXPo!_vv~V=Syq`U4^y!$+zy zFC4FmLFw2cd9)y#g1~4Y{VZcqz3!E(+mV=og)@vSMJ@1t0EenqR`>71LXvFI`YObe z7%Ir;;!R(x3_OuM2w}~OI3m#w0S~og?59TQ|MK&luQ!B}FbDadW4-mgU_XxjQjCv8 zc|dJgpeZ6--5$L(Gh=3mX`(AEUDM~cT*d~G0?N!3)>|X~B)mBZ(p1yWj+6(p@5260 zIHR@n`_3V^vKeL+sJJlE2bB2`GF1CKST8j|^l$(i52Zaydo|9S0bi`?h2QPU?6R#M zXo12v5QdYSH8m7l3vXB19ywf-MD(tYet(G1wGi<-e9)DYDC?H$|7DN-KI6R?(`wv_dC0PiS1}3p&WR)1%|XfbaJJD+tSTB-_GjF-eOr1Wvt1nIg#$3! z4WD9%PZa`k+v`tB9_K~(7AB|_kYX?Tzq4uy@wOZWSgQQb)8={P6mH+Aas!ncs4L0Ee+^nKgbX{i{`|@46 zYYsr-5}zh|cOldxpac!NBOKlq>RYE+@hC~+T9tA}ZAxr!N92tI)kg296TRvXk|GWU= zo#O(CgJ^_PnPp+OCR%Y6Fqfk%nLpgVWpthP=udBF zGtmhU;X}Oc=78?yW<18(yT;C@?_w0!O$ao6`oYC<>r>wmKO}s+FnM< zWFmGe`L%m0pikIA$usx2V@01cH1T(Q7+GTYw-yTb6B3RcVpG0a86p)ZCmAY~hhFEf z|27MfZB#RsDI-A&w<8&o6O=}2&}G9B5qiiiM{_jIOpwpv8VJ)w@rKCgVkZMYj9r@`9dH4F64wv%%-&|R+PtJipiKH-?Y2lrea zAk#Mot^>b_A+{fGPmq0u-I)cjt?ghw*;5^oRB)&1iqmiqPvm#g?b4$bXwpj*P0cNT znI5S0o89GqUfSwdwfVl^~EKt975UM5GArNe?+jOuqwhf3Z&M5H)|*ahrs~q+3<@= zRoA2Vi`S=5#FgncrU-}vHx!-)%92X@FmZvO0?LZr2uVEB?sqy=q4Ls{028!4*Kv7S zn}M8{(|z&!V@duGE9=XSX>EaA{>M8pWj!~`ai2+W>#{L33CcWTuSloAvnuXZvh1!% z+}?sDeRHwwegsO4IK}C^FaG0z_M%WW@}meZ;yuh4GR_2yS2<87CnnM}Yp3S#%C{mA zaOSCo^u5RWsK@SXK5@=`mFsm4 zX(=>rftomjCV^ECLpFCMfZHqoaJKw@C84N3THm~PSNTyg!>s#Mo0C!$Qp{`@|N3Uz z3P-qqU-+_t!Sb4BUzsNQa8`T;G4K9%d>jgo&CW0)oM;zMKLgrFM@V3${*Ov%k~{)W z)1Dp)df+$W7HiKfl@n5gJ=O;=is)|PWw>>G z=x3xrcK9{uTH`zNt~#gg*&go~|7G_OXMWtJ;v1UZHpS6djPHFft>bmNrSR;;+=N#9)Fxz47XG)rw5SaRIhCZnb3FMN)#oLI}fP7;OZ$?tvy5$XCWvBdQ{ z{xx?6EknrjdCx1(r`dU`pliIT^>J2*+~y}}*npJCg`iB(lRvVThi%@%&c~=W5aY*?45R{uV(W zVN(v}4O)f_H{ju!6r9T|=kepnEhPD@Z>pu{Q2Zh!^5Jh}WRu-0?RUl&8(67ioyB8y zw3DaqUwGfsV`q5jHuB8bGcasV-`?`y*IuVfNF%U}ldotSQsDyQC2T{E^uzyA(ocsQ z-zH3mDvbf?+{$TpCBH7O=kZPG$M#Eu_2&^kmX_Y3qOOeNJd}3-Pu9gMi?-cx+IUu! zU-HAsLJv(!vC00o0sYVBRLlA@fNn0p7A|^7SiH)aC95CEA}~5-i3EEuU^jQ%wR!at z86A0?7XkZ;@=vouh)7(ffg__w_Wr$Np$qMG1&@NK2kXbiIK|;}C++7#)g$J|yI{fq z)nMD>Pip3w*9(q8(M}qHXdi8DY>e&*ocq%=yL3}sa=ue3!}@aFYX4(gy*S&^ED?s= zVz;?a_J{}%4-X7-*s%J((<3>k2W?%o};5+P4+P7p(Pay`oXel~@f?|KHPKHqqf4hD7l60w+-gD2=;s0j=p!G#^qnrYt4%B-SYX2^% zuT0D;!70Z%)g0>ZSx_y%-mnTpn&*U1R)&;j8Pcl<7I6yO8hh;2f6wprtv+)m<=LUj znYNTp`BD(K|CD>8r-0SeIm~`#m}pyeV&9IC+s(go^39(Y?`jYW>j+NOrr7<7 zENDD7JJ^tnPXen*vX8o?@T1@NMG}gN6nGFcD{fDzVj1np+vNfyixQXuolaGQC)#m(|ixLn}& zS3N9=Ew1Suwqmw;Nl!#W#-5Prh{ef)0}vcX(rdY{P}x3&o~_9CK$&-!8v=w88M!mc z=31ALr3qYDC9*$=@aD}|{75#kFYGYCl&wf#;P%7fRehf@zgMFCE|@T2eu1|^U}c5= zy|dFK1;FT3>JD+_u;N{5a*7S9ki7!vNQBkXjQN!?jcqtQC8%}euJkKtE?5&Jn!SvS zoOeQF$(UhIdBDbz%6`A)p7?z;^`LgKiAg!L!dVr24Mnc5KGQiiH=FzPpQzZz+G{QW z0jr-zn1`D<`4@lsR|m0&qFrdh5?#bA6!2&wkl6Tgi;v2>sX0UG-TEfoCqMk!K~H%= zJbZRv0;fuN_#1jl#y>CiBR^K>qka=UkAD`-ca%g7>B^P zVu9iVxA=o*WQ>iYntRnQTkmi$VbQs;I=AYQJh^OPI2v=Rc72_k*lUO1H5>Gw;H5v>V$IscgBb{fvC+tidbaP? zN7@|&RM^acMijzZg~o7EB(})vzA6XxO1eR=S@PPTfK-45BF>|)%D%83VQ?_1$aQ(G z*02}tgHt(#UR$$X&W5JV^-6a?x5*%@Og5O>q$GbFet=u$ z^g$D?pjiRYLQxlb*N#jTTz57A~4JX(fc@&}2ZI6y2ijVFz zF#7~-_pzul`uH(v3L5|ZV!u*#NcE=swTu~*>2WGeNgsE>vis=c*$$_g{#V1w^buZL zqDhATv#S;8`@`WgOS4J+fz$ma{YzOI%azRWjQancW;e>K{pb<=seFY0>DiE(XsLC} zuIc#-EhKkpQj{#H#V2ERx+U(_)5m^eOAq}Jn4Pyj*{SEII2|}YnypKLhb2?Vh^3^R zspI?;<%!z0roQ@gojq_~_}Q^5;9I#RC5;SX2{N#l6jX;75)utaULg$rwR74g(~tVb zs#riVk+^Jo#R#JEaW*=650{%d9YJGQhs3~dymP8SF3?_~8HaV9+$4PLf|CV50!3(4 z?C)V6pcYl6IUch@;T>j|`iE-2R>`MX)pehWH{w^xeFV7+Hx|sg3~RYEe7Agn?}5!TWS={tcm&~qKb=IPcC?r`qtAZ< zmu0&TV^o*$BqAuxGC7+aG`o~e91rTBnsVQiPr)5c?tjlz&4&WD7ew_EZ@?w3+^k#w zyu|fF6LZc`Al0E~scGrvDJda-3ssU=X9XH#Q|Lo?6v7{39n?>PQ;Fwyk8uLlx$qXu zfl6O30_-FTLJO}rs-th@?sI>f;2B0Sz%Y(J3Ona72(+X}H| z%oh&m=ot9>-W2h6P-{E|a&dLB^;6MZWp1Rxpui1Hv6zUt3mc>G-%yqDEj7EUgRQS| zgAO?~>N}Mb{;aO9hAK-IozC78xs>T+L+dBo`i9Pq!duo*ETy9>w8MD5e!Z6JeKi^M z!fuUfmvzaaw~Y0}#k z`~xb|{B|~-=5JiHt?QK!SP((YuFtUs#u5S)952BYiyv_jCm6ahI#lod=698YqsQD_ z&x!FR=Tsx3BiVSAEkdw?ret~a9gNmf!um?Qv8@j~bdM`>LqgtG@#UjBRnjDaUq8ehz5Z}pCrW|C8 z?|W_?ykMF4Ets|oUlY1iBDXF3Tc~<_$pk#Al0NZa#Q1m)EbhoI-*RQkr4&b=bI42C z4YFXN%f?{{1YQKsxou-BR-I*rVlze0seGE}1UtYjjo~xLA|-W#1JwSYw+Ns1t2B4Z z{&wa}NZKTDoL+srO=a%3_eJr+QU4_G``llD>u=?^&fokyFQOrT`jU=dnZY*9BVNc@ z@iY)2A63aZ+5mL$x!5ci0aKoT4mrQ)s*zELR6i}uN1di{np5GHmh+rCs(l|iVh5eY zn%_WoCl+ZNreW=~TX!c+9a>1m0j%>+4DEVn%UJYnwSi z5OE{(^t<#AhC5?Af=h8sB_K;YfwO|K(GK7DX4{|5s>NUw>7I-Le}87dRx-GH3V%5% zzPeu9pKP9HReUI0sPVOYtNbO$&L_a8J5M)7@p0N5)F#AjJ^%cHo@57Oim}wBjk@h6 zS*Nbyn)-J#U_f0>eVqgJACOF7kKXNY=>!JTB;`WuQVk~+qBs*1zTb{5(|*zePa{oP z-^`C30O6n;OFeXYuxrejRY7ody~Pef4@Wo3&}%;3@P@Czz?Au5)C*Yq7F*ZdA2!97 zTR=*ymKy@1`*m=6Gdc4~hc5rAK}LO<&H6O*t5HN_aeZMuSP=~}YrmlRg1SFPOiWBJ zKRw&?%7k0DV3jBf_h|zL(E5e=4;?E0D4DLs z=80&;)$zxErFp$G@oQ46i_OE0!>wa}ZPg_|cJc*vhEMm0Jh|W@B^5r>cx+=~W0-q! zi;KdUyv|oPpPN(oG7qKRw^jN*AK-t1ozywvZMzrwLTlRrvQXm#>GY;Cms7MLPt@^K zv?`%39*Pr%E%seX4Jku`zoa8!jj*u?p?HVHhk4CFb50}#SfcpQcCJEfiz6c|wGcM@ zxA~!%#oG>5dvPQww{abDH44laN^aLr&x4cLzci!G z(GX4B=mL&kG>V9S`HR@%2150{WTZ@-DIjVVZ5r0 zeo8+YrS}u9EFdbhWq@ap5_54!@K$n)UGKF%2TQDTs__TsuiJXO_sQaNevQpKej~ls zK*JUK#__3nA+DXyJ=qx?zp?89V6%w2efF;|ryqbm^X$jNGBOK7vQziz z7G<+N7TBSXvH?z$t!Joj;GglX8x=nZlM|B}PcxRn2kS%^QPPwfDE_T~XZ2k8I4MHM-Ghqby;L2ZqaXYpCC&!ZASff4d zdg9v|TOYr0OYNhUd)2YzJ)4A5$8!xyKApjFnXw3ShAS($Q-dTJ9jG+t6d|3M2_ zfLLE9J8Z54Ci(l!9j)qAA!#(0>Y#)+P*4EgG{W;blc0+kiC>F$GqVrEWY4Kd;a}&q z%-EQ^wJzCdB4rV$$N- zcS?2{h6aW0h~QeUW7v`;JyZ+=s;}p$S150i34}*%6|OS=itam8`4`GUyi)k@N;~j! zx;r;pK+eE7gF4Vls&3-%eC%BdiK9>x*=Z{I^P^I-lo?hkw?--yM9IO+4HYi<-tHC|n|EOI}4?*)_1=&BEsgwdR!u}E8uLcH+&~0a+#-M2dUwAx4}SN~tsl4kyn9L7 zd3pa%m!$iXe@%xa#?w81%!W6gEY^OPd1x{J@S_Tz4~Sdy3LlV|AJFR=n+Q~P!Lm!= z4gNTffCT<&x1?;WIDW@YTgmfIsr)1{o{LF0-kC0<+_~MvBaE$CLbjh(N}0|iMV(xj zmjA2$ygY}RDcpSg*gp@y`5ny$%uJ&q9DkGwIsY^AZbwKaTtL+A*n40v}6BL#C*j1fcqCQ(UvDTfAo#S z9Bo5q5>WJRsP^5gpnZjTGsHNtqzTBsS|Ig4D*9@t>g9X?PThYgqmpvy)O&;ctE@?3 z0R?iYm11y(+5or0e5^!Xk#29ajOs1gu85B-pLlV))9{feMmb_`@K$2JYj1^fn9$|S zv-hM!|291y9s{|miN@-$Bvy5`tUk4aA{h5E&sm!8QRM!(;L(Ct<$y;3D}T4Wvuexn zJ`wtvJpB_wYM<1|(bsT%2FRw5&S$Z$O1e{1TKuV~>52A)%|t~1zpS@R?8Fe4*WmPbGB9#RXz?_876uR?I%6uBeL zCEGVD0)GvGfzfR|j%pj1)p3~ry=fE=j(%j)B5v}_(`C%gD841?pK~9nWg0lA?!*hno<+d6 zbZIbp!F-RNCjhmFG=(jX;SSgXtvjJv1|!?*&5*#nEOO;;0YUPkI4xZ>hXeLyZoTN? zrKX^6Kex{NI$0HN=?fUXO*~`2+5LxCcfLP2T`8S??FK-gqQ9C{28iyAymQf;EknMd z*uQW#>WXt4w9pP8n3c~aOA3dehV5{5)zxYGxuQII*|Yl)zb*I>$cH-{DA%O!O@!_IeluJN@HFp!^ zuJDL2y=r00pH=I6077>?BLj?2eM29cq>PLktm_Y8YFSdN_;lvLQ9PcoO|0vo9XL1ljR0?gdTa_ zC#cxYys3~DmC^l+ktj+(5BJuBeeyB!(r%A_X+n~cD0wFtOGn^2ul(){+P-2E9CZ`# zT)T1?h3pU^?siO4Y9hbi_@%LaStE3&{y%8I`1L9IT|!F4>+qaIJeL%sr|h)LIH41b zLLUI?iWlV}>L<;E1p!XV8zRB=Xl%V{n&Z;n_4S_8+#s`y*?;mM5NOq#YfJdjSY7-F z|M5S0O}?a##lHEjiJKA_<-PX>#f>>7awsjaq^_PPvkcQ&4lF6_8)H#2ZmUC{d&hNKrDb7ZqBKBqob>W-t$#S1S9;FU{5XYQ`92g8En}NH?)tc*RyNnTlTjX z4b;jY)~B-)Vk$6*TWCJVeidkHK9rt_r_@WZc^YWnxbECn_fmFB@#@I6cQ(2oMviw*2Bm0LpoRMA;`K;On1dkSfw#sGp zJ;>9&VKUgWjkfK`7!*N8Eoe2xW_472POn#-y5*&f3ldT>m{0dW30!DIFv@!9XK>h! zB3#eUW{6+yE7#6caa0^`AzQKB9|W1{7Rog+d&iuFFh2@U11MLTJlFVT&XQFDK9$3< zMfQBjW_K}v7=m<~U%yJ>Jm5P6V%M6YTXWpXaV<_uNB6u;1T&?VnK50UCFL4D#F{Fj zH630D$_8S-ylzWAk)A%j+i)EJjftVOym)ZFIQEuk;-OC=?U~_!d)RTr`k)5oL)4u+ zNs0_RiUd1%6iKo;nru8~L;G5i-;(1h;fUJbA_4yS(unEd%j*0%e@pA`c(8x8C<`F} zA&~e6ep>LMF_C#FIerx(!iFf{`=EhueumWjqB?unuTJS4xhn#+NG|tMlfaT-%jp z+5K6N%7@vGe3V;qWTr&m1jc<(@Tv zWMP0P0*N5~8lS8lyJ2xdP}B6&Iv5`OVCiK?&`x$KESxRvS^YcekF!=n8w-&th%=xuAAD8as*Rml^Jhu&`d8VKtM{qL>2jb1mCFX^9>zd| z-%xl9Jq7i%<{z~u$JkMS5RI+HR!2>?QxwH{$wEi}GS~OyFRTuM+ zS-)3qzr&O;CNqe?VRjJmsD^a@JZd6R zC+pXU3kG@k-VcH1!2RWC%GRbldC_OM=iW~hEs#!7-IU{}G zU_@EpWV(-Dob7{NvzDMk0%Tny_?hE@%ISYYqENikJ)MWF!UG=Fj%^a7B{1WnX#H>$=M{BWeqjf{(z&8n*N5^3-3|mu`hLrhz zyt3tgFnlP@IQz^KL?VW+;VR)bZ+Q+=h!#XETGhA@d>i^S$i)Z z0v%#~h_#q@YEIYyI|$4WFunzjN2-IxF9KG){?AYEfxq3Hwl#MF!5PMhD3$vB$DLmD zYvNKx#@l5U;PJIk8K4aY#2!gkowvAMcCV-}s49Tz>NktgoYslcy1pT`nxU~)w?1zz z-7sEtA9qlf`1Jn09z9S0A8z;5xV;XwDd#B`aVcNpr0w;vK0!g)kfq;4jl~)pCC;gX zYrg8S=)%f9h4bKp1!#T-8_rJJhKpP<&f`%SiZd&~ITdhz)DkA(e8`Z|9a0ox_Ra(X z!I+VJZ|YjadXFRHoqT(2ZF|Yh+LWt+jCe<*t^7(#An`$7&+S}XiIg;-_7gA0OUW{0 zatEoi!c9ulphWWAuPx_N81y87?SBFituO{%D5%4BgaBFqkmOMmTeW@Mg_W)zqN^^F zbu&P5KUpyQ=XJn*(4HyrKX$}wehG0c+?Sv;JoA>jlH;Z#Zk{&jFCaP4 zux+z?EzjNd;GHw=gC2g;RB$MLuD;j*dLFghUnvzNI={d@Kt0u`XoD|jrW_}~LD@wp z%j!1Vp2iSVP(tyE;srr?-G|w|a(XEx&$}!3%Gy$npYqKZI0aF>TXNa3({@eXEO(mI~jo^71grel`$@4JdqQAkvmxucmwdNb@O zi>YAU!RV0E0Uw;q4q`3DUM-BD%Em(|fWMIZkv?o_DAqhY^qOTGS9YznX~LcM+~S6_ z@j;0uIptW)FTsHRg%Xd{V2k9=j*o=->H6p*H<9Lla%6R{=G}-BUEh-Yvf}?|0g^UG zpT0pBl*HjGEKgtjmj@}mUypm*m3(KuU!Yw%fVquuRYC4K;)5oEv3TS7LGmu`e!o8d z>a7UIXsH%bDmvD-lx6Ok;R88)FGjcDQS@;7Axa(SKrTF81txdTLTrVD{ZzUPG7I@) z);?8*6uod>23V6@1q(%dS8Qu(8INu3iS0^GBtS8mrCupIGWJkrKMKu1~VJhFaI zn&|#VB`7QPu;2(~T2*arRb6xn1Q_U8`up!{LmKP9lDHAvkdD1|^R3pa`FUxdZUif* zL!vwp`6l5Ojz^Ri70mT~E!ey!EjT=|@jEGEUOYk&SI#`B`)BS`lA3=0i*JPWaq)-@ zwhFITP{sI2B=V7Y2ugxY@j}=P{6(G9{I8?e{LJoz1pP3V@e%Jan#R6_rGToU?U1Ye znSPZ3Ya*})`dJ>@`S74~rxKCS0wh%xlU>@#dX>i`5^*+ahhwY4SK88Kb$87+jrksj za#0%WftFMdHcGqa!{ExmY(i%Expi-2e7$xK9kf4mI=6}k#iKRFyw2XDWhyI}B_DHz zdYfr3d^QV)_b&zOs;b7TlTpW?w&iq=u_G4O0@Z$|x3TY4nsoDBWvey#0;>sI|Mqa} zHP3oyAq75-xkB8*O{qs}MOW{+xb#`XeyL#)&^|g9+i2)Y>vNA!bWXlPpHHVwwU+?@FU>)6EkQ{Td$J4i(c)UT(eV8 z`+U&*!OG;{nGv)7-`gf9FGnnQie%P(=L$zGPRx=l2l}Bom9g;P3);@?(aKup@fbye zQVZ8RI3Y$+&Od#XMrKY&<3*y&A{A3#wxFf(4Jta{5AP*?K*WG4sW%156X{u-!Zm32 zGIKepT!3vzSL|7!;9T`6qNJOJJ8;DM_y81;ea8XufukcyBt5g_Mnz>n>QRs5UlVsn zDqs8;HJDx!4y+$D5FRceBfIov9{rV$LC?Ne9Ur+AiHlUE zr#!knA>g5>pk-u?1{a_-Iq8$EZsJmCZ6DafJ$Mj~1&=N!TD64vNVXqJ_bHqgsa=4n z*>f^gJ1ET0zT9e{ICuCHgkWNxUybHf*LrY3kY7>t>Ai14$Mq9yxz#yq5LXtZR|Zrz zDh498lXnoO7T`2yN1>;vwO`2UuzPcb(B*el=zOBAWuJV0z6Yy+X%@Q6mvbu@I56gt z0~F-8$Bx=3*8}QS_e6g5eh0hFYepI?V+rB&-4Q3Awrz}>)G6;1jw%(G3g=F(s~6`_ z4n-no>U|WbU$eaDHrJI+r3)G5ls8K4oT45nVQoWMU1E2+Pmz2piWmReQ~8FO4z`dJ zTyB2A**_$NO@l@gS|*zh{JgXU-9%-!9c6Y&60f}1WMw|M(u_pT??94Pp^uCvbt>WG z&@!Y6UsW?#o=DVS(H`iJ_DPn?TNaL@Nm^G@?V0?MU%HE}d>-<~;VF0|SaWvqo)c8K z%PaGJVK060?Er=hU0XA;Vr$yx(woPN812U*W?2Jxt@PO}m#@BV$oey<_ZfA5LPpw@ z{iK|n*L6JrPf2C2ia2s;-l4O6Ey=O{VCh&}+g`-r`1suu`6I9UUx9xR%3T)NN8$$# z{%T_d(0eMz@?Cs`f}CHia3WT^ksX6uv|#w59zM4?-dFwUhHps7k*){Xf|U0mr+3HW zr@=)V!S;vzMMjxGr!hwq1Qd>T+}EoqHcbq(qtK?GB}oaeSF~%0cZ3 zU==fFn0f^bc|$kL=j!L9RnyHu4|h}D>FmX&_0ol3is^r2Z6%}NHCed;#~3X{RmG)5zR2IS%Sj*51?5&njNSHjaaj8& zC^1cnH0j!zJuhTX(AJ9^F1Z2w{f+6^b}6-Bv2%J~$=i80#x$12RoDzCjF#nTb)8{L zmY;KSHQEx%?5UWfp2Wwg>0fQgDBpa!V-WhRZ5XSXz>W&AJ^%!P9*4_G*S>pm8pBu6 z#(8|KQAh9DzagpvB3Bc;Bab*y&rg+y?yZECh1_s?k`lt!fW z4SgzI=w{IpUd!FhapoItU7Fw=tNTVYXzprji$@7bD_{StohrdilJC1&3GJApxj#ZK z^Nd#uBNU&s^*(p)g&5ouJtpTQUAgsmwix>dy3^0nEZLlcYPbohTR5Jbqz7^(NK_&s zl1g;7OdbhUZ$^u2zZoc^FTxLy{@aSD-~6f8 z#IBwa?)A;8?8ke5x;Wk4rvn(VCA$N{5^O%8o6#8Z9aKTrPSP(*;pGdipKq$y1uwM0 z;~N?cXY*T1N4RRdAZo{Ngar`_lp7NPNXHy8hI- z0Mu5UN?;gdNRyk_;Pw8o^oLxRQu#%#{bXja+TpD3FcS>`?&R+t3DU$?TYIceFR?9T z_v->Rq&kfye#{Dis9+rxZ&*^amQT%@>J7fO>&x|R!=b0TbR;;Xb}ucysHdmK98dN% zd}JSzU)LnK2I;*}AD?JsGQlq_L9l40NPR+3hi^DvF4~8R(vgq>%^|^z^6&t!v=hyd zg3a=nV(RSKOju#(r#l*#uYuI4oS_2XfY9o`QG4uHi|dtr?(OaE-2nlc-_;pH9C6uK zb@N0HzghI0drfT)+%Rbb|5@ zZa)`ZolWs#2x6iWwWc*cDP0n&UUQC!M0|Ff?Xvr%3}D`cfPhU*XmabwP@q$c=GF^x zc_J5hMYo+h;#aG>MZGMyiW5RXu_dqaiW2S$+5VVcQxrlV=%#S|5rBokL0EwvM7z3f zrK{AVo_9XuUiM?3=SV*Lwt|k*u>PFDsg4@Fw=^*Ux{~Z>GBO|Ld6Pjo9^TQXa2doBa+B#pp`m36rx!M{W^#A>6aUiwOK;THTUgnCcDPs+9JG<}HYs z`e=cUrN;0xX~u}<*o1w4mc`Uv`vpa7f>tV|ZXj{Go$e5{`x@d=XrF#08$&lTI@LBa zwH!=zh*%idU=17k`OW|R=D%{j^Ke$7YwWGx(RYCn) zT)R9zF(I$Jle-3Yt(&YaJk(fo1_1OqY zWc#0AH_OKb{Y@CQ4d{x zDH*T6F@7ogB;t!oo%yT$lAFT0K=g=0waomUTF*o!vQ_XGu|~-w?qEW3V49PJHY@i# z28b=Hk7coVr^>#=g>c}2D-Zs^wap>iMeKb4V{L}uE_@*OHfsG0)CJy|#-KMn%?y=> z@4Kt}y6G`Wmmck|IqmX0%u}4rM$vmh`<43E9L~#~?DbL*j$N~RqrA_5bBV-AK7!nj zkd9H@ZR9Z!9&M)w7t@)!Ps8L{4rdS2Fx7-GX1%t2Iw*6&`(ok;ClIU|{%Y>b6qT3D zrS|v#pxQrqnTOMH4atWaS{Ow)H9f=f2YmJS@6!JJ`wtKM*YfD-Sm{E#2(DouVrJ{X ziH@Y)jj4e(@8fBG1I3;4+hONp^2k0p8~MD;E+`=6#Nll!Lg)sUYZZQ^_`H@V8$H3l z24{-JTSsOBsl@FM6%}|9n5f2?4=P-KGvi0A260|WyDt^;#A#cZS)T#FA-i!SH+7N-zx3HtSPp7B+4O~tFBe32Y*R2(K zviCh2OCNR-0~*CCm=V%;sOu)ZlA{tkLXfsdQOv9IcW>Xqkve>BH=g=0jH~)X*piob za!JPo3c4CwTZ`+~RY&a9pXwhX;l~1x_f3i%v!8QZMK43tAa<-Bdr1gpp8% z+onU=wb182(IsOu90+w1WKcu&c>6Kqlmi^n!b-8#$(F+crilpTKL*vK4}64aOTV(X zYvU$$p~~=SkX2ghLqNv-Kbp=xoaz7l#B}P8A5L;1GVse^Om_tz%LKM+LXmXl4 z6kT4Z0zggi zwKX{g#s>rkpU(Pwhcuo!YznoE`wGC~TTux)u40i0!e_OE1o0Td68rjX5D@5bbs{x1 zG%Sn*IBCHn>07^!Yp<+yg_uI`>gsMY{g4lf+37x@V9iS?DrT?TJ##qjH{k4c5;L6; zN24As%B}thD<3pO_DGGV+l<-i1Ek=_#$jpy(x*1r(EZ`989n1iRnGM+k18?x^6aGv zAduyN#y{)Zae&NpRw@YN+N3VoaX+<59=_NH5>J2#CZ*ReOeH{ayo~*@8Ry10p`vOK zFjFHu)nV**g43_$Jm?MirnK+a`=DWNne0i)8)nHLUad}cluUE_sihqq^W(mwbM!cmO?s?aIZ&^J^X{sBFy4{M6&rt2{(}Rhqh~ z!d~-hWELNor;J8SxF9G!e?w&&ng4=_J3=Kwl{(;K?6tL|=#Aj5nb8CviKA~Awj5K^ zDdFw~yM(-eBdZM;DNtVkJ8V86`2hk$5aLBsW{bsEp-}V5*$+-IGZ|%mAo%q2ixslH zQ$>IJ_bw0Y)}S+T*9DB@1y|xX&xUJ@#H&ws5~w$16K-lg%bZ;8O;csI>bhp9JGq|F z_g1+c8+GFkIB;V@hx7HmmL}I7VOcS4>19Xc@%;3`PQM+ff4P*cf07#|^?#B1^DB7w zaIAoWF`({*17<&>g^tWs&V{38a|HlA9t*rZ?!?YuEqA6%N&B-RYJE$;5 zIoTpg!4P3Pk)Tx1EJ7P1vX#29FS^%|gqchs(R407+3Ay-wXG|SIK!h4L%+BT9&g`1 zR~mte90O;hP#+JPGzF7OL9l}O@6o?_t7#~=PJiQw4jAWOqehB2seKgCz5dJSO`w8g z|DsIgQ?t20&3cCCW{TaJZ1NpRt-Co%70nSN;6QOKN7PaXE_My}IQn*oCP+8$rGC}y zl(=>cDU;Uo=@9Lq1p3P552dfO&IB3a4gv=BVxfhdBAoz-3#swHJ0}Dj78EaS{(#38 z#=t?_8XvKmqF3Pya_e>Ut8)WR7Inj!}4Mcg;Uh5jWnhTk!lQlg zkpS(zTFk+W(cc27z~ZWhLRuSmx!yI_J~8)Zv}K<#Nf^KFM-GVwIEjdnUTjX-e*Bs) zZ)8mA*ns$cVI6+-Wy^O%#c4|w*G}E+&xT?ygFHByOf~{m^w_q*(;551(?2`cZfpY9 zwO9-t7FzbPK+`FmCo(p_$6rNTf^7kO4Vvq{B_Z?N&DO0yTN{O0k^;v=Kl)!oizx6~ zxo0olP&o>J5+FqQ&KlAVScmBT>f&We*-0KM-15K3ml&|jh*Dn*@(@JPya)kvZ#e-H zi2H(*`SB+=sC=*rE7z8;e$LeU zFf~p@L!3|;1ib)fh?n!R=7yNVIp(%U;q_dw?>P>04a`8Ksi2@hwgU~?8}1j9BMW3z zx$gWgtlTt3oowjH#`^jgD6=LHX}N*D)J%x9Nq}=`3Xo117HpeIIj`sCD51!mkf?hR z=mUqLn&B`6;XM*iQeo-y$fNj=YJkWDgV|P<4LRGmUArCVvg5Di_kOLsx>PDhl?x`n za$XhG70eZ!7_44v4c5-;gu)nqM(m!s5G{O6d0?O^-b>@q^ zq9Pa9C{%h({+FO$ZnGLf>jm8Ld3wFS=O=w(umq{HJ9iPh)q8Cc#sj8vSRB9dfq&g& zZ4qPL>h9ELq{ajV0Z7{*mkef`D9@9G0aOJTkRI2r)fN;%XrlxQvZzvlUObhPVC)*^ zm70s<-L4DAG2|JI>!TgOj`hrxTWe<~LhLug7gd^r8NIO!?(Ui&3%!!1(x$X_g&tq7 z(3aYL5gwY{4m zr=;j#SF)!2-SL0!HoUE=v85eoz6I%;StiX6c&|*3rwx_vdYY7NG*kh;S@#_W!5~Ar z*{>ouQ$FZ^^5oydwuqta=*U{9p@3FflEY`DiT(|$0LxpqT$581Ywkfi4~!-K6&YWh zPd^i%+=c&B4+MO zaw?Fl}3M*5yM)v%XY zJxo2mA99?LxOWy5#euUuAFnT&z`1ZNvE+Kgw?3t^#=FZi(IpM(@&^z{^G{`q=zctO z-az=?pPB>vZ_pMM9E{P1eL)BDzOkrt*!#oH$nCZ$RT1vU->pUt2-pq7{p)Y8FkdoI zCI)5i)0br)7GobBU;i#1W9E8{o+#Xe629-|Qt_MG(cseu&z_k7>sAU5K_7b-S4};w zETtV~n?8R16zwld$R%)#ZPG*N*(`s~HN8P&kt@8T<#zqndHTD?wkjIY67A z4*E9K7q8xboM=o+$AEQKNM9B0oUr@GO?9oxp|om_egcglzcsUxa-{3Y z>A{*ZS?BUnMRS3B{Z&*TmI(~;ncoo9zTEmnh1C9z%W_jZ6t^EuwM4cmbr7hQ$^~ra zOX`L&)W6j;hHsdX$I1^;VM5oedN%_1p^PnF{L(@EW3GC?yW|E=w_l6Il)C2DraUgC zo^C%Bvh?fI#uNZcjCEs7zIHkvO?Z!Ea<#_zh45-(HB}$yk95^m{g<>`4tN9A-HF-@ z>FSKm(`Nzjv{g@R*J5_UcIe4D9?#*i-qi@tQ4?2yfgYxI;c10nb3p=@e1r7O# zV~;!;w(O&!gYWVrQya?9nB&W2PnF%ioYcHBwmFhsa_s2D1|ZKhtWTadex-VVzPvC? za3}Tjne-fqQh34ASk_+e-|}e+-P`cAOMpol{^pwCZ74){P4#(p?*qVj+v9HxUfd@*7>VzkIoG)Ch^9F0GM!5=DtQpfGRRdMC>HZ7FYwz{x9U_trf zT&|n63X{pTeC%V4#oM+|`RxO~!6kDc`dumy>H;Q`2QGOu6mfx`o##WR6nE3xND zim{oo9drgxtf&Mibnr1+1sJGx_SB_pIM?$a0w<78eOH@>ot%!%RTauJx+<)o{gQPg zD_4u^#kZo8aY4`Nv}XM1ni#^xE2G&8yYkz{?0`Xn zZFXH{L~Evn8*Qh;X?lfK`QMw!nw7geLh2H+kIo53>~I-v)7}JuzL0Kiy?J2iwZ68* zy+Vpbm5x*!mxzXZkpTDo%^Bs`Fj&)bUo%US9_awq;ytrun}kf7RY^mz&4CA(jg4g9 z&NOrHb>XbdWAnx~JQ5+V;9v>70|gK6xkTm%WSw9~Ik^1>&HvsP>dS|guViCN4a@>1GvY}7Jov`o zc~PNMsoS={;d(CO(nTJkaun{*Z{NDK{Wn2Bue1Dk7cSfOlOQXIIPEhBI z-AA;y^0%&1zS}CMQ9pm#S%{Qw(vVB&h=>~u#*yayd_ph7A|XTg!x8b7qvB!QK0NGD zKA^=E7<05jbv*AY2%t~X0V*HxPzfA8%O^$&50RT8u_G1MWl9Q&x!OjK&C${K-bbf1 z&pSC=_KkXwnL`q_d^dNY=N;dNuJ4T>k(}8*yZg+23dn`)HlbAZ?n4r)wG{h49{pM6 zGFWeE?QA)%$~mCAgj)+B7qA0Dxz+P4zUqrGU%UPjF#$KzV|Fw{4_U6#wN-t_LiDJz z-7R1AZh*U&E(`*9Z^8xPorU93r$wO`Pej7>pvf9TL>2KQbNZJ0RE>bnIW=oTcXm== zQnwBq;7A{hPPr|1M@SO;3vtv)6dt0PSSqu^KMdWi9?r^2&&flSm@ zSzbDx^{aNsEg<5B3;YgQ1Ak?ZeTbk^TOaY_sk+D#>q04`bS|}9w`BO=e0;Q$ ziF&R-5@ncLTwC*wHO>9|{P+{moO(T02H} zX89L(czR32({`{er!&elV;1@P_z9397>VIA4HY&9UOcVzr zbt+9PpA0yB;Vfc#Nkg~&KwnScp*i5XZgqw%#$ooCu^-w92Ax-!G2G8jBS{7?%(BTG z+Z{_ze9%#9CCTZDFK9-zTymh&6q;%x}tC@;jWq%Sp7Em$zMVk`rwRKSY~ z)VCTFpp}7qXp;;gzv35NLT9QHn+_SiDIdJ`p8=2bH}%@ClR^~Ao~dj7GK76$mmpTv zDbHfp)aK_A2w(aQ>Q^a%$+rbb8tCG~Z287@VYL1Z33_S7^TgA8TI^G&tC;o)9@gw4 zZ5{A`WA7Hx4MlzKI01zf6v@fUwbucp#EORLYhCR}VNF->X=I%>x}AP8aO0&%p%v>? z{{=Ylcn=P^hIcXUvU}osFmLPpxj|dMIra_r2u1fcevh)k&(d2vi(gF+?)X!;^{e%G z3Wufp2j9Gdfjwqvr@=`psT8&tl#zLf(79&iG-M=)Yl&1~DcK?Qp@f2hFw{tTiqq>x zT^S-X8BAD$OhmmsH}Q&R6e`}(l>iHa#;lBJq{iWXBAK&ZH+Zn`sjS#EdvdB*y5*@E z9yPr;$Bm_>UFdH~;1Jnp zf0dApNusNVVqY+){BYt{mbp(>mlH1nBKtNj@jnAya3l3+$1AvsXa%hQ>e?F3+F&#; z?HJowE9|J|$fuLTf5!W;Drr6*R2(u@elY>NJXu(>T^|BOqz1qu9PvwA1flh% zrKzj#8{I$6?0UeZtJCVyP(xWMnr zK~s)E{s{FEA^M%+`V9Uy12ed8ywkI4l|9*I!14;(E5xgS%+{=!r{HD=aC#<1s-FZ+=d^3ZV)7o7o}D5l%zOCd%h5qI5BDlZmPNh|uyN zL6)8Uj+UJJ?E$dI3Zm+IAX4vV*YmB?CwBj2(cc=mJ$h6`u9V1qFRQC(!OSvmNNdOr z;IaE++ZeL737lbAq-N04Kj1^XV||swLw}x?1K|iD8?OtgkWx~lK`OSG`a0Fhot7g7 zC)=Gz&lD#oBo~W?)Dla9I>ejtMO&p zD?ha#Je6{lym0{=ywdAKtC76BwO0Q3R^^rTq2U$UMB}nFe55yx>=p86V7xETY@qCdP=lNpDr#r&)@~Kcem{A2` zB^as;@cn#Z5n+e|_A2;_!9k(e-L$k?ou79K3^?+IU9zp*2k4Tvx5<*4caf*TE*3Ui zluTc%!vM>U%Av#WUtkTjH)dLIT>n^g*r~Pb^ZW)&W0*u+HWV??MMhq_;y$m*2P7b` zm~>FVF=fAej~qAHz1v+wEvsv717La?@3!&wLqi*@0Lj?f``>mtTL_<8BS)?s3wN~< zXZhZU8g2##Dx+hqV5}3Y@(6etF%h>*BFV|7Uzxs~ z9hbSjkgrW*@$cG!ht}x9jVb2B_`rGz%FN{CiC6-x$)mbs^&a6=%Tx1MjGbJ6c{U;U za>FnIzMC$2CP3*AxA;zRM^%HJY`Pz$3w`l^XZ%$uDnV9E;GrG_m;j5cqxu3aW8T&F zavrUipPI7m<}!!rUPuEc8?fNd`oG6KdKrJCjydu4OPOpvDBmrt-CJ(lxVV+#H?p*( zj#4sd`Fpd-G6JQkrl$M!2kVsjm^JgRb)U(})^j*_oD0Pv_i}#)glopV@xcDkgB7Wy zm*Vy?i$74S%iL4*hB-mNuKi#bOll#=vethc2mbAD&=?npi?x0IB!U$L-4%gbozMN% ze3KVl#ICV07K_IEz-|#}-DPZWfRKUEE=9xV4*+xWVx)&NXBLM>@&S50kD-@V`6?wFHY z-)Pi66z3r~JbcZLrLBD@bx_aKH_)5pQ{K^GH3-I-+`cMV0v#jqrp6%wB)wkhj3$z8 zYULzdDdbpGRDab&c7_FZ5r836p7c~PK!DkuTa82a7ROWQwt}!@B1hiis#(@1;gH#& zXLAM@LUT~L*C4NefI|k4x3dmtI5^(kpvrX20bWJNxVf z2Ih2v5Rw=_A2wg1jj1)=ajAD-m_zkYVR43OeqpUzGX?c8L(z7FPHyn=_MTf`@rk^P ze7H?lUHUiRR#_9WW#2d)w6+BNDrw_xDjBS6*CiOv1&JHoZ`^7N+01*HK0t()J&WOQ z*$55+P+`#MH-^ka43eGdai3I~H$bra1k^eVFbl!!iH#ZJ;&s8?C5J%NlNMx~mn?`2 zesfy<70#FRW#z8@0Wfb308Y!xZ`~$WhUUh)&fHrX&8=9P`mi>86aVV%yQ>RI0 z*LSPO)7SgB4UIPP^<3bvHF2kck=%kPsn{y!B7pn@5qTOrK;#49715FIr#zpZDCFGZ z1kJDf(D?30{CY8I^FK;F7|uGD`?(CDyvMx*I4muhT(12Ir*wkurT#@Q)xNMwEd{o( z&!^o#FF2&W_v$A_e*iw7`T3s3z|NhZVd(@21!1V~w?Ws|kvfK(u8BpI4Rh2ckYiF& z1vPYv5>YkNlt;&8NZ-ttTz#(RJ#wE=Jkh1-nYaWmKRN9lvd#De)o4fs&|DoY`i^q51!wSMbI-56C7@6EVgycIOzDLVqXhN1n()p zGedWPgVgF9?N^27Ga+&N72D>I;eI^{dVr0Agm}!{!Mf!aNx!NaN zd8QAe^(Xgi;@|MK3B&fg)rSRk)eiOHb}0NydRO-@<8VfWxh_6qN4lb^!h!&jNJ^n} zy9M+|CzQ$Z4SeK9(r4x5lS=V$uhh?+>2#mtXCwNaj*S74X}PUjZE-n6H!_18-mD`A zE@Z}R(}LM%sVIUwF_W{~5wE|tVd}oU+h>fiVEA1T{y$6p!1L$A*p_@aNM6 z-FwSwlb$L^WGvr+U%8n{%6kRD7KWO{agewJAG^pH_;O;)&=h;@Z)zp|fC1nv>qUJG zZakkbvpP8kR%$ED6=k%4j}l`bxUs)a8UCDB*!)~_1|??VF+D9OH>?Nl!b#he=`s*> z+a312*qv5cne3Ihxb|J|As7zYnrqvdYL9{9%XnbBUccC{P-qFuTovLElba;Um%9)o~FQNPl^6uS$$ z0LXaaQXpgHC8p635*65G&=52;vbolA9&k4IF{|uK`fZY@R5V7KJ(YM_8hrl9qQ3JK z(1ypq0<$l+AjIt@9>f7^fkjo8-L)%%VYnlpkr(ubXB!P%leVoiQ9gjymrW4yt?4O^*GUL~ zt|%gk(O;7r3MM}|CoTjI_^)?#Y3JWxZU+5|59Kb5LGTgSm2})I)*xXe2>Jr_ql|On zX9LVIukUaUYy@8y>%>h^4>&ni`1N@=!)BVYgSCS;RyzT;Vq!kP&U!|BCaBGzjh6v50+=gfJbhuaLClP6ME3dJBn*T zy63hR>Qz@$0zc!T|q!uS)t6!$>n>b%2CLTAS=e=~H+i1;8OW zrf*|ulT5P9&QUT}FdnRWfG}^@kQu|tb$slI!w$%|9Uydt*yO5$7F-*IDljm`$T_H=|XC>{1f7F57 z?@gPYN?j4~Jt^&*NLQ$`FRttMLP|(V9^EeDA_-15ct|iV4x8&*vNb*WvPcYux=~l8 zPMP(nbxaai{p9v8&~r*9fs@_A})VYlrBzOy92oU%DP%*IX;>+2vrayl<~RA`%M~ zlqs1DQ%6ynnI?~S6tEL8hJeKkY``%|h9`4@%hq@^rc8D_!wraB-kK8HL7VH*cQt+ml*}KIy@rbPnqorIc^M%*J=N4NEJ6ZC*-jTHd@N3*o@E7PD^uPOMbU4| zt6T>M7MiYdVm@_zRcqVnLN$_U#i?tm*VNS+C%l~kWnX)%|C*mJorZ^&8@eBcbVIWa zUr>PAF@-5hOrrRM^wZ61p(;@=)dvq6GySob=%@PK86W=s{nY&rJ93*uF09G>!AZmv zcbrDt|0=3;D?_kF=R_;zPmXvjU4FRkMbZH$U8orWnPy{;Adg;{ta&sFWXk4pnlMJd zg~-x}!Y3-{VE0b(w}OGY;6_38Z2%_uvHjiv{<0$w;UV3m^%z3>Fg2#S=!|%{SG4lu!SSSEgLXfLHykOMAXYq{$DwZ zMg&SS5;L-_7oJijm?fu%kdLroJ1l(tTeqc`LuI|AE=7QDA*(`o3tVo z={oQLls8Xk3RMN}co2WAv<>0bHkJ-eLj+w!O-aBVT1RvX z{_V-AO>FJeQ{mVd*2!!P+DgoU`2M>m)*&*TA#iA{nmk|Qx&w`Z85iaebCO!S|4dIW zZLX{^qpQtCcB2Q2wY0Q`J-EgvK-LY`)m_&_w&8F%T!Jx4$Uk zM0Es@Hmx%8)30bSGy#0l^Q((sjnKrWO<9RWBm5W&3~?B>w5$jbCgMnm=StuO0fx4p zbhypSOvISfHyD?7=2SE_IQ|2Ux*#2-`h3!niM7b{?SyuYw_w!6EPPY|Qml^HTS_o1-0 z$3nu;spkZZS*($MSYTDl#n<|Y7v}Qu-JyL~II@J#wuMP}xQ1XD>c_!%P&N(qV8zGEZ?5egGZe(+YiKaT;nJ4;-&^q4owiR+xrGI(&Zm=IOVL!6`qm zK-X^ALuS7MR6av=7>uLEi`^4GKYjAD?l*pIuWd(5 z=E%!u<9a2oOu!HJ*-{jwa}w=@k6YTAwNv|Gp@7yra69VotAYg71*o*IAz*&jjcZo9 zJ_7qMV6@cK!13putyW!#;H}!B+ZBL0L%np|3GtBBQ&gQ+KHmeX1Pcd4W-n%G2AoFT zBzG*1gS*@JE7CYFL`08fS6W`Ttzd*6C^TTBju^Tgcj_mxg65Uob4vTvz#;3% z2>wK`%0B7$x3s|BM;63{|1$uDqmtq4w%I`Up^~6(k$t8Zo59bh zNF{y!aD!)yxiuF8hoxzXu$$8ruNFGivX`(zJ2mP zmUO_fx8f9<-;pZQ3+~_@1w2iTFqvlLQ7TIRO|h8!VZ&RcSKy8aARvKTTJmtvFh?Ye z6RzXW!Rm_$4Unj%QYK_3H~{KFGPK-2CkrQ=Di-nV*zDAh=HJ{5xXDJPTcGC`Wo2ol zkviAZG&Xx|EU~5_`lbK+pV{V{KQ51_kxRgg!tyVpo=?4g?DQ1l2adNYT3`!3N{{fo zC{MXxb#gwCP_Dj_EA4~GULmE7m)AfNx(s!9@%O%#D;?7d%QL{<&GM*b=~2EM&k9}z zO_zb2-fsqOW5$hycfe5kgMaSX@WSI_V?B!Ryu^USQFexp9W!7g8&lQ?xC||}MzOnL zP2dwsvRzyauRBpDTi#cYN1U{+7RH~$?xa)=9xxEff25ksr`xXrOlmJc=l3Y?V!~V5 zlXM8q!t6t#kUQ8^E5@K~hrqG@v?t`MCxZGYMg7}0^uxmUf zQTzs|-(>Re=2CTiHDBUv<7!%n8gjv@-@xm{lZN_tw6s7!&-gqe5d%KH9-zwX4XkI5 zJ0{#B!dkur>6$hD^;M~T>#v%27!1py-3F`v4w@DKTyPg)o=|S7Aa(wvbbuFy65s5A z$^|ezNl85j{Enrim-v4CU~wVyfMQ!(LUZLQCXBuybRP0FO;0#nUN>+$0|$1OHn*M}F%Uz8?e z8?F@R^kwu(v{a=0HgL>v4!cT#Po!V^BfgMHNH-LkYr1m1^6L&sNEge?dT{@_h@#uGO`YLIaOB%pFwLUE;Us#7>=NUj=j8-gVYd(Y<0cCfv-7f@xKwj-99hVM+99wYU z+#)lU&UUdevy8cn;AI3@CV`}z@!8g&8}o|r(Ayd#;$RHm5q7ER5Xh=;Hv>crSZign zJxVcS%ky2@A;5{_S8ISc1)_!#WB~CUL47~&np64HOkXWc z-a5eSmXqcTz~m9dA0nG)QQ1(Q3{J^_ld zXEd~EY<2#z4>xAFZOb7ud?7PGBQDCzm%tB(H^T@;mAeokq}~%i-PmADqbj(j^1=!V zz$Sud!NqRJ6&Y%+aGqNgrA<7L7DX4SR7Rj4q9tPI82>TreFXer*j@%H<2}-c&clm< zMZ(~h?uC0DFnEy^We(!3 zXZrb3fW+FpFL;o3g`Qvud!Ng}x@%1`?FHmO0M3u?9Gnan<&Xeu<>kC$Y zfRNnYmomY)oQy`V(V8-6ZKI*D%44uX``lNSUshvdom-87*`VvQJQ#t`TH6?F)#FFQfx7b04j2MXQ{3(;KvYylaZz2j**W3 z5avKZeYIU&+b~lpin{T1AG=_#PZy5X7g)s^snd2PmX`kBT4PHFKv1?0UI;#spPv-p z>$X_ixTX=Zk^=Cj!<)pC6jyc_=FrW7bq`$`lOv8XlU%-@#IckT`yshxuheg(`N~=B zQOH%=vPWPoJWtlS^{4M?(ATA5c^S5_y2{vSn2`GQB52%_Db$|cgLqdod|mbcOOLU# z?HpoE_%On)<*%bb$O=LesSxkSkBd{CzUl^$vWcF|15gV|%WFnjfC)?@bLV~J5+C}Y zNspTg3QuC9sH(M7&Ax+5CfcS5eG{`ia=b!F_l~?$0Z&tfJWD&cZqrWpNqW%mCjo$| z^<^m1D@s{B?y{6nizuFWyCA>7uirWsJlkW(qX)Y zHi%sa9nb;)5^yKSs^BP+?}!7X_&~H{vI%`Z4fI}WhZt(r9b8bZp8LJJ{3l0N3_|JO zx}MCuOTOzpTBk_=wPt5IU2dD&NPC>iQOxnuSO`OEV z-I)feapeP_krw@nfCubWZ%|W)tNb@2X@<$f;`J2e4u~93=1A z2n+t^j)T`FBpH2dQb~W0xy0ct+2oE7&hF?IxL#x(myTR+T<2~bC;aQICDYX+pYuH@ z)>I|JUSjz{53ffleSXUCB)CKW)~=`}G(2nX_B}cJ!C9u3yiuugKb$d@vfzFQFBfl=s&g2zblK1Lv(nHu_!V_l~jL z$`_&Iu7WVZbemJZ1I#3{GI5lg?yrB!WD}+SO3U1T-hQ6H>5cXk`QNV{va~iJ{IK#9 z2Y&Uvb$2vm!eB?tm4$`+PK@#7@T(AwcC$E3#?P?)adF_Tc5iik#kz3(^dn&~GXcg1 z1kt;f+0}POaT0NDw(bNfsFVBwL(PZ4Ze?z4?Aj-(!>+V~9i@1gS@sQd25*zRmG-s0 z*RY=2>&`DNa^#!XO%M@8;wp`){|S*|+0u6J3q#?ExtZYnJ_Z3h?v| z{B!^Z>{6yTwZg4DSd!=ZKOc^4%a>b<;sV#}1C^g$03Jfy+zLMfJ3@<98c}4IkipsV za8ORk&OUmAm;TPD;Z-}EnO0?SEi$Lyy*Ak)@5yKqX60nM4;9QuxQcQ%Kpu!s^6p6b z)slY6;N=&WCr9TJ_S{DlutoJ2lmQp_`R94ZWHok9(oa>>SiurG)&z53%ktcuw@O+@ zR@TW}z!eW}RHXw9 zzJ3cl`6LHkm>1LXCTpq43VqO~ak$E)N2OzY?%%)LrS|-16S=Bn=w~;^$JU3J5gSLF z?CaP$BRBGr4KPpXd4CI4@4y_}!N@lKiaTK8tT%3PC5>gGYg#DDPL{nf-$Y>;4U?U< zAzRINgT*46z2AW@Xzn}kWdP4LPm?<>Tn9_f?=fO3F>Gm|3Jd4e)j^z?2gfmn8Vr_u z**yj!8rPQH{Rb@8C1W@RI>ixamYr)E9eYq0UOV8ENJpRSZfR0;zv)sj3U>)-`7537 zYq+}zBtZ4_9qy_qO!Jk~1pgl;@lM=l_m z#yK0BtcO>a1+?B9SU6(^q`1mZS zj{y-`bYY*dt6hJRIrUMcAyy9KlJvmqX1#lj)roPTqJllJCPZutq;}m}IqXYNNu`x> zMtV9JXL8L+J~73e(-ds|qKBZoBwppzm>!_&&aJ_WprT|?V;j`I}hH4vsyMq1v z?*gJCHhb{9m5iVR@*$W40dp51*8yf4Ui_*}a9m!PO=&9n{N*ry8M)|%y z6^JhI5FetId_?$i^Kj=tAZDP5@p(Q3Td13V8u zRvh*$PRT*Oc=-_>*3k(x1p3f#UWFGGq6@;kD&nntTn4jjgaWjR>e({6MyYsMQN)3t z%tg_r>!p2uc6?g{k{eD#m870X)Ft`}Vij|0=*Ei}G&N-PZ@x8W_=8!6J&o!$s4k>$ zl*(eU@Q^0l5ovB*UL>EJ^VHu34Nq4fETBxlmWO=EvW4y=cqV{sq-dPF1?0?6#V>%< zpT8!fOgEFW4dS(Ztx3uF%F=_O(2+Wn=Y%A%^L_HaO$G4ij_~mCPCr`Go>osyi9kRE zVQDZ1rlw92WTTE`D|s@I`=cQAt6aC#)y zC)wR^h)f{;O3xTxYXkm}#x?FHtG9C<_zy5aluBgygmxf zmAI|qE&->OYIZ%2C=U+@J1frPN&0Z-?%YVkNWF62=e=QG7)r9Srz7+9>a zG_>txQ|$UH?G8Rf=iZE8%uQmvEAYsEo03vloviq~NEfz{xZrSly2c7VIx^z$?wSWz z45n}lj{4>&jQ8}K-RzEtyRI1mT+{;m5#gHhwZ%pWBCuPuKJ$mV$On${CLqnT`3Hc` zRLJDLKudWcVa$#_NhO4W0N;9h_mo( zwv{iv8z@Riqz`IaV_?PN+}o<2JHpvlR#rrvcN7;RJ_FtDdD$2+UlrWA-|R~NVqp21 zMqqJiw`-Wd;{@BwZrmS{eN`YF*nj@(#+ed!yP7KUrlsXEqZ_oHu(x-BVdRh^qnDU+ z?2|_|=*>2>`%C!3dEh!H9|(E(=|W(LGW8e~cBA&u*qdT7kf%05vb-oLfTHLkiuyqk z1Z4ADvD7jDGg)zQE=_Aw&O2b|dMaM01#vmi*xMQ;#l{{+Np%ogvk9n)LkX1RwQHAD z4#h&S`-r6YDUYL+@8dx-;|{pbX@T)EAkP>6oOV9;C!gT7s?$5WlIe`h&lA-)eRopj zqDBXP{wyRP?3hXh-k1f}e*6fyMXw(^R^efL;f>0}2RF)x?CtCVMl#4CdURSM=6YkW zaH4^sjt|E#X zE{NF{NN!EVWd+X}+5h_cykxN0RTKu(M-q4u6|6&JgL(HMpfKEBIf#ffY<=NSB->F% zG(f`d|Ea06_^N)~l8j9|LZvA>SptB-M^nKyJ^t?Js-As&7~wi73dm?$v6b`Qy0K?} zRus9vwoJ`?a~W)-uE?_kp3A)*2N9zfBTb5vrL<8&(X%ejpp`m=9jC;bo_CksuPb5z zYpRn4VaiZ0v$MEha=SfWq(==j^A8TZS(6IbmiWhQu<2+`F=}$!zPxL0wO!FQGz9~` zL?dPu>`1O}@;-2;T>m`;%3tf#S5NgDSY92GAvl5o z&9#B<3a}i9DjbW_D~#b54|9}(qINb^g{J?7PZw5iT^8Ls@@Hmdk!_t6j}zd5h3l3S zxP@Yy-WIr1v7wj5Du>5)MgEcBK?Vsq68<#hW;psB!mYiAU6VaF_Q9LPS>N=2$IH@- zv?}}nuFxd9{q^g`R)uRW`6fMx_KrN)N?mF+#*lLEHPyVVxZc7Q`KKzCT6R26@+j0( zK_=aspBrbhJa1-L+e%7gHQZeRL&P*aNaC=Bg0aUP4@s@{k(GIQ!?AAgO5uOhhTKt4 z0~yD?GEP6(_g2RD3K?t!FM&pgW5`I66Ey(jbIjW@QSD_EkcNiPfaVBhYsoCv2?T6Z z%+gXO7fGN$l`={)UlPMd))e9L$GSmrK9KXoyeY^SBdu?I$W!6jg`&#srZzXzK(@;V zdaMA<>%DFyPi$?&yVrwsbyUpXB!Mk30a55$&BpT2Pr7sGmP#_iyupRPR@V5Dyzkih zvunpv{7#FWUAk~P7xRJqY<R4tG6dt+=q{zxb|1C%VRg z4|o}Ar}qJLHGZ^zmyFE(57DWN|L~xVHST=~aiM(OANO$NDE$|%Zt>UdiGM#gSz?`P z2XCC4KhiM|rbo*P6keG007cx>&KQN6t>x&g{f^+jj?_T#h7tQ|s)EFR&EUD^?(w74 zc(XD!@ij-!`~Eu9)BO@~_9>l@xbiE2rB_Awq&q+eN~D*2l2?_idA1T527ZK6x1rUM zpcc(8?ak$}4{p*i07Z5%daX7n65*s|D%|pl+u+K?nI=l{FrvLE64-VJSklM{;I6>H zV}w*>$Yh6$r&XbooDH0df;ZQ9zMvjiZRKpe(NZ#g4Wd*9leJc2deEni^)KSruQ%R@ z?#=&Bi|**)%CW*ABO1u&;U=^RksnH@Kkr!L8j0M)JWz7dIz^wNC8AW6z)< zp%zBKL_MhiT!`zEKomLq9F-v6bl1Fo@z>Y(`!8TcU%j70px*67`A|F5eDqdDPv7#$ zoNS^k4{Xg5XP5Cgr2`PCl35g1`jpoG_mJWcf|PBcRIC{c`2uk_InVZxD|HcN{F2FJ7JbZ3 zKma0wc>%^74tw}Uc5imY;{Ey0Z((73&)kxJfW$Q0G4C!6ah#3B4Z7LZ@-$_ygnx0T z@@`iTYfNC#6ye;|E5in58tuv#Uuhkxr1P%)Y(mRjz&0#_E?1`TKt4fu22lSuTIc+Wy0~YjKSm z=~zQ3WOJ3>(Q$lut2=J9HDtN*SR(kxjGEPsA~o1c%nc1r9n8a>qmyM+jfh2jt(b;He|f3?Q|MZSOMhR_%V*(BP5!8z7@W&DYjl zMmkpnT>)G=6iZ7-Dk%3o&i~|A3CKFt)z!`5s5!5h|CIlp`~zQxE;KJ2j))!e_YPH(Qyb1yJZJ?p|950CaT z@irj`-^Jg1{4eeX#EvVBiHKGnJs4WNt-*EB&Guq`Po68H#oX29pErn|)fkV$H&?PY z5W2PMEv->?gKoWRY$A;4!WHDweL70 zKunSMejIKdmT9LMxH3snrJe~z+=WT#z0by&^q57J_w1Ey0nnQ#-ChZv5{C%DUKysl z8*2U@7m$i=ue_`fSMl`>g}`)dpVRa~0CQ!8-ec#9g9l;FYik;Sr&v@8gE8Jcj`HzH z+J(BrSZbs1@C^>$9377qY?yD3J}3{{#ZV)B&H?Rkq^_}Nzn^g$>|DAta%`lY+!u6q zca>pQk(K=Q|D);LA6JjkzWaVY@AvEVe5$IeUp$1rribO;LdPw_ z4w1`%3J8N=%mDaEMI&dYMZ~W!YJ@8>J%J zZaf0ndP*J-qazvX7`}jvJ>WG(F$K85T9yhUpj#2%h>p*tSodM+xJeU)AU?h|8!)Cm zDf=<($-Jnf0+Ci=@vC$n$L)jIkuc#yL7@2a$@RL~VY)vua{aFe3aA2e09rdXR^MQ1 zaO=dMUn*kxuWq;wi=+#@1cpX<5kT7`u}-x840CNk@8tYfexYEikbj-7{AUS>$Z9(O z^j~D}WB;#z0{EL+u+GUv`G$=|FRQ*~Tzs!e^wl~04;H^{tXqkEpu)5`8DL{i25Jx| zgm^RVL^F;Y0^6RL$Z6MizVYfPW1R&Mv_B8LgJtutjn7*cp4R&tto8^31!*NDci}-g zOhUXFz8Gy+q|*pOcNZs(%uho`U)YAWCA~DQ9%K)NOb(8ZUPDO7zF!=|u{PP_(RBMC zrdc39ZY~T%;iF}U8Iu%KcCojS@R=}Y@;DM4bsW;10Jr%({g8p!EPGL^jatjDPWs)h za)D1X!?{WT;6BPcwM8V}51k*@>sB0lMq8nN4duv$Eyz$tNd7 zOv3pR-!;9*a5`lHXQFeUIBii+w(y3@5zAzKS#&lCxC??b^|vbPw~igZtk_z#vnXg2PF96n;8yh^QM?78n4QTDOczfB3H43MjpI!o|HMQ zLww~-Y!2h}gVDYYG1NDpZ0KGMNRKPWJBYNl-BC#YK|c-~%}LuFFWn)2NYPhr2fw$f zu7v1(2|Kl?r%BXA4_TUb9S_L*#qg{Q#-7Vox=3!QsDD&=)X<}m7qQwIjzjCf zv09nbvf0vSD@pccp1|KX?_*f7ixa)nUV|qFRHlFIX#frlBlDUqE`n=?je1d3{Uo_* z=eO++n?d^fz#;v*jsW;q0p-R0@Y>!;``gd8?|UG%$*QtS!=9(>=fAr`i z0||#nLie%LC82v@ab^K2mV_m=G68uRu#!J4p?(bxYLIhG88s~q?{bV1q2fP5si{(r zC1vO!+G2u86RR0I6$ijW$JsDv%Zw{&L7vaSRtXG+(eZ?cvffiru`6ZEXD{D2KB?KK zO*w4o5m!dPib6XgQAe(r>atW5{Fy!%qV^H^fFD9UI=;23rDbnEk_5p|4IIJ4Tg#S5 zUf9;+^bQJofp<1|i8)M)pqhh>0h`sNy>?Zw(I*W)MKDV4ZWnHYZH%jLxcL1HneTTF zu)HSPLagkcEm}1{&CQitQ7}E|Ax{fjm^dTQ)Y%gUur4<#x!zn77RGMJM?3$FwvFcl z99m#azeYG*OK+NpFiBg$^)mQPA8c710UFo-p48K_jxa80ID8k^4s~C`#XDLCf(#2+ zxMp9j<#utWQ~J@zKiXZ)5Rc7IJt0I8g^0y>g6@%ie0s0g@qh6|c+A+BW4Dr9HbzJL zgFI~;K8&Vy{_!TvGzGFW0kDO1EH`BM5Wc$Pbm6J53bI<=6+m=U=3{fGv(d2AEZuHJozqbK{pzzZ{S|pg zq8=u~u)FR<_0Vj*`r4?#>xN)yTFm&5#~&@5m5sriY#qbzW3x+fpLp;@@F&~XGUKFf zniIGxTC30DW>w0DJjN7X8|53ZGQ}`-6iG^VqduSFTAYn82=xTD!f_nm9!G@zuhlxN zlS;Z1AUi)dtqvC4Wi+@w~hdf1nYwB)9n%LZQ1Qfqcr;spVtjcSnjS~H_wH>oX zO3N`>ux;a=!JU&E^Gp8}JIV>n%8;X%?F6sDe>etsds74aEzUZbgM^O0SF%|)Sg;P- zzkabk`(HxR8W4+41sU-+{=B7+(LjRWdZd||E()fVc5P&jGuc#yugSOSbPV^oQ@PC~ zNOVOP3Yz(2)PE`p)lpt8XJibRa7+#lHXd=vt$5! z|GRz73Z#3*$I`Bt{HP4+_EBGJT+Je%l1#$YZT#tE^?6_?bK3~#PMO~^CFr~XBSC7;Q=%yS8O6De<#|n?ZPY31h0U#a2>$H{2DLb0N zu>39}LC)!AYT+ir0zi5M3X?E^;y2)3fAo5@QRa0psJVgcBd4CqSci-Df~z80+FUq- z2zyg-3W|b`{QGC1zr3;R217YgFkO7s?*dJ$}m#g96|8;+qqHyJuGXSMS>zIuS+OWaF^V zLlADd7EI&VG6O}b^D{x*a#NmU&h!S{Om>6;nF>(FIMR=UG_67mcr3_RJj`td1j8{1 z?eB_l6b1e3FgvCq;5CunJeMHdZy&=YZ}|gI^v+=AM`8frWX{UCF(h1c&8mTdJ^z19$o>T^d5StYYT3oY{h8 zkCIYedVYRkCYx2gvD9rV?Ggb`GsqvuIT&a_h$6#7Ltczg+f7#3WL!tR*@S!FV|bAt z7Zkbapf*Xq^lMmHR)WD5E{aWl&dIa(6zx(J)Uz5v5bdM2 z!@fGF#3EY0p|sE~ux0CW{F>J0GO>Fb-@4UE#bBUOO(?^}@R40v@!AV98DbWxD0V;Y zXszuT<4BLo&|7Xi?}A}u?BrJ6_ua33rF5bWSZsuCJ`%eOi~0k@<1EjRdl|>szgB*N zGY|{drk{DoU)GX+40$vB&;i-4*kfhs24x)kuCE-rCgG8+8!v$fT~xj)Zgjv0mF)- z)A`0?3E4OB;KUNM{R|E4z>Ytwi*`~0} zEHsh;%Pg1U)boH2ozL>0IHiq=JGpUXjD+lov_tp^Z_2gY8zQYk)qnhhS7y(_K7yM^ zlBc6f_XVy`kWXG8etA?yHQCd^&tM#P1Wz8nihWn;3QSE?t?HZqF6=~OQW!^uYd_E_ z%UjWyS4Pgv&Zg`uFQPyTe^Z1ztlDZ;$*u4p>Yv#5sMy)FV#Ve%VO!Ll3%b`G`67^l zDNe7RX0fWN-RJDA69IXwX}tA?--W7xXF_^86i5UpP>}MChmPgGul^uO;`S>fWVK~mkU{L&tp9pJ&!Hu$4OI9q z0`Csllp*P6km2ZKeL7c5{XV0W_-n>@GJzpZGC}Ce@}lHzL((U;5m!V%5ty=sqD5`9 z^X`Q?PNWtSQlCjRkV! z=mq+5Y0RggfZq=*-nLL!2 zqU!tfv{h9q<7mAWL0(?v{p?C+h>1DAK+!m^7Z`xPWB91LAwOpr#^xBv)TT#G3(1O1 z^3zTG;j>lPursl_S^MQcp`wl*Ha#Kabsn)#(MtB}eTwwfPweqFljbx@h-7;bF4@$T zz?&&&M8;;rtyrFs^=?cMT5j@)72j-22=x#0X3@YFeBV)`?=Lnl>QlAtr5z`EKK#pT zc=!W`TW1ox0Q_sJY7K#DnPsq(sqZ%<*5*w&JOI)G%w8)nlY;eeiE zV{6?)z6Psb+~&MU5Z&tBSzRRb8J$ep+O{x%eq%p(Gw!v4jPuc>7piU!#I(5jhOUE4 zYr{szj>X{~>gv$W^m@mP@9QJKx16XKm0U7}#mW^&5k8$*eFfMXGr(s&u@Z$gO80g# zxwlf|JGFXz3B1jubKs!o!X z*@BQJj2*ddRqvgmVH|dJH6;(6Ex&pb$lfI-tisgOqC{9I&%U|hayhZtSus)3?bxuD zuNA#fV1l|2^6?gM7yE@>;v*yiYbrh(?h1b6V;EJX^e7B;>Y*QlpoRUERISsPH6lb` z!obPq9glklEI0r+v=5c@yajs`-f9WBEf7jTMy|^+Ep^$-t?qW`D(4cxz$L`X3kY$J z{T>cp1T1$T*}S)JXQpA(mQxv*?XQr!4+6|^Fe^7?BN0KQqfes!M=t4TS%o!R@!T9&F9usT!KurXcO8QLKkT5e%Q$XsN6AR=oQbyy%U4iDbi zSiUmM8Is>#@$9a>{8B~C|4S}{jAgv)Rnd1a`deEPS#oo0iu|3S62UczZ&%b6;LNoA zwH#I)QX$)C+`&L&1PKpBbi_p7Jk=J&!#3a|A0dI0v|iPCj6_sr%S#<%ZNCTTZ$c;C znf1#PPY`3@e`^bAw~k}=CGz8tob`Kjv?IC1uhm#Btn8=|VBH4;RUCa>5E#~jwa{3h zeEIunMu;PQXMIFxAMId%yg~{j{!GH$j_oU8UXXKX}yk?`%xf=^mtAb zj>p5?nP7n#_Yi(Wn=9l$I$RH&1Q6Hp;HuuJXk1h8*5HHt6JXPKemBKLj)d8R#1br% z2y8Ilt)7?&ZJZJ1?gBCK7+~L;?CTo_m>Vj?RmSIj{bz4biv|Kri8JkBaFpCL*wnQ6 zqE!4-QrizsI5uEo?YsQWECK($|1ThHH2o~@6BxMr?gr#;fMbr(UTr0QuC*QgET|Bc$Imc~}Xn|?afA*EuH&XTqjA#8?Dn8hVY(iUu z+*nF{6GQ_fJji907n9BQ0(+gIOm{&Mdv;cw1S+?>$)CdJZFejY+LSIuecoJm=DrbL zR6w#01&fD6(uA<&k5M)$o*wMn-hfvLraHQ}&05g(8DD*j&6yWrOWm&(@H^W{2{rYp z4Cj~M6=PDzO;#kK5a?5_X9yv|G$-J(1%oy}phI#G*SiJL2*0KWM*mQ6M%_6d8w|O& zOp|$y6mNJD*ShG?FsuprL;VZ>o3+36&Mo_Sa`~47*=A-(I!AFa&+?>p#f~jnx^Y}x z?f#H4oKg8NT;GGHGWS%%>6~9}552c%FS5Z}tH==>Ooh04VKZfn!c$nP9oyB{VHQCOg-Pl%gmXps%uC5#DBy!G?6 zG63{YjUTUc?e58(CA!%Q;ti|;mfOFhr7&~bT}<}D7*p9oe0cW^I}Bq^iB_b%~B@aL(D+5&N3 zKoegEH;i4{cENNxI<=&Se%HNQPPp}%w;JE0Uh`9jFRvYO=F_;*cOKPzOc?KP0S@-m zHiSkr_Fkk1&FUTTbNM~0b-v4VodAkFj(&csy(=&*C`fpIBHeFzVd%sPkB%(#TKp#t zCY|A116-*jA-%cje^C5;=1jY)v9f1;D~A&Vxh&Gk_`nX`3Gy8JW#Dw~C_sh`&m@?n z1+O*zM2a9&jx)Glp{U`Q3sc7*&S3eZ9*Ux=5)17BnE;amzli?)oqOQ2Aj(CCDmuGSS8r1>c~ zw1ww2m`h!)ZVew6HZBSI8BgGP0 zVDbCjB8`4ZwwvEL2GuLH1ZHhkc7;t zWOG9x5prK2Q@U_?NmALexvVxXf8z^nBlr?s2v(qakp9H}ZjFs5@@7w&du!+$gmK}3 zB{=qR*HU}wWFBYPMsPkm-7aqb)0KyN?yQ|w?JDfh(co~L-gQ!2U`>d(H&gM-Wmx9Y zqt&5Xa>?YfhApNoTDD=ak<&SUb*}1aMm}n-b9;?BS(7V{_pcts%$Z}^&>DI0m{+?cUZU_k`ZU7UX z;#V^E=}6^FX=w?sBi)Mrb`^3c(diW>`^PwV&7wONKT0C)r~qfuKgo!y6q{8NP7qHR z4=+>7JGJ;`*;VN#UNBtfh@gR>mTmC*Z7TvdA9PWofmy_hax^J0ah1)1H%7fI8?oLh zE`PvqDX#S+*)i6|_oDnoS}=SR1;;Pz>yHzsL$^jWkvfgYqj-elJJ9){NIjt_Krt~U zy2{1*Te!Q$-HP*|^?5A#o8GFXb47a>A`pOVWhZ`Cx+Anfg_SR}!X?EQDNeGq=}i*S z{NYnvb=J@nOJ;1eJy3}Usxm8mH}~_Y2*+o@2H29tYR{VD*vQhDGetB;0PNWnwEXE$ zS%b57=|Mmg_S0RmJ&Q!^6y(CC8W)|%w{O`C2oh1`>@2}alZdddLF}}1bl@tdn;@1$ zjAai3H8=`HYiR}Z=V&!1DMEa5E(2kNKfsNc$iCu0Acl!*!Emc#|y9t zqMSQI!tC1OunCd&xQmy37+etkR)Y2K-T^cigG0hggwX_TODMV3uGkkZ{}9@-t`U%lOd;=oo^(e__#4vnvjC5 z3J`6+NWzlrs7$l&SIcm~V#k;h_#Sx&WN5IFC$*Cm_^^<{vhVat(__)WFvKBQFw{zP zKGtYK-jfaHc{=aDpEA6TFYCDk$p8UgCvuROYWPcxz{fX=P8AuQA+Uz6&Da;VVO!l| zTNW-eX|dz)S%9bu(m5c@d=AXXX=5gcE8o$POiq-%P5u7pW|M*nBuDK@cI+bcB~~_4 z)v)e-FOu<=wsQY2uW`{T8p?;#cq;e>=>!d9XD5)88#a1Mr>oUO6Nm`qGYs?CstmQ? zCO>?vDb2vhF>tSntYevRjt&}|g$0aqKJkgVy5I-O>0dI!)}`@l_iSgwI!_Oz%$Kni$!zcP~*_Ehl0gY2l$U}NJ&7^a+ zV45TvFftKEo|`WIeK4#@zsueuE!D9IBAc%a(t1P)ZV&$BM}3r~F#rh0C{d~jcYAn< z_uZJ3OO1w0$oyJ_1W@3y$Q_`J=pcJ%c*VM}j`PnlO$R*Cxe9^xw`*62sH_V&Wye3( zfS3b2WXYskQQL%!zgG#yS!hacZ&bJiLNMYOJs?q>ueM5Xe6d9l+Q4M24G-d@c@<6*LZ_&|b_uB}~?&h0tr-(VpJfz%A1jVH_nS-Iuj03g1M zgz>lFbGx}cs?^~PQaVGHw*Wz3gHKaP2F!y2u^r?`4g%rlg;aAC31>tx)lGb0{n{x2 z)~NCApk%Ywslf+vG*OgLnxA>Y)|$de^xZbtjqz~QshF;HJCUDa3Dm#kJ%NKXPTrG% z8^5&?L@289Ct6S&C|(V_(S>8UUaMP15N~!zifc zHH7lY$n3@+&hXYX{l7)tqQ{S>2|Pk9SA@yNnycb*c=OnMu~x+~Frcd_s<$6p1+&fnF%*9*;^y8jul;1r)W|jyYw|{kJr;HsY`Q|b+ zZm=76ir7Jr%(9ixy6^OZ_$B<8Nvec?5q4-jy3B417fnRMwPf;TIDfvafXP_BH~#q(n6KxMp^>InpgzFeqxUz&Uc1T#91GWxrJw_iowvAroB0sjcEWdpHH z(7U)Ye#q?`ztQLM=*!_)CHiGpx_6p)?u}iY21q*qqdF{;BDB{o4h-T+n0P`4@KP1i zyo~_fO*SUNw19G)^s-Zi)p;_W;C9Bjs05To&K=>ltH`9-q`ltxbD_Z{CDJtIqzH;K z`IuH&P%t=q&HQ;+d*uClHBuc(if)|Q?QJzEvh3~@bMbc?^h$VXhe5)gh^LEa$OKA6 z=lNlu)6E+1O2p98Pzk7bV>H&O;ts`?fS=P%h66jnH_eE*O8W@^P-{mvZ-#BCuX=p} zskTShKPDu&L3i`q$Xr$cpAX-(BAy-Y`zz_;{JuzJv4fYa1nHOy!a2D6(G-^Uj3u>zcudnibIvhfl@^T67C?E`_d@iB}MJmFjpyt zyVnXP2&B#haZMB-JPy+FcjDVJh$zi!zLiM|+xRXZNH=Yd>Z}%vY?=of+P1&zfmCxV zu>_vzYvB0%2CR)_r87ypfe~?k_8UJq6t222-1Ip1IR4rIK5-2Ka#o*4kIz=R*yhMlb`kqF*T_0Ae43$V^RZ~l9*JpH>+Kz$R)@n(H_ zju4~o_pOo?2qK?y#3HlgQY-gBD2}|~UJAq>#1Yl$sE6>xqb*J~mL=xQ86}ck+!M^- z1jAR(#-g^hYtsRiPWk!yQB9$sK$DhHzqzqo_7@`^m3Pj(58TABCMjka#EpMjZCsZ# z1WKLK?a`Z3V*p-bTj$R}TAxYAjw8ST)T>OjMs=&^b(jH6xpFWN3_zKX3SxleWypf! zV?f@%WhNa7k+@rIZY4<$K-do6KB_&qe92zWv4~}b2aHN@QSeN^ovBvs;E&ofnFj6^ zbmZw=33_@N<(hj1+(9W74~qjP9};}~5(Mn6?4se*ttdmG;`8{=maOzt^Fsu3m#at% zKna(YloruCS{AlvW8hY1&%H|u3JMET0c)Wow#z^4t~e0xX-1^x&2Y-(+Dnutus1bR zwg0uXJVpi*6!FMIM<89j8d|Gc_iwZZ8uOlnX^KUxLi|BW(6OfJp|{fOuW)=o@lK@W>@-<6T4E%$MS@%MkEaS+85e=g&cFEUT?n>}wOL)C5yBlEK^r<%{3GYoBLQj~37ZGBsItY2a+ef&=q@ljHQUXR z*5RF&;mxj~um&490@ArRU@`>qO(lv~&=fGz@Za<_Az9Ja+esibN-e_Bzc?+T<3l;j zuT<6RR>uenwJ(1pMb&Vm#$*aXcq9a@WvJbUBJ4z3K%u0reC21Qz$(j2!9C@nwkqxl zyr|q@sjkY2W_8$c9)N*ws|7S?P1!GA>{yRDR6Xdy+c-ISl-hG+X+VW_`F(wT3uQ*2 zGq9#m=8)bKq472^-pf;*p}Xf(zqV)HA3EyTh_v`-V#= z(rv?6Eq&QqOj~tLJQo0KpqM3Y4UtxpxzGmY3&-7e%5q2{zwsv0fHnDz9`y+ILl|98i!S@=@mx-EwC>w0 z257ihM3L$0m7!MR7v-CJ;GqF=po`AHb(9HKWOPY`w+i%tu&}UFno-y7s~^A)s>ZrK z(V2Zo`0-_MaPr|nC@ogTEDl=pgPy&aW+`si&HrITHmUp8931Ql1#P!>kULm z#7IUwF^RD^fC2Dil?vEm|la8UjVB6&_yL1BzJymg6#>i7zD&%0p}_bR5G{GY{j zr>gX?0%vX2UWVX88^qdDaF42L;6PRA@MZKo&ik-bo>y*QOsXhRclUQlp5d9xqVtGJKgge?w( za()*Cl1*DxGaL&)mrYZOu@iYLsPkDxpSOkLhZk(mdHU71{tZ_Z-A|J(c!!*CsTOT= zj8IXjH*`@IqC>cvCG!vSUBeg9Zts) zTt(WYF4-77qj7;i{ay9~Xn|C^A3z;%9gSNL7LC*x7J%cy9P1-;4~lP(QhYXu)!szx zJ*f!8v+8)>uv7?SA3JLQuEfu<=TE?pz@AAm)~2Th7k@L=CsAtao7jmHT##Bn`pcA3jMmWwR9I zqeB1dJ?)sIL`+%9{tw81!|r=YO@w2RoFSL=mS=|@tc>~!eU8ht`(J*^wf4L7pp=No z!1Cc-Obi}>m0H>*C5<$0|8%!!^%7~$uIxY1Czd^soVw*?8vwFK8b}Fp+Ume@mWUP_ z#yuZNu@`9}cVzNF#K~OYU<8KBRgCZc?e#=fAmR->$n6XY0UtwY!6~}s^+BE3THGZw zhsz%q!*98X%!R01u(OLqr0wi~^aK?{HNWWvU|yRq^ZV~GF0w-xJFf$A5Fe<#0v_Pz z@^WF`3~rJ?0;hX{IWs?Bw#-l#r}#1?$s`K3{Bu_Yt6Hujxx*0-9SWjbAhfOfG+?}_ z!XDrn$Yi6INZ2oLvGhP5%&8cVB&~GEYC)62yKph!WOpGjp>EYw4&JOeI!Hk>_Dnvt+AVCgC5gwgjy8NVD!{@F&@g8& z?oQ@d)lOs-iB3e|rF11I5~%YZJH^kQ$&83>WTF`U5ass3A&C07?kp?Zi!h^KWPZNl}s?}5BLviGTj zk}S*m{42vEqT%%mhOzKwl9qil?(idu4qZbe^0xlF3N;X5_)xbO=0+&;Ui|xScDb

    b(PG1kh6A zX4i2%;836~c!fQ#8Ri>!ha9}QHuI?Ik+Isk8FD_)g-%Q}bjH6Gk5(2)+e@J?dq_{b zbZ&8?e(>`xeJAYp%c;g$BU-kzeZiydZy?tCixOuhwBg{M*_`%qE&i>o#aJTTDAnC; zuWnv(Lv83|^eWteJ1d$%9;kMrbUIN>T#haV44+T!`~&dz0&Ml@@ihRNFO}(D??}Bh z{&00j#hEN<>J*@ZbgyCTxt5&U3w+smmcEL%4-8N2;|hmE(7B1G3@7SxAk!y3N{VmK zqzL}AMJ)Qjr@K^}WS4>7Ansqcj;^9LER&b4nH7deZBD@gWJG+Q6h*Ixd9V@l1n+#K zdA+4&-Iof?b;4I(y-1SkwD`y@IjC>0|{D@^iftC&UgK z8Ul+maB-Hf0D|x(8Z=BwSXLlT!{VqJUUw_5I!VU22lV{tN-1GeRW)HQ#hHsxd!u8L zTKjt*Xxe~5J#~Fzeeq~)3xLgtLvs)Pj7he5-^<#icY7AURTafhBGzPxE=|5I=rF)VT=zV{Et=@`!vG{I* zU!nGv=R-gdRkau_`9tmZsLCd<;+MuD@D&JLFSZ|XsJAM8s#?Mj3$@apyq6}`F%zip z>Vjb^{n*2w$2!o>NYEh>5MWmBg?!xM>}-TBW6;353dgg#w60$Lowf&PX_Z0hJ9KLJ zea$U1!$XmR*?fY(;`Tr-jvFf1ynla{I=0bMXcDs-Cq=`HocPk`$3n+Vh~G@@`L=40 z2w>+v9k>e>Jc-^vCSk0MGP8a?+~Bu7efS^_#dpXdE^^2j6v9oVo=sJ&etq79ZNiyeSFF*5yU5m)}7}Y_o#BDNI(}9nPxRJuKLPmrjp=mXg8m+ zap{E2e2!cdr!yEt_%x!$p^JazzLrnE__{k01|aG>0X48^3-cg9{Py~Fx}xFo$Y@>O3cB1m)}qxLNY{NdsN*b|D73BI1}TGJQ5X^ zS|HkNVc>kBs;V~y7tb4xYWz4L7lZv|&guhmn3!Cj!WpBB@{|}tJ$UJ7{q(5RfWygP zU7dxV9#{b-y`7-2h4H)+S*Nh=$*_{*;eV|0Zf{gGSiW{7UYmZ%jzr0O;enqm61EpO zWGd*2J!&x$phK54^k~Kx^eo`h6B7?U49&40SXY&vb`MUT?C}T+4A#PG4V}%qex4sH z>2`(y*2vbwwOw?mZsjj_99FYi0+#0}dOwe});7#(YgOM_uL}~`o*lQHNaDr+ut?3Z zw`LcWiQ*^IdIPHpvw%!9UpKMDT=*R#x5(`x-BRSf-qnmry>}QsTJKPhtTe&kDoSTG zEeU_p1uyHuO5x!;u#Sn3PBdx9?2p50z#%Mh*S8?MblMP(jrx-&$wvk3yh`_T@lAIW zo|%%z!v#&P#7>+A+`-neFAF_hPsBfW%RTuN&12lKp6AX1V;&wqmYMZ=61DK=1v9f3 z+M&V0WL{z~5HrEMta4qPDprPokEWu)jiIddSpq)U269ms!Op_JZa~ZAM@1((XD{60 zYJfOxnvNo8DKaQ^&#*HRm`(8;<^ zkHVrSV>rXbWnXIPDblrPj+%q*#H(3LQxpHWad1x-<=9c7$jEwD@i}dCQzQ6CjnCoV z?GZ>fLAtxTqTvCo7ChOq(zeu?pFdIjYSw?ByTxNNtktMs0k|_JzdgnSQp(1m3rWsj zGtL_(N$~<9w=<9)Ynec6w0@gX*+fH$dldcpnJy8&kuBBsl}#=LNVB0 zs}2*2IMVd%cW)^aOmP#UYTmVk*@4V3=O09E3+Pn$Ba*`tehotv+gk~liCnmpyT*RygDGnt+sT)NcoU-f9JyN z=FnFDi?8SdMOa<9!D6jJcbPjfS3B8H)04|o=b}~tc>PAE8Mezk8TV}1sst{Z(O}Rf zaUz$2F!ZkI$+&(y#i6K}hjQ8xm}A1hYkRiP6&d9*)zQ{$Rl}V51U4wg2xuKE&|k#< zSy}>_7r;WSbRP~`-AYR8whh}5CKw#~U6GG9uFp_$x?@iT6Z6}C(&%VtIFHS( zpvCFK5^EEiW4_eUG~w(x1lJ_hh4<1mQ)yi_eh1(CYb;~+>+PZ^fKK{>m;~ov|8K7k zigY_Y$~RJ1IU1JBoEZvwDkTefBPUbSlimxkcJePeq=4NF@Md8$NxUenkbHo<_d!B? z??#JDSqLZPyjzan7c9~$(UGn+j*(!~y5JI8cj4N4vh;N)DtJaihL00c@}7)GN7bTZ zsy*Njz#1&&@T7CTsh%_Cg3_Bb6Fm&0yrLvk%CNBD_+w;lmsNv}=P}^1VgG6z1!|Vy z{|09w>pcg|_4-#Y?e^qCkrs$==wC%uJ5$5kS6**#^x@xLi1AX0{*IF&)5*fl%zE%H ziO#e1c+Q88LlTg@*t~$sfqO&X=Lq1t61>;#wjL)lckz+fz2oInb;O@`=b5LO!{zoDVWm7X>aIs~m8w^p3}_4DEqLuy5Pe0kO*N8M+C> z_vxza4CES+eC^`u{C4ZqkJ1twz>1SS5B+TQ+OY+E5uyal zI~;8gi~avLrhCv@$QDzV1iK6T?N-ONYpV6i|F!g-{?7O=foUZ3+o_KK z)3sBwaj(7{ttx!JDjvr@Rg8=R;)z3_x)i~`*=h{{9{{Nx8ccKxZ}!#9oRyb}?qb#) z&Rv?D!~Bot1cV{S@$XAdxBm=Qvn@8Kzm)j;@H}}j&m}hNe;zTmZ;kq9lh~#6d2U$U7X2(TupMWdwK2STimLC})}mN3YIN8)dISkEq#_&R>>$^!e;Q zeyD7>(geFTFGgWOic!8jQpvChsO{~^#k8Ry6f_%W*u5M$Q#aXg6zyJZFTS)|P~e~n zzMcVaW0e!znn1UILve^^Rz4D42?_Ih(DmbdRZrcMQiduk<1Xz%~`XT=BpcxY+# zX`(nPAp(Pz>9*aTzKQGxuN<4<+L){%n+DO1N;xmG9e};#p-*}%(K6u0`)}6w30gB6Dc@n~ z>lF-wf3CEJA%X$0L5#mNaiaM!@?HMa*`9r2DG~q>btzxLk*>NV8yz$LQ#qejNk8c_ zmUipx3y42p#EC$U)4!faYcqYmo^6`Ldte0t3`qSyHRrR%n4*94``F0_^6bY6@+NUw- z1Cb2>{O?N*3Q_t6nPK3B;Ctzj3NBQxJ_ zv2wcX5%ZY$H8lh>Dq(1jvDf~k^Q*3Eckq2C=@73zlBz%PAFGI3JTFPE34gZ zk;`cN_kg}(H!hR(uUFW)$nS^*`(ZYCUedjH@hc!39H}9@7sVHG*{u`Fyr<;&Oj@^m z(4)OT$_L8x^e!)Npky`R?G{r7=L>n`R!o1#Gf=l5q( zd9oIq(-2D~=>13LF!6EJzET@q*;XRx*h@~3FR9@E)s(PR4F20|bozvjeRm~%TuS!} zb^%iXZa@bFW5!?v5qMFx8ZXcw>581wsiT=7PZD!Tc4Sx7O+P=jdgvr|IP_1^t)^(; z&?#QE(fgaWICPF)E(d_T%$Xw)0QZN8%gflODVo(;mL400;{|FL#XG&i=juzwRfTim zR=faY7$bES5C^$hkru_2g&|2YuOmYl>pG$#Bn=OO6!X*<6sUd$Ub&qm^=TOQTW)I3eS#o1<*|*w}q|hp6py#4o58eURQF|GF zaO<*QXj9P4LrGFIxX=lK$r_Tdd#(K6fCPwTVJ0(Gt*xy-*0RoWv3?O z;?UQlQM(!WbnktEVD3V;?rX3wE?qec!E|^{24@_$M=pqe?(+X9482Dib}6pksbd@F zcW;HRt_`-@s;`fMe90%ICE*hW8Hv(8hf1f`qxb9lb**D0PHb!pxSo6c6^s*1-TpBX zM0ru6t1XixL7vSm&MHYHbU{Yl+%$N59b^-$OCE_2c!1E?xg)qq-e%-zCR>((l)(R; zZ{u}b`n~LPVgDCP`Bt>PUr&8OwMl_$XXYX-+|rVciW0@>MApBs5@KXrYWNbHg%@j`BdhR$V_8ofI3iiXLy3xze!KQc9`xE0lIJkUcE(EhUb9BD!d6|r`IiU!TbO=UQ@mqoIX`jjnp~+{50je72O6h9O7jU;qT^W zkxqz-T?AVZ*33#V$MYcGAO?u-tK6&l|A~{R{e0ZOJ5{bIP0DcrsnK0jq%628!Xolq zU?>?G8ODb#UsjPlS=&UaVq+voY(~isF*AqUYIa+X2eybltJKE20jhIv=nMF--m~`l-Mr z0@u~+>K4~63YnT|b089ffl4o>-7*%Y)T;u)egY7Y`=7a8bWj{{&M%h(E())m?T|I& zoqw|t2_J2;G1Yi!>WeS+cUqLLf%56tzrc6x z?N?J;fYwumn4ShPB!=)6*}V``y+o-Nq`kp6Ht>j^{0Y`0)ZSc^W{kP1zo#I#scxZk zw$z&&G0so^#L@2W7&*=;)9c4f`E-=-6%z?2?Ny-2Mc+E z0VcDTV=t18c4e;2O=;;V^JyZqA5F&o_#{Z$| z+~b*k|NlRSG9^adHCmXcDP<(*$a2VXh(Z){YUZq*&t;*^Ax6cdFv_tU3v2YzA#7=pLSlUj zf$L)~^snlZY^;0!nL9e+JnRsr54b76^sGwdDhcR^Po|e zo!0w+#vyG1cJ*5^%-#=z$r#7EwG5NzBuRr_jhLVaJ{i+=jnoWPA;F^o>AI223{Imq z!D9db3s11VzxX;aVL74-74`8^GUA>E(B15~I6ln#TW{TftG7S~5&szNP#wXauyjT-icV4x4~A9x_ztzc`l5PP1$tT;vthY|yX!}gXvT=Y=WCesc2 zyPxNn9;Hce&dLfoyX`v%Jr+PjU-tv(riM3f{^Yc*=jd(q>)qS=(Yvi#NZjR|Md_Im za~2{eKrR_&T7flJ)Yx7Hp5Of+mbXI2?3B2=o6G8q;U>kRrJ=~^KSSK;Lr1|q>`o%T z^9!PH_R$^{p=Tk%GrMAe4~gc104Nhc(cs72C^v?h9<7#pz^LzOsE`SCe|V^1I9%Eo z+4;tcS)1JKs)~@Hg_RrT4j7N0LaqpUckWp zx98af5jPwPrd~S!z!l`35(OT@+Tr`-CqCB$iW(0s5az1at$2~?3mevn36Rg^g&|F$ zZSS89sj3_8%oyu^_p4*PD2Ov03o%X*;E@jy4<()g8A~7|nXP~Hc(*g$)_NDuWAmd{ z7Zf@R$zV*2`j_mPQ%lSjX@hPvCru#cxs z&7XYa0aAfq>2XLUcDpGhwUp%=$ zi1o&^r0jh;Fnk^cVA_DcpVY_RIX`~)p@yt#cKcT3-=EV*&C*wHe$rS0I~^opG!FG3 z-WdW(W}#}`iTH8_N~@h;&_mo7S_>jLQIJmObKOS?MC|52hlsZ+9da99bFcvhH`Ga7 z{|7fK4cyP7Nq|ALDP4(d_~yInlD2Rt?EAjCK((H#>)5c!TZc3EcqLLL5*kvb=_ek))I^Hw7zr>>9A z_;*ZxGdA}H1$O5BRYGAhG#-tD!a%w`J0&$0iLCCN{JAlFeuf8ObVqQ?*&}xs-A51C?yGy!}LQ zuNeM+euj%LGmB?}smlyXfUL0zvMABxB_LYedMO^;dgMjnUAV+dZMwkJk6*vjLS;6E zT?@+>pjHQNV9VlQ`KUzlpmnW7r7f6id<3U;=+1|jZKsHH@V)7B&5eym;Cv7mfd|b0 zq!EYh~_pm#*P6dWB8<7BG{9c(PYGtnl@=x^uVlaBs<2T+E#1_qs!%@te;HwcN!YC=H%p&`;`iE@pTxr7C$&@A&(J3Apv zI5bX!4=QU)IzxZ^S{h9VOBW+x=sz3mP7Nj)C*UQom6FelGEMB39Xccq8Q(wq-5Y%T zO^@zp{TldWojpZT_WEQDRtHl{k9?TN%ddjNcE4gvLqi1<;BFkrPybH$Tjbt0wDhNk zG#*BRiXsvCexc9neD1;AEwjQ71PF_YSz+ZVHkMgn4@QF%U{{YBiyHS8qH1AwVvK#sUdbRu2Uxo5HH#kgRYx93icwgnS!pIsHrixIR-3dneGl)xAK$BIzVXDa6x~YGW z$e9qqKB{%+hxCpuj~R&GXMZ075$HQ1u-MqkUP8DlL@+q!Yjwwa)-;5#TPY-q7Lgrv z-Z&lTFL@af1RPkjD-v@&uNYzkc7N3W(2_UHViO@qEiO19!X~MM;3+Ia0FAg5K_p!h zlSo=zpQ_i}nzaCl>IpK7e32r-$`~@e5Ec=U1hX0r2OB(0Vn_aqpYgkO%x_8U9&^;y zi}`cTb1=E1zvtixT9T^(M4MtW)p8p%1*y8*IW4EERE4g-4?SS)Iu=hfKe|5Kw-8-# zi2)9V?<3`U+nq`+J6qhb#y2m5H;XM=$~nh{cnPp##h%mUflt}TaO_#{)x~w7q9{lX z=TbvTJOv*9vmB|n{4pF8VaY%zXx~Qax|eumhHFQ>RYrX3OvHJ{6P~llIKxx5_P%NY z2}!=cjOA-D89nLrrb8F#1J?T>I+~h*MpAjKdiI5pNNa?26OKH)d8+lXh99|<6ECpv zLayl7;?$XQ??Wp|_u$4R?N>u@Z)%xhyyi5BBr9_TLYkOMEudxZ!65m6J9?eXqc=RS z9tG@zHORSgvwz_DQy_XHU8trH1C&9U(TT|s7qwX+6C7u>G3YVB;>7x?9vfZ2)KJ5h^2}5*GuXC>iiZsr=2R@($vt<6e(3~ zVrf3yEYkk_&vIZ(WxVD0rsiGHc<0BReM>!Hi-V#7f1~N79Po|VbBgf5&`G@K44(0j z7XgYr=?QI~)pwvSwBd?Q5F++2T%?6_S?KIXQ#J32S**`quB6w_;`b~U=ce2T)cV)k z`D8LJX`$Q>bfD3rDYr(ZCkU$0?2Swiz&#$uovRmog@+M+SjqSAj{j%k)Z7FFOh88G z^3~qh8B|~&@Iw4=-_9s{seDvnk-leFx$^Ld4m48gJX=DpH4c2Atv7Q8pT{8-*du5o zeROZN$_H5^O{8dsKii3sW4mX>au zm24~Crt`3K;LG$}Ybq-=I9itCT@qeDA`8-7bqtdNrFjQA6RD%G`LR2@g~C9>m)@S@_CKQ(CP(eIS`zR{dDtoXef#T5H5Lt z7o>LrtgXRF`kkAKPou6KuIg;ibXABi3lJ}WYbGRr#~qpA5=FCtpL zX4K~7wCM#wWzDl^r}$H%v`_Y|jm3oAt~Y>rKMHYRisMyI-WvBtET(Rci);_IX=P6+Xy+~orxaX8JY@t$1xJ2S-FNQ-(0hSt;WZY| zi-xRAZcShYl(SOgw-Gn=U0VS8YjgWXvxcr#ctF(3#{4REZ7kC$<_}fG*EXc%8&m%U zh>RaK5hDO(UNQM>#CjEeH=mA3euXqkwLJR(C=8VYVQJI#Q$6{=m})|Io4ExtfsA=I zreY5-J=1E`-p5Q+A-gUU%M&X@z-Rl`Gcz)(!5^;XtSh*88j8k0D_u<*`pP#hv;24< zYB2b$0qWDOyE1{o;ZAO0wsQq2yOZ@M=>$u3iUV9(VPm%NMP1IpN4-k)UTK}sSJ!-V zgFvdIUpV)Ry~kOhj!$!Q7BL(BE5U1}7SUVBKziLaC@P{}M@#o*4zSY6KvSlx>wJ>( z-%zQ$ApH8Uc;~S-{nkf4)((Ri9|$m6BT@7;2#dKJ&O>Ipcrf2mJKVGm$Ma|d%W>PA z;khwTc>=rwldrYOeB(I1%|Sq0$(R+op;*{X+=Jw4C*EeCZGS8(TPSWNg^&u~^1r=w zJmvh%uTKL#EdXj?q241<%x*odnZndZE zUt7ZK%x>@e`qdUEun9J)lC;o)HD*z!k=6|C?!O`2YJnUvxAq?>Wnt1??TH5)4@VLW z2lqoKWk9@=SMykWbfY7l(k~~-dc#ea{RNS!v7ejN={E|AI@o17R?E^LKSk^(=6E_; z52VH{cRW&Z)Oi!bot~y??nQq5;)V#n3xKP@4TS9qFin4V{!Qg^DSpxyeIhA6QGovr zxNXas;F9>t!72xz-OjD?`L_}Wkl))8A-02OC=-EoGGxAU)5gY+dYuBJxOc2?U01Rl zo$Y7sx|4SK!C51MlVkKD+$^w3ljMUg2heRpE}DO+QGC7>^S489Vh*a$t06qcoX?$_KOD0% zb#P}~dK<5sr?)=G?tR*_9J|L|G@m4jd3KtY4`H~l7(APMBoQrz$R&e_3*UB<)3(@U z*;=UJloY*azk!D~u>*D1U@CAC9O7D*=-Nt-x-2qvZN5=meb8Rv$9NO@G8PT$pbLhu zc>L28Rx8|{=<L`cy9l zi2O#w*t!3N84l#$o42tq1;#s*4%XL)5I(D#;W8GzwW1c+{iM%^bC-@;_`?oVcRs7x z)f&22rWGy}goB)=#-r4OM`6v2&~pCKR#D_50N%7`8vKn%R4B zFXla3C_pmYi`JY#w|A|{;$c62rT?LTwe(0`y)^2~HAI~cCo|B#Su}nE4bT$JTwL{f zv{NTOza}0gp#O?FN49})m{?vwK2YuHSG;j$kFrqim*XbsThSqr;bo-b-73i$b$G|7 zH`A7K_ogkOJHPZcagfQs$z^ZC*LB9pF1+L^oeTLW3oAd+oHw(Ua6R*Tv%;@S*Zjy! zw}E0J3tfe@mwhk}pRSv8MlK}uO zKew5Z<{#~kesYqL<8zuwdvi-=ZsR7^QGKA|eZTC*rh(Rm*n1}AvsP5Z3PLB z0fD>A`3C<9L$&8X9(9)zB&i+XCf`z8)8RPg^sv? zw2ui0@N3riJIy)f;=R@wuW}n)Ed54TqMVEGj02 zH_#$vuzBQK{roNZTip68cVz72$E6#zxRByv5T_j)N;r*Oa8sEiN)!Ofr9!I+_pAXp z+r7G~*idnCQ-bF4_PQyqA0>=j2Kkz|j-%9woz5k7(k-?=xiIJiQ9w$DrP%IK+q9iL z_9wY#NyJh-E6njqGT%7~AgvJZWY|HUtChSwBoGO^XZX4k;Lzc&tZn#tE9*0u3)rE$ zaxgRB1^NGJ8Q><)2l?(L4k-DrM$j9Z6oCy5#S0kWfhTId@K8!Q18%CnR;)y#25T9> z1Bk00njIP%X$)a6y|wxYb_g88+Bi_a=*%QQzUyfH>1o-pgmtM2 zYiJ%P72@?_M$X3x=O8Xb&=SKQHPOlIZLHYKR|HaDX)u*TBAY^8;u0Ja@tBpldNi>% zAz)Y_Ef50{X{v?GTGpG0ePTZ{?ouDFt7TxIirj{#yo#i)Y| zV7m$ZYeLTBZL_mas%*4-SugO{#-kiaBJ-mQbQcJ%fX5KErz0{a1TZT1%76xr52vDy z6pR6DE75mwcRVl8XDgs?LiKr4HmE>(E&y%wR|P|G{nwu?%*}(3f=W?$l>zi@%(hNq zzSH`Elh3dk^lnm5(i(ScXQOh<-oZM^!Pt_Zd=pH~;$&dp2YW}qRP516sjRG2NGkji zkS*H|ISQGmDk&+NAcp&8io@?Xw^UNP+aJ5^LH^yy$>W*9x2E`w3dPCXKXQ^Xkbdrp zZ&E}ES4wIw@VFA^?^KU%%ht7)WOOE`1;}Dg)Yr%SX2&cH0zOF>4oYhSoQ_z6o@JQcq*vz=h-S z`?Gyt<_&&(MS!80Pqqy)-i7pfFXO7u|6ER8sypxzgqY?J7v4w8@zDfAZ9pOpeb0 zTLku_M?Qn${MtwqMaTtk4C76(6uUQSf1~`2r2c2_TAd*!_sjvP zD-T66kpO$&sNJRhR40rV35viVbckoBEZsmO63xE`fg`L<%Qo{T~eOS5!3mSo3u&{&q%SPiptcJBL!Q%IT9RFVC3UcNBzHHC{WjGPQoM z|7MI|@$p4xr5<&TV^-9{I=iPcza)DlxN+o%aH|}>F6h2OKx?td16Yj_4v&SJ=lg3Q zbR#z0aJXR3^g=L|>UdHVQ$6%m0?1l4Db9dwOkLv)l=uz{NT210!A$GjM>pRp`jpVF z@*zLgU)$b$CrIu7eqvvwE+8R=Jq2G`IqH7V8ZANv7d$zTufj6e!?CuuOTam_DmH$$ z(?dr>H1Q=L_%7p11VHaCInWmH$ST^5Xtc}r9`w2kd*vHacV1$TYubvd)X^!mJbEzc zYYslgiS&w!>3z<>JN*!;Ke&-OORFP5%&qJMdn|7?i9y*SS( zXRgn*#zpViAHp5pov5sv*9)@J0OaL2)||@@15!H>*XV$Ez*CKmu)hz@3P|y14DmZF zf=A8?FufQZj%Hj_JRr(y-E1hio2C!49NN`(aKq|cJ3AYam8eDN6$0TOl^m-(EMMr=CN&x_j9zyn9S0ghB+HwcSBSec3!1Lqfh1~apWcY6Yu$i?uZ`_JP_K2nqAxUvoMc{Lr%5T`I3SdacE+R zY@TpJL7)HI>%itzgeNMKzSPaN%gB-7u3zMW7~$M}bYlCZixLUWV#W-(m#Nal{eNB3XB4)_RLiI&ZZSaRGpx#ClRk3&F zzxNpoF1qE2~T$cB^MM@UJw;exOLsXsh)Om)S~~Ev+Co}hkgh(c1I5GUr4Zfbrw;bulpH^?lX7!A ze3}8`5wu|0if=;Lj$*s?His;b{)`W*dkW;VG#UanN4M&Hov6BDE7Nl>uZO+WxuZ=R zy*t%AB!Jkl$bW;+2F&0seRx+n%r>dBbHG}>3t#C+@W(n6(3CK{DZ?S@l$2CIJg%qe z6_(!_X3S#*J^$F~Loij@{$DGUt{vM7z712lj`@xKnx7LlbR0ArQOlS$4fLdbxQ1lp z=wMYoYP1uS=c#%c8lfvc<#9ErTU^DXO}_3h1Nu+}Cta@3o?$1g&t$`3Bxg-IqG#kHMN_^<2rzj(W<*<~o8Dq8I^f4?yL^hHUKBXIAn zuXyGj)JG^)*gl5QG}|vFf|~+S8Tr-z;Jt?-016TBY&~rW|3@4qx&Q~@7tKSr)aK+J zUQg-B>Hir?dgMH;#5~}V?al{zUQPE%Zd#*Do=n)fVj^nvkYTToj9vg4)Cjv&<)gLT z^_17U&%H-wLNvV$2F1pC{989QQiws8+49u3qe_(5%qlrTQNY(TXZW9S8WuvY53USM zQEt-#CX59fsVt3@c9dBuuB@wu>4&Q#0hwHAEg%vySMHgI`W;32V~2vg52@w6C= z`36uK^RCrtK?tC_sbM#HMwg~VPdz8h!fCTbm^$&naQ8LuGg(8Yrda3$?<%| z&r?&K<*Xd=>E3DMZo|IWaORhnqq0|Y!~fb@X4$`J*~pRB|DF#AfM5$loto96N9d3mBf#G+DhNOr z;fjl45WovO^+2{=ph0V6$eIr#R|yeTBY;St~#5 zGOgygbIoB(H$V3h`|PpZ9Y%17s1a0F{GRheHf_eSrI>UH8vqudAfvsHCb#DZ@?EIT z0iYfR^UH|xGuxo5G#Iosu5dize_4QNCxwAJ-u=8Xu`nwd$`#UH!O_5xt7LmMT|sS? z{qGfgQwAcrEsyS5)-+aM7T-nt^K;P(O!+?CK%;5r*u(jt(H)zn>X3xGM}ShMlPGCl z!YqJ?=!*3{*rfhA;s!|{sHrT)&jfvtI6{Cx(7ZE`zV}K5t_`Lx}E$Po|KRf z9B~&m5InIOM~*9Ky0U;CRg#znTC4*cck)u5&*oM%^GxezQAw?eZO_!`HjgV}yK<*T znnJP(OOYWKz#!xQK9|B$frS6&&?XZr-_ zM3CpCM~q!OO}UaKZ`J*8v1VlgRrcvPE%CVYGgh_5EWH%~)AJ{#`|Jtx-1gTr=5x7ga&s%_LqZ`r!eCtHE@&D(6H z=AF_OEPQX=OqbKP8+A0;>N2+WwLVOS5G%m{FjeaNwNqJKi?Lhg$?0p--?h(bH-_wN z4@3?Hmv|00p@Ks~Bxo_~2V+*Hcc?AgvK9JrM3llim$zj4P2tuOd{W6MbIi$aQSJfh zm$|ulgL$A;^3nc?HR)zOZ2Mqn7x~L<)Pk?M$P#bskng`XQ z|10>q^5|AE5d(yf_gWqBIH^#ezk$1oK#WjkmlK~=gM6!k{FWvrH-wO;?l+1!eApe> zqjug_DT-p8!MJf4EV-<$SN>#JfQbkW;DPxd4HahTk74O-P00An46tXuT9?Q94A%Wy zC{x!OtL<#FTDHAf7{QB7zn1bwhStGiJJLIF)Gn#WP~3OdKf|vP{7lOO5bhlTt8N)6 zG#-ip(hSIvR!#8x+E?43k{;DHFL>pfEy8{jbnGe#LbwXk6dcg z_SKx^fA(mlq~y(;HyYnY_TGIq#woWQ%tZ-R8t(q>j`H z3Je3@P=*gh1Uia*kPzZ)U}QdKk@t%`=U4Cbyl`by3j#wBk23SWXHCr}B$<15^NGY> zk>tBTmRhSq32oT&O=CUDDf2bktW=ErW^f7co|VL>miuC8#}`~w3y zb+_k#jLa?_RN~Z~hdLXeJI>7fa zJAo3Zsl#x#{jXdx8>z`n18?;z@5T`~{9WZhnuJK^t{DI&)rUd*0%&Lh7zP_42^hjU zV=DBf+jf=pc9oe7V`F3RFpg`xp__NC<(;NqHqHJ}7oeLm_*_r^)`i|(2qmKFOXcau z|Bd{zixx)rDzquxvxM?|OftJXARqt~@Zb06UM;W4ykh@S)r8nbK8()Twq~mK$Yl1BvYmt$D0eR&5D4E6%7=l;Ou>x!1+I zuqFjT*>ZI4yT5ap^?GC{lq+;5zHaV#v(ZxzUO#B{bJH?9sL-~!9 zwb`|XK?SEOroUvz9WpNHd#|}Rr#^NmvE|R-+tAo0$K$i2kqbZF2N>|Xse0j|Y{o)k zy;eAa$N43G2_T;qJdf%ae?IP&InE;u@E{o>@g5IHJc@Ue#52`Y8=ekmz_tGmx9-hjtDKIvIn zT3Rc%%kns>fjh`%hdn%fz!cXgVM}9eq$|!b08n3J3EiU~X>jIAm;XtxT(!wzWhYF+jKbSy&wHm%zAXuye0C zr;lnh*V_AyHAOLl54$RwT}B#Qv!%_*-9Ovf&C90N+JNuTha`+w6l?rhNoffRinL4r zYDTFQZchVuqI1y0Qc}??1GfKM6vqhfm;Qo>&giC2Z?f{HfI!+MF3=iA_?7Rw3+_Pv zPY>R!4c0&eJ0yUp+8Hwz`3QmFJf0iG7}e2Lp?zfA4)#p>ZB6?*UMHW%sO9XVkVJv` zDMvs=ikz3n4%;5WoMAxl?yTg^V@OMH+Ph+V|WUwO3YKNOC?7Q14 zxeM~yel7egE(lSjC{!L$eu>+ww6UcRJ2rZra9_ALeaH?W5+xAgUr%T%E{ODUyK%4@pbTywt z{Q50pY_g9UM~B0_dI83F$5Am`TpjcW=so z{Gn;hULo<4xFN$HLMEjv-z>ie<2}c!iMh4v{JPn^+Hpk9&hHgj>1M%#F&MAWCA`o^ zJp(J8j1Vg8mT<_B|S)#O0okMz}qx&X%pIuOF;ELxb{;sRp%-jd>5Q*Lg7KL1i6a z4X!(?`7l*MIQ0DEt87k#q{U5qHkc6f&o2Mkiop8!*Xp-Q6o5+IoQKx>bYrpg$XAS3 zESe%E>veL~S7%0)C}5{_pSMqNCep!{kgkzp2>f?n9#rVT5%XrxMa?WDm-`AhQ?*xa z={(h90|j!uU#@POWFE3&aBt$VecAsw|C zkY1EFo)^8+&+c{9-Ja zEqUdGCj|b^kLtta58B$=F_vJy6}A9yvRVB^yxs2btp}o}`K^+fY_M6O_W~AdbHI`s z=3iw3G{aOuv)e`g1~_}|GwSH{yd51da7d`~z(r2e>!$&u4EOA!d>=H8>X`i~s5JR? zir6GIwf(asvo=VtXHw$_!LvNK+NWQJKMwWw&6}CEP2%g>!0_nk6y?#eu`W1BrhK~T zTHXoA+3iMaMeQI>_TvYLV($ z^ASM;n(#jSV7&fiaQ7JlJc9L`jp`Er{!9H?>K4#)D=!`hz zDu_&Gh_le+J`P9tV`~fgUR&M#i&lZl;Vt&O1NJ@0Jrr2B44yH2AJ+QK zP4$(LlhOfkq@Pa~1*9lUYWu7NfmSmfMEdr|JsaduqgOyhuShX2HfCYyU~U?>S64O2 zmCD^`1R_+wQ+Fz3tmy{}R2?b@!6=|WnFcK1Ae~71QuVQ4)h9dtlIP(`{YBte@~kzj zavV^@lji5*ufZ%Bi5QFpuj^(@ggON!L9dUmmeXx;k(hd7>GHpBRS?7 z2}UGW>%*Et7le?397g%b$X2mMo{K4(hOazm6yQioPK#^%?fLqvz2DN}@82-Uo3~H3 zaS>D@%(L3&prz?Cpquaf>#6hPwM^O~r+U@)`(xAPW>-#w z-ahJs7|VMwh@WTRhkB|=CYrV2(KrO`bB>iU{{EkXa?_9AcU5q=w#HyhU%xgwvGS+i zg4qzZwGnjLhU)02At5bwn0hvBFnGl2FSF(E-=tpdD7Dd{EQTu*y<@Sx-tsZr5)M)e z?XlWy@SrJ9X6fHromku&+Vw7wd!yw=(pFrD3{jVy=j2p5KN52z_e7oMksoa%5s=V< zTKf}sb#_Z(LLwszD!gdlf*Z}Mn*T*o&EEqmWVV%7uDP^sc;H%rK=0G$s}(jY^ zaP<&%J#6rJ;YJkoV^z(|pBlo+%7zX{Xgmg%h;R-H$$zBWUCgLct=?V$3HmZe43v4` zPL7{Iw2uyuN@yYWk|yQ_rvWWQA*F&a*7jdb_FqrsVja_nC%^cYpSq|>3e__KyW0>- z4O2ue|xpk2Gr-UFPD;f zEOfWLm0QR}n)_=CDW!{r7NYB3FJt70un&?1wkE!5DAg8${8K3)!tK@{FAtz=vBA72 z31`ugln<_fP#y}w`CD&Q)r-=Sjal0<0A|tq4Lw3AtqLC9?L6L8ULuD4v(D;mC^2PS zf-bBKI;{!tAu~x>ufqm?-gQTSTlVCEo_~}2+VlW8hKs&yZCwQ7v)FV4%>=tkswejz zVKo`Q*BDdvdBO(2bFtspap!P@@lNcLc9pEqFsL~Q&Jqy#=*tkXQpX&P4EF!$%PRPHFKu~zNN{(5~Zz>l&r03L* zDb9%O&P_|2T3HD{jj-s@&}<&t=G`~GM-&r8Jo(G|y1PSGfxh2oX`zJkG!*Nj)?nhP9x=9=0n+eQMK-umXyL}1 zBdH_4+!5-(h~oC2oo&_!k0vlL5$^;pfB;mjcg{^f~P&LS0|`K=leORGMK zzdy{rOz=?6_Ex*r2avmCEm2(&7e(_4@RJ7DjF62{n>N5fnm!eFiuAGsAg!junn%5L zxBsvJl!fytTcxfsMy57mXQE?Mgl&>O?Y>VinZ@sl;O8;&uXao};_C}O@TZCcYqNw0 znz75ANthW01CrHHkdfEj0C6J>^nd{)f&inCZcBB2xb=3N4DS3GC}ccINp}Ynm98P* zCG_mQ@IpD>1p}KV6`4rx=J^K(cCSge@%k!^KB*ccb;EQL)m?wc>*K^k^xKi(n6tDU$q0A?1*htR?^W%at zs@M#tbRg*)C&z5e7Waa`5MHb=&x=79br7@E?8L&cF3)aE>{I=Nlr7Z5k}xal2U*&6-&gA z1P2`}RQqz3<6!B{M{6v4B4p&y|GhEdP&foxNDAezH*Ee;4^}oqV>u4d8Y53q1fOS2 z%&e3SR&inl;Q3=)xnt`~JKSCh$!M0vVo|Bo{-kOnRTE$!?Pp!9AESmxEl%f>#KfBF zTh_qX1sB4;6}_^&UJXnq2`dfXBrNWzmkvz+`GZb*OUhR~LD>g+ANo~wl3>Z7z>MqJKIrsTywMn~w2<`zg@w}GQT6rJVOQE*b#*J3mVEkXT_~Lr|aG?l_*Bo)j3vbztnnJUJGXx;b9mPgqJJ%HVh2WcgOLtbxVfh(h<`hw5UpK`WX^t009apbs0cR=77#0z*aRyX1kv zq)bEW9`sa_=tiFg`GSZcl6rLi_z@1y?I+~Ald+tAM5OY}V1%KW7_Gq$<{ z=nX@pb>6&buxC?hg3;L?oS)`tGFNEsCQT#0?w4K1H|;7!V-w{irX@Ia@YQ#Vwh8oZYTUs7C1-9{i} zEUmS({9*qOXJ!!S)HP|h@rdTm41>FbGV;f`+1zbGU3QkeC5@yMl58QcCkh|~f{&s=IlwyiavXcku6s~;@) zBW$3qHDZTB z{%b8P%LbMrD<9@LXtm-If+yu)MAt6CMKB0!WV3n= z;DG@1#3XwWJ*jiGQk{4M%zY`Nk0)N){?~a+8E|g+%C8Kn`dmIFQq>lU2G9Sk^}MZ| z9Ag3JR!)`9H@)8waT4uiJ#)chG8s@w@=pUP8g|yK`Jw${tU`G>^;ZUvO-3yK+NMT;WdjBZieMM;KDn2T z67^ipqmz6@>U8eg2OTU zmy!xurPe3pTur?qHviaIXPQ~txmGEHR7bv71pb2Z@E9|Q-c!Lt7wp@m6AQKHWEb6o zCpfD*Ddx)!Figt-WxW*sgM5yV?o`IWWPjxP-MeHJ?|daBHx48PyI)i{EAA;*<)8oa zdxkcl>wny-G8}(b6y|gK*BVdk(t4x{vwZjzsEo~N#%@m=>!tJy$ykxB$*bgAcWa}^ zFe2DOJd_zPos#WQq1lm(6rl{xrw>DR%%EZTOE-iecop(uR>Ll5(z6>Bb4q}SXx#LW zdu}Nw{Pp#1n%`FZhP;sT<-yj52E`1G_|eOR7e-L>`;GbrBK!83 zNW?7sJo#MJq-s+{ddlo1$<7H3na})g=4jzg9+69)RK34pS5)|>Nk@9QY65-6M$)}( ztt+9+;^|rDlQ~Hae9G#jY$ZrkV4&R%vm|?OwH^)!{ospZ3m(W=RI`>Yc_qVSp>hDt zAT6}Ptb#G13TT7Th`SF@t35N=6BZeHMED4OhN zoKec5wlqP(H-0gr7AUy4k2a z3d}+Fl^fuxc)gaFXB>10k5ih~2+EK@Wvv=#q!oC7%se$WW z$%1dQdlibw0($CsV2|CYW|8jpMcU4*TEoU3%$~HN9WCq37Kd^hh(5^4Che@Qx~Z7D z$nWBn;G*yD+5q>=gg zQ%09S$^Lkf?D+L?rR1Rl@_R892e>?F2pe%`JwkWpeavrA9e7HsH15&^09A#DAcgUX z8d75o`7%Eg_d1<3DALxJrYj*a9c?f6AGX?qiA75a?e183<<+>fbbC&b5{L^izP7nI zP+H`Z+-DzLJ@kiVoGKIR3=8y0iaoJ-SN0=nWz^6a-X(Hz3iZD%z(VTIym9piwU6$| zG{Ig#?6%)i8pQlcR>pmtXhYJ#Gg{oWtk8{!l2@S6--2COs_w=N2wQ`((!ywh^J8~A zyR3-Kh=T_oS>#3j>+d^MR&Yle^Hw&cb+506Z><~!_b{KqQ(1#nrAbLitZVAV1v85`~%i#g|b+)Kitya7zpv^8!`! zDO@{u-lLo+)_PFQ-mg?8MHZQvE|%|fp;~clns^!t0Z@bs3J&aRAKzR#e&3agAbgg% zD2Ra+;k^MSK+9DWlPk`MNPNxbczg;B#BUID*IFa!kF)k@jP+Ehn$#Kg1twP=1zTmA z#k6XO{;%BotT&1e^z|IdD|q}Bp@^abR$fH!oM=ftzrn$tf{wVYkrA0aJypCgK}t_a z7WRB1b;<1VG0`r%uW#nLj;Oq^y&}Bb| zH8^C>+Gdc0NPI^LD2SdTMyJauIW;#p zUOx{>SxqUa5`r(;r0(8QO{UXFy~=4B%6}7fez!b{pU6Fw5aeLUbK3|BMac&_V1znQ zJaA1BVi3fc@QOs!xOV1K5vt}krhABPUa1}$aw|WR26ZJw;42@|Hnmy*N7I={L)rd+ zd}tosO5CW7vdkdcBN<6ZmLX-zHbp3fu_R>6zBVSrpqM0v%9^zYp{yaJ$Vft(Y)M0t zMz+cRyZWB<`>S)D{$S?5uj{kC-|v^gcx2@E*p7J<~=+R<7{okbQo>B0lf2O3&|*ciK#^de?z4a%s`-ug1zrN>^1fOxQ64 z>%liHwxhEqfb&TOE3h`w7rGL>IaIoKefHOnUk`J0JEsKXs}5^dVJ_dg3vcs^o%y15 zfOyq^DyDFQ{|uVe$< z_f{-48g{jl@9IA=)m#ihlM+D^vZx6^QID^%Hc*fV!bE^95~1D4~wW zwI;Bc!g*pj6#ykP%#5Hh50W8M1D9ZGgQ{>JL?Ye?Ny^K~T%%Pm<>_FILXBK%8<-1P zUt0$7k}^17{WI!lj(IHs*qJ4?#Pt6Bg<0qHeg`Qcsiz@KOaiQP{ZQe@?jk!Aalixq z{L*{WDHlyHw?W4lL!_9De5!1r)>(3WP;JA%i(l6tMSU2K_d~saFDKkUtvPLsaa*nq z_a=!Q5y_2%^OCVh6E#Xp_khOa7!z*aDc!U)di&AF0B@U*{^ny2Q&)KG$ApUe$M7j5 zkkM#`ryHMG%7o!3+_9JMmm-g+biZt1N6mY-)?ESAMWZyA$l;@SL-Igr*wVz;s~bt% zi=LKf81k|N#Nrb zuNC$PdYU~LB!)pE!a2!{2m>ToZa+2vSO+wvry7_{$^VUb0smjGC^oydv{WWj@t8V3 zjU2!L>0|k2gS(6}ca42q?kFo;^{TV0sK7>!6B*Bj*~9@_4ow{o6uK+f$;bF)jg@X; zt^@b~pQ&dp8#1pG;PULSmzSgdOvVEflpW=_{+h+s)b{41?LK;@N{?b8_t$7Rm`5Wf zK+3=SDg1W7{u*!zjzw>6xLTXB>&CqV&&ioFTOyXbwYfQ*sLvY5@|G_4wN&#Q%>|Q= ziJaO4;IMN<63JV?qyIEAGTHS$w%Eb2LiiLF4Jvk~M!D_KkM1TrNzzzxJ1ZH66wS@E(4^1oHhR4DozYJHb z38%Rxqp1TWuZ5l&=jQ=Izg?)^nDQZqfn1gSL$)XJG5swkWGL9YP#ZLv+2Be&;0>rv*nuDYj1xV+ZR*uqBrh;rM@c~>=C;f&0;>fR(6DQ5=66=vHI$no0FCS z__91(6*qqOuBox>ryxPhYZOnrCb_)4ZasF{4|N)+Mt4D(FhVK)s94yUZ0{*9%Frgi zkI)MqdQ>!QkSjx!ZhOzoz63%PX~fvpC)dU8#tItUn`S8#vzI@EWQcPgsQfp8 zm^7RNsFNTjH`VZ<5kF%Q2MFvKRBE@a=lx@F9?HPZjK;-~i`ZQ6B&Fc72cbh;qi#Ej z6mF&*gK`oOm&coOI%d5HMR)pl0R_iDkW@;boefAz2+a6qHV`sbJfK9u*g6#CsVu69 z4t);is!pbEPgsZ`rSxA&(}XGQ6QmjxuZihA#%!R-GhL1ych5?Sn1Cgt8vVT1pZtn% z%WUQ5OH2N6!|Kn*IW><-2puCqh`mMJ*25 z{fj!hc=KiEchY$YY=UbpkmTi>yHl#<`g*P}d|hS_y8T;QBy%rcYC2PFA4~TSLO8Jv zOE0grSE8ti(O?lG;Blz$;&BkK<3QY= zidi*^80mG9U7Kc~u$M?HvK!`Von;r@f{TDNM!d`KB|s+4f}m?&L{?GNkPfTd8ri8~ zCj1(1cbd6BBA^;JC5ec!Oa#`1P83MZDDgPfpMP#(Z``%m zi)}n)q(ylZ#+Y~VTihU>hYgTjTFTT5=8cS+5}Oa#?!X&=W(QRI zYO6-yANOWQ{%nl0xo;tLGHQKg4`p&=V`+8xDmaQb4ndKu9q$>$ZXq*C+5a%;bA>}j z!xqKo0S>H=vp#au1OkE+^4&slAo#dJSr`+hfQ${7&YSAi1Q|e}RL=#nh) zy)Ph)zr6E2;GpLR)k#jTgv4C<0@VAYx z{UK5&n8%-4SeQ2*O|Mo?YCmua5}yuv+US0@H4pdBeV|&UnY-5s;z2q}#2fp9#KB#n z1|P|)=S5gfegQt~FwDx{%c)iho$OvabJU>*CeOK)>xDV$tiJPYbvyj=Y9TWB+iP zYNeaFEY@#Lf4Q!;8YnKfak zl)%H}$J7HvX9|GWMp^B}nt(dYsd4mr#d_tGfCKH_Kkj6hvqLn`<8yk=;>BlUUco1b zkr~sbY1h09E)06{8vN{P(@_97@-N!aaYr&5asD2XbHuz)H=(g|@-lRn->+!&J(@=kZ^&E5V`es;-INfkw z?ko^i_zah+^d`wHGE$~s;+rJh*XXqJ*#_9qSP}U?<)qu4z_IJ+_qswYZx#R}g!Pge z^)sAE3D|FRGc4@0&>RS>$SOik%JeD8FHeT}`{Tq9c2&)ta9wiIaiuLsUj4QTJj8Qz zb6P1iBjqX}%|?xW{P^*|c&S_#5PfSukh|l@M|_7Wrbhkl6ib>`!ksz6ZVuM`14lyi z%+k^b%9J9zL7t+;1~U9mMBetc>o^c-d1+6JSyn8NI1PBhwE&?ohpw>^dM1`K0u*B9Mp)GRzUHOd-my#~SmAU82PlQSwDVEyT@g)Jbl8`vE z!7H`v`Isl4S{F(hKUjrC{~P}g${MzyYcGFv$D!Z?(S z%bf{YJitx{f+EjWpvk!}r992$h3w8k5YRjLEi!e!d-zn>@ z_10woDqQfn()4nSBLq~Y7&6FMA8*~BEq=7MRIGoD4&$VBLtdf6SALENMgJLHrHo&0 zebLku9nic6JmDh|e&1yY-G;_|C0Z7cYwO1Jkya1^cvUaj&)-i!<_%;zK!vME%kLkU zR-@5WmK1BTqyX&|LJD}5bu|OWgBGX1_78Sk^r_6jZay}kU|M!mYsA9IQy{N~CY{oi zr|3)>vZsIYf4KxW3x9K2E7@vvLW--rs)akskh23M7 zpCS{an*(g@h!v+$zy{8>2N@!cNc(OT)3R!b#;vW6e_!1_Gk}^{UY?7JMkf&3)#zsD z0SM;FqFd|u?Fkx|9*;7VL1K&rBXbp~mid8JdqZ>kK&U@E_hfh+taIW-TR*$ygtm54 zKY&mI#TxF;hcL}-JLz#A$X-m)dl;YNqFuPxsGuNXySa-wmmw1o9Q>eIoa~EQ8@btz z;xz0BGnQHqS40Ag-Vv{$u&`2UDU%)wmgj0I1XKJhc#Xi{%!r==2l#E6d>26NCSti! zRkll!`YEy)Njfu=)SE~_#tgBh1RS&N|q8bkJ+$gHC5cWMRew`ivYlc9xZhnMezFssoI(nFOKGE@B5iPCdV7i>->HDq^Kg5B}D*zVz3oCg~ z+nS4QuN6ldhT4N{&$zm|4;t3pzI54nObF29xO7eV+21FmxGN;-nnG>{rpD$@S5%$T+fd- zft(>b<)Q)gvwz{(sOxbg|5w^#iK5QhVyQbQilp@#uACu zAvSZ{!Y5*@ir(#p9Ea;@RTt!7T%k+*OHDlV8$9+u{62Alr_|I;l;o)}-Zx8*+3QBg zAP*47{o9iAZZax{4sw7Un7FaD$!)4K8dedjsTnBbZe4s7?H5q5)P4Og3RwLS07?I> zfn^Hi`gTKx*4B^{;_FUn-G;CT=dKK~X>i@Fx>SFf%dQ_T8w@)gn&tYBv8~d{Zmenb zU{Lnn!bK@VTflEKNQoV~j?K=c(JXO8WsP8NWdJS8Ji6dY#+X$T9d^@OH`Z1Q$``61 zlj$gJu}FOsalLXUoS-s3#|1?mJps<63W9e0JMG^>E!NOy-M*ZfMbjvb3kmkh29bQS zzEZ%8J=bDoQtvH>N#t?D$t37$k%fyiUO!Ie$JlyefNa?WGW_IW1Su_k{q&K&dElsW zp-iUmJ4%(E{cC8W@zvq~BohfVD_(s8l+HFHKsk0f8{(Hf3T* zfN%b&$=gonUlirUuiwABp&B}!O~qY-u=El_MqbYN?@WMPXm=7Ngusx`^EpRw-hu{m z?SrxzWRss|Ue=S81h)q@dNTpUa~HA6zJl)et|o$D?ZDiBibwdvkR|>$3_71yQKMWI zLt7h1n&8NQl1=ZqlJG)Xq_7vdni zN17Zip-*p}g5^UzU5JQ`bdVP0M9-6tc5B~?{&RX;;Fg+FlBu-;YpsrsRgvFUd@e=g zbpkd;*wyaJ@Uj#1YfUtzrkPpNj)|z<6^5aoP z=#qb~+ur;E<Sx{EQlv4p*eEO%cmK z274Y{ym*l+teScB*C)-ssO8nookC^RU%cue9DZbEj2)7 zwUw0&P>byb{W(7dMFd_l8KiVh!)0@%d*~Ig`TFi#&Oa?2lSf-cCFW(FbFZ&w4~FFw zm}VX7TAMK>Lx8Ady|3^&TgUUTELE6S_G!0B9K`?AMMzlZXNpILr>l}E`GfAif0g4u z+XjJ{Djr56v{-3!_wZ{Vm&}oh#T(6INu}==Rn~u$9T8 zk+IlYC=X&oWdOs>{XG6Dj8i@)Xta`C|7;vYHw}9qy{ZC2jR%0M<$j@!y&50SyTu4p zoQmnV6@HEzoF01mAwWm;R6Aly}G(~Gb zPj`LIQ|R9Bw%aIPpi)2(5qcr*iUt_+OiuFHdCEVv)KpgH9Q!JXrv)4tziiaa z(>|qj`3g`%9zE=uCWlWZ!xS`#%RayVpZssO$GwMTaY6AXjRl;~iR%v?a}q$nL}OSj z@gEjt!p`pYOuAekg9n)!Sn)jf$bKrJq8F&so(+TB1Z;aAVB|z2#~zldtVj6{86Xxkvdt8dMs)ecHEU}@na7D-8y$2zdFh?*JpBa% ze!VouWILg{^Bhs(WqCD=%F+!(AjYjX`02D*| zmsMEVy(??I2XSv)bne-c5aofJ?~jNjq4Ej40HPlM!DVJA^rTkvHH6_q=!Pv_t7ig) z94i!Ri`pT2PK_U9iEj>WD>-#P-2H0)3e z8WO&#X-cjUlyMmy#}46;W!1dky&TY}NNn;>u~*`#ViV$R9m4^#~~VvOTA9k_|&leJDO?5aG4l7+xwM&w)`U#5L1E&oe~XpUUhJo^E} zU??^Nv3-R9AUAgCGb$DvqzB$oV}6$N%xQWk88Xz$Hs3#xC~`A0k{v51E@(c{v@mo0eE@~YfQDX&z0ugoq}niGP6vO zk6E&3--ucY)RCT^4lqu~kVI`kstBcOLYGfJyZ3{}NeRI~=8#!XJ1fuW)2<%W|WCE0$ zAde&UHtY;hun;Dp&8`ErL-_f!mC}7*Y(=T=+2Zs&wSbvZv0R|y@L$rj1bSx2e>?{7 z0AVex*-mvoDL{gj5&2MFQ7eC+g}Q635D)HYZ3=c5ro0vqp7b7_03aBTtU`~4Z_THN zk6#6vzSz-~d7tR5-HE3L_CQwThadJMAQ=Cl;2<9cOvF(;otH2n9Kdh|ob)xI0W^X1 z$d-R2joFP2B}W*Hc)v4gH+8ZPRQ$F2HF;k0JWSW>3n;um=|5nhbT|>GG!3k=dx<}r z9}sY006!KEa{3uhvC}A7xisSx+1E(SUKuJu7{}@v(CrIu937ogew_e`;68!e>|_Ll zL6h+%x_wIRM&lhQ{Y^&k@U!vPGaqm_9d;mo>hL4*A0!aEDMTwOBiwUtc4U@4{H$6< z(&X(a61IwQ3dyXiD7|B)Ojp!8D{A%qp~TK(E1?;xWiounvyarML8eE6K z&jEN0C|SA|aN*yAQDurI9LIA_Tv7l_f}BA3arxbX1nw#IK>WP`)mr?bfb+*7$@WYT zLH^&6ylFeX&8!T~7TKXq)&birL(dhWJr{kGkv}ShSwAN6s zFz!!(y!1xuc1QGfcwvx#v*a}x)Q%U4Z9>5qeXh_(ykP~F&4W$7rm+v*r=rU z_Gilg9Qrl%={PivFG29+pHoVAvl|u~3r8B_J?<5EtwEUXY6(OPw2Vo~cL9SU+U`@< z%^|BYJ&Qpz>rNrQoGTe}t{KxFI?pTm?f+e#*qY9+_W_O#XT4OkuPXJU(YW#+u*WU7pi=|**c zgfU4#zlLu?M)Oj)As!Og5AYa3!jMq{sS1`bOgK8Gxrca8j$h_xw5~ecZQ#zt&m35{ z)7G=%8)(7Fu65{_PWW{l8`M9b*aG4@5nK!^ej+~@-(9Wf zMCs}L3bf}QGPFQsJ~_Z#9FyRvkphfT;lW{1W2x7Jz4%HZ$#_q930a^WIJ;LuEzI7v z{}M4)2=H&Gz|v0?@YxXv5I=ek-UZ|$42$peAkt+P*jcXL21r%-C{gmsx$A|`F_bGO zBmOK*@75MHm2pI>@y4JJ0U|7T>oo}7Dm~Qxq)uK0*mm2WrwevEJO<sn4>tft*V<%*-ZI? zc-=|q=s!292b|9tSC2^QMXv~82pRw29P61I-+i_=v)RWZnSq3}I}tKTs}Y(d)C0*> zigR&o&F6#Z@)A4Vhpj;S8vu^5*H8c9 zIWR82FNcH7QRhFuae_(ez_z;&G>+S;|2X%o>h`6<5>Up`Zt)yOY1GWllH-ks<$vC2 zz6AoXD*Qg%mOOt`^VTb<#$KB3{$cJh7lEGQm1iK^dv~VtK_^SNYJ61lX9P3xZ_EHbHdOE{5unBZBOc z?N3$8RQjj{A0Ho3l4+mx&Z5VjQM&~Z7_c!CgObH4zPMZTHv8f;{r(PT{n1hz=dRw!?q(PhzdAw=6e>7z$z`6btrKsh$^7p=zt zoFmW%bEPn3Y!TJ%RDVz9uLJp#lkJ};B5vv-5@_5GEqo#4NFR)gpOWHvh2;^3O>Uoo z!P>B6^8HQ8LreWrrzutSKF^qyvG9IZSITWzphGL$OtDZ*jO8=da%@eq^B?zd0J1PU z`mZukfD8jb-vfdS`GZF75EyZ>uqG5N?#v}oOlgs*PY#xk_(h5>w{M{OdZTI_U}NyN zlO1y*d9o%SypeJtk7i+I7%k3Heao_N@t-4GOMQ%AS1VSMm!GI4s_Ziwcf);YZMw$(e4W2( ziYm{~9lDL;->(_d;Bl>8oRx2*7g9p4F;6DuvXsQ^(s)^t3HO9wLl8F30NVy>vp%Y| zLySI#C}Vq#)fzHC(FWv*Q7bi%JVe+HjOxoE$ZQAPYNVA;a59Dpy@!pUoMTtA7Y7PI ze6~*lqq{qD$ygK{5yJ>2-#wFF$u6iBoXT!IVGea<%IwV%rK*#GgdracE3?x({aeR9 z@`Z8K#o34(&wn)5y-{Z1$Hvc)`W3_1`-d~%e$)ZHhA>Hvx z0uwiNMmgLIzCfZBr2g=o`%%i{fc>%wFj5%8Q2L=KfC}4~y!`9OkIAr_lM<l)ab&`mKNz*@ZDr zVtMW5gocs;&%?Z1JI^V~UPu9ZqR5--&q!7Z10Os_o*zbNnK)8r8&U{at`7qQ5iwXn z3PP=+$ih1f}f`2A!bca-kYRa2&bX z$U(uBa1Quui4-#IEr5fK-YBtutZi+szv}9YsHU;HI;0FK{OmO=<;bw0Uk*(Uqqh+Z zM&A%KFssOWcohK=%X$T!zXDy}363n{RIVhqQO0yp<<3|;3WoNgAt&bY;(%z$Xz$!E zX8|l7GAo{TwsG}Pe?;wTUHeh?;92!Z^_&UgOzyOasfnfCw-U!{X{0RUQ>U}0ARw(Z zXkBmAmw@swL#}c$@3k-P{RhIHJ=#Vdln?WvNyjcDV4Mih>tT@Y4)akz*A@qAQuQ}1 z@vBLXwj)|H$4AFPcge(%cC(rTQ!Ee2%F#@fYRU^JL8IV%A#_ftnp@C=3&;pVgi=2J z!2if-OrgIQGs)Z|p8r**j7u#YVa)E<&HlDJz#RwPzO9#orHVk_))buZpMrE#pZKNG z(PSgB=6KLy=*uHUTZ5mKceB~qqfze9<;gCtdII?u;w1mn-842y8%kL4_d}8Yi5F*8$mpN@W`_ z#>1r-nqHIF;2)Lo&|J_7?UeP=meK`IBumuYJ3#kbvFKha%9FWwZ1 zDD<#)&0aoE8wPcbCrGEryR?8DF=ePz|-DTtGN#_5tf#gdb8_8 zb3xnpJv0|=kyVB5psG^v6ciT>J@-s&gScO@AyX?#U35IavW7DR*j$~oCQ&z`& zwNix9-L?q`r?r&jTMF%$o_);Rl_(sCQ0p$oBJ(Q&q9_w)T^`VIwJY+FDa5B0ut8IL zW&f0xas@IUBC=ErQHFb){tnm6hrm*Wbgg`n77NueB{551zkWFoeeL?WH#c=QL3N0e zqg0uvd>(-f$ZEYca;Dt)lSl;7Ir+}eK07>?KrkznK^@FFp}FazbCnZ};l-C|x@nfc z^FW3W?6+jUr+4x{?IEx?O4@lbwOS>Rv5QeYgk78Vx>1ma#Nw0=g=X}z7JH+DYwS~} z?z$??UlBKjCaJ|9AdEp6onQ!-eFyVyoe39<07VJeP=I#SGdWHD><4m9X;xF{;sK%n z`mWJgfb@KcD*TXH)w%KQy#}E~<6jvAlY@**n=C7;uOQF+A!Q|_`Opj=1e!#x_LInJ z(3TP$bn%}F7sWX1@=fG)z?Nhzsb^Mh5)~p=?zDGsS&G;89E-*Mb&wce$zdMgfwp_L zzjgrtZMA&`r4|OkJh7>G&+gZX(^~j5YDg5?cCR+kSXsQaP5UAqDE%87PXNi{-%b!s zMw6TB1u&Fbd-`oTvPgs-t62z`S)D0{mf&L?E3*6EB>nA;_G##lslT5e58^RZhD^Z{ z@Y{O|FAOgOj4K!T2Vy#I9K?nA2Bu;&)GDdZP5vt2AVabx{dQG`A67ZP!m|-$90Pg= zi8`j=PbvMTEVHwR58>WiOM!tlv+L&%id5+S?>@gn1g{-%mfn0 zPvq~UPE0f%<1_qOaT@&6^-Sx8m5l}GXfO1%%3Bj}Bl6Gz*17wKgg8L*v6~n7T;9I; zbZAtNxe}NUdS-q9@#6>JBABN6GB9L&wn~qD`dhK9`a)#lUkz(59mU;)J7aA<^x01W zWPjH&y{)ZLQ=rPnW&nRgV%`g_R#g0Ch%V^GfhdD}a*Yr19KA>+G6v;%E$bu65SkaWOIY4+7vdw) z;+8uV!VvBu5YAAbgDkm#ifC_AOw*_WxZ$&E`!B;dXG(_}IDXp-Bq~6W3mHIL3k!J_ z%z?#4cKz{uO$34kf?f#S+RxZo0WBk5E$gG48=Bc*@%Gp4;G@4ixH$Ywjm|?-=`qfd zNIgc}D@!|My2L}C064Cw`K|TdUuuueWf#pBG_JfxlQidv)dqq zwfJp;K!UA7LDkrLU5PLm`v(L}{IX$pItw?My|AsY@kmqIzx&MZ-s`pF<@|kKd?A#Axh8O$~V5FR(iy zph~v7bPiSU8pVk?Q~kw$TxiFsk9G%RjQ}AC#$k|*PhR$i_wT0szPdShwbCZ|FRBLz zH5QqbYJUeAH5C4#TN6hAwXUCNU95>-ABdjkY(Di#^}qJLrX=`A?a80nWA+D)$ZZx1 z+d^i(D>WWLC`VbMWJ+Yvwib{? zzVR#x^ClP}f!ggb`HlDv1I09C%RYxR`B?QKJAe@}hOAOe?!aW&)0>-8s|kA7j!fmk zl#~<{u{Y|tKrBoNuyJ`AkYUxXEd(a2iiHi*GQf9kc%VHr0Y*GczJu+q^voLd(k*3+ z7&%gIk!6w1T*85=a#-fAdOIM#(O*Ic<2UjDfrd^f(-KMawLxES^N_byCO^Jl>Pi{- z@EX<3U3bfd&T0RXVCuQ!)llc(@H(YCv5!8kzIdky%yCFz7RZB!Fo>A2oy0G76;(^RU;=)$V6@b3k3?zeU#)|hEPZJ~y7YBNA0-1^*&sEBH&!|F7|sfXT3!+ zvCdn6V;*R@|D}Hl(QRqGdJ`Cc9iYp;AfO&VSr6~a7vMpoQpaN9K47UEZwd|Z6E{F6 zT=(38sIO0I;ixjqVaj^%8fSBKe0}iQ7HEih(xiS0n$7F+`6T-dMY8f!uS6^Z1F;CN z0slz(#kTco6>R=`-7PGoOP0?{|9K=+i`A_gtY^zILXfL9ju_iCMFgBRuD<+5?37fV zP+PG_8cQ634tpT?cSut+qS1Gho~bJlB9pxm%S~s4N`{2=uAr2yv0`Eqnq&^?}Nv>0NQ=0M}??|&Y9_m7^pMh z+a-G^oTB?*5ExgAs4LLX-{0>aDvgr^gbNG_jD=!q8&uTs{4oH6q$q?qQ?lN|9SU{l z#|7G13gib`tJmSj(`!++y%()GltL+*AC!s3t8ETMZCB7GeLExhZTH$1qCs9lxa11Hq0Z& zZ(@5%6bD{A1`(->Bra|Gd(hlTq6k|5UXqN(Q3eVlkdDf)VKm0@J5f);@>42E&W;zC zDt*Mtu4|~4>AZgIB3&+wyf@Q4h%$MHYL8HVc=_tMgk*26<^v(sXJeNOJ$QxvhgK)V ziGQc0yOU-H=NyKY)87`TB*MHDH2rC<`6)u`bwJRf4b1g#)z zRZUs@h$;(B{JpFS-9AE5KaKGfTdgU~UItZU05>#L(dsh4dTsWo3ke+26H` zK;hxmC|RIV_9MzK3G-)*tC!WQa3oj1wV^qgEQ*We4!kYU{we;16yO7l`&5{7S;jcv z(@}bLwIw60LaC!)D?x@AboKl^u(mXyMyG2Wsm^P#FPEirgSn>4Flnr@w6YF3&@+Vv z3~n;^MIZV%u{|hf@z?v6&!NhHp3GjJ7fyrF$T#7fh!{l6ZD9)501PQHe_&o&6d2I_ zH~qdZ5=n>Zb7G zmD;ZEiR}&j%^I1>$YImMtfFZg8ES|EM`Z#J`LmAFPEUz;q?HIy46Fl|&4g~S2JCg4 zYCa9955hPy4A#N&;P==C^9UQ0jga_*+5&B0=hso7><`lh6BSI;Sb9hZ19;+|l)uvQ zALE7)4*~~aO~70q4`Cnm@td@*H+JqpzE`|0>_Ty-G;>i?x@O4)*x=o##~0GR>G2kt zG3!7vB0;{&qaqLcy`9%IbR-0yU1|R8rO7$D=^J`&XuSiht`l_o#9hH> ze~X$XbNS+ZZj`Q67pk$6zYU;y|F}^}WP%f{ZXq*2KeM(1EE_yr^;!pKL-bNnVV4Y41UljhXuW{DBDK zlVHb9bwB%_%8G6rnEMz(-t|mK#$AF)V*&Xdm9RYwYUmi3E78{sGb zj5{38evb@Ui${fqn=2^(^s`^^v-^&S%+oMqml%&^}mVB{GLz6V)^qfXA)*qA>! z6im~!h)Vf*4}_D$us8DnvAbHs{s0kpA~EiV=^!0mp=W(v<#0s8k*m!`R0Bx#-g5_L z?db2{zeChtwzgUffM{-*!e4mGP7RY$=6Yf&H1}v5Xc|nNseHo5oJEaO2pu9TUpUrJ zy_Aa8i-CS;XM0ND+6m(>BwsJ23h9}qshItGz#X#3y?I($fgM|K%+3ZYJc~VGPbJ(A zX%kWTRI78Q2<$$InD;lhW7#v!wQ)z|_>&RWr^*9`f!xTfy7z{K;^9Qzm^Y}h)61iy zIfM_|!`#i;k+*J*wP0tQ%KjX0fV!P&i5D_^aKCeNQ=L~sKtxnI?ITJwmdlWVwA?dc zAl^?Q#9^i4cn}Hv0HGNW72Rq{e{LiMSbUTvV<+OCP}}N6lM(8CH~$kt_6P4rMyaDOQEe5ACzQe{s2Y zR1y@sPk}&{8~MofA&^iS08;E<3k57g;itb)+=Xyr zIObG_*KsD~m=JTvSbQfB0bgvFw(Iv-w)>-vmGQeq7T6*C(d_x5pc;o~HVkdL79EBB zW8*MPN_ui|t>r;={QExn<&X;`lwzD~hB~>HfRt4w5AMg5Cy&l?QKFcTv;uf)_~I~^ zTQ)Uto)K!bckIMWWbUrSm}5F2?nVgIK{gJuwgv+1Ubn@i*#Q&?{b#(aWY;mD7MyYU ze=UIbg3XmP(mEx{wZJHao6mLTb(YJdB#Pj)mO8*3f2=7qe_1U%rK!I6lDB(~v{@1U zAfkV8x%cht>Jx8-F1MQe+4go!8~UU9Z^-~t~V1(mCqLPF~mXB?e;u~k^AV;;TxP6XV#)-)-gTRPAEW;#aydk z1LZo3*u?c_$^&|aq?rOVwLZQ1#9Q2*{2>a}T`DjXi>f8i2)tO*{N$?ke?K~e#+Y*} zeYw%SAKtB=L0#emb$^oU<*NX*4Gbwb7~HiEGJhi$8Cd8G)E=k~(}5_#nW|6I4&65%CB_ zQYWt4N%PSvVBO(MK!jze-htE{E|6Oic@cyXFsoJR%h`R|mm#Wj2=VF~zmp5)ZwiO- zE8QcY!cijg;{f6Xu7>G&7UV{Io zV!HqMaYfL!Y)EgdZ+EWrda3_fW7xaraCUm+2nnMpwShjrjUCUGFL&FzN|Mz;kN4kD ziis=-ActFaAYOrG^Q%i(UWk<1{TasK6cMPVDVhj$D>$^9=*#$&ry6Rna?ul1zE8X_ z;gxWTEwN*Fuwfh?1eOFuG9d89r#D3RO67iLZ_yinhFymISU3esyr9NVBM??$1Xz`q zP~ce**Vx#gQu*x4cJKJsL8I~0oC1(j`wBIF8Wyy=e$Fu<<5RFjaD^Xr$N=ITt-94Vm1Tx{DZ{a0ol6doOI0UaB1B>#9zP53sQ{cnP0Mp63j z7bDW&)MCJBrE4+&yRRcz-Q;-o9$svZR!qNr*>f!28E4UF{($X$WI9Awvf#_y3Y=H1 z>?DAE(!xPNpz3BfXqeV!V3919xS9U^cvriq-(`JW1N<>>w7axY5$B4J65sj1bOttzM<&rM5R;i7lU|88{MR$`WNA(LdwVcp{p6!`$Ro=cXH&M1C1ZM& z?5BSQBO={C`Tk@6T2$2^W;Dx3KYYcL({T|*#+S&(Ku&n=!llOX&0ovQ2R(1*7CSJ1 z2A?2JtahHdR|Ka0rHM5DKSJBh+cZ8f8;mHZ{k3zpsb1BV^*j(Ybw!yKX=jaYuVYh| zrNDI#ViS>y-XGq~5O735}FRl-Ghw=X@@(2K2TBT9#|B8{$1HcIPgV z3A_fzh%nDIYM;V+h7!pVy8axAFhDeM9fm7x$}IF&<@y%g`*IIII7`8TKw^WJjvl47 zVEQf$I3Oo|ed*2=VH~Z>38i{Ob$`G-6?Ag6H^Z|U+(8l^7VgIos z57?tO9wf+_-G(Vg<;l>m!0?G(ST4I3;o&as|;4RiGE+qb=Qd)hy($DkLm zUUip@=fgS8_2ZmK2qXkJVaULcpq67E+?aDr@UI>CdUM^-q6Wxav-j*iGps>&z4(2tHt^TTq8M#A?!||=Bo|cNYDARQPl^rH zHgUKRMb9kuaJb*KD88U4Cb88Oy2n&A!(Bwa%@gn4pC&wc{wEtIm|gN#7eOwMjttq zQ$@&`WMY{RikxzooaTH!{O*3&_5G{Mb#+}1d*Ao_b$C7>&kl8r!KP`iAJ{X3imUDc zECIAT64GG1{f6(N=xEv~uO#fjIelqF13-Vw6> zKNhWNrC{@&acr})h=aFWMTMq_{1hOBR7!2DU8`YZ5%ysVGwV0Q+=3zIG4&VDJ_m9p zgg`@izX|rOg{EYn#7EVJ&$6v&{N;zI_dV75Li%@4RZ z7;hcc$^*p1w)*Y0!xgI1uii=%rGBBDB*luHq~JXs`2NdYTfUFtcZ#5ivIv<(=4XO#>f_ZYdaks&wPvAQxHT;OKPVhqO2dJ z(xH2DNXlt#rlw}u3Gj$+MdMwfn806j3j$$0vmJd~?78e)2yw_%aU3X9N(|t!# z`*{5I?XY{16`v}qv_Bqq=KP}LsG+WT9|CS@D5N3AJm@EzRvIs^RZMr2jdld72P=Wp zqwepe+pl&p61yY~-mhtmRL=%YNAkguGm=ySUU<;P_PM3L$W@#!SpwUm7W4GO-17F! z>Z)>koY$lXQHtxN^ZZE5Xmd~Bj#vA`7@&>FvQP;qcedn!B3QJ}B6Z_aS4FFR8>|zv zD*TX~$-??6G@ZaAqy#ofj>fo8;bXMjDd18p%mE? z0ttJ7pMDbj-zdijm`==R^?&D$hywe+7!09sQR9^0Y=Am1{NyK3QHnQML~f*ND-ou0 z)Kc2mbJsZ{bbImQM6UJYk>GEG3tl?m3t?-bZF)_6z5dofsY#NvpKZ6FCzViWWzpJlv$L$QG)e-P z!GlzlqRSj9R+-0iey*iG>m&Gv2Ly!qVA1}}AXcn~8Mz*6J2Y?-f8MRjFUM90w(Z|U%(HyJ|ekp#fuRfFYrmS)1b9mn(UCo{tc?S+(|uD^ieji_(ck=*zR3^$D3IK z1+y;#jD3n?eKbylul@pYp}@_3Cv>YHLk0w-i$~y)XVO#&_Q0=SBGO}F6+(|3P=6~g z-gx)X5o-?v$DI2h7e-E)a!v`^$uu%fF^9({B{uH* zXeL*ks^;+*+0@XIA(uyQS~-zF)->tKJ_k@z6ffl)G{OEsn*oLAofIdeUQ#v}k|;>2 z2UMJ!6xox}VfEjM2sjoS1K8;yA=@pdUWI_q0L+iioYWIN_o}@B_&lyjrLHJ2ih+3M zrD^H;2UM_fgG$C+=@0PiMUp|f&rdRjf(A?#@#@}22$E)Y>YY8HVxmU2C*7>ZNL=-X zfxhA5H7we|&>4`$7Pb};w)|(B_0BHroXBGX%fmXq+5Sr#VyNZtz4dm9j7D@IJ5j2l zs>YZ81wkJ*r+C*5iNB&%gBJ{jK3r4&MA1MX{U-k1_{zX+t!JmwL!_zUD5?cPH|=lC zxKAOGqaCl{(q6sFb(f1amEGtGQBG|9t`rSqxyQ}^sRf_o!@RxCso4o2rwvlS3wj*m!Du*A9eKgjNiI>oJ#pf_FeucpTmf;xtkFP?3i~3J{=)c-JUO!L z=VYHAK7N#*8p}xWQmCpJO3wzWcFD8t@4XAWJC0Q*pVl9XZx8p{hkURr3|ns$*9yG5 zFZdtCt77u)k1 zdP1AT3HR!Yx-v(suBa$sicD9p!5lr#NRvCF6uyS(Qsw|G4F2SQJ{CHZWi( zZssy-R2Vg=_TuRI93{?6BK>pz%!+ZBQQEnlxz*s&5PTAyfW3tMn^ly#_4s>0Kh;>kA{7;!W_t?27q)w zPvdlFVPRolHrx-^;2=}XiK4yUz=x&-J2tP2RyxQx*6q*1-+JJSNpgNUUUAr~X5a#A zs%8DIDnuNvL+jLNN1S{F3k`nScsDGl*iNBUkwxK;oG!+7-LB{#C6jJ1x>AI1_Dg!rMEt-43>ROZS5c0)tF{KTj%|as)Qlsv}S7(TlYJG zMPjO*BV2@n`gVTTO{ zZu~;?_Dwont0OJZtr-aQly;2XJG*L)+X3QQp%;n_A6#2YJwu*1)ZT;>vovSCyzWRR zV!)Cu@9`E$sIW>YK5@3!gK{NYRghFmIKy~-DUmF3&)a*jbk?OJ#e@#UZVO=(TfP{& zrahY-S)Li&p5zj^8{m6f@)CG{`@~aVjwvpn4aNbQ)z0$Yt1)0JQZisb35g+@MY4PFQ)g{`)n zs@rLLVee$zXJ_TN)7@(?tbY`80a&Z~lF{V5(2?&mN1{W`1#P5&$T-HY!P=FwG5j|e zRKtzmuYr~1VS}fbCpurC2Kjr1Lwh^@`PTvJs6iXYa|*miw9=TX(fdX@CGPq9=2DdV zIJsoUanlggsMHq-C>S81F@|C3$!jNS_epStpV5=b=7syv)A;DeTG1!J+`^BwEZnyMJ5(8O2&$50zI*ht}=Qw}e&g{Cc$q@@q(+MUd#Dk&67pk3H^02|cYySc6lI zNWq;xFO6eqVr>sfwgy(ei>VUH{Fx@u`-ea!iV)U+_HUUzxK%6zmIjRRyu3URAtpig z^72~L2w$EwA6ko^J)(By=<}Yw{r2(A90s3%{#!*;4MbQFy4L3K1K8U{I-c9rQ=V&2#3JT$>ec^Xz<%Qh^L#J)-J(J0y~^WZZ{&!GUO{A$tBRxKsfZ=0;u9)yko{z4GwYI$yeKu6xQimvd*%Q{Iao7(LG5Kfdi> z*URLO6v?4k+>f~$LMsp=3DWbvcI|}4>trRlO-t6J0O36j?L?eQ35YcF56Uk6oG00Pz)YTwUnJ- zds~UF_Mt0-iKi4cqxr-QphrN7G9Y@g%b51cHe_uye(w)U`(2)QS6NkP*S!bcMFj@A zEa9qw-6i|*7BzkJKbyv#S-#`It1&}6-D=FIXe1MP7g4Eq7wdL+P(4&hWUqg3f<08b zdtkRid)-iq-}o-XTUncMCm`8@N$Ou243<6GAY}yFMS>w>r6C$fH)0%EVqga5nD&4T z;o<;gDU37ow;Px>#}HggI}nnQ&q^*_{u!eDh}krmkJ=Y=$h1LX1 z^X=I}pis&D2jP)017Wa$cnz~jlFqC=I4DXK$%Jx}&F4=blX>98nJq2UH`VKeCa8oS zJy~zQzdyBWbhLJwABn!GCcN^Aj*v7i^yT=n)h%aKVivwl1b3$O*x&K-lMqOys$70m ze=5Rh=sXSJS(nQ4Ja8gd)h}-z`)S?NJzKoJxmo$Of^#|^Y;C?es%mMP=Kb-iAj9qKfk<9u+S9UEB2vTb`7zqL zMEpu{-P*gl_05gh?lTRq#k2ey$lv9t6sYlW8xbD+Xtg4 zb-&@l5CFgB0VK;P5~f7IVmwuu&JbepFmtJL#wQvpa{ApetVmx&4<(oS%-3dMX0N3=8$K~`WwA&+!S%GE;`*B<4YG= znrs;Nuh2u&(rLek2KaHhl%D2+IhX_#Vvc(d0C-Nj6WyZ5F(3R(wB0-;^>!q9PHJzD z)B$#RbEbKhGQs1-Hz)7#d-uLosHU{%CjR|L)&1k;4SE3q7Vrp~bOE(@4!f_sQ@##N z*28M>ca*nsy6M^YhJ-I$s>jU8mjD|`q>T2=onk&+2Qoi>Iqn@%mroc4)yhc5VgmlNKBARkExE$+2U zqSAio0hU@r$wHQBmajt45T7oWj_gBBYn);`W5BC-wWegQe`sU!yO>>F(D|a)YcZ6P zB6nH`3@aYV*AWGQHc+vY(sBz1#rJ?W?viwJg3pClrMg4Q1HEVMOzB-VH)SFcM-%^c zZ11hJ_H5?wDW;+*)7~|AQecw8JdnFr60Xn%YVACWl`e9)6(TYSrzxmRB_mRj6zz}F zh-dGy%q98b@uw({x^E?p>8tPpT4#H@cKFJK-~338VSIbLsiD5tN3qHxk0avYd+ISw z;}g40OTC_%oj~YIxLqF1tblEg-SZDoOn>!cDA=dMZs1%BVLvF%wC*)#^qv^$UX9?n zPUm7zDdr-)dGqC`qnQ_fE{9U;)ut(h(+4GaIY3S+rw;lexbV6q66HaeX<2G5kA>=+ zyA_7cN5;W8fyMZzzh{z*pXKT7Xj2p!8R={Z@?MHUQ22!d6#}e{Dfu@g{PDW5Lmf? zgKDs7CrE_@DJ2S4=*L93QYF6LSQ;E{=4y0Aq!dMyWr(Y`H?H|n>RU$w!q@D#g!jNH z*w_v${d>T@poA$pEt5I4*#l@amX^0pf?>#nh!0W;<_bxg0$ZZFYkD{1xbk_@4TnDwkBL(;c28Xe)y)SUngC^1}6h zsQxv*wqf*f3Mz&JF3al#%1z_@UaKn_}f zkIxr1`?J?0OP~>#EO73|LkARrzMwd!z=i#<#sE= zc5o=|M4K9tH>1`Q8AD3<@H~(W%QiCCiR5+;(o_l^eSVB}vMfpGZjk@)k7w%N{H>av zuF^PtYDLwVQy;J^dtd09&_*Ar3Tk%35R%Ukd1mx*W_aQzWB6Cy8D2s|a z;{5EG$5DNj;{UV&#O1C98Lk)Ee}wDS^(}??#I+(|b899;jFLER4LIH^WM^?4xL?rp zr46Oa{1@LlD2-6eHS(5h%O_|TF9G%Z^+z%nziio#>b}YQvmUtE5s)66K=`FMyci-C zSa@J-YHHQBZaw5Zhf@({mfMmlasZ;=j$XF%I1|^gzPg)k0WvyGasdse@%x%YB&xlt z?16+<(6WqbUEl4pt*BEd@^FnSr3sLZfOsM_;;iKGlSk`1gBxo~RC`{y|CCRm%I)BLdaxA8Qhl%_BhVddIHD z7_l?Fvo>TiGz0eIVP6uZOiCOPe{KvO4n2)H9Y;HtSK79SvfkP_8{U8p2_ZE=TS|Ud zd(sRkIL|WAtAa<#^Y8mZ*ummk5Nc`Mcu4*+RAp)z@v+Hb?4cnz36}oY>|A^ zwiBae3{Mpszb}U`g+%Ng{0~-nu@H*A67xDnRKcf>TZi-hr>HsqQ=Tbba5F`6*EeWu z6!!Y7)#~1ARfPo&_{UQC#rfTqL_NKP39PEl!R%0ec_D8YVcAZ)km z)y{-Uoqvy*_;CycBca(2b~=+yjO(xVM$E!jrtJ;uRZ`DLb2%P^2Z}?0)Z(FAL8KcG zGFcHav(HB>Nc_14nbRQRX(INACEiNSVRFkWAV4={eX_H~wvSK}2{IJ8hm1PlX_xI&PmgaTtM#T)nvVK`JQRDwRa&E7A_!EuU)sz;pLJYoQS zIBZVok0IyF|HN&OYx9-Dy-A*!P?+YnA1I^Dem|YlXO>z+p#Eem;5u( zs%xvJO7WiiT^22W+P_K&c8<;oi(K$2wN}V4ZY@adnGQcdP41Ig=+Urklgk^-zpT16X-#l^ccnr#rQr*<1p~YXyTF zBYfe3-rfrhTkIOrQm3)69@6Y8^JK=i8<}+E$o9>e-@gZ`q!U-5P<@Iku|MO5dlc#* zGYbSJj=%YaHidS@%omtw^XjL=c@yFgwkghy--k{IYEzQmOP!9w>+4Au3dMCdH7!-j ziDUr6m5dCsOG(9KT9=By@J-H1jALlfGvX->sRt~NG=X|8Ygg%38D~!9JO{9qHmE*{ zfJ;ho?UR|nml4j~O!?^P>q~N{kFZ18>eH2E?Y)xliQ6Ecn6B|mA8#O7zI8nNqi3Ju zSuFGsOi-Xf|DS0G0J-_W!(4ON4(AT^u~#TadJM|J7;T`%3Dn9sSxHs;WKAO?(wFLh zT=%NFiW|opKs8j=56fH-hXLq=#}4|*KiyjV*I;pt&j5XxO|9B-^bL67j5j}O;1O$- zA`Nk?Azbhv0*RrXU;!ps5eQ4$@ktM1)oVcKEVyY!0gw{%U8Z{>gX~N?!gckts<27F zM%|}R0qoxdbxH{a2;maB93g@ahb`@DYC}AzF4#cv>(eV4YQG0PujoZ!KC52ttYz~Y zh#YR%DKS2%`6MW1KXKu>;C;pT4y9?M{umD5g5_@*7dZ2JKB}#DclL#N*tR1<2&}v7 zRxuNJuTzaM4z6p`i53dhxVJl+lB(L8nnooz(@!Dw%mqWW?}c8L$u-8kqz_N)pV=S2 zu&ovug9+N6gl9^j#C0XWIHJR^Q7K>LjzY~^-vy+zHieXa$e=%GM9|gZQbVyG+Mu*U z-~1*XSiGy0r~^s&IN)ps`r1-u zBYxTOwl))UK~P0#5-I$0`aY^+6bzWg{UgtuGfDJ|vf#(Y3}GW=vhgUUS-V2Irb=Id zP`*6F^oiNr++2~@9o-m^8-59IIX&tp*W_6Bx5}#otknU97~KX1VYKTFXTvub+MB=3 z&MKsHd&u7JN=&S@8~i<3YO*w7rgdz~>$Yg-gw!*4lqQzG1+flpCeLd@Bl~q9p!a{K zez^A4-Ad~VDP4HQDP^;E8X%Sjh4pLy(=tFauOdrVpy!BfBi{qr91@rLc|RyzW+rz^ z8z?b-E8c`~O^0^*_m+!_asu3FB%mHe%1VEol6?(>8$@tGA^H)|Esz%|ka})5w88lq zL+N<5_l&yOj;na+l}kL~tM=P#J?pP!P!bAUiIIxRZHbs1&;Avk@icWiarbPQjOe07 zyj{{bU`z!B;AD+?K8(;@?{GZ)v~aZw2Ivn zyAB-WV;n>x#>-PpUa}b7K^A=%%71xndg(w0x$7mI`GM2@9M&{G-pWstFYUxBUYW}l zp5JbtdHsW1=?z|;PZ0f(`hlwWX#SS@$w;$XVF1p$Hy*xaFZubcajw@Tl26Dz#ajdM z#I8A6pcNMkO>)+Mc1HO80l^2&fbovVgm<-kfx%rtzAILBrp)5*OYkxj*A8)`a8gnm zP1|nKTn#q-t0c*$xPA4i`5KHx`Kqc~6r%7tV>s>nF;bm%L3=xU*8fKKguEG=&Ub<) ze*Cy*@Tv*kDmOP5gaB{`5_Qld=$2etL;=)fg?; zIW{##5ZcI?&NhZbnBSssKm;?*3DApZ4xoJ+Rdu2)6$dU&fTb+*-=_gZ{wV(^;Q*Gg zE4cjPKgL|*A3G4El?u--AWvO7)d2XD>B#Gz@WU_dBsgaNlbfm2qWPY-y+9u+oBh}i z8HLb{C3i}h^yEKO>2o{IVP73M4niJZ0s1o#@-i3<*CCK?-_&u-@1vcwJ6QFU_aBcP zaecKnwz!h-QWtuceIhm^@3OFywn?%DUj!OMAG7#9FbHog^(#^4xX<^Mkec=Oyz;Z# z|B&T!S>HOz{XA%q95s{}=9#-zTPtCD@PqP!cdSRSY8!c|bJf7euQ*`i-)5-<1fWcs zjUF%kJ}lr6E6amCMkGS$j~xDctPI5CJkI31TnMC6du9m`?t%#5YnB&Z{+wM+I2Svj zE*^f@*N+FpCG7H$fl-ko7Rr%nbC)aGx2UwJ)#>&YP&OT}d}2PxD|y902G|{eBR7)@ zl&nB=DN0ORT0f4BT9-2iTrDkg@fS+Dg|}5rppMKybDQ3sr?Wd7_@ z?}@Q7#J+*K04q^4#`*V!UO&M5hTmT@g^m=oFKJio>v2N){M?w5$6_!>7PvsnaVfFcNo5{RrhX9BbkunQOLnqhrq|KOE8z{NpIZyv5JOQZi? zT@{MRGQ!I0L+RcJ;f`2 znPo7Q24w8MGW#>aeC_O&wuY$v7J|i|teE z>w$Gc_I9;uns%;_wg;Am;H`55Rl-CKCC{Yse-Iz8+m!BBGJ+?Uitz-Q0T2lRQz%d* zXzs&;0QWfk=O^EG0LdWkZ3+vpq_ZtrYuV2&C>TJC=|Kn(Zw{fr*_3JmNH@I+5W_z1 zQiY_h?$oQ5D^Nxe#G8=7F(C5m6p6)->@9Jz$oZ<7_ z`qOqpA?tjZ@seL@7TLe+H}B3*Ahfxay+4ujwUH!}waLAr<<|?^nXi%Y{ zsY%-Squ-@uX{p?HA8upmoGv`QQtZ(O?pP3Wxjqb%x9vdWi}_s-Bj2fU&kxH4nIWcAq!~+&llz7LDPj|(=*f-<1QB4C7hHUE zOYI7+`e%EB*)+hf?de+^3Jbl0{!!*H_hXMS(Ym8F`$8*#VEFBKobxv2%+%EOcJ*{{OgjJ9gnOiW%XNF= zd$}Kq@`NKWNU3(;*bczG{ITZztZr{t;N?WGO1X2op@(UFZ-pRc-N9B5d6scewv{9? zEE&jZ_%-pJYB}Jyll86Oqw!TFCeU>w}UOZ&wI= z8+mk5IDDno()NV-@owj5&VS9c_gWZnfV_TZ*CYiL2Y15Hn{+jD$4_6kgNzx2mEed-cS`wUQ>a;R4!ldE97P}tIew)7$~yxQYGY^RqSU zx^^~+WQPVC-~sflZ1`t*#>cOih8}hHjM5V%kYhj|lG1bCZO*>n6W6%1^zolb?Oz7& zM`b@-VSP-<>3<7RB!IE+gt39d=d!FWv||cJOmU55jQjYx9Wm+0y#!pwnCQj~`O7b* z>3tEOQyJyV{VW@+F>uyT2W;8)u0d46*5mWw-wb|E%GfShh{(LZ*xL2WTjYa(fgSI=9uHk_z zQ+~@0lk=P1Ch3+0_2V`-rT&x2nu#`&=E?q{){IEad0Ui6I&qQ(80u`eG<7kbksrL) zUZ}j{(=o$GwP1(Fzy)S#jX)j6A{{~UHa-R1C$AJ~3UH2j53Ly`fHY~Wd&)n_dRmTb zyRS}+gCa!}LO2UTMc_JsczcgGtdx+RmUfZio={6#%8_T}xMPSB3k4H;(p9=$D-YJR z+I>Ah$_n%EiW2~qX`6)Ju&yML`$A}RpsgnhF%n}MX1+m>s8R5an3*J$^%Rri>1x9&dg zDky+xUdZ~!!ngOy5%p7!r_sETyNhRcZ+);v5Vbbeb=fnn;DT7}j>}K&*X=jXto-#m zEiH|RBkDCOnJYZz>(V&%>@G8!RNV7=_;H7VUaKk*g>ouf8gwNU56vY|FH&e9GFRl* zFGWNlS{3i4?t2Q|YkRd9XNfoIx~W@F3C`|)WrZIm7H9pEa&uh) zV{y4LIp?oNyHQFs=*Vflz~jcX&zt~kK@XO+0)?F%$Uby1=nP$c;u{unj|!>|X;XZE zDfv4%203v}pYg$N$3W5W!Lz@z2y8(6%G?)U%fva&9DDY4{MK`6e2PnNxe7Z_Jofcd zBcW%7ly92I|fFZP7y%DS2cS8BDuY{Pa;C+v_1qO9ans5|Mjl1 z0@JLSD9qVB|4BnoZJABL!oU-un3kyqfY02+BTYZS95GjHDt6JK8Y6Y#-^EP;m z37AR&?1p!HJHoo!paoxDU%&02V|f+wMWm{K2IRto2L&x|Z!CEuF!#HiMrtIJ9dr;7 z0srz}6C?nlgRsPqQlN&2fx>YGA2{?I0=e{{6;)LNSO*|rqITxxML9wu+*5$!+zcwq z;3v+|&Jnaf?fvJz29`#V3m~eA@>Jf0$HBv7{)xk9glE4(VEDa|5FejTv!(w0%dOT4 zIjL<{vc$s20JsMnWRV?4s7`s!k7-K_E2-t4Lwl2k;lnjx*dh^8T|Tt6++`Sl;`iX- z+>th=(*|Ex=O${R`K%ZzsGCFHDc*3%76O)S{1wQ&yMja_+dFNt@Lm3msAvN8Cx);`O@Ca)!R=V-mZik$bKEacMyR zj(^>BmAUMGs(T@k>zOp(+;r*py?r?p#T*Jx12@ZwSL<~Q1Sux@1X{hu6m6*}JtqO9 zDPo@*(u#{^60dpr2e_vh6{m;4B|lXrqleERMiSO-Y+#oU6Ng4 z0?4W23#_UuI(v67=GejySSbTpL3321lF?SH;PGSdSf1)4L zPW`hhr#MqO2fT8r2Zt_bY7TfQkAf+sDhor;`+76wn%|jET=o4sfI@Q+^1}Hj>JOkr z?u)e@A|C8RWP|$*Ok3}-)w%=zXGuRB&Pj%#s~ z_63H^<9zJy*qG{Nu$_Q5aKExFI)l5fI*hMF}o;Og*-MPo&vCe5q}A_KaCqV%JrWZ|*;; z;q0#PDLKkpED8v|iPut~(=)31IkR!a7e3CWs@!=93tv1HzW6R|;d)P=UrpfR7zTUa z=Wj^h&Q!J~?(hIhd*eZW{%NMQU6x62uKoxd%f(IJTRgkR*4|uT;S&PIWmr0Ie0Nt@ zy%15A3ToM0O~qgBHTG<6j~W_IdsV40HzLr^i60_1{{8|&(Or<*8@AS_f=?-U5tqx> zM3R9Yeir@FGc_BpZQN5Ma5Kq~PWSc#0YVKA?;`nm32hJ$|aZ&f{;*UKR!IDtCxI5 z{Pp=K-YJ(FWZ;pxZ>ctd`mqv#JS~YJa(y=;T8%Nc^jb4StN9|{52KR70LGYFTk$*tj-iL zhMsKwTl`gc1#9MOduFgU#FN^DpmdBXxfKou?|EAa$Gnz5qjFuHBAfZ&vQ4kE_D7rv zJ7jqQ+`1Yep&P5+O{eRB5X5Es{cDzLi%#=C&H3wNe!9@Bs0baEA-+TVt{Cn$i0`zW-OI6) z@2ZYLYSpJR;(~drzYhr!$l|szFpz6_7j#MMWY2b&KO+z-s}@zST#t zM}jnqKcnyOsIjIK{kj57hU&F9yTT11-b~=}*X8<;!jI!Y&K)OWB5u;m55hBIsLIUB zm7vl$m(QEg^RD@1mco7$+SJ-Cc%aTCA?P#w>Qr}rrQM{_zTu4NhfkS7u4k~S^cW1l z-g2v?7V3XBsQWcnfUzAC`1}#WRHJBhj3yZ|2V{pHKC z(ZaXI)!)vI9XEg@$8>+*UPCcV+uNhvSD~b_(i8!lcsdOr#+e|UuBZKKjhzp&c5}A( zR*y5`4+I2{L#MwLJg0Vo%P~SBgv!WU z|I-4fFmoRLo-4EMy)X@J(%#uVwKZ`!l=K*#l8ZNdA7ep(+{5*BO(9T}$ji(Ioze41 z?dm-pS-*uD(zBc4Z0@16i;FMnwtJy)=Lwio4Pf2lPEQXgnL@uieW2neB>Qf!0aBF? zRE-7F^ZMi&)!<8zs_+b>+)m4zy$W(e89|i= z&j8o?P$?PY!sTZYb=>ems_S4vytgnq;1$OMeW^#WrR-?H0mam@$3T|3-}!cm<}KOYX>4sHJlx zreWi?eAGb0V_)0eWP$P7EZ6m}y&3UC2K!w(^hY&e|55fG;2NeKre8)*6@N<<1Ya?O zh$i68QDL6A6m@lmhCegyIH{V+(AO7v`{I!3Q{9E8ru|5bXDvVDqjeKwxRCGZC@w(( z$a+V7*z!!%>F5QwWv}oUjK3{+vIN(^LsIqx7J2{3s6*N~`7Tb?mF8{wmWndsZ?I0l zMSe(eWgjQrF8{@OAo|a3CBU=)T$^1ww>dYlInnTdJAdU?ja~ba7?F#sYE}sC-{31f zflo^tnyyqZ06b^7DvSIy0>z0YcsGF4(BNOC4>d_#M1r}J4id$yBhx^3!rqPUx^dm+h#7W(l-=_5p0 z)oiVMWl?UjMXPDAVV9D3E7XAO`0^`WlqE?NgID&?(tI1XD&<(DrxagPw%464cZKO= zupsuxgWj|0L)z-L-RH5G|6p)8kA3t9DVU5$g61#v@td%!+B;RXG6%7jlB9c%75>=x z+sEv3tZOULFaiORDSkS4{YqXw*3?qlhuw6%hO5~dOpJ?TZOukqO%blpy_Chn(HWqb zA#dXAITIF+cwXGl55tW1^%?zDGBLl)+=@X<3leYHe(yt(5vM}?#~+SSy$u%i@^WrC zZve-0e`>x?Jr`g2D&MZU*aN_=|Aati1ER}5I*j-QeiAE)SE$fI28qi^gW+pIK$Q9R zladsNVjo=a5jURDJZ6MeE8eXw#(lrfr;agrYf>*dA%);!C=Nw-XEDaEp8emfE9W{s|G{ye7-kA)%6i< zNn;-tNlu-f{xw-37Z9x}%(*YgLL+Ef^>P<%w5`oD>F8jUV*6vvk_KS*ghF`x5Di~6 z+SxU0gXklXjGYkx0T{fBOIsuJGu5z{JRZP6g06-1qn;jXQ70(;Aq)Sc zJW`?@QgT`}+O~GI7@+TiNlc4jz0+MN!;GPjg=p=KY6S)<1?@n8dsrE(#9SdZBUS*q zv%nkkC68b|O)CZE4$66~Ba^$Kzu=N`s;A0JbM9=D<#Z>A;ETARbb~0P-t+n0$1-9t zkC1`HlP4K@Gh4fVyK>9RQ*W8Su&fvW0SbVWS2AF_RBf%0SA1duFZFBpJ23tDHE;`S zYznb#z^*n969t2Ub4>(U^|ag;!d0QBza5*vRNT^N7@*QCI4W^2&5`fHwuzY z<+_qAXZwX@LU+K)ds1S7c|F`X8XaF*WT-WU=LAvmaow$kS8(lp#!EI6A>7(!XCQY9k_5p%NQ`%!-tm#cdox1vaz)nz-ezSCwBWRfJP?{ zvAxiOL6LoG-%QW?i|YQMkL&;P-x=`ts1CsJD}4MwuT(kQI&yYc>3fGz=ra$u968YNg0f2i^>rLw2T6%h}x zyvQ7*shapfMG6Dd33Htqaggbi&I`m@d9@Y`j)=iQn|&FNjGZEOiro7Y$nULt;)3AV z_spi4K3)5>La4UjY`eOel*bDk`?>PFpB=i`<_o>(u8Yp$YDP>07ZGo1uZ)50 zLkFj0hTzt~aROw`@Xq%&1$xUb@AOU$5c5t1vAux)F<0}7W#pl0me`TvoBlOxx=KeT z``fVxSfyKbNu|E4W9y&9xmm|KC8!dR);FbIh~~;XHDUXm)zeH>`n~dgJX?}e9Q#E_ ztr4*mLy4oBpEKblLPxZ>f3>rR)VKbq)WInV!iQw_)sF!GqyJz&$=a%Wq2t-o?u3_m z+tRzexi~iPlXUy|mH!f3Ei6~IHstWd)u=$P+|}Ylkqpkm8$$MO_S%P|sq@7Mupo%Q=3|}0 ztgp!wc;~9~mB4to%*66?Nwk-wPR}~kT%*rcNizf@B~Omb+&rmT)9(p&=~80h!F6H@ z<#7CH_YQOiH&Z}Pq+>FVON5c$7?6SXF(s3qf6#K#?~a$u5Zp(G@iS#k8szI8q`&-d z3^qyf?+M-RFg$hYlx@EO@VG@D^5Esrc+yy=mK-y;sxGa{0%hg)86fiKXd3Egmyy5A zGyMC{v|MgbUF2wXD3!+C%0BVCDwpCvh>GMO*2kc46|gI7<>czuHw;M9OQzpFq3EV6wXTzKG7hc13c`<-jnhfX!5Qun)Z8ts%Ox_;? zxa4&6eMO<_W}t0TVp2=|;T)RK@e{mUu^AEmc5weCG5Gp)2#zb197-vZi7m+N7VrQp@Hgx*du3 zMnu!U#gPj;iKh)3ZPLO{6D+%_@= z+zI(Y`Q^R6cit84t1meGnS9wjEy?0YC9g{wwCnbJ z_SapIVu7nZ9NjpQ8Ly3(zYdmL9pC#PdJ)@YJrHes|ho~&N*Kykl0|aLVHlR!!J14$kMaw zRz3olCZ@4LZ4GA{T|{&+fVDw&;vV}c98pHEM5MR;-7KvMm2x{H))-n;nrEQIEX~iq zR5|JR;d*nJ7WxXoXYbpN-o z+dFEc6=#JeNAX8DrBVCblL>3#VDnI7V?Dr|l5v<$7XPz)yH$E+8-&xXKNt8L9n7uu zVeBis3d8M}<ySkdr5d%HibVI=`My#O9f z09{EkhM3BS{aLo02Z4BeP~;hUD#@47u?%qkex}#L3$nT7L+pF?7U*Uh8NaUd zKq;v`QC;s*506v?S8%UKGc#g6jG@+kd3~tayrRS_kT!NNIq1=er|&d(xl!GfQ-`o& z5Rg-&qBOK+;oM6|J+F6yCN~`%dLDi?3VcoTXwn*&W7qVFOl;V$OgCn`((~`o#?)24 z>iptNfCc_Dq63jq-45mg0H@6dd%P}UHb=dLLy|sxbQ0iiv*=O!)53OlJ@@jUT|2-j36(PELe zc zcd8j|sHUk~e+1QwAlbs_1|&mVm9ykMYeqZ~f^i=gf0-zh_aEasDCYSjK!giYYk>@c z@^MD_m2e3~A0^+PLgX{RnJG;5vYPUQS6~$U{g>YM%iDnNwx{sE#XY0(S8W|RL9(Yt zet}kT`-i+f?03)7XE%Lr5iTK!B!Z8GiUIJXV)=@+JPWc;i(s?{itII2>{eYJ+YZV@n51JgpO+26}xD;ep^}6C|eY4IUJagJBUwmg;W`#!2-p zLhDw!=U71NB=0>(02^p@fWQt!*J9F>?_7<7TpH8mtQv@S;KwNEkhx*O$#nhabs{k` zq(_B5AHK+oo-A?q-<=tpeX_ROx3}Ec!#rASkX-mCw!UPmewCp)h2i`kR0^Po!IYBd z(Yy}QJXAkCaZG_+Rl(K;Db*udZvbe@WsD!&)Byh90%%HS-wB^wy;paa{~<>ctr^b@ zQphxtx)0QUWr>5MkT@Nxtc)roJrDITMX`lO+Xo3^*Cr1gC;MQI*BP3b$Ex-LhGj*? zZCQuWn_w3FM#VMJ6g2oN>H-+Og#%Ojv`voep!y0^Fp%E~=Ucqnt`tL}(myUaJC;{w za*37Isi~+8gv*`h&%ZNvmf5tb>7FQiH(ilcn@WL`ksa@XS^LCDnj~O#hq%(z@(~F0~jZd%#L*IcgdUITF4x$uHZYp(y?q}F)&|?!il|F z4H@s|Ftw=LS(+bdk>Nu^d9HQM=o6o zggJD-YboOvG#|%1;nC4kCt(hdHp@kjQ@H5~G)ZC}jtdJ(+ zuYICWMhriHhxkKgz2`z94zcFzErVck-^iCd1-$`;?Xjq7P^XMu2NVVy7$6xPD2E&b z4xp@#@TDjTHtN3U$-vLLn%l49zjkl_P{w=U#)1tU&&G_B_(ub6{T7< zCJzOV#%i~zAhuCGYqJgrF4o&HKprD>E3!txGW7tGLQo4{e(tf*AzxWiT@ea&9%M?5|=x+##J1SGCT8{Pzywa1!>RBZjnin>|XBO~XRMZq>%;-vl%& zIIaWgU^95wY5P~iVI(Jfzi4*L`u6nn^yb>!J%G#HSS>x@5>j{eEML)}>^ry9Pe$1R z%uip0_BAH~Wvi0r8!6L28>}2tVBQ5E%nrl#)MRGo_$>t~-O|XN%Do(U!#)P1wPj=yFr*n{6-;X6IzU;1<)zJU zx6}|w?U29i`D2HSx)v(!9v;zv*wunf8-N9_Js9qjd_&H}1wZuP_oPb$U=e~||Qe#B6ke^0EP0LmJ- ze`bewK0HX_&9-0w)!;>nCXxMTBPJCR2V;=(GV!L5lRBC0-%N(wY3{IGoW4XFv+_k_M~0}g5Q7iZO~x|A`yo#UJ4>(`h8Kje8~qu8n8MlwAgH% z?5vP=&3s_>BvRY0d2BKJa_G?E9kEl`7hWgmh#f9$oWlq7>(|Y_)$&lqr$(2OtYI8T z`G+ahB_NDvo|T=&4@Glx1d-BLH9eRdJRCv1R6iPsW;=6>~5a;lkk{(d}PzCd1|-)ZNTLUXJ20Z3iH;jj~VB~1S5hga~eA5r^v z80#(TX_2eIZ$83``e@-sda(4&leY9q79Z-=FR7-aR!?XN^Z|waQU?TiXmaNX8&Ci} zKFt46ypl4`l*mU!o18piDzM*Jh~;mN<5N*l`BY+DqrGNJ6p7eKYXw({h>gLXmc?sQ zQUDyfIyg7mlLiA^2gtvc=VYsyh$8FJR7aQ>`ID6dWPMCmB3AKXym+KkFM;{|i`yFNI=ydCMg{KwPN4SHIm}*{0wVy^dH8-=L&`Dn) z{i?BhKU=riq2)Ivn+_Nb^Wue=+l%M&lFTxO9s?4KmVV+z&e4SR`i(;*OF zzEB7tOQ+DbR$I!R#vxAw95~6MUr7)X4`i%`ZoXf@fEm0~w{~_nH%Afo;P`>hLYeQX z{2ux-5LZ@iU9kR;marJHx3=s#es%n#1licw!d0qt(`4255(7BzIo~J^6Y#`eh* zIWCDAatvgK$d%hkvL{jfhO7WuN*r+VAEFDearK@ll9~t=)-7*Bv2Ucwy*~_YY_eiD z<1{E(*NmVFMq7N^wjk8~P`QWP1*qw;nqWmM2B3;(-)b==BuYL+*8K;0jQMEk=MxZL zc9|$M(GoncdO7;$g)BmJjr;@B7q$pGdSzab|Esl`dEzGytaFyWnNL{QJJby-kL_6? z1ix-O-mE8(3U0$#jEMk8d^{(|cB5qz8aX3<_xZZRhvDF!Sz7S>~R%~Lie)u3_nJ6M3% zupO4%Zr|)czF>gJhvc#PuG>tM@fvQeoL7rn{_~*D{WX;!tiZbtnTGhhghQS`=Mn=< z#t_%qR62_F^LaYHSX4y8IOlR}V@nJykv?EcEWebL{yR#RNwvSg)4VQ|2*ts%Cgg*s zTqb!DxjPP(Pi{m5XSp9N55*roEQjNWV$M5X$SMj3aPZc##j*hrP6+bU-=BZ9*Y>r~ zO#dt^IWw{@1`*LE`)pm?(kR*`Qx*;wthG#q&;lNDk`eV;>^bG0a0ppmNY#ja>X^W zD#DVtTUG{sgEuLOn7Y1WB64KH3YuGUTuVTg^Nj|u-Ee@K6(CB1ZYbuMj%l(a9*r+1 zxSNzLsz8vOQI59~JCIPeD=_D(RW3BTonU!JX`uJcffD6uMguM;I37nizK;K<`n>E0x z_2`r-Key8R<&T~s4J0v{?{^4f95DkB`SSnl?1T^0s{b7q4O>nz77-DdR;)NsV zRP?&7ZN>1yv)N}Ksdh(xoRlHE$kHL-xp6QJ zk{F9G*Feb*Yh4gPWRr>l9h>nY#*d>;+}nqbI!sTCAu!@q}=tU}%YF)lY(`_SSy17p?UIoh1>FM>JmtkZ- zmJRs+@fT1w=p!Rw`6c>CYj2*FiJhA7xZe;!O$5D3fRh2VbgBjk;R*;i z_$P#|9XoBG0eL_Kbj+nh!-3mTMGTHtoP}dq)ViV9_5fhM+WzrM!MzjDKj2AeueM@LQPef?F^$N|^XUhfeIvSkyx&u#A0=kZ5%%+YeJ_bJG!dx$OPO2_>2TwSPs9#G?4p z;RT05P_|^V#q$gfMu%}4gM=yvtogvGB2yKF;(S8`cbI_p$Gbbl3j#&Qn5uo)-xEZV z$>cgvjj#DAWL`8hOZ|^!n#vL*Eo7cx{(J!hjS4{q53Zgu8~{|20tB4R!PuG_xw!9hOBkaI#ecq;gz)B}91;5HyLHjc zT2H598-HxwmHh#VRl}Yv5O{S{f*DD5pb{l+dyZYj^-OM*PrgfUidY?0xg?TQ*WVVq z42rdg^71NT>RMKR+i9JL2wGFiWo4zrnoq;SAckr;3WvG$Tk>&x@{sIpX85p7#R)d= zLabr(+{D(%t<$q_U|sy*67k{>?0L}TlF|-(K$CLb1O|Te%$%mi{ti}Ly7zx2L z!-`_G%uN|(3btb(PN$6A;tDq*M8nIf2D(VT0l|L$ckaBq9~2rstNA@6)ifS{L_|Zc zb_i-(AaJVI(|zjlZ-&w#2X6)^1Wuw*s7L1-WRB?AfJ zi}FSAGw!X!+CgycnmI@iV>$ssTH_7l?y`^daIE~p`%|)tBn%SjFdhD=ThB>MBd%Za z7yxqdMzYrv9zQ^y5cb>Ro;?2T4Wkmy3<{z}v#{Otr5Z+#q4dwlCI+e1K3;Tv~Gb z#HlUjtgmvGdpRL-SN-SCEpmNOw2w_up41V%kED?`t4D%Co8JBa7?)=BC)uLQR-@ z=q5#OEhT501bB@pJHMwlK$Q*)8-33lEJ-IP*2Ok{qNf^qockhD(&%Mmkx)Z?Twwb9 z892lXLrlO4CR{)YmLh2su{@9yws$SkKfJZ&b*p-~@5E|#g$Mb?ipXw5v=VdLfxVfoQo!%S@-VZZ!My^phwTz3zMgz(mnWd%m*e%R0mmP{N^`_IKR zxe#y7*QvfWBULl2>+P2U2iR>shvnH3p6*ot{M!8CnAmj zmQ26{P_l`ekc}8f<0oP!4zTuVKl1s8ETgUYGz<(uM7@9aj8HK*5&;?*T!LV^pijKE z8P9zL-uSxp$7+W3uu z&n}Natr9!M0ZR4Q7c04X-|@k z**sZnWMmP3Er*(QSxp3vggf#+s|uj0d<>N3#|GsyQSpx7$ZlgXejFGK!;EeV!56oG zlNAvhi#_0R(N#Y2-F%n6^|0G9-mJ18XA;c};HR8bMPlKN^;c4$PW;jT)^N17!G*My z*~ja@f2=9=;s{S;JI5DyY?ED6Mx-?!&CRd9^eE{*>?GHzXg!QGT2Jv|>x|er%TiBtDVClS(J0*2L8o|A4?^|r^^DHgI6{iEm zqjpw;zlMPBY9PUE?y7LrRNFT&7>Gx;v|eWgixdcve*e!7+mueOl&KU6q>VV*38a7+ zS(x%uc7V#?*uCC8o-z^RPDIV>T&~-eq9NZqV81qhs%?7aOV{*!p3Bh_@3ZCJ0=9qi zIXM%mxh#i`duDL< zKHqPKl@m$_-uCGx7!oE+3dP(d9Pg|m97N7E18X-%;i-Wl%XauM-qa}3f5HmE3H7!T zK)i)Ftr(%}#ypEwihUHI2+j-iOR-wRL&RiB9}@iE?Fe)FpBb*1ASPzOed=cGq$^P& zr%#Fr)-!J9WDBZXK5%&I^8-qJ{o<3+;lmo=n_c_7Zr@&!zAgeBzF!vuKxYRT{Sm<| zOPJO>F}&8ke3LkA_>P#(^7q$(6QcQ|!zYy%;3WEYR$uneEXPr0JtjnvQWuwEYWlM$ zo^ZUWx2CCrmwJIte5dsL7?OvN3${)u2TXpiOCeHymv}wMd@wIcK`E2jSOWYo4uL_d zbE_#eD|zqBs{nGPYF(}OLO0@c5C&{hP8K<b3CB3uKqoeJdKL5tkiQqw0;eP4Qn<#=$QQqcGFPMogHz#B``ahB#sdV! zW>iB$gEzK2668fSVUd6GMR$I&cU8_`Zyo(r4?{9Pg!W}eZgiv}08@Nhckg@Ba=J?} zC$hPvdHmO!TXxcNp2yhc%f5d3|9;+7mJ9C_x;vr4CZ|qp3=Ej@om%G|v&g`CXuFLE zB+T+?tS=|@MX=dBH03v`X#RIYA zwTW^Wro|I_42X6yk71pMJQn}IU{V=*|G zE1if*>4Itj?tI3Lk-^0}`Gcl5mlFNvwtsH7^Qy^?f4pRPM%?ITvgF4T1*;WhBD^%C zBOGE;_5-UR^y4{5Hx<^^Pc8KQULXWs1RCWRv2g%{$BTsH_C+a>N&u0}gQjq0dSE2) zw!7=Cj6$j(t4Y|ID!KS^Z+qZ+*zYA>+sPW#=pru>L%^x9RwUO?Q(W|s{ZY2W!F5|}KRT)n#zn^bJ@HZbeBGy^yHR3oZ^rUaqxB~R znezHKYTRHg#idi1u{S~F0?45zwlp(oot@(jd*Ce-${s5W_T6=^86kHvmrc0XVo^YD z0kEsh7n%v6-CZ;C+($msXrb{c{$aJWVam8yDc6HtE=48fdx>dnr0A)Pd5UE;7!xv$H#` zPe`2&pk2frLOxH0zg3KXJq5>#==un(yFAemKjtGK6|8XF82GFHRDuIg;lgtf*?d9| zGsT6NwiT$5gqTWF+f7~jw*2Ga^39c3iKI9QyBRm@UpS1qx{`a3ZDno8((v%5YW9G< zP~x(*Aqwel%X{z4^0dRw8-#Hl*?!djWDl4nf`736n7lEAL8}N|nphdGyncSpkG%sP zD?So2IYhLi~7Sd*aA_>c%}O8P+;v(!VzdYW21f%ewtJ@ z{!KRPLv2m4!ssng-QcCQ4hwV%#u;nGNl4^QE5lNN7gAmEl7~ZXZt6P2C{rKh?VC_2Lo;MG3WdbR>6^etLwYX zlfxW)IeWuP+Rmpob{A|rEHOwcIKLvWB14^bZ2&C|9n z3YsR*<^ZQlO_8A0S@zGRPkhkauTLg|{^2%b8v#NqS_>u;-QinIX>56oL!4kg<9(xr zpRe56tmJD89XY{Xo3-mkCZw!qtNC|-ugLt*$!G-Cb9XqlA@ifgBvOH4uLmI=bT@=|7b+>niCyi{Xn24)v22x|L{l4 zJ@|3(?7*>LJ^?bXx4}nPg%!<9%-{#jDTI?#?Ucn45pgbvt1jzrm^4T!_MykqBF{${BfXI49sHCS}w zu};kF+t!7%wVjky3# z7kq@zotEk+1HB?7`T(}ya=7OF%$6s>UIQ0$#99a~u485K%E zZcJ3}(tF1@7aA^UYnzWt`ZU>m$flk=AhG41!_8GT<1-Ypx!h~*kysNzDWaIdqU|}6 zx5_8k>mTnq%A@1EzL_lXnS)&&3U~igi0YX#jK0A2mhclgrm2OMEg@)-MMM?kqr{;} zxL{%39oZmwVa@A9xrlU8kq7o?vpo#U06h$Xl>`SMxsw`P4Rr zg}Ra3p>7uyUB#k|&u3TM9vbL^?so3YtH;{4O(i%Uhe($mL{eQ}%WW=wn;@Q)+jOqu zY@5|5H`SC#!IW7~K9hV-Pq(E<-FyReyn4}p_-g4O02w#GZrK}QT~`g=oN%~yJb!;a zUs0P-w1fGtq*UD$A5FLj*NFeg(*oi=NPP9z{obL0eL6E(5ZrHh^(qRk{rG$1kaa`) z`B*PY^|D!6%LSAs{w&!i;|6_1UY`@n5!E@a5OlM)qU1+I#8v}XS+sn0iU(f-lDvN+ z=0`@Vqi?OHRWban*6_`I4lI4d=m?>>A}yUC7c9`>IW}m1RCno)!hKW_8-{!wN3Fu^ zlVGf`yN4(5EHWbmA#ccPtwGD);g@R{oiDV(Px%Pz0E_AE&4-wwE)Iuyv{3C0ES&M9 zP=7%BK{9P@jEGsCc&gbPz7k{FXd`2xdr0P0YI{J#f2Mim9Pookcr-&9hjRT8I|YVO zND}!I5~8jD2BrZo+s9!KNsvCw;EPsb#Wt2KC>w!OOq%mkzc1Y#SfVD8~ zequ5D1p;~d?*gMu>dLj2Ip#Sa?OM|UHjkvK#tNpQ1zw3=@Ck(feu1K)6Ny?!%#H*( z65jQN#W@G%Y_Eo-$-Rm7md)ua$XD=BUXhCOy`Q?eB3dQV$({M8*?p%608>anlf+lH z5Ks7#mDzV1%*+*@fHs1UDm|k#+P# z{6fd-FBek$kWfJ~2OI>VlO+uYW|+L{U(;O7uLU*)nhFp5my(SJc*Gx_ez5LE8|Q@g zODbiYr&X){3_#@0JA;Kwe%XRGlC;ic=3LJAK$bzk3prf6w9dX9xp!k{O7+puHUFa> ze4LuH%iHrQxyAP`qFrMP9p?Wo_GbANmUYV;q6@6fI`KrqHJhwNx{PArih{HqwXS@y z$@tSOmnv3kDc$n-=gL(3{CwB=_({RHDzO-^4BV9`tfw`nd#V!>q++W-Gcb&N#m7Up zcnkce78EZIM}zI>_TQQ2T}^{Q!-nerqXx*3g-NZi9yiV&3w#!Rl-e@X654ia#uF zs_C2Yb>dDe+#0S=>3V)LWPWOgITQ=w(3?hZzIY-)#zh}s$z)Ug0gP*Yb+ry|It+*~ z33?{oY`PBt31< zF|-S=H1T5r-+!0*GiI`(@b^=TY_^eh7VpIK(Nqmv7TetH# z1UIN@DsyLP4)}+k&ru6c6?}blUxxsPZ0*TY??SKtTC*M2gb2fe)s*c{o-G(HO!hqL zb9xsi|CCJAyy!V_2L#%zJWh*4kb>e5jxL;Z6-M5P3>^;4g1@z*QTuSg*{8c?d3?W* z6&|Bnvx?&&B*yEheWwwmXU~%f;;<(}RL~Oa>UtpTd|Uq5TSbrOjwDz&f=*2SW2aimANqHtV(*mH_D!XYlEMGEAB$e7!cEjw%HBSY(ycYgMqZ{meJ6by>F2R0${tEPQ;%t)AMu3Od_&S6qmM_@b1q;oB_{?0GZXcW2cqx{aNkGD}++Nv5vD z!GO{HUZ6rx|DbyZto(=7nWIJXVZqMLlRwv+3AZb~o>P31qahmJWWu=vFpl;w$Nlcy z5h!{PmlxaXG`7k(0IJuj&_1QJxDl@!;>mMUk$-Zwd56X{50g#Gc{sfrHW(xqhx)9hR8 zDokufA>7Gh;u9jeg>4UGsK`KPr#I)kOq9jSD0g9oH_Y(*;{4<&bG$4^)0mp7g^NCS zmo5;Nr#~y4A1&mvlQUu}9uo(d+k1p|u~0Nneb;$ic>2zb3wbL8clJq<&?)DJNfnP} zRb4p4RSw=X)VN>;04zXaU+Bh^Z{Trs(zvWuxiJj zY923Nkv!?*_U?X7Au3+8Yqfo|<9su)OwwM{{u8$t4PpxcBQMZcy|Fq=dNcVF43Nc0 zWZfte&%^hg72^+@z7>jrM9JzElaIPt1rn5M6qRqp@%Wpk9l+`hEBFX>n93hdoYu4S z$hrtdj8SzK9*dV>WX2GbdD_F&iYS0;?nmhdl-Og~IQZx-1>@|?=A(b^&6qw1DlJP8 zKOOomKUcGaN^)Z8O@amCjj=Pvj==R96RCyQN1uz&lfFVS$pBaxx|Pb)hf+-8>ECP1 z^=_ep5b+PeZ(dK4FZ$n)b|oQB6{X~rSsjIAB^CGGOM*5lsyr3Q&n#_tJf#*??q4ZM zSA57H{nY=69BBT{uGX#m>WCEul$GO&o=r>n0d6E*q zr%;KG z-#H;sCUfC0GU`uqkucGg9y{9`eyqhGL94Gu#0(}U#wRO=Ay|)d9S8`V$|P4j1k)=F zbZU8VI6v&_aNYVFOJK31GnZ~s)^|RxU1q8F%E7+L^4JawvBB%timjP(y0Zt&NTjHN zo=3UW{)7wbOay!E?3$bb>g@mCTDliZK5p;oT5^`}uGWT$V85izdbJi|-_5^pcNerb z709|ebdx3A_7R~a28EL#FW|hHi%c)$bZ@mk_arItaY_ADJ_9kl_&4&zS1@}zDVRU& zs|i!0Y&CjuDZ!!1@*;^i@%Vg2p_n!++Q_f&YBF%pWy^xc)pIPwRmlbF1knJQGJdwg z36Jus7<*|&xgkp@rru}&fz{ESJ^42M$^y4v+_%Mv+|{0if&ZDc-Zo@hIpdb5#e zwS7SH%iVWxPiRy-%R2I7s|9bwS|X6=E$z7;T-Rv$DdL?*^LYRMYOc5N|7QWn@6*}M zEYM%L)Uu*+6|ZW{rF7~aR@&(&HV(8GYb~(vjlnG;aY#8x4-I*PN<>PNB;n#PUowlu zg0z7v?={bh9tGv!s%wYt!%tae z1Fb!}B?G|E%2y}k=(R(xX@Z?zVw4NW%@$tZd8PW1r*y`sUKTy|-4m;w?Td?x0vh7? zS2&!)0s`imhpl4asXZ=#HNg}3#4iSww*R_x=I!fYNwEKPip!-aS|FgbwH5lv5xxJe z_v>4o`X_QokF0vN0-Xi2vu=UbR06e~cIkHUlq=c?}4mA_FIXo6~Rm91#HaJJR15d<=!r1EQ*+ZH!+?Gya zT!!Pqys`Baphbh}K$KR?GsH<)BQ+?=6ef~yfRT1a7eLWlaQIvFzNnXn?#c!9> zueB}%Lo8Q8+Ct{F^VelE_Djj{&+&bRfZ=@aD0LJTAC&RcqY$)TR8^eVbn6$=B!5@! z6HF8I97`qegrAT14ODFjUZ1c`A)Ik(L+N8IT+sXbFoXWZEFtU*%CyZH&!kST8oTq? z&K9i7K7=6+xSc+PTB(Y`V$5=6mHIB3-j^XbJ{S-3rZn* z{GX5T0B)eRPpJe&mM_<2_}*xdBFZKFJ*+Yf==KE2 z)*dXkk{=*OY%}>4hN~mEn9fiSf!PE7CNkb3d#rxH5DeMaatH}l!8mFHJlg-5^Y5;W zd%zxD<_F1ZVLOq*zEI*+(1=3vtLT+3{c&E&oD55V5j`7h)rD9XBqGHvLrjm#2h%{llg}iM9Z2JaM~^STn+`KT z8tZcK_IG9{FJBZ9Et4=lo;5=NU?iY=a*EiRwto9!6=Xnj)^`Ab%_a(3R^_CgY6Bs0 zzK{FlmK_cj&M=NBA&w}dmAwC${HNE#03$)yQ#|MV>15InqRo>0fRN#+jp)jQVceZ$ zPr=%Xk}9bK7Gou6_{1@!JXBF|#NMux`EZ;`j(F7XH7{1UJfoDjpPkyHV-ARX)@W^` z`AosdvSDkYK&%!^%LEWxpe%xSbX!tOP(Uj!X778>cFk&|#Y)pSbsIcPBjaDQbFz<; z(Kx7P7m*zB{Rjo5W%ijVjOwAeT}EGdQRjk>papf5di{{I`K4ze%f7Fp;6Ta|zBS(C z@Y9jp6M$6Yo%oM%PzL@UfduFpF_r=B1U)!o4zR~;Dzp5;C#_vMNaU(VDVWprIC#90 zK60T%62==I*h)Lh$jQnEJWjw|15Vt&kmE&pC>K-jw%FXt_`HRrYrHaPAV~4ULAa23 z3L_2R#w-FGS!%?f|3_)TkeDI@skB??FB`_)k z7xQCz;qSpR;!OxG1elh4y`&Pv_d$@RR!XceSm`RzGQyc@*TW5APYcoDXA}h;Uin$8 z2@iX#v<|3Kz&m>!c7guNbByXYe3*O;an#jz*uN&@C?wr}LHJ$VA=3s!a#h(Gws4_< zgE;99-O|a|KvpVVUGpF6$qbK-B^IY2efzmn4=AvYJADLb8w3*p+8eOD7$dY>IbR+e z!l{AOzT;J6BO_QI=%uiEsdeM@%)96E6UL+73=6}7&;I!NAXPjX6Ai*}@U~ZHoWUQJ zHyHL)8F`4c?`_a)D!)W9ucszWQ=$m_5)@%WwFb*>OER`eLZlURw5mQ^y6w*JU8S)pWRwW5_93| z?~7bBL(jBs&R*X@m@y~`)zX~~@6nZM9_X2ms}st^V{CQ1H2=$`!BtjP<#O+Vs3Y0l z;2`lJ2jK(K0kBNUq!BK$J75%>B<4&8pIHPF99^(7VQGEUg?Ow_E%XAK*yj_H?rtIK{=SY{YBG5abkFLRYKH1*=hIt7g4vWapd0I<{IEAAo$vJ(EBxC!hJ2;BU(#KeLvOX z+zJxmd2WJ`>8%|fD$XDn<`5X!YU^3j7`D4Tvcl@4RYdO0_4Zt=EOaBI&t=5O9jAg~ zI3bnb4$cS&CxjD=TGbZZY6nWory$QnH`|xuxWU$vY=&p3Kys(TXd`;`T8r_eFaB9I z^=GH7s{x>cflA1UCjWX-E^Y6D`d(j5pWG}D7I4*K!QrJg zM(C=`Q>V}F0TbmGJzHB_d8m>`dAh+06s|91LYD=DXaiaBCeTIS`yWk72ts;R^AK}{ z;7IZ9{-An|P;u-KIM5p3o@`oCDpxq+QhR}JdDf-MuJUtPVJ;vc1MrUz66BBhqcQOl zpp=H;(_ppVXtu!5QnyRJ2rZ=;4t=8S@-w$8#VZe z@?(bHTys|iI-ZUDRNJZtv01@@S%Ux9&wxM*PY{TunUz0n5z*U;LHJ;5+7ZM~(!1m|wc&iHk67db`)I6w!+VGCs8wAL+pd{T{!gclMzi+nqh3THVaZdf zos!`DsY$L3Tp!v99?~(V!Cfy(kbHk5G>jfO|17#5xmuGG=1E>-$i{S5&_e!9_3dr< zDM-1BdI4`ppw$8oBv-lstn(?DaP_c_*)%n1c{yfocQ@kGXY^mhcAlFU2(hzILW5u1 z6jDGsR;g%UU?4cV0M(?AkrWLh^YKT^`nGK$xC?|hP2UsGl9%NBC?+@|qPFL|r18g@5m^&a*e*Xv~Pq!fu2#CoM@P3Q}>AZD<9#kVx zF`7Eo7>~4K+r*&@I^2~$n3+=ODskSx#Ct8Rc1Azy|cgIwi+z`_8tEqHQWt+B)LwM_+RMLP{2B9;wjwy4h5RPBG zCv03VRkOD$WjJ`@fZ{f10R=uyEiLJeaQp*CG4Y_(yz^CA#b6+T-LgP` z>^lc&E!vMbAVN_H2^OalC&znqfp8+G$0aoK%ON`fLs09w3)@<~bUw@g`IobBpq@+V zqUYA`PN(S3cU?#n0O4+Cfu+;bI4uzIX5@Q9LTuprR^B7voPfCUME@l3M|VuYN&k-6 z0x5YYRj!GR_K3z+U1dD=#TXtX$&wTw%H`Km#DlL1l)-15>!S8n z)VEq4WyOL$wpTk(JmS-PCVlo1!R!*Qm-5)>XAjoWskW-q3l)Fid5}-Uh_M+_ev5h6 z$0xFtw{2g#6Im*AF<&=H5xDA`47W{5Q8kDWJs~$pE zh}d-q)D7*(TY>y!U+drPEp}^VNl96W0CVKVe`T1VmWZ9>PCsodD~FMiEE_VWfCmzX z0fSqQZAR}j2=ix@WZ|jpe@EmWUTtqHWm}uLt{tdyeHTBrhD!!alq+B zA^2i$9xYp;H&Q2;d|YizcA_qO0soZMu(u`Bu|98LCoXm(DE*|V!ZQig zB)FrVeKbtWrM7?cKHSV1>y5_pC_oLo^*$*{Juh3J3rXDvDK=)hV?XXLLdmsfwx8I8 z>P16EQLgQZ0EG|`@vCety2JDh@aX&3B@1pD zaBc1=svH(oP&*Eugsi&yl9EEVrgeHcCE2f{;)+vkjfH?qoau=K?nI0!exU@$An=rD zG}pKggQLVHw|4Hrt0&oYLm(b85sHOv?m3X1$mq@IA8ynIZO`a)1!oVI)m1AzS47WZ zf1?TAAkS8#D3SzFBKuf85>Nss%-yx5nwU++8cf(uD(1L)a>odtJ~GYT`Kt?WYu&E- zpL}`r=<4zTE469F1IbybJjmdqmT6 z_@dL#KW+EM#utID$y@Oq_zb_p2xec(?EU6#Pd;}nVJbZCu?c~qLo`R@@+m7KSilGe zT<)#vN1_w00Qmf3A*5l94;|wZ19yg$t#nqXtEePljNKJR2MxphLKp5`KX+~73wRqA z!=m>~8H=h%?fn8a0wtC5YiBPO7ZNK{7ZBAm;+t=TJQi>;97^WU#@ea}e=cy@1IZnM$-ukwyvVU+|Uxu_WR2Q@&RK$u6G}@30(xf&qwnfiN!n@3h9UW1dINwza(< z+dzdFcp?jgI#oz~r{8rx;&?;mgka-A$$!KrQXA$2-rLwXL^wl9aeTy@9u0*uyAR~=4L{rES=Fv8<#1#It&gC z5R?C->D=R)ZvQ_%TA8TkP)!MQ+}v($QLG$l4rMtXs)@pqoRahTke1^dVkCy-R8HN_ zIVViWR0|=88dixppAWyQ@8j|7-+H8jeLmOqe!pJNr}@^v%k2v{xtt1L^+npCna2>r@iUTc4=YKx{&p>?{Cn1ugqI!Iw2mG0ZDRz)T zTd#pD=;3-U$OorxoEB&|-H4iU60r+f_|Xy4a{KilX!K_myecZ1nQ^Ay0GilqSm*~Z zih@h#d(rvZ!r+o=#&`nyTF;c4fjzM~bWL$8Xk~o?V<2+TmEvAD6H!zq6ow?zJ~}nk zkBl2Jp-8U*U2&AI+)T%>yF?iGUR%rBTA$(dCFO9kM>u1%#tD}!VV}z`D5=Ui-Pcz$ zvI5}I2oh6GJl>i(c&;71jvGci8FB84ew=^b;|g6$GYft#u;e1!ObCY|{|#S+z#>L^ z>t8vy;@;yPKd-JCD67p_8&v6>yI}z&L8eP~NWZ}&$42Zof2-jPLnIbO<7$aQS{^!7lgKEmCTL~zwj@MKLaSGAHts{sw zpTL8fTvz(!9m3$XyXg@@>>kMgQ@ zVg25Ru=8UoJ-wqlO-qJ1lRW?tB$twznH2%A8laWyFrD&oBzP3tQF(|>u{>dt2jiM6 zOH0kG)1fcR9epck>tFlj#nyeL)e150qHO=U&BJ%*e|~D~nRRM#%BXJ|=Zpuh`-Q3+ zb_bhMk0O;j_<=lA3E$)kT^h;As1P2t+|3{R9J_YIxtL4TFdg(=v(q>h(mv|&!N7c zT$nNIM(RS{DFQ+tL|W>0|Fim6l}#~Y;Un%`OIPv<4Gj$pY_R9izRSpq7l3utgA9+ zQ;lh6C+;d0I1xF>V8IM!PB+wP@O<_LI**dF*U?TK`-$?RI}i|>_DKAyS}2Npt@nJ+v8{GC?o*i?JtB*eyJ&){Ij|$yD33_k2}eMw+?JMWNWf% zEkPSed<*lxzb|*GwFIukyBi{OV40aN;+d{EMrT>&IWN}BQk8RfvPT3Nv_WS~CWVG4IDeBdlSm0$?S&U#9&D4f`2imWC zsPZ%YE*ULE(Nla=8*n0!f5NBf7;P#Iyj43oL<+tlni|FrF(;FsR)FgarNldXlGY(t z0Ye6GJQ?Fno3{wOSjC?1tuV|0VIM5h6D=F_Ne=$bAzM9@?w(Z$Z}dzx@p1Pli^wv; z0~(klnL2=$0Z%3p@S2@t>x)Ri^7-*mNL_8Xz17Lgixl*J&N0`k5~fUmE>&wuD_EFX zbA!+gMh+r@2yeJX1_VP)31flIt`-(!Tm1p*2K&M#9x2%WYE&6^BsIn2WK8C1pCgZO z#55Y)5l8K9gQcqw5#{oHqz@r2$7yzyks52or?ujm5J(;s_?&ZU3?2U^tBM|m<@7u4 zhg?A;$)*IXF8He|=X=!?#aAx?+8>u00dW~7B#R(Xlgc^B4=`@104VlE^9HW%szWZK z_k*lT0Tn}s;~^J;_vJnAX%f&?hC}iS6U0Kd=gZ*P^UWO310%^w^vRhuj@#T^A45^| z7C1T@6QH@KQI$)T%w$&rcG3lS4(h-bQoP>Qlx!-lPQF)Zxfa<5X6UdmE#I`whc;yF z0f@r2*b4c*&Fd}lMZbMQZ73=DEZ5qe0^R`~@ntnzO7#F!xwN);%A*TcNV^G!+5^M) ze?~geQqHSicmzMd*^r|?O!FYj^n-{w8PonAk!)&1Lxy9+owCAx4J_QdSJ&2zveh=H zYg=50Q+c^0#2oT7JE`NN;*u9>eDpfc!}y=H47LbqF}k{d`bSQ4cd_61^hD^M=5_** z1@&cvaqgbm-uCw?3!?cr58o!Vop{GTu zt`LEgmY$99%(8pHP&__U6z-bWNBe6v$L{#1MDbw60vs~JZwAz z;{d*EOz$cAj(-1@dwKW+IzQ2aSQc-6Jw*oDjyu`Nv;-sZK1RgcS8r?UL5gQ7)rYb5 z-{}2F+X+p;asZ1wMZjaj@IM+zH{INDFiMEDCg?fyVImNn{P_xi5BSdg=YBS9nkMK# z1yk|H(OJ+Lb%wlEHu$UkCZKmAV7#0|J)?U*E?)8fvjEF#nLyeZvV8A%0`uc_`~2!* z@xvDVipMfWwzd*f8fI6Q+g3X3!EYX3DVj^&UY^WD@!{u7yt(H?Lbs=G@5Q0IDG%O@ z*wM`F(qM#Z2KzklXy>!9um1z#Dv)lU@2x$Zr5?IFy*b?QJmr>of5$Jh*4LY{U>?o! zsclou%FG@xFstqLs1Deh8}>hfQ79(d%&p2Q-~}tqaEP*n{oOc$Bz(YeFiMfK_aZ!W zPene5dg>OsM5Y5)NumFE-mPhr8 z0{=e^MH4OSH(U0ehAy1`-m)gXt**WBh$mr=GxsPK%1mC-Tm6Izb`Kd7U+rw$8Q&c; z+M2t9(MOBLN7BstmGP;*TaP@mc;{#;15Tx+C`1mm^4#j=a-(=ejiVAfTAm^QceY-BrsIVL;Zy>TIG$M( zm2_XU>MXOQq#A1Cb}Hvi(=9%9(-BZ$%%pnw`d-HPAaQJzJvln z=YeN7RHZ9uK?)!7O4o{7IO5S7t?f7br%ezwa& zq%7ny3R7U2QR6!8UvVvy=2Df#D+6O9o>bp@kYz>zFF#TYREjJh^Yuh8>XC>9)a*bd zFm1q|mq&QcWdai!1tyCwoB(>e_WAim)8c4j7fKHZCg8aZnA0@c5>xrCcZ%6OBgGyW z`}tm=Z>SNv-%>-eLGPc`ag_7*8f9$W<@J>a%q*wjuTN*gl z!1d8*x*FzQR;7A-BMNtNt|E;o*9{u1%h>K!x&(uN|a3xT5L@DI$cvoMVT8;e89av+&A z-V!iH>&2aZ%IA8j-D`Y>zQ0>X^TQSkyYC{V`As7kE|Yk?r+;Oo7vmKmwztaJTkdcR z-M_~Sogcr*ALs7c@NHbYF~P#*s>xfb2pxLqtZ2*npI2F(v~ce+zdqdQn0J;J7|Cl$ zt&3<+tj`XnPsvtP2w1okzzB+f#FAkb(<*HKcr|>dh#%&GRaF14p$b>H#z%mWqp-Rf zIm&rnfwd(vAQj3iv9ZZ0zJ&Tyad7b9FVL4j?Z1#n;Kl*0=)i-+6MP zw+8t+g$w=_j-`{0?P)$@NMRsQJ7sno&VHv{bOqRUlcP! z((NL`7j^oftdesO$?RmKoNS&}T*u273im2sIw@}CrF^!8jrj&!4`O8)b>0IAzKhdV z4;ZVFZ5earEEDqKB|Ytkr(`W{+en5;QwApyk5w`lg1^~%0&~x zO`N33k9$;43~Hv-3|YEB~E>uc7Eny zmst#s-K=TpaIU!jZW9<#G>wn%{VCM!fOf(UM`{ry*zKxUv8IF|Sevr{Q$a|it$b1X z@f4Ii_xFNSzAnmHoP#SriQ?g->Qni7_{6LN9Rw>%2Qx-{4Z03qLPx-n_b7B&zrnxc z_0!dWW*e)o^-8^Wth1U#pz`$}%mjCbVah18kxxvIk#5xRIaKA5 zFI}{~b@tzgFgvJ(HZ&4Zeb&DJjd02*Mj!zVh1@m15{(Uc0OW9?E3Xd{^;uuPR9D6u zrz2r#94Ge08#PT|MykDSRTjPLe5?dS1Ww4CK;}c=D$j^kdbXZ8BG3gn#I#E3AN_84 z<(Y>xg?2lur747CW_2z$`EGuL6kDieJF3?d$`FsVwZ zNQA$mEscg8L54x@0_GB-*C;!9VRg2XcoJqyv;evcJXS6$aY-YejD85e3q#4MIuzgK z7syxkbEC#<*o515V`X3vP*eEtmYat@ZZc=)cYT;d$j-_V-h((_c416BeiYN!{inf^ zCTxo*L}TzUkjIYdWO3zvz-d8{(2)+wh#M*S)yIUmMY1Saapm+ABplmfNEi({<$L+Ks z3Qt`LuM$D)#)swr!AdJgxins!BE<) zg0Z5t#u5*1vQ)Up=+sh)XQ~y$xh4Hfe}6oZ!A$0V+nF)b?@?!Mt{Q;9cg3b|sDOX3 zBYQ{Z3XTjFkk2E7KzO&QC8;@Jw_|kHm4F5~eOiG)*arllrM4Ml{pzMK#!;yDNiqj8B3WvMR$g``g6fyMi zru6|HBXkZKrl_&d`VXlZE0K#x8c=M{tLh(CxIUxTNByi9ClVgZ^Rzb7I^5r+x)jy9 zgE>Sp8E8bWF<&;7&Nwk^Wbn=6Pwj`|)RWa7Q7}FO+%N%M9GkU(%Cn)`C&rxi4)}~ts$&DLG789`k8pL&EL2d zF7nKKpjn!xq4NhUTfv6HDvI3tl07;K;LaNMbOaP3RdxSltBB4^#e;?m57hn~-oj1U zl^YKqPCkgf6!mw)#Q%J-K2=9b=24j0586>afBy}LK_e0=zsMv|xc8B!p7oV3e)Tgzi=D{b&hXT-LL;KvV*aO!GQ; zAC|wKsiAgk_>53Hd`viQZk`XEexr{kS72pw`@4LE8bNrumNRxKs@fB7rk%Dr)~P@S zPszZQMIAIBr99IdX&+Ob*wNK>&2d&M3Y}u%9qf5X;7!2##}n4w_y_K4UMjV<@ORYD zPSu|op6DRT4hBxSc}X*H`T5LN#;A4o{Pdid9XEUd3C=nL8MCVktWNOp*gN8|{Hvb@ zR6%r{99oCMwHGSg+ErOV3_(mPWiK(tgWSeGWDtp-pcQx3)%R-HJ>ub!tC7(XEWP}hQIZorL%t8 z0@m)#Z%4!d(8l_5{xWO<{_UiI1T^Z24Nd0vuVgty&iLLgCv-L0=yh4yqFN#Oyz}1= zk-9-zqO@LPWWle`(&(jSzi+!B2*q>y);6GP_Ivm4Uki)4#FwJ;Jh@!bgepl90Bc|j zed1A8fw>GA#K|D|7)xq{^sk7QKU_x+?SzSR!nC3SP6(k@iY-##llgQ%eO)_aa>V;; zewD^I4Hp4hc&?`ylA7=MZoLsDjl`~-&qJQKr5$|?7qk@)dTzyiF$|1AMplOr;tn=+Zc$OllDc_f%AP!%BPK1 z9BH!7r*wbTHZSbfwk)(dXl@PN-kFaSOI(pi4x&{hniega4?Z-SVS_bR@8_+C ztzM_2rBA86x)C{r(5q-v?m+s=bjhy<$j=AoQ}Vfv8huc zx^G->5*(S;R#DC1t^t7BCd5?hL1269WqVQxgS(^Av}Fji)%+Tq^_ z1MTx+fZGg)yd^(ql{xN4D;*5yLw8_+r}M6SG!}&R(1#dWFw-b-P|QjDcQ|M5+I5{& zhZvKRLaq)Ne4jQYt>zN!D5T$@_h_doHw37#ACju*zuip<0{D{ZiQpt@Dz>0~(M8>m ziJ_1&9IezTIzs($&jwBVfo_JQ>L1?(F>B>qAFLfd!64(hr}iuF!;lK;qm+X1hAvfg zd89Gf=U!eCjHPxu4$BDzR>;t8*4FGk2di$VF|8^d@zh_Su`78JSlQNmfo)U6HT`aS z0eHZuq@VkzXm&Tze&cn^W`IVvoZgEbu{`zrLezS zDKlA5@KvE6<{-RCvZcBCz{LTc574_VXU=IS9j}}83Jkq2ygyz*sxhq($2J)GHa03i zut+Tv%M4ywiB;=4EvETSz~5n6`B|4Ad#UOQ^UDdP!&{bTBaimA?sgYv#_GF=^61{PUu~ek+oAoJB<;2eKerLM<$RSBRarI^z#rgv~MG##W zJP5-5%wN<3u&r*`2|@4>93c}FcXVV~8(by!D0GH$c&xYR%;`lqH{DModtB2cm~6&8 zm~ZHPSsPF8uH?`8crFe*9N1u`D6Sb&68Ed~)8)w^(E_wx$>$G-mKaNWM|`x{`3}El z4&eggqLR|OE+r|B)3jWHe8+TYUe-4R)7zTzM9*DSl;(-=S_yD1wTM1{D&CbTh`-ew zw6U}Ia}7f$WqbsZ@xBEu8JHRG}OYj2|S zcjDGh`V%Pw-aF4jSzhN2nA*5xf&jso5(a0h=>Z91u7ZJJ{ukTO_p#raa)49Kn1H>6 z6{Mt4=?KN67G32t$14~8zM@;{WyBBiVJ2hqa{Iht-Xm9cF@;*Xi^m*NEQ^n6}+=D1T^fXGg=qF zLT`VV*7yNON(yVeOt>t1$rR5^ATN(;Hmgcew|_isQ4@16UD4c?+w02S8OqiH83cP8 z-$U2|2-IdpIlH$6i;n`tnTr%SetfNAG~`^iC-PQvy?oEcOvViC=i;Ix^9wXr+62o@ zaw)&@W&)`0QLDkB-rkv0`;pRm<_|&;5i0?+nL@N5d)wK2OQDMiduIACR~Gg*eM6J( z;HDP0KXs_;2O#ooXcH@T4A?Phz>Hl~xS+ZL@{O_{R0^CF2KH+MM5mM*kuU5qwRlQ2 z+`@F#+O4V_)Vb}Gpu$`_&t9%<3^i-yJ6c*y%{)C_`pL9gp-bZ8{G|uBRffsRn{O;j zK@wS`n9%V=CD0Vab;M)q8|qfaZaQ;GKwKE- zh^g+3wXNWhv*SB+zS#VMw8&9Kz2x3$1^PtE6wOf`e5W-9jIKycg=5OC+>#X7)Rj*4 z#luq60(4FqTo4a7+>kLMyHN{UK&(mY9jOUkE3JK7m&2*b>Q?Kk{BrLQ>XusbmCt{s zW&qIa)Jz0#blUG~Av~O4*O^l))~VL_%0^xflM@zIb02ZGfT}05kKa15hIX9rt2q~| z%fZATq3=-n-ySDE)q&bXNfS~mc(K6uGX{Aco^2@C4QOFju;bfzE3wJA*#vT;V|urm z6e59{nE$HsSk8O!@HoKXMIxbiG#x7BRKi1kY|eNLxSDv=m>2J*!hC%`x0RPY6Q;PU zi{KH!Vc3@fp-4gO{Y)%k%I%5!owv&6$W)87%T3fIo5i2o-w;dl^AdGw^iR0!si1P( zQ4;V~Tox={KpfMDVZvBcV*^UOIs^!I#01U^>$hEj5fz_?J@Hh87~}KcgezS-^JDtV z`wczC&szPw;+2vdx^`A(mU<&3FqV-Js)tN6qI~JOdHUV%%aO)+C~>T>$_C>;rco2y zK^lFbEWk(yv8}wb$wA)DIAFF==#4pkx;b9pmt&F9WwK<)&xN54C!%#zz{c|8FP9q3 z@TrFTRfacfi=B^5XxUK1*J6oh|M3*ww~pc88S+S(+E9(N9sz2K5YAs9^6q@((v)2g zDIF$rMh}L(`%qRev2DMiuy-l8 z6s|DOYpFU}Y|9z=50Ii;>eJ+b5YVlNw}6fKcevK(GehYJUDw<_GSiV;BQ9Bx9lD_6 zJ;;~h@rvRjVD}_nm{r;TP9&2c5V58{;Qcem#4q%-F-dNK4J z%%sj?2xy>qtDo2b@ZN)r$5eri`d@j%;o#p8Fo?g-u32VmMb0_}7koA^s5AeiOlfF1 zDID~~-k$h@?a6kbyv1c(fL6i|W_fG_{w@gXX0)=!X}<7JkNeNLx%*(ZV#;_H34%De zQ%*ZW$8STUM%uUpeoL)9!Rn?=3WOP(izk?Nhx{xa(wEhf*1uU;olh}&216e?vi6ki zV37)Sz6TZM)^$hlh;z$+xb&8qruUDm^l@;syZDiQMTYA|B*rk8?~=S8?hyi=BP=w} zCG`QpB7eBszu*NnZfj&X<;f@JNdyay*G@YV4{n1t^kn6ZD1A#F4uXWj&ogeeA$TG9 zd?Y=DhRP>^N7k?a`P7=G)D25du}F;?ZQHrqq^E6X zeQ&dQZtK%aJotA~A6rL`{F2yPswQT=zQ_WpZ0MI(Scq+}Q^7=+C*A-_F8pJk`!)$39ICS<4R{ZjKusdr?(i!a5i%d=XL_q34) zg5j_jtN~Nc$aN5ljv+oq4T&F-^?PN`pC#}DngH`>V|oUJ`TsO-PZ9U~w~`WE?d z<Gu3A;EUa(c@?h+HyKqB}ASo=hUhpbbVQcDiXnxWiL}yX@ZM8aW^8K~W zGEQzK;Q?5*)oCMc=A!B2o6{XB);!EySwVA!h1j<^N{^M%sWXI7D<{W(k5ZJP$QO12H(1w;OXX zmUwg@Oo3Z__S@^*%}~4*Wi$_|dr?4ZeZFn2_oE!4#(N*6FS|LV;8*eW*TXgHqKCyp zSS(PFY33v=>!3C#{=RW_hn%XNe#;s#hg@o`6d%KD*L*wMxTG3yz2YnxR?p-kzRj7Dr+`e6Q zYwQ8=PPl5uNXJoq+Jpu4%)wrRwR9W|{-oT8<`s73L8GdsS$J*mWppk@2!Ee5 zC#kD{5N(mg77tneRG7V^e6=#_hh2@i=^0&PC~WNHQpfRZGrE|jf5nY5Iae{Ct%4bD zZP6!iiVdwmj~pg(&3@riq&S=`2_?*{@>5LF?Z3=Bqc%f+Ze8=B589tog#jmu|^FyGsOV#~0)@3ng`fv8|k$Mc{p| zb(MO2MNkJOi|}NqvgrtiCPK3NndGzNGpuhf4J=Z8(ifG5sG@5Py#ZVdImh2Y9~mQ2 z2b?1vCCSsocy0_{B%Vt`I{{@!yTI}t84c24TL}}-E$<^$X=H`3Ib>8y_GNm*a#haF ztn{z^<7_~*Ag1b}NfcsgT-(PQR~T2vjp@g0%`*Yoj?6>UrBQbykwRLLG(c%n;jJ4R zPLG1#3iQS-hSZM6pR$lli7~@tpWsnQI7G&aCOac~{EVI%W8;1co6`JA*kiJ zKDTZ*o&lM~3|LF$`2~g4SSohbxHH0!z_(eKjZ%`pdjeFHXX<^&0t*$o>&rwOkbWQ- z?USy{wn{zf%9PQ=qvHUIM=qC_?wEvn1qsKdKfi)zh3~VEG!v4lm~%5oHe{OXtsE$v z^iz{ZV`IF75006JJ6NR1^5TKO@<-^#_?~UB6D{&|=thsnx!bqZ3h=Y>on1H7MHs5N z%Qv%wev~%&2gijALHml&7@0vYd5qEG1>OcqP`PYeGre2uZD{+2VRA{aL?Rwm2===c z#Vf=94kfNz_ityza*0{sNCNK?$!X_#z_`gS^)!VQ$H8N4)DBB=OXuC8z`Bs@m6g3A zEuGj9)=BYD@WNo_SbA)gQqr7}=|QplQb^GMAsk9bHFx}h1!sv0y03Zp*VbZeUB z8Vlx(?rjR z%2MS<`r)!QgBRORmgd1}_R)(-VaI7TWxz}C7-W6K>Pq;pU!`xc5fuaHj&U!)0RweJmg=pizjgx|3>-`0onN|a{uh^P0+hE~aJ5T`(!3I)buSylNG>Hy z8gRV0di~3o3QnLy0Vuul8(SRJh3RM>wzdF4ZZ1d&YkYSmR4INqa(-`jg6F`+sVTdr zYee_j(G#=XFWy&jOSQvNXqp=1RfSTQ;4~5fOK5G#an0nD??N3N9tICKpW&gdc==>n zh2-f)>DdND-d2Q)Zm~2M`FG7jMBN1A#3hsi^~?#$GYm&(El7$q7D|TUzn)-GSd>_8 z_tr;idXkUU!YgAh1MIaw=Wr+Mm$?!HE4!mAD6E9W74~Jf>?{vW`8Ka*f?-sp_}-+$ z7R$Ez#*G=!Pd|Nbrm}5eeS5aH!Pe$*jAWo!NDZy;EsiATFd9(3IHuwns+vjhBxByb zoZB>Ueg%d0@ye*C`Zv@1a(!bwIUj0UR(c1oUuUFApOz8;$6rLwgzI2+>xjx{WgUb7 z-9G&>B5nl?^r3VGJ;B_|gn8vv$Mml%v_k^mC)|^3qKs46qj^%Yt!W4=Md)P-k$)@5 zc7K`@U;+#&`T);-mO#2J+JS#8>IpU#wX!mJyAy%V_s`;EbUMa>%aUGxgzW^4Q+vdK zSu!|Nfr@B;eK+6qU~ZZ$IG6;F^BiZ0--d>5&DNaijM7Vzg}>`vS#b+q5}F)!uMJ+E z#4g@?VC(X;^i*T<$`}59^gR8gIlpwaPS%|?$$e$Dqzi{ycKZj{)^0-QTY1ETSh)$j zbOY-^w(wKJt23t&q%lMa@QWgp#1a~$^@=O>KWlrqhxqLN?k_F}e7u0q(NwIitINf9 z=yN>nw;49WAKJh|LZCB(=%+mIF&`V}-*n{D-E%APpjeTvJN!c^u((kjDD<{_wfx<*~ld3`g= zMKn%RGlQOG=Hu>O)70W@*lB*J^2Iw!!hjd^jux#%!1RZTaZph6(AfBe(hR16U7iAX zE8{<#%MkhtSq+><&tPwvlq(jW*G4_c{Wwj&4oe#|GYzLhcKJvO?_iKil-w-U{3U;j zJI|(H!1UvWr)mYZ)N=Mfypf=izkw|!5P5$sU)Dy@#Nv%1qggfy2l3;BRl9Y`iRB?;p=wHZ!~rh6Wd9Bmv73 zwSAFU$=FXuIlz$4YBFRKCklx=Wv{2|JFwzvojO$_kJ5E~(Y*e{696mgZ?PQAW1Hnh~cnR{gHIG{|b z^S3bzjkLlXKSwf8Rv&p@p?_Ib`K*+eXrzKkOr=^+k(wC|i>EhlJp!Atr?-RL&x^5p z@})lC=n)Z*Y<^_~xTrV*!ejFem#m|8kuOW9%#GhQMNT~OO*c6o7ku^~EdcS-)raMB zeatJ3e4m^ra+&mKQn&2Y0Qk^P&w2) zGf2gvwbKg(p1a-*k0uByYL9r66U#Y(`mw<;WuE9T{)lQq|wrkSlQ({A4Ee~+iZ zS(&l!XXrdXhwlc4uKBhsjodQ&G(^mLf^e4>_>KmVN>Fn4N);?Z^*!!>`~o&Kq3j625 z&r^0A4}3XI*YW&q7txO)md-2_1^F4)qcR_yCl;AzVi0U z=@t-g_pG)`2mAVTVI6!)&Jv|fj~{6CHj+!tHqt9N(H@p z6q;RYT0awvtUN<~PnOurH@yxN&z%(Qh?2b0%EkTetEEFzELjp?vNZe^4&nLcYn}Ao zylZ0APJ>0uP9J_8hCUQlA0irei5jhNQtsxR=nQ&n|B1kpGsjO~t=y_wA~4EEBd-{w~6JP(#UdVgHhh||1e_{2Wk zJ%%?X>Wou?du5gsOef1sU-II-##NQpo6>l$>DVMmvfYio z!2#8r&#!LaVG@j+Ch4zTB zGJ8z($ycbG6HRML3W469dmB$RRW#ZW4b5v~X1XFIV!?E!yphF&`+=dg#M6e>k)MBj z@nPkSlqJB3GkVfGSv;^L0hxBEx{DeTFbcis3R9t>rG@9Be->+R=g3|Z;hf07%yzD? zaEwr4+16C-aRcVD4Hu2u@vQggtL7CgEu$sJ#?sqDZr>FNpWof$i2H6y_JK4FS^)55 zq4!1(W3pURXFr+|S|i&+It2{LjV%oqP8r2+1l3ucX~j8ckZWEE0jR0f!FO-?0Qo5| z3U-p?6RFMu>5H2)@PcE;n)f<3g09J$!Xok~`1eX#-yiHfXt|+ST=aWOqpu>M_G;zi z>S~tzZeYvaPGd>P_OC+ljk7u6N!UmTSxmM?)Z5DU2tx8!bg~4(HG}q=mX?%c+Q0v| zq$sSzc=KTFFSPGiSe~PLyoJfYiiyWuCKCQgDLOG+$*uI6F5BhVRI)dhN$d+7eav(d zQzDqnSZJ&O8-Rc z6X|9C*c#t!0#V4Fh3!8s*o=fWWAOx?TkVKgh0;Z;KoVHNoc9yoCmkIF7kX8p;5-5p zDo9I*eeY&p?$bTzC$#VQkFQ?@baH!x&h^+!^7dM!^XB)qn_-_l5gc3FX=~e;ub}rC z*#AVrlL->Ky6OtYV&TSF)K6`_v#!i)QvyCp>Ds|3_Cv}B(dJ`y1!a{AS5waSS9|-U zE&p&SjZ@MvCWv$l{8YFaqqfhjSn_KAi!^hKl^-1znub=ds!;dmI1#p+1GUW?U2@}Z z8k#m1E3*lNV>(A$Th#dRV6OKS!2J!GZ+V0FGTA#A;Bs}#xV!eicj4!D=Gu56erHR3 zcYW@D?6{3EKvPnah!)0pz<40nl#cuFmWUM6+Xk<{j;p2`x5_{!9q(2>p~h>mOLj|* zn(M4SJgRiaNTGu4?vA6iicyvt7i9bNUPI{PqyJ7%Equ8HW;`>OgSX}#}hI?Ju@e!g1TM#tR+b~Kh1;=|0_OXY-#RI^<8#dtnk~*J#qwS$40V$ zTgv>};)Kp`uJi&LQl;8IATyL`_ZDGorMCI=(UI5}KLO4^+Qw3)I!l>EF$LFYylBB; zB>u|Zn3e8ss*T!JA>mw4u)u-6`g^hC|HRXSkb$mgjUNuy#u}J~{cOA(W!%l119`u{ z57&lptsPmatgOL-t(0XM3Yj(mz)x&{;xX@0IAf$MVStw+q}!uxeN9Hkrl9NmKPg2G zxAOEf52r0^zbbc4()Jf`T*J~k>^gAFZ6OHl>$I1w?WTU6slLi=YyHT3l0P zE2K8~hIu9U0Yj$5*h->u0Nsq24vH!;l0G3?V3f0#W^!@e>pYkC6KR$*PS`#xUiSj5 zb5odWQMo6NK-RAlPBW#~JLb`jw2@(1vY7?`XR}pSOu)`OkBT|AHZto}oz{1q+_m}T z+vw<7t*29vo&v{yYtH-yHsVSa%rj8gDLtua)d|sS+!5-SIvNBRA1%j{WZqT zzTa)w8@;G5>KP_NAjz>mVbf3TL~%;e|5bD*{!IUI93M^1QAW!2Q;v|SFqEwWO*s}~ znh=WRO5_%~(lW6kmK;Nlk%dAmgoMeph)8nfm=bfOWy0^%pTJ|^@Avb5e_pTW(=!hq zk2n{d#97k}j#)B+pFz7!y-9@mb*QRf5bGYi?BGT;$~;#pM*9} z;%Fq_%x{7+L%YnS92+=k^wQ-BT7M^C)f{^AM5AGo&)r<$H8j)$`5d?CzU3~&6^B!p z1BpakTad}a;|l6@%(s9Ot{DTO1;@;H|210FGdin!ALT-N2EXI`A7nQLew@{UkfBTM z#uf8GG=q{&&?dprWQ8twZ56x0D#tO!7+1v0OUoAfx+;JNLNwgP;&`_}3&Am#aEKkz^?- z5`W$}{$FG>#!y~GSfkGjc}7?v?Nd;Q$7Oj{Eoy;hq2xXZQ7aJGxNjyY8adYAR$FZ# z!73j21Z%j;iuZj=u{}W}U_!VybUjpWw%Dhx)y2-nbucI-Bm{+}n3%+(Y&>yD&o71E z`#L;QU17Pka>0P?y9&0nm5hBEAeCy|xKhu3un|p^qPd!W%hE`A)8+4*?HuD0J>G=z zdXTNcPP42y;-(-t^A5wMkr9VZdlIjub|{|gH=h6c><~9R+f~eY%CLiw?&_IrbT)X^ z)O2VyUtGYtP?GTY9{%GGzYNx?M=Z1AWSDiwHDFn(%UZFZ-xqBPeeyR}J6P68*Aodn zsB|F(v8^Qzv!mlx<(E*BX@-fr`ODOlTh$H#Msci92dP}!_tbb};PTCFg~R;7`uZI> zy|oz-AJ=PQ|NXY|VZF~Zk*Jy~peR2TuEWZUy9e)Vb-1t_eODf4RB_hRdwD4D0E-`( zN3|hfKt-e6>#{oOB2EP0KL*_F02CPd=ntX^V`TbBDOvlajh~3RrmS*)G1b)$2iD|q zNtKlkP%|_9RrG^DQJd0RmnUoU7{BWbou&YO;Dnsu#g&?%RQY9aP3bI~eX2%w-EaM6 zz?Zf-c@~^jwE&X8<`H3mkplx&+8Md%7mRZ5lg`IGU+RA{?=ujiROphf(okH-3?*-% zlTzFsBm5362v~(|Vb*9U_?WyC+Tzd543DjO@BUg`T$u+U$zEl(G;U08t=tV6Tl=ls zAd>}VYX-yW0{f)*&emrp_!!Hv;4hyOjHUClJ6iv)G_GaNFWp+2x-Z(p+m`#rC!_U- z+XL^+2Mo8s;4B15r zOM-vYnWox#u{_hd-4XfKUZqUDFncW=6>=cfS!)2?b`&C z0T`G7NS;bltYQS-3N70Hx@$vw?1?3I71(yE$xhrlMX~qde9YTd@;$cPWVdM&(}n?s zA0GfQ2+#~D4H_Jf%ANMNam6UdNt(g9{H31$l#sabHGj-uk*Pb|uaa=!1NCJ%;&M&~ zD@;~C)vnf_?MG5P@9sLp+-dYjx-qObcs{(rH2&|xCRpDfl_8YA7NG=*%_vtphEfyh z)Tytc?f2jd4-jO(AGHhMpJ6lC*#=VQ4QU_TB8E-bZiL6hEg0U^(z%FJ+vjBH2rMaD zF&a?(U~nQ$V^Gn`Xn14k{cF|E>lrLlFT%C6izDB!z6oix+A9=0Th;Db@ysn9SF%Fx z^Q#|vQybR(I9crsKqf~lKA(1&lQ1+u+nkGqKZpxPHpJvx^Fq3QKrRn~(#hybuDsuF(Sks{EF-raT5d}dvd8&4kDnR=wAXU_F z5eN#ckr~%=Yn^>jry^EXeGrCSqpe#@z|6-MAJx~7xY~B#`Wd4GJr~0zAMnp0R7t** z5q%q9aW-b%@6WfPN|X1!?Z97p(5D*krJkC3)z{QbI)pFQ^JZ4oz$W7>4>0T|(br3X zi%1tDPp1Z`KmeDqg=~VHFtc@6)ub03v-!tZ$HtETV8|3INOr}^9CX>f9il{ZI(i97 zk3`gq$5E|z8DJnYP|}f0oed{15*`N}h*e<4#RWN9Lt^ZZu8umW3n|afpMJsca4hYg zG3iKy~8qx{DRStZ3m^RW8jxEb>G(qV_{x$L6 z1Y%xr!@-T<)E~Ow6u>(0dwuXq6#r+ZyPyXlm4X#H0F$7&STwBz#nU|gNvm63)aJK} zvP`nL+zC!emB5OW!+T*wkiry|k=H`4NUW@|@0y7zN66+|4pb&cYk;w21RiZTXy=u! z7nivUNuU-Ka|B*e^D1wHwdtVwCkb4+ulf_u$7Nx{dTcfK1!u_#i4Zvi{} zk#KKyK-Yaq$x>G(>z2YYm?`xm9yk`^%Vly4;yW(%6tq14M%z_q=Sjmxg?XDS*ImvyL zgb0XBho^M~ZZ1wtPd`@cY`XoFB8WA@S!${wFTdEEQ7QXoDsNz4fE#6P+;I`qc(}F0 z!X^vo#cMKUcZmEG_ke@#7?q&&W9J#@sYA* zPX^<9h6)auABf5s@}#h{OA=Mj01=FNv(CM7WInPGewx0B15KC@SxlUoAQUCwEDJq@ z6$Z*kFc~r!d_R!UZv1m)D z{U>{ER;+UpJ{AzG|88vq1z>i%*7d9pn1R(JECZNFso^38g>;P{x-I&)B;-}k!0o5+ zWfFRer0&7Zt;z82YuGpg8M-VCl!P_A>~KwpC-?)qb|{bl4ya#ervg->YJg2P`y4su zr99w$-r5D4Sxcpn;SP%_RRcQ;enr-Kb;Qgd!k_&(QAiWUU_z6$Ev%zHa}|mTi_viT z(9y1fBZcj&!6!a@Y85`~s8098o>xb^LUd+yLWk4a`AKlywlD2?;OuJUL`+>{?u3g*ccWordB>%Kivr)8CBEmz6nH&o6`X+~^58 z(1K=;L{@twFmwj|SrRDQCx#^n{x&ug_*;3QDs=$#7N+l#L}V*Xiv+kPSfN{2gRNa zbD{b6?-~7iW(2!*pJc3e_3ho?#{V|i8*2(UQ%@2z^59UsS?xGGv{+~QdIm+j{75`Q z6>uVyijw<6t#b~PUU-<8WHq@Vx5d=YW{P4>tOg_W;T<$_q;prA#HG2_e@}r(BBlr$ z9it`k7LE}*dh4VYROl!H368l?zvDNtKuv<-6ncj7MnWdUH@`Rbo1e5u;YC(C4Vo*{ zf3`W7-{6rWDCLfTa0tFrld1%uQ?80-7xyd5hD=TQn9x#ui zb$1yKhNM4DjTg;!`GqQw;;hv0EIfBYpfI71GtM2*NAj#R0P%@WTlwa(DhE=@{CRF9 z=W^rf<@{sRO6Rl&{*P}zzOCi&5O3IEGu;STL>Q`tinmZWck{t_vQ*5}x2C%*k%$m- z#Cy+jr`5h|S(T&5RzlgYol1aWS72#%aO~FN_^;;1zl(gnJucmag4}a%B1;sdg%eQa zl&Ip0m0WhQ_uf06lGOzot-|+cTGFRlV5ENY5uPF2Q`TJN{amb;I@-MbG7+7>Vwd6q z$eeP3qV6v!r7h?NCY9(k&PuA)3A@82kTFgJ_<0;sQHxa~8r0{*ylvrJ?;&(=sw89p zFkJdwO(Ef|q43Cvh)$WQap9Q?hOnhvKK=wfFe=K}B>PDa;ro=MSee@S(hfuY{jsAd zv^zSLL)XidkQdf{oIVstATuM>MK zbWJcIECf~2(8R_HXHN1s^r`_X`$R`1AQZp+; zaGcCelp8i&Y@~-n)926T|4Z|Z+7iXuU)vw44`|1Tq-&~BU9j@*X78zhjtL$_4842a zvG`biKUiWM?M5FzH?sc(H)Ur{z`(X+7=UIwGAH#eFFV~?Yx37XCWjnh9PM^BLjMo^ zd4)rl8$e?wDY{QBt*zbdBN{oE+wXJVnrhrC{>X2-8z471zcCOhZYCeIco5v_|&LYT!LiL}5D`*O^-u);8pk;Nv-$-3`S^*yTvHESlanchIr_-%ULs z7o6TW?t>vrUgm9p#q3p|N$^BG9B8BURy&6O>Lr_e1{;009nMq$W`IM+n#i<{ss3|A zv7#j$)W0|*K*~6*-i;Q@6&4_tUaUCMN&ToP7Uuy(Uec~YX<1p(<0XuY+5%ERn$sCU zsH)<9&<4gXLQyTYgF$Adpv&}Mn*@TuNWv?Ez@1lC@+Tb&N*}JBrdR+?!&3-$B6OE{ z;r2e=(XT$iG=YO@_$ddI(kyYA-rG5Nt;r;!B~91@`ScsM*uQRWA^0+tc3y#cgwPZ% zEST)qg~sUKdIFQQs4vI3D^CGKI&gSFOzukXNt{iPzMRUZcjFV)RgGt{tgGGqqB zEvV9|6am+MXkcl2M)NXoYhka?)t8sa8PgL8bwBIMO4R6|MuHDkb;O}K!Fq>C9!O+z z!(0~XNYNoqTk@m%g{$GdsMELp{Nev@c*dCa2X!LO%33%gj956)Q{{bL%aSEI1K%cy z@CvjG<8}f>V?~NE`_j2bF4v&ei|Nrl_NwX8N`iXOmhe}4z?8>%MP>8-W~npwzTNcn zpFQSgNO51k+jTOry=#+wJAx}7tL2Ltybl=*4G*}@2{%a(+(?rEZvlok2=oq0S)C8A zb;`+>1>e-wl2IP{L*(k3GeYmrIQfcxRQX8A2>M6GZfmK9YrfoO{}H6(cqFL8_NkA{ubOfD>k`%6#s$X;$T|~Ia`KSImBp0f8^7BL_Y=KcKw0)~Tjcsbe~OM3(`YcAkqlD2Y9Oc3Gz;lSy?Yvic4 zlTjNl>R*R1C5Y>bp>~sI9hMh(o16O2g8V*nzqDda%7?jt*8A?IK6o7qUn`K7mQKum z6TG_Ydd#b~d`xcFeBP&X3K)G1=CqSsqM@$WjQ+;=MBzRjj|WZ`DfmJv7Dg!t8#eho zJi~Jz``OcIlnF9{5y-alBH~P5s*2F7k|ZJFu*~k$g34xuAR@VeD^5>-9<29V4X4={ zlP-Two@A*6MaD{5vw!Yk7q;8Zl>`l79HoM^4?kC9rQsK9M-e$LVav0kb$PL2L1EAxcC9uy)+=2Wy#(RQAZz^IVvJU`-JyXQJH(d ztJjwB)3iRB$w|6SFj3dsEj>BA-#l~_a#RwO>z31$HgWjP=AiWbzV(umi2TkZe)L?`=Xvev0Op`wSKCVSAGdesKsf+($GJX7&f*SJy(@2JqjoY==d+~3*2&RnA!L1W`ft|YmAgL${!Dk9o4h`O+2F5D^Jo7s$JQ;&cs(QrvyF&ymx~zE(JRPY zzpOCj0_fqalkTOCM{EW)a?Ur&WuJa3Q{=O#r&TOS*H~Bpc)9(8(|)m8qSg0z;rCY^9 z*Bi)N%iJxGCGFhg`ZnW-z zB_#f>Og^Mp$BsDDDYWPB+O(+E4@Ozka$k-_$8hN7C#{>2D~X#E+;g0HokALdv(d9# zox>>aLz=b_{P-rOusrVD-DOGNts$H!_*xfxvQl{)CJERcj6dg)!qiI}m z;!s@ejsDW8vTMrnyDflj0(`H+LIAh zdnJ~7cnTzE9pkn`1Z`_PzTPHr89Yewc zCCv@6>=|l6%`lgKB)X!|6ETV0Zehn9yWXT+glVl+3(5sBy4%QO&hN;xE)63$3{@1S z)3hbyAuuVE)Fc@?9%iI)FB&7vvPnqY)=&7JRaf88jyXDP=eSqQgdGRnlKayfwL&KK zH0SEe2A{K&A|RnRhhrht3Dv3zKBv%LZRIZ**J-i>Rs$ee@TQN9)Sp+p_&grV@+U7geZIw>pJ z{vFX`>&@ZEo8$BV3S5Zt_s7bIAcDM*++R&GP)XH0d2+r^-Ih20N9Ps~+&pc!;RfGk zhl<_t16)}Zb`8o+FXuK_hEDBu9o8~)-iLI5p%hcO7JfWOSfQj!qpS=DXVoNq+;IV} zdbmsTVRLS8>ym#l!WE;9L!6OU+NMBq!)o1u!epb*P)tqiq*@m=-vCIg$V4~=8Nf~- z?`)0711fCh&B#i*6Ua1P@T@r0I^N3Hr&K6<+P}1lEsQB*Q}FF&ay0RI7f+}11&^BA zv9Hcz_6c@`oYQD$h`mQ{LX*Xv@hcI(!QcQQ3$1UC5+oul8NSH&+S;KTGxImBqz4d! zPYIZZ*7_7yhR@hM?{<4=)MpUmTPxXQ-{#s8(L^M@eIGs0Zjc=Ly0&3|_f&XS996Uf z?P>bQbM%la+ zwa1=O%P1JLW_MPINHp?)cs&J0+(2^uweX+fVo8$yIN8!c0#ISWK(UjP5TtT;?=(=i z56kjNEokF()yxb?WuLr)S3AgJ7!VhupA{4sSR^K9rGpvx@R^~dC97QML0gk{#4)yF zaxG&b5zsL9P=V5*j7zBmJp7}B#&eNq)l!nn=t-myxF*Ql-Q|A1@YRQ@wa&~$y*0Dc zX}73xKoHHWIH6}>1u%kos~ZeYHNq6_5nQlk4X*8vB*t%`gPMDI^#doAzb-J5p}6sh zwdVX!YWH3b`*iD=vu-el8<&`yGidWCmo8m7wJwPm`N`vm%hfMED7tjz%A1vLW?|$X zR?1*}-s{>(j2V$-Cef|g@A}>Qs)KLtLI^KsgTHdKe%)vL*ZB}Y#{g?~oxWddMU7#% zf*YKwU;Ldqq@P|f>chl${5xYQ{v+_htZ*0rNQ!&*cuEP0yC)U*{_zcIZz~&z_<0{* zyM}&o2LJEhHzi)$=DN%f{PB^Aq`Uej?Q@Q#!cT8cY_i6x(hZOTsdwa)#nLUYsx36t zY3fSZf5(R%>zqR6XctgLo*B_E+xL}r>W+o));!;OZ#;xK7_-tayiK5VwYS%5Se@+r z`Kz~PYpcs%>{W+rSgmA4O49OjYk+)ouYTzAGxY>s!-kJ`=1y{?mXD^};_pizvLhn= z%4>$fG7!33R+adU^z_GdT``B3MhVzrgtf`{1s`LW?Od$$Tbhu2U;l?r{?xUN*`KFw zy?ERK*v&HuLYe?F6RaD!J_7f5qXj4T=y*Q6cd90#{e4{wZ;<>^p};H_Z)@UXBi;yaG+DN>v!ks$Q+ zt8u+;PpcYUzebsQjetAZBr`zW84;zL{o>g zG}Cq&%b52N^xLrdhJQ}>Z{L=hjX50mQJKCF`^CaCfw%WykgXklx=A%Yw#tWrw+Ui; L&f;tt_G--kbSPl= literal 0 HcmV?d00001 diff --git a/docs/assets/images/screenshot_coordinate_picker.png b/docs/assets/images/screenshot_coordinate_picker.png new file mode 100644 index 0000000000000000000000000000000000000000..fa3d37b5c5cd6e0d08ef20c194fce92474cb3560 GIT binary patch literal 23990 zcmbUJcRZK>`#z38qBM}Sh@wc-s*EBlGC~xJG9x29%3diWJ4Hx#R#_z@dzFe18QD8~ z@9{mZ=llJ=eQ%%N@Av)Z*X=b*kFLjc-S6l9Jdg7@j`Q+Xye>t(i(wauM530FmbghG zZ3)MJxpz?DC;o0ZqxiqAR##+{ci@-f4m~dt=_pA?LQL8A%~+(3>i*{Duf?vebGv1K zdtIa5uPAnoMWWHQN>!JuMcyQng+X@APX7I=%zcau4&Hm&xA1!HxVfM5l=S3Pqnp20 zx3?~5j%87viG3*Yt9|$)x#@iaLW5YP_;P<%2cO*LFEYv`fA#8Br7v}-lyBW) zVP%c0PE(LL#m;V$HA>!OTGzOTHYKIAE6~c)a$2xyRM&7{)zD7brd5UgQTL;F($IYE zuMW0cUwO2L_Og&rrsML=yT`IDrKP17Ha1_^R~IV>BlyjkZl!Ck>%2+1dh6D~6LPOz z#XWZy21ok(QprULACU@RGPP*!?Y+mYp1UWDezg z^6lJ44afEF-!D{Ie))3$&nS_o8t?PM*MxtFDygb^#m2IbnhL}5H}UcD1-}`)GIhUl zJFQsn-@m_ri~pIly!=%enVk&{4HbjN-}#%rf4}zf)vLmfk!x#?1@`m1s;jH1IUN?p z)Z!Bo#MIQ5BiC*3&dki@KDG_bpE}LS>3q_qv8m~Xvhq_rQS+5^S zNAQW=zMUgBa7|X$vagDoo`E6OYN*z)U!&aiZ+?No%a<>wnr>_LG$hD+J%9crJNr@a za+#r~Nk{&Ho}Ql9JVrMo?S!SHt7~d1H`Z5a4;DSP3^Y!c3-JZb&g=Gi`ubO{U*9ccKUacysE@7O3^y8SOeVQTxojNL*VkVfO)u^q8uG+#MPub& zbL)`x4-AZ&_!MufP;P8&eEa_WNkPHoe49!C>AtVx_+~dZx0a6vH2ObZyLA>i#1#}A z{u;n6rLBE5B_*Z1xAzG?M%f~0HAuCwHml$`-*o%+C94y$v9T6&!#8j@u}-TCuZ5ii ztgWr5)|Raf3qGd8E}!D$l-%4{KlgY{HAq-eN~$kFWJA>6UI5o5Hs-X_yONR;(NmKN zvZ2Iv5N6CBUu--R6HoT`_U2ZXS0>%0+F3NcdBOI z+h)Hw;dkhQem7Pw*ZSYy+e6zZ4@NsIPP`UzDJsccUt6KYoEmVJ^E5)#@!LO8g2c%G)Gb0KnQ@M~_ko;;LOOVvQF(ulGoQiv3Kv@=+sn7{Hmy^=w9q{*{-;LD=9Yi36qe$sD{Q7ezSH_ zZS81LJ3Rf|LKKiu&9cYUU=)bPki z?_fTV|;J$H^afLX-j-MbSerlv9J=~{^ahYlT*mX>yPbKAns&OS9<&-(suPFktB ze!5n1RsN&VJ^S{NZ{NP1{?MUgoSgoYyR!eXad1!{Jb19~_wVxYzd4rw8rWhSGcz+u zBqb#!?}3qg5!1h)pFMd(hD9rFW#{7h`XiK!mYJD`G~ALISMn%I$iV}98uRJX{y%^I z-1FqxTj+6xRdt7hg9B1iAMSiGfPG77W$Z)dR!Ac9L>!r&-!Q8L?){SzGhG2oCNU8}pqk-h3-KIXX&-wRx{q z%=F;F1J&#Y2beC~y5h8N-MTe8HkJ&j?<(@X#Z14<8zF~-IyyQ_Ge5Ytkj|Vr)6Qss z7~DlkIX#}!b#JUCGuLUAkM7e*tX8q}aK{(^gY2rVEiI~hX!jpDkokE04pG6_*tYr5 zaSbxO`c>h*FOTW>pAUEIW3N)Ot7UEFxcm7j&hkXZ7f+lMS(8wi;1kHibWBW4xi*tb z{D~Eb@844)M?FPm<1_DM=NY?w^X3z51Mw-@5O%ls@7dEdzIZ%;zDw@ygid+m+j|vAW1Jxe3|5ST(TgZ z^H-Dz-Cg~Lco{`S#ge&yzpn~&&(6+nAu%v8?ERrpXrEoXs%vEAy`6?BIyd(E3VXQUR zZuSJu`ZE*NyLZdm+87QTIFReSF0lKEz|&AJt+LKeCePhRuGrdMeDmhb9%kkMJl++Q zY0-Igd0m?6^Wj{=!osgF+npy8F>wgW%i}Z$81@^QwddAre_e7*UMLX9=ap4d@^XZb z3NAaX>{nA$YyTc`>%$#OqqXy~-6D>2b8`%1Q63%?INpl4Zh7EVZ5lMRDS=RJ9kJaUDB&_|7LGF@1-Ta z9+l~5*oEy6A3h|bG1(}P)zLZD99LggCyL(;{)+ll!yzNfZ^H9plcL7_r0`l_MTG=b zb!Y1Ujax^qCApOU;nH}S;OOM!ozeF0uk!LPg*MmK1sa#}`rdUv>5LwjwXT5qPw# zva)h%Fv9%l*o=z<5%+c-;jbeibeq#Oh;$7QV~J`TGcau4Sx}0~a_Ng>@%JA;Zm6g{ zD|A@AqNaA}?c2B5qOg)cldd8sAf9J^Uju*=ZXB(f8gilcttu-kBSXb115g}U-`hIu z_D(7BdR<*zNw#q_5lJB&cL|7PVQEPmn5o|iB4Wt-xE0UrY+h_-Pk;YYWY<2Fn6Ic$ zv`3Cm^YZeVIp*`>jMvrIi;0So0CjS6);-Exq=g)p6b=8Gq~7{qu{fczhGSpX+$;rP zft*Lh%*=fFq6O*1i4#P*57lx$Jr$TvX>M-*$*`VGAxijJUS3{Zxft*$;_fQa+d+;y zTZM##l2TH3QHfj+=h;boC@PA1Y;3G9^){E8+p}lSwxMcACnP+>u`N(>P%p5h#jhQd zlxQPLKjPMUvh#@5;Lk0J>l8(L)q8aM)}{8*ex z$p?&}U zHX|dWr_Y|r{5<<_gTQH|x;!g`Dcj3t-{cx+9wGtT+S&rdl5jW(wEN}pxCF(otgQ1- zJv>-0UZlstoqE^D+aD=P^0E4V7UDs*c86gBso^#6V~-LZRj z72=8U)5VzNo<+&R!ose$Dy%w!&lRf@hcm7E+2oMxNM0%dkux&(e6g8yPF%Rp{a}Xk zj)CL+;4kNLeWg8gbe_l}l##bpR7}atC4xgkPc}$hxNza3pkQ&R@yn2qD=I3lA|mia zs*}`|=gTtqbR6Gjh?b-2raC6+OFv!9 zr&)0;z|hjI>ihSRNWbT?nPcaP-u!p>$2B>Ud#N_JFq3Mu4n8g!S4Kun{D9%WK|_4R zy*}xGF61luY#Rdw{)XoadmYi($KB9z^S}q`C#i4jm6ki?iobGL5^Om%S@nUW6QkLE zftts2VchTm9X(Z*R8_o@RYcn}{T~L03`yEEb9VCMWbUO)(nn+8J&sYEZKYsvUC+f; z84s?~Yx`{ZfBohHDL%7yFO+y9k#*!h61T9(P<)HV+Iph>5XT+IKfiVHTtb0w-@5I- z^;v$rN|5z@T}w*~I{Itf3XS5y(;{i=c~7Vr`H0Mf?w~TK%h?A9gpxxVeZ!NitcUyT zs~nMrlhow@*uk?D!e6{ zEKnkO(PlUCJCs7gx9|To&v|}DNs#} zY$zv@?*MnXt%nuSoLoU^N=r+#U7lex&~4APoSK>{xvk|ybop4T?Lb$r`AivlQgUKi@DRHF~B@u)R(Hfv-M5iN}u31PTm3vT&o0)N5 zxpIX-aUes=u`0kP>aEMOLqy_MR8esnwFk$f;M3U1gBD-s#p+hTJ5hQ01J?@=>ojLm zh7R>66nD36-femO&wqN~3D(o6)#5(@QLlZzFKB;h(ap(5%9iu48~R$#^|EKO7L43G z{(N2-{%cN}@bu^@tNf8WG89m_x={WvwMcd2cZy`Xl_|qzseOC)xJE}Gz3i|+CGk|u zodR9fZsbaCKE5ho%cFsts30w$O&L+fiJLd;$d5sx{Z?J=77@XC`SN8F2`tEPb2_tr zP53i_P5@NhpRdoM0o+EyMSVww3aCHa$$kz+w>peyP`oYtNA*exMEJ##;9w zG%ngq99~%%r!+7y`1b9acIlIC$oc(aMD<6Z{PydYXMVl_fI5jJARs`0(c&mbkKF*l zW9@nS5X1xD0Sl;cO7O0^yB>FI~XwW7Au{ED&|{d1(h*q$wr$(o-&g3q+d zJc9oiPrugO#JF#()sRp7_T1k;7&xZy%ML+o)s4p+X4(!hJ3$mjHsAsLltk{ESu^nC#pTVaDo#;^DmC}f<(|8 z!wm_Pl70-^&<+x-#mUJ@@Kq%3rKuj&Uzf!10+%iw1CfAs@JVp+zBiGPwDj~|Slf%2 zE^SF->O9ZKx1mKYBU=t^Dp+LEL&m9Dumd#@iQTF&68F*fOJq|5{U?~U%=d*GvB?`%{K~2ZiqKE3wh0Na4=1Mosl#(6qVQ`YMoA$3pNsypMH$MltzT_K5Hxk84srfp_cn?QHqKnxJ<J-t~>^^ty9B}|#M<&eg-)F;xiRE>0SY5m&1wMH?CjD1=%Bvq+ zNMUMfQ*-KW32#MuzV*0E%ga={Z>PQJu<%4Q?ERPteUoi9$7wrvbolIddUqcBH?n+$ zX%kjY)w>%k^}_> z=7vbi{r#JMdAPHCC9Ye%yu4gPLT<%1h2khW5{IV$TMzQi15%TiVO_M_>x(*X6g%hU zs3y90?c#_@d*`8{`B%qG|IEwVT2Uvn=(Z{c{N!Pqw4Mjf64TOR1}-GI9ue%+9@J$65q-N(xkrr6WG9kyWm~o}(QAD& z>tH~xLb$avi{t`6x^=Pu2CO05m46-=1Zq2skPLeH(zoxcLRnS*K9craQcz3I=FwOt zVKUknKrd(K4WPKaS-kdh(%^P>8W}bH-htL|M}dkE*@b%*7HgJEr^?D%MJ1$VWUgMh z!a@?2mEE_~+nYJ5s;uC5S}B^~KHLs*^C>B3D0UxS`tun?!4yiBE*P8Fyv7Ih^z`bo zjc<>&WmA@H9wdLSo;RbRE_w5Xb_HFw$nclRqCOAmWpQ=v6p?rQ82KgIUWJ5Iy_1i~ zF#3JMTiANMZ9e!eQ>`|4=WdVy;39RuH->%t`Ta?F_!;{-i;@O59})>GT#}U_o8h>8 z?f3~cakQHqU;g%urmya54d=Hx_}F2xayWBeP(%df+qX=BaTJM~{uUzxI|A5zGOSy7 z;i~S5iJsJqf1)3a-dZwS;{F*X$Q=3QvFAr6E|cZ)O<_YuX`uk`6C}gGMdjNIEp#6m zcI}pXD?It3DFS767f~s`f4_%BIW<3D2^K%RU=`4Zq1LD6>)t4Hxt`^9i?iMNB_Bh( z(#EP!KLNc}R#&&j-rk;IazIvAKA{32EMSwfkll(9m|9pcd%zFq*7wo1@ZE*~Fyiui z2Og95SHOwkZ-4RCW&FB`pI3b?HMnHWXVljI?lB4tH~r>x>jHr`hx(q84?g$FIu?KNV1^%|S9%Es-a!>Hqty=`KU|4_UlcVO% zn|smb)gzbKH`}3~x$K{LTBg7=yzJL36 zl$x5lE$cod+sTtka&lD9o<6nscfp`G98{~14kqyzUw`%L71_|{@(?q+uvicxEG%GTilx=m!oc)O zfm0$jF9>J%_6DGOd}^xf(66XOaFDyGsS`k)Wj-=tKggvi$H&L_^35ALtk)dq<_0fX z)~z#85Cg%6wYId>A><+|6e!|irut+NpqH5fHdaQtCJ1Pqh(kzA3r;ye`r5VUpsw<) zt*op-%)FGoi_`iJP408K)TE@NU|;hs`zUP8pd9f4MY%cR+gOIOQ4He%q`CP7S6pm26HS`arleud?- zfB*xwj_7?>=0`nItzyBxgGU65%U85EBOCM?#1nxevASZYgk6ra)c-M}-rn9|pR94kSD^zP&^5~2UQ=3HT!oN*CUW@@Ab>w9zpK`kXEX0r z?jkt1gjX+LYESo8;tYC9Xi4-84Q*#-Wo>C~)d6e8vhFZDNPYe7WpD3&Cm#-ZP&0af z@p=06X*6yXl!Pb9-A~!sMEM3$fAs8GO4K5dfnPxq-MD#^rC~e38qPoI+r8g3|F;)_ zL`F`o0~Ho6gymNN8j>rzPDqzz*m437qjs0IdinYi#3=T{4I6-tjv%o}+*X5f>c!4S z@JVzMU%`9TL*`2Z-%UfX+33QGRT$6H%U`#etcOAo265&TD5V!KUL=7$+3L!8M!BXy83HWEtMyY5*<3D_mkBNy>}o7o z1;{0}L#QDvg z95W7XWz`!u#Ly(O;i1W(*4nFc9Y1!=jTDH+B;nmV?CDsQbA_I58X z6x8RC@TAbO;^=hNf=Bl9lD>NN8HCKdhk`Z}{q{T%wOLF}O=lJt6M?<9tfDF4(Jmp8 ziITo`cD_Xtyec7~qN36WMI|4FmX>z3o?G~I_&{B2k<)7K=1(o>Wj0zBk^c6M4&opn z@(i0&RN|A9Wh9zt1aPqPv6+bQ8z6b7Z7)xVIGGAq4~u>@_%-OSRpcl`Iwc|!1)6gQ zX`sK~;vXt^Bf!oU#usGr5EV|JInw|Z>sbS^aCKwjOXt<`9Q*9A>BSq@K;nVKI$^QV zTj`@`YAO$^jt2$rp|y4V5y8hhUU6}7uz?SL?(2J;rAKsj?w`_wt|B42PmBzP4?dzT z8fpEQShwuFzOs`_h?aJJ;jg(KG61^#cUTALe)LAh#!6r+?(6ICB?&mK@Pu|@T}@0( zBsBSjh2NqkoDvd>gxDvJI;E$rEs6sf|Ngz)z`y_zL8McHf)QtJHrDLiVlJRaXXWIa z#5ytv+4CeMChnuHN8&f?E^&Jq7AAwb&0|n|7`g=uODs}AgH4yy*H&#ekLlC(?Bw!J zEg3rGU}*Q!*2jo@ers#HbJVH-TTp*b&#|nrq#JP~R6J{!7&iJvZp`<(deqhv=?-f6 zNo!&BZUFO!pr+=NPndQU5x2`a-2*vPIy^kQ{qR-!d%C(Zl9C>Poaj9RK7IO>+gXk< zAyQ&|baY7q@^v5-s6z}4d`Y#A1qB7)N=wDM54#kN;FysOoxJ`=dUmj8-^IklL@8i< zw%8H7#1#q#mRPW2L68}3iqY9$hjKAD->hY2S21t+;6-GlygLPTEVJ{Ho0k`&TYjiE zvaccPvfUL@5)|ty|0A-{NYxopLV`h5h)(Hn3*S5y;*B85p6Au1CSzTRD>75*{ zEqT;AU5fdMjtDIMspH3=B8_h)Q@|PKH(G~b!t7$Iem=fMG2jd~6Bx-5keubV;r;vf zX-W1o{X1z@7UQX?sD^>!)jPp2*LFgEIE~xGvKpbEZ_l_fE^u2}S@F&thQ*lv3?>OORU-EU2nZo=;#|w%7vX)0zEyq4-5|OY6>e|YSDHZ6yek=l0zjp ze)g;^Q3cIIBqU(YVFM_*sjPe)jK!V2hir?aVwX+f#ldO=L;-P(&>+v%@OLTRyT=lG z3kNAq(vJmXK<~6Im^3yEj*Se>8j+2M*mmfEK|ewQ4qsx)8UqdI?KKRH7@wa0Yq|Ba z>D`!uwO2|K65tRK$f5|S{)vg}$VckoNdnDssm68}f`(%*SU!4-77Iq7AVhiC>(_Ol zD&VcS5?v4$c4)k-SZnwWk{6De7@j0PDM=bnG6!Mj;Xh(=bgQV4m{>J5G{Vu3-%bSe z+W?+x(AvvuVY2JjHu2bzfqK#~mQ(#La4iF$34P9pNliF!`{54UarK`+A;=@rckf1c z>^}0H`Xe&KZy+xC6nr2|R=2jQb+_^Ah#UAS>~wYvvS->SPpbRuy(e?vs6$M8k1$KA2Y*r#NyMhg?{OIs;M#U9KAf5NS)UoO7QR0@1mngtdhQ>$bvW-+;%g1zVzo}lRNHl zhadj$N>8C7Bh(|>s44p5;#$v=|Hs8!8ZEdD>fSIf0?0${CB$Ip$prI)L7=fY>&R?^&j+r&X;hBE2y zA$ue-9CE`&eH?NdeuHzB)WixriW+*4D}-n)12sfo|cS83iCEA?caH!<&$In(6Y zZ-1WN@0yiX=UQeGKl4Qk*WJv*av&NAr2f#tA{sct>b?RX8>;L6Lx<3-$TR{m-N}BS z;=V>jNy#cGD2Tv~hwH;?h%r`=z4jLfTO68b=-S|wX_01q(E9vC6yBQ@({P?nmOW&T zrzMUv@iA5@{~hr}n;|W|16Aebg9m3g)N>W3*s2$Hcs8dqllf;a+07i!F$(Ykks~jvU)kIoinOU=E&>`Y832mNf&>DvjpmoAR(%r% zN|ueJtg8AgA%KDR`QO*4c3C>p%G~le!IJg)^TAy_*{yk2CygNUzX^^%!*Tswp0G2m zig|Cp`S}5Jxen07v?^z%us=7iUfqV8Rj(kjE&(K|XJYcRnr(VL7`tc;V z5R0*vb4x2LEKuO^oR!eFw~om{Fos2gK!ZqM^$?6ny(%fAN(vNx?se@BJj@aH7j9&~ z^aCd(TcHF0ztK@86_o?>K&3=Kz>;$CPka8Ov$rSUDmi?gVIaHhSBeT!wD0l5TzH&*YZ0i=g^>CUwk28m4XJ!$^ z{k^?cV2)@kbg&7BL_&Q;Kslb;5-aGDCgbE$i;7A>K(w33Q?B_a$(ea+ITA$}GEbcU z5y1xZsMV#VZZMZgp!FQ6xc0^RABzRe%~~ zL;emz`l7QvzFd9#)ZiuoHPM3P%B*^v!b)Dac=0vP)G1!xSAWvA6p$0hx@y%Ryz)1m zsO6IRUMJC1=mU8M2G4y*F53oz4M@t$LjRBL5r=Q{WpJ=KsAL|fSr7hx=D;zMQGRtW z@wGa0F|?Jd$OZi)j@>0&Zr-@jBg{JvY=A1t*y=e0ws49*W`f( zc#DyXrSqS63+mG1FMZjT^X%szG}P5a!w_Tm!Q6Zt=+l& z5KcT676J!{MMMOnco98Gcd7e7&@U{evJ5x(Ccb9>o^D>e9&(pOL1GSYiL4}9j&A>c zMW2HlTZ@h;tEtJL3F^BQIo??qfn=TZ>C;QFQpq4;v5f)yXS+mq5kTz7_g$gr9$2-#MCAN+YG}#l$MXfE4`7Cf0S3O38eK zW`(LT;%bu^qC}K8?@|gsc-J_bb7HAs$+!UFbyu`;Ba_6&&48b5F6+jVYA$@`ih2_E9ks7FWkiRcI_x6r~0x{B-o$9Li z?zoDs<)RP|&r32gvQzligkQO#zMgi^_76MpFgylCLphYvDJNkK+8tHu1Xwu+2s2>2 z8jzK|yps9%(F)m4x!(C?CCi`A@5+V_fDyzE}TR&j<8c4$_}%?5SLd*WQyG*H4+l=z{LXsKKJuW z!1)V?92)xPFsNy*;_Fa}UWSGOx(cyiwI;S*d6AMCzv>K{i1;*!iG0`#!CURzszij3 zayfBP&XJn`1A21uglGj1Mt2ft9)$+<>!pU~=94xyHh}H>jqWxEzQ|n_MwtLN$cn$j zXJUAb|LkCo)E}v#lH`>u47?N*NHx55O(dgjco9P=(o6BBm$ zUruVfz}bWLt!Lvw+vn`;O33xth-3ZDug>1i&?%=N++C3HbMU&i$UmK}$g!Pzc>)(pFXqx{;=#(Zg*W7$EsC3IbORKq6A0e}e$7WTFAPydrp~bbG0*S9QRNWMpKx;w*w5CdaWdOHf88#~bd>LmDLsRQ>k>R#*I7*g!Sl zKXL0nAqro3Au9i+?=oT9MsiTiF*{;&{l$xOBx0xpE^ERU0Y+7NTldP+GWsjeXU}5L znGg*b>MOk0wEOmzC-^9t@7}RvPna{58vCXJC#9~g=v+QM?(mm`MFn>MU-C_RLnDah z7onkvP$w0kZ!fQ|0*VyWz0eRwV8qA7h{4_*)8DU0RGYxSJ)BPHC>sI)2`U8qW*{20 zoPa@4ZPu9ExF#(f4TL~Yrhd#Kn!^lGr&wXm4f@g#Ed8y${SDYX!|}H4cDtgI<1SsY z<4)%ZP7BSdfXl{Z_%#(lV#25RKMCc`nQvufPheb?zz(4S<+yq4);kd3UWMC{sPqgB zqzLjjl)qVJ2xzVz`%?`+gW;m{!-wagGATk_0(0Ads#{%K>o1$$dJqRH9y$?9(ec<3 zwsPLz|EuTpKK|z-J+jL9veAP|QmJI2e(h^wY^U6DwQAd*vS)KYxQgpsw~$Lvgy&~` z{76XTO<|n=0V;)gd{~3ysH8zgy^RsxDO!?C5gf)=SPD14Xlxq6{Y)(Ra20j;-;0fl zs|Mjq&<-^EcC2WH;Pr5QG(&)a35{b^19{v-Vgt;Cwp>^xN?Va9;PNB$UZ+IA1<+b_wG5^eFYqsxKW#EZ_L*r;f0h04xnP? zGSz_Bm4XD3fPxn!+&KTg8`{9`zyld&=)~jYdx6F43yk1CbYOCYYC?7B{8oa11P_Km zBYeYFBu&Cai~d?QOK&Fz5RNqzLGB|;9j8XVD0KVO+v$WKAJDhb>DUa6-0B;I>jFVq zQiUlEZZLZ4xfWaW_4P@vKyN=I_-O!&Skg!P`pB_Qxw*MsazoR$^w1jHa?ELP7h@e? z=)lg2;{@hpS|H>g?sx(lI%5_FmIQHoIMc8NP z5lZ`)H4e)>N~1yYfFecU4RjwKgefBakf9hWt?q_it@& zElk@IaF!w-NF-z#;_K0`->z+GdA+&_XhBF%c>0oth8Lsb(ks-@jm1Go#pEr5>IYOX z`?+2hBMy;(BTyLK)Xdb>9<|4fNjDxjpKukCDvw$_nWA}E(aL`ij2RomkeFY4FhcYK zUqKLq&`c3WmR(H5M*AHR3;`FGYmKvt^L}u7{Xp!9r3*fg)?C#$z4iErlcVFes;YOj zd?`N^ZouiSAZn3y0!ShrM(bq`HnywS&rk43ct1irK4^#ovct8GWjma?*WKUqy|5Q_ zB#2rwGc!WefF$3K*09TI@d$_x|9yry%m@C)^?*dU3Ic-_RTCDK;3dZW%|vP_KS++$ z5Z%cxQ+-iHMC)iF7!rcJL@Y`mTeN^u!Msyx@@boi_OMmegY}8YosNS)5AC9&`Vagf zi{d!lL|)wHQBncOtx|05wNm>NohKm=2s%&qZi4_-Pp9Q5Cef6-36Kqz%zM=oEmvT2 z@@bgpz0q=>g0_u@HBZ!Pr13N%v9rYD=n#1v10vqVVwS{FFO8}1vz$F3QD(*S z;-xR>AtMy}_;>Fl;SeG;k+kbkDfY9V@`>~e0$4^$%9CKB319yyuIq(iNfVv5h@}58 z%#g3I?^YA&+)(NMu?7wysE9O-JL(@9xfXmvzIU(;1wtIH687*L^d!pT61^_&**aD{ zz5zS`w@j+NJ|^y=O&IXo^JWEG55Z0aE8~w3+`8Pt{7WM>gx7=F%Vl$&4yD2!(XqC^ zehzIuOsMqmMm~7ZOz$h{#%%aH>4f{V8=yxiRN3jl8b+9DyT1jovVY?a-}YXLFht{X zPD{Ro>4f(V(jafT1dX~3$|nyw5F8FJMXHgS^jf&c79Wq9vOKA2KL-fD`&({vaw;d_mI=d zT(Zq7G~Z}U2w>P!?l|?(qu3PA?bg3Cz1gWZ&_vKHnct|HbO+@h0h+% z@jXC7>X~2#jcfIYuxGF%AOHwVL^#qB(WQ@29oW$DS^-mEm6Ebr<-mNWJgDgtu_FnE z7|e^tCo$NOZV1|mU;}WRSWG#zir#E&teRg_P)LN|5e;GtCde%Q^%Bp;KfCBVwFy4i zaNzr^|2NA-&asb0-|N5`oIqU%Dkh#1W)vjB)3A(S(()fvmd336vfpcKPq0*<`OXW3 z6$>{?1BQeNt_MyrF>GRQ$jr5ruVEJqhEbk*z_Ep&zkkhrtzRkh<|iy?-j^>*=tYEF zHr^0|C!T>ijn%#WjrOXc1hgK)lrgv<-TuWU0B!Q=jOCi2KYcN^qRi!h3?l?t$4}7A z>sr>Sd41uvBcoiJ1xI5aRQ_wD;bRJrLc{VQXB>PNyjF~+odtPfZtwUo@_d|wgV3&6 zepe=+Y9=NZNQ$soe4EQ}Geq^g;`UD1`MJ__xK9r%cD}_JFjNNFcvG22utOi`;^I1g z;Q}j4KsW}`K|u$@_=AId1LHb*^6{wEJbK^uV7-rF;AaKKk<-G$nk9b#N0Z^kC4?kY ztphEhKeTz+YHp6c=UiJ`1DK8m`H36VfiISnqVfjBI1MT%XZpp;f$%+qFw;?LD9312G9UIU>I4 zxwTzg*H=S16#xiA?9g8QIyuyjDHxlMLHuKgfMwx zpkW7LRzT6iNIx;s(elNH%XP#-5S;$&=~jphhe>-s&d!|?Zz(ds~!Ah|++gXG@}Bm$LR z_zap(IIb`QyBpj#-KkO76JR%BJ#|VtejExKImRh_{4v7j4mGt8p+>kf7bZGuTurkV`siUG27|yPuNN^ z)Uy@Tc-l{7F510&$wKgN2!8sxG5 zY~Ce&J*6M8bbr_ox@^LeCDC-x8=BO9X;@s3bKLnPJ@$yO z`2gJDwyj&e260>V90D-{X_8y;c>HYSO8vJc``s3M!@K7xdVB%Z7DsqG;@f)!O+ zTx4_Y0=!mAz~%E}t-p?thn(hyX-`A!d@qRk7sC*7100%dv~FG_YiRZA z*2~}D1H(ZQICWi;xOIddIa7cqIHPWOJ|10L1#q)6Rc#*m6mELzIUpiD>)vudFvNp& zO}u~t8F)uRbE4k}W!EpLzliQ=OcVp0Sv-1l6&*LaX!x!%yh4n15<~|i18yFk3V4Lz z4_dtS$Yci&pc_PYka~eHUp|FI{jg}(J0M_a;|Lwyc5-ren<7s4X-%W+LJT)xU-bcy zhujx{#E=Zao(HoPEGu0p7cgv(5*-UcG#FC>iO<#V7PkKV8}Yxwdiw}>Q3H37?JGT* zly4GE=6|5`u?#GO1C#+xMkwYuQA5JHY}Jn~Ei+wLCSh`}M!0}S%bVeCiZI@H@Sr5T zX|aus%D_r-SfD^~Ih7R^dxG>13=jn-ssR}D1Q;Tai$Nv31f4ZyObPuP@xcR|*+Uzf zL@@mmo#9~RmJnQA_p{xt-Pp&st(>FFAn z3Xc%%_cxGL;BZldXU`DWf@Si6`*e&>YVC$DY*!$)C162-z$OQO!$JCxUamNdnkJ%V zC<6C}-nv_u2a@*6gEF|$x@UZpWYPlcKc=UrmptqW&&|(&f$aq@4*K%tOUd3bk5l5! zOaiGNI@Kc(E+g=GBh?4NUX1Q05HppboHAGKVCrtqQGv^frT-);A44yNBbg7H&cs+3 zQ57E-F=n}TS^$QKjp9OwfRvQlzoZS&2;+;csCBX;)_f!AsDTsxnHT}#p}YI~hv zl$^?Ab?q*%U)+VXuz?oFJ7>y$Svte4D|Utkg?kOkbq4kGx=D)(Jyq|IJuJOkNk=48Wet>!G$K=|Aropr=pM!|ORCj6b_&5jpsTY__Cu|E!Ut0>s^Vl$?q{Iq1 z+>ofieCV=m2Br%eSq$NXOF)H!*F!3d&on$u{>`xSJ%D*vE21bjbftL4n5m`7s`oG?eH>v`B6NfM-C#UJ;%y{-WMn6f6Cm-eJ z-h-KrTbs9yQ`s0u@N6XbbzmL~pjNBB(h(Y~z2p=6C06$qgTCkZ$kf!k%nrcHC1`R75ZMm>pppDeNin;kxmcLOXO> zFJ8XXo4-V5aM!=a%;irUCZnV~4ddQ>TFi9@O(Eyi0C}4k{?Q|@`D!`X`A6(}3 zNRik-@lC=~7XY;!8lv0Vf!?uf6(bio7pj2#a&|Bn{C%C8lJcIyuP|g7<;ly($7kVa zoR_q!>T3{sH4CM!I_b$vIOh#$8PziHJyX(M@1-k74%**w{;uD54%7E$!oNZaXu@-( zVd&CaRMf+$HuM_RjvRPF0JHVxN1A#kC%K3?L+1VNM!x+xJG&hI=2LpYp1k??Kl>Ce zAH#AJAHtp1z4bX4kPQmlZf*K&0w7wJ^^#Ce^Fm3%g=4x1j@*1o6U@ zG|j^2#F#$XTE4~f4PpRrd9gT#lgXeEPByy zCO%E&OMX5BBA0+oXhFSD6EMSFGHASS{nV$=3Oq>fAt14Tfa)JecUez`MZQC+O+U(c zCE0qcj46{4X`^PrgSXB9-=#(so1CB&W|^Fp_Ss$?2oSO}3)<@6A&-XZ#Dtgo_l*x}ZLT!)iD;O% z=iYehykca^PReh#U+l2Ck3RL*B3pjfo$-W^gV5$a%=?91da&JW;+MofwaG^ zsnMr7I9|cin|dHRJH|ayGd$pYZW77y+ZM_1*1i zf>S7DkGc*$wd1hAv*`Y&l{#1-@}*oqR$iub52b6fqT1S@)w!xL$aC#`^3um zkIl;LyTjkO-BqYvg-`(!uI)VTSMh@pjxnUnCPDBcBkoe+s;&SHobu0 z$zRKz`119iZ%(H@C8#G*cULVf&mosT3f(z6I!e6f$wv!>mKV5ogeLW&iXmvLW8Gch$C28se{sssg)9zj%I9MP*!Nt?I^7pGTKudy;zc=QOJweQkW1ue*XMTo19m1kGt>x2$4}%erbj&NrUg0Yvj=U zQBTywgQKhSqlq7Knyc7ZZlNTFJ{!xH@bNNf`y_)mR8;)_tposgA1q>9$HSTkj|ha3 zx|S9f3e`&}z0ZMRFopi_j`vjw5DwNZQQVtOsj#9B8b4Ppw$`6K+!~P>x9Apk@E_!$ zFm9bEOUuhL$fRs1PDnPJ;pJO~eEA1r5*kzq@fIGuL7@G2CJe-cw_Lr@e*Ue$Z2T_b zgM8FoNAPw8C?N~Z3hu*F2`cM;9ynOGR1C3EUKpvJ&N{Sy{G1`I*2%Z%corB!w{+tj zTarM2-90^SAf@`y9zOp1vFU|lPE7@f)$(XD_wI=ae^9nPuvoMSNa;2=HR<5BIG6&z z0xlOVNy7MOQdmonLu==o;9yta^na$~a6Or1E*KmP$}b!{tnw@XJpqF620 zBF4*$hmY?&BD^1Kb5m236JOptF~JFH;(E<*O^1(O-_U&O;q<`)tk9Zk8E2+pW|l@U zg20IAh-FPo-lx$AdztBM^Hb&Ho7`%?kSq3R$>OU|t zlA`kGVtC@m@tWeb0WOXwgO9<;&O~&rRSkZWGBJPm$M*nFh9ip*=2$`2w5?zm8)FNs zTwK5IX-RQZ=NKDZu!Lkzj5~vrF;&yki*K^yVg8bvOP`&co!^&{oo?qMmCakz@nc~S z4m8Z^BOuAl3#KWM@jsa5fX*gfXa+^8iGvw_QZO-uEe5A^lp$+U#o;3_q!NNJ$C1Dt zxHW4!)C_(m?kuf|q6Q;mQ$Q&H1is_x*`5C(Z>z2k81OJy!lQ^Tq#Mm0@qQ~LNj#mq}iOA*_wq3~m1Qxf1~wmIx7nojd7?^QF&($Z>+ z4-^y@LRoc3Yo-f!C|{A>m0&nPzO@wCT|fzA_pf9JP{uCfwGtH|nk=Wf#b8|T82OBR z^A(Z85wbZOwOIjGAk(DvJm{K#4@|~t@XnL47PuD)k_7t*n4q~x9qCVXL|{L9yt2e7 z=jTIj9d-j>^W_|%CEj<1_gdkNWTN1-&%s@R&FBk~ViLo6G}P&Bq+yr}36BC`Ix$&H zxCYR4#WPOAuD+dQJ<_-n!_=2Qn{|xL6?jkh{IUP{^G@FkC0D^w+(|tL<&GVJ*b23= z$t1ScvFqX97)XkT!71PJ#Pv6)5O(j%Gku;v-|7l})bIx;P~u%SH}aiKdG~cqcs?-a z69n*r=JBU@l5KPOmkW^`(cX?tbV0+sWYO)~^vI^6lf8GTA(&}Uue+-S7h!4Anput>1{tpY3sL!uGvom40*TFdd zsDIpY(L%Vl`J#9>e*|CvCV_X#%gg5v0I<^Yo4uLX*ArQAOSUcIZY%?U_*6=^Fu?{o$!b=PyFjCZV*#`Km__(0p-7kF)+H)<@gf?5BCZ5B8m!SISm<1Hv}E?G&!GpvVEh)5$21Y}$?&bYM5mZ}Lz6rusKO+`zCECE@E0VCiPWmRZR zP>Qn5pkNaPQ9!CK1q4K*LW)s9ipr)4NWn&A2}?i_=y&^9bUOV#dGnTg?>Xn&;#hDt zT)@b!gp@=P%zTV8$+My_PnXF?j!9w9%EHtT5>=dk?V2PfC&vsKR;#;X>pf)lahR<3 zyc-Bk2D`ARC><$s4zS(y!?68a6NjkAfH!r?jFvGz6QY6__5t4VcrV<; z@%(HIfnzN$7RgHgbo^I^n7d&^^FPiz->eyIaO*3PJi*pI>1m#goVm%B;hH16t&iA>j7k&$V4u*~FXO=~xQXOVN@ZF>!6xn=%-#XLmbtx%>VppPRMyX|&CXD`XU>Gr8PrtCCP? zGmkWXN=tM7|HuETw^3rsB;7d9RUG~BDd~_Zg>H~K1>6m`frl#NV3lU7g?Do8RZ)bn z!XjL}V4YAsp>`=KxZT_;mwsShAHG~P=jnPdam`xI{c8T(E^)_7+MJ#Hk}na4NeJ$Z zve=cz7T#Q7{_zX5-9)!IJ427oK zb57f_RsX^CsM;xZi`u^7qU5ijB1;Z`+4y)}G4KG&38xwJTY+E`_%hOTpn9|*!jMMm zfE^N%njULT^k_k4lm=I4d)Iv74JiQ)Liz&z{hiPOOC*SJQlhpgo<8Nn+_nzKOa@dh zG@3J?p9QwZz2PPcw=!)$nek_zvZ{Zw`-MyMg0`|K?W&rLk`!yM#<1+!TTcTgK3hQK&MAwoMR}W)TQ-T^95Q+o3l!(YkEeiD+t`SG{ z_CViLIUjoskeF4_I5Y%^Kp)2unJ6Ilg0j#A)G~Dn5IU4hwY~HkDL1}8AUv&0!~0#T>A+*U`%}W|KQQ{5vBUzQSYBkKpL-DQoj~L?Rrr08Rt9 zXgBkRG!9u|V$2dVQzPd|*8s6tRh}-G>lM({kpv48S_{h^7*C2KW))!nV!uqGh4|`^ zS~bHpMuTilvq^v3lQLPPyzvLs8Qld#H7ANGWH3sezH1~Zz3I_f12TX?&H(`%;^8mZ$FT_m1koZmm!%LZZ#(+Bx+B+$eeyep+D2{9 zFTBbGLB%$?89^I|-iGh2_l=M#v2f0%XQ$g{+h73r61HxQsjNCYYz;P$ z_zgg&5xoQI{8HMlmG`o;@L5btWuI-SksCJnSoZJ}W(*;BCTYP~r@q)6=Inx+pJsFO zc)ZxmskEb&csyHqXL1Fv@AwlA{e#vS@e1Di8G+}md#`fa(DluJ?uyh)BA%!N=HhF8 z2@1vUp*n-!NQ(mL9NzozlUP6zo%Z0NND?SsMiSl&LUay#1cl84Pa*lZ)G;Jef1Ddh zXlun+AnCV^MbI#l5XZZHVL0^BlKobjWL;|2V-cS4An~5wFOv;!hqfQ;^Hi`>7J}{A z6;bym>aTmeAHOp#_Z_WGqTN})BB1TDS&cT0#;RuoW5>hin|L5^?*s5-@b)=iT_Bos zF(rYE2Nj-78jxpEyI@k0#tgHTn=+T8+uGy#YDz{g4`#}>jdzX%N@Z~y+3@;S7N zRw2(fK>>LM6f?%tK(TL_q^U$&;td(ZE%oTThJqXnTO zSYu^*ZMh;JVO^Ny*-jDaNmNrlHaxYiG-i5Est3DgO03st0wo}|=Inp1*32X%?YeO0 UDofOhAa=@m&sW@A4nB#00||(r`~Uy| literal 0 HcmV?d00001 diff --git a/docs/assets/images/terrain.png b/docs/assets/images/terrain.png new file mode 100644 index 0000000000000000000000000000000000000000..f4dddab2f645c7a67349e14d1a4afc9b1ca2d7f2 GIT binary patch literal 268716 zcmXt9cQn=i|9_j^BablB`Rz#kI1>B_jKpk!-?M(j{Bunjz~7A;}&YWo9QX zrI2~EH^2Aich2{m>!0i3eZ8LJv0hOIdKwoQxEKHcxTvLxF#-T8AMnc(LJhuSb~V>NW1)KbNM!bhHAR7(M#o`;r_!{$3{X#>zk{qXWKn(XE}MjP z{5ns1n71=7BMpwNvb5cfmOpy^# z&}}bRY-1j1%58?e>u;^ppoyAmGQ+}X0PNb{k(`{|g_keyxJrowXj;C;uL&2=WAh1^ zNLTtT$8Sg#8xww=JIX|zD%L_)`O~N_CvX5TyD(y{sYppld z4u+go3MlSPl1L_48FNvHbxV+p`il;4p2Z9!fw>Qn#Gp`r6P1dQR;Ly`W`!7t_|dL zVwO=XvPO+voCbrWF&3jSV5f|jj(cUEZ6BC13-dI4h5Sx2dvLu}D?dx|_}@v+$#lN? zXU{cvM|1wXVE$w+bDhHahdH;W^PL$m4!GZ1hGr>yii6&iCQ_=SIX1;xMAvwc8_9vHaTS4BPf6nf9fE?^enW5I?FGAvWL(k`zp%6Fw@C6aJ=EM%g*PKMUy|- zgVW^99%(-hjW%cXxGhDpc^^fNIlX=~+0!`i^1Hsw5J?tM4>MNeKBbvb0KqSoUO`z)YlaKMGpQw+j=cxZS_Dg zU}EF9OEy1oYNL==;Jt>Pnp z>lK~rQab)sE!uKuY}fyIZ%m+N`HXP#DY#%SQvF)qkn`=o6g_?Y`M_wxo7TTDL#%xa zB7#Iplj*HOX+bN$YhcV%1+*A~`vBN30y*t~bH)Ahh7e4#odNQG1HKJbNF(f`WsH}T zlam-n042ETLH44rmG%8551h94g;h<|ZGE6nh{Vu>#{rQzb(!MZ?H{;Ty1GnD$I_Oi z0HFv15IBQywmb>=eN5D5JZ(G2D;7PK-%tK3TZs6YD^2bh?#R2XT{2L}wUxg%H#RX7 zIv-oRY|+XQ^X0p8VyiIAOCkpcyqL2xV@X$3L}aHhxZ~cq8iZYOYuGnfr0%~s}7PV|C%Xt~>f;=&v%YTe0 zoO@7$rqx6)lX+6Xw9RI`{J-y8gD3mT^D8%MxdZ-GzR+(v)8k}l`-zUWxN!YVNjN9A zASROTDfl1)4geM8sTP~zH^1z`-NK^uho*3}F8x(u#NNm~xpd_=(uCH?);R8|c$bA+V*9mLrfPZB zpB&*K{OrMNAFpKX&4y8qpI7G`Zd+-1DzOx-?*91mK`@$pYI@ZThs24iK8maAlg>FC zdMUK6-?9_zdsS*2FLs^Z?TTB&iIsBCX4kJ2zF76&6{pJ;4?=dvIQU>8OWM}QJ!UQP z*SpokwOFi8e+z5BNZweEt-+0FXJ4vd9hN1Xp7b2cOu6ZUi9@(Itq)se=Xi(A^#XtFP~!cc?ti z{TN_DUT(3~fSt+`Yf-B}UfazMJzSC<)rjW_{MU94w&B^lS6k7zDGPKJXZbBMpZ#Ng z{hArv#U))@;@ok5Ki1?2(MSkFVuJ@0gIv8mnybVO^{$@u8Q^?M)a6gE;$AfW;UP_R zGva5a{Q`*ues0KBWak^#)cv>R{8;l2j-sL>n2WxZ2IiC3?;t~+OP4QS>7UkFsnhFU02j7qr%u<0X+W*rBg`?|jFVaV2xyG34^4=gMcH^s1( zrhn<=kd~HiFmBp4F%~CX&!c)uiiBc10?ksTs*R~|))QVvuha}H^^-ejsPSvC#IFH) zhH|mjDOF3mtG`q=nvb$5h2}wnMe))WlLs%IVz6bqbr&qIgr`$ID)yBxS9T$xQxb?+ z`b)}GhHdFC5^_=s!E3?Rh=fg(K}ZTa4QES0BF1J=yu~ zCNL8c9O$^TPwvip)jCdel~9Gu7jtxSWZFAOz?Ic^%G{Uh&NfHt6J}4!Jdr9^m*_8{ zV$?rNj4EnXHx7Ax;0kQ6CZCNcos87f)R0KHMO^dlPQ}%x6XzIT!x%ugcVvqfnbm!_}l-#AI18b{HZ>4E{pXA(^Xl&)$g%aq(vUozpttqrci`MMG;T+A>UMr zzr$EytT1XkDdJwK5CAnybgcTjH5j05gOQ-Y8YEU_ zY8Dq27Me)uqG5Ob)YOdGNi6B^4NGdVINA7GA(4P(y^o8n7h=#DXJi1vF@UaJ0kDxq z0Jr}szj4k(@+;%N6lMx!nf^HW*@QL|d0=fW>oc{c;YV6&=(LED0=O#mS(FVDCAF@Y z%dRpXo{(|XlPkKuKgeR09g8Jyw|kW9gh{B4D0>v}O^6Nisix_q{eo!A-VBlBn>e3& zjPEP1S;eEw(NvUHOl3<0nkRl(l9--;cjOg8#r&EgU*1MQV^c%JBvn@;Za^W39QS%gGA(=t$?=ob0(VO(m0h`N2mIyY-sAH}m5ML@R`6 zy(tQ271liLH2EBePi(GHr07dH47_? zAT_dG5lsWoDkA{{EZP_g8w$axM*`{*B>tz_)xvAH2WCU|w$}&NX_%kj0v$d4KV`p# z7DS5|zrnCoa@gN&6Mm0gysj&O^--Li;kv3A;Pd-%V9GN`(|GTnD)W5ZERP3E{#Gjw z?B-oS@-d@yBG=v42f?SEye(DLlV>2bnaM~W=Ezf*ie-rr>woOW)8A9|su+tsnanwv z+}-tysU&-Z9p!`t+uHKL_>(twcNc#ASib7d-Mf|Q&9jThBX)9Rc@s1-;5H$C8*kr--B$1Htl9g>t_RR-u6CnH>s(@~uVQ(0$vP z-^CdTS|6eR~jti;`nn#rBE|lP4^!M|t z5_SVy`)y*OITnljSlv+lp^Ct0nD1(03_Fh?2v+KkuqC2g4PQNLOXJv5kBb9zB%_7W z5O1O->W6G3I8(Mpwv4luRBO3|b~Of59euasrYTAu#>Vc)X-J*zv8)z#`X zHHkm+XVNI+aEDckUyX2SNy$=H7Wr&H?5ulj?IAiXd;O%1_qgr2efs%@%L6$ITl>G` zHDD;e0T>KCO;Q(F{2!QM*s(sJ9Ab*&!9s?o;zkFnxH@t;1Q&^y9^#qKFIHB^=tN*} z_4>QT;OOS#AQ0$#NBqoFi}bREqUXK}r@`aWj3at;H=CPOYVSN6W_5@cf%Cpl0T&$+ z302`>dSSS%o}Vbqg<)H+7mVgmP1-lD*3!XZWfo1?0fL}<2`NZFo8Oo`;9wL$p?W_{ zsVFP!@9*CUG8R|2V~YaP9Vf@f$9Jx{p{ut>(8h>S0(~)kByBJh2C#u}_gfznqLsjx zmzIl3`0Fj5@@aQzZ}34&=-TO#(%6~D`rn`Tme^9BKf2Yu_kiE5NR6BQLBO=;9J+>lZ37^dM|LwlVR)kv~ML>0i-m z$7aIA(~61FYoZL8P{b!w0nS@tYJ*Y_G5DX4OOJmFmh@r7%EBDL{`EK^lRyBz~+3Vkn zjz0LVvaMb@A9v(i~n{BCXcvg(`lIQWDxcfC^ z>D8v79<(vG>TL6iqrr)Q^Baim{tcq$o5I5IDv~S)IZa~&I7cG`dN&hUDcQ1N>vN-{ zqaal=HYhHL~u7e;fp(iyHi#R86aakcE49s$4SQ`BaY$I?pxAiNrCB1@cN5E(LSDl<&vVq zlbeZO;u7xkCtU9cdUz6)ger9_HO}Hm%*akZ__*VI~+_kGmU&k z6|6#!GQz^B@IKa%Hc*vYV}%)`pM7D@>{(Z0|OrYhhx@kB{9lsv^W(M zFp_~mk+=XT3`r=)l=cc5)|1!I@jiKUa=4?x6X@XL;!@l4u#nz}?RQyOto&eMkk#WD z2;dAaWB>@tPgtp6Ir{!;@0_1^L{F>Yfvy1&-ei-aTdx+t0sYRu26&lwTWivSNLOk$zxkby^aSbsTcPRZ3D( zM>6E{Bgyt%aTrGlo^Fn;EtgcZ+}J%Geyr7gL`FY9GK~}8$x%w8Zk6|RC@Ec$-EhI0 z@n*GrTk-)}E0!Hd09qloMmnZu71C2#OGFv;1#wWo!SNGt5PF7496bQSAOIf+r8E4( znDXuMuzL1@yC>7EqSxHdM4GMMtk|_)^AW^bNcL6z=&u6y&= zTHsN?v6gZs;2bKal)dNsdIqU&Zf5Byn|^nliSGB&0i{{aQrayJDiZDu!T_LxjOtIFN5x z(5zH=QgMf%9gd)R)Tbk5>NssVit6J>&-{&!rB@AmLF~z<4m!O(>qrt zKrXVm`8d@PL5qRsL6=D+l^9JC-D*i~6MMs$Wdnptwo{+wi^t5c`M_tB2x=J9-Wb;M z-o1Y_Gyn?;LsLq6?Bfd47K9?NYVm;pJEEz5SY4n;)5>BgO(hg^W%KPfT zV$TszZxiuz(TUkXYwOvbVp>K<(^k2?ns~7a)mt3>n>;Qlk{aN%3N^(1+ujMo0~ki2 zu#n^&p@|74$tAx(_p?4JH0;sNk1=(*`BBD{gnj;a0?t$;3KYN847ZP-J*apsy(whs z3WETMyKFGDy+hPpd|W2OTg8&nZx08B`^sOb?Tp{|)QKMY%&auJEJ^>_%I;;Q9$Mhi zOS_neVEH4cPth!|*){Z$dG(4=!9oR@JlJN8n0FTrBd&TA4XvmYLuDa^i ziXnp`;P*MlrMo(B$(Y7|p?!nL6Y^Mg3I(}T*bJ#PGxe={4MSIYvXu5u+D?#ps(AIfJq{~HZ3hY* z)bBa+iR+(x4_3YYr&`sTG?&xS6prKF^s;|&5`IyOEeJQ5TN znwujbBO@cR@|Rz_q<3*R=YVoSJ=0~;2M;VQb)KkWK*>Ie1pUp!ucV-`_j}R$`}gn7 zJ73nA7;8IQimX3x7ZJY=)i0dq=si}GDd~n>DCIRS)!yp0b zG!in8iYNq7=T+X`ymVE24&HBhW032zXz20j;EY^A!2Gv|wU+nKIPQU9Q>4Fq`ks|s z*y)pm`geC7+&*TIJ-Ul#Dru?>x~qhbp2#->zlX)y7 z-y6(%@yOyKWsH4H`>G@t@@L77v(9HU%2+8WV;W`Jo-I(=+4xHpAR$s)>woK(bXBVM z65~R;2(9wD&sH=Di8uFB=wzrR)y-19+?*Or5eq2oMJK0pb9GlHh)+BM z0VObiOCI)15&ca6uRtH;uDK1MM(g*7Tc%s{XXb^Pr**<>9m>3?tH-f5J4d{yK0i>& z1`}$pxRkF!4Ck!IJ@m2;CZFGUU2&85_IB$D^IF_^ca^P4i4Y4s+!=)fSQDM$dE(Io z>O4N5j=*7l?bi!TS@K?oUGrlgX86-Or(zy|u^`Sd?EMwp{80e(OGUK3`DY*MKP>ko zfBJZ9Y|W}Z;2`C-^#w;dAYN%>-z@t$I&U=B2#YbnPIve1pGUJMa^#bS717$Dv~_rL zy0B14yn6dltBeK)i=7V?K@QQvuqnh*%pQ>wnXZ-U2x3k-xrQq%8C%sCvit$>0W3lAGiAud9D{O%#oSLR=CCJ;G6&Bo7g7VT7WNF$PsH-oxon7eitDdBNBi!4k zgOcqg*x*3kIUKN3##$;p9=2oFvd$eZpbFT&z%c+g8wSu(f&9so{!9s>c0_D? z$0`&L|K|6>Enbegq{nst7VdozcCy2(xD`WEJaqi?PWOLVfWP_H`|X!;xI$13*2w>5 zbNesz;YvmZ)@ps#19W>r*SB(Zvei@!bw)e-l2BSBYyiPPZT!}_s+Fj)@Si|*1h}E` z1VluCzb`f`d)+aRMT$E7o}?J9y$T>EMr$C2rBg<#ql`_^`N|2EQW;tmDSBA7rpn60 z^%DP}kurU<|K20{@88MGdOJ+z+ym9_@;q4z{y4YbY6k3#W_^=K?Szy8t6E2%VC~0` zs+>t31upesErirRE&}6zo8-MqmoKf${MQ7xsh-^%cf3jxWY3GzVr*Ys5n`dqZr)`* z_m+gTBiVrF*f;l&Ba+E?)!vcX158$#{L;yi4->-S5-{Q&2unT&23(2l${z~A;baG| zV2hs-o|cqEW6&5ll2($27Ot#<#7F{;k?#_vot$uk*)qYu+MlP;^zO|ZEuB7^&>;o& zfv)3CYHBVlc6x?fCWZ7);`c_6^b0#F--6R9ON!A+i6PtdTNRHYLfiYGuw9G<8sig} zDS%Uv00@TiPKAoS^`Ap`x-uvq>JOeV&&u)a_1e)oAWRC=3i|bm{MUYuc{?dS7HL{s z59SK2hS2ETEf9(TAewL?0t6y{*T6W113Q-R1udI5TKnZc6i@EoC>3qo1wB@B;A-5^ zTkCGS+dr~Q>>b!(7?h7zQu?pe?df&BGqS&)>|LJFzpn|?O7cg{0yCi+7?Yh|>x1Fn zIY+|KQD3XnYp`ot?R})^|Bf5Sf7BN<8BDR^g_XEsu~So1j^+b{gSAsv(Xry`CHf&T zLw%rq%K#u~6aQwaMxeBSHzX3MW_*1s|K6vSt#MDh%df#Ib^gZ>i&Q6Y%E_=K){79l z^kZyqb4z%aj@j^2Lar-X(18pghuE+&e|G(ebJVUo?uk<&PqDdml^#fad z!J2YnB0 z*gd@*i7H9&SX};?OSHO*6KMt#AC z?V_upGN5)x7uJS#1oftXx%RE=a#%xlb~-@i$Fnbede7kRg-ozxyo~8tk`I$|)02oL z>4YdvwkYv9b$j%~+9?F>t{!9O_GKtEkpLa)`^HGcc^<|&6anEz4sPSBQDKW~{y4CJUmCqak*vD9nYJi6KPgql|`i7YRG0aVK-Ehz|x3`zZ4&@5+!lIx2H^^uVv<< zvbx-BrS@K*Eh){0Ol%A)p8j1}SpLMp*xeAVqC;}+aY;gZH;ln5YiDI)D*>}k>-W>F z8SenAV8JMb`J85IV)82F59Yghg5QyZK;wyDiy9z6&Is!?$`n?L0&?880lp}62lSEKY)WneP9&H!?&7@IA(&C}*@^kw2J1WU9BT5M*!PO43YiIBv@}n3Nq-K7X<;B&S;X>*5^}g1GAD3brS|=M zF^=tO`KU^xmxQ+@NQ5TfAe~DTud8}@dP>QW2|08E_HVRo)|}&QtR-ob`I%y|Rue8s ztaHxtK^sM)P5;`p32gSS;C&Ha?CyyB70Kz#Z|qz7U)?$%OvxK{G!Gc;$FWl7V*s#n zPEI|FMnDhxA_A-yP>r!PWP5feOp>dAa1dwCVz-ugfrX6^Kd1QJ2^W_c9StC85~yT% z2M#=H@4tR@F!!Tt*~YC}-@SWXwy|+|i&*A4&A}+pzp&l2xz?{P<_sj-xKJ3J3TY$;y2uw%$0V%Ly&|I#^>FI zc!h*0XeIeIT(vJNWOxe+W^4tCH~_u4$}eFXZ<$r7Tetp%yfH<|%p?*);?+HneUt#nizu1VF^>ev ztUzA8!X`mKu&AZ7vhoM7$Dl}`Z_$r|N=?c43V4GT9QF`Iw5tgX&@J*+(Cd#Fovwrj zuS`Jq+1BEji=W?miS_An>{w~TXWgNmYwkAm-@ep;&KhcOS7{hK*@zFbU>gIEx@B#A zs_z}ib@3kiX~o&rV7XO;UWB4n^YOf>(&_$hP;3K13+7KI8vXqR;o~`c!rtvg0KV!C z4jp>}ZPc-Cc?+_5o6yuu!+P*nH4G zyP;)dHnuxHPz`G9fAe$LQ(BH+QjRxx&o-8S9M*X|h5nWf3z6q(+8)*homTS)iiDp` zys}l5mA_cK8GQwz;RKV!geXYjD!(L}UjtLoa=I{k+&?S37~C||ayk+A&a{LM>ouUw z22QH`yjGvKx2?k{KgQf581Vz*iI;Csg8v%lgv?de)tT3Pr%+6N4JRBM$a*ZExB>C% zD@-r$-@o5)nlCrzJD|m8*WH1LB$LViSyAW__doPK5nt|2)Fc8Nz*9~x4uAumz?m+Q zyd|PLB0QKebA(os3*Kn&RznOpX?Qg4fQ2o@Nl#o|FQ4$mPSlHq6;Gz=T6Vn!HCL4W zYsKb!Z1y?g5`vI72npa#qBl=CYTUg2+$A$^sm%|@mp9ktiWU|Z2_~+FS1#OCpI~t**LZYSqCUO+$-*In?UR zTy6G#XD4>8Y_0BKQhu;clJv^=A>`8_p)EmvHzE+` z_xsQ_e`vo;I&=lJJ1`~Rjb9B1A~7mLq{o&izwL~ke{*#ROwz0Qk)7#u3tvp_u*%&o z`dyLyf&i*pyXU{Z;0H9*!~${rw=maC#~^sXGNo`1=fu>waoE6X-MkqKT8X;@viLws zvgFZMeQWifpz(;{zY^!4%=k3MAB>Nl{F-YImmkFB6N|6I#}OSIY8`!fR7jb{B-$r; z-FdEgf4lwo@9tuDAn4DB&i7h#>mO!JxrwOdR5>f##4H_8Q{h6l`av3W%TwX;3aFS$ zb2DLUhMZT|*B1g6(F!M&(?7FTb&oq`T0VW+UuijAxpCvhvo<_2qaO!KnI`Osgnx^f zTR<_$?nodYiSiz3ZG}gCqwIlY2D+|cXM15eoGl0ao*oY$`pRZ09p)?9@f&W;@F4*c z?7RYnsKbw0&2;j^nm_dPoPFGT6HL$a)Hd$~^M(f0lY~&tx31ujT=vCH+MrJbw2tU2 zoscP~J7>EsXBA`*Y26XD)4)mm+2^xu&(r=eYiwuBq1hQZ=lJW{G;d7U@$a1DqqBcu zmQ6tiv!_#M^A~c?+9#TKZ_GHA;WE;I4}t=~P_Pp&f@uhp9lq;2yNcfhIkU$*g_G?) zkLi0mGiSYF2cnmlbzaZY!l+u0-U-%|j;11UCn{zGmd&y=v)4U5Dp*w$ z+GQ~4#mw;Q##cYTnH4QXn&wU{`DCoAr&8rTMbN;Jpw+P?@Q8P{IxGTCEoR&PN(>DH z)N7(4nTwB&%xb#QFD)>YTg`^dr%ZUZoctA4*leA@@%qx@>(I^Nms9sojwoS|0v!WG zwz!TU_r`6DA-q|2Rp3^3{$tn)jQZ%u7-HBMVN{T)%)Nn^+W4CYZS$=`v*QSD92?iT>laKRnqkt33@P{iL-Vtdix}u~-Sr-aA>KOnLiNv9f5Y z(8CiaqZ#Mo@u~`XSi@ja&4ZINGX=G8KV0t@z+Cj;(0;> zQHS=+`^A$r&!88J=5AS8_kwp?D3_V8201PbJ1%DVKd7GU+iV}vud1Qi=|r}|8c5JF#26=VUg46@nG}zZmo6je2Urn zWc8kZ=%VU5rq$jp`Tisogx>%(S3FWxFy$`ULvC&e_37^?aDxP_{zw z>FQv!&+kP~`Nh?0FvoiC+zX!lA^p(J@7cszz3Zb#-xtH5 zW3R=PRVqht(+*L;In9Ayq^ABU8g@{cb9SuMv{>V27Pe{3dzDw|mZaq9ila;Vr3>?4 zx|Gf)2YEyP7WLVExu%7C_@pa(o_GIWu+YhXcar0E;Qc;o$yDeXHug6MY-(*_+LG1e zMdXXGa84BrMIjN??8;1UMCY}&-C6jV$!<&WMu~N`UMIalk{rHpRka(Gjh7Y#d6(CC zQo{2!;$ITHhh*FatU|jaqz){DNg0C|7P@Rxce=U-?9D7f4(shqw1dnMLI+SL9@*B` zkdv{fk|<$RG_sYzpc(Nt8mZ#Sc&Fe`Bz>e-zFjVl#P^TBN6Kfdht=aBro0(sCgFmF zcY@Ah%&Q9AahxEJvb;r5uaCGS~lVJ^B> zF>z&wRCx*d1CZ&MXRC$U;u0i9qCPU8VxkJnjdL@o+=?xdF;hcnhQ_Q z^BCl}H9NK(c5WGuB=hdKo_qQSoaLoomzJd51}#6jFRdO+8bOjSX@4AX<9d9~TCqOB z=bb@}Ij5odWbj~L-ktE!ehw!-4fQfA8hV6;f#78lSD$gbQs9r_f<<@vmG2u9=H6!G4X=PCowR$ZaH%AzThQ-V6U-(&4PN^Y!qwq?8!h2!%Oi6 z8t`d0=Wjs6iB!t^cQ9^c;`A_8D5%nbFEE4;-X)OmPMs&b4>{TelOpk;HFCCB)jPBL z{H7rUF}U?Wl$f6BUUR?G&UU^h#fv+bvPYQ>+x|Orx1fHZ4-J-m%l4vm^YLcy%;S0X zu8Y}tFE^kn~+?%A&AnS{94F-X`7dqrDTf4EhMqzDPb z#Z$-)wU*a&0vAY$iFXVURpYm@CXP6ETP#3_a=65<;AMAQ*?o&w&QCawym+>K<|64z z_R!ZGPVg=<3Ej`tINiG3(l;U;%}`(`qickdS=+uwIr`bKvcsS~v*OGC$?|%kxg8@y z8Dd*L>A-Yy@@(7!X<%S0K5!tcBp!;4W}taSgDECq-UG1C zN-L{1YXk3G4SrJ*HL0iwN%Cgm-rf&)s{%Icp4d|I+tsmPhP;8y^2?&k)N>Sh8G-jU zOfBg8?oms29o*Y7yD=tFd@nyMUyDzYCvykr2gzr%tNu;##qEC{sh(zl$an7iczShW=PST5oEx zAU$~eHKSXg>$$g@$g8>Vwp{xPJ^8)WRPdNyiZ;Xd%p1_2kjns&?U1I%P8t(>8uDao zFemho6ARMo3;$s_m0S=N<%7N+@V*Gt$>7LL70kYp*bVec2K3p_Y~E?VsfQUn!5=Jd zPJW@Mz)GZ)!X~Wz6%IO#XI_AjQKf@b-j*XWW#)s+NSSqm?<40=rlk)K7kc%$!S|15 zc{%=8n7ZcdpTy7ptGnVynY`M)0qQ><4Qm;{fBz2T8IbqhS@if6x-@(ZSoS^xao|4K zS9K@5o;y1`fjN}fmb1a;{duL6xyzSsa@B3#^b9_Z(j8PfJLY5dJeXcJ8Zq;% z`_u0kv?w=Q=}&3C;_=DW-JP+`^0@25>EHO%FC3~47}{`PY>^6TGRl$9u(bthlW194 zP;ZW3|6ciwIN0*@;)K=SuY-d?BNGA z!Isb8LKva!f>CPjnzp;~r@_rZVnd9a%~I-nL?g*BxwOA^(WvRc`Kg z6K+BbAPg+q3RIL*Fn42f+mQ%XiR~#kbuFk2J3F1Q4y*BeZ(4TQN{1mmcvgF}^_?I! zqjE$<1hVH2=(m{MVNaV3uDFmu+bWB^_}21f>LE$B_jUQq?sWO*bMZ{f@s^?U8P*Cx zfNtci1R<*P)WCH(a6MdTJBVCYM>HzA{cYAvgk6nVTku|QIL$fR+jMsf*%Jr}pzd}L zgS|ubP6Mp_n#eBzTo9i0^iY1VYV?IA7HTzl@fIncS?R;|!4MMySR9JMpNZLWYcn4f zc{tTnHBC7hu7=I+|C#Hw*L>4+r%@A5(?mu_-tB)7$D{i`E`HxaD1UZqvecu zma%j@78ddoYU>1WYod3S<5E)vkN!P9xwsO$7d(Z z$0xIApDAH;zcnKOfv)bb?N%D=v%@lQ}+U?Ka4c;X>@g6J{f_6;c~xc z^LEng>6$+od?2Nx$w4rm^8lHilf%o+jlrncUBZA@m-s;kABoi+@pD!zBxEKSqe4fk(*8B->x1F@_3oT3)a@0O?~9=b zxX}CRTZ2s!V?8wU#fn~bezP+tZM}cz)Nbf0l?|EcJt<25prRRW0%yl!*bH)BNcPre zp$4~da}%3`o+W&*u6j>PWy*pXO*X)8NCQAP6sD(w0ZcABgDpe~ES#!ca~{2NMLK(I zU6Ssx@+BKOM_a?~aG3yQuhe%^pXTQ^G~W>{R$|0m(mz_1dDKqLPMDRMY8S8wF4UdF zFD-p_RVW{gR=oV|`4>}$=gTke*H%TGhPzr;b>-%P%jm5PORgHs^f_I`+c)i?3BZ8I ze+l=_@q%76f=k$FA)oC$u3^KH3c?{bGC~hAmVysLI}2j8O6493Ckr7M;K=JN)YtQ# z7P`pF$vuOp(wxMqUsX0?e@b{yC>Fv~!|~LDa2A*#p_mX25f)Ryj9b_XgI5Kz+xr67 zcTiuw<9{;XY`%W!ImffFl{(*Pv=m)y$@NKkBHf^e&0B&*iy2>(pIrsHW&BNZ5}XiS ztoSD{h8E+X|2Tpk%I-r2dn$x@E_^R~c`SVQN&U(5*W=}KP8)xd>gpy>PrG!y7YeRU zA?*j{DAPerGp^E9Pn`k0VDwMahg(P=WM1^ZrDTuYZ=d5=r)md-!^pl9WtMdkgWh1T zBdGyQgmI=fcuxpPT~sVo?O-l~9RDF0?Q!%XEMU7xsc9v2^-3&qS39`i%A~po5bz3AcGBWOM+c_N^a=;Z{>)zU9taAl z{$f2FmX~X-6vSn0Z{EE9_|KR4(CyZZ-x{w)t{nZRxq9P~Rtbr=WUK64)l^|ZISm*+T zMa1Bak@la=n{1Yj$KU_-9x-7=9yH+Aem+u4`q0oX=@UZ(w{>JUWml%gqrQTTos23o z5qhbv{#%gc5;e7<;U$}EbjnzE)Bg?*yy~(qB~PcP0+oPv8+JM!4!@Lht@%;6=&|av zNF9K0ZABs$-!O!mUxS8wcX6~|X7*4)+>Uxzsrh|ncVQu2OSHt4#K*_iX(t1w!X~%3 z9hxdkO4MgA-02H{cYS@juDYVaupD!XAMSY3JlnCZc0BP;Di|PEzVHozUw8?jMo^#o z8nWC3$$NVJm1W6KM%OlVb-oMFu{Xv&XSPQzt845!t1d2FI)JIWU?lo6tR{i+L+_7jK>Vh?( zVMBDD1p8#sf1G(-&oIt0QeE(*TnHXxLU+DQeCXptQH6i4G>C}*B487i-m&1~LAGBf zx$1chP~nw8MF9e+{5&|ggx=fP>GXPXv{nn=9U+5d>Dlz4CNT@_i<}(FM>$bYnBH9z zoe%T_nUF=n<3WWzZl%y;H|vI-{SA9c;NVet)54ldI_SkOf(^912P$fy(!C0@8uICh zD6c}$_66&GYT(`d+JU1-KU+^{&rb9$!I9O)0jr~cQLW~q>?w~UT%F~mL@@ewI%XZZ zvt|9s>uXXcSm)_4cuv296H;OGOaAP^z*XZB7?VcwU3^lqVB%0}6W=Nzm`;Eq&g}58jIdcMBRlPSUkS zTTsytQ~iUR#MY&2cQ{prUCXfHKXWHnQB5=7{uvX%!3pBf&hlk6`E+jgZo%WzgGE2t zet<{ty_ohtZWFavRB4cRxpbe_zS+}jvO}Z30Khre(C(9>F;|%tdiu+ZH5O$hB_++L zMwJe#Hh4jO^OOfN$F66}`S+sBuF>aI?e=@0Hx>Yn%Hb^lo0ApHfA%TONAgi4DzxH?l%xUW5v9ZIZo8D0^jIJ47j~E5$`Z zlDJ7(nIS7PGnpCL{EqMU_x14Cb?aX4Yn=032g^HpUKOLDNQI$G2s7d+F}KaL;5EPG zQLn2dXT}c&#_!nl8`C*Y-akletC&s~lhsSlIIc!J9kVVMg|$K#XdQ-SJt{@dxE!_wm7?_9_0=LgC?2j+bjD$a%8+gSPq z8sQ}{d~DS=$a}-*I^s1R+iUJSFVSndG8QcyuzLE`!20s=!9%Z}-!(43J47%rt7|bz z!QFa0_D;5)YIN9lv2ylJvN!dY5`D9&w>1%15@j3vJ z1HB`tbDR88pLXYE@N0kaNAz9vG?Rm;2aUZZ8(&z8{Fz;JPhjFjA6Gtmv3x4YwzSmV z8Zb^2ui6)>_eL4#1+uULK~bon#G@J>A58zq_-!Q9Fs%2^mOYqlFX+vun9E$PPn=8( z(izu&oEl=C!b}xR^!PaR_wQfWB0n8o&roCRn5pPb5m6ZA_Cq2g6Ew9%e(LJ*>KFD3 zEQ;)vZjHCMd*fW!v20$ibxkzl;jcaZ5~IeOnZ>kJ67*CG zwfR`g39CpnLZDKhLMu>M9iDBCazw_^d{-@FS8F@2W|^F4At0DiwDXJg6!N`n)*xQ! zWUAA3j1Mh6mXDSXu|P2PWyUKjD|MEx*7mu2IBJE;q4$oBhRO&(0z&$%dx?w}HBni? z2r;Nf+N#lzFPq#lri=Xp7NDXb^4- zAD^kb*BO_+mMpl{GPi!bP7yNuIeP}#asspg&qv+Dtzw(Kj)%$gT8+7-Y?tWUQxHP9+0N`TCsfgk+(U|ZYDBKvawhzC;xk_+H zZewZnuuUsFYVuouuZ--+FOIA%LS@5nm>ZtZ4jYq2^GO_KGD-TA4=l(4)egQK) zlJWHE2e5ewS4CpeDKeQ}V}E59t4d9UXtK%@+!IRm_0W&PFbOnV zRzB)Vq4j;1#a`3t`&)zV?d)S8s;l?Ix$Z8>NruOPP-RqE{^M^_bWfqlfac|UiH5TW zrKnrkPMjx2H#B5oWu;WCG|6?2K4ME5)gukQ1N_|mkEQM_r%y+xN2ir~XGq&cevjbR zrV2u-=;32t1Q+&1S&cWm@|gQ+gj1c)C@(gQ^HDeX;rs2NP12#I#$9|F$!mou=l~h` zcf5gto<1e!LR)7HI;}Vt$pQlo!l*zNz>yhI@Rfyn&BK;~XQc1OerQaVinwD^&cPVQ zBrIFh%Fyz}V=M+M0 zX}NYxQzz%9-XkSbfnx$jDOxwK0h(huWHf7Lo%C*C;eqTlsUVAy#7GatqBXnX1|OXQ zIE~vKGD_?e8$&KTg>P~7Jc>H;w)jF8UQ_kSe1ECSdd85IrfPfTQdMfjpBR9*UJi^`Ma9Cl`?M_JtT73_2XGU`WLrd2rAOEY+E2Uj^)#N-9d_ z<$wls=;r+FYR81%*C+CVGa4&ej~vJ9sSp%G>1wtg`QE0xsA6)0lT+IDz9Y00bWSk6Hfen9xFfw1gA}UaTmIYjP2s$9K4=D^0KV((dhC)x8`)ufJNQ?ZPqvb4P|RS zyBmMUBMx&{jmOCZEUpJE&XuySmtI6Y-O2|zk$0A6wk$ea6Dwnu9lg&EZo0bKJ+hs zIx}#%tk+!Z%9ShP;_NCNKr$CX+qOF{zi0JAyRUkGv@N|-h4w~dwxMFI2;9p5K;TKT zzk7FTqqvvAf$1%fUSVg4g0+}x<)h6J&z zYzJa2EE@*NBftG0T`|JLgX~EnH_zxXjbaU~;|Jc~jn4i(7Tvyh-$dFjNKp?@z@s^| z5q2F6$DyUVkmt?}*r)fNTfkxNZI5w85BjCH?$ zy}0>;mJ!=IyM`4Vx?A3no8xezK_uaunAU_}+oW4MjdiN$rNdMO5&%V94a!A=UxGC} z-6Ot{BRW}@Nyc*_HSOu(+rI^qg7p9i8|OXFkKJk(UiA0gZx%Gj_!O}FOk6YZ<>^1^ zVh%r*#pA{*DthKt3s41@S6UKOz7nltoBaywv_Wyk9o;hiBUO>b>Py2yT zM(SNT22bk99Op3CEJs{S--?F=_8R;{$Do!pxFJo?$CdfUvTylP2uWTPHB zlT7)QmX)@Se!EQfuPl-op2OaOE0TdLMI*bt;;noC7WbyW!;7Wf9d6iPY!<4Vdk&pY zQNWrY?PWkDK^_qc7n+SN#(S=~RlaI*uey4EUocq%zuF{NK8JxO$?}iy%}z&+)n0{37GB*-hcE1D_p;o(PlNI_(1@gC9BAyyZH?tcW( z^#WP*sIaOYtpXAfgkXd16%_HS>=2$H6-GqsaG*OlmF+`va~h|OW18k}Z~yzRt%6DT za?!w@*G3WCGwLLi0P|<^pEMO(y81g2C*8wAucx5M0pe3;Re>fP@P7`8@i8&0iSJAW z>Rp{t3|rfbt~&ViXx9HO%MLgf%B{5ADDV0seh1%^z<*i+MfK1v)5MDX$F#X3f&I`v z7t~e4*D34W8g)j3*n|gP(5cuL4tm?Sd>p20Yis`y?B1AD+&*1d$hjVlr!o49vv}L@ zY-^-1Q+NE_LnFRWg)cf2CAfGJs)LA-FR%-&8Q&`HKl;k8;#p2b83vPM)GO^&NQGVu zVLk4Se0IxAwBrswDZRWkd}TX4f&qLnU*`sEN3{>MfOT*5^Y{K3XiZm)yuGblsNcE_ zUSxk(1%%md^xBIq@VB&KJ5!x{2(#Vd-=gXg%k&9JI2y#3aQ3hQ;N8Sn)zkAiVISVP zjO<-7d9No>_rR|3yurA>Z@n~V7)67PvdCW;iQ%RhzD}pD<~n-gJu8P)vqy{!1PI&P z+n$TVyN##guW4zqvat9=#8&$A=g}k-;1if%)sM)cVwmfhC63(!*dr>%M7)l5jC$fr zj27MvCDW^=>#-8lJF>NMm@}u))CsXk#0c`Dp{%d&zEvhB*1njU&3_ zM+`o#Eq8Pz+$b8CUgK?+K899M5I<5A-!QI4?^ z^|?X6)j{iZj}3bOkzwj|9yVGVrA*5Su;c0k^r8g0M=R{g4V{KpUqvUqOWOXyx%!27 zgJ-Vb$f34=SDj+zu+IxZ4^6d4V)N*V3vw2RU0 zsEdA*=DQGXIxuAYzIXPAqXeI;(4Tiudv5PQ6}UN_ZijnNd7W-iS=CxXGAvgwzq{&5 zNW|g1u_%t$$D+gdqeK_KJ=M>*iN!orGSxY2cY%ae$kU_luq_3jf$SAA8C`*6a8eEC zDhyc9F%!=IIF>jrPu{bDc=j zOayHU=GzK4CRPL}s$pNNYp557xU=fEg=es~hk1D{xf_OkF$cm5hAZTPp;IZ&$`+zPCcNK}@sFodB`!*f>@@`LH1JNeI2W$TsfD^#q)q0zhd1)63txQF zexsW`32pAD6*q5q~;qDGV$Egn1pIN z_K*5Ex+}T$1dA|!RKV+@sgV6>fm~{8p513ud>riceJR?lrR}m@4GY&@e5?T3R#($8 zq(dk0Pn;w$xxUaQ0)xP9GPu^Hiw{B(Uow7SGYqYH}Wgoje?V#=?E{@{fKk~Mj0ITVc%JTd6%0oDcID58BV zL7VoSb=7*0A>sb3x7L3hw65&AA1=8)USAi@@N?*VxB|V(nR~<6ebqai#7}fPN`!uv z3lc(Rui?QR&7G`JxUMbKlXhWluws3*#vnW*VtZ>#>TR_1lKJDVcbeynlr-x(OYo|k zQ0>FflbZfKzjqccmLYjX^SnBI?>(+i}aZZ`f(6;Qi#Q$VGti5|i$&F+I zlItZ{gsk#AOVH6OFM*0@(RuJgaqp}&EDxs(JohZ7N#d z>0&)z=kY6t@7nzAw$H`z>?%4bFY7s_&cs>WeERHJ(@GlgX@wy!$DwC-Ek*?VI>52S zS&HfjJ<0DTA3%G^((q|&OgP#PmF!jlZ${$`!NzvcKgF)?qiS}?-STvI{82=Y1H5eJ zPM-*Q`bR;km?r=cWFlwVOU;EH#82q3V{W5rI8S2%tY}Gll}7}660gG2VvetBKg=!V zwXwvDaGpFVH(OBZxJE7&YV8D4wQ}o^Q<|81N>!E1$ixr!phOYx43pW$?`K?mbWeVH z@il@gmL8{|vlK<86|9S9SBU(6i01YWgHu0CJx3Chi&$9JD4U&3GU>L$*YVQ!792e9 z>Y-%KL-=`k5>$|1JWL9YP%M#e*FSYTu5~+3y7lvDSRfbc`GbOm&;*2_qD`w!P(VKK zTgIs1Q|N*$PU|X20Ir`Vv1(HNz;z+1U&tfEJ z?b9hnhM<~PSFcr=E_fuNsgc?@+C@EETeDZ$mVX#4PfShyY>3x7d^q+|nZ2UOTU)t_ zxw3&jY&sNk25n%4@#6IRTtU?6EY1*o_#-_k%p+ndfiF%|U6Si0clwFUff5^&zqy%ELuF3AM78TS%&m#?9x7W_hIc}z8cBRH_ z{(l+KVFJXV>iwmfkcf7v@tC#Q_SF|pHsgHWq-;5L(?{P!AH5Rbx3f_^E~sC?dED%! zfO@Bl*Afp2mSRFe-K3jYSfNO(A{!I(KD9AhySgu*%(b-X>fhmXy`P%wq+H6<=+ooEgPfv9`ir7{Qu~t z-(b)ZsrSm9u3*T~&-b_7sf7&)Sh9LzF1hRmUK!OUjXCsCrLX={bLqFdNFPcZqMM|f zbMt)M_>^g>eo^e<`1_SZ=0%=Mqcs2%7xp`2pTP$P7a8cU{Wl$&K|M)NPp^dX&VXdv z+4J>q$@Cb*t~eGADWdpVV~DDf5fdx5tYfr_AzmyMIjnV_oly-isQbUahqG{G zYpdR)iluAy6QX4V!PRFZ7;-oS(n!pq6P9)bR)@$M;l?Y4H_r>z(oxeAv<-toqYy?$ z#*YXB%BZ&os6I;qb%`ijE?cnJZ*7P6g`upfzbssCnJ>Lb0*YZEpL8Ok(@H_8@$-}a zwtk^;SVWxse24);(55r`oW&@|L@{@9bR<^?1{uw+UB+y+Ogmh<_=Eq+IBu4TKiHw% z=Un}3wWG0zkmKmp)Ws-zCLvAbXVz;z5^+{^V3p9IMbYNoiwdUBEw(2jhuDwu^J9aR zP-EAu^Rxy3xeUCYE$fYYV^-}mN$%>zsjt-5T?+NH^r_O0VPM!+>GO?`>fyw*+c2S3 zbQ-CO(Q3&rr^_iHx~6}PNt&}Cn;RUou3)qCHu=G&Osh((hx&2ih}xUq&U07fx97xK z0=|ZqZg0(&mUfl4rVhT=Db~iR`1`Y9*;JM37K?kov7Yp@v9;ZrEA4$_TvqkGWfQlU z&&n}wX|X2f)!yO;gkNJ_vjMJ1(h;Qk9+i3moK__M_dUhyIulZ%H(qZ~jLS1ALieiS zG{hwQ>CyBzt~Qx-SD(EyJ9<bf<` z24=(2zu9+L5FRDWE8WZKhcQM@u_9Pe&nA*ebd1PBANAP^C$5pTF_i5a4T(e|sQ*|NVlY=))MG)$6zM=mcDIeAU*U@=p)8A$sg}n_)%g zBgI<2Rv=d2+{|NF5sHh>(P-`K;}lIv<8?{^ev#p*K4#U(BK(tTbu_p82|hcHaU7fX zVULHU38gto#fHTHpeJ}iw$0;HPqa14m^Ny}oR2as9})@29anl+Z)}AYxoV+pm<3-* z)YYq3v5Ax38Q%B{$%0`@EuZD=GQ}9)vbRb;5B=GD%kEpOm@D`Bpj`SX+3QK>zMmxa z0nxs6!r#Dr^Qhlc4g;fWztn7+ZWylhK&KinLbD8MI`cFUwp(j;BLHQN*iX zaBKw+$Ybt8M>TmHjPvAY!tMw!G_E+0bG4m3aeR)iu;rZh@bkNE%q(lYj%B!JG!-qX z#<00Yh7b8l744dS5jwSzjg1L7=b&TmtV(}%f$RKn+cu2iaTV=4G`@{vJeR$q6HZbw zNlD+f`qHEEhdq4@KOaxD&3Im@pK=Cof9$E$Oqi1CogWdXq2VjOm*=PIW2a+;jw^*V z9@SGIP*{;hfkOS+?=@ecQIy_|nZ!T!b@|W83B!(|`hli9mErSe`bfjMc4^=7kENHw z(f<|(Dt*`6n1n8u>ld|@+o>4B+EK}tiX(A81SwVX2G#^F2=pvS@0d%;Llzo@tTj_=>P3nr|mJ&*^?4HGw(;^JJ*U`4ZHLd_}SF_|yF@pFlkuAhXQbqr;laz$5Hx1Q5DE#>L|X#x7IuHo@S z!#ur|Cr==*Y6V<`u<7wFkYfWf#itcR!!zr?OiWD48gw9cl;Vc&IEpA@D}Le*KnpD` zd=4$Y?QGAMmzRIqTPw=EytV{!%idTe1%g5?dIFF+C*Y*yLCRLW^JL$OyB|%>=zO8BJg#yCjEy+>wN&3$(zwEx!7ybUHu)Yi5XD_TWzV)VWU>CkZyom-qE zjd=NK=}@GrSL+e`XSK;1Ip#$@`Gn>eG9yVKM6t1?U}SMxEZLS;AtiTdvoV{Mks}NoSfApUj~qGTnno{tjlIf>`qFPr zJ870UJ+A@@|8bBqYrZ~q?AXG`>3fez_i58?;VenAhx-MtSckE+>c}x!T2-Ti)WsfaHq&`?9$rzxOvf;_%6UoxkVCUXG<# zQi}i9a}`NEi%mLrigQx=n48Y6lpDb*Ij8vu=#H70RL3&W6S0tk1N57r(-9{uUF`UT z7HH2#eAg*F%kHQ4H{jIhT4beCA*{&WGBJxD^Kx`-GR|kLzlRFG3X;DP2Bc~o+tkA7 zv)i+l`pp3`Gc$YMztSeNxVO#h{2m-u}ty74=LaIa` zQdHzX6Mpm=;v*Y8(>wY(@D>9TElXQ7>?2MjL4MAUzC~v*pu6Is{oF5A^4PQ7;v3Wwfwch1b@ zMMnPRFJVL&dsK~54lK&x7CzwUK?zz58ta4t`k$&$lfyTEZZuB4@= z3kL2@%e#WW(!=*$A>Vk?5#lICvL4-WPwHBi9v+e=iKx9(RD1jP{{hQ^*Lg`MDujZD zs@rjXb!IXrXYzGs089dLM}UTl^4;1EC?81A%+%`ou^&VHF2u)28wAmkH?Cd#!Bxhy zIXHJ;t_gBm_BZ19z5MS$*7(*BkOjOHsJ#@h=i9!&6d`}0s@@G;E82U#9d~LQQu$4` z5{d2UGTW_?zX5B%DIr@8{)ZB0PW%NEVO}m43TwZGRMYa^@{##}l|zaNl{FUjee7Y) z(P_+N*rkfJ*!!P&Y-#lggE{=9&D?u!>Op2CYQ}J!7~L&HE-F%S4`@oLr!@!{>v@9LhrQ#8Ej>#@Hy@VV$Bv~PL993xD4x!JoDfe- zoz!8G_`zdt&v!v4;J(`{g3BwfUsKK4phhB!QPCp|EzA4BH{GMsbM^Oar-Ix$Hyib! z@ND#BqM*ajPcJEMAz|TDQg7Q;t(p6t7SPe*H2I?1Zb@;e*!uW%s;2RYAnYm$(<(Yr zXPxfIHbvFg+gs`8y-cuCRYAU^gOx9~FgNwQ?I@l?#=0%> zSN?GLY<#Cc{|;q&SH6w6f^F#hvj&ryu9(8+6ww1`SD@v)5& zdkz`;AZS~YUVZ`iuO4qu1bX}O>Y=-y!M!ei<6ICBjf*Z@>&7)7J$f`zoCD)@0W$F* zBwPr;3ISx;%hP%_Kd%xXs8syYrS~o)aytHN=j6R-a-M{L76!0|OnAV}l=wz@LayP6hvhZlze=RURjFSw8FE(Bf)+?(s&>+i+;v8zlA zr|pLXZZqtUp7NV)>^Ke4=<&Kv*ZC^h9|Z-K)LazRVL#WSI;@zeSH*Pg)zHk_7e3hw zO2>~2ncij&8-;)zMXE=rt15^3rF&;qFWnt6HyN>CoO`Tt2$5g^d+vE_F@ID)C-#Kx zSMfrxL&(i7(cE)qt)4y-N2sxw7i__fC`IJ)Axxw9Vw&1Z{-~#3;sVTKT>01_sS~m6 z?{4PtSm+#eNNf~hVPk(B^@TOutPY!JVi|8&w69G^g-$^3KOsV?7^nKRtb1VnWaYq5 zL%vWRo)c;q zx|q3$=V$H>cFFtCPl5zaE%Ll+q=3Mf2CIOp^?-R9yVJil08Pb6hjYF?*r1KB) z3;Rad%q*91N20LwtZm+OF4ttQNcj59%#}GwQjG%N+`3XV;v)Eg|F$g^a|>DRX1V>bc1*_OgV;?U-LzhARPf zqD80>OktT0d!1`jEiXStX8Is^ps=v;cwE5dlfcdIFO;2}oVcFPMn^|?I}-F#`#D31 zC2AZHMOsi+(!d$g2(Vbi{h7{=Z0PcTGWjmc+L4qaSOH7AWov77?R6K#{kBE7M3?sn z2?-fHrMr7)^g2o`UIEra>@ukm95w1xiv@lz6 z=(l1Re3Qa=NQC~Bb~k4TDod%6%yYnP66>G!`KsaDfbtTC6z7@FoO2momOef{PELaA zY)*GFrmww&Q4Wji8kuS$3-aPx+)Hz7r;MFc^#1++FDMIZ{Bdk5HaTo}rQ0zbjh6O0 zl}hZtd=6z=C_X0j-{FWw%K8G(JDnQNxZ@#MIW86h{qhoL>%#QsnbhBXvZ=FFbSAvb zQ*7Al60S#e#+G#C^1CcLbA9b`bFN4{yQTp+8GBj%WnqEP&+|7Vn};6yM{t$(fUx1K zhi~Q0e80cPs^4}E;hJt&kM#E$raw=QzDBEoe}((9TKg$Lc)ugw-1&zIV6R>jb7jV; zyN}oDzuq-x{(E>?NNPIrqIzd{cUgDx1FJb*Eq~HbzeihMIA59bj|w(*G=V+A<2auB z4B-qK(Wd+A%GMh)?PxRC{bU5Pu9wdREC6TGP~sfK?-PM9mZ+3+Yl|dGT)N6b;!{`4 z?qCwGdP||~9_TFs0y2n72UDN0!9=nT7&k!f@!GgZZqrjPW!i{6wUa}jM)ei{GMZWp za~wkmvww2EKm>oS5oo|&&;5mi?3%WNrY0iO|KGvCwez^^6B|uU zj0m@!A1CGkt607OGJ0~zsuAQ#kWSBoozv+C8T8D3Fo0z9!=Mh5?}^wch$O#}X}(u` zE(42Qyh6fagMgh_{Rg6;R}O#DlCHqr@>cD@u?uC^vy2$rONRpT0Y=tI!hsLvRKP4N zT&6H1WN$)i@8wPP$fv|8+5Ng(J7c=-vXc}U--VX)y(ccaTP{0al_QQCxD-WVQVS-l%5`D+CLIi{}eLfQ3#$k0ga}8dVw07 zC~_3xBSvAzEWTHJy91Q@zTa6?jBQ3p$(BFe$hl`Fr*2Wq> z^lhe?Cc0GP&CpP-SnsF!tMEslQs6)y6VnAJ=@RZZM&vAgo%7RjnRLFw_s@>#9uc!^HYE;|%_b_C; zr^lthWe_DN*>c1xY0X%Zy3V!inK%SIWO`g4(q)zNn`rE)$%^JXOLG3P$m*fACYfaCQSuu;HG$ZCYjw2@}{cidyZjd%vqp`l?yc1_t^b9v*N30IttP z585I;oi?G*>KhDu_|gumJ{M*TLeKsG%PI&Zfkz7U0VEon>1x)xvL+758-@czMf(p* zGV>xyF|j1R$aQnP9>*R%;X<>Ujg5`1$1C&FWQ}L=_^@$vi;B)pMBx6Z6KnNlPQCEL zaG3~;tXO>CZ}Z$+7d^GxRJ6w^nl2Og@A=5ql)?Tl1J;wKrj?WhrSn;z-!ere@>lpf z{YL|ye4le|VQ{;Z5BoUXxw8f_p6=VWz9Dbc>9_=%O$i0DMCPCme&;Op`Uvx}jj`WHS@BLXd5t z+!cvBd!;2EcGiggtW4=?2s#l^Oz1iSDm zP7z)9<9KatTO~Y3XHcbu9)ZLKMZD4yc1*)XD(@wX<#Y7+pKXx$*?g1j>Hk|f-r5La zsUgZrPEsPzLQnmPs!H!h9j)Pr9zZ*P%*)~R>p!)`n7wC#sTU|Viq|;8ZsUB%> z9vcg5mNdBgpPb*)iwG^~$AdBqsUD|dz9sY0zU?^?hg>YF#2)%XL3cDYH3ja(@6YlJ zKHY?L?ef02jt7CetcrNRpTOJ^(@17ST)An2$Uch@v#W2=3kj5aRU?Z>63B6}vFWnj z%U@6J-Fx~TlO74#eR_}EyM;snDHql|Xw$>!(W(j<7brO7K z?PJ@st)1Tu^W_AKszl}F_P#5hqkO1pDO6Fw9I`Q@1`9+GnN8$$HWmY^M!am)K_roI zqTbuyS+h@mHa@ntmTrkey)dHEl7S=t%5|<*!HH^#Z zbFs843TLBp!vur+-l|y8o2Wa&M9Jvg;iY4Nf1i9DdK2p$c+t?@90adFC#)eLrLw-^ zxlL*U24Y_f0*TI$+(Lz{BSC_cl?)w5$7dcPWf(KIZ`To$<8lk09%Ey=%p zQ9f|v%ciD*(5=h&EJpGoP6{kn@vj&cvYksyrT{++>{B&`4( zj9T@ZfeT>e1*&Fk+sx@ssdT-yVDc-8zuSw|p0iW2P^kKWn6<6KyeJUnE#SC@JxBf) z7mEPN4HE%j4Q=-Q9Z!Du? zvp=i2c2b)Yi5pb>0Q46gyV-s^Z_pQ}sv39>i zA{fvZJ&6m)ndx@}0&Q&}!5|lG?x@l9YM=SbnD(}|AC6_6$t`?r>{N#kykev_FYRB-o`uwj z!==CM#qqULaa?P*+4@=}+92)6jXZflk8|8};;)@}e&5Y+tM1q>a}&xgJd6 zKh{?GrtrF!7R>UMur#d_La>?A&p)oxVIjq7O(F4LAZQKlH^$DE zkNB<38=nE>h~atRJAQfL}*An4(uYsiXiqph))H-Q~~2~zGvH}C~c9zFvHn=`&e~W z95+N`P6Fy84_J)8KzI85KgcM)^yi4?Gu5CMH}f=t%w6>I-zC2MxVq z|Afb5=@niPiArc~A}O@r>y*+X^nEwWG1k4&5%W)e-NwGZzrU!4EWtbCO=<2xuwmJh z-uA#yh~i5(I|}CuAt3J-bWSj8)hLBm6ieMWHa7MPnq_WjH_)j2E*>Px!Zt$`*j3sp zVq;knAVZcF7(gNd^RNcyVN6z+FS;1GTxx81R^>tDuMR-&OH6#(vsTp#!%ussx(tag~}o~ z31OA5;=@xNj-jckA2H@qV??-q(xH%?F7%hCCa5Xpd{(cP-PHYV7DPfJ)VV+bD4MYk zkodo87mb)yQ=nIV^tl!U3;Knx)g2py$Vy9WA1UUkmBz;T__frT3do&LHkwkcfJ7(rDRt*6h!}5fJD|g5f6v{G6d;dxx&%ln!*Al z_E%>_4^KrK^cZ28_7-Vc#x*bN=x7Qi#GXC(s=x*in71!#?m^+?$6pYO)s^-d9d^9@ z4+gsU_}=jk2-pHEQB(9o!D!Xe2lGGIa&p9CRaZLHv{Z_Z+YXhq#MX^ca%risM={9K zr_~pnlSV}Y|2dt^)$iiBq+|UZ`G~W?28*{QAaz%0$w8G@In0hnmGC#4F5J87e23b; zK>b}hZSY>IaS4^{@CjjiC-v+4M_rz1f>7@%p{lKKyeOf&%4Iu1E3hA3W61l zcI9q3$h7j@TAeAiYlkkSS^71|ZTXUu&S?qFJ=YTaHa2GY>=jf^1_bb*LEzZ|xCNs> zu`mezBs9H%j}Z-1CLzQba5xQUcF#s(r%h3c9G)U#Y#=F8#9L@V!{Sj1EVwK8>`7Za zfW7pc00VxKasv#LnOG8hMVz+MX)a~c+#LF(I~|p_0u@4+Fe+uaNMqvcSt;lw*d~Km{wCD_pB4b#uV`(L zY6=VX{8jWRC3}f_Hk0FP(fU@VbR$0F^BQF-HmNINu{aZYC8e8m$rgoFEN$L?YlVyN zef?=)$@Fp3ATSM$M0R}~$^-YYt80hx5hXe91!AZVr6X6eFcyDLiW>|ZYXDZdaz|^R z%z+ozI5KU@t^$??KGK0QH77dw?$hmF&o|w4CT_?w`uGARELcE$i z%s3pZYL_BBSmizbLie0wnQ>9?(D3ld!x126;w-JG$Ro#Ift945Nc;DO-{X4TP^aEE zRr`Csx?NrCr>fs2Y_vy-oC@+~D9ih-;^%J}7D$48*Jri|dX2x1Wvcj=xwMsG znjq*XMCzr>%gQ*EV5-h(EG*Rj6^L0I^?=C&%*U6Z#NxF?2I+k9_;my<2{UUxD=XWi zMwr?hI!bKh)Gg|Mazj}7!iB&;x|s(-lNj_1^6!j=jG37kjhtX#>nDu-bBw$&o%=y0 z%yDY=4g-5)+xrzf5ZJ{5hZ6 z?{G{u_w8*im0CV5&j%m>W`)VV;_bE!lK{B#;<>N*El<#7cVzLe@W|yd=;4QG!cSY; zVl7p9^k@O`R=_KJW(frG1YH&;!$hvT!&TmMeIib$ZNZC02hXPCLC8EoCzP~%((n2{ z@b8Ya`bv(vnneaOJt6X{P8Z)$wM#LZfpQ*w_U*uppZP^c5@P4SC9(GPQIkocCJ6p> zXL1TE;qTn!sV5-smp&1zQ1g?Rs`3u^A99gvdgte#KOkWiGond=>jpj`Jw>{MNsmxV z&o2E^)?sJ(TO)(;S-w}jeaz!>`mcNZSe1oDzBl?#P?#1E^YVu3WX#|95J=WwdmUb= zsGHxT^5bbE=ZPt0{5*@#fXs92tp0-d_;{l@Dq__giE~=jfeUjpE71&x(=V@S7xf0X z%*>NofGj-Ss!Hiy4A*{&N>I|V=B35{J4wnNOJ4xZpot7uvW97q!D$nb7Df{K={Mu% zYep8M%+)WXz>ptbmF*qUb6J|2)VgU;_$p0wjGr0;=+FbsY{ ztc5MopF;+VXV(n)xPVK+^I19FuYUgWubupM zY7%P(=V1oK5o?l?b5*;W$FY#=I|;Wed#l=i`*+7zUM~d^=Yq1Uura*Go3I5#g;^ucB%P$d%a)`0R7^yu`uBl$mP$yfPI zHtjaVb6Gt#l0XnPgg*#GHlo?IMJOs|&+ldwN(#qmE)#{N;qyVfAwgq)DBc^os$voV z5XlV{#IAYxELN>8{Av2r((>cTsemt>Y)js$G!KKw2&UqTO8tkMf2Zclw?ZB=nd1w} zT+;w*imy5XK|BN?hto4MV72#9zbNmy=&mD$D2zgb_x^prMB^|1xGG^7hiqMVyHarB zz7JmfL~KlPHqND7Mm-V0l?XImiCx7gWqo@-@|!+I-|pQoQ_^v#>!P|wm$8jzRGd9` zi{4ktIGni)cCLEkI)2X_%@39pmKS$B)&s|ATHEJmJqErOtn`huc0YI3iEHZQJ^vj2 z^1htfXS8-Qq3`Dp>A>;&SVxJ})O4ZdK||}aaCcTlq*B&DFo5e}{o)Ja2T`f%kVjWh zHId%x?^ zDVTIEdw*`YvS1Po;sby#jZ)_4<_g}tfi{!U^Ha7xiSO^tyUs=Cw<<2llosjdt6lQm zo?rKTKLGL-IIIPm1}jW!roE^99j@V<1o{?PeJOhz8~E&D_~8NExdOP15*{G1_K|Jh zeY2uo7|eAw(c0PB*}-9^5-8@WDO>h4uH5nv<9KTKx7s*=o2roxyMyt!k{2SN#B{Q< zvVv|#hdm4phP9%DUc|z7dJuyCsc|qz6vz$2W-9RH3iz$vz1HWFAlkLHn~pTX--`zW zlwLCNG7KU;P>Pg82NQHSg2w3%yGpC-?CSDzXXlJv#^y_STFeVGqJXat#r$QH2M;Hw+aqIP(Z>MWUK!0}02$)@vND~I z+zNOVZ5SW`<5ii}Ktl6YO+}GC;ZS5hPoh8+3N87-#_esNHs;75gJQj zEcr+=c9N~J%a##Cl6{M$kbQ~9TF5dXB4Lmak|v49PWBL@B3a8$_`Q9f=Q(~y>c~H3 zX0H3buj_oD=j#la5U;&G^LM9d@!@x~|9ffBLr~->J;}GqR7=CY>TL}SsUuRF4Utyr zM;@V62?wLx+|D*F%8wOGdstHM{+Wv?iJNCu`d2?QqkV#$!#(A0hh>Lk0s<()am`aT zO}?M@iizv0 zORu~^B%;w3!8GV@)zN0;T8wUDM`Kh8UIoh0y!0VkXv7Lpi&U}ePsc%H1GUr2VfsAv0_Iq3 z6odov^QYd0gKx3KxDcRTK=ca~|0TS|t8Nrqd|Asap%y%MQYBz*dfPKNyNX(wy}tK$ zJt!dH-;kqn#hW*2_U4HKv^3PmeH55tS6h#Cddc;zyz78m`F2Y#_B#ggSFzO8HB&#G z1ltEC2pKv_si7d32O~a!j)#J#1V7vTH?LkH5O2@i&!&(tO-4qKjaWHs;Ya~y+V65V zrP3js24-3&KHo)%zy6;qBR#!h0E>lV0BqlWuhRa`Nb2VAYi5!+9^&j`RZZX|4^>9) z)fc3t2}OfxX)pl=Ps!a*92ZEMh<(L#aqPRZB`#qzb9~d$Id9VPk5ABoEzf52cxO2s z3ZXW0)b$(}dp9o~*nrV+aG9dfo`oOg(3VDVU{ykS=|U~}HVXn~Gkp>T?)_~6Nqu~? zr^c8Ng5ZdHgd|5bhp_yUW>7IvQNcUdU`-FA0fEgBg7qc9Od1Yw;G4Ex)#;aiP>V#c zs?f2js2&t#Sd@=vxWqd;=RRs#`%_IjCDxvBSDizRR3goN(mXBwn%tXLZz_g@wpV@3 zX6jEcpZWqlsjs<8hV{2)I9G_}d;&{j+K*5IQ(6p5t*r)cspl4b=I(}l|HO=CeY;FFqCmNMQjVSO2um2J z16o)|_80T=JL{@AKQEX_y(65myYOCA{ZTV-nqLV=le6KGdjD0c*0Y1>pM@5Z|1_uB zJmw3FM9`u1Tr3Kb7nS#J-+JY{^x?2Rx9ydc^2-8?I?|Eqx*tOBvk3T})4>T{quw2n z5B{~pheg(-`N)aTR@^*?#f}R49{z8RPYq%SsCQz4hA3v$z8YiIFUG7E4r5=xl*_dI z?H-t4n+$E3v@Vt=lt_tLzPYpeZz!sTb|QE-+%0>2QI@mgXI@O|d8@j;_lFHK6(;^6 z=}<-jh-?PlNvzoUYwzDxRCuktQH4Y-soLT5e{F&Rh05rL<+R+cFqwPQ&NxU)*4)tHu(Z7fedYVbiC16ht8Oopc1_K zU^EXxC{Xos!YGsH1r3J|s>Hd>0?VuB&dqMJ6W4?VAU`&jr4JR@fU{kKOKsM8tK+6GC6GwWw#!j4T~5-3Nr8Kh&) z{4kGkU)qo7=k~{GCIyI!G_Kf!_?3Mp$LDW*VSbfN)mZR$VB1>%RV#Qf^E`~iZ8i6WeJHzM6ecUWACb>#}nV?3piIxLP_m zxA6}nuG?Qz0g(mp4rY2Zb`k72(9>N|lMAoNz1_v9mzu&(|;(AV^ASr#NA(9-0$>yy={(EHLdv%I%V2r-52>QQ$`X>I3Gh z79CUh$~%P`6>DHTsvh@qb#MTX$c9bc6E=JII6nIDzuIJ>{v6Z?y_mndt+yvM&#>2~ zk33vE?xPd+BUUUXK*G82iKBs1zjMdey7gbV7tUsFuDDiIP@R=nJ92;6&-i#hK=@Jh zORTO4hvqs}j9oJ~-{~0NP!4B4xu0hV-Ysok*;YpfZTkeR)8e?aZ3wH5!3%I2xRQ14 z`gPgJKMbJ=EIm36pPHI_lAWD1?vNzxwNyB5q0ajtFU$Jcn!26mga8`x5qD7okBG%} z%7chPu$Osw`r_D^FOa0#2^uHHfDI8M3}ii+F2>@pi2_FuXd@VWcrH(MfF%-&WRgj( z}b=7ZYcYL!p zxE6WO*z+ooRwPTQ3LJ6gEL`1URS7q3lF_ydXr2Riq_~wV&E>Sd_rr2KENyq1O zKn%oB=_&_67vJbi3B3JW>Hm5>BX0=7`eQH=eWqHuH-m?afIH z)5Tu#eOixE^t|x=!qR`xs}fau>0^ZB$b9@qO%8(>4;W-<37jvU6P;Nu*k+V3 z@GKN7zPsw0H)@rHH-8MDa`P)mOV1akQ(N_iWnpq@wfjSN`l*6EdCuT(XxrTDv=^P` zu5H-H0;~dtN$9)wtX6HNL4IS#TY<($&m)J#PmquXC^Xjr!ojqspU*VLFyk6Af@;Zl zDGfrX*ZDRH*P+8%(!(KUF~E;R4pGttNq-I8h1 z_F((FSkNEF_CL4Y@YwtPxFt1n=fbKV+jF-s@`t4dOn+An>@5`qFD`w1H9i{vv$c&m z*R0K6kD%Gr!SM{JOxgmZ@6JcDfBmE3JLRH;2motJ{yHPq^Y`yxaJuIjISLU3v5#n& zRSd7@+S;1U<4+M+@G$P7(0{hY+bKobVqXm$f6$Pe%!YjeF-X%QV4X;i-8{hY48AH6 zEJSu-)&azKh}OewrOt1aLTbds;Rc8f>!Y6SPbv~>ST~%|;#|JF< zfwwJE<6np4vETw-b(!5QIed1Vr}JDpNP~sl#s1gzh4|GC`;mOce)LDtagD8WQPv61 zwPR9D-(PN=I`hS!$Cd%y638;qOVj~N3yZFDozjs5htmpkSy3VTlI-!Bj4_NdF6|K{P)i$5tEmQi9GkX6>CziQQ3nqcR2B% z647Gli=W9&p^A!Yj556Rq+9o!C0H8F1)WP?zN~{BPqNNho><`frSB-OD(f&x%Ge29 z$oza}NnD9{z9fLV&orCm=4dABk;(BBm{SK-@VsG4e44y}j-ZV~)CDxyj9jlJ%DKjo z9{-f;^5Xd`RS8Y)&gU-wHa0F9z-5fRuemcjHLoa^HWM)|RtLF_b`q!1rj#cW@<4Y} z0H;gk3uX~YD@mC4$$E35$4LS7lFRa$4(8>)lX&Xz?Z^Eh^Yd}xK4X4$iG=t6Qr}BG zJ${wv9P@()hx}0&nK*k1m*O&-d}`qr(UP5_z3plb%UYu!kc9Z^2-ZFD?bXS1$D6EP z$@1F-3&Y9$O*^^MTn$+I5V9&>4}Nhw-@A7&DCm8+6Xp^GJa|DU`gDTD_Uq_qoYBdX z`t-b5!oh3`M4$jJdc%P`_Y4ynS3xQ+DLHlew9G?u*E2~i0|Nsyz4;}TSeufA*@nWu zSGP(ms`r(q)!zh%wXq@*G>0vsp!M6WS3a+lVSyJ7keDQO_ZK+P6;dTGu~E2UCCk8t znYO)=(w%UlASaf8eW^<8fAg*0t#@m(f4%AB=y!&aOi??CWu?Q&zz0yUu&}@_@3j>R ziaO&oi!FCO;`Qr0K6igk3`sg(_nm01w;spja#}ZIBqCujlG}2#nipz8 z^UzDN*R5V~R~%OK+M0{V7n4fwC~t2oH$2AYhiKJda-d&1B3ve}X)DbB%jcxC^Uo2G z7zT(0jyMe*O+cHD1aXkda3;u4vhnm({dNOfD%K>X1cK_*lj{qCuiyCg5N(;bblVv| zBpy`3w^K-zkL@8e4BdG~kDKLxt=aIS`m#mOD~UH1Is~JSO3wnj>7beIP4wT|HlH=- zsind}Z^?I&$~-tQp!6qdx+_cBNA9a+JPAkE!}rNw;ErEg zUx&Ac6WoHM=mY^z+Lv2jl6%Y~y0 zNw2yEzBdX*70F%U^TeCyj*X5gZB!_49|w>NbcgR>`9l4L>2vFyJ3Ew8uxMf%5@=aY{ZvN;d;9pe>k1bIA3Y59g{|9;svO4l33BoH=?*#=+C`4>;0GEnJx& z91ygD#mxH|=YV~|PuJGA4mocCc}UXnVo^XRh(dlweOy>@k1dC)=ZA$N2uP`?*@Di7 zkUUXF+DD4eF4ZlsUUdBrwXeIv(PbJI`o;xV%&`DAuT56Oo_BQI<~A+2#O#d#(%vK__y!V^wSue zSrZ?i({2bE7eu$B*&-+`h)V(YNi#K{Q1;L^zauCTWKH(?9k6HHzJT z@$kykRT2Ni7ob4hbU;OXOJ-GxRb@>IP&jR104kq;OuDScDQ>2x7x(78x|AG?$@*tP zXuniB!_F8(Vm%%qlEX_VxIriI<4=2w}y^skG=Jt7m^GHqTZ2bS|TrmmnW7`*#QbeV?z{E*EkK^0MX06`Tzrr z!qJFac22Q;*ns`Kanp(|;)?=-L{d@(-O-TXP&I(yv_;m(XkfLCbu1IV^pRbb=G^*I zefOwbv$GammcDDdJBRriq0T<$WR`CEO76CgAnVD_tTqWpCay_TZl$v!d242&eqn8l zCdV_>_(Pri{QP6}l%b&f@5NqP zvQ4z@e~a7sNhB(bBZMNu83%KbK;QWW2-?9ne|!})_355F15v%d0U(^=;eeyp$;*Kj zswTu=C5#PRJAE#93IBS7|8{BQ8lCSI3;fAg8Z?!>&7A7!utoKjmE<@ZL!xhWDdq#u zg$S1N_m;h2bZ2JT2{y+oHdSss#l>H1yz z>;VL~mV(^fgM#;#;BbTcy_{N_aUoC!zj(?h6Ug1EXjRcuqtCz_do6@XqgqmAh^M2yc?{_HWkFVvA2(M&~T<4pK)4i3I ztDim{oMz&ZiOjT}?y)M8CI9%|l6Hjm7~eV=;bIsZ8rmt%<$eBj)&9P6%^;(`AQnph zKF6lS9qSS|PyxSe`a(V2MV-gb!(kMi)F zfXz*CQz|t-j*D;lo|!ohmbQYj-kVoN%st&C$c-3BM@Il@K*h5Ntm<3$NeFa34rDZh zUSuqRmnMv*Aom5qeqw_j-jJ;u?lpykUeS)Qt3p>>o?xfK*I$+v7iV7Z-@THxwX*d+ z4(bPjM9=k zeQ>?{|GWVFB5pIw*Eb6HVKYfHX8123ODKtaB;@o7Be)?)A%XRw#?;$#ConJ&-XU-AwUwFP zfnf~4B#`##3I@STH@3Aj`~Xsa9biueyVCz@qW2TWaL+Nrr6H0mr6uqY9Z1g*NfNvC z#KD}nIhD0Dv<_{H1};8V_p+Av|E4Rg*? zLQ?XQ<_GP>xj7(#bo#>)0334M+}s5^b>qx@0)_lN5{DeyBI#Y)3v*7}mG^g|&b1|)$Kf)>5&Z?qhu8>0Q8>BI z-^r&(&3EGY%-V1owtD6%hV;T3&z%)AHw3hMp1-ZAsI8#7UXeLMDA!?9ApZbe_$Xg& z(|7OMn@rN_aSlZZLhSg_0j8vI7t+s(32P}O2Kq7@2E+h!K-CpseMg76HzYc{y7HVW zja&y@R{sds-J9*qYfDWOrPc;`xlVf;=LOaEI{Rp4bE@ZPA)*A^>~&w?ZR@@5Bx+)RcNGpwRz5FM9ik}E@cv)4jfaN;RK~gk9?g_Vna)NfDoslr zK{|?82dwE($jw+zHPkVj#$up(O32$rc>n~dA)+d@6N!i9(=oP325#N{zBLcYV`#ml zu1ub3lOQ?aI_kD}7BA=b>ibO9OrKx%8!euc@>`72NkQVZ*N?CBDEY~qdvQzjv#^oi zk4*vHq@kcvqaq2dfcxToTgJ1M@s&W{Z>fe6mDP6pS-l|fui-`xBn>P-Jzn$2Z}a8r zd%Jr+JHv4pEV?t}!Ya?+8Rc;|XjAY^e1lTEZz|%9G|CDI!?U#_&RC^zf(~U(7dW5kO5K(P@{>A9tD|>59>H zyIgheYpCew|9Y<0ZEWs+^OE%#ck&@hQiB8wi4vkIAq66&#zr?LrvE-+2&>Tj0e$X+ zvzNM^q>djyJ{GWiIRp$;dHVTY-)XDh<#VqlNOvT**x8)OM+N8|xx=K1hsfrQOLhPS z5`maoE_VZ(fYnKQf}2`e`qtSqA9M9QfkJpxKytb-%!+?*fK=5^Cgbr0I&SXc2&wdv zf54S3ptsi-WKzIB~~Z!G7P*rT8WL@Z>p+Jhk3|6G02oJ5y5lYz8;WE zEzlsuvzR*Q_zTfX`f%EofiNDTdmM#U+fbK|4R+$O&(vn8Iy zmUyvH4=Il&}paZu15WW8>uM%#g5KPr$iRzYSASUr3FZd42own8+RfJ2M{P9ZQgws19R!*&I} zhe(BuyUb+?dUc*-dL_gEs`sXt$9$JpKR)dB`#Zk#d)(ZdS{MALDUxf|FTa0Y+8=rJ z*=u4ZyDcJ0SDOAKgGlrwgj@l*-QEuOIK{5urSQenyt;s&tu3EEtEBN{PktmunESjrPQP>k(Mgm1X|FW0y3=yqMN zI#Q8`u{CEm6c`ATqZJrow0iHzaSL_Qp@5WlA^~1siBf=6-K$%FdXh~mq%+yo6C@8~ z*+P(jTu_O{;YFAT2Y*1@d$d}hk$C#28p+@dkG=cu%Kxea%i|w5VyNpZ$t3bM(7B)3 zn?pg?w{O-zCn$+}F`m=`r^?}Eoy+*})N;|m!NJaqi`Po8M%_{5IL&nY(DtR(s=;*V zC+aGf>H;kQBhYSrX+R>I@6aM+lyLN`I@vTb*|je{&TsU|{btIyOdn;%^}ZpEqM9T;x2^+1560CIb3HJH7vq-%WyOUSC_p!CX9|q~}l`bXT z;jxGQgeW*N{0_uC)U>duWwEU^ov-#|WL&1mVX@~uBjdQQ5a4Er5LwFMV_2lZc>kT4 zEfa6$fSvgvlq68WGQ!LK4#~BZ!#t*XJgA6R@@{R|^?X@w_ao7J`-QwP?RyLKyYZT3 z-m)1XqIs z^?Q`OYg5s^Gcl`7G=IPMSGP-fr~OKJ{do>T4+>k6+-y!XklTK+x5UGInBP@20h-q* zxl*tDcKUZksv+&o@hSrJ0L4CtBOy!)@vq-*74*Bn)dsq*CW(9upqG*-)ywuBeTr8E2y!81NiN%XdX`)fuHxOU4n zA5!{%PfkLZd5yXl=wWO79enH1A~@+JCDJxoAO6$5bj0m-h8IXrY8yCgBSt+Uj&Fd! zIPxJK?D+)n=qMaL@Mq~B1U#5DunBx`H~mj$@vA#yA># zlCgTmT|U#G=rS#=?umX+%MaZ%jGy#mio2$7H?63yx=#V}TNgyKhJ_etI&U zYXlsaaT*oGLO~fxp<`BK_twL`3^H%7za6P{^;sC>JvqC2r)u0F3I7v`&!K!f!j{mO zx2jXoTxq^ox0=g*`l6qr)|P!wxXAqjBH}DfCLD;O0bQs1kF%@LlP$$f-&q;pnYj* zsE6`Bah;77N2{5RJDRzwMtVbru|bNbYa693GF=AV-46OrJ^m`(S+g zS>#5c0kv;IhPL_au7l#~eCLBMnH>w`*LLQ|cQb#ftCLn7_gec;UJnYA$b8|P2m=l! zN+V|V2!cW3BZWcyAlR0GRH>hT$>0@E?;AgK5VmJbZw?HkkUG1>z+d+bbLt8Kv2yYo z23<%YA*>tpxYf)oEQ(A-_LF%eCvgnKuYh}g;*7qy7i@}vu2j27-S$%6_HvVhVKNAv z-L?K}o7=k92FY27(aT@IkjEUk|PtRG7y zPb_5{m#CpyeO)G2Cg;MAf@3>XUO47~FOHUycisG+S&8XBN??6FcrQ+N49;_Zi%Nt1 z6i-KB@IUIqx2aa8LvBP@K@myDGT7091`k4<2^&4(r!7w7h>^O9$+O^2qD6^Gq5v+# z@4CBt$@m+uih*MNXtc#s{rpuw0z;%PoOfT0uSaxQ_P+wrk!tmj18$r_V4#o1L3+9N z)`Xh*7CiPGDqyFknajsVpTmF+&?^C#py<|#96*OtL|DR~J`Mg|x7WW%b}tPWkieJYUO9cmSNZ(aZwsF1FmNiKz+-Z;vp8Qo)=TURH$3k4$%PlQgMSG@bPH7~BC zN!vwN+5WICI)~?>rvLVKZw?S5cF1IS1GqOTE1RH!U~o3y`J)@&28lMr3el@zS#mcp zmkiZe6Hu*i~!VTcr`a34anIG^3ZM8=yc>sa!Uai{{i(^m< zv&EaRe)`|V&~fh93HTNU(;z543?;#X;RgmNnPhp|oAUC>jM??=c7P8W?}rfB(H*dF z>FU^ro)5mfzD>^B>WFj2s{>bD_wDQfJWUD{qZ z&%f>MbyNHgv7MD^<(-<;#nSWX_s?uLn>FY>e&Ew>hxSJXsC4?hjpF0xM3|mAR}RxKQ96ySqF6*48ObaBqbb7^ zt7h;@D|YPCvnC)Ogh*X>?WcHkrW!xq?A+}f{V9m)*tvg>POAc+t5(>%u=4hztEK33 zD`yi|X%*Of-Cd@|nbxkhOLk>k@Bw0&VwY`f=LX9C zl48X-cV=>MqQ9f0bPSD54-1BbI4{Mm0x-h42&T{utoQnVGehM@yc+OsRC~ zO%&x@uN?YowUQ-dtMq3fd}bsgLP1DQnc>05wuR=y1*XHYFU11y ztXm=fTq%9`&iD39(KGhV;jDJNzrC(AF+T`zXlTsyVqBj09!YUmJbly6-Lzb%b`+k$ zcw$PZ7M)O-h>7|^RjFv<97^ObK@I3T60h)zZx%RTH2B*{oSP|C*$;x!bj_c14aClO z9&0)v7&Vz`%M)m%_w$IfkhYugWv)@vy{Xk&s9T8q`$-obf5Cn?UF{u%dmV%fF(>a4 z3!g`Y`!cp#R$93x4Npus-H|Kk?;)PM+xggjCQ+wkU?pL=a+hjx7Rn~5zMJHv{HYh4 zua?wfiEY1epOv>NgE?EB;%u=z(FX4VW?c6sQZF&#wJO@T)sTKnykUGY?T11{V$*;_ z0L15c?j2Q#17_ytbWjeb ziy!lMz4_!tZnu-8;~APSj2fU78L+amuGhDTi2{5Kh`%ReHIwQmUX8jtRNgQCy7|j= z!poNYA+o)trneeCfxQdL_#c4GJ-gR2KFqaH{PN=cgBHhdPLCWarF+RGZ-^;&+KERR zhw&*lgUbic32MV;hy$ zBEcnmc{$)N+1nEG?KemCj_)Ov_> zT++@RD>QNOc(=JA*`<_ZlK9bJ@!a@Y;<~}>3mu%QCT9IkuPH|fg3JuA=PJnY(V~Tg zX0DWnrvU?8`Gdu4s~zx<`8RbM{ycjafqmPk9yKy@0sE_CCB5TCON+cL=flClfecVe za{FB(FyJxSKPS@RrF0etQQ>GPuc|CVl*E1z%r$ZKn} z!rJEYWKF><xd^a(T}Q~$+-2MwmReB7OQpZamzP@fS``J!{K#7BWj%yZ8u?00Ps z0eBaib7EXm63_0^17IRRSu@1p7UmZtQ5lky9Fg^uR6s6Y$UKccSlX@;Wy=aQL9{iV z5cQ$G`z#u$O`*t04(K#}D5#zIqEPzKhg)(_*?XxIyWivbu~V;5NA+Mg#}vxfTP*9J zIpmPHyfHy5v5@T%4O|#7+&H>>>?sdwjnf~VI(@%K5>$bdCwO8^P#&lnhYMT=;tOx?A0=BjF+x76bn z4Q?iM_O7SUKkx1S>i!)gMipR*wmGVWJeZJ()u3x8wz&~Z;tRA`(QzWr4ULWejxEm5 z!xQy|bF1Am%hD>Yj!vLNbdn_&j2`m>nH!Q?u&K3iBGevsZebCn~ryH}TVpBp;PL zlUN{JLDtXb;!1};9_L}_YSoRjFcn_DMqxgNNA!klScF}PmrP5KNJ7oM<$<1_eF{CO z;Go78I`qy6iwV)tTE)_Q8xp?PBZVg|CljAPdE1B~Nm>>;%x||9`7DUeGp|jt`*&U3 zyHi5GIqyFIa4pv<_WcvGpJ0*c@PqBmv4tCgP(n)9a?UJAt6Ui7I|zxLg##{-AOJtpy65o(O2i8pVTdnM|VP{;?MS zwKDA7p}v9DOIZwN`0y$-{hAqd@7Ke<(JV^-vg6ZTuHf$;FK;T1UHn=iT@jVV&ApIn zuN|#X*R~C8!92k1&usRO~qF|z@ z`Q7=^EpbKP*ELU0+Ftdf!$ljgw27N1dXJ2{PMTlYac8xpV7}$y0^8`(oquk zfO+w%NOH}IGnD>l5=zVD(o&SR32TTNojrus91;pBYH~T8t4Gjmgizx;pULW=_ODi5KYz81v+iBr3d8hVFx+bQ^zA$6DMBr9G4yWce%drsygFdZQJd6e*D zg)X^8G5x1%&M@l=6Tgzdc}XsUJs3wCB1vr4Q;J<6lnS(djk-tp1kVNVr()?99zZ3m=cye*CBVG*k6q7< zk4W5W(xy}S-o_vPC@0YJh_n9VTf3R*J}1(HzR&J$=IN%I+_~u$sCeoobCpI?sP0YD zdtzZ9Wwo8alH|J>o+|9A@Ki{qkRT$WzzO~rAA|PJ_bWYZINBdyH&Mw1HRO*=o1jW> zMr`WmGxBbHpwSD6=p8advT7bmh9Bj9CSTZ!Do|dm+8J9 zCu^nbzi=nTzSci|WF&ou>|Q&HEeo%|bw}=R_aLR;FZadsc1zYzzKTb1&@=T|C|OF| z(VyDl+vBn-_#|C+LDBEERg1{Ur%JWHF7CF=MwL^Eed3G>kr?hl62`jW__rA;WyOKT zb&Gk8yu|y4k!JM2+l19{8e!;ztnHC4W~owK9scVJ*Xn|D2WJDPdb2_qdv6Hfg8T3(5p&Y%twgZumc zfuHF8FDf&iZx;e})3cN12pVDdw2Y)ZDWUpx@n@G}pxf^u#|N{k*DhrFjIG@qb$6sv ziN#;MePGagi7oQMZ>=F4rz*Fs#U`q!;C zhBle?xK!S56C0P1kodD2yfGE^J^%B@I(1Pt=4aS+yDq|7#hy*#Py!NJPmeKX5U0Em zuQL=DTJ;P6974}AY(o--L_vx@I9@(V3~(Pn5F*aO6NwUS0h^nNapXTu@I4npo$INp zZ|vBkd?c+JOL_0PjRby8t3T0Ki%VY?0v$p-F-`u5QdbYmsrlE<%ZSmfGR#AMu9YM6 zVTOUX8r6VUzA-=>p0d9At?u8{1x?P&S$+=At3-n=1qDTkM_UX3Cb=<&1QXtD<7bMB zCOielHCVTm@~KKOaHV2r@S(%ySG;WCcLAypI6E6j+_#oos z$y6wgf$nB*wh4KFO#$s0VO`zmsfQoiMyaLPBR;!VJ32VNTR%FN!FB2sH~`&!hIM0N z+S+vQJ-vQwxAW$S5!cGl5AO#T#eYzP0DP#RJ=xt|rjz#~tTn{CVNOOs-!tR8-nN(G^NU86Lzln4n`TJ25dK zWBx`ncZPvvYJ0*q$1xO_^0~mtzoN3d+_)qe;<&}qBE=#Umaz49cSgkhbH&jNBwmUy zdk6_C*?e!>+rE}}FF7EfcH1*iAY#WrQAuV%l%0_)-SzBQ-S6K!bn?o}-<*DDHhVPU zx$(Ke@&eva;f%`n?`vv?{!2Z3;6S)i*SVoK7-2A$mgQ)w~n_bv!Q)v#lV zkGaIuSNSIHVlU_u<1fdCsNlT=18qG$%dB`_4n9bbYBMI7ez1~_%Msqlj;5Jqd9i*9 z55H6)Df!^I@=wc^u#=V}Zt>?!#TXW*GN$ew&mK^4jS~^yMum~gT))djVIPn}id(Td zP7$~+srcyRzt&5)e|?^?ZPGVsOJ1(>sDmo%E%WOB>-W63e4$S+wJq=Vf0uhv?<&u4 zpycr9>D6tIp`)g68^0uIuy?u@m)<>mNaJ+S#>AQ9bH~1(O`eA?(!Z(ie$c#&_C6c{ z2`cMi&Lisle4T>A08^sKji>A8;W45`SQH(f8A4YFAbX6^=Apyx$5*v?v|C!MI=CB_WA05$Wd#EQi8M->lX8 z*6Z=CCko~wsZVS#8`AY9=K&1dUYv9s*ORTZT1Zj2vl@!-_ybL=i-cRZte0fRcB>LJ zB<<=^r-P<$jr;h_eO2;z@C&+k+%UF`^v%noo;}gV*6vP#okcgH$I1no&Y?G=(Nj@T zao@)Z^{5VqLKM5$*{7P$(As{oU?~vv*vE3f{&Bx@(!pE?8jau41NELAnvB3l<9ahu zptA<0_9U+!fFxjPFTawnpWOD-FVOe7)%cgM&~iq!v}|8?3$O_oT=xFtspe!N#jLap zVd2~n*PB(cI(d^D8)hXkm@v-Qt%rcqam3`H3P=?2m4HA;A<(PbXnWL=G0m50(;JQu z19>v#>$asC{d`Y{)#OHu*YSFUHBuBi?_D&yAf>6vHc@O-_Qm}!Bn#x%A;ra{9N-UythOm1z_`uh65efzL< z>r~Y%h8yx{FZasns~F*-xby1OLFUr|5)8rLb=^f-zgMnShSst zwPk_xU%f|ec62)|h04zb-wuApO?V(u!PrYJ{(dP%AgYp`Rmanatu3PUOY@qsiMk*p zKmh>&)!!2nH%8U=tCzAL{T!O?`S{}pzQ&RsfexMK%^^XL9vr;+;uBE}Pje}VYztI3 z(L$IN!8`J?9Xg-^U3T~GU6>v4{djQv)RXk|gI@yyqw(JMNJ`xfp7i9B9V}sY4|uq5GX!g_>+WWjA1ZI=Kb08t=Ayy z-89!Y7{+~9`oix6+)bT;NJdtNAThT0Lpfw*iOx^rrMR4geGTlu!3(L<&z}vsoBD6# zAcbd&a`0e+8_7XclNaaU6TlY3|AIhd9{d$vTwJVf#20_m`N=URCZRkmf?GK#z&e{K z!dAPp_Ivp67qi|+=GUE>nVFi5Vg-y?9L>kg1n9A9*n>=}aDrd)J9UIA@ZXO@g{$td zZt0m%gD0cTpp69JZ0!{PZ?dCKu1aXm-aTYH4asDcP_LTa;_FjcJi?T}}BKiSwn zA5+Oe^?We@W=MhuW04KjYVnQ&(EU8BW!LA1ByqTb`MW04m;If8Z9bAH!Z`trk(UlY zSY?pJmD3~~@aHAvYN?Ys9tU(fPnATS&2uR;d>Z7v_J_KSmpYFZ3*0=GK3^#;Gw*#i z+Rd0$A!^VY1Z5+Ai}nKooeB=OXva+=XB%>r1HR?M?`LtV>{zpWvDz8+Qr~{vtsVW+ zk+bYYSFYqQZqj78soq|9HZm7?JA&%cJ=vR5`VX(!ofFPx2|LJ3A8w7e4hkyUU+mB* zO^3ZSjrpQx2l_RU$db}c6Ly1X&WCgRurs*ivMmq{LGhHQN`b@jvJw(uP`pc`=oHYt zpaKd_6oMuj>n|CM-s!#k$#_z5T`B!K(ah4)1X@|x@G9cGDamGrhOA#q82gP)0>5oD zcj|RuKLeusSprR~dax>fO}WOy$<9z%R5bI*lZsmz_?$4Nd10~NFlkXPYC$A^t-4umT!^`JZ$X`*N?5oc^26(hYRq?p${sV~bH)Dx zYd4X6ZMUZo2)_Hq021s^+k`pq;p20fjkjw8<|_wfpz*Bhui^>xaku8ef&zw?%XYE- zD$t)%1CmBXgc6UxVei5XO+4FpPGu; zBlr%qt3FmW>New2AK=YdzxTiJYC_D>PxL^wRh6Kj(2TD~sH>}&(OTOx8yj|atq~|_ z9l=RRWUx-US5v!*t}>b#UNK&62a=y{E!|qUGGKj5-jRetnBmdtDhJa9+qMcq%|-I~ zE*)(A5w&AbX)(&>{spox7iE2hx1rbX`dWD^$M<*Zs;SMW5S9dKG}ey?(LBxM;!mAh znTaqigW9j}jrSi#elTKP-`+_`Kodr5eHMXex?KAHcUb1Mhuh1mtv`e6vZi-pd%-RL zi8zaOEs%HeN)g)`7j!XuhN_DR@W(o|wq_qMl{kB%!7=FK@upA7&eyfr%RXh)YA z`_Tw^5qJ|iEJSz@L5p-VFeKl-6W!m{eEHwXMyOcaVnmQ25PiQ#Pwbvu(v=>N47iz^dvdBOmKTOy0WL z=fwBJtwg=Cu&_|=*=IMIC@uWHGG_x8)jcDVPGoMMgo6}w8} z?l8jm46fX2b-Ws~T%8c}$%a+^jKNcQpnsszXuq7k1J&vMTzMO@1Zu{vun7oY5e&47 z*a}sNuCeXn5f8ER=Z+scCe4*ga{3(cAv+RD<}m!meUO1coxzCa#R??Z`|9TOxjjou zU#`Ai0baB|38}Qv8!XDI6QRbZjkPuW5W|3wj(o>#$4_9g8W@m4cYOPX;Kf{0S_kbG zh!WZ?>s>mvs}nbpRi0z#0yXTK@!HSqN-l5jbgahdSLe3=v?(+b1=}}033mu@USILL z_99{K?l$eqlveL_(2aXH+}zp~dfh#$-lp@%`6V{GGR_|Qy0nC<&^*vjl<$Hau~$k2 z|4Bv_<&JP>Y?z1$lC%FolRkIw8rf0bYWd&ZYyb80h>Jm!8@qwq{?wq{?svZ_(+}h0 z^ES(w$rPYY(F;SWiJEG4hCe#&0hwH5Qzj>68Do1^)Hx-!&E9n$PIo|JKTlmr%)B7R z#K#|g?`f+!r=R)nz<4bqyWD2D(CLKXkSJ0_AA-du&aCoS*HL;wzA;6_abKA|P>>DqRtepd~YwJP=M+{-rRAX*W3>jT#> z2CiTvQ=b+4xslv34=CPC(xAQ3Y z*==toxuzEtpFT3#%;8#GiKKB}`EM}N}RHy(x6H z09a2`Gkt&vaR7QikBK0@u|r=rq*eGi;RSpNvp@hI0KPpCQaRwCHGQvi@B*OSYe&zs z$DF)&r@L9}VtlSu>4W>73I_>n*rTD+Ax|TspBvS$`eo{uR=g6wE|N-XqGiUYkj#st zp!^T9DvCI0h=9(nBft~%%>9ftW zLL9^NBXJ6Xh29A%U*UM%@!98ZAH*fy-S1HPpKVI&0;S|mjcLHDtJS@~eK-kXQF4n) zE%pCn>Ad5q{@?$9tP;wWLO4-KS!HIVBdcWZnVCaEl59~{WM+F?l^wFT>~)eHdxz}p z;26Kl=l8wc{86{ux}EWQKCkO~T-Wuu$A8g_wd$oOQ{?>LImvz}zgE9~^08D4r4-q; zXD?yAJu+B2nh0gJThG1E4$=-DKuVRVU2v-0nq`&T$zVNc7IPh@|6DhHv5=lt*CS!q z&_b7)~16L)cO@4^I<7YhginD(Si` zN|soSKDGn_)~3`awXmcruXa~Z@PFxcpp6WHK$p<6oyckma40pEx0Sd51`eF>eS(s* z@V!FB{>eqkNIw7`b-fmUenRjGk+9)GvJ#cx4tq~ZEbtXlR=lB zT=BWNxdsZ1`~SO&2C)j5EeSnV0*VlTO10Is%&G3OeRGa&=VDx*d66qAB67LSF<<*S zQtgp{2?`~r*~lo14~mkb+!0;mb_it!u z=${bgzVrUZbWu^?t%92SiiRl*WOfvU3RCxq*RsSAZ0a=f*egK59b3q0Vh-eodd5;) zwTmGCUVtp`l5;8(Of(B-J#%v|seWno{LOc2xt0%JhpHm0HHY`=eK=~3t966pJc2H5vslrMO~ zIO$VKmw)(4{Db<`OB7n`HQNtsYZe|pl|i6XWe{`-(g;!tLK4cZu3YTMql_Shihy6= z{7S>(sr%gPD=KW-LxmqrFX*D5hrpvIw9EiS?HHi}m7|qatJt8;U6`zo8@`&sOr@q4 z@$K{Od~edF8Hw7kTdD~-xnUGz^Y#DU{6W}U_{e|AX7@|{6=V0m4U~H+e%!%Jr0ZyZ zzZqD&Z)g5)D&>zY?iP5R#H_x!rHEwGQBXv&XnH&MIX%ELRw$fgxJ|9GPF2)Q)%BH`_oF-e>U+RThQ?Dm~IPX(M) zte2N_^HoBIult5PmR=?DaSVHhkd2*FOrp3%NzG0TVAIU!Sev^PX1N0en!#YCp%!z| z*M)%~D1FM(?BsFbAk(#Lk5J2oq{f8-4ubXSDm!!FDPCS5z$}HMfW_~?v59V z@f~Sb@XV;Kn;5aVyR67;@PjFrX&Jpdib*8?^sKUh+3+ta?pL5~%E4V6Gh?F|??uh` zm?XV7OW9xV)NC{vRo_{8ZScV9;eQQe`ni|bMxt)2KqI?M#MI8i4!5>&@!}xW@P|-R z@$s@?1Y3j};sOt0cSRlc8Vk!R)VO<+#@U($mGcLRGzXt(eT#fZk?b$8`B}Lkz!^H} zI+9vV)l6F}*2mwGj>#NFC*V{@CDyi5a-T$%s$*+R?^e1SgU6kR4|koi-yZD;jajSF zKrAjWuK&40b)XgtGJJ(q&uit5Tj&&3Wm?9yeQ@sE|+gJ7C zc`&&u#R^}&h(MwmNfF?vV1-{G|1^|zNcZ|sZe)iPep%^R&?|BM+e8fPSi^Z3hap9Gjve1F5i z%aJ9@lOsEV*^_+jWV9pTN1kZxu>zFC85hp^wS_ zS7hwv!%D-oS0kgZ}GJn0WT&C7i{nh>mtBVk9eWYd=YDvvnQ~D~F{n-V;Gz~68u2_(lw}K<1zoa~muh9uOn^y&cY6tJBXGkJ;0y`~)7!p8UHW?loV4sXJzI@LpXuakpK{ zM38UP5#djdFsC!0!D(OF_>hLdA&=cL>DGV2mi%OoI7x~5X|zI!9%X!Bef#FQV|@Dr zsGMiu=V<;gqgcz@5fk|GW)Y{cD*ZRYO!q>e)?XU%tJ3xql1^`m_Pl>j+Hc;&M_utUT=cF6R zkP^_*U+@JdI#Eo?+?*vMAt~vvAvhL=29i;nJ_`B;))R;r%w|rf^@Vplf!UNFy^dK= zp2N^6yMGs7J!Ad;9Okp~T;uJZKX-i_31r%fd3W7NQ$qEXDSX8;pHJeMskQE5wv7wd zYr|*Xc-VywFSy-kf;|Ur6f#ui+zK=)gR`38>vC50`H#?={VEzkK;8Z+r4hA#TWxGDc&&>hYFZVrn{{1P@$WmWS z4|#3k)X@SMKs_uGf% zPJHP>9&BPYm2hDskryvr61|)X1e?XLsd{?G#u8}H>s?N%=cxr+zXt}lsx>zE5 zxO(yz+U zQ`@+?wdjM2Nr(s}_Q8rHzPAFR(QO?pRW8PZ@Oi{+P66V+m9`e*JNPO>IdB9#L#uQy zTj4}FB^2z8=D)pgg{OxOQpbx=>rao@-507SDyxcaG*n`)4ddIrkCP|8aSpY+V9GMj z<{Ph;_uvC@<`$xS2lnkXat_HkQ&@>p`FU zQ&g`UGFahx!c|#hF_xz9w7h z55cjB9pU4wf&!Rn-Ck*7vbf6&JlXdl&9~gp=A(P7YBY0F>%02CC2ZLtkC`Q6|3fOYE=YB4QN1xYf9TJ2 z-9>BlwM46GmU=Ok>Pl}@)cKUE!-NGQA1-Std2j-O22v)e!c{SO3p%<7Tf7TwNhO$} z2%`iOC&#w4RhYh;|Rh(SF)hG==0!ildXMbsGEqS zq-Pa?IJ}QbS9`72G*IU#99L>^0kVCnN!C=Akjy~^P3ke#5VgG>(mJ$R6eQ{X0%ndE zUx_PRmFvYDM(4)ZR^HtJN|S|`*JjmnL1J8-sK@?y0a5Xh$C2&2@3;b$&S|x{^HCs` zP!s1-IRmxy_%)Ok3rz zdD(e-&Vmv&THTO54K(bsingqD) z&>0|)BEadn7^3LCFg?Vt|0@l`!+v7e&+;VdzT1H|`2n|cpdqHF1-7XfXJ_L_i@QUp zp0WP^pRZE8?bpMNoqN3Bo}QnmUaeUzZS=jnF1^#wdOANkvAsrl&Dg0BfnY-@q8?}- z9WuS}@-*d3|JM2+`PBxcOK!dKoEk3!K0SEcaWKlK+G<>0|Gh#1wUAn#p~({)iF9r+ z9@CX=o_fcAJqK_=-~}EadqD=2;-*+2Ow}%wjhY-qUOsMQJ@OT}VW($cfRDnQc0i+2 zUV5)@xuCjWa9K_*nnSUC6ngbtg1`c5X_3=nVPxd`+yxR!m^lOvtKQ;ncS=NW<#|?* zji0V#2j{)_7ZV-ohV_@vCal2vM=y5Vv5h4_cDkTi3aCY-X_M=1j-eo6!AR~{Bnc16(dD2Ky>gk~9;v#O<5jI%BQGd(l?>0#mN+Mn#G zZjS|dFLG-Y)*_2pQ9V69X_uwpthsyZEsUd#_IA<^=@ZPnvFWd^^T)@(Q(sYj$?!1N zYQh;tuS><@P@?Xtvo5`sm{@rCjwnF3sr&iY`kEhA_W0M!b_rQZj6((szv2LRE~@_N z&jP7wsM@92$FcJ(oED8f5e@x9C5}a=`9&my%eZtu^xa21b4vAtL_W{5f7#l%Iueud zKFhmzqgYt>J87%Cw)V!sPPWEn!>c>oWkuEKN;od`)4w@_g*gtTGrlxYte`9ws=y ze)U6*iy`y@>K=m@r~fDGvBg)ggYnChCBn+e`kMQzb@(bfJ9$dj)Dx^ClnpJ=rN09t zTpz1E#x8%Ho~G97R!`*!A`5w0KDvmLXiX;s_y79~Dqkm8cZ7xYTb_x%c^(!P7XID&J@+xbg-p7qVf z`EBx&fyS*{#s|fh$M>6dKf>mema3{6HPtzK&bwV*UA-;WuU|*_CdDIu~1$3J-{Z-2G z%`|jD?G0|a$0+HO&G3nXUN||ha(XCIqa97INGN+Q&x*=&n1Avl^~E1Y1HDI)%(_&<2z1k{<}ko?W-2~fJz26K zCvpal76vC`B%pdvHWyCz|7QPh&>MQ1vq{UZt6|;NlTOZ&8I~v6y1*nV$r()W^z+|S zQ9)O@eAJ$rn~qE|QWw1rZoZT?r{!QyCVhH1Snp+NDW?_1;n>R=VBz-s;CB5Uc6GtN zdbt3jnX5%@7W=xorKwdF##tCbczAey^&Zeq^Ad2r%lZAH9OAJ&llcH}?WqYa^dgZk zsi}FuOJZiFbq*o+f#5rpPAmhq{^04Pk)fgLfb_|c^=9)Qsduq@a%q}*`b?=QiPBz2 z`%6nXK@^cI6{e$mEVPP!!=y0e6bruklSSq>HXxT|=iH0HNj=#HO6uw>+tQ_}Up|2% z?+?fC7hggc(p?~A`zsX^sY{UOe8(w7nH--wBrPdn5I8G2XyV!!M!wbUOl6(%W0bG? z0@9_wF8%G^GShNxp7ifLk@w3QH=l|v05m+s(o;*IbwspGc*(VY_U6|;=@V4KoCM!k zr8VZ-*OA2^Ide)=Y&5zxMeQq591r9$gmxXM*qOUHMQF~LQgt7`9lcUs)|bGT92lvq zCzz@q(t9NpkF^>dvaxx|g>e>)hG96DDi*UV%!~?={+b8`fh?&)nf?{ic~3m<^lzKA zp0VD1LtvccgxH5bxUojiCL1%CYb%6R8F~oVh*xpH7Z+i<f8Et#^dDdL-Ug`dfmo12>zGV1E;Rvu33FYO5%*#!p5>0zENghrB~Bk8t7ley{0 zvwC{4KPjbc^J~{emfzdDTsr*hy*rm}{q(OCOQK!PiX~s=N!4;JmSKlijoy^nOiK-^ zZ*2U(_S#v*;SkKR&DS7+8`R_Z^Wm#PBQ}I=M@;@OWCX_sUuiYqa(F(GCH{#=1Qtu-ha|6vUV^scrti&6d5=HqlU+OZC)Zu zGaQPtqzGVnN8C*H*s3kBUzg*X*dE4sX=_0PB^{s+%}8X6k)`09FR;OD+sUx%!r z{@DBU8scit;c9t34r}0Wk=^5DJJrO{ux2();`Pc9I}(y{z?+$1W^$z*9u!rFQ z+QQ|UDH6*28x1V3W1G{I-upo}Q!3W+I0JNW){M#Vz^S2;(ec*j`eInk;tF2cO;gI+ z3gGi#f71Wda|uUzf0KjlZsNyqkDXqf`lZY1Tr_8WAWmXc$SAqm7c2XlYGAPb#a9C^ zhB!$i4P2Ezg6FNmiMx%p2`xWp*YIY!rDhZ-IKCqRDd#O<$>$8M?O{bm za{e%085b59UVRO7vZ+*P{e`!yv=Qpk08yO8;6!Crru^PMpACR465 z;WZo{X~%+!*p!n0kweU;08%(3b;owMIIUdY(#VJ;?r3)E*A#G^){<^DD|&tlv(O}_ zj^gSp8Ds2U#KGQEtfd778-EEw%_$!DF)ZBVSK>K5ZRJ)w_Lxf7|}*4h^D zHu|@$UAzxq760<+%}D62WC9KUis?E@edoM|Kyo8cYDrmA-!+5hUKi&28iB{EQ>uJK z*H)bnLu0EW#C@>^K%dWZDcvRIr_v=VWB%+jkRTc~yZaG~gQsk&@g__VM{#J=Q=jt@ z4JxRZ+0v<*nWHtQU44-|xSY;zej8z-S5{ne-*vuwe}BKB0pX+n5XIHmZ5%`2uJ%_? z_Rd_VOqQ;g=i9Yk8uH@F6W}m(RAVIJUaJzjJHtU}M!+z@`&W_u(n=p=#INNnG+JKTs^K*IH;pl z-@>Te3+y(AkQNv!GXE4PbC2HuEl2EQTk2a1R#>GMsjo1xkPx66oJq^5s7nI5Kpl>N zDUoxU#DwsJK+#1&zgjdbvB!$}vMed`_v&lugN~;v(h}R#66^c$^xYQ~-JihKxi0jQ zBQ~tVkGc{a4hAHoU$;3NwH6jSAyVgs z89ZGx$e?|wV|?IYc|07>dWG>SfyzjL|z_3B~b>G7cJY2N~L zX^TJCAALC^Q%D~V|15OtLDy|b*GF1%ClgtVEnIv1FOBj9%L4YYA?t@3)%#*hOiZb# zN2!m2d^5^=x*EbayjwJRGK8x;J|3){E|qXytHHVBUQ5)T?sYs}sWij1NgYZ+Z`)+Q zDK+fl6Cez`)-M=^OIG2kmQ7v)Xbi-=orn*tZWuVzyZH`oAjiJ&#;hj4Sa{F$qGGd^ ziIQ1#qk)L>XrvH)R!mN|9K7)o0K7fsaspM)tw`4c9E~@?$8<3bpn(Iq#x4L9mj+&q zgIkw@@kSGxdYV~I^aJbwBRF2_jv7Kd94j(+&(c1p_U;?mf0<;k3XC9pR8kY(jB4ij zkJyiBZvN>tkDW%=lTVzJW#&h{;U0)ovE85dDFdDj>wZ4`^hL~_Ku-CE$17fL6hLC7 zotK*bhONHaP5YW6CGKvuwv@|PC~|IQ$gWJ7Wtc5)SC05rj4gBZ7*0IdMeq~HfNXY^ zsI-Xa{XfrLYj8wFM1cza?EAHV*Xi!dC_fp=&&q7>MkZKaaprHOQx1S9%beS($dOnU z6kRkef;=G8FvnxPdh!;1$e^(+3wznfs(xusj`FRp@YQh%DKW=mmqBZ{bLqX612F^7 zvg3C9owAZrW9G>8d1LeLxusa^F?f8B$kob~^1r|CYn$?cD>&J?_C>wn?Up;kb`EqQ zBgP5|d(K z3G)%RE?uO^FUXT}*-*$G041qnKQe?oz{1>ID_~ai($%dgxfb0{4{a_6@!Hh4Djd`<<_^!mBurdoWc2VVQ+Mdk zdYT5z4bY?Q^Rb)nF+VOjZHg&)7vhnvQ zy$P4mYS`JIcCT~8(CZlXu28F?GBG|sKT6T+PAA7d>-d<`y%GDjJ(;+PTP&H^)#<4GRq2a<{rz^Agz$F}QV!MJl%{++ z^M;H9e}rPGWXyv=-yMx(oaE-hF4z)#lw_o+Jv}4ZYmzxM|`t zpjBA2)d>fK;xjW8DT_vLqFl>02qbEBgn)DHrDQuhqEU%6z#6 z1t+Tx-pf@N+8mqsse%cvAbhFy8a`9`+}1lMAu2e8?bA2X(9<)D*s0-SB_#4OW#~5T zKp4exg&^eRh-M;A zTNaO>N&n@4@Jr`{>!k0y^H(Wv8`Nd~;LYW*k#}`@U5j5kZ(#u@xWBWM`xpPl<|n%2 zM`lHnB;BWLNJ50Yx3Xu&SyowmzMD2Sxj8TB7n2_0tW)9z-L}-)m=_m_xGfzV*7sIN z^GoOE=Av#q87paO~U?M=C7yO;;|`5Cs%s!UI@eOk>Z1roX*bYLSGz? z?Ue1u{fC|BMZ-#*7kXJFT(3F)jfkPAS7YX^wP0>LD>@7ZcgX_+$S==3RURI`HSZ3+ zA{2YuL`szZyFGp{t?@zDZcfatuTN4>Fy#{npMrvv;^M7@k%Zp80@|li>^m8hQg6N2 zlEen?X}RyMtSzoR^O=rNL$3<7G1C$^maUFHJzZKfqgp+BrlVG6v+2hLTtnZcz5?yHI>!YM&nJFWi3h&{v_s+2oA(c=C3(9 zPOYI=w6wI;mDnxl+RPZq*ahPs^TaqAuG+{;D3LB!T|iT$Q~b1fY05=<3>HJ@9-$c9 zh*2C_fBDiFKLmF3694CO`Yr;HB=MsoBR{a9$Rh%|0&TitZ|fMl4fKdizS?lrL!#f>?~&;)*qCi61|kyXcN_g!P7FDS5x zyG0S|x@cIMxy)<0k(^ubW;=h-A#-2JPYk z4-XH^?1s0R0p8yKL^?k^yYgtO3vFu)6D^IAk&#eNol(!jRv~Q{Kx27Pno5GYj|d-G zJ!0Swiy(;eeMFuC%br26($kCcGAsOL-}ygo=S6&q2)y{tj6aZd*m+`A+h>v9^AEBhl@3Au2W+QU+Ni`TsbSnQ0AZ)LSj0hAkd5M2}Tgr!_(Y^31V_Ryb@%9+>@eIQrM$RZy|DDSs_DCtGT3 zzUzH z)=x-;!o#yQ-ns_AR_)?K+oh!Jx;k;sb#Db58>`8qrK$PDvA>o4PK8W$0oJxHjOF4* z_oq^G76^);RMZ-ae^O6(G>weLBRQ1`Cnw81@nG~x8`KPK0ZIwGaqCojN9J1FfhGIV zvH-KQcDK~-pHv23T~#Ba?WJ3V`G%FY{a?ZhD`tZEDN;Q5hOY=&(SN|!B8Z$mBg+~KB z@Fb4k3@DI`uR3w$tTD`S3$e+By#|LtHQdu(g z%zJsI=!`q1cbpQLMV61T?Jih|M6{_V}1iF@ml()_=kTA0%+`^qX<(Z~`i z$lPt^r$(~*B`Q45%T0uw^>2p;=z|*B-M@al^gczX8A_zlP*G90M$8Ey8oC43L*MZg zQIWPoZ{cynY~VN8Z*&ujfp9j+aW;ttFs4gS#B+7O_kP_0u)mz1uYw z%pWeg<5FJz4$?8+O-?;t!HR|jDWF-}HX)D{)*U7&M%^&+I+#;eLIP+jH+LDzBwji) z_~ljW6TAcXBsIz{^KH>6vZGWtCf#whV$So%uH!D0Qv0d~=utStBJjCJJ(a2~&9`4D zNQQaVWEJn7K6xf#JJFN>K6RI_IQ7M=h|NWdhRMszL%jh1cS_=mD#y;h z+?S1h)P4DK_?hx}#4%a6ZX+Cum7YTH5{t!1c)CqHBC{0v*y++uP5lKz8@frmEgIiD zGNQa(O>UB@SZZ*}wQ$Fv9wFJt0|`m^bLRTbfUT^60{N z(L5x8xZS0|_KDy&5gDhNpnw5ZU1^nK;So)TKf&vo<`hYM;#C8kJY8*Ly-onlvcCPN zV1k+b z?RHO|x}O}8fYh=G857I<=`a=vW_doNvWonCdjL5v+KI0(l-rFb^jZL-19x_Pr$|}C0;GzK_dhS=6)Qeiss^N|2? zLNj;lVXgB4Ta}sVA5R3J62nHKX5JYl)BKxCfBn0&XL zODNv@O@ya>e*RW&7vc(niWsqRN>0^sDuY50BIp8r_`_NSoYCmq9$}5 zUw-}3+(XDB<*zx?DUJPj9>r1)Q9@#^V%DEl1p>k?Vf(RHy8}9to|y5kDQ|OTMZtR; zR?L}%$K2pOKTWv12qW{^1qFxW>t1|WsOFTEl&_~p3$7Dx^4z;09g^HzubAB8?h({A z^>^&1AdTe?JU&S~VcR12x>*vjX=fa`pAyyIa=5@ za;QCd!AR2FXXJWXqdn71M2By?4>FT<5s%@Vr>J!C3V}D)!n4mn|(>YrDI2+n|iOZ0&n?{}pTzNX0+Hpe_1qL7( z!Wqjqs(!>1k6BpgN!Bnik-jTBG|}fcEq6IKCRUNN<2N`MyRHv=g0&ccHzWEYz;<@` zZ`4z-g;a+^!&0Z=-7?(l5Tt1G|EybTJAf{% zt9v#V3^bmFRCh;+szyeV52mgMS5;NDKKvj!{9{>Mu4NcLdH)3#(Kp|}l+8zLsGQi$ zw)Xb+x;f9oP${c-_XUN2;pckJ8_=jYVWagB{E~w>t|NYu49g)ZVSnSkN~u?xcZyD z`P~5vmUlO&8j0$?_am0QJywJ1Z=D>L*V`R!^s^e{#)q93Z1Pi2x=f7UZnD-_xIdJ0 zQ|pzR-RaMDZ5{0R$+kp6?Y#VDPjsz1GWgy6e5-l5gw=7&iws+~- zXjf=*42X_@)w&&7K5cFGwNy(#+4j!|~ zt`mBdPIE^G+pa4^ZW~i+=3!ztl2xwHfYrej;^}znBtUcinwTiIAFT(odkr6~+d>}6&VEYO6btgHrIPIuSbl{!-A*s?f;;@cJeDBcvi zf49aGCZTmJoh*f;ZtuGxw`zzHiMw_nqCf}#&QlNHU3QcQ4mX&dVxs{0BOeNAokgpN)!7B43Hyb00z)R_8JuFldDP35ET6 z3qANuyA4fDPHS_$UhY$Wa2WdjfHW;Sc($UjaJ}*THK@=Vo`_8D&vfzCY#fpE)gJx! zbK5qhxDFKB_aEe6R4vYzm6bse=&-jk{58p`6PB|yF+Ng@ zR{1(BI#J;`dyJc`f7VirE~u=^t088Lzk*=&iQpZT)wNl-?K#Nshjnfa#i<|*EjJfO zwV=qW2*&o2IPTX*ZQw3N6CK2z$UVN_IPW@ff{4(`*L(Y$yY1o}-qCv-&-Mwy7>8h_ zzT!jLMkPe}9~--W>~EK=d#esZ)!y)sx3qAkeEyEDgDOAj<`b!vz@JC5jgI4z?t9GQ zFaK>^4{KkLpEz7dTpl#ppCRWfFf6q_sd0lL-RDEqIJm}?-zv5#-W9%Ax8D@94Ck@f zLXqn5cF#x1hz(1u>|I=XTA#4uUg4OXy9M;ohmoG!`65=mNn+k7HKM^kX1%sL<}C!p zp8w9QKVEfMNO3i`clr2w=ik47KuPhOG^u`V|63XCd6aLayqbZVv&3%kHwa~=Kkhof z-FgsAuW{q)g`cVthp7&=a}{f9@+?`Ucj(Ac7HV-5qspT2TEN#KpQgj{xUab>tnk4Y6d1p;bze!k?1KW&wJ6%<_KT)~5R`a+&t z6ao6hN;XeF-L2ask`De^P;dur@8}3FijSI6$VM4`^dv4`Pic5y04x}mZVbFt{0uA* z03^p!Ksz#8U7d`Z6RDKF!uT+dMyg$ax>9rlqB%B*m^{q>Mly6^hl?%I$Ozq{XO?PeeN(2=Y($^b zK^OZ=UYYqhnCRc)qUF@qmY`MaZ1f-O?>f)(#;`v!W@AhmqwpqIJ707u?s`n58XZi( zD{_M{20xppgr_0!hbwUe)Cma*0G5=K3&4hzzWSpk|JHa5CiMsq80P>gXcyFPwkGD} z@W7Hr0nzzASU47e{US&bDaGsV&pyUGFdfcpp*;n-QAngm74|CBFwO|9)5od z52D*{fx8H=Q5`Y$wKxA7A+0-%HSiL5b8-PNyLF;;{b|Z%iu=Ui0>0 zf3vwNNPW82b@FUROY-1rTbSsK0&NubDs{Zu)1N60CY$46qBaJZLfCAxV_x*q;$r3L z$$6-;T}SPuCH}nGC>wnty^!QA43VI{J#bbO(vwQVlP^pTFJ9Om3>11Bsp&Z`yq8GD zub-Yk((DQ)^sTJ3#=)pV^|2pR!7E!`!Y{_&>{1q1;!{kL-Y#XQEV#J3irl+5?lL$o z0>8R4T*4=MdXzph12PjKB92QKti7nzH2Tw0#}Ciq28e0d+4(n+>>PT<77zR^CG;6r zmljE%P0BJmW*U*a=cnmF<)r7O=jAaY()s`BBlNg^LrEAA>ORp;#~a7t(nnL~=MMK= z@8qYbN<}ZX)P7tSWMiX3BKQgU*+4hvLIjWqBV=zSzr4h3d$d!6@nfTrrQWP^K`$@e zfY?>?U~2G>HlJQG)T6JKW4&3${{#~16zEo2bofCIYj)5%C-epLZBlJ=wBH@F<6BvA zjWnxhn|-_G*ps@Gt>E85v^RP3t$LD-)YRfJcqm*IH8i3!#sfka^7Klq1`AkHy$%(r z_8}@6)Ooaou~egPKK@ov@WRIC-}<`r+K{;<=6X7y@>WO7%gaki9_VTqd5$caKuxTp zov*K@qjNKBtj5jR(^FCilW=c2@Os$4__Nj6qM(t9&y&!ygI? zUa9xwNeSlusMZVd2G6Gn#j@85$s($(2{<8hp6C`hhI1cNLEC8evY z>(eCN&%K$d#RBi+si_fxw}r^rGo!<1ZSvo-nOfy1@rM%p(kJ`L6-Gf#5TX9tg;pO8 zlemH<2#a&Xi=tsv=|HM(3p>;lFSQ!KT1+<*7?{ZrwyaxLXM#ZYMb3)GzxtAuwF<%H z79XEUscj4uGL#IZ&245E{rIh;9XA7LY}k>61Y4_fGVD}{S`-<{{3G&k$-U-=1|M}O z!|e{XXjMcBsPjux7ItwsYr!i3zU3D}Oo<|>WE(_Jq!EaqZ@_^|27qP?HkUaqUf%I0ad2*YmV; zA?4U(vsBmP|HFEZjUeg!2N|qJ1`=s@GnrMA)q5vL z^X_~#e`_+r#OKe-y~Us5eAPQ!{VI|!pq-YFzr}~fYn*O;XoJr`Qx!YH73@z1LFQyF zW>WevE(4ZPgst}O^HKbSNjUskEvRMqSObUbZ(Oy1Bb6afE`atFdwBu%~UFZeBDOjHlUR!bMH1Xtc46NET+`*1f&#%pBUQlst()60G|Eo) z+ipIUocmkSD|J1pM}Zscw`x(51Tw{ziIh%8lF0}B4x$wHT*Sm)pZcDgz5;c;22MI% zdDx}{mPum0Og`1HD_cB>l z@pV*OZF5@(GwJD#Y3u|XKL`<43KiGV+58Oega?MH{AY@g`OD8s8Wgrn#{Q0tP8NDX z9#X95%$_TDoE0`Mkm-@ut9}Bw$HdfzDl$UhMpS@o|WT$<5=TF ziweMDi|0!GFa4k0{9$L_f$!L$HGlcCV)l$EgRFmA>HC?XW=Ff*1n*F<4BK1`Q5IH6 z8X8VAE4Hq{XQ2yc2~0s@p-GL!X7OB?gu8fuye8E_*fOJ_8lB%g7&KM95d~KaD0zFU z<0c}GGwE{Vfq9(f+_5wP2;?&&qhv{xriKO)1(z!1lC;FWvlYh3Ieg|RpJHj1*f0&W1zhB znvb`R?9wOj0oDDTUuR9$KaiPt{f&@6(~>2}J+%h3CJ(V9LI0qn5h!}{RUPIn zy(PDXGOUwb=5h6>?>?}4?q^*#sl!iHWAlt?<2NAV^wOKN-+R(YD6k3?> zkl<@%Yf7ccH&0AVK$-i!v~+cz$stL^VXb$(x(*UK+|G_@nALkAu};2S&WD1cdT~B+ zk5%*~MiR$sRP_VIZV}4krN#RDw_CNev=1JHWX#8zQ$1DzIL zUH#FngZEYxE1$0DDZFW~qrSFTE~opr^pHDmR|f{GB&t=@?^$*H<}4rgGI;XDh3-7| zrJGyjf}10=yradi4{=u!r%*H#GxIgJ2aZ%qs`@+;I5zG2 zWJU&IvAy0kJGKr_9eARu4wu#s`o2X)R}^k~a^Dl8B_y~`$fkg>pyF!f502{~3nF|# z+UEGPT{k5Dm2lWaAzCH`k-~++iw|k{%@iF2Sc!!%{m2Nthi!h*^f5g!Fgo(UNyJm13PQ*T5APTs$1n*Vo=`+!QiHN-ebbDs76~mt^w%`r0iLLu-~!0zot|j6^jIJeC`qpyG6{C<%1xNjz%>2fo-ky$PdTeoB?R1ar|7p z&2s+gr8vKMN%P(sv27Uauv}VO-SRX+ONxq$3JTtZJUwSg$!hP|@g z$rWjbeO93AgIX^YhT!uh?Z%-+M(#DCDC#x!&J=OUuO`wjaHictaM(gn%cLFxDBpZ9 zm=;giA!+?d&@frQh_91{oZCDfx|C2i)5$`2H#Eix%=Bf=|G}(+1`v57FCn^9rB7E% zddn=bP$#E^#OyDVWMr&h>HNK8Yg}wBSP+Axpl)^P=LX#NU?IaR938t5A*ZPZ|~^Tk`i7J`l4zN`#eUQex`!ji~QC3$BT&l5&+cEiDY zt)gMHZ304&mg#D1rzm9wDxmYDdFaUO?N@{Rb@UCBdaOcA4`fgJpGt$-A?&h1vDL57 zgvOsgZ#a0HhexnAQ=R+!50HwF@wlh)f|eE*e^cDojz<>1nm8?TB7TjH-FI2~gF>2x zf~6LERJ;lj`EmbQ{0Urg;H35SaeVQc&6$&v3CM${r>Eg#f!YXmUtDmnAm%2-<>Y`x zdvJ3F8yPQCo3pBu>r;6RH0^bA6gre9l3<81>Pc24tu2~H=}Uh$KWkM%o3^O<@UNFs z!`3O`8E-oOa8FkK8>^B2o5^v_=7j120!farIHDmnB}ScNzRtmYMKAbqC>Kd!TACWu z^>n8sl%-|Mua||(Ic&V7zDkv9He>;!q_R3<9h$P}55rtpQ_7h?f}haIr>WBf@H_ew zUQy+?4+R?+lweFZf5>#28M_?gVNp;utnP{DJey(2kLHY%l;Sj%c1Vz%V(vt#m!dT+swgk|G9oYka2d< zNnNItf(MLS;|75bl}$TUNon(AXc{1V zX3u?iFD@bed-0W}W!9`H>J!t&JWd3AmW7q6wyXkoD*_=zp5{+w*HO$)jLz3q`rd9; ztY#r~_%9Sy>*X8Ag?U*$l{!D58(hBX%CrP60 zfF`6S;^vGm%FXT4H_*}|q3{6*txrl;>HIg4SY;WE zC|ijT;RMgD;MB1p`3XrG+q(Hxlm^De(n}#lI)~uq1k@!$2HLTNGE~HBbXon+Q55g^ zWA>W(Igo9Ryu+elz87RHO7zejI3n)SQU)LR7APKCS&9*4Z$SBXKt^S&8{p!^Z;Ek`14RdmG#!~1pC4TbFlA&XMZzc$MLWHRd zJBJWiT8t*47V`*pFSgbl_ddczBF*ZgMy!Q%IBnWDEuyh;S_&y))mHU-HesJit%LyxS7(xC;AY=PHR875vo@@9UNyQt z#xf8YWJyuPpBgq!&2N|f`0=HGv3SeL^aecrpsP~(w)14YZyUfunYiEq%v&J?tCWy`LfCXg1x;xcEmz3ro+NH z)j)O&o0_Zf{ z>bA?Lhp#_?>i<#o=HXDkZ}j-fl7_sQv1CbMj9poV>`NMJ$TmWSEJGAY*|V#$?=tr6 z1_?>Bmrw?gC9)*TWStN~_&z@0>w8_lUssp@C}HM#J@B|jmQP{-M{-)i6g?cMZf{SUG|oG3rT(HB<^x8}`Ky4*N{&D`YcNF)7q;U^XV_f^Wp&w1CAyUejz=em#9OY!mR02_J;Heix;N!f~9fDr_{ zOPBthqNe^7i$by7EUxEwyQpY=CXwMW59cSDtV^0KhvDIIeSP6q!wU-qCQQJY933|2 z*Hp_pcY!Nc>G4AuLWpFN`B1VPX4DcLPoR1Lc#u}!?j*9`%dAAxy&z5XY6eR^tbxxe4Y?LHP*Y|SblaoU3Ci+S9>aVkqm z{Zh2SYJCI}r}1}>d)wPJ*t7%%KRW07bpe=Yl~V>o3o48Vtv+uYUc6Xk`Wf^h zRrP>&1J5`34wFC4w>~*wI%1aH&=>sr(umXH=eHA2 z0(KZA0WV4iEhj)Dadt@ap9kvy*563J5mMp0nb*M(dil*uBd4!|TewU5jaF@NWC6U# zz=RD{525(~3SNzZUphomP5#?N$`eY!iQ7`=$#Zvh4lW(d&q0^Z{y`?p&n|J*r+*OU4C|!@3+)$z&0mL?#zcnsk%?QbTK*= z24YsXt>U43i4sUr){OwllRrzsdHg@+B^8{P|LEP3b(MNw(r=i%!cR>F=TeUU#A4-m zr%DhmqQ$9|Zgs6Y?Lyce7OpDRix=-3#ux?(4%JHM`7 zgcI;AQM8b?LnIqM41a!2st}Hx6$;~vEhuYw{HnRRxvZ@7TG7OJBmb$4Ws#_CnZuJFr|vYS(BJ z1YHc+p`Cm85^iZ~YJf3i(BPB7+^hPpP%7TuUNcn_R`uF^2pIZOL84gBPLoc^RJ6Qa zo0hd(Ge4Du%9t-M9HdQ-v8bJln6Q?+5j(7{CD|osiaLa3{fDWO@*=0r{@EuZuU4#1c36Xrobeq zi_@)YP66~e;>B#5LMi1ystFj*oS^-s_(F!rK$(S8p#$JlkxsQq$*Nf1G|Mt7-r8&T z%vN~gdGF^pnUuL@h4@qpQ#{!3sx2%u)Aw8Z?*_$V(t*$JE{u@@3X8p=;?wmnLSGpf zT4VsGEMVfm7w-T%Ic|r*nd?F+0HN@N(*l?*3$Q~yJ->iKRZKLX9y0Ou77oTRB#S;0 ziKd~Erh=>v=6R1Ffq`n$#mG(7@AEwCbrnw_d;-F~E>1{;KQ$E)iJH2axRTkVj`SU& zVlB>7A|V7$4Y7}%nlJ}OU1Mvjt1v#}Sp|FXG&`IloO;D|IoalOCqiH9GKf=!!{Q6g z^ls?Mc44kCR-Rw_kC{9Zc$hQQbPn!&C^$pRGG~tvK-sGd@0rLX+2h=*xSTI;aN0Xa z6u?bo&;<{8PMbgitY;a5cxuSSRkQK&{lGAJc{vk|muESi!}tLXyu0=teb+S2G(#74 zTYmPy#K*(-rW^UkmsjQ!TPnDogGiBh7I!4!Pcr?OS5ERh6Q!JFYMzU?Z-@(SMP~D! zHICwAdg}Ed1T+ONQ){~vCZfW^3guX63NZW;sHbmsyhX8E*vCB2@HGIM>v;Yk+m4Pl zN+c2>pRLnJp`k~_%_v|w9u>h62_(w4F5l|pqYcDTPB>_QHpMJ;fMo4XI<&<^h@_fpim~-{V$umw-?*dy(_H{j4q=2?X;Xcm*rJBhup+?fRO}r( z9HgPK(UzKO!UK@xz}8p6$E{#E1c_k|U9W*u*ivO8j(R6D{GWDqvqzR;*sgG^%id3+{r_Cv_oa0?*-4~S4UD z>A8GYQOeTemC=`0bwWuG3Pl|GFt5|8Okh-Vphi&T7Z+=Z%7LDhTevuO4i=JTN&;86 z4`srvt?;O#G^a$C<(%7pN$l^b==dEk$tx)+7-O+%M#XVX4hEcEPw`x!1uFnh3bCT% z!rr04?W!rE_|~9)f>zr2dPh8r+PJe_zwGCuPho_Zq7nKu67%WwN+-8Z@mDb5i2x*C zfk;-L`*_j_Z}R`s0@QxoJp{NJxW`-`Ja|>UWM^enu52VK2u3!{ur(ST=OBaxpr4|O z$}JH#o^Bu~dbt8Jb-sB5f%}PJ9|Zd%@$KQ{r1t|6c|O!>liX8i0OA*<>gPM+SkgmK zx>3nd2m~A^q0e`Xg`GP?-Yb`eNk%HUp6(QjmBx zDn}LeXm;PjDASr1^C5!&&CU}c6U%F!JXxL?gOg`1cEuNb1hRVS5HL61dTHEquosq) zPpkmqz2zcvP(8p}xn?I&NdN}oXYx7EtQ*bXU=WS0U{toKluo>1fF`!NUU!XZ$47bcNA(IFWWHLMaAsg`!am z#cb621{nQo;O&xPMc;ITG{DloHs`Ytk>9~0#SD>}N@-v!s^VsrTfh5l z?%g_w7hV<`-Pzq$jF-I}J(od1NYDCPHyIjM9qg`E6N$IqJme}=9Db{Qc_V^;q^k=< z7jlZh%}VsN1}wGfLGVmsa_t+Ubv{oisEQ!^`6D2nsebuQXUe$&O2QI(j#iDq4m9KZ zw8%{b&at5(FnpJnzX0dS0a;ZK4}%RYk=AejXFDA1IdK=LuNew8;k2Yw-J;ZC{KH3& z93SMj)z-?S>2vjVW$;DE*5i91yhPEjU#l4^PMhjBfqU&Q!$Wy1EnEJiR_DCEKhXA{ zwgmktJ_jKy*+!hc6>;)PL*kiFGG|^nc0>88VO+p($lStWe>#A2h95`)#3MMlxxq22 zA`<_o3_QLq&D2fLpF!x7N-CEAC-{%|cN=^#o(3Z*2+ls5CPd@eskr&4))P$0Qg^bS zb07BTP=!#pp{QsJ_+--!G=&qjIG(Pqq#Z_!7QJQ>hdzk6!xKV1}6 zbcHVHffUaQnxr>s6p(6A393#_GDdOYX+()O)0E;(VL7a)>n(z(OgZ;;SNm~feVklD zQIcxvz5A({Pi*udeDq<^IhXw1b&uoLfC0Z5`M5WVHF@OzrfJ3a+u6 zBc~Q-gw#&bghgD6FlPJsKw)xx9JsOIM(@3G(+bDO6xhuFhjAUw0^;K5mu^qb%=q-P z*Ed^;bJtt9*kt9|y2^5=$S~>5Z4^oLMujR2Xc!mQ67}mHpQhAm7DYDhA!+L(AW;j~ zuvopH`*ACJNSRt^>SU3QXZ}@hniV|sc%-Qn$Z&eb1|M(mpG>ZXF_Zd zD5r%s8zB;(ewcNUWl2&Q0E@IHY&an#{+DW9Q)Gf7IpaKMW{0mz>!YR3B=4pt2lpHD zl(yq%A1H7$BlJ+fh>#5YZ?U;#yvs=l7*VXi)$wV+B5-WMT-5}5*U+n*w2X;~i7?p7 z^$32GB)WdJ$fL=(VEkQg8yojNi&r~Zd6RQWXZ*gG2esYAvYI@OCyL1^QtGr@_BMOT zlDFRl?vs{wTPdo~FWE};KD>LEza*Lq@gJfuWW0i!`lHA}Ku&v5kULWn?2{rTo3i^1 zc)b1@k*{Xcn$138Ixal{r0l5kjke2x}`)jhqXR+)9CJ~^_4Wf82(*dHUuD7#F|J7h9>OC>?i-oWG(e3%W&sFD9Q z^{u()?b~nT%72$R+Aj3U%6h&Bvd9>RCyT> z6-3S^6sKZ-f?p^4BliaN-=WN4NSl4|w$aZ4upWahzLdV$c&d=huu#IM@8)Se1OhRW ztMy`+3y!p!4Kjh`&=}MX-NVC0f1d|@aP~qgF|#PV23{A3Zzs_@;+7SCHy>V;k8x@Bu5sX@1;7#R>D%Rsw)rn~lUHG;|x@Cn3auy)16^bD}k_5OG0YV?t#u0|s(eW|IR zPUZRW0!y>FEP24VGchY?+PQm!clp&T-!WAmX1egWxD_WkDj5!#6~@$nb+AnPQ^t6G zR+V?t!ue880zExdRpn>-m#ue8_y^b+**V)4Z$zxlPcW1vQSmF0Wkva!=|1#TRYgV? z`?pwptl7$T3dI92wPxm&PxC-)6u*_0#!ky*^)#f##^aseCZM|l!73qh3zu!6+ z)DAZ4a@OzUlI_wLxDaVrIi5IstN89Yqf#^v6Qah(LpH0=zv^r)6nuJ`nqL8Q{W$Uy zz9Q7;c|d?v+dNr`n*F z_Co<@$IIxEhz2;48svFUQzPJ@{er%IZ{7uuMj9a!-ZfXV8>GN<1opiQ%ikSO?N0fT zms(nKQcbZ~OoZKXm&HMFf%OL42wK#f)xG) zUT3SGvt$lzpQ1AZ$%wr+@yQXvIS81m;JSnMp7Z+690Ucaa3Pd&-6VV&(VLbueEIU_ z3_ox0bOIuY03L`aU0UwAMR5)rRiE_*z`8^k?LJUgPIt1ZSn%??R$ma`1F}^P0s?^5 zOnt%Saxm)0#^$hIOL;ha?#~YMZm;W*yBy`+*1Gz?nWK?e8{ulFT@~NmXTb}zG0!hS zH14{upe#V$T*l45>QuhZBO$ffz5?BugF2&epaIbTw?T&tuhQ=RlDWY6 z?vfYM9)_RqapsqFttSxf>fDO2_(6l7nQR_E|47t$$OR(JlO+2j17NVHLZTlf=Ka!Z zKEQdDrS$w!p`rqg1IIsvXZCt|;WgI&s~ZWbzo(nJYbq{xh-az4DRR}rnCj!6;xXp) za!9Zo^nIz>Z$Y1hkd@UZ(``_1eLe|gWini6oazMp{jAfmb>qY_H|Y{&1%={m8?Y7! zHZX(QW?UPBkDjO}Kr3T2#34*2H4B-a*8a4~Y`#2_slFg1C-+lWUaZh6o z_xNHah4b!Ar|p|q+xaw-#wI{yw{j&Ip%-)cP3U4h%ei0EnJ7y{)3H*o@RH0tWo z{=N6_pMBl9P*H~+4AL^W)i!ke`Nq-eE3Ypr=hc4yI0P0T$9r#i424+H+tVW}Rka}a zS&lRQvd2BhrOE;r)DFa`3|#$+IV<3 zO@XJZd}gKL``6v+fSLF2-#<`LP+4^(2p4Sl-V%51q{Tx|Vc^`^!wY>WW}u4tQ4+tH zFL5H@OJn#@+NV9xXl$edF_Y}44_3oHot?>@QLGC^|E71_D@Y0|*j?IF~>^@pJT?}NIEiV7yezr}lJl~wDaus3i; z1esjGM#nupsKnj(k;8`%@%5NW=6hDrTGE*)f zB9l!`v5+Q4Aq<8qDJc;ZgdX%u*AalHAd5-Z>z2CunQ?~%4WtEd(0^2h>s-C9!KcYI zeFJ-nI{$6+D-~t=0I!3^J3hSU)2+FwsC6T(Ek4k?Jhc;=aIXi}YSAjpp-JX~hyrus zPt&3S^)2VI>ibA!h|1pZc))s#L$<#wYv5WHZ>IT4lWu=fk<@&;ia-)jb0pYE;kIi`0aJ7 z?oP^q7h>sA*PN#b8&-}V`R_W+oE=XTqi*l$=;-ffLO+9pcW+|tEHHcodU)N8iRO^mR%5k1~x9Yys+4y-KOBj-xS{-?)bDGOi}u4@5yqPb0hUk-$fFp zYy(%oJ@5dmogGlx8pbG{mO@eB(r$6TK7v8V01Ay&<70wE_atGDh4CxYG3OrNjEJeF?B_Au|*Uj~6O)ot6z$_pZ& z7oQ_KSkBto`d&KIA0ULpD!(`2kC5o~_VKBRQALaNTnF<=6_!!E=Mh}qcM-HdK?7%a7|+?ZAbgX!Ml;<#7DT2?UlBT@|04e zKl`Ui8K}7KxyrI)#{~uIFSB=qY29Vr)O_{qOZvTjb19qGrzY#lUd8>Ht`h*I9Y`c0 z#-~KSPxwIn@@xz_Fn4UZe!qWo`rPyB$?xBFI>F-G8gLRPO|E&jID>z$LI=ZfYbC&k z?vNiiI}1mAX)VUGMdFK6ftyUWmjPq+&Mp;%&LZGfDU|0mH`wYe3Z3lwBhTH;0*c7y-GA*gl-#VWsfpIcrl$Ywf(44_ zOvLo20WVB)5=_HQqS+@E*wcU)N0PQ%0uedUi`&ph4X?9uuWY4uT0 zSO&4gF}ld!bN7Ldv(GtQXvFzKn)}Vb8x*_0!g&Yx*sopj``yBaCr9;Jf|#CTPRfyuZ7f z;7&tC*KQ1E2G{Td0j^=tC}Fp!X*56`B^jJN2lC!C6O+>hEOqY-y9a$Ohh=cY&tigC zP>>^PfGX{0(XEWz*0(G*1W=PJYaVO&(`8fs)7ghWbv|M1cp@NVsgAWv% zA1#@}W{1noaEsX$BMg{RY+%*`f5TZw?8<=C!`mTpPn z+n_C=qEqvGc;6%Vdw|U4B$)_c#Hyj36JNxpNr!j&)$DQkoOD-E@bJp+XCgJN+%;V1 zJQ#_-&W}5(vH4BAURG66cSXX zx$N;apjQJvvB8NMhK6$LdlkHG2kT#*W`SzB4T$*QZ*`#*ZKSW>^D zCJHA@gN|%aBx`oz?elSV(KwhkR2B_PLiJ_PMK|A?xXJ9Vt>skQs9s-Po%ag@dv5@( z^`rEeW8sK+!g!I`cq69(63iW`L&L-7CiB3TQMxNN8AJ(We4|}G3+g)^c>lVYn3=D_ z<~H6+^a46Ml?7=8$g%DZ*F2g*b|{Fc6Ya9Zrg8c5Mq4LEPDa8V01}a#nfY$FHK1#5 z*6vG!v_HkVY7s5XF0iAvi<@j|CsEfQ|(?p#<*r+D?3Xn@isFINtH7&aoEn zrAJ76>C-2aF9ZEGa9Ez0;687Lh3quhS!+}z`*WHe%)Z~NbLJh`OdO(x5<|WSuy8(B znmRlTZ)_yMHB*Z+*+MzHMjp61dnsH!UEA;Ah%c(F{hvVz7rSy_b4%ujVB zbhut@%8yA$)6p%Vu$k8JJ^A22R%RAv4|kRZR33K|>aY00EN4LqTX9fBL!kZLJ3+0L zVzdvYcLQ2h&W(Z0wYZZ^6cC2urjYE9jxRjDN{BIvNK&{rUNFiqgxDDF{&uX{~G29pq~<6`-`7 z8Bp1ZRH;zpP}?6&Q2CvEP{*hjDqY`r2CGzyOEV1;KJ+2w%rr zp4Byqc2t~2RoN-@AZ)9OwZ0PAp@OYY=AgeSNP~g?z&}X|;E9*xj)QL^d$kJ@0z3Ox z(Hba_^niZcPotuEELLk9adQH?&DCNeeZ7fS@$a&TmFQ_$Qr6cn7&L1r8nAZ({*2EF{ zetbzuic+M6RMsj)e+XX>D)q6%CPmSl(nP)9Yi#rmm_XBrWJII1do&T(J_XKg->43n z-LjQ_JpY9+Xdiuj$`g0r_yV=X-yyf)$8Q_dx#PgAwWY$$4+^q}hljIYMy9K?6H2gNu5R32KHCRr?<#s%Q4bRowBGsghRyL$j^j!R0qT}xjtc+8>})LTDBp4IDD^p3z|>`I7FVg1s|ID32D^01q5Mk-hmLbnqm zp@sc;6Y2~3BCRCV6VoiRjJ0wHzwQI~fmH)T!|InWFG@;+MP5^}UegW?=#Bx<^X?QC zh?qq{e>i~wiU@T`IrpSJ4s2Zd#>U^jcT4yuAiA)F0wplrSdwo9o|FnA?hwf?(d9&9 zZRP)ZeE?$YPb_~1D{p6D;T`!l)d}4WXotnMwfmH*e?L{Y!O^DTCgL>Dp)ZGVxe&am_jB z9ZrDduy~BmWYB>yFaaFeG>t`ol%it&PW!YUXAPu@<-57~%)Zfjw-t5Z8%zOKEnp3$ z`uiHld~X@QCm|uxQ=>A_CsB+6_x8zS4}JsWl@$T{6%GK>iucN#N7tzgoDT0eIy%~3 z7rd%L`>->fN&^cba0H1C@@ToKd#`H~KUx-NFx(K=yrN-HR7TBG#cfFU;Zs?3S{G{2 zpxD9@{nc#SpOu73CO{d^MkdyATzY@Dt5tX3C)iMXt-_@K|7Uw8cxmu<qTN+r3`%He2)+6kev#ixz9cX*+`-J2+^n$FH>xcUiL01?-)iXMbGaGWvA;yMrVKy zlNLq`p^*}DrD8DC_07#Vi?f?mSy|`C#;)hJJ^`WD8u1yToP-w)XSKYxx~74VB*o{= zZe3-3$ni+I6KP<`0XC4ia&>*@3S46p0a$@hPA? z9)cNYv6FtBrR9S(9reWQ#Q=Oo8&aa75z82&lYIsx(uh6STI>V;ic#rz7ujjxFDoIL z_j@{_w^nKKs+1YVP6z<3mAp6@M#jgXE``bqeZn)C?r}M zjgkF|GSPyEW@K++=D!iRcmfW$uL1P3)F}7e%6gN1tdmtH7docr=tzx4;!-~ioEjiH zS=5{gJH$+_ z3`ukb*s15r$^LDe09JS5pi_gKq|<{7`u8OGap~>YLzan zjdfatzXw>=;^LynYB^VajRQp$*_lBKNfeqJGI#TF-gRvua^XEka&nmn z-c(tbxsLpz;{x|%%B0vh)k3rT1{(mlN-;L$n zZ<9wyS4zJs`fbj;$bwo9V9BZxSLv>1n2z~lS68A%1r{LQO!4N}C`S?=1}-NY9he&+ zSv2Yj?fZ})4o-g4e=boj>`2~HkYoYQJx{i^)p&MN%+=rp8Rd8pPVmHMmQQJR|G-o8 z85S-7ImoeTs1#$u7?hMC^KlFYw#_8I^1PW#tcG+c_f_iD4oF1ee|D(@hgW1vH0H^yJ~<} zLDsgk$f;c;{68(gZMMDDNyZSs(?q}sdZ=QyBzQY%*nlbo+)MhR16~*zuqht!#LeyC zPt7OCAC_=$7?|z^zyhGHc|gK|F5R_$ztO8YTm5(wsBUbA!*sQDIN{C2^7f;S zqxESJJP%xTK};Wb5-~lberccp=imR~z=CV_bMW%s@VzG#A3m&4;b-NEUsfirD%CILH4)wRVk6~ zVhnx%Y2M~tHWyRFl9jI%%K&H9VKep)Hm+2R0V7*NMrgjZra6Q@rTWw*B%fGcU{Y;( z_*X~$VDot{)-!_35}AHIc(Gi$zw*D&SKAqEpR5F2Kx5wq?)^t;AwGqJFh4LhX)t2u zvw@j0a3abv5Gov$D%QPc0CNFG41nW6P#LqE3l{6O4F1}E+A(&XTr;FH>{h=B>X`S^ zklUFvb(DZ#s)ZZv5>yN<goiD_bKnH6 z4g`#ij%pWrS{Y?KV5u;)0IpC5(ZV=79nLTDCnGrm=qZpyF$5^-fQs;M8NDY*qDA0! z-Szr6l89nhEyI(tv7{UODd2Pn&bVUabM5|kjQaN(5V#e3+9*e9gtFULNhG!$s#5%d zf-cb0)5rF;r;-@sGH&N`cr<%15u9^h5|?uWC_$Sk*U#3gfO=1i#^XwepbGfqR##R6 z+_6FonJL1Vd8cYr!Ds#b-WIt(_epcvsS#c9ZDtdT9dp)a*N@goe}KFb9PtQJC!l7v zFgOfELlaV&zD*adP=3iKaIH09UFU~K(AEG@tMei?bDtgWv>jBJI+sRm@AsW6oVD}w zjKbH#@#oRX9Oe=czjcED9FzL{)xp;6hmKzp^=_gcN9x%zS82)Fhv)II?p2D0BfzFW z>;1n2j>iM;y1%idr3IK~5{X^)=h0g_wLD3TjEovrMr7~KZdse4YsAvu6N_TjA{QcA zxp3)h2sl=ckz|a3hBY({35KZhj8HBppIIF0$gVx1` zfnjn4f`^zJVBzdv>|g)z>h@FAiw}hPr8_;BZ1db0xlvM*3AT$Z+h(}p>3$h&L8SK1 zPL1&z5aC8ITI|RGeo{T!^A$_e9UWK5U*MWB4NeCG6Q0KQ_4#FMK6Oq;rGtZpmaWt+ z6&|Lj5b&j2EMBV}liHMbH{C>ubN|qJz&c0mZ*EXqb>PJ=RKX=jCo2NM>&h`*2uceD zeIFm+&b3}E@v0<}VqJ)z4W^aJoN&^xqMH3vKu6&qu)G#x=kgTqNQWiFmr-&OPnE@nOm2NBk)9RjG5Wj zXU|UT{ECCBkB@eb-!CsO@9ez9KWe(Ik&~APrbKN%w7Hxa?2_4tcH#DN1;_E9>&F-@ zrIEZ28em700WA<_OnU;eRo`w(C+~g!%m8i(A~nPf<#P>3ckOL)#AmA>VA2CdI%6@k z8bB5Sw!E4Gn!M_~>aBCe5eNZ(86*oo5EISVi&PMkzp4JZcW*LqjL?J+B)>XX1#Us3 zH*b6#0vy8j^&m>yuN`Ilo7SNE5m$Dt!F!j_D`WT`x&FGnb9}S`LQKeNJ2eT9{aen- zU#=xdR!c+)q4|+ms#A?0o3~&vx*Z=V-z!#^=#44{+%s`sg2qt8(QakM z;)v5NNpENS0)YmUka)AN{Dw`-pT>bFn(Z%HOQ$vdSZm6 zTBAklTatr(rupfd59<%?blX*kLM5Lg)~ugA_EbD$B(AXgQylP>)y$S3lVNqnSvfX; z_vKr+!zpcW0Ry2qAe8wgtajvE+F<*!W=MC${K_fw|Kjrj2WEjybtHv;0*o?&W73r! z5S#sqkd&GCyoV>~^zl8hI-Nf_k$gygC0ZGQMlGyHr+FwI4v}E=QSESulQRiQB-B-M zCUoJ4U1XJ>JqzAjqa^z9?iVv(ymS$?re##fPR^EHk^!xDS@6~2r0@oQBm&goG$$^w zxA7lccu-o&TuLG*L(-(k)%`WI0khIq^ zNEQdMc%;!;;c>faY#F4v13ix{8o^({S?JX&;tJet1HjVmg@AuG@MeMxI{&;07XAJE zl(NdI#HCATwK_m!NgnRy1$zNm zf#QDN5&8IzzrU*t*W-ZODA$IY5!$q|^G~KJap&T8$hk-Mh2x+_zrM=5?ml^o!o=(r zr>S93Se_}$&G(>i+Q#Y@`ie0`h4t!>6TXUj7@yI?)rHbC|1YuKcttB$*8AP*=a*W9 z#I%xj{bo8hC44RwWw7!0)^7On1U`VLa~Qqed}F50!|1+R*?`Luj}gvL{HUvox68NF zG4C7hG%)!u7J_n!@u9N44-LUHeZ#FD7j(QE9PHz4J2K@%3Airt^2waKiktCKmq*a@ zo39mz8<#xadjuUMJo|7bcZ^I<5363I@It?S4rQPD$)muG<1W;rejSo=$~NLhih3=ASd+L(@}KzHw@?=$=ErD(oKC!qqjUVZp5g%V7T zHgc`MC%f)PiGq^)V6pH|j8H0^CxCBtn+_;&o~8`(2)@cd3cQK_**O`g+N-*kQx#PD z6>JRSp7GOmkH-W*S^qv0)cT!^ztQ$@PyW|5i}glFt<+D9F7|H?9DfNo28J+>R-;Sa!xFtRt*7P?>}ohy z7Z)7xg!Kic)n!C6ayD`2B=c5b0C#es;~$Vn<|%k7^hq-lt^FuJ9fS&Lbte0fOGco!yIlMh z+=HD4@KikK3oYH=mNDwzy1tMtpb#m-2iQ8R~-;el@}|G8UE?o@vqA1>+eU}0}~8r*kDbas>Z<%T{dotY#!h(LU3~x#pJ;OVntwr!dLw|H(p*dF}bWAy$ZUF)WuqU7d?a2RzhyScp zx9kmFBbQ8kZTlP3_GoTDZqPSzj5?&_A}mC#ga}k*U%#TkNo@U7EZNO@!@@{qd$<~D zjl~l6yG`{;%}q^NPF77*7FhBvpgD8If%y}#EH|oKw}B{AWuuc7ph6PYAgmcy+6+3E z@Oi@*L}W$5;-%||NGhZZ8WE+duZJa*&o=Kmae*w>&!19Cxwp0J2F0R(f_r6M{ivJF z#JoF@t$29-cqy2-f@m=EiidZV;z~TrvDkb@RR6ae#dRQXHpa{ho$%z}jp>QE|3O;V5N~NZMS}Tra&*CcP=(`?;)h zR*Uvx2`*Jg0a;9ufJTM{R~eU*S6pSiQk(Tw9LYIn`la|Qi;D4!ni%ku;#|9-5fboR zG*7eo*fpIZs&p@ZbdhXvwAOYwmv{8%6lL$|fcIZj@SlX^&F?eEUGl9s?|*_1CW&BB*yT8YSx*RQN#UcK>t@26W6Evk>i;25FRCp}vRuX(Q1NyjsG z8bs-VVStN>k`ZcDQotGJTw}WOQ^KJ!geU4)71#uP$UJ3+8 z%r!EVUJ_U&ZzsWFh&6mBK0^#1_3cWV&zH40;%7V~qq!@;vUHpA))ledx}9yethvFr zBknZ6y@EFYpm@{uva<4SK-=#1&#sdcAELtLuc`L$FCh67sqnuLW_O+u?dkCSsTrEp z@((VwkW*QdGhMHbxhf*}A9Q}W*kv$%+TPTVPRJf=@5E#$cX4V-SeRlzkup@#%HEg= z2u2%x=DbpKqtoMKqq!VmZXXaU{w5^~eQn{|=A9B(S67^= zSqgJ`<_7Ar_9k_%odcXjmru%iP`i40;Zem{T{UH2W%tP;Syj?SX73R5RybJ-uJMz_ z?=-|z?iz~-Ap(8j>+fqHo-tq1)gIFQd4AG?Xw63Ox^R`>0=P6B!l|D|{OrVHNn3%B z95=hwgSP*a*Uin%@%sJXyV7N~|El!=0?OsekgM)5hJ>y_usad7Un8_5Cegzk}tE zY1_p%E?F^u%ui!cMl6Ocf0GvHXK8e}Zb_7XAu=-Hk>@H3!vk?W_-=%y{ z`I84VlkQJ|)7KYUVMdWj>tqD6HbC{G!@*P%#Vk!E`Y0M+nr1*M}=E*B2T&Se?)tnt?f{iJ#sFqh=vuV5WQ5V5Wvpc}+yO(xjrZw=fxBJd* zpUGU*uU+N4i~HDaMNcD)lm?5&qyzH3ixU=MoqP_wcU9+=go!m0W{*#kcjdOMN6y^L zI-e$C4wOK_i%l~DbKCO#oOzsnt7E(^bNzF6tB;zHQgv%<=eN#a9V{E+_}Gcd*;NwX$eN zPK`2P9m2g`LxqEyB&=4^0?Y17|F6tH%iEz!#5}ZZa3z2Aer9`jFz(9`jaVKl= zOJaBY)ION-F6-U;#;WJlf9Kc!_Da3=eXx;RGkoOBV8-c8$?$>|9|uzv3{{v$2-K4wEA`9+%ck9(cL$} z$Dtgyz8ecSY?gNq>gwu_H*EolEva&yBb=6)*7DLcbGvJ}lk}~pbK%;J{_H0!z)DON zLd;Pp4x);^!_uUFDtq7zeNZSfW}OhaAg za#jn~_jhew>3r7c&ZLKJmipL$f!I>?3-Sqmz~+6O-^_OI{n;MA>? zg)Fqr+^Mv=K6}x!>=Dl2woZEE{Z{qALuOk>X#<1UqkocWfa6*>^kTm=UY(4(-*E8# zrgE}JGPQneEDgW51@h5!1*}~5^xOK8ZR;vdKKd^KGm-~6-pbaG`paF@adDxz4*?wE zr_S*~h*R*>VIN(PMnMb=Js0pAuXJ=7QOjDxio(c{PR>43IY)ar?<>wH$+w!k4~Lh` zsQt#8rsdGeE3CFyZ1tD`0Ts1tgZXWXq;Dsg%XRr~EgDh|CnqH|!f>Ier@A!x#OVW- z0jP@;%Wl`OoYWEfS5zP_q|6m-oxV_CumNPXzZc`O&gd}Bcu`dEX72buVK*Uv4qD1) z^_1=chdr<9_g~iQotz*UvHyDTz6rT=dNw=d1<>;>`l%@^i(duXpL&mA8tIF`^||Z1 z(ZBhWguvP|c7ED+^HbCzIM4g{9h?JvaJUi?2CU#x%d_?X9a9XHVHJy@F}VuMe{J0a z{sZf3d0>$Bxgqc0PW{T5`9cQ}IfG64YMUmO+m7~4V7;?mPSSn0eU@hHnfDu?Jpaw5 z@$tsp;NLWAo+~%qo=>-aS!y8ZTq_V8iF!^&CMounc9Dg;o#9$9&KjN)V-YVzz)d1u z7%kFA7W;7k%H90)*N|D~YsPv{JfK;!g^~*hmlMFMOV#IX*ZB+{(z_^5Av#hrohwuUWKD@GBD{;4{)&L{H!lnTwbLxWnjg>^Aa<;0bMgg7p>zB(#$z&ARtxE~J1$0#Le3cS!L@`ohqVX^Tx>b~c>q zuC@SuNB|Pz(*K$&TL)_=l|ivZgAfc7;G;SFVj24+cB2aIaj{y0SJ8j|?}m@nYny5^ zSi3?{4U>{ljbNE;E5B80w{j4{tPLw|rj!RYCItyaYnl6cAjz_I8)Jy^@xbK`TV1j}_4p!Bb!B(!nvUsxz{_fbBwd>{rf* z=vqZi<&5_Czf|}X6L>EW)jL$XdbP}^&pvNz)cxF3>s+%z*ERPB`I{|g5!m(~lJm1g z4w*bfVXIuBC;=-hHa1C?5uwd(hpOqu>!%SJP}6cknWtO#;+%v2hVybAY?mC|I6e&i zy8K#WcOoHpbIn8j)Q_#>-&;Bf7sl^WO70@Bs~wY1Gn0z-hA3$*Hnt+tc8{G@xA!_b z&Fj>L?!|s7>T%epqU%mJD;l;yXfH{h{5o2dugj8(Ppgx@c!t96S7k5z%e^|_ z$=!0>bXosF>rBJA>%c5x*loM2Z-@8THh6S}j@89q9&v`t~ADz>1&wam^>v~>&gM$hXZ3e`Hot+)|_2Gin^=)|&u$~~f ziK!8XeGuTtB{PCb8K90*DJ|{oXf)@sQ3Qf$8yS6Qne7tO;!IC*Xe_*m+wfrXDL$D^wFoA zSY+{wr{;Z=E4L<2wB>Ppc)W^epYZum=E#_eRrv=LPgbEODVvvG$UH<{AVHeXu~phBqcdH zx>#|Yr%p|cZf1Skrnopu*<#H)?*Xu93mWR{Jt=uK$~TD)T;3G(icb5O_}4E8yCu`9 zhwN;{lDY7HW32dKR0d)6G?oTtd{54X(p=?jB4V^V4RhNDKl=ND_7m<4cvH?OO-KeI0#(S3 zneZ>xgTpYqHi3PWv*Z+lK=6o;5F;AZB0>=LXFf{uMZTvY(lYw1jjBhFrRw_iJCyl9 zJa9jJhAS0xCD!jz%0GDI?8gV5_wL=mPpxiE{auPn zaq+<)Ng^emI>n{9NY!mL-)yShSdLVq49qHjEUj>xrAC_n<2$N;sK!p8FNb_?_z!Eg zgyBm!!IO=nMnW(WY+P!In;kMPGCpyi75j=1L+Kj}>85&p z#~L&jJZl(SxgFEx{^81cTN~UR2g(FnwPX{v!x}SU#9r&HcAv|vqNiP2A&;UVH_i7$ z&vaP9Uda9;6xdh1DgH510Xs{&Rm&?9n5CpP|G#VFbt%~`1wF&@)tg__1#-yOzZj8F zI)3p#Jw9ArE~V%8r3|N%(n7`Zo-LoW3UKr}YpNF`7<*UUAeYQ79|5%4EkOqaW ze5SG_aa>XLKR1m3qr1vo5KI6vj{-NhQph#fF87dX@=wT9o(WGj;r(epg;T+sRqcH6 z)DF+;wtLj{@V@m~?T2bFF01j^oqus!VeMYP+8;m`-FGSDIN`jxQ5P^5!f3aj> z(&Yxe&dascgzbyWV=u#NkuiLn0w|)|NiICQ9@^zvLcDQUapD;=u2|a=yQ6H_z+L6U|iO8m>#6=sI!)5fdqGtQ9z1N?b(3c39zU;1g z`#rwjm9N<;85BLS*;Q~O-E)kA2z80?%sbtl=`yTFhvZ>U&Z{8+)C>aP)>bk(NoK+c z8JN`NunK3JSq{n-R3eupwky=l;Y3f*71N^DnHeYOZBHmaXpNCnLzu+plas(lb8l1K zZv_TF0n3rqef|BCrsX~E!z0UcJ^_sN3#}>CjLM=`nkY-|W9{ zMLi=`uD=Frx96&+(<)cvX{Vf!8KB=%UVBjKxlswSH9656T}b?e)C zVsxhP3^{a&TqN2jU!Bl6r1Ufg>3W?{v=tTe!48bdZTe9Ro>71^zizZAqaY~ z4o?`q?rZw{Y}@|ALHpT<)lgVJm0mGFv`+CFYjK-sYm`b4kPAwb?y>tBhB=B4)VSm_ zTv_#j()W3J!)(>t(2`tIT3XiGZ+w2$J5$iM-OE*{S?lx>br7(C&*}?MAU)|dXn3E> z3t~8Vag|?UOpBxbn#|4zZ0vLu^t?Djfv!gJcfB>(uY?*4c}1!?%}vykEK;dTER>*|kH@47`~ zZMu$iKdX^kZM}dXl1+K?V+`1NxgY2ZPQ=i-#`9LXjh&OOO zU$;`p>OGmPEc!zw)o_AzV>K`uiRTtQw2nj?Jo+NTzIy@fib7ytV$ob$q?=BE$4uvz76A6PoY)b?d(Wk=H5UnXbz#6JY7_DfjH^p^pCFzMStVziyl^4uOZhXdkM#B{?kwq;nvweLg^YRU_yM6H< zM2=XEk`EvLQh0cHT&}29ZLdg-?C&vOB^h&VdFlTyo0;(cmAyXbvHq$c;l_;{DiJRs z4Z6q}9|zYKsrAj_0Yx8C-KkvNRGZ&t(>FYG2QY`w%UKX9Q~A+Trh%CA;@?*5HPz

    DSf81<8Xb^lsoM#be8eR;RCOS5=Q7}`wo#soU-kQ~VOQ%a> zyvZe9LtX1j#p|Y|o58oDxJikLumTKX3?x6-yQY3p2?0eq@0E

    9WwH6K~`)0sHpm$^z9PW7m<-V+L0Wp zrmIaiRg1m4>c)aEvSzbN-ZHP6WW5n@mhPFpA=magH+L%1+hnboEYxNsrj*PD&!!;4 zN*%W#0qqzfx@JF$fK@maN7%r)T$wuH@OOZc$)$RCjb3r(YkBb{GPPu8t48&>rH`Mr zo7;H&+5bA_rb9Y#H$aWTyUcRZ+*TH)%eRp}p!ouQ(aV=+~ z-qljpTA8`=DMs%EMo z3tteKY!&1YN;vMBF0HK|+HOU##Rjv5bF$!br=Z6;k3qz$8Q@ag$YFfRwVXE+5=iw= zR6@3P4RA(f2lut&)vLC+QkjRd{i~q+HjlUA+4!=(#xrPv@0y!)j<*@!HZQ)xri#2{ zZJpgS&93?mc5T1w(S4xOU^%1=2VM(rgXC4>dg?tV_D!9vr20i2Wkd|5)ys2Z__b6i z?K)NiEg`sG{bz3k+`sSF;xp@BvFg3M^J&?_Yv-aE)wXmKc60-*tmF2{Vd@bvcO&$1 z!e*b1*lK5H3dvNkir7;5Bno;?aNKorrDSDOunf;Z z9=U`W7#6ApuZ@*8alG-{P+>kZSY13YpkY8?X6NeYc+bnm&%xdM z;hVmwBJxbQdLOfBL&;~%QAm5!JN#N1oWdE<+&Ci<8eiKIxwO?A_3onbSn;mZUgq77 z&k4mA@v)R2!O_&4YDXNqr~YFW0SB!pE?K}T0`b2K-jdUxi&I~On(jTdEuy%8ReSF9 z_Qt&5WP0i?-%BmAj~vQ6&kF}k-_n(x@Sn7<{^8U;IYzIrVZK?AyZ_A1|897+O6# z)FC{ac1V_ltw{-e*6XR|!oGPm(Zx3l3O=h{JuZVE#iXQmM?)0fQcC-#=hTkIG%ppF zR`@JaSHIIUzw$a^H50oV7uljyo?u&RXYKTB^jGy>LA8S068AH(N9_-~$XyZZ!d?`Y z&Q-%d#%|k06?UX%VXd*&@5y0edN_5p0t8XND~3!=Z0KnDlNH}J{mG3{iL@-Nk5_{8 zYp&W{$jC=khaRxxKhiSB;Yj#Dq2n6sgk0)NTs2-kv zJpXa|O$pgbl4z^;EkdE8Lw>WnyIWI)0?vOgK$M)8buS>t+vJmN;(n} z2I^j%E|rgYPlL$fgh6{AnSj7*KW93Quty>IGon$nbnJnIL%ejO5mSC+lmJL}Oh`z8 zM`FD_%Jm0BL68EenN>3@d3j=Xuj-rVokyI;vO?Ilj+q);FJqB;c$4GSR2Kfw~*)z5GXM* zeYRTokEic7B($aZJNiD%>T}v_P4I^`mPO^G%o~q!4FBbEg3!;=Ys}B1oU}bNI>TqP z_OeG;`$e1Yh6;~Ex#@6Fk zMq0bEB!$0KDEjqOa?J3vACVGsA3x$++rUWyakJ z1$rmB8l?>!o3*uDw6tZr4yOKmN6=3L10@3y>a<6ca2mf&?t6JHH@L{V{pmQCxKqAA zRIOfun2p7^XYZfJxD?UBvL`2Qz;-Ec~Y$a=CKSBKI4M_onC-JV(}Arw&Gbus_!& zFJH(wp~5aJ_92wzWTa{E%{V@_LqYHD*e!EHJy95jN#l6qB~#-9_F)QM$ zI8_=LAh$Gcd|ws)^S|5j5P9VjWBvMkUXAtm17z-~v@ls|@_aYnsEd z+@Tpgn7lwU>XmjQ^PvvShyEhx@|UlxhUVO5DSq2)f4ttPV7GVA(1BkGI$m#YZ$RVE z^p#g_-LQy^AvsTg!X^syEx+@;8g-fkQtOQFc~R%eyxqCm6&`OFRkX} zRzPYb~NTZ>^nM}JGcb|%i)46@>*4zt%8fiV9Ii8z;Zp0_tIDT5rb9-@so* z6r}?5>2iQtam&4Z_sPrcao0KfY_Y3S6c@ky%abmOZp;1J^t)d`H9=p!*W2BF-5d*x ziTP5yj8L~>9}cVX&b}+t;UQN?96YvmtHfv}pL1TcMk&?MWQ`s6x3@3rhe|L2Gpce?CitC_T|UR#061p`_$JtQE)WTtvdMV9WW` zt$*?nLg>;Zn2tzE-8(^(#~4b3j)w8r6DB1B4H0qf(v%>^A*c3c?ag*f1}$3O5dEcD zi7~Y^r*jTsu9g>m1#^x=J_@8-?TtQTZf$F;<7`cn-`*Iv;L|Ve+1pgy{tof9P<6Kg zoh=7Ci$@nUJM$;)xeV~cK%`PhUYAaq++#p?gz$KOG%sG?@|#Z;cmq(M$&N9AgO>`8 z4BZFssg23&DV!x0rA*v_iFTecJ9#pH5)wL3L0Expb>WM_hbzqcqs+t7n^bByx$SoG z%(t)STRD}Ppvz}b(Mse_RdDj#`(4vuUCv#-`(fOcPy2TD2>O*~Dwl@`$hD?RmzOI@ zk*h^EnX2NkcdVQqK780(VKjPe()}}xE5Jsh8guznq;vTM?8xq7^92R3iyCDLX=ZyR zNKYuCG7=3BgZUFhTccHU>qD`K+4P#MS4`xK2(5^ys234f%!_~P-Y6Qq=NUT4Uc{km z-`5W+L8^vSH!Ng=XHI!a;5u*G0+GA{ z6v~(1Y{}&isWfvh7;vum!?WMbp)7#E+$KKHqDOPM1~!#VEaJv^i{RF6fBYMl!Z>`w z$?V|z5=KAqFap`omG*J+@W*%J@(PM#3NO!Tus4>>D7W~a58DSKB8-S+9aYLz1QtPq z8->%KTvJbG%nZY-rji?@$wZjKR#d=xxJ@R64?3$u2mwb&N7Vxehom;|%J89uL&C1D z1y?70#iL*IJue^jo`%G0(6~UF^h8a~&4MnLO!5cQqUoMuF#W@28~Rl3>lrl77x~_^ zw1G9CEl>{Ae28~VqYckwdKZ!N?HZfjp$2sp#^5jw$K0}a@5JCb7ZZC|QL&xPvztdA z3jtSZUtb?gs`fV1_q|Nw$xHw3k5#9oCPOQyZ3q?5ydNG9Q=8ULlauyD4I+X!|AFn1 zjCQ-!tB1o4|?B_)H!-Wbl)_jPo&yB!WUb6&j3dnf1^ z3Kh&NZqRH;&C^jSv}~0S@pW4qi`!pGuWFx;58*f-uo!MZ5Lo`k^)0TvSlGO>Bw!?_ zD00YUcc`3hQ6hbN<$fK<=dKs;E=DPCLk4hywDjc>r-&Q{6N_8+C!pM`*|2lF=X1~P zenID?u+ZRD#Q>$BNwxlcw=67fncaG*^ZGS^6S>E^9Pk;2J=|RRJ*UVl)~^_m>a0)P z042(cP#p}sdVV9{j$1UE?%Ls3jQr};W$k(meG(H1&TlRW2@U%1*p-)eGE)FVwOU|q z{yRl>z{~v9X|9x{RKLmK8<5i+M}Chf@SF4q$dyTky_zXjgV9i;F**r0|32rH)h2LV z_vf8GK3}?CSU3W|%*<2DBQoc+0vXxZ&QC_3YI2jHKTo|^Qd4(xwaGmqPN3_FB>FI& zUVR|>Dt%NsS_yF&O$)PbA+=H@nvi!;e&-1W9?W$;B0uVAlUZvexRMY}#Ts{YNM9u~HrS^XJNJL}E z4r)s3jb{$iK{h209~KyKM36f(hf@QG{F%>szGkccAo?37h}nG)rhuRa)|5Yz+Aynp z0ziRczgd7Iox*H%B=~#W`2|jXXZ7dGNDdM6M?g{0j?p55<0jEEug@t>!EXz&VUVV& zP8t5U-b5x7u_or`{t%fp_j&q_Ddod^UpFTwA?;4nq9c$Y4kYw=Xh%W`T3T8MnoJkU zYCJ>0{JMX+SclW9Daqf*#;?|H>YT_D=k;(t%?|(SoujZ1iY%va0_k!xGDlsuJ6UX0Kyx`{R$`N=t&&nd1_u0I-XYx@>3qK+q%VGms zYiL9`vrP!FxIst-@jZ)SyN3K)h_No7Ds%S;Gi}e~P%ToIU=}rIx8^-YM{}IZE=M|) z3AORl!$;n9Avw20pkghu+HdLGre=o1*5rTivyvD7+P~HDN;4dMN)(s9A0&^#W$N_# zw5>J6yBp2-6#WJkgPnWD-2W6;?VmS~v&EQC(&;?mY&^8RcG*ES;z_&EQh(Pe*742| zju&jImx7e2a4c_A*4B1*277z+#1dhl3j>ADN$J%Vsyan~Ih1xZ4JlTNRKnAs+i51a zGcdL%L~$qWvFeF@Mp`dT`w?`(oe$j$cBr7mQm51 z8DF(v+J#cFIk?+tQRvew=t>owD2^qt@(@4BP5OsCM&c&&+mBc=9deDD4Sg#wO0*sx6Jx!Zi+=_ng*5ER^_p2wV;vak$6fhy%6jf&Nb)iaC-`gV@#8 z)ngH`3(({GrJ1R+i>msF`sLfWG1F|~=oCx_^(fQkX>;fzyzlk@xLC6_yQ{n3;h> zf-L1Yr6eAt4glI8yjd8Q>|jfi_+V73+x1#m^<)#|S0UP(gHE2QRuAUssEa^ijIhZz zUk>HS@dAHRZD%G|(JK}%zr>*tx@cn<` zM~~8rm?@NdPVQ`N_0K|j-AcV!*Ge#lx%bq-2;cZUh3(0K7b1_o!yP{2J6T}7s)0;B z{OIZsr&Uq?`SW#ZDUn!>AiAN(Mu%#{OG4aSTwG89o0xxcg*YInC0cwYDiNb_4a^$* zc$6O|05))fHDSWU{BEcR>NpZ-bXYL!5GoOG8zb3wh{cvaD{x?FPBO(>)m)?rX3Mvl zG%uE)shEwou7lU*W66hPelH?FjC9FctHlAkfK3(kT{+9M*=4aA=bUR;z#gjGCG+G9 zB2NGm=TrYu1NnkFIMt7~HusL{X-;MdgD1P2lm-yj&dj~)$y(UU)n zCmR|VU`rYJNQdO6LA-1K_hk+9Is4aSOc)=YJ%;n5{$Zw|u)HuXJX=uAi55Fr&xxNt zu6yu#ZA`#GjmQvdl9=xV1NVIhH;34`TmS?@`mt4^!p<+|fHBtUzp3G3S0{j0j2wkS zKD^z~(7{dF*Z;)GD0bpx0Wi{I{+N+LyatUYn6p!yf?+8)oY7Hu<-=_a+f* zpL`(a4HKJ+CSWzhFJE5$BNDI)ZL85sk=;&_xXkJgWgU~V2HD=B@510R_kC13a`bFu zyT|G3@!;x!cNGJ$Bs`OtmL^nSP=iydk<_-15L5{ISXx@~`Lme3Jc<3nHAGGz8yCX8rFH_8uu$z#by>kfZhIW%!Nnp89t89A$yyS`s?c;ah( z`X5qnb=z{)yo>C5s@r;J`FgzRl(WW=>5n7SnrC+pDIam-?Y+yAYap>EZJw8OJ(aw3 z`Ai#6zH~qif4&iQI`+cMS5Mn$Udt1u^+YAw%-1gEKezo|MpjeZ+O}>DuX{b*4jeNQ zOlPLiUJtWx)nC0$Dc$NtH^p@~+`@2($EYyoso>~{#Uu6EOdNe=Df889yIBHj^8@P} z^h9A9AKkn>Kj<15YM$>;!N6^*%dwRoT8{mBr=Zo@vZA%*FA2m1Jh~#U z`6B!E?0(jH@2QU3iy&iATpi5^<)x+E85YB2s!dWwef=BW=2jn=kl%N9`e5o)lAo*` zz<52wj2vCT#v7QahsQjm<_YrSuyj06>6KU$_3%oBdPV}uh+2CS)gk$zRUkjSFabdC z8>68~gu+mgYhWy1n58$5oJTHuEkqFn(((gQgIB>x^80%t`+u9G+B7nZ9S^MY4a~%m7hEqW^EZFnE5 zki2D#}xHi`#<|C;t}jk4DNmI=T|Y zlIqU*^n5+^pV8vhwBkm}{(_g|Cu2?j$#EY0ORYm6y;kdEeD0lcqvD#?R2j5t$buML zMn$ZK>c#m2l&}6@ia&D>mCp{zQYjMm#fizp_9*mnHjghmY8|6~FA-usBlp9h?5Rk| zGn%KS(}_$7gAS#f2(xBEEQT*n5NE`$hvKr;tgy7>c*fOS(~NjT%j$GfRh5nvhKS#< z%|lSbywAusydDm3yJ;=21bWXmb=<(8%fdOC8L|KV?ot@)_aTm7~qbHYP9BvcYG|eY}9o82xR6ii&06*DjIPLHz6}jL*?` zIy=pMYQ|uROjF`Lp_BX?PA-)b8bLuiK+T0^9qfQbM5Asl6yU zbV$Vx9QC3y_dNS%a7=8*-h2GG<;Irc?k}Dbe;(+~6uP`w2_a=1&Zwa# zdH!r-o{=x{XxkIns}tc-@Epz0O{4pHbFB)~AqhxFeKu7-I_ulW%+9{P-rn2&rA982 zM(2WfuPGxxAFZk3RnlOuz;%g+6Wnz0t_kF@bw0W%2Fxo4tvvGK3r4uGhlSDD$ojXM z*^LRLxiw>-f~B~}@r1w0Ziaoak-giE+r(qMW0a`z*si>#w~EeJ?ybFF^P6)^4_J+x zzh@G82L=Tb4rMd&!8N877M=hy?{_Py>+hqpMwvr%dwuD9n|8NpR~mG8J9g`sBMYkR zbc)mVrl?fYKTW7ScmVM!CppGTnpIUyPME~M(m46wWd@@Yue_^0^4Ti{f*{gZ=1df* z{5pl$^9kyB#JMpu@=4sWQ<$N{d6=Nlqy|$>92w@^xaY{>8&pm}C!^1aKPTM*3fW6f z;N_fm1({OHy;h+Ko2vI7E^r=>)!}UKRFwtne^uNYSES8Zs{K!4YY_5WtA{NKiHoLLV*T<&T z*40Itb7fniQ=(<^^W`hrM4<+zL;{U6F9Yvkr5fYlr*wFBJ^}Yofl@K5SScg=385GM z*0r((BG#;>ejeO!u;@d1cMBRZ?lJzp8GdLaxmPZ3kYAtX;8 zbDZsgGP|Xv1+wCD)4Z*q1C~6g+G=7=Fu|)Jhqs}^MnMtX%&iQI2KB((pB~E)*3%Ma zjJoSfF5n|Vo?&=4G3z!OVbU*3b55Ll7d~DzTLjA}&=({he0`t`zfQ!y7>7EiNrbWj z_)oy^ZPc7sFpqx)Z$Vr00sg!AAbSB;fH%54zsclYgX<^xHFPgBpbiz;8xt`-g~z`l z>$BZ=a!Q3>8FH`5+BV?ugD*`x4t5nliLG33{Ui`}kWyW}HB~U~+RC=ivp=!#zq=Nx zRQtDks-GGbu7Ou(N4i&i+W7MBzpB+p7v}BSafq;*Z&w-Sz~f(=n8vGu*unI#A3GRO zRFJdo9@c)=^TU2%-vmWyAbCvq2uhh3eu-oPr!|UC@OPzC6Ke^G`i3 zo}y~6MAz5@eAC>*V)~dj_2l$zlep5zq&{1TCULaL)G-Mo6+Ho2)*Hb>!ZYU{rtf;B z%ewt7bTxju)9f?648+;Je=R(5s&B~pPCPy{??5V*-}qM1^H(qj><}-CkT-tk`cLkS zht%P9C3D-V7hFnBvvS-@!#gD;x>Z&2P97h&o{_TZNu}M?KfQ+vzZu$>ycex&*5EEK zDq>f4UHI{pmz|ZBMh~x#L}0!Jk!hb+#3GyNFlf9!gsleg@*zw0gUO;Mcub;XOJxtX zl`uo!;-^Md%{_`@_IKKK1qGd4-)F`mERr z*;^?oj^sPu4$teMi1Bj^Mt^b#dbYCO6}R#k2j2E-id#| zc@(XphPyFWXxs8UGJDbPeQD`gj7BO>*!ESgYMH6Lrel1npgK*oYbc{K62o}7)W#Nl z#};!o>-i;#i#ROmNfOWx4jk9$OomDoyp&Y;vaj!0&0>jAiO}jWYm6B1it?uHV%NRp zZCUGFQ8Y>(Txq;nwxyq{s`fkr);;)w;M_uFyDtp+>gxheS|g0`HW7=g85N$&5YeDs ze&p0ekGbE$EUNZ$Wgcx+wxt@#A7Pi3@O}czS@i`ag5f1jFnwpKt!r;oAjs!B1J+J=)rw$Yutr;3SZ}{oj)S! z3V!{Z>-E-<*}%%fY`_%0rxUQeHg)VtIrRvS`Ydad!sETcxaE5y@}6VAD@K-oO7oc3 zIo11E;LjnfnIydCRrTWW)jcDiLcM*vuiw@?!npIOpJSNu$t zd{}1gu}~MVGO;_%NoOU$x}cK2^SchXE&(gqJYCa|CuXSqN6;a>ilFmyub4e>N~`Jv zajgA6|Hm}|cnwPfM`=N~bn4uf zj;uQ>&ELO1@bjBZ^N9i_qiANJ;8OzaH!Xw_jX(zPISd>h$HH|GY)Lg?&IcXZ9_JfeYo%=@>KcyrPFq0Yj{;r?(k?vi4<%@m>l4jfh}lXE<3(x zCw-DGKdX0E_U-yY%&z^VGk=h#p6 zp8OD*Z+oANHu>*50$FIu&d6ePjn`JC2KSqCUfh+tKo1{>yG!CzMw;X8;by{WK&&bn z@rc97b-P>Ju?2MYRO%LZMoLXM(1C@Q;Z)-*hRlG`A9d6*G92T0pG~z@#`aJ&8Jsz3 ziUE6IHh}G_pPzh_!+BkW_aEPKDyz~tI-$6t)Tk%tDUXGNlyH1OzaHGgv)9S3d@q|V z5~oMm*t@yj(IsMA^?zHAz7o{<)hm9BK^zD|B%SPbyDKTf+YpABt)G_Qm6pp2Z$bwo z^ck&ortft@;XS%GJCNO84{kuYcIWb zGVfSByV>bJ@yDKB{D2D*rO6Xxie5Ko z$N$-;?5(Z27j#|kJh`_ITQ|@!1(RtVm^y>VVFx>N0$U*2>M5KvV=ig`K0ToU}}7lNey=Kd%va?J(pLa#-zi>-}j7wks;mpZ(sUpw$rLQ z32&+uxL2t*XU>;lo9I|11q#$JpJWDOje_7$Rzssd{(_pvPu~>R;-d?6{-0JyNKkOwo0&Nb0QnI(0RL3!%e9V3~mRyH5}e0%o_$a?|~xG$JVmeC6E!5<0%UHg~D% zp(rO-!-{F57M8UMP@_;2ON2grCXq0b?@Txe&`-hgE?W9YKzl6Qq>{|9cZ} z+l|Ba&##x4mjjcsMCd3Vr!~xk#((;xzqT(Q@Pmh5*rJMQ)Wd(G+}+*%jPJr%fWBHs ztXBy&p}s+M1$SMG?aL%pIywgBFf-iyj~_k%G{%9a0G{LTUgpP-9J1CbGM;v?04h8T z$x_KZ-BR7qEObcP*jj7h@!kEXZ=Pc*K#_l?nGhj1AF!5`zW+tUY5haeyP-aACZA`& zbWqIg`T1MBAyL&!>mwrnb-j$L-md@UbL2bU0HPxu9s4bgo?vHYUe- zcdCJR6^7(DVh<$KLc_(2A)y#B*UpPx!yyRoF1|(a<1&P8Z+lH|+g;OE5d2KqTUz?msd!a_JL24zK2O)o)rIWb;pKGsB#!UoX2-HZ zfv`@Oy^o!9^CrC$x2L3?uK(fB;_DPJtMOyK&~?zL*gkAP|^DKSU^v~}~0{iRDn!U)bt zD&7R0$=LO`+qhJwWoB*dZBh1j_y6q#mrGsgnU{5clvy^a(l`D1RGE|9 z8Rn4jL)*+Et+V-pLz8PgJyO6BtD+30kw`=3?++lOZ$JL9`$@y!QCaU&JXq;Hdp&o+ zHk_52+u~;8`40bpkZXE_pZyACq|6+DGQC40F3&Il76tv1hL;A)5k9MVcEwCU@jxEM zf|(l5D3gpp=a*3-Ef*bwqD9z3VRT0sA6n1p1{NubrsnqA?8O2(jWM}4)f$<)W<=$> zD#$+BpR&*t%F!s{l%r91!ITqs!yJw)NTHmFSfD;uc`jxZH)g{XJ^JN|PHv}jIZcj< z5V_mb*1fgl7wRd2j>Yx!yRJ!QWjq(di%5y*f#MIJK9xkkIu^uewdN0+(5FebBA7_Rcrc0q63A&GEsgs2$|oZ`zuh??Q|Nv`eNH zRaIwH+Z!7jM_`T*oj$NxbOXlIyI(tg_qDtvQvLYD5@Zycvig2pUud5#YJF8MO!_$g zvGQ?FAsl67bFQ&o>`|^a7YhK|2Ye_ z5)cku3IxH(mFTv(wDhp(%>Ht~;w{yG6E^94Tbcn6E%&S5$Iq-BnI*l6yloIpF>YqG z6B8zXE4{iZbmr)Ci+s5D)2Hfj86Uk@w`R;b0|jx=GSi~-1rhiiMZ(R)HPp9p2(){5 ztp@eCx9l@el}E0EDCA{V$1{3ntv1QmxhYxxa%cXG#}GyJk*3C`haI|8EOvB7%qfp* zPnNoj?17!SGg1v?!=&m5{*FG5&Ufa9w_jYXGt{_k^yx@rN&YX(O80wiv#tHDIsg+e zE+})^AMXC&DyP$hFZ(PmD>s zv%0d~x`+Qs&!dcZFioA^-27x)`pfSRX2S2VfJ6a#JyWQO%!JFiuEeY2Nk3GJfV7pi zfW77J{(I?u-9GQSon2h2AJ5I$Ny|O@_ao-)e;^xBrNesZqhi$ad=GztuT`)}L#C8a z*ta90jZZ6YTzM-jeS_K<6OYG3SK-PH9z`(;bgir0nJ6v?{t_W*Gn;S0 zvUt#~P3)ATnLbsI@Il?$^6ja|$MrwU5=QSfgvgk!aR; z(5#7nZ9XUxd!5T~6&d@Hukj*a5Qt#AhNt-lX;HLF6}_OMz#vZYlgS3qQ#>Px^5r1} z*mABn(nX8E2lQ>kq8H2yNh%}zxwrq5BSSL19VVap?Lw+QGF#eChm zY~PToouX=NoV=z_eXnzM&+L3eI9gWx2o8xCeH)|Uo0;>WtT#2K1;P29?~4h*m|%(o zVqQlkRuw#s7GZspy~1emIEFJ2&(P=^`_thVdZ^#Y#p%%%ss5ok&<8ZfoDKOqaWA_! z7Jo+hmx_Muchq(3JD2FsE#|+AoZlJp0OS9+R(E(ucN6wEc;@YAxn5B9*`EAciYrJc zHn-Q(ZEMwT>(1>Ef{N)@$^dD0&NCIRuep(G@aDaiF>5RNDH_4or4(evEjS-uV)VepYMn(fSWn2NcO?#=#yvkr8z*l-F$EBuv&BSkP@v?T<;HI(Nj$|v;=}f;I{{K zf&7T4RtbXe)o{F@Y>NSDD)3{klGZ%sgqv6bQ$(pZ9fxq-wffw(u1-ZZi4fBz4Pf#Y zXKl&8=P=FOm5|XOClZR}MKhnk46EW0E5bsTW_JfC6cVs~paJ^&>j52aSeAeBdiN)2 z_^ur1QP}CVj)Ei0aTc@0mlwutj;HaQU$$y~L7z>o7_YM?jy_d-UlJqrK~kU)xE2(X z^cVMq!u+dsaYe@AgvOFbt)a*m4PuQ9h!o6WLQ;CK&D1eqw#R?=%acPcm5Wr+ayPs@ z&jTeC^eAk#jg8mY{#$liMns5d5Sfk~dT#2N9STBIi%QSMPZMcp#Su$##a#|Ppx^Uc z9D^&ArB>e~R|2$vkv893KY^;lIajt?bj0b3h2Lt|f#43eGN~Kzc{uem#iu?!lm*EpRfDzLjhG zqrgKYk|w58uH5(6R?7ew?xMmgC8HAdva@A$rHJOkI{m z1&l>Ke^u^e>dTX6*Pn~{E{4OTVW7grem-p%UYV(5S9!J;By_7LV&+=;DO-P~<_d@9 z9xNykU#b3qd|91p31Kz;yF|%5m&sFZT&v+&o%Q#&CnFP)I3`|CSK+Gxd*7=3w#Rxu z)ze_cu30f@@&@8*YyuJdocQa+LWM4&qt)K`W+6tHw5GFQcWF-6_xHlLZ@0N`@r3=# zyAi9Bg~~x15WIO&7h*__@m2e~Zh#yq7;h)A0j|0(&3_5U?W z*P}xA=+UCu;95VQb;(?bX!_WsV=}>v8NA$^TD^3(%q?x;E&{Bip4SptnEbff%)`jXOaaW^&@NA2X-`ZHv5 zV~5k7JA6$Jt+fCJRfxS-NeE&9g(0G}6rN&^0LY1*IEeK-K(0C7zdPh9=f6GcCgps4 zq}*jcJ4zwBt0b#l)q_Es0GPQ<#xr-XTzT#|EsL+M5gNOw$Sa(Mw09y3xZl+87Hs-}EI@$-$aYhorQZ!;a(?DW>WZ9|9rigTgEycl{WMW8 z4<%Hv8%LV&PAKbodi{UdC|dLdoRMfIK-9QG1+N&uh{%E-p~wv0ABuJqM>J!26sFg)ypvfpb%bPQ^M5gWYGR zX1mIcO+emG*2dS6Grn8-=l}jqplKH2#Q4AZ%xsdoi}iHtZr$;Hh_niDy|>Iy@|vaxC?4fU@_jAcQ;rP3YZLGd z?~m&BU;cMYs{2EUkeR7zy@MDp9*@>1-W|T-=y3&Rk^g>NJ11g*_Oh-G`NF0t+FkSY zrI`nB}EEwRr+z zYS}W}$CH{@Rt6&rrY&}>t4iNh{Zf(kwA`QH9iC_3OoYx5OBSUHL~~frf2VG#;Wq&R zp$iV#NUV11;~Kg^byYbDQ1j0h_y=GGaZXH!)H3zxVz4ioIxH&OS36!cK`5zy@x8JL zPR3VejbZ8VTqD@@YK6}QCT0dPV2;2K25GIVdv)Q}^Gm%?G-Djf|O5VSZo$xaG zi<_a8cgNb)HuHH}o0((|%)+Q_I7Cu2x#cR%G}U4nh(F&hnj6^wQr1UNR(6`g6IFMx z8&-maUfnoA;6Q;rSzxhCCUDF6wiWMh6|>p_JQ-S>(6Nn;MeFX~X{k4|(__*)rG@ow zR{c}XHOFqnd)*~|r=K&qWl|0MpwjvMn1{Pe|EC4moSiLdw~MV^^euS2RhPS*<=Hc? z8&Q`{BF%x*flU>{AwZib?YUrCWGq3wUG0C++yEQzLwB0A>&!jSFHyGFZc`qX4b5%| z24xr;8p6cr^Mk!H=uYYsw={ubw2FTfn1_s2s$s%2uvFd%c8gD!n&W z>}bkSGUI_K333{FG5q|tf!CfVB95{6;*F~e*a3Ek!T%HfCTuf9y)F}cU;$I20Z2pq1soPtJqHqIpZxFGzH^B{JHZlc+L_d zXS-0>r+uN*qVE|7>Fs>TVAY?AzT;*z|uJ;eQ@tB&aV8 zbJ&>2RT&qsCLOrRt!=gbnH@|}VKVLm&v9coBLWS{&yT)wN}P$x7O=YV{nx>~67I<} zOd%We5eyhmTF?n(Y+Rrs-Gz zlNm7#Kvgp?IESGoE_%vwGJ$LU?_Y=jgb4MngRhTV5F$_Fh!Ow^XHrYM)%0<9VJ4K^ z^7jz4+z&fR00wnA2!{z;z?*`HA>nOvbN(!711QsG^N^1DCkR$-x*lJ*m1>}g$Bd;K z=7qsL7-Pk6UAW!_>0l%`P*TD0Sc*!3bWM|ZG}Ly*m0OMBB2}EK`pI{zcW+hu!E}lK zj3*3wwn6vvYi4F&SC=)0fYV>unw+;!re}E9@ZwBWfMb#0@>CJ?-ZwWa zp9r=4K~ek0o?|g{$oIN40anu7Od-#V3v43v@s6|5xj=5iL8t)G_~VLw|8(83IGjOt zWvLDInQAz%xD?J~Msb_?A5!j8lY>k3D$pOG2N}M>77Ua-)ysK#g4&h|1UfOQ^aKI< zr4@i@L&Kd8uT0F?$=7g?XajW+i~`!Q`Sd#c6`>boHhhE66VY6A1efCxN=E1%`?@U| zngnWXY^d6}EBCo>YAcoGJ`dNy)@Hc~3xet?S2`W+#5qFv#G+2-Pu_$rMAuR~q!oK`VcPomOhD*lPw@zo0vJR=~>ErL3dhF1xm7k9ML|D);5!=c>&xPKdyhKd;^iei#2Ekb0cu_pUe zI8v4&ghE1=q#8o@j4df)kkDk`QYc#p*^7{E6xp}uGr#9~uIrqC&bhi|=Dxq*&+>l1 z-kt}LBqKOk7_&fINi|L5y^rf5$aU^a!|7u3-BZJUa1D^2u;ST-{;R&X_PgU{1F!Q5 zMEYmS7_0M%Aef0}K=?@NT)tBK#@4o@&1v4d^P1Q48Ed}@Dz$P27M>?>nEA7fXz6FpzO_EZr*%-LqSeX6c0Ne z&S+s>z-ncPDL{V=557FmUk+_G2d-@l`#I-Rw;^$`(rc#YC)^f?mB1WYS-4x2cRzJ~<6^B6xK@9}xB4pRw>e|vb*~1jb^mny2jn>R#}9tGzb!3w3^(o; z3xhd&{3JwiS4u%H9y~D*Pu&BQ^q%cEw;`IQrR9pVDvRUopi20BAv z^=QDxFc=%4$Amgg77N4M?#1Oel?)6G0|mz7#-+;-ov=9n-2r-`Y6K;wbj~f-vg08? zG(*VY*Ux^>JZNTShLBHz+NJIZ+EyQ{JNoVI#h6)IZ@_Aa^_DM@wRqRNv-<-VVrw>k zzvOVE_4bxrDwgCq5y31)_;3=(bS0Gh5J$$eG#s?KM2tSoyLV#pK+h$)1CuL-ucafD z3j%kvtv9CSSQMFwyyt~hJ4y{}HYkA!2lf}^ScmAQVw?Ne61hoq*uzU*je9PjUc|I=~4Gk^rM$@{c7eU8KBwA*k1MMUhgZGoc) zHgU^ymU_i^ZO06}v$|Y*UVe|z_Q_HPJGXvJ_BpEpxij^DUf8`C!o=c!`rce$&Q}av zJhIbu&4Ih`7buWx)~BqG{l0cOyEiMW2=l^5gk&Rv4|;n6bxfDRUB$z?Q`0!Sag0hG zm5+}r z(u+aYc6N3a+BW9Vf>5s{h{T72V2Vf72o1cX1(kmrRZB}WQt>%h_E2RYK# zwlIDGdS?se*=G9@Y21BL$Bexh6@=isTjET$6?^YI zH2RDV`mRpU!1R>Mw3@+Xn>DmC>!4avR+gzD{`{jcETEtt-jb2F+5oxS+e zT#)+4Ti?GLTQ9(z*VzXJez$pF(KwuNDMODvp?2RW1JHP#tlU0iWhM9P6n6AJ_@Y^Ru(S z8F@t?CP>gT7nul*;e6&aN$k>;z&@{=*be}`8#wm?ZL9BOcPK9o$! zrE*3~Hp8*H#Hb-a&dvGHdZ(^N1drI8TR0P!z&{3_MNxwkdEb9xKrVt%dX>PWPBj+H za`n;1{zIux+^l`+4~|eBDAd|o-o>G3R}ZsmKZR67N155BJ0u4OXWBso7dm#=&(9B3 zRd9GgRZb+HJ$Nx~we!iT!K-CMQ=Tws%A;+p%m;!V8W!Eg+#nwh8@ocxrBWH|v7+L2 zc6^abo)la-@S-!$?f!nJ6DL1@=2pW4aE?Iy%T7A;C~@CKMC`$CLA>v?YzZ6_n+bCJ z8IUX_kk|MyP8P0YF};ObYyHlut34&v0%dnk^TKFwcBE#fYTkdoV}mY!FHoLNWwF7D zYmeQhrP$#Pv2)>3;}v_ug|M}-7nLO+_*;GfGrIRv^^Y8vJI+;#2f58HW<1}wr&-bO zRLmT*{Fhm{Ej$C3bI{skWD|_m)cBX_se#i&;GF)t z)t0pFo_;@HH>Py>#tK!B<-uP-{ZKpQvJQE8NIzzuGdxpL=A->8@8YqHtM7^)Mc5;F zz0>;9973y3GKb&f7c?4IzJ2R>F-|xKZ7|yJU9<7UyJm5v<<6~upO*v2!Evl0h&Sfm zuc>nQX{>P0z3Y3yF1UKK-(Fu59%!OHi3nj#fTV9ol#hgpoRrEN@dTDlkW9wV!QnF) zVJ!IDq%}_ukyNTEh&~X)-eaiyiJ_r;)r@+qN}q%#=1V=IFp<^hCTgLH?iW|DRHcb#m?Xg}( zNe2S15?)#OZ-kGJ)V|w?1BS~PaQZ9{)GLOTho5S_%n;Ln_XG5yRM;X=H824gk{42u zsMk}FMV(-Oi{HVVM>86_VTb(vP@E8i!|+I3* N(iSeaUBZ&u@bmrjf)00IJxOu zNmZ3UeXz{6WaA^`p$t{@`dKH8a}2MhIiKcRuPF=e5^Qc;F!-}G=`-xnX0vGFkX*ZO99DZzzpQSuaV^`q+>E13c5}u`6mdrQU@Or4> z3d**)6!#?BC_dyY7*O?Sxe~><%P8K8la=#}&yx@2)_2uBe^I*qb>HO?3*|+IyUWM( zwX~*iQ)0mUhU)L7b#DOdUi&^WOb2zz+2o6iv5`+22g?H*4eqD1w{N5DDf%vMZnc z%4wOOK4o->sEbtZ#XAG3-ow#y8pNm6?@v`^_8a#UdOpQM!u6zilKbPZY!=yUwx8U) zKI*P0_@Im~i#sy4E4KQ)o_#nOSng{-*Yxu!*k~)VpV!>|Ny!S7yexOMwK#{mP)@ZC zLy9Du7ylDN%dtE)!GL_?SwpuuAZJY z*wGhMdTF*Uho6u?mLM>j)KiRoGq}Z~7P-mq?in}|zw?eFjdziXVY zt_&B?x8xLOjmU2`X{#zIb_sE*sa3CR9bspw2f9U;>hGIgptHC@N`N$GoLV@bo?BZW zE~ZHG=oB3c*h4Vjhunj8P~rlt4!8DWx9Z(LKkh60@sLO)IG+ZULwT<7kS`=uLb^#Yg={LI_tIq0>9svr|_TP_Y%UkS(`AT9U)O zNv@~FAm#4%YUm{OHwZHB+*$u#XgPALIimN7vPo}!NA^6K?v>!YU}0vWCq<-t758Bh zjv3l|W+zc8>fci7Sd{S4%dVO7w&F+lxT6O97sLCc+m$Xqo!*!aT=}P;tNQzFzfW;r zjK}53JrUe7;>Wy2(=*s~=_DHxHNk;G_A2?ZXR;TRiEDDh^13}XcY77x{O0|JE8cm} zUpQ6m>9ypPHZVK;Z`l6{3=1`-WO?JnA$hd4$hVNnvT>Pbz!dZmdU%^8rfK@;SPHuN zOHrrQ`(kBzzvWGMf*U05P`X5vz)XqpSHpCNO8V`T{-I-M{zvj!vttCL`V z?jR#NTlcVnXH&~4;bn)8I1mRvhZr;w!VBLx$J_u8MLAW7m;EvQYQi{-fuPm;QpC^x z80Iu^zbKBZwKX(665SqX-x>h-Bs|11tqfst4E)dO?p!E3pc$MGSgClDA^&&tsaw?y zkHGn1iT;Ahf78wdRm&Z401VFNQA$NQ4gKeL*Z=$t-`k8UWDtVE=Opv#VyuQ$uXrYn zCX2vSS5KS?8x33A_@(>I$EnNtZvHblS=GrVV03%Ru-^G3w6?W2aH~JU5`@dNef2_L z!8ipgI3$3GmJiW;CMMF9{fa8541%aUGf=ZA2y7hBzm04)aTmNuK4gtbZU$ zU1NgoWyOpUl9LuxkLeO{r{5L{!pGqEt9M{J4QOe1mp_p@l#tcDzZt?Ycw} zJZMX`o%_s6MxxTSI72LWkDB-D_PO#bT3RZ$D=oGxwyXBe-C4{l3mmU~tg`w->*$fl z_bYU3qlgE_y=IpAYxFw>y#w^63j025i?oqq`N=e!@StpTH^O_TLnBP;QB*Hcrg^G= zj{cwJfbWX`%Fg4RKRcCo7T)QUuD!N|U_R?B7AaYcSZJ>GoV$A>SdqLEiK{HJL(%VD(GH?kUem0Yxock0)Ki4`dg< z-UY0H!E=?R-$#$6rlqlo&_h3ZKVJt!PUU3U21|WFL5(sH-s}NGS@#jtK;eI(NJm^o zLB5)^3=Yh;A&B>Cw}xo%4l#zCb0~0U3)2KfS z$oIwpll(2mbY|udDd9jLGe`A`RmpJCI~nVqD)qjI8`re<8LTLvY|i{Fj4Wg^;`T{9 zAe>7@MNMkHjjFtT2`wNvCH(VMvU#3zF}|n2ZL)TA^=aT4Y3apC%g9TG7x;wdnNJ>& zi#3c^WE*7S`gk2Hn{hgjpC_P-Pds%Zz0(h zNI8@oin8A_S+K#8XE2tW$fvuxL&oTcUMJBHYcv(j!dhPun1HZ7dB9O!(>qgEL17ZK zLX%!Q0rlb_jONq>fm_(;a`ME9Cm1zOJp4_e{gP^6G&}jO#CX^y@7c3Rs?%?kY$z=+ zhs0<=@~7DI>3Yja$CxL4;vG_MUo4VjB#KqT;wpW1pklrxV5Ve!YujC37*=(R(WQ(; z^KE(lW#1}ZTVw7cn?H7k-I@5@eCEAnDx*Bhgl*~O-=~I#C7;nRa<+bK?8x)(g|La? z;q;QKV%pocUtLT5@gY$r-~i)_297%KQC;NnoBz!FysybfB)9g|tjX>85#zNZ`F(!B z;HX?oEy;G$qX8>X@AHsQ%pjLQ&_ywIPB?84GcO>)czAdOxV{my!0u<7LNqWwY4FyC zA%aK@-QdhznC)i)v>GS6)l4(C(ZIo1o}XVeV05Y1y271qp@*vl+o0-ZG{@m``Zdh= ze)9wQwg-D|s72sauB%}&L2((1#n(PvNr(-XVrp6(Y{_^g9wF$7VT!ENy-YO3^y|>x zhw&i3u0u16-jfy}3D(qQw|$dO+@W5XNt?eC2N0Tm@83SlbW`z-=zz8p*k%LbRtha;j#*rXtph#D+uONCcfH5Y?HuWop%!_E!AY-4bk|Cj2Sxe-Aac>QPjO z6prZ!U3f@2^GffMyZnFF*4``d1w+>(U~x`fTAEof(~bm94n`MO7pTpvkzfN%ie$k(fO^6>HO3_M9sx@Yl5b4WL6n3Xk9PM<c7%I2{$n2SNa0~OeBvKI$WQ! z1gYA{y(MR=x$!R;%g(=i>Tl=2_~qKyd}>|tWINys{%tUKW@RY~T?y|PY7Hj8PcpUD z>>yW2=vCexKVew(uC$;p(TS#@IlSq;L*MDA(_ejri;;c+R4Bl153JuO$NyiS=rvi` zm0;@lG(&_%2tWq;U&(*~sIIdG>NefLL%QTp%x9>kiL%mAr6ldb{SCcr?O!H6kdo?L z;TKLjI221s+U30)4Nv?oZiLbjZ2r}XMNjYWOWS8Q;la;w4|6bthg>Q`!G&40sH7#?WhfNrY)`BscA1`2(t28K`3t#Vn*N*kKpmiBfalq@k^!Jzj$ zpaK0NzH@#>F||#uW~~+e_FfA4N^XO`Gleg;-R}K;_{^Z%78UOI|Frm8r6O?cnJU~VUvB>jzaDHC?uFNs>44J#Ii>?(T&a+BDoED` z!2M$JU(4cauAnD67$G3{Gs7@US9FR?c!nCrB}fQ=RRN!Qwo}bW;Ap7mRlhCTPj{os zG_i>ZNR9q$UAnz~6btr**jLyeCcR#)i;2?_5zdxF7maUn=SwC{G#lapt4A5hm#P@L|2Kfe$cg+|J5SSE%}-! z?AQDmPSxuilB#3%76l#@TM$|eA+ZFxF+R$a53Jr$h2uYzP@oK`asPSG?QJ)m+nlGU z#Uh^sb0aF7I&q(w8q==*MhMA;M4#5WQCAnh8N)={1 z4PYs#c>5MoB;i&w)q|C>WHVI$nnEHnXb79i#S>6DUW9U;(`{XuT^ej6J%ZU zu%jgs%Qj*SRn8sU*Q#OOlTT6%k<9en`7)gBR(&hCBHI3ibobil#Z!A9j|0ic>XU>| zN@}v#3S(U*$jH8^*=()>uf4r_kC!s=Phh#Zu{9s)Nb-Ge{ton2b0yj@qbcyHSApQ~ zRCXAJs%suOUCu6qO^bPw^nh-_8N_MJxNw=^i1(}*dbqYm%02%&eN|05nR&@-JyUXH%j-QfYkp8;qFk^B0rG6Np2FKTlyzILj+S2r{W|_$)t#x)DmJKaDBOPvx?Ba$;9sXb# zfY_4AJ_~VVt1u~86{%^O31XRGY*G=sx2{N1-ZbonS>$l}W)D1N3m?v4h`X@1fRnu_ z&J@L}ABE;EN~ePGj1e!mGB>nCEAYPwGdt_;=AECAM)>_0{iKA1h5`};1AOA{2X#PA z0EY$Gnl^7DzitAkmy3Sb)(n^S}Lp09E${7lbXp`|7=sN$Is5fO5LK7rB*k|3Gw9I_xy z(o8n|NtBuCFLs7Lq9g+L7SW{_}K`34IC6$>pjF8L5IK)i-w7^k{ z37(a#nCc#m(|~4PEuJs2WPx&JI&iCCq+%m&AYr9_?w_}fUY&+sX65q49vzck5!hge zwwV2|+!O3V7ex9Y5W97Gwq@|ed2MJ5Vd6C~RnXo>qf!e*s4BdB3Fo6}gLA5ZYq<_1 zmDw?r@p->LTO~u=ZEY?_5#pIY-5nE{zxPdfRakxfL{RHw6^$j|N3p$V)pGuNBmj2c z0HWYzO*NPVgQ(}ZgQ2xk&rVf=iFpk?CfkD*^UgB2gEEAN^i39|OhP0w5P6ocDDDsH zxc$Vwhpc=L$WiDkm(t*OY~sD+qn9>m9!`^J_-1x-s7kV#<_u{DBNi6JU5<9x%fwD7 z)QxJLO!u zn|O?G26LZ$_cr83;2@%z^#%2p4^Gr9PrBP@!P$DGuW#*NR^V3W_ywWtq)*(M4?j}| zTL_whwg?>BusK|&4-L4yHwhC~55WowPSJ%4r?qT?sR<_dsy>%H6$4=Qu)2EHmDZ08 z!R4sfeq#khTV0o}p$1P)oijF%d{jS|n(CWJ)o3ya6KZC} zxd}ksUglt^v|7C)n><(N9%th_o^=Y`jC8K&tGpCyxl>72n&S4ok_wMTffDbM5}~5X zN*57_VWo{s)eS?bhB!``9Z5^y|9GWW>h&*ku|a{8+;X(4jf9bnT43?b=Yw|x7M}_B z^c>0K!F9peC=eG4BD?g2{`-cVft#o(4`a?_dXW8*ZVPk&h9F8yIlWb7J@t^kHa;67%vqt|)Hs%1nEuyPjAkZxw8IkAPw+-psK2?dhFbzjGV-afw*8xAAya z`=-0Sy<2Xo<+bp5Dhfp3crT@4TE4P`#%opQl0d~8+e0r^osjTXw#nkz4h1=r* zh1>J&6v)U7i6uqg~Y469Tq?fDnLk@BZ<*p z0&LEG^=n1_pqf07_XMSQUU? z3K&iW6EDC#uKjcvM&bi=6NkXx(Rtz2kZ0G$lHqlRJpWF`7Fe5raslOof6zBCD`Gc* zShhA7Rdc9C9b(hv!zFGbV8xl7AmvgaL>4%pFbx?>y=v84SMnG@*yQ6EFP_Om^N2U$u&+so>S`R#(4Bu^Nz(r*Xh;jB>;F$p$z_r@6m%pt4G z{7Ry8i6z*y%eR(oQ>WUNmoHgeHc#N_;`z0D?GXNXbIm0r!B1+jb^(%0PQKI?rI^eT_*H|{t)pXXNN)LmEt zg65ZaVw7oWPujz>Da!J{mT&+5nKiu|83~n2fGMjc211Lbv-xLL-^w*e`0Ru1ga?+< z-eHwnJ>#^jwDr2O;z^JnzBDgw)RL}QjI3BGm{q;|Z%Yd@Xd8z$1x`OCVKD&S1j~&Te|u<_)(W?nOEkAO0J2BCkXMX8+slv zLW^*7o{nS^7J~a)u;T3n`2-W?33`(3xe3NNgMh&WAxvRv+;~pOryZJ`tD#vd^dVE3 z^B8w6924PMI+NaIHO-Hbr4>{QjHjs3>CPc0ayAAn2vhrX4B8VOAI{eYzoG9gwos-F z9B%mZO`#kAoTV`4j8rz{Gxy7+ai2@v`*69<3Rk{QEv5NR`_1Jn`we^Sd^Qz5f70C5 z=CrA1kE^Fe>-!4u%0tlrR;M>L+m0AY#S=_yF7<&bGaO44BO*eN424z|4vE9czE&6( zj4nk`98XV+X}r?N+nU$sl4LKQDcSr81hKE5x1fR!LfE+9)~HxCaFObd?}R2CH$-U21(gb#zVsj~FV6wZAw zLrvq-EQY6|1USvW0GB)4qxlwQf^&C9?v8!y?xrPnf*yDGgZtztGa~MrS0Jc&2hjmC$l$+Mi+mpS<9!-sp(lSs;8P!-0-C>BY!7v-Jn zag2n84%o^Hx^6tVX2x!!M;fI|_0Ylz7^Yo8Txb|;#HV}c>wL9x!k~dG>HbXdC1z1+ zj}S6#tIJfXZIXiMe0>;{E2!CizCQN-0wvYeXY}Ku_mH29tD!?~#YvVkIpv$5p6z(v zarJFaQ!bY7^0`jZIlQ~Ry4F@th*!K$@)&3{Id6=7F(K}=r7|7BnJ826qWOI()$hv# z=$mD5aa8#%15``b@G}&D2M#)ok4%XuG)+i-OPHy#zn#>b@kcktBK#o9{EtHFIe(JtojdJmnw_jDh7cRVR5UQc+Anbs zmnt6Jq>*4>M*gTUVIE+=H2pN--&1Y3(tw@&RjU4T`=43ti$e>h-@3L|URL&y*S0A* z3||Q0P!)IP9vyNugR6z&qmS@^R6Y8?`Fg3J-VGS^`c?SV@6%?Af&~o%uP!0P4(3DW zF%eqKMhN|CuUFdSkn0N2zk##_c0N|2(v1Vve;&e=CE7*iV9n-dYY6A=ukdy==7x>! z!3aQZ999jux3kR<2L|d*!Jm|Bpi-f;`upX$s=!_rn1Pl5d~}F0rWy^Z2$77vmC zfuE*Rc>YvU+Fkz}@L9`zK74ClF>CS(z3sI`>gTxI(=AU3U!Fvn@JFynCGg0gxuO$e zsGXlAzY%9$-JZP4tn#zrFVn^_-3_jgxE&4c82j#*jAEh_wq6uzH} zTV2nqZvzBw$Y)Z(%Zg7m(VR*f_{P%Al?=dvgu#>839Sx!V) zOvh8IZ@7;-!=|@~$3@bPXCbfdBY=ZWo|J5BZ!J?)8T zCDVspWB}c@6?-79VvIg;;?L%|+;#Sg1k?}vfUP>qWl2dQQ6M<_nm*j`u>1qS^?{DK z80zapH4})^LaB+IRyQGbeOzDnCB}myLpYOQB7#JDdc*I;8AMIu6Q^1jf>0Iid(eu) ztQ;szFe`qp=uJOvy`~r5(K77SoDVGRCV)#aO2{Hf#)M;I_3s!E#e9I!dVq%qLKfCw zk7W&Ux}%v-#E(fITWdNB8||5!(jLXRxtF1iO|yr?_ZW=eyIgo4Fd#xR4Ts!dLOrtD zAO~=h8^m1w9wnfy#&U1#a2_4fpIqW#G zc==?(a}}?N_kOOft+%skGWAxt&Bg~mJ%ciQuiq;N3NF+x+99M=F`H^$Axli??(e4+ z9h97#-JErO*k=c<$Cte+_G6suc7Rz|H@b40JW9L8+zDgy`E{k z-K2e(MbqrJSo5?8h-w(u>nWw>-(bRA`E)9vuy=-$Rm5;^_RlRJ*{nMPEU;gf1D7r{ zLZk}lY0odcd)rUQ5<@+#>U=>GG&Bb%v`|a;M zbGheifsyIlv16>q?ruCfUjkQYs8kq6x1ei%UDjLG{fD5S_%UJx@dQ2;Er{|t1hIEN z=%h=%vO!BrUY#rRBhO60DY5E+@x6^eWFHb0^EfIxZ$=^HZCRNQtlS}UB8k#v_*}vN z-|r69^_QysgM<3w0{@)@B4WS-`1C>N3QItyC=*UlZB&5n`kSdCxK{tSQqL4=0}{at zj=C|5zctAV+G!v|M8G0`)A!42f3997W52=Dwd+!k&Q#vF!B z1yEu{2?sG=C(@Y&^V7uVwY=&^#33sJ;&O4;{6ER0hj5Orgs{dSDdJG_BWLC0pr(S# zW^i^B22P7gMvF<@ z^G9|*HqKYiylHKv%k9uDp~$Y;*^y`n;G>fIWT>uA~m6WfKhB4nTh2GMl zAFWGBd6R*MHt(2_jj3r@`d;mN?pSgZ)|e9yqDaqK&adzEX<}_@inQY5scg*`!Ek7O zn*FzF=KQ`yTA_5uJ-5Ry{1vkxh|TmNUIFS0CU@`Ry=I*0=k2In0TYx!rNxP<#=xlq zR|A$lxw>&poTMctI{sPy=`RO~UYI+f7*2?;G2#9MDj=OOOwg5Xp%6mjz^~^*6q7HD zm7sQl_KWnsvNF*m=6@4)@nZ;x%j95?X7>zb06IMG^Wo2|DO{%=A3lTLaq5mK}BVnz8+ z+V0n{``xO2?#Le;gtk#wyWY4%tSwcs*Xcb0BH0=h4lCV#C6)vxH;$)=mDd{sH?@Tw z92|B&6>L7SEjf}qBavy=OVm3VT&R_H{)g>n%}*_-wbaxc7Ty(BSC`RfZX?x|#t=+y zYD&z?ii2NSSNdq*%o0eU9A)&xLA`lXCagU2wNss$Y(t_+s>wxR@7<0hA;<7&_b^2+ zoB+FgJc>=nyBt3A{fIDA<4L}wLK&JJO-14V%HP1$ha&b}Gwl3-ABE6@7#;JkcaB@j zZ>@t?D`J3Nt|Ife-q?^3lcoQl^6vzPmD5TH#Nr$eWAWA{me=weSZU~oI_&$*%@dMs z*&_I@aB|Xku>1PAKE`bH;lm6uGT}A0h?`IHg0VtZG2`LC0O7*c>z}N_0CnUNFq#9m zN9T98=bx)AHrPH@Sx??sbldK>-s*-4{t$zk1KqW?-qcFK{0fwVw^oL{cZTP;(qNzW zxn_H&KJ3ZDX+}09Q=lp>;YSm{J_nKq8CB9#e zWX64a`~JOxvhq-xQ<83OH(N!K(s7L@LfpqI4o+HVd-KdVg77hvpeC_(uPrx{F)C4C z&OP4ekp(A6A~QW4PsOC>^cncQ8Ognrz>)aqKO$QAZ+leS&Qr}*u9?H&O+0C*)LrtZ-Fx~qWHbgJlBRpu-&e2gUxpiXE2QktMCCi@u6->zL@XGakV$?-EOS)8$Kq&)2Rn||L-;7!f+|k&h}W~fckkZk zm}BJZxPAz+0`hQC->j*ja(pYvRNYLB8`e$`c(V-5rEkXC;MajeQ0~El2Nuo*J5v5q zk^KeL<-cPa6U)^lE6TR|+S-i?CoI{O{?ux`__47K@q<9V2Z)HjYH};j9?i*LAdXCu zc4%u8P`tW5#zJ6N{{RX5pBOjciumm|rl1}R!n+JUSWcb3KyXj+Fc9D0cq`LHoSW@S z7g=n+-W)uLL_HzA^iezl0)V(=0F9^-mV7UM#6{a4{h;@Pd|Da|JY-utq1}SWY%LS! zKBo9Ia}a{UBV>7m#SQ_Qms)oH>CS$SHer!FZAcI^NP@6HKkia z+qZLk|Gao2PPV)yfcsR~b8uv6F`SG9kp+X{__~)bEB!4iISl1oR*`#3cTjC7=vM3d z_u)bIxA1#w5p;&dMMZh}!GVE8n&QZ%q&SVno-U?f1J1_CtA0xn`wm?_xAjgMB7V7W z7+gf5MXqU2>O$dD|JkJ6Hvxa@b{CXQ92{9;)UOO7v^qA$f4OhBfah0u*{pCs&1-hH zY@aGE|M8jhzrHkmKJ?w`ZFsk~I`^D%n#18xg7>9PY+$-B}lKKyRSXS{!pf3oOrEk1W+WQ7@d*CUasbV`jt;=!q*G}N$9sV1$Uj(hapvoN=- zM2ivD%`_pD+I{YXsNS@k`kZ&cj*6X0a_=% zeKS)?jU?@VqKWn$4OIoB=V~3tFw_n$vm4v2qA71lts}g#KXyzr31XOZr+^Jc|%+ zXrOo+BWVk9A!6#>@8$Yup^1)ghWmB3iB?c#eF%;(6a3IImEE{c*9wm=&RC>#5TK5 zT~5VGB}3-)`K<4&_=Cu978W@E$}1`~(f1K7@~}_AAjZzOX44qxe#4q@ zZ{$K|r#jZR_}!#*5VL{4N0E|>)v2RW$e}}E$c=VAeg}Vi*L6R?ERnfryhic!Zi}_* zd4}C|bSnhoKO%}J754DiB7*U3WAZ-qzDds5d)teXbHf$A3iX(XOE34AkiK6+MQWDu0$4WaK|Ky1YWWJPX!^4y$#RFXB^TSmh6aOAv z4=N^Opn)dj(c<+!@x~ft75C+tNa%9nPvF5R)mGNgVT_-in(DBSUi|nmq(>q4^DC2_ zy1Kf*9fkTLV?I|4uMC#n8iQEeIAKiG17Y!SC8W}Xm7fm2okzB_%C*6bbco?Avnzt3jCAmg*SNQZ#=qhU?GLXngqd5xpE_)JbEcZ$}DlgY$6ph-Y%9*{}{iXo@gZzCeqMo z9k6D9&!Km0??E(E5IN4o!Wn-%GP#uy?U4VgXqU5{iwl1(&jJq59EM>=q~-U-#*Pc0 zy?ImM7223As1IMa5T|0et)lF?EqaBbwg31MoFz-IVh!-ZlY|=w1q9Yc543N5{|i5- zZ$Fv0@h>dxi@|jcs){n`MeMF-7>ZCrwF8D!P3#)no0RO6+H`Ol)aQO<>o= z379?%uCA6ApM2Kd{#+tk91XfQDw*zvo`Pr!zrFjPJ56q^{ zGz*c~so%d>VLq4KJPyZHnbu1wx9!UK+=O0BulAKhAF5esMz)y*Q;-Q;beu`qz2TKg zux|L@bGbKl|H3m#^V=}Zy2;egYBGfxA(-hw6bf&${7eYnc9_)JFcS!9 z0%zFQKY#x8(?s7~Db!HY5hsMKd=99M%*x8TkZHpENI*aUX|ll?6A;Fy>HrD#T>rZl zC`z5+Jk}AjGAFR$71uu5(4hUky4VXgH(j);OM@Ry zD5kk<;K^co$Ki6I;fs123e~^%6ix2xY5GVI|C5t{;;|Sa`5}@bkQg#DP~3j5i6q^_ zhw!|uF6i%9_#mjCSwwSkcA{D&<*96MsHWWM=M&A};s%F>lA-_3?vb5Or?x$&Ix`Oh ztYv7t_yc9k&Hi^&;8XasHVFt@5ZnFBQk|pItN-7G8PE;@h4~%bcv$FRgRsTSY0Si_ zD_?sDDz5zues8nU)Z~Z_sZv(Hp2%58D!wZ5)V|pGiTta)jlQ+zX2yJv~i zfAfcC=Z}az%Z<3ijKf~93trPc;$=26IIJPXCEDuylIhXLlWQm%0B2R z;qlpxW@1GiQZz9*gtIH@XUZ`Xd@z}r`GGMvt;8Ej4~Ye=aR_A>5>5-f@bTQ3zKz8R zt|v71#C=bKvbHSj`?~@x3kA@jN`!y@su&btRN)k9WeY}dsUA@ABDEg~cAT+nCR|)& z1=Z!Z>VkIx1=7Mz1}9#az!cYm4;H(XYyA8T&KQgCb0In1zU}Df{&$qwf8;y?r~a`u zdAM@1E%4qt#o-La#j;RG@0hMhQVJo%(rv3wROK%#A@5QyR9H~|SXrf3&*zxSTxg9k zC+idwLMWke9{Pk9{>HywzZ$7Lpa1>ay-hq5+tJ1ut>{`aHnP2B-L5c`2kPJcbC)IJ zAr?{7wgpxN3^5XDRy<%2*3%Dhixm}FikF+%Zd>~K6?gC+c|JQm{e@JV`8j6Uv+%nJ zN-sw*b8~sX5^i5r_wP7Z<^BUC8XE%TfJ3U+1k-NGcReU%YnKAamUEK-^rq~{ibZ}8 z6p@B1KB*q}Iy4Uqx{vKkn=Cwy`mmRPyU&Me`}_MhS?Ya7g(3!Jn=_VuL^Dg9rSSF#>QPx6t_O*zU<;dD%nw8)2_#&j( zqlF*M#5^`I@ceB!q9fejm6jE6LjIj{k@I+X3!>Jhmt$t|@T#TM9x?Kn2j(H45Aq#8 z>~U#fO({b#RO+HF{Ed2aEG@Gxe&oGzwxym!`Of;3L%=B4bJ*`=Z;hiHN;7kuKYU$M5i!4ZHa^pVd31U8+mTC9~5d!~-#In}MEhuSx)64qs z?MH1bl=aY)zPDM^n~_8{gfbDBWO~?6~eV$VcB#Vf*1GadP^?+vRe0O#UR#o)&f- zQxF`rxEq%gQrUwMxXZ{&?dOGg{wj}H0Q?``l@~@$lZ)i07EtW=SWFH=4dp#QxK+n- zcnc=3r&0|>br+^{3rQ`5`?PncUSJMuhJcll%{A zt!+to__4j?&#a`Z3IeAtOg{G>KJYH@v?<4OPz#eg2#i+7Uz3 zPmdE3Y-}mJ=Sm-}{!i$!n_J))Rt)CF-Rfnfiy_E0hjY8b-g)3rnI`Au z4@%7WZhD}ZbKvk`nNF<>I`wUSZ)}dqE_nK;tB=Hs+jRR6f%L==pCNt zf{q{?NCuI+Jh&VAvBK&E(j~pnrk78Z7ru`@4fxSi|4iVWU0VwMp30ERH_Kbc_nvQG zRCA=7@y#ANERdQg?J$hf=3kzkIpwv&?Xeb)Q8d6Z5w7qW-&kO3Iw#m^EHSrxdsw;N zvc%PIGBuxT?AUdU44{1FTNK)itM56`wqGjZ(*9ahQIIhk@{K;^*B>VE@SdVHr#M1T z?OaVW%(2Acy0|k(HgY0 zJo;ROo{O3opyL~XNQ0biFq4S?`SYg}Z5p6qfa?&%?-4siHp!`7WFB$;HWRN0Lknkv zd44q`Js}(J%z87ujr&I)S>$LHLw_4wdo-i-BOq2&6-zkaW5U7cXRELMo~xbRuMKEg z&oK%VnEt@a=0rQam(jmua!W%$`G08o5@;y${p)4ucx5io#iR^23 zAtL({HP*6)Y@tbFNVe=!wrn9|D~cq^mVLip|9fx8dC%!RPR7jhJiqVvvsz!3&hY9M zEe+s0*zON0efK%lt*c3e#Qidam7OvIP~-gkJS-I3_2rcH0FqujuZ-8Te?910zRZT7L<;%VqPw1`}x)ayrTdL#wrJQ1!a-Oe!nttl; z=9u4}kG=ixXz`w%@4Z}KMub@C!&WGq#oF51dAj*$G$A+qQihf|1Uev0p=kP!vk2y4 z!_$u%63H1UDfhSMDm$kBf#B#sY7_~ls-hwR?gd5sP2prJTta&v123x@3ib$i3q`Ml z8Kw+Vi{fa|2#EZSDtb04zT2*o)9Aa4)5J0z&L!fo_`?s_4_Oc<>7IzZpbyVkP&t$B zCVKPPDNfG0nYm9>ms^k0D#rdB&dGVB>k!MJee76FY;4T@w^IJtN!z*~+wyO4XDsLc z&fI!;-^|;j;FJ6X@dOl72LN?PfgZPn58EUgH5#@QLe(dvkAyULE z{Q?L=ZFc`^e}VWaHE=U$2)@r~{GgV1 zEO0tbE%19!(AZwHNTxRg$3Q3s=?mNmkZz;U!G5D)0FbAWm%3z0cO`aeMTxZ2cye7x z$a{K`+Bdqw2NA?}>F%uDoAu^tI_G%s2m7Cjjy*ZtP%^67&`E{Rg*#0hbd8Xx3uizg zgq#G7s}bNfz=rH%kO&s!;HM>0PGFUSS*Ror9kOf`c87>2@pYtLO=*9K;Lc_)@RyvPJ00QY+EcG5_-A&OC%jWD ztenzj5q&PX;KK)=0)4VzlBR3@5`{t@%_|VIiu}wI`tbtovrM(7P~uq_^@7n1&>yG~ z{CRy>KOSc#k!JYLevB&W*Q4yL4$|l-z2s#=wzA#?Iz@WaPr}vL4!lNAgPHFF27f7w zWoW4dpZ$(eTC;}MAS{ZCa1_DkTxWLZp)dPakObNQ=dr~;t_*8@I1wJ#FcQlDO0o8x z_Ppt6y{amebi`|J#L&5eElS0StgESrZa3s3A#EoL68Uri?o0Q0@ZbZ4+(fy&vdMyL(Ubb z7rAvjk$8M_CqA0cWS>EUC9TYInlCJjd+(?{UYE__eW_2T%wDuMEj4tln3z%Jk)RmP zZU+h{Kj6UEFVNLz^-R~))Ra+RdHxHsW=RQ&y_PiBm9;fN6}WozFsM#AY04;1Pl`vW z|JT~zU;b`DkoCy0b2n7xA-~fHMtGEM^C4qaHNeeHG()Q=?b7&qfb~_0H1dEWB>Xot z><7~v6K%oeENuS?n1xTM+!}@-dfx+bd`|u>q&1&$~ZE@IPbmDnqd>>?x^#tcm zy0{CSI&ms8#~ySjI@0H$$HMwYhKv_e@7Jn;`i0WTrKJc^+KsP+a6YZ$SF}c`XyJgP zrJ!4Pi6mZGQTNk{X&B1P8t zkDlj^^5XH0zZiDE8sGRAtN$J<%xx{tFGcj}RXIn~@KUKJn#c#VaTgdA-inJkpRZ@@ zY*RbzeA3M#>-W3fLYm-v`q&@8PHM-gVikGGWq2lRt7;he+671a=|XaxZhm@4p7^k$ z)9q-gY+m<3b`I+b*YV!r;ep=XV?=6vlaYW}Eb-;b*FfP28Jr6H*kx<&UzpzGrLh0C z#k+D|j8DpbGe^9~&{!}gL=-{qgyYb`?)q`mDr8Av1Hl;Ilh>QtZk$4{u+W;Co}AGm z1fzd51lwEuabEcL)@OEYPG+!3&b@X1+@`X0f(A__k;Vp5LLsT|x2e!OjF!hj6Gd^a zM6U`>RX+O#*#e^#t33oWrnEDkY{WN@3ng;}H9b=n{-yxgA!FZ~D`1r64yQgAOx4)0 z6n_hUlGI1mX9&gxze>67=5{8do8<^C3B6`brHWBhMB%9kn6KIws3V`ek>oe>OGqI7 z)2k{d5K7Q`q;soa5J)VTq!;MImE|+K?`JAVNc>8l{r#K4pDXVEQ{5x$Jow`edmkR< zJhVmEBQ^b>(@FfZ7qkeR57hKDy5bS7s;%JJA-sTe-;Sww1JrTQ*xlcs&@uIT;ExaB za~mH&R^OWi0|}i5(<95aPWS(WNd7Pz@$c-=i#QLx`7vN%mVdK=n(6+Sn*80b$@ME! zkY~(kjaYoEz6Y-3uLmGTY1Z!FlGamKKsC7wOPi_pw|ilR!w2l;OV2JkX~`~q z%-Y|XF0TLQ=;CW6RPMhSS!}YN6i&}bOxWO8*lQQpR;aV`k$f8V81~)WjT9y%`^ASr0=sqi|qr!3` zfQLqZ=&(3*Y^)aO&bK<+ z7~+K^noo{A6*2c;p?hraD&iXwX)J~gH}h>>lS^PG-FzghlO2=r5-dhm8*yv0Jw^rU51wNMl3wz)@Uxx0g?Y&R95}}& z2BEME7cNL&ya?O%=@*g=JMX5XM}F=9V|!d%dfTpaSaLS~9+#0vTjTdrR$#Y5Re0o;ICQ8cduj zI(%#=y*9X=1_R%k2-j75Pp3=CjnFv71TV|Z6_$5n9SA6H0`O7IXD>hakb1S^`WYr* zl11Y&+;|K(LPQX5yi7dDRm9>Pj};K}`mf>W3t341bc3X;;q(n00cTm0bX#sAP+@QR z3u@YWmWK{^;_<_biG74E2-(iRnWrsv``gc-Hkb{Z>;tsz6Z|2Y5ZlsW`wLB?ol|!+ zrya;xcPlF^m;qxaAv?8Zu0rjUzbJaQps4!Ka@KyWSj)03(9kf)R2z{4p-FbM-070| zqnSjFXmLvaRtKAj+YBja6e^W2T<~0cJ+REy38c>yU?JvbSrH3o=V-%NxnC(Yf%gqy zIk!0vW^fqNii@=cnmZ{*kCdLv&?D9JH9WuG!0FuT&P-C-+!0OKUXtLX0Tp6W<$ zsQvMH(_f2SlN68kU&(ESYg(a`jh-MXDd{$RJ2^Hs_S;H1C#6VEL+IPMg6HN`GH}SF z8qTce+Sss|LqAw-u1$dROe6j&rn9jDw?nUf^}lc`k3PrpL_C%sU!P}a z@;Bb7R9^J_6Qaj=NLh0`ggX)%Eb0`aBN#m?sY#m97s~1?rLp+(vuiG+=i&YWO~c8P z8LtLjW>}BY7v7^2mRoeC_}l-O2uJv|PN+9I$4f3fNMs6{eL5GTy8M~3kl-@$B0o{0 zWg_~VU*>7*VaCJ9xg*~M^C;sjJ`g|k=WAA(2`1H4kK~lOI$K3Y>BcQ=Cro{6Yz$u5 z24eSiiIIbz=w+1uO1ML7tSR!=d05vvt)-=2>!4YIi;;2VG1WhEWq_UA{YQOTu+xR@ zhEY+SzDi>5e|xrtmzkM#msD7$dn7{=dyJ;IGOyrPTgV&nvsZCP4DVH}-wAXYU7M@X zmYTXD?@(D5tYWXVUg+_ANWc-gTJq?b`6XK0saLL<=>$p zb{V(x5Bg_*i)ZbwfI7ml{BEw{jS~?chf;=bmpa&H78%ee(B`NF6VnrZWXE0QyK$D4 z3ayBVW5FH4a)6L0d+eCa-mIuCbyXbQ)%cS;p+uYt!8U8F0g3iwa?y&hR zY!!qry}cpCzhOiRR(xczuCzv{Q?biR-FF@?siI-$Lm@rge0*51P6i^iqGqecd1+~B zDJci?(I#9%H_j@aHxN^1bZyq8V7U6{M3ma2M@=}{?etRNn!j&7rRRJyiK3c^*SL*{#Z)^4E@d2iCx`()t8 z56%4E-rj=Z+E47ul|kE;PLx7!{P;R{3FPtjL0wQ?Ee&eBdN|M+j~&}P@M%6^lq=h4 zZ1(=@J__WT8I*&ScFQKC+0LeWH%}!)Uxp!W<3RG{J-(Y;QnGYV066u&fRCRa;KJgX z`Rcg1?AfCIPgT?YCxY+PZ~g-5D&&X4;rpLQrx-IcGiad3AJ6aUl#u6S(&WDnBjEnl zASmgLZz}L-`QJSc3#|$U{R9hqHli37bFD8wQU4Y>39IDrwgsKtHxiivO-j)#mFZZU zo*VETL|kVhLjA1PQxLC+<-YFTfnH9ZudfQA_gWa*-LTgF`?X#uqZ=Q;FbnQja76HT z&ZLR!oNzsTP2sxxS7O3TgvUbIU`3$(_Hu7^;uu`i>whCNrBnO%`4YNp z`dWZ1`;kJmPGdtZxz$F}4N>LQJ#x_)Mfr9zAWgz$bZ=TNFa538|At9H2*I?3Zo4yh zEycy4U^tav|E40?`8?Fk)R&L5J!D6#qmo}XO)CN^nGkg*fAcl>AJtr{#<{uXel3N2 z!+oc_-raGz8kr%!s(S9~jI#uY#BhtZf}f<^wzro|XsV?05Pu<8&Jn3-om>{FLf6Y=|U z&~o{cqn3ma}F6-C2lGop5TWTWw$TB4pbOY%g@YKkXp1F~0 zohwqmVWn-b4iu|9oD*Cgoh6`dA7qsID~g;k5Nvq{R}racu_;Qp_GkPRfZ(h;hdypx zyEL}ZN6&euW|snmdwI}%sY!y<*w^3r@5t)x0ZDTv5?0ff*V2UFeQ&ZYy|=%sAoH({ z2f&Aqm183->y`csj(OFDZ%Z5UwfI6C|4lt%7q(Ojh>pQgd?c>MvvOuRhx#%{4@bllP&yvGVKP z4xrW#6bB~2JI#0+3DCl&(uBt$ooAcy&KakvZP`#`8z1fKbk?a&3kL4GH0w#@uaW-! z{Qf)G^2&)MWhylopJES-eGdFil0K60_jz5N^?JA5jGpaYZMY7`<^IgnbXGv%-Mi=0 zx|wvL7Qs$oeWoaLO|!f&(wa)c`R~w{JSitQl{4mH-VFhf-T8`)8>BznkBV26qZ3%M z5f;+SKc332>7=-cm3E&GiwtM=2*WGETb8(UQVgw#*!#2Tf#;%UzVxIZeAhw*7cveu({L zVmSlcZ&Vl*@70MHx}XNR$^RcJBoFdEmB}{~*F1(VMBPrnI8b*Ti>T{ftG_fp^wy&_ z6A0)^m)5j!E8jyoqQ;6?OROsOS4IpAKD3eHP(is@cL_6|HdtdKv9C$_MfpFZB*oR~ zf{}>qe(SZg3ed{S*d_4x8Wo#V?R?-eym7{c>Li~2mUUXEsspWZQ?PpX(&C~UUxE

    CEK{tK*{d9coQ=6OmR_V?Y*h8{nNyL}-o|5U3(Q80Y63Cc z1JnVXvZA7H9p}b_{xE9qE2xX~*=k4$FZbB50lLDq`f{2nL7(Pr(u3rr^lD zP2T-u;41qgjJb>wYg#&BRN}7!S60Tp+cd0$oG7I#U2K?BvEly84ejCvuicvlX6>Ck zJUndXo*<4igc_OrS<3Cw;gXUPbNH7kzj>)iX9UiW*x+g+zLJ_9y%e;~#<=q@C#v3m zu6*!>wSKYui<*Mz@x9&Y0!Bj@rUwM{{k=_d->rPRqJ|$2;ch$2@WHgk%gpUPEr9oz zzPjz^=N0+wtUnH#t{KlrPv4p3+8?4&S~~OfUh5YeBE1&K*-5` zm_ABWhSk;*TLBAqGVi(Z!KpubWc~j7*MoT;C+G6@h$!m>Yo1A-h%1SCiK-YK@I{)3^#$4d%1-im1Q$Y`5lZ-&Mr01wJY490dk z&X(0nFv7>eLNd8aWyaphN*9C+M=o=fcTYi`cIgoA`U@SW+Zjr{jJgAN1Eyowk4gW2 zuJ_ZJlm6YAPjh2ZiyPJ=Px%V++xGX!mlkHnHJ=T?-{(VvivzL9xMFK)m#U=5VNJf) zm#SyyN7Yy&uIYeL`7Xc^Sv5a+sU9R$^`L_A=znT(q#2+xB@|W&u{X zBg-kn>~z#1HtOnZdL`F$B7rwz+D8dSW?ABYkY zUW^qAk%4RfSEc+@#p-`*oG0p3!NKSb2D0pQI?Gqr%SOLFm_i0V}=kUrho(zg~-7 z1N_1caNf5R>1pIUC!AIf8vHgw=|$dc{VAY&ZbYsJMP_#ukWBUU01}52&G)wkxdMO3 z6%^I~i@ze=`{EEC9W-E897z0=O}%FF^D_Tz2ih4Jln%)5y!ikK=t9+c=7VF>XCia{ zcpiSZ0b9_X)djBq$wmM1Y~e!I<6)@14#$x=JL` z>)2hZ+&@2QL0^P*MzmB5&J4^fr zwFp8*@0!+kfwqGm;OXqS0@gUW$rbUv<%YfGSeg01^D}$kzMAtf<4bUmNJADEKQNAa z_7BEN?ku|cFLQ!F$E|eui%}Gfg?khJY*R1;(sF`yJO`6~d^Y_w9ufOV{46aaEq`9> zre>i|=9+BGnG-sw>$v1DPj64PKo(jKr+4~J(T}x#e%4jmjYD$p7v~Cpa}jyB-iWLn z0?<)HMFvhc^2=ua$xCT=cj^3_R>g&e* zf)aZikp(alBO%iDV3l-g+TiZ^Qb~C;$BQxLT26KLy-mv5>b%wo%w&D$>xd+}d<}gZ zU5X~Y->Z9|(FrKJDwA#Q1>5uCrlZ@?aGKh_HkO!v1R9()tEHCmb`AM^+GoDz}Lma zml!VV0%6Ur_ykc*;Xp9Q(Tfb03LrE_P|BdD=tN$X|1#7RfRH7x#MmSCY+$T-SrQkK zA+yeKGzNnWE~~6OdAIE~Pps^PNL@d#1qL3|v%e6PTj?H`FMm+NuturC`hnduSARv+ zi%%Kx45;pPi`6LbmoJue^|$hObkuc7YQOCVv(w_`laAz6IJe?BY=J%knZ(q8QAElK z+LY6gecp>w+;nL_3cu244?TLZQ$Xap%Pat+1?ox-Z(!C+H?=`Z)X7 zjyVr~Jo`*RM{F|WM0+idg+Dte(%WtpB z#kf*#v4f6MXecgcYWnu)^X~50{jK8tTh*S2kte#8kz&9WK>hCxsLFddv@{6r|2072 zGg-d?;udRa(uk_6s=_rZZ(T;m>gLvr4ai2v?*~?y>~*;Y9;`*_uns1h+y%B!&uEZy zmC^ru8{idLJ3m|L*@RKZoX@M@2j^7wxcvR4)5#|Hd&7_9n+TZS?QM2XFEkJ80-Hb~ z@kGooc;;>V=6Rgq)^u25cjj^Guu(yI1!ZrxVRsZZNx!L2Q?RkY@BU}tQCDjJa_M%U z@8?fb#E+d5KU+BO_%C`hn)?jg95e}tDX#!x0wfoi=_&8PwoJ*m`|t7mW*)qxyho?* zw$<(XyRttd>~k3|Qsvp*}U+{oVF4rKtUm4Gygso6Rdl$Xn?Q=L`A>rSG^H#am zRPT|#sL&!>f=*mg#dDkl4y|jTgr(-?4Ox*$y_)5-y$#RO?L9sk|AvMAZF4rCg%6_s z0QrL0c}q8c5_Z*F70#&?UmKgS3|z3CNE0;!8fj`Gs-tey-d{K;z%wCcfs}OLd_7=W z&*sceH5bU^7T!XzROwjs!oEvOVe3`V20L@E3QSV zYXnV)TnzzT!mA5->Qd_tB5xr!`r3VadrzyJ^p0P)J(=HzZ{F=b7R$gB>QT}A>e==3 zayBaPzdx7O8Lle``V}n&E8{SC2@z;$3D=R;4eOqm82z_ZU%dBcw=(=B-jrc3Qd0-l z9#sNuF|5M>`@-nZJR$y_8P7QKp}XjqHFdJ&HE9N2!uvGN3WmQYpNad;zwbzv+iuW? zT#+Z}BxPRrZfpn$I$0F2+au7g++_I*t%JCoK%gW94I983bIQZ#b!ynFR&0k-|Jm%4 zDMz0PBPw1qT*)HcV|#7xO8g7pkCQuKy92@00e4zL zx%4N-h#V)$M(S%`tMHWW!n?;aFfe>MaS_k5Sjw1kqqEHEv!(!IVLSBryD1SJx_FFN zN%3l4|Lmaa{aNxguFW>JXfX=EroePz-^WI3W%V}PDcZ0^YNVAR>;_StuEnnhH_6QW z;PPen0uG0Pn}0fO&W~-ka)BGI@@s|bLL+Q80V581jxJCE9y0K_2>7W|4~eu6pM}q2Btj%)=+>h*Wq!)IgiugJVWsupo*US6s!kw6>0eWwEl-duOAyvMWoW z!K^q9C#vMOdvs7?Z|ILm<|YYhScE7ejwIjtVY@-cRhT7Lthu(?@v$*6rh%JN1zZ6; zKNGa;S1DZJzTm-&j|VKsRgT@AZBn5J`s67NtzUR+xW9k7!*AZ?ttU1L9fdZj{_|F0 zXD<$b+XW}{&DXlsaN{1h{MtS*f>3xzWdCj-84^(sxP&pD$8fv{eI6SdbCyu~$i6%c zF3qi3*R~h^PQvhOVBkfm^%5Nl+J*s7z8+w%rlL)(X-3VQ^ww%vbu5eQB&d`yPGlHC}V;UYI$Iaj2A;tHdg`be{eGx;JP4!^Vg zQ0-#&NDoF(nOB)t31!Q#g-LqDq)&c&PMcC|y }l5*3M&frMjI}UFQJ(5U8gW{ zFU3mj7=!-_BZ?@+vRLsMlhT2=l=@SI_4t?{I^bBayf+I5>DG?kO2cqRWl34v8dunShLalT zay-+)e{pzp(T$$3Xq@CP{r?)O+&_FBE(KUmMy6(DbcCOuuVLMMyk@${4?zAeZ~=Sna&ijSF3yr| zC&5!KGeP_?Ix=$T(W8S~5EMq=?hTqk1&<$;8BR1`k&(HwKIT0Lx#s;diD>bT*Ef^p zH)bD!5bbZ2aCMthULwd`iNEXEu%s{0c^I(%ZT&@m{#8Ea)(Ac(Eb?lQv%3nyS=SEi z0VKYT1hrE>HpV5pYgv0XOB2oD;6U-IhYy;0%;i3o-D(yISW1VY-^q6-!a;Kd<}P12 z*#hSZVDJ>sVR_n-bhAJ>;9rCSSHPFv^{*am*wY$T(U!lm#@$<86zW~t<5gf+gwb>+ z{z0{$-+c8nTU4^}s{yCT3(u?n_H`KSFD;2=Y?79{rNHTQ^ytwHAU8mKS)gzF4+M2P z6tG7FcQ|RK% zpPiebZ~7fV7g+8-nHDTL-8c+CK4Okk@$q6tC3Pk`EQ1=)%gdv9b|UYMUC%*}ed3Yo z5#LJJQPX_AX_0i7fLxAC2_I=gs1W~|u7MC`JUNk%7X@uswrhx$Ij0=g;RPf=i=M^?2l_C!b67{KB}nytL$OFwNW49MSs=aRjF% z4YmsBk@Bq)JN}k}VUw+23nn!lJ-&+c%0w2F5;VWEw7Tc^K5+me9-MN-HiQptOqLY2 z4B8*#b(i}V;NmhjVYB=TbgIs#?=0Tus6<6mU^<&L<^&zUooFh|bb{m^-vz^3{ZH(d z31g)mS}%1Dh`xg(^E(g%DG!MVb$?iZbduv2W0{JDnfdvy=~1u`WsACetKNk?B2EsD z+l(aLX*(^2b4l4?`)rApR~#;}t`U>Y>cL{KGRN_j#Q5eK72rV|6O(g>;qvt(A;FM( zbG^=Nyu>5VgMxY{_sCMxo3e9V?cm1-s}p(q!EB&}8RH8M1>xcS+g%4z98lyxia6sg zh7~*iJo@ott*g;d>V74;DME*oaQMtr7O?|4*18!7R5$)Dw{d`#$?U>`VU+p8cCWL0&)O)FjeY zX_wiOrLQpV{22pgT}b7HIu^LMWZ9jxad=8^0uNqN&WimYn&{AJBAhJp?t5s%-c+%H z*}bWW=BVYWTKox4&I0`c@G~zQbPv%BOYTFgg-L#?UcNqj2EF>u`^_2Ng(g*RVc?8s z6|DWSHG7bP-xDw&Euaw(TD%UCnp#;y`QYtqOkDOSGmJ)@ z{`_k>V_#ck@3_`1}ega9U^XLX0fF-|bxNG6)E%FyesTCZvrcgxc=?pDq zZ2jBK2t{n1t|rg(HvqLWbC>dP+hX*|FVoTsJw40vbg}pr_qR@ich+j}55MmmGn)0! zVd1t+j3l~Ewyee-yrZLGRA?~iuxGThNHmmttmgJy)1oX_eW`SO5$%3&{h#r+t=o@J~oaGd=mBVAJs4~cr1b>PqCV^Wgndv#{a zzb=iB>}0Oj@+WDE)!3Gf*;DGg5vIR(2u{N!{uWk=a0K=8;Pn&IOFOCiL7@O&(S0$# z*Jj;p?xS>|){0JPgikoKZ$|IVc>NCmBeLHIT*jB(Zx4k_W+g7}{aS3!az#VXC1ibV z?LIUjN?nq=CUEl%OKDZ~`6GDDUGvB9AsCRZGqu)z3m~m^H?p%*App_b zU!aOZ8zNMpqV``nDaPm7Te~u3yq!ojni&AQjB@!eJPnfH+qfcPdaotO|IRGM1yV1% z_Pze(r(S(|ymIa6u`!tUf&zXNL(<+l?31bAzS6LHdU@|muqmWnay9ewGX}-jUi_8% zr2@J@56D3y8IEbsWxM@uLl#bT(CKIy9@U8B@{v*SaMt59VUtNUXo ze0jP%l|FO=73Nqz;!^p|(RAWt!1t8(47Z6##zm>`K1NjvFZ~70sLN?8dnPMJGeiSa zuO9+K6%oOcwi1Ow1x7{1lAfu@a21EKQ*UW?!-`#lMlfKLqNcLMS}IbEr0m{Dd0b`Z z71P$z_w}ttP6ng+&KSI|@m{r~4<9a_{sIcZtLzWe&*0qua~8y?vCR|+;tmt?nr%B2GS^fyTpc%&_zBmij zg*Jn?hDFpk4Jy8D3%dU%DO*QVM*O&1 zDN>J!gcnfGP0;HHTXbuu=uzws(+OTQb=nY|p(|_m*yvRj0Qpr+i45=i{P}l=_ugA0 z2lia3^qG7tGoRAiYdM|J-oA8IBBRHyuF|?cQ5Q}Ym_s!kTJ@hqB(BRxoI^;ush)yt z4}06%+TcTjbZpQdj!8|&X|ShqjGYc$6eggQQdEO+pa_5GH3zuUtejfCfxztm>c*#a zVy}lCzi?h;Z6^%tJ;CGQfq{>A&=hbY6YWWb9;&nLno@(AP%a4~c>uU|i=V9@ zljUbSMND^AqaN=zE`&aFtKjYz2Nt$&)g_!T`7_R#6 zR*c?}n=9*w1v2-{NPWQe>Lru?&eEQ5?yWsq@|)%dC2Y*v8@KEXrq_c!mkVk9J`LQJ zFvdNfEvnkvoZj;qtC}v{Y9XQD`Av5(ch^`r+f2Oe(9gL0Ng%EAj@14RJ*8o(1rUXr ztj$ilP~5A*SztOZ1#G{hgJTiEUvStqJkcZ-mPZ$g+giBwz)MKK7sifKO^|o%4#_@z z(cxN)OrXc)%i+>rfb8+tKUCM80kcB-_*s5{yP#pQu16h2d%|}CnWA7d06frEQ|4H!YRI? zZG5k9{VqFPY`E-OWg_+G6;J8#D~`ciR^<0mmF^!X>;JjiU>v7S{%ehJIbTZTS0+q> z&m@va0kT!|B`!x-)2R#OQ}>gJjWtgqQXk-k%AM3$!o#g%UvfWLSA11dvwg~U@j#(* zuNydNSc*Wh|K-or`}cL>$`V>e4<67|nH1&a@h7y4mU_gp2wqb@AATLnp*&TGwtgN8 z5ILNP_Pu!WMJ%^2lkviPKgI<`YzowVg8ClakH*j*7I0r%9UNqO{bAfAWj#}gh+EQf zvRWasvp-NCd+U7)LFoq;mPG0-<J`KWp&Ik-z0SA4BU=@37a_2PU zE_gR58OUz6<(k(lI>BMJ_H*MSXj$)6O;KD%D+0Fq_xFbTwbv;sI(lbV_a?=&V9);+ zO1pf@e^H6N3Xivg&|DCI3!7E{e3^E~S6jSgOV zINPwgaw7mYg|IQf5NL!s) z7E!3)(owWimi_U9@tl!#(E6BZLXt*n$uWk~uzb%tN~dc6uxZ`!nF7z>94NOV3)32L z6r*ejL8I+0&H>GUscfOEF91mL%e`#dvMQ5FF`8td!afneq4BuChRhL2X#Suv&j+4T z#=p!Z!QV4bN*AOI=f}lA%UG)lMu(muSey(C(-Thio*$748Y?{0*JMMc!;oX}8C_*{ zRhHX-272^_V*KSjc4G|wjx4k0(BM!gUJMQrB-pK41gI?5Zlr4umA;{~VqGX?&#*0~ zNocqE7v#IszP1)S)xmgI*j6JE>y(CUY&mfnoVuIR_q)!{t25J(h#bbgms$8Pp{Wry za;E303Zmqcn`DJe;|)fGed!v(B9eNp(BK((5i+}MM`R+AXd)2#=h4!l`6d-}0Ff2y zIqIYwxaDJ|)&eenprN6uksTHNLh6pieYrq;IFE{&UR)H*{Tv;N!Bb)GpV5Bmw7La> zK`|6Q(J>#pRKpZ1Yy?c?2$J`I2UB|5a>}YNB($1$P2GKT((6{i027K_?h)|>A?iXF zDa-v<_w?Z4-VvYKIyDqN9BBeqF-?Q-cfaxN9~&QSvgHQFb4R5w$)7jND71T&$3eH=+8p-d zVi!LzX#xt7O%v&~-F9u){bB8(z%RXOkV$e)N3h&^Sm~Qw-N6K$(;UUwrApT6ni3y0 z@mO65+};Ll%r=~Eg*OX!{nqymYA(7SGyo0y>n{hKg}-wj*Kg!RnVXl+$43bZBnvfL z1wzZcAKjq}mv2VSt~I}N=(VM1Uf@Ir99M}S9{-)2+g$JqGCMo{f`aV=q6G9Rg(S-U7f@ueGfy8%Aa=q8ooj{@)%qA zS{h*C8YFZFn{&7;#KTU+u%dI*#>UycqoOO*RPea8-SnwLOzYkflF^_Y8J$Nc2 zKX)VR{#=Yf`mGKzTv@!Ns7}0OpORRD-19FtI$6;%>o~OgmhG)-jEcbAS>_W?K7dfa zu%{H#B(^l#>l(3lBx&wv?o};M+lS*%VF2%r2vx3FULBNxH05OwAD$%b+%zzkkbRqX zeDJsfidSzew^vEnK$H*616FHbro1pqX+cjwy)!|8beIN{)Nvf554AHgOdtLCHpi?u zMUh`4fd%(@q(pHXE}G4zzq0y3z^qH=;cuADU0R#^U;m33cr=s&l{PVMxqVr%OMlarTC zzq!njs5wv;2$dpupAWztSoTn%L{u8h)CmhLBZ=GLbupg*Y)d{ZDg*!96K zdMu=g>EVx|p`lr)!R~bTMi>&)Jy30(NH8xk>`fM0@HX%(IcLBMG2qw?bF)!_=#koW zP|XcOSc3g%g(+Fzx$bm$c7*N9YQP2$*G`+7R@*c^q!t);LE7HW`t7|u-6BB}W4g>j zXA{O*kS-Kq*#Gxz4Vx9JSMqRkQ;<|xKlK@*!j>1(Ol z0e@~-+E2WrZ6v%%^o3Or0Fojcy7=8hB&0RjmKt`l?d`!dH{uh;YD-_mX6CyD`S^6f zX|7wxq99(;{P*8KX7`3K*>$B(ejIdUPCfH(vRh_veY3&;&$z;7Z-Um4%;(~0BZz1O z;i~ujaU$-;jeN%c_Uroigq z*HR|Sbdi6M2fFhwx#4Sti(2UbP7kz)2c!UGc-_b#X<3KzYJdp^6h6bg3mMDvE@L1G zXMXtZxHgu`>6|#T4#t8V6<)E^$sz9RSEFG~(sydUc1Yp8^m%ECqH=xBbI&R_N)+~d zCbueYnN(mh+a-p+kh7XpXuUiUP{IxLd^+>FDU}{`;JF(MRjne{*@*&@*ifJC6smeE$qKtCiMH(6(VANN`sG~g!Oh?U+VemG_> z_QuuD*qATlD2jvl!zC0!2LpT1kBLLzCbEbh0uVv;D&%tnKNoB9<5oh_sSz}4n;TDs zlp^RHJg*|6q{#5W{{H>@T|!Pz&zhb0TXR-u_JIU~^QEH9abhjfuHSpsqRQmh zhgW)kv{Z(99V(2;nY)(mkScbEHSD%jhD|Ga_}f}T{bRaL5)ZiTo98XFi`h9 zUjUo>angA!5nI&e zwpsDQNS%j;MKR?y)Ov$9$C3qQDVQXz{nY#K5J%Oz3sG@^g2u_18uyY788fI!dq8K8U ztR(dKNcB?;mE{RM4u^XljHXAfEp_v2=(>Ix8I3|tp@wrQ0?1kIr{rrRGDncBN3e&L zPDgNZW!XFRI6dfY?&cr)-AHJX&JZl}@%aYD69#1cro_GXjCTS(`bR`XBNNMoMYDCO z5Qp1|eVx>e)VK+ibTrKyHo7x6h-GgyRr2qWwmu0t-5vh=Z;H-|OumA~9xlti=IZiH z##C_7r5D^3_NMol2UMe_d2q}2{8!oJmS7)uq^qQ5}_*m~D zyjd+?5nMG_WEC++g;Cc_hw!J zw5DG`O2jMUdGQOTrM-ohPUPlV1CYJyTi5%F#|n~Ev#+b?^+Se~Itbx|iRDJ;656Q+ z7dUj_hJ}1G%V!iwsli9WS|={UugO7pQzS4^rt>$I1M6AJG3^olv6Z?)_ax&7#r&%n zTdHQmSraSMbWKv8sCb+vlT%r~egQzex5Y1g^}HdNCN=+Va@*IJntX!~9U+*&JQcCz zDV@S5=Wl6&0_Ct)~#?LY`a)NP{S?M8dyIEOLSp0=Q@sJR!#;su5 zCx;PinR0ZQVEH|-Bwrnt$U`6t!lJ?ih%GNDMaJg&6#Y|gWfP8NTtPxoBhU-`tGk-q z!HpMCkf(yf+o}=}D_dCPE8h;YAT&=zxlbr-GO@LGc}k;fcu`7(W`4lHjO?KZmkiD)FpTNq8VCa)3io2zq{MUG~k-}Qk5K%T_&qN1ON2f`se z17&px@8nO4KOgdr-BKOdMa#K;=c*gg1F9WUE#+^k5=){*t=eyxGHaaM^CLqwOLu> zlM{)2?O2MG$9BV}$C;el&>a_&nd!Bd3-jwHlz7w5#(dp^Be1?_~ zL`^!)rGo&yCB<2yqf^z&tsbt7-k*ll?^pbNLzd9{KNz)}Haa z#GG>dXJz_LW73a^Q+HJaGBhCjAkGr&bn+l!ss1Pu&kN;a3vy0mY_H#Aq8XF!nWj!N z!u6M;Oo!FKMp9|S1^$`I8zh_BF|(0$^Rkvw&oIxA)ZI)}W9m38Xn|l6ZY)ZPNffo| z97yS`I&qmgCI^EF!y+NbXH+lD<3dRzpOQMnQ$HKgqdUz6!h7~s4OtFh2nZF#VnTnk zrIIpMQE_3onwQ}s7Uzhu(xwhZ;1QH|h2{wMNR%ki0@8wcE=SfquJhIuvc@mH&aGST ziZR~**C5iO;mlwb^xFfm(_&E$SRCqY*X(TL0{PN!r+O}lRnVGBftea6)PjrQ;t z$V2V+0Z7Yb?4ND+li5FlQqvPJAlX}RN)S1u#C}M}*iTJDu_EqzybpflBB&|8@sTvoX17TO~ zHHG(#I0@j(Hk#EhxF{(p>GA6-nFhZy2E@Pbf(qd8*3s+pF_$Qy4KfEYhAIJru!#H} zO2sY4s<_>^|I%`2ty7+*IO08j(!cxlWFdyW?-}ded=Vb3#9G~=f%ANyiDx9wpNEtq zn(yX*b5j-bx^=^vZ2y*7&#AiXt@SB9qI z1RES)mz9$8Y7pK*5JxBPFa3jd-*x>0T7*CF@5f;eJI1361?7U$xI-epX;YPMA;APB zOnvA~Ct)Tvz(d#amb97$enpQci;+LLJ!*5bq_(+6p2S`0?# zrKsN+V+a9;ZzPh1Ufhp#9g9DsJSitRJ+$05$IbwbGgUcSHgcO36O?|;wn9LM9SG5396*Lj`S=ZtdL;+@WJcH6b28Lh+T$)IFpI-b~C2oPaf1|b;ubOEO+@ju_ogMRw^lf-V88`NEO`Rpi6`6u|! zJw+vN4oWU{Zfa^S1eOQ!3deD=Ew|E!vnYWZ+&+w95UhwgVj?O%ilP^lKs-24tyEN) zwbpau)KfA@rbXaXMQ&mp`+Yrqck9I<9z7a3<<&fv!O06E6D4 zT*Q|jQeva}M-+n028N@J2IU&wdZtH;b8df$?3LS}OQ1W?bf(gF3xG-!Lqmz}kzy2= zVbMBpp7Rh0RXy=Hn+lD}al{$_=mqk(4 z=H$iJ+0Vvn+y0P2ufq^b(IGP@cWH5%p3SxyxD)tGTrU!2>_uL4BAVUR*BIf0F=`Xdxc|E!CtVD ziW404txDm!#hrAjwP--w2)xa1y$ZvQZ_~W!O0WOUd!hKw`9YSEV2#P$mdCU@{4Hh; zkO$qu!h_1?XUHv!%dl(;GYh$d)TIu?D3!|{w(k33C=Bj4yeA6Bgg4S+qt=; zZ>)v2pj*S3W?j#hml^4&o>m9n;H3O-ie<7a1^pGC1pAph?*mfgDIXPHw1Tr$7pPtge3d%@wqgVtU3g1z1 z+5CVo9TrqR3*w2YZ0~0t?o#6+f+$+2iNId^QTEEKkwQjZD=Ur*#>;ectZ;{9iP37m z^2i{7wW$3O=EEZWE!iC$k`E>ZHfscWX10#82 z7$;DbFlIF_z;Ya~fXY z!-<9)?5B)@~G!%41$G{EB7(b4s-=KZk#mD z=%F6s1GJ#pM#z7d#5)+UXlk8+mAqO7&h!bJf@2ttxW%kZ#vCcDs`83mrXd$ znUa!>Ft(59$;bWl^>8ThnhD!XmrEl>W}9rbaxusrTx7USs2ky<~djfAolQ7?8qx zbus~uFhEf>Q3YG1fR?E)rc*Kqa5rFh#A8ywy>%BjLAw6gC>oE5k~d~^9(k?6sG;w5 zIqCKjiuhWr+PV0Vm63%|+@wu4=w~B%BSN{lAe*Ys2oMiI3sk~>wvkBHsOPbv&>ef6 zB_3%@Es8Nh)mXX<^L&~)Uaq(ftcGS=;{8%;M1$AZ1L{XT7rE(uZAvMTT1J;NIEtQ8 z^{a(f#_eNVzBaH8H|XdubXmoXH$0S$B#cftaJW<&rMk5UiQJ(pV7+#*S<{@*Jp<-4 z*yrjuT5PadB`uADb4(+#dwsTN_s1z`yQ?Xqj+w``c)c1=L-U4TsSfwWDB)$6S0oHOh(Sb$@F=QjL z?Vfz4YAY|d!ND*$Mwtg=qnaoBU%7F;g=J2|+80)W$)~Z?2s}K%H76Ac697@^x$9#i zf(~Pd2l3(0`C$4mSk(Ju-_S)Yj?gh?*?XgZ4VL4H&yC&jf8IJ zKaWWYwyGRKGE%6YrF<{?@k^S5I+cRmPul5c&yubG^Fq83R;hOVzg_@^^&PWt55F~7;HmhsID)E~ASZwl{W-fz# zB0^U(*U`nr#lnIjcq@ZN5Xg%;qH4xh$N}sT2&}uEot>wr9@eOIHsZwMnBe`nbMc|r z!ICJVCCxEAVe#~!olH&#-p|Y9H4Q({dtqI)oCNdARPw+_Us-8oVZoi*Yinrp5Yygs z9}#m5Tvsf!dZeBnh(iN342m6yXOU0nU!4f$BF(K^AaNywK-M;I@V2wC5bI9cV*20$ zi}WomDJvO08BHr6KSH+Eg_V`X%L&oz(QdcKKKT=0wPP9C(X@~2qvfd*Lil4Ewn&M3 z!EK_{ut4>0dM%+FJ23k7Vd;GvAjQWMeaVlx{_BUdpg?$wimU)QEXw+xGQAq9iT6v2(UZ%B*8 z7|zBVQ$9I5TJTTrp48F=?#!6?bZe^d<`U6nbYr`&^u{=vxyK~+{O{$;p|edt;B>(V z3d}wuFl_wx&9Tm;fK{D=;){LN*;rNht6po~z6riGonrr;{>%&P?Em!-NYk~vI?Ks< zDm1IS{8aE3p{OW|LH*t+J8z?c*Yes-w2QEjY;CnJ|9M4UCi~6hMoIct>z7fhCqxB> znB(1?9G5~RJ@4I%1t~j|=T=Gq)*9AH(bG8iW2_QKM+u{&i|`4J8X9STG-fVp&9@Uy zx~nAIb6(zcX?N-{kX!%nWT|n@!O!M{)#^>1s){_J;38s`Uf1x#piQ6qWWI2^ak6v% zE%tCFB=YiOWsc&x9yLv8eMP|=x{d5MXeOn5xx?m)cTLNd&y1#vbQ%s(W)VBt--)gR z=~RbxuE8xZoG8x0M_GDrhXxsf*F_{>-I%l!v{TnGov03ouCiti^G0y%%6vdXBmxp~*&soYgDv6HTZyqp|jLnu2nPV@|priFw^9yPiv^eb1? zB-vd3Iq4BksB5vftn3z~{ymL}fqC(@)Dx(iSfcOFUk+H2OSfQ`nS&||{Hkp+hY4kr z->C?hnVAHFi`{Jc(en0;s|!2pnh#~qaKjK1|HC&gMPcJBz3=snq z(`G4ASEf}I9lCC~&{sTPeDT9ckl3RcO*2#Ns?RF1&^IVkPjd$=yK4;Z9K^kEi7?2+VihG>V@qV6SBZ2}k=QBc6AVhsg-Pu)RCU{S45dXrS; z>$hpvPW=U+E!b(ZEo?GvXdMSwa;8(AV;c9SvpbjM@`V{GMF{v)p}}V+Wl| zSRUqY0s>|SqQ{B=?a+Y3 z39{ttI-ZYf+m;@6n|-(GAjW}~ZWvsiIL%--X`i*&n!~>FHhz|P-^L$}5}injFb-Xc z-w?iRX)`;vwB(_~o0EOTxK;G6V`^+f_ZyyDkY#L=h?5ame)zCc95mK+k%Ze2Nk1t| zZfuocM&W6$6)ACZ{tf)O)ofUdsxU(XLNFL^XDiyLRpEG(=nEd5SPc{fya4S)G{ zi1PTSnU5b!>=Fb29_%{5v$GYvHGO?}(o8Sh&9KVI)X3zW|BPDhSC+5WCO5qcHBjncOLl#W<1W*%5W4Z*PTd=cp z4bEcs93!(tWRZaMSDiW%qXPj!Zuo&YSH&tQ()j1o`~44$Gl{3|0g7g3l2V<+uihVa zg1H#_q?A}amX68YmIz^H=11LfYV?{cE|G<+YL2=4 zGzD%}eKo4`1jAQJ*N=-gbNHdpN0D_ClCkZtEoQIBaqj0j3ybKx)qQi`>%4U2|D@jb zzmUaB0zIrp9aOC$TI_-;EoG&J19otGY3Ezj;&AyHhj;bw)?I#(iYxQpSC`5XH;i(% zF9D8J4eLlBycK9?M~FNgo+E(0$9UgRHE+nsiV;PjHE2`$k)(t~XboP~h!wM7uTDAP za0Nfj5AW69C`41b|9&RW;ZkeSwzIYWshoOl_SSc{nHyF^oYg{z= z0ZNOCFCKrp08O)DQfjnFCLfGlG;i|1&-hE+LyHFEPlcjTy9c)x9zkie%z=L zGw-d$Zq~CKL(#jZ7|ElRP808DW_U4(4YQuKGmXnblBM#q<{GQYPuWD!)F^qj^e-V_cDc`p1aj*L9k zR-nbt_;9pOQS{HATkn3G;=zq`H_2d^f(#@KHdghajg5_qi&%Fbe^m60C5sAt`%EV$ zW^}-ikA2B!mtuo}U~I(OPiNg=Px?jSoudS*fc=0C)mTQ%qv^C>y*yzT0<*}&{5bwD z<}UW1jgU@6tBZv~8tMs0M~ESvapjQ1#}MI8(ZP}T_xAQ$T3W#2kS8_^-eK~{Nb;7M z?gN@GcEGhPP~9GSgSR@_Dtbxy_x!xyk2?KR=da)3H+-R4`I5fi^gJ8IYoV1TeV6lyx4|jP=krbF80U1$4Hcd;F_nU1m*m!(=-OV&$Lh9s0;hu(= z3~8^`y?+|x&VW%dF4dEDnZ~lvfUOkPqI;xm^l%80NwMw)pI?ihM#cR!Kin{{8H$4Z zgj6v;#v2aH?d@S=1-ZFYhv)Aag#4;um&HO$(# z)o}IkM?Rf$u28>*mT06p>=KDatLb`dH`77aqGMdMh!seH~s@cYG zZ%56DYWOGSVXYY{hzkViBxl)x9ny4bUq)kFhmJzG4g&sf*==(fjM7||FiI34B7U0# zxhevB?2xD}t!yDy?azIVJ7a^Oa3v!mvV$2|uv|B&>Er1xzeMCRB{G=aeA;mEx4#z_ zEe{SR%LA9Q1(~hXdWv6gG=QC=)2MqWjHq_)HNNa#TVkv)E?i8nL0d&ZzigOe*WBA> z>(8H^jYT##HUdS_R-pUey~+3h1is6!TrdlAwm|dv&48h(MHnVVZW$&5XxpD<*uF|H z*RXt0c5HliXXhx)4U={|me*l<`&us>!**HO9h^1}9jrS@WtL4u3(L7pgDC!o>Mbb5SDt-}?3A!4alHPY7+Y3m3vF$|Fbi9m}xo*=B}+FmL*3m7kT7OY7~ zD!FaJ&VM;8I5aD-HY95)O}tV}wOyjpt?cUqBzIDDtk{O?{-+tibkp>@>*n}qQsRHB zr%}g3G1$PJ{-7i32ter;H++%QrFz}by-YQs^szQKOs07}6qvblx^Bx|uU$z<(gb(Q zw$O~|r@~uIs(J&?Q`OrKYgPh(#;%uNP%si;b#4ymg?8(4mZ*&H=Jx*0=Op9{o$36| zACNYE-fQVX^CK6F&4tMcS=+*L8trEyRi8~VGvU#6odGv<9r*cG!Z1LyFB&G!xcUHE z7RE|=nAk&R7w5r`YmgNLVS9j{YzCs(=qP|!PI4u6hg(2p`LOh%v$I!^QlnTHE0%$2 zwKGLe$AR~RNLfj4iHW_Um#5I{uVtxQBV5Q0;)P)1cUrLJ0mJ3Kl&R?ii4mFA$&RiX zGT;!cWFw2u!LrGLYqZDDal;s(H|J4mg+5PpDQ<&^@de$!%C;ugZ3&e z&+cDFo#A5*L1L(>FgO~9h-X4VpEcDr=zYY0ulycsva8ork&C{#8XSz6yUQWU!K5wq zW3fDwC_JpXd1CH(ozQIxDAXe2nzl7*BkypWylDb{EzmHWAbZdT%#87CtrCl{9#H3mmvWbs-VFP}x!y1$`RJQA?-%rVnV z^O~k<7es_ACqR%InlBf@67hDDG=r$|?q#C*s928t>3f&~IYk{kIeEcnRh zL1OmZ-|@gLFRbt<-L5iPhOn_tcCveSXEqmoBpiQG`dURB0{3@9s6-&w3XI*bd1rGG zZIB(TJjh(K75U(_s)e9SPWHNsg85kU;mCU`+Yzi`B29M4r^IXxvhQ${n(g-Y_g1~~ z^+6vtv$v+ahGCO&QhUB(xjMCJKb@1*D4}(Wq3fx6!5AMA&&$+?vskTv|m+E3nhoAGUfLKyD3> zRziZYeC8;_96rV>Bbty%eRWMuIwh@QT`V;+R8*n@SLDsvnVmFX0IM$f{@hV(K;cTc z_r&YzNXvCHp2b;v1EC8JDRKH%pjIN3kcQno(&+nAz*cbW$+v5D3~iB_>%S`2Nl9d| zi5k6X{PFniR`brn4`3m#mYLSC0Cs3o&3J(c)7XoU>_jkVGtvH+kcDkm&dF1L{%$Ch zZAv}B@{*+mmt{tEt=pvG?PI26v#vZ-#aTuwM{m`JIGvtm5o z{D=8AEf6Zy}z^3J*Z-1srsD9Iqm%U(aI!zvLT!X zdn7e62g9NYojdlC@OqePrI;+RWK1DTC*Soe?>vblN%pTWSopovHM8Eyj_ReIv>i$T z=vAezfQN?%r4}o$D2m7*hOiXJmsSVudvP|d_jmymcdMoBC zYk7|Sy?eKlpV=L{#(Lx~<1w!jz>|m~y5h zN`25ro8wnQCAPz)4A#BMFUUQTdXa{|zgQ_W`Z{ppbG?+~WW&L~)!~y(?!SQ*!+v3M zRbTO6rp2?}z9fasslyM)ZSR(kRamkX!v_*wnDzrX_zg{^Ctr+qv;^ z!PE#TuPsl*?px29P4 zm3tIHO{iFaMNcIp1hFuqBv2SE7Zrb2Cli8fIxFrV6ff=j>-u{}@`Y*&TVa@i9F+hF zwC~I(EaZdDFKd4ljln;A%f$L|W*y6AIR{rNqvHdri%_-~F~vs}NiJ179v%CUK zzWl-8-Ow!;LWn66FD^oG&2lmJruqCF`&-rMcXMp4+b-pQM_TWN8RRbZZ6Saut&usLkp}lRuF9rZA#(a41*dpH|M%tRGHhV zs=^zWQ&F-0*`_}^tMBVqJ-btFczSeM!qvxI?3~R80*SKqGP>N;IM!eyr5ZK*P1l(# z2k);P^j2@K6)J3e{PDvSdoMyjJn706y`LOwvA%6%TsbHr$n@KdrKeIW* ze3=^T!wE!6A`*H5lyfP~mj_ot&P2iL^BJqMUNdtOBln)-1r1qG3s%&REBQL}1I2d% zTngKTe$LM2ZaseG_SjgWexBpG3TNIy)!fq&(gj_~CJHMtt$W2UoE3ISKRRY!6H-Wn zw`b(!yf%ITJT0TYuxBag;CuPrr-{^SrQ5Jr9gy;`{BXtj;Pcc4=|{g$@P-&(Nln@iGUlRDk8T9-yV+eR?u z*$=B#ggP?h%M#z&d`^KqZ8wWMy4Pi%sEY`+aE+m4Azi0LB|?!Iu@GSws?J3%i7juamvK?^ILc!-q3hHU3X& zWd1KQOqIkaB7%pq@qM&6 zj)sv(fUVw4+I?wz&J3PDhoO^le`iEYGHU5Ji+dZcJH)OVvd};VGyRNfr1R_A5F8FG zRKZOpiRPJnMysuBU}7TU{(UAsULF*O(rfl4F6GM6bMl9?e^%s=zV~X_cLHFqxCKO{ zv8x&&tgJ=l``X^j@B4a(wp8yiKB~hcg||nV(wKvPK(;)~xAdKfDTCu{6Jz3AFHiTk zsJr(bvo^H87K_l2kGORs6ISJ(aw=|qHQ()$-)czxum9@q zflC=pY1sySk)w)k13p-<1zaS2cZ@#g-h6tRAv``FWdod1aGvSGKp#h=iyJ{6rJ7nX zBFOUK>k^feydQJr#PD){b&V|{Xmql5t^isS43_8E0Y^3^U!#`X=`%wYexBS$)z~X^t6U=YR}JKTOO(P zabthNg?D3oBlW0>$4hlCPE8@%Nj4P$Hl|~*0kK0JX~tL1q8QW zuF~kf8k0I#-l!bl`NN^#3*yg06f?m1yJ-5)k6d-R2HWfOF>c4;g8=y!UtlLCA@PFe zBd{7kyF6;z9*(PiLUeX^#+{cQP}J0P@`lhii9F7d_rG!%-kB1oVmoB&b9?W8&iOXqbWl!r9nZTI25jI_aNmfvun5 zT&Un!ussGhr^X`Z&KmSza<SF?Ygb-{?bTX(JG_s*(Cn1W7Vc8n}BtMD=D(qp~{vlv5v|;Ix5_MsxT4;xy-$t|B z{cl}vl$w>-7~M)#8|xGN`C<+Nm<|t4H7`zhG5-Jn=1wcy!9JbBpOF4S&8M-kpeXJ2 zLpJyBzn@R1{MUP!FU7&an7Qxw5KUtaIau+r?Md4kpvu(xB=ykj6wXqr)0%*ZET!2$ z9`PK1eGar>sXt~a*l<0>y_~$kciyX(3Yq3LPLLaf7X$PL+@$cR4pws8Y?d7LMB))D zVR&KFcd#!B28kEiya;Sw2_Dl9y(<(1pq6F+YrnLx@s21n7fD4!MSRp*^uRY@Wo%$z z@O_A6xUw|k+R(2TiS61hhX?v6o7N&;v{0wqH)J_2kkDFwuu$JAV(N1+niRNQHtsxG zwc&iQaFcPJvuUrz{NVdG^9K?9RygIvMt7U6=d0UiV>dVb{fy_ozo*jY;{#Nv7x_#^ zqr&*t!FZlX$gtc0D zQ4JkR%YXt4e}0#9TN@k2MEDX$(rcmj%JKM7;=+%%o5$qj8f589w=S20b>~Ptk$0OV zg;3E6o78@9yw(|JksQ6&-Q7+6L^|Ra#fZ(g*6Ec*{+CkFnGA{a5V~@=@Xj`=;zvNu z5-jph-W5*LOb4|8`E%#;a7Rvk<*Yk6T}FJQkeFa(Yhl^wfA;!?e7gBH&E+QcB5Y$< z#ikp|(3CBRc>x>RdogDqyCLNr1O-i2SG%SZAan=WZ+sBh3rm1EB1%~aOA>+XjUYs|XAl>~2BK=Z5o#-%mSS@edS5`}1+(0qNMMe)s^cH0HK1JGQ_*nSZ z`TQ){Fc16}%_f{t$?eh=j94(~Br#MB0fz($qB0`}N5H6Q<*H2+q`N-Mbc8Rwr+NY? z$)R%dsRu)`+=y6JtH0m2fBdk(Np^k_zT4|O9{S)A)A&6AY&+4z+3aj|l^u&_X1NVvzAaEj7O--nFDwfm4)j|)wD zlR=UST)(C$|JFkSCBO4K_ee&9NspZs33ezC|2;kY2aDNoZ3pcX9&Q8XO2^oEM$mj) z&D@#XuX(s967)w=Vf*7#uMJN|#!bFk{eEKSh^=E7eF{;>mB~3&+=QXh6GC&tWgOmHek%>4o~w0pX7A=_v$q<_Ne6SMG98`C|3*Gc zu9qtM_`77^KT&Sj?{m0MzGHM-U)Yps>fCR#dA;YK$mX5Y>v2KLR)+;fB@8X*-|p3?nS)x#HSj zoPCs*E83Z7CsQMu$@B61cP;?P6(w=#@-pHPIJ9WIHZ7M~x(+;B^0L>MRad{ajAdk) zdHjhavf-dKM^NOIB%cWuvw?jn`vu@w_>GT!`hUBNqlTO61{QRVP(2FKPHIOzQDdBk zpty)KkvhDHTI#>&)|Qr*!z<}T27WH+%TcVF#GF4wGgj*3C&s%c%FoGcE>-S2433R? zJU(^!K}18{41G~8gApr-@*&6EhY=%!`UVzZ#ac|{Z_&D#5qoUCZmrL9qvbZ;7UNTR zKbl7EMVYf;zxZ>-afopxLRP&570)y-fdG}&e7`N?{Mb9mIJAwY#%We$=$8nKB7vU! z&_>0?nzD0nq^73cey+<(eVQCACcvVq*YGC$ss=6`=7k~j?o`Yb3^hg{VU>Cv*oq^x zj#myxGxw9=Nv?n%;wB8=fGYBjWUBzT7(w1|bMFV|!TZOj0`2_$r^lxbdS*2sDjjHX ztGUBv8k2|43UBXs&*~H-N3;?e_+Ow_0V1YXEP!yJwA90`PDUf{iMN}S>V4?!l#!Jk zer4E3LR-dYZx}#4FErEfWngN2%MeVAf*11oHQ%!G=5qL1+KE0!`6b>k$p+Y&M^C`t zT+Va?0lHC=Dh9-YXX3@mdfp-~Y27-urRk~0CKVowo5NYD^T3?wDZV%oo;ZMNgv%H~0w2wwj0jclxxp)I0W zlxQ733@bY2`bR!K5&fhRh|MV}DJ*y9vg664HG|&;ih}xCnWYV)6M#Bji;EqAn)=W| zu+WYHgNqe|q21jGrxpepmbX!aSTTxJR;((n|LSKQ5lT2rqDMQ$rC|C2jI~D29T>1g zmLYMH2;Ih3DhBqx+Qxx^KP^AzGRCKhuKDi1Yu>4v%BWMIakbXHr5nzUz7SkSi4m<0 zp?Ignn!})D!D^+R+{>DDdXdgd=6Zu)FN`QsOC!Wy0ZVe@b49e@<`Op=)@;F2(geAM zpFdv_7KW`%FL!qXtB3c}-JZM7GLa`pq@~46=89fUZ_Ua>K1!dW=Qz#(@>RtGZ)Ugj zCG0|)vxD>T&|pHTMg1psTJRKID!dct>9ys5uzu(SRI(mF8=1hpfAGb>%yC6ixjnVDw ze426f^Yg1PU<_?xZ##M`jv$JJGtR|B97)2afRQsbHHD%Ti)Z;?6FyDL8%m`7-@%}! z%(wFe;1mG1bc%V7;H97|d9@WJt3{kWb@n@34{viV6 zjGO}jbZKpE?aNU5wsLP}Z=>&0SF!ySJLko*>g598(hI6}i^FVud>`uT1v#XgA6#85 z>}^=-x4D`B)|vd-Z);hI)v>Zpy{p|8Ya(>|W^YE&#-Fd_PR*r-HMSOZAq0kS6J!`P z)Sc`f{d2!I_--uBeonn~=@NYLoHd`imF4FCj4wZQYBbXygt(I#$Qbyyw)RGh7PJj^ z@Ike`uBjPjzd?0;_H`R zQ`jh`1J4x-`0@r;xL;MnW`ZmX@Vy(f*HBkqf`D|$EKow?LHg=`0|+l5lKDeIZjHh& z0UitKxegyxo##V69C%e&h_8ZW$k;(qx*<$<6f2h6JKTY9V`gExuP?_f@X@0HZgT-v z+2?we7=auj)L>k=S6aCLzv`;o)H`aPO*i2s0z#G&2~<)fb?b($`4e}-brbN6u8-~-Tx7k>{6u8#_E-LY!3WR5M(}n+%1PPw1}ylTFR}*px?}n z{JW^V&V-#>o1Nvjip!ngFJlMqL)85Iz*{|yCzMu!EvzD{d@$vy|1w9-gzpC^jGLK% z&{Co@fFe2vOh!302g|YPWHDYPsRgb;4dV?Gz7S6EP7vdZf{oLzvKwKlJHh4Kw)pNY|y=q3=_M8N>0 z;Qm_+6jOk})V+PngFdRK1!5|&zr-&QhuF1g28>=5eEjy!1I@@-R#S~-QCMGpTzJRS z#H1+tYysvyu{|;EHnkzru&Dg)%*}|JlP5}#-EjA0NlIeN>B4Ve8Cz2R0n2=e^IYxn z=6FHDrIIT9b0210KN_VLfX8r+;MViBaoYx>5&Qa>SoZg+hS;TMzd9=rOBB}P!M=7h zPXTGchW62XAFsp1prB^(l<3N5aTN(5P)U>DW5l*iLO^BljR9He=Ja(Y7a}?b%@9n$ zx$OKcrlLD}R1&>|N#SFzdzN$OANOR)!|?nu7ys#KNSxXB5Bv~!e%n6-RC??rd^4JX ztiCyUIMlq)_)=Gi%Yig9(g7d)_!M2}bMFm;7XxoW@QKHa93rjiIl>yox4VybcOP$O z311zPM%@v1K0Xd?Nn?Dem@C>!}4flF8Htfw&DP^m2Ve?BdK2!Q79$;Eq|#e zS_yv{#xC|7)@g3Ho?8?2xpDVx9NMl&aeSW5k4^&R96{8==+YoiB}fd{DJC@L%2h`} z&&IX2ueN~)%DLL+HD!m{PdL*E=`7aPSv-$jTiFZcX;^K1s zJ?aknqUk(W8hm!E&u{pihqBJX!oqiU3@)YP;gkr6hgC*UK|ro8am>D|%nWj?KP7B$ zZ}Z$rb347Hl6;IBIdeQ5tdaWq`V}Vl>Ds=plY}&*E;@~7)h6NWnkKgn|_o~m8kSa4R=4`s6p*w zudJ;-n%BTAdvkMBsC(or;(rod+)o&2fY#+S_SSB$Cl$wU4+N+aOv5iE=`c<^Q8# zw|br@t*B^TI@Bh*FuxM{^IL`02g2tJ`HL>+e8^a8XKfq`&ady<$4j~VI}r0T)Zc%D zOPkOr<+k^46(*h#MHOaoT}DO#4ThTkNyC5_he0ts?HSiyreX5GXxiU)uZ@pk`l<#D z*&~aB9<`KczR|mAC*u)pBh35NKW%YosYi$IK~=R$$(6!e5}8lk>P!^O@vW41xh9K< z+}f;1A2tAE0AFz?xXRQ0@3&vS2BFi}6Ij0W{QDL6wdsDM+M${qjf5Bng0|fe;o8G{ z>v_Ie0)pL&lB3fFYzk)Y-0dDbIF7(+GZisW++(H02w~NzizsrcEr$g~IQO^vd#|O& zRxR#;NR?z$t{El6j>8j+1X$jEing`1x!n$(ihwQ!4sA6Og>2b2aq+41ymuIq>O3ib z^{Q^kV2l`KG;8$F7)fUKiUwZ)F!AHI_$!oHTve$m5U*b#3N1s)-DAxLv zv=(mCbN}yz^S*goz3Ra}Thl#_7Dp^g){(^{Xwx>Ry0-S;vU3nj+9!fm*@9N54#s~1 zHo4Bn@h$!y9MQ=*9yQy+RKadUp>J zD>Lgw#&{i)t{5ghWSkVG9sfDf8P*eqoKA7n(q)jrC6|$&mEF0YtV^t?ypEfn=gE^P z;C8p9r1Cx{KH~kt(c%4nW>sdUx3(6_-~~;bT5IZ+*t)R9D7pV(Pb{_Pk!$cMB zmveQH-S|2R5z5qJkk7yiwJpSlw(_%coVSXrRNvjD4f^-*y>j+FjrqOpc|i&N#6*tZ z;vwQshluhqnI@n9P0_!K2T7c$PF5K&cPAC-T0eO7z@_5r@NhGXQ7&b8uhq>3E~IgsKfm9~ z*7OX#bK-6pbCZ5nB*5sus=9dbB1lZcR&~-Vf%adGApYKZZs-6};iTEF_*{|=c`~5G zaw)C<0$gqkIBUaAP$xCj)%RA&dnKEOAGey=K5O zDk0&&IEu@0>y`g(vkqvwvl2ld17NZ&kY}qIPm4f3Z8^JI^)vmgM2%?uH^a?eu1T^< z9Metq5NAFj>p?KK7Y@%Z9TZ5=i9Z1W6eX?Gw{&AEbah$D=wJ~1Q55u{-r1QEQH2B?*Pf^;QaXyA>*9&rvI}w+qUouhhBCf$A2A z%OP?hFJq>UAvkz-&`8FsuM+7_amuXyeQzt9-m`Ne_Y{1~%?NdQkM5yX-zj4$jxKp@ z1it+SHZn#mvBeBaLt?y-zRUlzKK<9PUQIA8K7_6>{Z8T62kIL_HO7Lc!LD`s^m86< z99dq%kF3%T=4p_$;5r7bImfx*C9ee7Zu2sae7j%Tv(_FSd8f})p)y-C5fPb_Wmc}D z%}#5vGO@Sxt#z7GHx}}-CjHP1uOvfaLlI2p_TEbvPAhJ6H2ZwtSv;1;V~E5;MfVTb z@7p045Fmn1ZTDCe_NI;1Z>7*F?o?!Fqj2nPFo1um`0vM7S@UYk{;6+^CZ{8`*|EVC zU2irwY9aczrZUOeftDNQ5`KI;2O8E48eGquID}Zh_%r5 z*35@6LT9k9TU+OW-S2FyWd-{OF^R{Ly>1Y3F%OUUCCv;um+5wh+WwJtF~_wIG);C~ zM?K`vy;i=(4Sr11CjVjsA;uFYXq2AGDt@`P7A_K4VRD%~R_ELwabBC-QRwp%3xkr4 zgpz#A$e%^7+kG<^pPT}F4_wk$(ya{#OBhhm$oGsV8G|5w@m$#KW6p-pbtVI{8_S-4 z#TC|!gS!jqcb<$2kwj(<0|#fX^!MxIy@z`yo(BHpaBgrB?_GzVwBJMC>j95j)zH>2 zAE(mvViR8 za2=4IW|S^`}75znljqwFwJ zCodN9CL7f`#gq;^sU}i~6yxN6YI1!lJ2m9&{O5;#A4jS~9tIF05 z`sAxIt(Mv6B3xKh?NZXcm)pT&m6VwH9CBlzUAUI2aVZ6E%tXT4H#o~#x&pCragP5x zL>fc1B$fzmmT+zBWB>K>c*Vue^OTNm6Y}$UpP2k;v1IJRG+cyQDp!=0zUVF^>;nCWm1QOl|9S_Ce#+UU<8cj+QqdVS2 zF%gay42%!|JTRdT`uU={DX^`!$Vwa`eaQkD8Qju&wk=`=NgrHAQR&iC|IJ4P-0BT% znfZn(`9ot)HTAW%*CizfA6z|sdiFUFgn=6-Qe<7=N8t(iPr#8C^Rrf`cwliOmgCwA zjN@QKwfl`+Z=(##!Ul*9W>{cKSLA-Uldb@Xom;)Vy&P7=K_XF^Lgnf7p%Rzg1~t!- zTgbFjcXwye?2T)_|MZ+Qd~KhO1rL=@_#Xx|OErs1$S90VDK4G&(a7z3sg`i*!XaBy z!7%4_t>V*Z-PrRSZKUa235!(+@E%a|)O=f`K+p5sV!v6}jrDi4D;{-Z%GN8HAvjl! zaa?nx zxWg6HnYQ4R3v+33L%cfif+t|H)GMX}RV4<{d*PxZdpyB4&5 zmqY5+-43V+o$EJdn-6!J6+tQjWcOd7G$yL?qIaMs4_f(F2dycHLU127@76b`rlmoe zeSP&(gBmVd)SA+&H%$R2kU;x{jw#cm!9V+}QCLX-H(H@O5w=fS9O3z2vsbSRzj-6Z zqj2e!r6@DA5Ixsdb4nzJs3uQ58}S3=xJ!J(CSDT<2M0}{y5ax`=DzmrDXX$P^z-uH ztT2d%;f4>=r+BR#!AZb=Q~R5f7xZoQZgY1UZc`vHw_w#vFt37%Z=$YrY$Tca&p=A* zyr<0K&{O%nj^1998IuPC-j}u9Kt&$DOGS9!LNtSDrQ|slh8foibrK9Ly_c&p;YqDF zUUn+%x39v65h{hKkRM!9WYKSih88!Df+-+i)!$z(&g#hRp^dW{x{y?ulS3_~%59jz z>$CMKq1b7N)<>L@NqnKPTbwhj!s5jYAu1w1{Q0^xOS`oYhd5RURymNasJOaNa#J(iw@^3Expws($7D^W z;p1m2VWY|fJmJaV_8(R z&wV&b6Ncc>4=@ty=uiP8D-4d_-@{OJG^4rMaWr3+`Si<3n_FA@C9F>!tsndrX`>M8^q7s+1hL(HFUzFS*C0EhxVP+lc(>8$@H?Heo3Mw%`Xr6^Z&z+{ zY=H^!;1{8AUC!@t*O`$rb(Ww{(dNfSYf)2~LzC5i3r|W}trFh4n^bVkd2B7{An8y} z(!&sU!TWoNv2&y3t>;|yM-4NWw;Lev{l<+Oj~_pV)N+0n1^^G04!IWgTkxSp!30gg zmy@4=pPx0F*RseLmyM&9pWOZV;pq|d@KoSmE3a>>N=NIThKZ9~g3Yd*OQZ0M-y3q? zAG)NldJF-pgJ22!0;ARPz*&h*K=idhZ0{xn6Q&ascbyNj4EVjtRLscVOY?U-bS&Kc z^S;`f)OweVn!XV$(Y6V59FBG7KTTZFxEG~u;9gAil8X@;q9mBbh`IGw-arLW3`2Tk z{Pj4^beVvIy>=+30HR83!XTEoZ22M5p`_xaDx$G(X|2+^n3>YlDOltiv;k#6M z>~XDuP(oC~RToHz?71y+UdC+}_M_P^Qj!~ek7kt!Yr~=8;cMdJZvy7Z0OJ>TL@dVV z*%3iqkw>@6W2w15yFs&=jb!C;HHk7_&X<_etg6@GsQ6Dfh4}@M`{b>7A6vY73)0&K ztwwD%`pjiv@R;8~Yv0J1k&iE&&-rYOERjORP?c4D4{GWm$#@ag(E#`D55I(46+bhgPBPbhqJ^sd~VB+LzYeU+lcRMRulBk+oXGkOI3}r1YCh3U=$C~=L^2fucG@GMRs)&uILHS^ z-J}l7uhPQ{LQ}9ILJm6I1?b-M4F0H-=Vbii4TxqEu zt*&yWcAbG20l!5pdhCUGsih4~!xoIZf{9G9weX1qbep)JVARNz_d6JK*gA1^Hf)X< za`0G45Hr}RBPg{NEG(rQBPqPgd!(DyvaHpSP`tM*A%#S0dH~hDF{p2qz(m1?reV** z2_YKTR*^q+vIGC+>t`zbd*M_AwN#3T+}<`}^fIb2j1^QEK)|i%c|JBVb~WQLg;dIz129XE zEWgAJYA{)1U*2{qU7c15e`V2)?z!lu!1^zLwzai2ZJmIB^8YY(=HXE9{r?{#632|F ziB2&g$(ps2b%?QqjBMG)Qiv?s_t4m~WtUwTBqSkAmPuJlWG9J)WGCDAHRt>LUf1uw z&VAkIk8|#r`F!5X^Ywf_o=49HBEk@NnGtxZVhOTA32DM-^Qy^<4g7+$p7xL0;ZU;W zEn3&AXt4Gk?zM$`H=I@ew76&zaM%nHpurcX%LjgiDmu5PNf1s6-!X9LDxZAA8^MU8 zRe+^h0a+CPO;w&Tknzz|dPQnoTKO&;+NTX$UYTZ%o}#^L9TyJrnxm@{s02f2Z%+8!W3!X5Nzm?TYz^>V0 z>)y0RHM`%;c@MLyxxbayW?%iE7eG<;uE)vtROuIiCg>5!je38N{wn7-_pjfET}l7t zu;G`kLN9Y%E$|0^7@kIc-bJNd(4KE0b40eicR{y=}B)^ff3Bz!BBF0aL*3X!OWEx4SM z6e%bxu(c<^!Q-d`ABOYITo!)mm5e&6&_5tg;RpMP2ka#3={=9p16HbEgy98`jWu>NP zabbc=IWc^v38hR8Th4kW1}1wu_HuIWi`$EfXHc-K0X2b@!5OWRh_miY5`=5&Xr*armTNrGDHzPei>(et#Oyaf#0v{ z?_G#+DASM5<9n(9EdANDdji7O9wMnP!M=$?kaGDc6nT@IcO9zH$qem{jsDJdd`MxM zR{9jpyo&X`q)&%^gQz&(Jc>vDt*uQdi#(MwGwKM8uZi^6yC^p- z<$Gyh!}!yeqx4Mc23{F@A}FdX4B?#NZaJ_3I(NVwJe(Sg{#!dlL7NW+a2AQOC2944 z0TFuWZuJOALe6JUcke!!`S!Rec23A+96G$RWC71EAaU|pFaF|_$cb90W4>{2U!_>j zf9lf0?ngl7fp-iM6@w@!U_$eCQi*N84nmPTc{~ zY28{zrc5TLBU(W9%Taigq4;yaY~ z)pV}mYR4RFKvs?}Sdp-QD}A}+j^s6|YfU1;0Fh;is?L$nDI58Edx80WhZPgYN-jy` zl3r+YS|rh1sY`?36ejUV+7mFUPld%H+01{3%rPM)F0%*?goG&4=Wwy!(_y3=%qZ9u z5MPeSV|`;Hj9xpN5WfdkD`eKH5Q;zDbr^SHLrBsDZ{xdW;*9Nc7Bh&pyvI{qD*i5t z_3qDH=;c)97*t$-a(A z5ky(vt4ilxi{7#Exw2AxYOd{J)l=2ZP)n{SkveBWb&{T|cNcsqB;hpLG_aJf?ow%W z*J8#Iq>)gF!WrdiyYZJ2FJ({J7?*ruq}9nOiV*LP5+yzGB25!j*}O7CEmF8Yv`3zb zuJH5QfXo6hRWGqagz+6%Z!pyKoH}^EAcQX7$a+;KD=jVJ_{z_YqT3=Ix}eLn@W11K zSD!+J>1|&g2~pgFJ`wf}Fu;C4`*I3Y^7Mo*s69@72G0tKA2kjI>M(-+&re+n7j+CI zU}hSs2JbSXa&Ex;81sF|NAB9SbnXvOk524}EgSd+=f9YY>ptY2Ju-*W_RIx27)-K4 zVj!Z(!e?jo%eU6YUrUX5518LJ4I72=gTR;b5j$uQs{b*uFw>hQ0*2|zc#BUOMspW> zYLb%6m`W><46WJ?rKinq3Erm9;JsHr?kLUnx5o_1PGJ`g&wqJRvs z;KTIPCR{K(d>^n^2-@G&vvZC8?3eh-DR3GKSUu4sDlYzI$sLZ|gK$(-r)(N90sbU+ z@Li6ADusv;KcpU=3$NVXw^|6<_LO{rltIXWw792;qW0s+n_1 z9hDMog9g;rLJxm6ub1m3(qj$YbpaZ|c2?wNnD{G&0uw>9^3l2C3lGf7IA^(zKJ=~QD(D%=i zUxgX^_)%P#QkFet*aJurXE7(s$UPm3cWb%dllLTP`Cs3@jE`_)y6MIK0DSNGq<6b36VUY@a}>0A4#H=o=^2n zS=u{S45Vaauzpfx1@>Y2Mhs(&Mn*a~-^y;=^9N4v?W}?9_&PPJ3BiI3Qk#%ptAV5@LO03DKL>Tv!;Xp zy@FAG;=aCE5=-1xWBDkP278|4Nr!m8vK7>;ibmnskE8FH9t`R7hIAC>(SQ+0;r)B&ff8v zP<8Uq$|q;}iU@feC+(2PQ(`HwMR^c^C$;}EnId`vLt1T^i z*9s?VU97Kmx)7p>2pks9L68k}aOj?DZXVhm>iDAybnwqFwzTk{1y;0L`$UW}m6D8) z-t_-|>pe3xHn#V8dGA4mp7sYlS`CCA9-Epfk2r>CVZcz|RsOtWC7W)XamOT0oyYq4 zOYeu%*AprnzEOcWVpc4OE@fDyRj0QpbjxuUBl@4@m>(Lpn~3LzFi>Ri3A)XfQ#<1hxn~4K9A> zOsr>h}QSRrP(#bWWf&kX+@nH`1={t{!R#C!(4H8%2^7#XR zfsD!q;f^UN4^2p`^S!=x{qr;m2>G{q`~z?{dAzn33DGKJvw(njx0KWrJPjw(z#{5m z;>XFo*?{AZ9(Y=Lf^_l2yLch~!w1NTCPx&&Nf(ws-7-C4)0D-MEvA1MNqj*RWf3s{ zl(F5%Q^8bhsB}dvK5qLO7 zf>BRRJ&1fbxw~&3>;_na^yqxX2dt_026=KtA~IaD=CcBwCpjXc$t~^0 zkrVaOLMIv8n^nMW&4W=Q8yun5qczRw&9JW?S<=78(3HM8+SN#zjrqKmby>iTa*`Ca(Z^=dc-mD+{L|$5;OM*Xm#;Bhv%vj?X zyssTfWI>6QA$2%HCN2dH8&E?5NkmE)<%@=}>}>7v)(7V1<}NOm>C2k?eSrBO={P2G zSw^>5pG;N(2}Mu5^VZy|j7Jw%V_JFO5-~L;+TsLFg{T4=`#z@0{nwZIPjM@wa-POD z{atGs$FTV@B;kWk_W)vccWX`v@Awj)e=_=``tDcUX?0Q{OG4;lX(or1k`t@{p%+5% z415%B6151~zLLWQpSk(-Yi_ zAc1hRjrkQ~h)?XRoKt?LhO467zMv@~>3_$67^RD%AH=MogKR{<}*xy;*X?7_ZF7 z7OGfq-GTV~{?8w6Gc#bGu|_J}Y+fg&S=W+gykw=MY@<$741F!o?OWMDZ|bvDZFaDl zb$Ja;ozO3HbI$8`#u4+Vi>$aCF=rvvl{1Z$>WK*YHhxvz6jmo zGs%dE%HTWzDUCt@0-91^E`+n`FQB2`53 z{H5i$uD?EhNj!c^Nc?1S#u`TU$?XeC~e1*y{dU!)TF%oeKc%1ke{RTN2Q)xwPC z78?dl09VKbOqU3+cvv`^0sl{{^h>x~eO~!4m;UU|cE^q1XMUDHtp9iJU$G-VM`4U5 zF#uQ*fHPXytK%l$PA1u;m(il>E(M#kRfzT+dxxg^!x~~SE5>|70};p1ilt$Tz06_5 z``io>J9j!Lm-Fo6IXd}@w1@m9dV=5cS^T2gn0VzEP z5Bg@8SnsQmGTn;xsYlGeN2*K49gRD^GU*hM$^b1}gP|0p5=@tm1!s>tin+2XSK|ky zg+Ks6hA5b~X4+L78RFUE08mmg@HV-9hiAE=; zV091wdE`1w&mkCRMY-|gKmo*I2aN*z#eIGx-Y#R>{5`IoZe&*}(4vsSN6|I!adL***&wVsk9B9c!{mmqke@SeBz=Eut-;Z>6sdbh2N8RzFVes#rL|Go?#3B@qaUwK6Vi8y@CyBqcC2Dq%!a*Fz}CeGL@)2p1X%?Cc4%~2-~!r+TL=>@~;k4>+-FQ$;( z>&HbH@obd6V)HsVMKK2n!4zYAJk<|N6FZL)_%PX=70lsC(*4vsw-zhmKsPy4a!6%HnW;D9Wv zCeic(EddV*f(b<~H=$d21b7LC*$H|BKJe^8NLJ&f8Q4;RnY#H=Bkz;>EO_iGe|Dj= z)q@8QU|rYaKTUu;5$sc!5^)sP4V~7Cy67 zS_aH=!#cNGF7HdKZb1!U@fU$-Zt$mFobq*)4yj~_JWnX=Ka<}^gJMD3bcUs*C}25R z?)PILK3g?e;_kqAmi#t8H$$$B&7~?SOyw zkSujDy0dly@uGG%4Qk@*VX%MonF!;W3{x=7fgoyOQs*`gSpo2#%)xgF#reD6b0Z0F(zem2>sb>>QHnPy@ za}YXQv@I7+g@?UPAG&%FJh1Mybzw^(xiHf(q@QLP`H+c6@KkAkheY%`o${Qf+5aaNgZ7`~=Sl{lCHWxMh+ZG?LT)rnl8d_(rxU7RQ2}pds zYhyk)FHNL*YJCf*zy24@eezfkfe~TR(x~zR-77CwR$Z>C^Dq*YXIk2@0Jv=_Jz({=>{X>DkJ3&0}$|$D`5bTT7^8%`WJv;508BcjUjQ zT7e5k5J|x_C0P7RoC2;*TNh7=0=o}h4GUW4g-Vj%#oNs1{HBid_6RYY4+5MF5w=}?x!Zd>m^@#Wg2s^pkE>-$@K4b zG~P;e#W9^mqU>Ru9HOI&9T$ha&oJ`{ed~}{Z?;Q?^pKo(M5L^1XS9u|(187;0?XkC z^wxMjn*8mM||%!vhOjS-wbSs6kFIw?N>+S*!Z-vx)w zL(sXHAeTwKgo^vmTPH0iCnqIU^YUe%V-1)DGhDlEKrOy9#}I0nB#nTR#xUq1GbU$g zBzs*6jBzNGeXF=86J4!(UNi7n;r<%@;mQS2q`Kgl{s7-8b1;(zt1<}XgGL*d#l<1r zB?TN@FF0*@{r)U|JlNddU-rp&kY}JMAOi;JsnuXd`Z>9m9^(WUrm1(2AVhY&6)Fda zOr^vN)MAnJs?nm;18Bni6ziQFrN__KzMgvne&VaixsM^92pOhrT9ghDDLJAG0BZ~m zr^~<~H%x+V>6h=(c`!l*kBBO>0_?VW5}lPNE@+ts>{HQVX($OodGbrqQf; zE||V6W7kB@;ci>4zU>aQ2B>`&YzwU>*xM)8ssEdx)2l5~wUtTCl}>x>`3;<@H51;( z0RaI?)+0)V7qVRWJ(Ed_K7C5pyBOt_+gmG{TKRgpJ6Ac0xi8xsOlFUT5!DM;LGbyr zSS6>~|5Ov~do6urX9_F}X4M4vwZ|Q$7+ReC*UrI}M`F&ZHH^t@Z<^vZ;>>f94`Hjr zA!v{3U(6;2pT+3YqEgR-Ss9Ova?R|xdST!12;Bean9qi61BXtSzfCP3&bk`nT=`!^yrMvoJqZdb5E(8eqlz5I5J2 zXo)3`j`vtreR7aY5V*xdUA*PY`p-X%UoJ_o*a_F9Y7`9JF5e1O_~dg(fhHIcap+WP z@GfvF8TAn6$o)^I`7~jgFP0@2z!jBSQeLYvKsV?f|C$uRz}ge(NyYdSpA*ps5*ZW6 z@;)FWVR6|QDEF6ma@+zv4sbKN7uOKMqOiP$TBznBx6-5L8G=M-6K_93xa~82yU1c4sNgjz+uz?e zOuEPXEYr8A*gTP>h+k3vdA$-R7@E)9X~L@9ZkgIay1?6M1y=zu5x`w#bep9rUm0mLhzsJG>t);!MUBoZghtH{KGpN!H3I!J+)gL_Isp!{=~4)0`~gc z99G5=T<5u*ZK&O-1v-wfoP6u%8RK}y^H_4=66;yH7MELawRhYbbP>vIAojC;dil2@@NvCe*>+@ zhUKKs-aaHVkOhMSl!63$uP*7w^G=+?o*~FM|FUv2TZWTC?Uys_|K|mWP}Q*lVH$=; z8%EZ{f9P4UU5oT5IWdDpKXfm4RzfHRti2T3IuWOgb!yswLK!0>KyT_n>Ch{1!(;|t zNnrs25Pd!2Dh5;|*vX++Rg{bjCS6TNq9zq1^(y$(GO9PH+auq{oHKjvFbv#d{zN-I z#V8%T+|GwdZs1W>!~m#va0H!aW*H@z_z|2gF6er@HR%^?O{Vy7Y=6iDyihfG(7E z-u@7D+Q~UrS2(&9f;9Ep7=V?XjJB_4r{}yJ7Kw>r$#8`q;Ybyg`H=UyOux-5_{E8a zdJ`=+9a`|M;482>G`a<_{-0E?c==M~`t^o;{k#MXdWD=s7aq-9`0lm0d=cpL!f`xd zY>4reiCsuI!G!7d`pG~lA`#Hzl|n3#%VH9Ihrx#iA_j_r!iR99!VoTcmumGg;O?6W z8LJ?313`q%6HykO;-{vWZ`Q|Ld&m7i(r%X5VXX_%y5no2N>xPNr)<#DWuORwteU_! zb{rE&Gq>7BHQc-RJ3E7Mr()nZQ!`rjgkMjGzuNSwbL6zyCk$_^MjMU1qYfL! z5?@JXQ`RZj0PXeqf$&X{we-oqN#FtoCqy=XWR$2fA1e+Era^Gle@&Z%NK59a?pehe zz#Fq%G(6tSE4dX~#7_A5gXIx{K1tK8p%7-!i@NGGap*@xzHANIFvp~aYf-~SwuC=4 zdbk4I#n5;aH>1;W_KZTy#aqRd3`BYU?ZX@Iwr>aXFnm}QSa4U!C#uDF_4a06^>E)A ziulBq$JwTxaov@_v+|n?p-7Z5_FG7YY9Q9yCR)TH!!@isV1M$^KFPY<26FaGTNArI z;4(rJGUrHkWo)Q{yJc)~+-kt)$?{$O0N(jBxDocQ!K2JhD6Iw=P?R6B{||y>kZ<1l z_@94u2O7#puMMFW-Rl`IlT8}DH^j1b8gKk{Ty`n#u4n2N8FRx)^0<-pHY-%dI&2wpF0ESwb zS09o_m#9+!eC}R9v5O35If>GNrpXG+cJR}zufHNW!ZD}Y$^TYBfLYWE>=OV1C>pR! z#PJBbd_o{kqKGe5fl-IQ^usRmRIl7&@Yc7@(Jef`^*NXQf8HIc14>4oUIz>Pgf_0w zWdTwuuud}`!n;7A=jvU{<)h$Ruyt)OKeN~fMNET)596w6uqB9~+R;?tW{HU4r!u#} zgt44ZP{u!%Cn-Fly2oO)Gge(}UuvRe-}(49dgy0+?0KZvdvth_9!~hCi8l;hf6G#| z?QA}VJBk;CeUF5#OL#J&R#-qBAo0s1lhf>KP4EgyyYutu!VTN26?x?|hQIwZ5_D@# z*f}_i;nyF$Uz1pJuRxbqF$vI0#G-hXr|i)X);xF*R`Dd)`Hqf=7{A5jIb$*9xFaHA zcx8O5A(ufeDRBBE28rqyj8f*-#>_~yLyTED5x8wB8g(o|YQcM1iQd6HDm5kLjW>bx+05f!3zn>1FCi?t2|_fEX-fQJ zazDwUkeb)Nqm2*53pn1L0)&Ghh8>Oe93Ay{gU1}e$@Hd5*shMXjMS0=pro|He192E zFCaF^^hS$P1Q{w34x7AkE=(0M+Vyw(<3Y7o=gr=sa8ygtVbG_jX7v%$5 z>OW_s<*|TKor6~rfcXtujfBzHWw4U3e^!UCH!$jZWmZ{85_J$rAep4_U}qvZF*lx^ z>0Yyh0Z+A2?H}6g$ZP|}x)36wjSs`F2uvA>@`H{y%>%|7EGwaFO(q1&Jody2&_02kR%D7j%v zsKRiNR$B<4U8L{*ywLVwiupjq^I~#|+-A_${UPy*`B#>VWORcvs6s33cv@CY46h{+ zuwbsEz=mby4C!#-i4c9RTio5#<^O%Xq2KO|V zsI3+M%H%~-XLV_ZQ%?_;iCkGxnqQ#%YiQ$(x3~R6-8jyp<~nTe1WAFh{1$OjNqm+m zDG0VWdY;Y~{rs1gA((N{m?K^+pUPUgEyc!)XJV0fwshx678dda*V2bE3MJZPt|`UT)62ER6PLc0`O7O$-5uK-nwx{ zdHQ#-Dsf@wGE|A8?1T*0Q^KY)U5@xB z6|Fw!6wPgpH8wRJR)P2e4ip7wU3-$XTbm^qq3EQb!z%i-udgq;alHWj{o16TQ&nxY z{8LYB7nbJcDfw^v;H?9B4(e>n3S}E@WEN}^l3#rJJVHt=fv2&GLMZ$E->U3ZGYSqE z=#c{)icx1+0{6w+{1dx&)eKYN7c#d;zBZD(z#cGE>-rx4H25jD7KguQEV$KyLY-!u zV%*@3&-A3}s7EiW%`S{bleJaDXmfI0|8PQx_k;}32!LOut9l5eXENu>(mggpvA zBA5|_84!XDv`7NYRD*DYA~q#l9x?O>!^skqdd!5iz4J!QlHd5k`bmr>G8Z0lG0`Bl zkJvVIAW*Z?;MoRLXvFD-)}BS-n_mv-Hq_V#VwA#JyUq}}r*$tj`0jjm?Uf7I z8uwsk{O6?d3-zC0+MVcq;t;gW;QuD(v@Pnj2mU6+z-viPn7heb&X~@15yKk z3tn3jlxCr`CaT0jCMeEeCX`C7f=8-PO8T<6A}-(I{uRxSKo2^Ej|w{t=FW-3gDn_l zXQozwO8CWyL-FO{=Xfw~n}G)cRytVtm382DZgVtS9r5=ch$J;mG~Oz_dHry2?UH`! z5OAg7?&@}xi-y1$1Vd!Ni`|41Gf((t%!h#Jd75;x=+En~yc5b%ZG}S;>=B=e$7kejp#?T_V-gjpeb{4>& zu}8miFC4d%s2_jr`eLI0l;RM$siE#lGCkm6EKTHb za#Y2D9kA8C=6e2Zq=!-}W$rMf^4qN*qk#@GHoUFPfj%fj!76&et&(u#37p7dq-BlkYE|Ezl3NwXlpD*NkFd4@raqf#-{vY~y`qzQ~- zM2%|Q^puppajj7Nz1gX$sYbtDK>uXUVH7nqC}_N4m=;K--}Ymji$_8qbZuMW zM{9znl>Ni2-NQTgEQzd-jvVQHtP+)meiTs@d@K^u0*cU8q0UN#76w`@9)>u$p2WGi zw8mKLPW>--5A_K{wCA9gm6gC6hbxG;J}vfr_ht2jPb019QA=v>&MJXrGP+a(zR~B; zpTm~;C0AZM{%yx2EE;Q=&u(EJ<h?RTtMmAU4+>02{84zDhJ1ucpT0BG_3Ra}_iN}2S#{s#87n3z;#OU#oe zFYa8M=)WcB_ji3}hK)kZxpe!*nR9@gJ%1=ID(Vb*kNw?cKpT;^K-SwR)4J4o74gjn z6(>qIIv$wHHgd0~Uir1(`^~9GRVQ-+%+hrx_-6mB@q4x0$5@E(!ju`1*OIp}uZ^DN z2{*V*_0&t?AWD&W;YZtfcR!Uuc1wCa)_l0(A&KnIJ#(h3GU~Lb%2ls#D|{1II@{pXe%gg$!NI6( z)8IQi`#XzO!Y1|Z4Yhr%viw|aFC9GZPA>U?J4mlsuaqz_^t5T-S$isTW>8Ps6A)^y{A)K9I`Uf?Kn_zJg;t?9JwI8jY+}B!mJqOHtQSR`yie?Op zfG(K@T$V+4QKD)%L^xj{`aDWO4MQvkaGK0xM?kT8a`q8OpqAB=h-~ zv`Y9~B**4o^=4cd|2lb1T%0D-u`B#aTP&O5g@u!ioai~0EViT1%O~W%$mJ^t)E_i{ zgQQpoW!8ZVJ0*T^XhW;cF+dP-y>;Re~J=J7nQV0?{ z`4XPbLs{p@yqjaw{^mf*ZK?F`Tt14pk;{iTYbd)4y1qf?+=llCg$wgy{8|I0aR#Gk zZodQ$;xCA2DyvX6;b7P>it(*hQ%xX z^BwyL)aU-`d78SDLwC-!+Is-vY`%O^-^4X786h>}zd1YyuBA6#Ye~T4onJ6J{0k=} z( zOJz*t>a3?|GC&+d80L~hRUiNolbjq>(*t=1YI_mfCyQ~6w^)V#lMWm%;VcoNgf}?&ym_Q(s zM!wdh4DVB_d2-hHF>}B!wBt!RcD*uw#>ei9=rqrBI(#Pg#&+v$@{r>oS1$6nJn<=- zL|s%Zsriv)({MHo%V@WpQZ{t#d4GRFavfxoh~-y zEy5Gg%O_CSkkdN8^`kv&LV-J>kQna;)%&^{OF7qNLF$}=dpCQ#+^U3vV8of9_$ATX zt|3n;FR8TZLt^;C;h!lbI1rFl0jXU+xFB(k0pm-DDyEK5CVg~BJsr3O^sg-89F(KW>{u)aR zzx1_SYjcY^>d6b$g!l+{E%k!Wgu`{=MBL89@=*fgDcPDqlHEAf)zq3U-T%T6Ii01MeQz@X=<5X_uZab=B>{M zWLe8>5>j)q%YN1RzuiWk0wn6Un-`H|{k_xdXTCGR3lH@tExB=$IM!fIcrq2p6K#E`AP4LlOvWc(9BRs*SX8JtApK zp;|R+rPr@-v=tCBI&RRk1Mv!Nya48%eJ+bC0?&q^;VEJ$j<@*g=;4dvh_>EuID)X} zv>%6xTv+ue86_C?Q^1MavQ`wQ7^z6ba#gl-)lq7J*fw07dg->%@@P%XA6ZrL@Jos` zFZ)bVGE+CX3=#~ILu4*{8WMI!2J8h-+a^Gs?VZw1SsqL@d5Y4^H#_SX_7iG=AZQcI z->8%bC8gkVhZPBYp&+w^5FZ?HGpeGg{IIR$f~n`XP<)C0zcQXsk%Wq4mfhACO0FLl z5<8I!5-1FM4^!!@jW$lntw#F!HNb)j!*gvTw;vw|0J?0``{HYKOiZufSVl%2`!K2=_b7LMi0s@vhZcGeVo8-pO~0PhfejS8Ol~VGcqIu;=s({I zna{rUfr9GJI=GbNr>`ZK6`zyy2ToDuHP>0Us#-)~^0v0LJs}DT<-GdSC*C-=)^!PY z37VWZ)^lY!lG}N3M85>jUl7`h9}uL<#(m$P`!Z>?uC=jv}$S!n?yw%H0}6O zQ{K1$`J-v+zSC%qfjV}E*qXJNv5~XaFkAXy3o<29?tBWOQZ51tyaUFfhysYoiXPXc+X`wdt;WyDqO!mXIkqH{jiV_ z%DVIxUz}7o?p`yBAAn>sJFXG$2>*eUUp;rXv4F$L&$bRG+p z4!)IFmECCan;scRZ=^?vCfwE2T_~;4<1Z+=9rLg6 z{sNGg2bSE7%0e-(qK>z*E57Qv?5xAuCBTo(HbyhpxC;qZ7PXMv2zE!O*z)p{PIGgy z0%kQ-?~3R803C>*vH{;(XbIcVPTsBW9(kNnKAUGdTSOJ9s>k+`VzU!T5YQ>mD(qjH zRg0%ot%#yZ_#G{v#F16m$;qjH9I%{ya1v$SYi2GrsA%zt`TEm-Wa&9QfNHj6J1YS< z@b&9$p+X1Z>A-CRqyi81-+v9TKz7rk1uJVrzm>F^66fmQ&o%dsXh;AT8G%==}1-wfC-O*RF%xvc|${)fvI z@Zo2OLWbfgjtBoxsKI^d@0{G>V+_3ShmE@jUt#3ShtkG_j8)ez1KH|yDaVNh+pi|B z{+2G7wQ(7nnW4vL`na8u7MAv1A1m;F)l{Bh&i8WpBHn$=;Z}pSU|@H0n;B+eI?K5{-)WC}#ah&^FGW+v!;O{+J&#w8;7~FK~UGf<7|2tMZzhhXP&&{1_D8K=2$H(<7xu=!+;i81Z(;M7ZEco{B zM`zfLXy^Ph5mTjX$NH2lhuVm`#aI9T&49D>G7NJ+_xf+!rj!9aM!n#bk>J+)!0u6R zDW~DL7W--3n#N0^`X$F$cv*AoPlzNyp?Ua_Q3*z;?aFavQ0c?2GkL1mb%gX$7y+47 zd23#L*d-FC{ItU;;kEHNu6XWqdpO6G!++LYRHG8+yT2Cjpi2?ygH31-dZ{U zUT0Gl&fHuyKpYMXr;mK9mpDu!xjI7Y6{s#_aMJ*(8P;h$0-*1ZNxqjxMuX-4>Xj?C z5K4k`w%gTz!NL!XkG$lc8IhtSyXw!bi$j+Vx6BSgiHyurvd)u!{bEuGS_S2Bbd7eI z{^953##feBi#_#QlNt3_oFC@WdvSU76|pw-4kJ$}aFeAg9rDXZir&=G)Ji*hfsNNh z=#sc*e{Jm!3?^rPKdb*5U2ZS*s zfA;Ts_4f-gaXiAZAuT*Tr#BTWu@}p@)ruW1rGIt0`uB6irDP$fhEEqTOL_ApnwEq1 zN7AF}aM7^vT-YaaML6uA5sM-$@}>;1=WVP!+lPMsYD*#@vwZ9s#lib)a~}1>1-Q2* zH_!S1-JoL@XMZ#fv`0(UzXfIo1>QHk%(G!8ZtnS}!ewBnuQJSeZ0S{GpP*t6OR55+ zd=PyLi&2O&4y>m}$C2`C@o0i&6ieG~3hw}B3vSqGNu_9oIYwwu!9KlsF(Uij)6XCG zw+?rJ92?*E_WMK)v@c&HPx(>l<5AHF)PMQvKkS%C#_)G|>@iRmr~JCs-VWG3y!tQ7 zu-c9-5Kg~9@~;2=wq)YgS00R_x+SbKz&@5B|AgsEuI@!qcp>ss_4p8$cs@>q8*s$+ zXtm`lRPi~H2znGJLTk@658PZ7UpZTLr7!{P7r@f(?YgZa zWP+^NU)YP%S#QA}@jF7eLhNtnp;PQstzka20|zt%?QQ1-f zE4lzR42|018V=1DZ{Ln7{r8N+8Lyp=)wmyOY0#r|LGAC)^Jb%f?7ClbfBCf-FCis2 zEGVc^>G3~MA_X-BYmj55v~|!yfipOmpo9Q2UW+5uyI=j60t{gf0GL$x;a*n2Mh>vO zo9SdJ_zz*WyoLk`p$|0nDcL_*>)(b38Y_e<{XYyOyCwJBg}0mtXvEW zVSS>+jvn+v3p=}CP@Q%p_W7|m264FWo;)S=EGskp*U39*rcaNaswpA~@!Z9{k`L3a zYJGiS0&1<<=-Yd19YaHxE|_)m@X<~?PAg8cV01%CL_WtHWduEqe4?s_#jX$CV~+FJ z2mG_>bZz7%E+>$XaajJ_{3lK%K%@AV1+#z$cZ)uOp$3ordFk*^P2Q!WbdUdf|Jpz+ znYy`Vv2oe*enRHb9W%Zh2BndK2r>&b6%D6K#b7W|zK4hWfU%-ut&Jzpbx=^?Rk^0A zv82qG{#%4uZf7nPA{$p$yLj2zfFA=Ci-coM^^e!x%f53B_tM(XL%L6k*p*pvZ$pUd z64)?DQEZ4Z1GMshO}T!&8;k=m)$#W6DXS)@Py`atvp{GVt0mZ04QRxJ)D(qfRTLQv zmd7%(#36m@Gl>~hJw_N}8=t~SE-3uy%4di}^H5U<(g#xa@dT>yWpm!4;kyWPLcC?A zs9k*`)!wu#9G9j$U8UxJZDeNsEzTOLv_6iSkGBWyw&Ci;<~xs*EiKHAHeD?Df*OLbnBLssqabwe9hh6y(PMg&Q@+#`y(6R zi!rEizu#b*%=fHRkc1H>$8v|0Jk0#0A!u2<|qfEm7{nvAU2NRC?J%VD&i#&;r*VGe21QC?23#`ky0ty6xBbp3X zfeDp7E(}Ce;C0xklH09P$y@mp<8QSzvI2hxevJ^KKLo*qHTx-kKA0H79SO?18eaw+ z9zc==HC*dzTdcdPoAXM04mWNDOf4rKBjLB~bC7fzdjrt{eMFC8Yy_?k*-jVY zdaAcasEa=2#FJ@fb*flb>p6ZRuT6Fb-EZmbnt-(*i6w)jcbX1IC}@vin~W%H=%& z-y6Y&ar2wCOzQrd5;}#a&BtNbm3eU5OjsIqGBOB%`Xx<^2P%nJBziPkc~IJN5bc|3 zT*arE;8K`i*5p2Z`r6gHG4yK? zC7rMteT19_S{sEoWFMD^GiQ=y4JNm4c$9l1=^tCkt_V1~z z#MGutTR3Q=pv7yJ5nv z8jLNqVDg8T5`Hwwj{>ELkdqXf;el8D(=Uw}^_VVk)w_esgS^B+syuu+b$N;_Ox>^0E zS%G2E7tlVf$sPms#H7d&qKsfX>jJMkjEJeJsiAw~xt8;g4;c$)jbTVi;R<5S+Lmu& zRp#WT2W`y%2rR%XOrpZ6q-;RQk#sxKDiAH9Xer$eR!m{GO?h%jS?|8EvnS0#NcF@D zt>5vV+1Z~oZzXDVhR%(Y+dBbgLoa}d8=q`($Z}RE;}f}> zs7S8JgbmQhk#@CPo6Ae{KKx1scfV7mCTwZ0borRYgtN5YkI-f2@af}YP*p`b#N0!Z z3cn$_3>gN9Ak{Ec6>4A^pRvWXiYjaIV+4jc?!Vxkgb9+OiZQVXUe2l`)iH8-u8vg~IIGTPM zV9<@|mO9x0LU*6Z;Im+OEGOQ})lWM*J4J|`Ognl;mV8nwP-rkgOJh$XT%ba@MI9XL zk9dy_Q-QTXfK3d;y-*w#;srl>wy`o5rOASUtDVg}5e517^b%{s4IEV*?5_NFzHuxQ z2t>hg8Xk(Hdo!|Kwh@Rh)vpCOY|tN78%i#rvYPMV+}m}DR*5D3n0B3h-mCVhQ|(D^ z_FbtR<=&vM1ST?k?{$wBSnMBFk2s0H#WjY2QUVPr)eK2Aq6Gn1;`5(Q?*AQh|1g!* z1g|Uj{Xjtp&vvI2V&FGjV|UhVARwl}#11!dG%SX>?d0u3NnJsAmRA=%EY-Da601t`o~4(#t~Jfgm@k~%T5_hQMn-f0 zjnnucwGCcj;CR$SA+!+4abT^j9fgG#-gg#O8Vx6Xr+`*6OoYoG6OIqH{pR!JA!^lc zHxFXx{Qlnd{R>WAl{7q5aaPXGLjE9DJ|Yqb!K4CG8CTH$?dp8EM>y>3W1@dF_C-9% zWx9pN=S~E@W?1G*-B79RNysBjC#9J>!9}|}SDt5@dg4=4=Z=nlpGk$prKfe#P6d=> z4$%iIFF5vo^H@2Hg$zC#TA5Gkb*!*qTxKa(`i-+mWQH8AO99HKCUWRd0sM;ndXG$O z-Je^Nzfezn!)k3vuge+sMxX)~;Eg%Ep_w8x|0zprus#ZfVE@AB(c5r$<8C@>@b6=_mi9gfw9As^=pKESvU6x>C-(o_vC$F2q%NH#-`5|{ zg~es^^@v?$XLl4gb4&(zu5P?tEN=(8T(FHU0G1!I@NZ_9^Zbaz(H^$H3@hWz$MII& zrff*h#o!R?l!^i5NK|A-p2&O2)o~K6a1$$v%#SiXhTNKkgpcM%U}lsW8}g=z?ACDC z(d0i(w_AbJfq^^0 zlAfAH+z~pSkY>S+{JTjr%4vDE)F0ij0VWiQ10BFdWgt-XE+xsnHWq zN=D5kfw_}tq#7@w%skSjDOWHE*=Zsu=Djj(5K|RHg=dlL?5`IDx%DwR95@L<7gCCFe>;(2)k&cT!xwCcAl&HS5_-9%;N+n?1j% z-oCaMM8S9^RMUpJgXw<6S1BVD3Lwg~LGIaP>Xe8ch!gUGf&O`RcG!eH18Yo&7LlP2 zP+CZtFe(`&e4c&!)IZ7CrGqz9SOgB6>+@acj(-eCYNeA_mbn_7m#+~9l-D^ zh2iW>W@?Y8&K_gdLn39I#*W4y5^MAC@6_sN72!_w0?2I2e+P{R?d`jFpXH#OBO<8# zA5<7hNcLSolztXD-di2)HD$P_LwD=KLz+h^qq0x74t`AMEstzZXYtrhRehFJxbaKc z@2IhU_vY~y8OKfobU3`+Af6{$n&J5(*-d)4n*?hQzhyVS$IGLAhuag!rJ%(f0Xc>jQ2Jk^Naa+$93N@vHq!vDkXg%W^BTjmH2>nIBMz3;VNjm z`sYJatDipo>0Mf0(`R8)d2i|G&#B;~b&s^yVu)OSHttiR8;Po-WaRFVz+_wf5nB4h z@N2#%uW%%cY1 ze=MRfDjORuCdzifJibpoREfcg$Jo6ZwC9^@j~+f03;JV`i_>}cj11ho6hfVr&o{bZ zLoVb=@cn0Wv^%u(KAA1^98N?K{AGfIfKz@AhX(*&og_}CxSDKj8T`YJ2jIp z^LB`}VA(}0)Y*b}WY`1)!sJD>VlHRH<7Z_uf3#`k_pjsTU3VGP_fu(dGHc6gu){q( z+O9u_FB;(wGk#`&NN2W*fW#V6(O?qJxs*i5i0*biCL)(-IsqH&PdQq>v zxjdsHQM5O?zLE4k`&wIU05 zo@>vDR7lPU-KTlKSswmqIBHh z&YgD(?tg~2mq%`vVn7fW3u=(3Gf2fa3>r~L3;$5WA_ocIqOd55Dm;M6r6>LUm6Ojw zZ;D8iVm;B>?%32EUT$adiYAH|Mww_9WoBDyCDqu?*Jf$Yr{)L>ZmgFFEvx?}99L_9 z90`Ze$BNHl@6M*0UONXYyYpsoIpY3k3OavmgAPi#OPb#whhMn~hjGj%F~IBZHs-CCG$mdNdGf^T7>cDoZC<_kFqmcL8g20=|! z?QsQ@&Eudn-Lp2@-mZ0%Aa>FWVyy1FgD^N%`U&RVQ5lfBW@eD2Z#;hw)hvIRZXLJ$ z{CTb6Bzw9;UbS99KiCsM({yCx>bg4lk^?+N)g;m6ie)$)FA~8QLFbRr_;C9U@{`eT zzqKoVo_iZ}#5NJ|Th-f(Kg*f~qsebbOZx)S85BeSz+W8qd5Zu6 zZ}_iGNJ&SDTzz6;ld7a@h`lwn4Mvi)Ub>{FQ&%@hY59CljRPwakO z9BoDylsa|fo<3_20D`70v!^)Y%SkVdDVgc6-tWT|BJ!_n_LY4dSV`_*fcfgJU&bca zikc}=3-mFpwzZb;(xjiQ{CeTDzkNq5;-AM|CCV2isU8eEIZ!EVBqeR9WpCyuCncZr z43a}rh|`m#W3oS-G*RNg6pa1ns zCpnk94#$5F(1CQySm9X6V*yVnaZCdrT_zv9@6KeIppl_8ZeGrFk>5NA$4g>>Vpc}{ zVH8sCQ77d*#b=G_)P%W@~Q-!+BQSd%Z2wvTJ@*n)K*2&+2vMJCQRrh3@gWxt*5D zZ;Nd5v7y@c&dd~#J?@zO^+D3ivc@3T#@hOZCfh4<5pm{>Q+=F>$QzAx3G2;_S0;=f z3hnjfo1C+Wy-%o`X^H1>o&Q;O01IIseZYhVxH$pG9AeU?U=;y$XhQw*QBDpl^I!9x z@(tR$gk-RNBOjZ9zJAzRzZ0b?5N;ChGvl|H8eV>Oy{vHa(s*z5<#W_lhd+7X4cZTV z=RE-yn|jEpES&hTy0o8xs_m@3z2R?xju$UhQPYmGo$c-JBNuPo z;7?&jUG4O`JoxC#y`!m~{F`0NpP%4!uPr3Rv-F5D!x;FL_nf8`+l33>vl%ZTcFVG$ zzr9^50hG93J@U{u*sReg)IX23oovCju44|Myl+mA>=|svn|-RFU_-ySAJH8FT?%ov zp>W(NK4@MITRrfiCO`^$KT873b@Rk8Pxh~|(I`?XmB54dUKwS1~1T6yE3{-7=AoPV|F*q*X!Qg8aRsfesr{HF3p|ph0n$%zF#kkC4)0kg-?J4 zzCHt-lL>(P8DAG%HXOvTOumfPIl+``qo(h_+_RXYWB6dO5DYM? zT-;D-+tv;|l(8g8%%~TB~uH;v+8{S&FwaDaffX?Fjg~a-FC9c1E(A3gMDN;@fJmC(DZ( zULMcgvF=O%mKEJxrb8kt1ocm^CkQ2i*;IW>)L7&44ZMSYBYAp^nrIXE(+R0(dyR`8 z*nCs5tj~{bI%!v=Rs9|v9i6=O(z$9gzT>S#0%{mj0f5Z?gY_=jGiS!3+DGT&xX9_h zMsc1~R*zLdbx20OV`oT(sKFAm0HP2VNJ~V{_UfZ z+r%kn-S+Vg$XZ}tl@M?AlrY}Q_7H_SrPQa`okitb$eT!fonLl*-}pA;cEv~=jw+omObEPqAY6Ld`Dp0F zB#gPV%ZIgk-60$}Ac~_6=_Jenii0dA^yB%`=lP`?&AkbY4 zg_3#Zq^(!NrjnRD_fsR!upo5hUxJmC*HaAqoSUOAWd5vKud~NYeDSHGGEYa@_LV7d zEXo_>;n*#YchY!3oH-&XIgznXq{q@W7Y1R%3fP8(XG_Cr10LvkgX(fwS&=e0{+sgL zPOpoWi;iVxu|!-BU=74Dg)!3iAoVmc9Um(&Hjm1MttmuZUD)E>(J=T66&`p{G3Ta# zlJ;Va{Y2gBYN;$C>_$_AZC<@2R_zuCawF;7UOTms6u~>Tfll01%v=c-d`^jUQIrRP zPe~%N!RU}UT+U9MN);s(CMSY4-7$H_BP}=d*IBy@>?zL=E2g#OHkX>4FZHjS^jq0? zcXf1>Z)3O-Z#QSbKLr#jQGagbUlC}EhJD_k*%WHBkTt7MQHkmYl2EZC=q2&(f=xYQtkk(`Jk)YQ zZhC)nwkuw|;7V-o5`yoe6y~ZWR+VSoWPIi7Ny4o=zR!Gy?Bly@jrM26M2LMwsbzLq zQ|R*rcb2|itE$ojr>?hm`xWG~9QD_QmL%Y*O%R`G!BqEepE~S{6no4``xa9Q?1D88F z7i^E0=W2~m2Uu2~J#|v7aIsnCvh(qtvz70hohsN!mhyZdyyt>6-*`U;eif42m_9?> z^nQ%b`s$UzqPL@NBg?_f!Ete0F+4)c!)_ycGz(#6(JGD1agvJdg2}@gd9@#F^qA~S zn8vn#Mw(6Zc8N)?OwY5bfi~Rbs=h*-ealaCODxaoX2ZmRzVlQ53ZA`CNuaI5$WJ$5N&!72t9vX z>{JTR3I7|7#_?Q83|G*wX8FzW=ih*~UqTVWRykI>zu1?bv*pbkjxMjd_qfg4?Q>Ya zhPM6g+Cffc`_(>H1?XJEko}IbGz`beldn2_Zd94AC8M*+;9_OEAu6ulpvZVH z#t0^ii9P#bcgk^8a2evLAdSe@meI~6xo2Oc-zI{)kwcj>E{hB+&(ock%c;)yh7`}L zjLld>ax+Cz-0F+Ao6FG@9ji&T`!O{189T^%pOo^>Jt{_jH8vU@yF{}u?tAS&?v4uw zO1{gjxc0VKvuM1q0#Hz!>-a86t?>f*m#^cN z-j9N9yhzw90~voM_;~%aK0)ir+7|quep7kle)AiS((qARl83w)ur3((Tno*UcsTUo zL02aT^!^KE6qAssa~pg`ck35|ghVIngy@sb7d9a^Z(DV0pB!{VzPD#OPSw z;kC8LZs}E@KkjTitFQg{rNgXvWT&Sz>w2*82vhfUH~n6iIc$3R z0Bfwp8VzY^-@fsf46t5c^;m|^jN{O=@@<~u-kkQaX>H7tb-VtbURS2X8GLY;xwEm7 z8Tu9M^e5q1R|{UX08Jj}Rb=cNJGl7a95}-+JL^;CwVn2$xGHzd5{J`3A;TyEi>#>E zk07%~+nL~0=`}bUKPz`IiN&J%8zFP8Ksi4{B%DH2zrmUU(>L4H>cE?-sm%PE_gWZ^ zFW@SeEa6=QWlI(|v8P>qo_QvPheVZwgtgoL4|948dt_$}H))_!mR`zNEn8E~>lVp# z?nY&T7cXAClA=b%C`!+o?w?4{Ypte#N?<9c*IxVjHKF_@Hnose38$gh(#b!To^v^I zadBfHkT`RO9pw1`R}TUsinTS7A9SSqD&z`{?KRsduw}yCh&$RpKAh-kZ#O7Ch_l*_ zdvYE$RY8ogIE}#kTzUQe+x2@x(2gz-*FU>=@2k}I%<42S#g=Qdb$+1wk?~U$c#D59_@g4LN&YFVYF;% z0DiZURP%)kzn7lI+wr!Qk?X|gY}WyIsIU-@q_;4b9)TYma^6|iXYV8|g@LipgP=dF zjMdE%0-bg~jvq#DO(f}?4N}f%SSQ|pxRIat&eTz8X{bDlGL<7mDyA>xxn#_niqII8 z?euh~lqmKCRR&+!-D(glo5a%4(%fXbBXmYBl9DTW$|rzbJOgnfFe%m`a?|vY=iVql z5D3GSe%{`Ne2=M=`8=RV=OSOSm=zU;qXj{g_=2s!J-hYSG+ZKos;wyk8`VL5qY<_q zi(SXDgt@rR*i?^^=#&heJb5y?L+wHORd*bx&&>JbWxxG{zN+azMBZ6)OTd-|m1} zWgN8a%!sX|a|qFJ;p8MDnpWdlw2M#nB$a+71#7|NnAa~a1ZKurmNn0`z?DJK^scc5YGfz!D4--A3W`u?jrX$ZSGsWM3h7ERS1 zw`EgZ8=E^fJNr35Q7aXo)hHD4DB{vOZa#y{}U+DH8{r*^r<6p`kReM3H z&c>RR(^=30X`59wE>#g8Zl8rqF@?iyF0mRL*Y~<#peFoghQS&jf8fR;)CTk+xZcZp zVB_>_c6JsdYXvwxAQO^gJHkX$EK-qS~vUp_UZS&B*y{bv- zb{H<1nW^ zWt@bnVNZREP%01nf`(%5KPr^Mf!k*|X*fM8Nz&1rszGvU{y~xne^qt=#Zk!l>@EKN zd%t`b*Iy>KDesD-igvkMHfW`AG-$P_5%CE&m!NJNYQlBPS{a_sMg)agd}YViU>ky% z{L!=YuCv0V)*Qv@=hSihKLp#_7r{CR**lj#);r8fs+Xl>Rdu7q%6XAEc|vUx4BmAo>Zq0seHQw(tZrtOei?qwW;q@}9&rk?Oyb+Z)P)RCaJgf__sw_I~TD zi*PlKIT^t>f+TujV|VD$Y7G8KBtW~-mR)UnVSmP5W^D8P;Ngt((M zT=~;nvU~llP>FhP*Hz1;O8juLgn&|ddQeTK;!1J2?D#i!lePNcp99cZsk9l%Z>!z6 zMorwhSoEr9=roC)ft3W%9v_3_N{|+VW{e zyIU7WUaLLcYaa<_abL;DM#r$|6!c$iF{Gu9>?>na5|v)nF%HTnC3is6kp%gFMFjG< zgOSJpE=`kKONE=_PyRG~_1T}05f-*&vIs+=z8d+ieCB1>sSfi&hZHPQA<#GU^--~; zRHv{>9)x@T=Mb?7q_BS@JADQ{g(%L{#E{K^bA27eB-^=foh0=85&YI@&P#XLDhfAS z{Whv{nm&49Va}|Ne0ARvKPa*8l~*(a$m z`Jd~jQ$o>rB;`4xTXb5`S*X9L`2PB%&5{C4ttIpZP%A)YPT^j=)?Q&0udfOv7m)MB zMZtk}*bgSe^R45*-gE5E27&`N)hdPT)V+w9Y=3fwcbGon`P$O)c6@)_r#wL@$8kQz zZ?oSPZeIASk1E)pU9)#Id0M-T(N#wwrc}jR{>A0o9QVAIUnTO?V!q7uQM#0*#7A7r z87=CP-OkE7uX{5GOA4RtA3rV|b9((y;w|L4doNWCI#n-y0;43{T2QwbW`wbUgcHl? zIsp6H0&$(VNhtOp-W=;z3?$Ccs`aCN!uEJL2&g^M1~D+77l(0g?REv+(Vlyd&E}Xq z?z26HLZ!-ied@=6hw?4F2yj2Rxw(OW7ET&hh)}vIs-(vhyj|Cik=tJ^FHg80u*b-8 zkbl<7_g+r*Us0nFbJ?pv(xOb{txzkH61yQLB4*k)pX=Yq-H!NhQf_K9%t43Y6_ZGi zzdZD6kcc`qtJy;LkOdBb=1SGd*g+uH_J zPGi5{?O)+If9}yo8BI7JC=_Q^Wv?pJuj0_~9{4m(8 zp78lH<^(|f!_C170Qqu}i-KE^n-pw2ptBMcXj3L1ztSo7%OEQ$*5xiWRU(+#48()f z?WjvFOCU}PV-Mixgkut8GSAr_0tF*#|HAl#rRTBGT5!j<`+VtV=eT^sw1 zF%w}OW?P;DjN@ynjF(c6aj#t>*HU6xCa70Kzvm(@~9PL=U#cZDRath#TN}9shUsU ze)oX7Z*3^UUQE+MdX&wvU#)n={qR}+VJ+;##({VXFisd+Y4jSTtmShqWGt}B zy&$yuPH!e3+*bUiMKkk|t$nVjFGcLX4t z;kUdAv*?b9Y^)Z15x`}D@w`c;(>Je)YCl)kuOJMnFuj9<6!<6ep!OVsGYN&l!6+Mt z>ro{56d8JfO`oWstEt(kd-oYC*MrSUD;Yo6-|6zMu~^ow&POX< zsL@XC6U@C8SO7tF^7<^v{Rdl1H|2JIX+v~<07b)|b@&aZXMUST zew&c2D*yQJccRkP`!5ge_>*l5qD~7uR?nf31*5sx4;bZ~kBrBz%fArrI*pe_9z>H+ zBu`q9Q_>xuh>Hj*)4zVLxIF=Ny|cHhdotAYw@P{z58_1A8wy56>oal&4b`U+I4|L+<9HnX|EMX<884AV_rM@zcT>X^g><*FX{X#{rp^zT*i z=FFLFj&#Xxk9WR*9dOCgFJ_G!Ckaq=p6h)3w05Vl8%)3xuB{g%)xKHSp^1GQI9q0lYK_z2Wfq7COzS5_!eNoQSK;>r{G0dEp!UK_^#7@3x zHZ@2m9}{oaSp^)bhrd70!5$fY>;P=$A@RBMU);Z^)k`U-xuPL)sLtEtDXir+H8qP2 zHBlXf?bA?cz?6N$bKx5OaQ$%_SjlQcpR_pO(VZ4)Z=Zy|R*Ap>cyBfIIbZ(NrE}-m zInJ|-2A)etP%~{vl33@WP;qv;GpZ2rVdBL35|b;KK|1RZf381j#%KtwyHk4^iRrl&;J)#H~R_k6`|(i|zfG%>+wN zyZ>hLG!fRS+(An!Ovu3~|?~CTR2hi9*-k4~i|!O{uxC z5D|zoEgAHuY>+zXPl|8y!l%4%DdYbFVsl-U6h_foH|X>GAE;U$?7lnRrMWq}^Mckp z`o1m`Fh^l`eA9P&P+>D)8+em5npS%~-@mWClt0Kom+$6-TY)H9-6quMbvraUD3@UD zOp=slRn4&>?EHvi5(>6)J9xI~5ENPZ>iyRe;(sSpqfR2Osz}J!e2Et;3dqWf$-SKW zUwJZ{5sS!diOzL238DL_%b_0YKGV}o3?qkj9%^XdYZDPO?$X2o>?VozyQIn6P*XjW zfcD=S9VNdv3zlB>e+q|Jj@|b=&DLu)TlvX(pg#D26$*rjY%ka6nYmYwDf5waydauo ziYmu{17{7!e`{-*+i4$Jc}`HV@wS91#_rfU*HCkW57AI!G_s6)+9{qnjreR-WwlOt zFVyeuzKaruQx}pXU`_{&WWhF=yIjJLLP0U;R0*3@+l^+%C+^V}dT zkmk%81c=LQBe)^+FfX^W*rXf{t@rT58IR@S@37^EdV;(H^qCgrcD-OfHkAYa4Dxl= zZWZhpRfjF+uHWVeh~pxEu|CtBq9|fja!LICCW4%r8;yN>0^zEqZ`Fk{0iO|)R5=WL z{`^HVQ*#)N5{c$qQeJZb*iRH}-qWdhfhUN?AlIpeKE;}F-n}7PHC9eEi>(1ll!uea zAE6qQjs4JiiZ~owP>MPi%S*qmYDv;#IcNSw%pSV*qQWm+GufAsBEQ%!IuvyttjvB- zhMdo?AUe~cMIXXMCH~V=xMspt5Uw`TyusPHG9durq$DMY zm;d(?(M_2TXNblRW?C2lJFGLu66gOUtU z-E&XFGCAjJ7nCB#uXLcZ_~#z=I=lD zE_Ysgc9u!$LVw~1dFdJnHyUzRIyMK4jYi;qlK zL`hEZ%J;vI^4%<@d3$rwk8o7gTtz3gio8|?IzHmv2VE(sQ`^^HCB@|8)W|M2y#FdD zErjo^cXK`RR$)FDae1RNHgpno)6#1lcpLKTf#t;95$LzzQGj_J$Ql6JaQpV{iP;g* zQo%vt0@3bx^S)WeK^|^IJGBBYLYcA?rs*&}7J(o^;2tl;C0H%FkJy&n1Z~SB85C8sN0ubscFfI%L$aF%Aev$SWLt=Euri4k5YWVTy_=|Vy8_TKYvgZ9 z*iJoYwXB9b&XKKA3593FQm2GouPq)9x4g}%tfEbjWv2CTnV z=qi_AnOOKju-|_~sC!V#s~KO>8f&L%Y18^DtLalpG&yN+d{0KOGO7M7N3ZC&kD_@S ze$uzj%``|!y@}Sl8ANwM=IM8|OnhN;{3Vl;Egz5Vf0goGJ`;oDCBC72=R&%!Abaxj zWq|gDsT^@lflBAe=6t`ZZV(;fPOK!7+m;%^k)n zxo<)=IXPBZ(wX0Pc=Hqpg5}epyd3oirFHBKq~l2wnD@xI998&0*HFErm}oJ1XffCS%~u zdu=pMM~Og-w1|`!QYxWb&rY^7kt-TmgAqnYClGMc2Z+jivM}NTd51khBeeCX@zVaxB zuIa6$Q>6@)4xDVW9AOU&HR8GT&^Dx{_Yj`6^v8+Y;{d~gRFFDvyRk3(J%ZqmSH;iZ zPkk?o#RBwyvNP3@a0rRqgC$m0MTQ*~0I~F05l|r=%Yi73&9BdX7u9@+d{Q=()A+T= zRlm)a9#zUXAFUMK9N+1j{Z5SUExjo7Y~XyP->Sf|ciTV_Zf)Iar*Wo(mem#{xXwo{ zAnJ}NG_Bw#zsSxuT)iE$x_XMB%G_d1AZy@kra}b-0M)QmIrKY1=Mw4ZXQub+##7vi zX+lW3IgQ&)oFCl?$1!0WvdI!1sE!(z;AZhz%(QaJwlMcEy_ zEZwMSNp-qzh*z!3%OfVEuH#`M@JfEQiE-U+os;ze_G>#gKex(?e3L79O$_=?z4o^r zal?Zx827V7Z67uOa784l>&yaD6+Zkt&74@Q@dE@zg*Ux zi!1EnhM1J~@pTUQfv2XPe@a@tEHTcEbateVDJzmC1uJC3$8ZRq^`Se57ZV zu9b0G+nw{JFBQoIZ|7u-3@P-PE!nc_MKdT0AW(WQAj6SVgPa1(#A&NePR>ZGVPc2& z+=2qr_iuOYw{L+S-K4>sCsMzxg+#O6@=nkV-r?l>b0ra*?$7@PG}})n*#VLXEv_O8^)7Q$|3Xm(Y9Y6;Th%?D>j4XmXVHM0l~Iu)5J<{=Lup{rd91OnvX?dmELO9*>}TF!Eip+S=Uone*F= zgbMZAH6chzp4OHFgXmpt%AoiRz?E+%T5%>g4riDm_IK z6qb~nLOm`tk@9ZB*^$8!54oL&ho>lP5Vx?nxberPwyb>gi49bj8mZ_{eE+SEay;=I zgW2oJX@j;XN6(`-_vDmhS!q!}4vGwT9H2;yoc_#5#oZ{U62we?f?SE@8-<3BgbH_~ zHOelR;Imz=a4<=mUIu4rpiu3b`;OJUkeCvK)k(mDY6xH?-k<_!J9o|lt~VAImd~0h znS6j<20w6A;_jbtA;Cd_cvTLB&;in`$eKy@E(M%IAfXAHP9zfk|NPO>-Kk4E0;s%s zmHQ@Rmk)PXA-E&Lbv6SiK8v(bBCgpx0gnayQAcXM@FV=X}OqGV{(7Aw=Z@qR6>rYjFglI zU<{!NemMGB*gYR7JOk23@IP5Y1Q}h7*wuHEt4C0`!CCF>;K29F7V(fZ8!F_L=Dzm6 zjSaDK&$n+?Zqbn&pMR}Zq0#lLL5JZIugZ;(L@a_bAo?slYMwOzy{C@-$9VyQ4Ck2j=RnG#t0;7fo-7nq#0 z8tHYJRFSdZ;dm$Wtl0c|iAn7zh?Vs9orJ0%C_9&}y=@L&oMZ>)*J|CYyENqasaWR% zJ%L?^U{Nrp*UcL_)u(t5OLIF;uObCS=??FV!ofEM^Kz%Lu4BkDUcFhj(=6mOH@XWG zaf<^WTU5aY{<7|x=J8^J{Bc!R{Z3QmvZuGPd9ng9x%U`5xx+Vmq>nMgMA@H*F zt*(oK&QH+^Ya_wV1$^Zs)Tcy;ALqwk{wJw%N~=+Y`o>jo|5GAjOfsnOqrs=oLPX|o zM?Abv92^`3cWG$etsTV_BC&@AqEeG%_mcVKs}6-JA7C^%tZczG`;vgTR+V4F0_t& z;Ya)W-Uy?gKWEk83K}0zYi@4lI9NH^8g8~?j^hD>|EYE*Z@F+mx_Z}vi+4V z`K=+_rKkJAM0q5}1_!{>(h{5mK%;}Owb44CY6u5Z<<->4yZbH~{sZKCbeCw(xAA6YKHclMbmW^ins&EBn8@qGDRnOC(kL1E1HuKX!N~$= zzYdSGiC*ek3mBsPT7JpF#?JmdJl;WxX|`{ZfY2c4CRJAv$A-aS!cFGSBtXoCot10X zviN-h?q$GTgkVV=&i?l*a09O+fM63MjErfUnri%|ycy zEz;s*MEL@%ObJ8irKes{-=|vx{?9)=)7ad65t1!>7>Fm`XpP4{OgSO%3>bG1=?5+j z-TvKO4>SvnKTd;^gpS~o*L#X<2s6f1gFS2`Ll$N@lW0zRc# zP6Gk?wKQBGxJZ+W)N17hyT3G$andPL-#B-xCAn$nyUW8LY@bvHT;8ZS>VBqE&NsL> zV^-+|Xv)scPROGwF{|`-aB*;STy2Ro0|CL^vX6!ZwP1sQV*m!TF3GvLueOmD?g`fVmmNP6$wNT-$C__Z!1`!3scnF`Uuir^xjr{bc60|gr) z45iW_gOPP7=Ib0<_GHok0+^Y4At|#i(~IyPY}q_+dVn4e+1ez z+kJMc3N%W_xlPV7`P0ZF+sH6BTgYFPmXot!YHn%@;!lip^T;>g&LqyYenpMno8b$C zTnLArO4DwIT?>R2T(~V<_Br!fvztIsbl?zs`eC zr#E*W%;xm1rNX%@yDvG?oGQ$+Y_lrHleb@}zZQJ_m09&J=jDZ4{`{|X>GkN|Bq?$R zM`M*UbQ-Bh^GPkmjUOoM1kg_k7Ik(BvP*kAY=5hM`Eq|f^O7kd?XLN*1if%z5(;j% z7gMcRYJ^^)4)kKYkXuA#BOvJKLS8{u|REv-Q6&x?k$DJR5NScGZ+iE9Gm(+^t2YQXFy_eQT8@=;-Lo*#* ztna(K^gV9Jc(Vfxf0pVLgEAe;?lM6A&)cS~w=bHzuD5iEX@cw~>w6g1ZQS%h1PmM@ zThUsz!juN)sJcwB*01+HM8jgC_ddSU0?NAe(+~@b+N?t;lEdrpI{f*0*JR$1Dg*vF z%{cCD$X%eDcTH0Zl! zuK*KC`IvOYs{&H>+{U&^cPJYH>>qUeiiw-czt31t9dh@~Qy%Q+c2Jl4r}O*My}_C& zS#!5Bm5Ma@)3=69@!kQYy9Z>pvkqeOUbLev@55P;g z$A8tcx``IYUhr=>xoUwqUp(kfE$!FJ-$kAU#R4ke7|+qO{YR(FkOLzbzukWc=QsBh zj~jq=2}gNk=UGxNZUhK`z+A{hzRV3Kz&b#tL3bkyIDLaV~H^b@V>gwp^R9s*0=ZVQRTmX=sr@5f#vOe z>%yxwXHP-SR%{&P4K+gW`lYb3^E&F;+NW*#Fm8NG1&c*HHKbM{K#KsYC>tB@ zSGK74nB>c@7fuqa4hIUHYj;`buOQcc-DZcFtEdD4X1zxrO|NMCe1PX4Q^BSz2?KPn zM}h!HPFPsCWH3?~>PDZ%(pDA7R6^hF?eS`jvijn^8+wHu?pYo+reT;cT)%z|ZSn=? zKe8gS!or6H+~>h7Ux+(3AS3U#H~P-!pB<^fZg(rY zhx>NN$ROGM`}Zje6G|-3@Q2)yDu{?G#N9{H@TZjtGGalwt3r-|yzWTh_QhIzzEPe7k*+tKT=ZH*+h1D2w_0JgdMN?1A*hI7bhhSh3ePqkH9Kz_F!Pt z$jZt4pMYOHzFA?fwSJ}kxY}>~^zpYYh1I5Mt{}MVA6Gqm^l*suLclMoW@6EAcfjgM zS3-%jN$JARvwA{{a`Xx&`%{w_R9;lvYZU@ z@d?XX6P@AaC#I(vd3bmz7i&x2;QYWe-~w14y2hj1+ZQEW5ZRfTyu`zc9+>ak%7dW5 z18N`#Ee%br`wBRwFTuteGGoSBdnYE2Ax0foSVWs7WS7I{D~y}_jFLfc(nhhO)_65> z*4?qUzxVRx?Zi9U+7s|E?@UXQeZFFSVdU;OiGc9_pM>~$Wy;dXSV@!ey}J6{&SyX> zt$aAP_9yTy{_ISWR2cUXm4)ktv#OJ|&XprTsQ`Sx0e`m~beiH#B?p@VgoD}WZOG}Z z_1d~1`#d^np<||56JJRfiosV^3`jlOS-FQF1!&<#o|?7e$1PnIX}wnHFFC6(qZxJ3ZF4B1D`(+`u;Kb+9|HP3=gQWObh`=G&oBx zfB*ZzfCl-B$fiPFVn%a8@G&`wadSMp6QeycFV8HEAO8BKZk2XZ^)z?R_Vro}!NxX% zzlN5LoS0&XAmeO~%I6oIW?v#zv_LRvq%*fu)4f@>lyb-4Q<6wN*E6m~1%7T^s{_`3*e3{3}MZ?{O_7p~lU@ z)6>)2dup}yow2Zt%pt^{OhXx4=l89pX2t&Um8c6+d$204-Q9W%nAQhSjB%0U&6DG4 z&eQx&p>wS=UklbJKLJBhga#)mpMOn5<@(-ZAFi&EpE|Z!l(@g_YleKR;Pv)uSx>GK25-p7ZG(4C@ZU`Q(uM!Ai}j}@Qz!hl~QvW`Pd52)dy70JkM5#vG4 z%^~f=2>NzR5#ac7VefwZ+v{1%f9nxbu%>gYQ=u1{Sy)*~nEzK$f4qN;4A|P*ls`VW za`VyXkW;1iNpc(2-bsBbULMcAX8HXxbqMpE#)>I z+Q2%!&i(5Du=VEgQ1|=)|5(z5YDPpTOp;{Z60#22vSsX16j>sB_FaQ0J6RIhh9S$4 zY>};OmF!!|60$^yEWhVm=l1#Q_dU0ByPZGIxz2UP`~7-9UytYGaew^i9DZO{)3Ect z2FMlh^R--++us|=0KB^EQ<<4BN)3u(%>m^aaO;QeU?{}sg0;xf<}PH#DaO5~{9V}L zjez!!I%qHl*9mwvMB87#OdCmqcjakJ%<&V)8CBrR5}m_x=8XD}ssVcwNxMs-yr~9x z4+Zf?n^Byvf(i+RM-^JB4fXVd6V(;0_>Yt!iiY(KZ>5?A%zyg+*mL#VxrMHc{QKJc z?t9ZUIlu=gAz>CXm^lo>-XdreqMB4%yQvlGAiuD14)BRyA_){odDRd>8=e;0e)xn$ zA`>z*GjExiLQjPUg9;YeybV7WEuq9O&)xp)I!yTAKK%1ye;Q83sGJE;BHXVf z(>Hk|>CfO6m(H;KV$+(gN(6UBY|Ima1~WzbWLq~BB3y*XzXZ@*0Y+z2&67hGupI=% zPFXuS#imvA=L+JIg6v7~Inf5U(4=pN5)!EX@S_BraEzOZ#S9lUG(Egi9+k{7C0D-fTxT^ZM}Q&qFC`@f5*QcoN}pArriPO>k#gc* zJnu2NKY!>U{PBJ2kfW)XmJ)EzhmjXyOk6hAo4K2&M)BzyhBC-dSRGs@0D%4tpeN{0 z*{+n|NGn<>;_m`qBOY9(5L*yx+N;2m$0p$0VbhMInN;r3i?|`RaR5U5^QRl6BjR9g z)a2wOP-`q3A1%BKrjnGLWPUJ|W|^9v{(_E+#X5uzURLE$`1g6ZP(V(6vH2*+Fi@Ex zx+$XiHiwt;*?g@C&yAb&z zRMp~ugFOht3=!+fc%yh@L0PcLw}m24pJI}1-w$4mN-eAsDtJ!i95+abN=nq>g*1A7 z-MWV1c;U!9h>tYQm(j)lzlT2ht(szq``(x0IFgHFS}j!PoXepGhCWdB^-*Xs0FQ}^ zAr{D=grDc&MnM6)9sI+Tki@#eE*2gPoa8wBujyS~o0E+P_O*A97eSSP?}st{OD8kr zyjMW|F0NnW@V-CPoMJ)$^5>h=BBxX4Y;0`}&>_YNUq6yeNgdCz*xX^!(6ktlJ+B!^ z5ZYCaln4p+3Gu@t5R6YHE4T#KRw#dKV-b^+%gP6JgN14~=b_zmfR;mzCWz#dwQkqB z;eQU*YCU?46vh@7+WiItr!w$Qr{9=gGI4;Xo{Ce*HAL^Yca~UrL^gLjuW|11qu;&I zkC^3a6sB)@xj>>TjV8j>Vc0?Y7lk2(LhCEkh2zuGD!G|gGMpo&!+DDo7=u%@Y4H-O z)De!8$*!ZhR@p8@$xn_|Ixl3e`p<8{b^|!v$8-z&PbeZxOiiC>rJXy+3bmG0MI_a5 zu;>ebFQ@ABeGmXHg26QdK3NA%Va91D*q7MWh6buBD2X_jlbNaR#wm} z>XqR1d5nhv40*@>?jId!g)nxI|2NVnPA)n^pyK!t3~?`Cz9jDo)|!uw)vSW$=jhU= zG`a}NA`rAeYDQA9iJ2c;_Ve?j%m%0<(9g22iR~=t1e)^V{~As{&rCNlH!ay5B#=g@ z_pI{F6S7bJD7H#(+!`%bzsmu6dw@jSlYU5THM2=(YQsM~e50kp9&WVXn4f4}jFgH@ zyBZdR05w$&X%{bP)-%+!zYD-}KQ!Z`pXWKQ{$0?46{tPw6HYJ%xSB2iM&MQl_VcBA zb}>uXQp22vt@59*hH5cgTxJ&lKHH+1LD>bvvocbh{V`aq0gK88ZWY$W>ks)17>}4# zzImO2`#5~?5s<-(5Si^tl zDky?hEb3LxhYe9f=}}%W%gk%@adr+QnMd)T(cIj1eQra{FE*rco=Dwqx2$*F7|hfl zt*1BbT)>Ewm!l=pyX4;N?1bm6F?@BsdxMd(ej78%a!N%qYFaARkOkV7G0*cO-2%X? z*tY@JEEelji~YS5W`(Rj?H1ExLCcKdE z;2gP@g)8iH+-Ldyk1s?w;DQWuPyNYO>LUu>s@Q2M!!~lY(D(0gWL8f9LKy0k%Bwe; z@OuN#v6z?}gw|&3_`vBb>ua5UBMs*G^2DRSRr`p ze#F3yt-o+6LHw52)Go6n%*Nu3ZxP(;t{?(+r3jT-HU)r{4z?#{O$WQsZk~Ma=`Y`5 z7P@b9J#5j@bim)feLER_$NUv7Aprr2G4BS8Cg%y7AOvda2#*!z zB|Y6mJT)3o)goGQM{m_%@oqMKs=ldNs%60T#19$I74{b__TsiN$25XtZ|xZ}T-Upc zlK^96Jr_{@0mMqFK)cv->(wo&`X$e6p-rLq*Ggv)9^cR5D2kwDudADjdbL3fk@&$~ zI>6=SWPiV9adM1aoUGdIoSaYm3j?U8-^;5U*S0K>>mz*uHe*`?y|a$3wX#wC2=o#B zi0Bz~a-CmRjnRzv3Iv=%7lj&@GuCk6Ury2p43rPz{fO@b&L}M6crd(REn>AM4Dg99 z=>*{^!cZk7^?2b8i1Y8bfxBzol$h*RYD%=p>wX>1(nfon^@)VuUD}kRtGQA(5Qsm3 z4^CcuzWQ@TQc_(q^QvDj`i#Q{=HjpvUsC_1{&*L@P0XN^wv&n$&k*ugd(vtC2D7VB zc;V4wA_|oH&nWqFs11+6)67nL|C@f%l}OE@vT<3pP-%|;^8$FS#EaPMN07G5nw(v{ z)g|!H?1j7CHa5Zm9~f$qOn#IFtJS_#xkE%$HMbnf%gM6`u(ki%VL_Gl>^*a8^Ut5X z4=?r>;4~!0z;}BUFnzUBvC2qHGfTUC5dPBz45VAgW6JgcJfZ73Fr2abq0n$Iqkv6` zFRTHeCSz-Liu^C98Vb~<>^GX_AqLoW?SOwC3Q=H6)sf4a;EP$v8I+IFZ2DdQDvX>wjYUO|n0*VM!Mj>{OsWPJv zPB(+o5w?^V3SDa>76fcQGVFyT4Bqg%yOe((8nY}mFvz@bQOdpS`B;3t*HB}Bl|yEK zXll25qr%>55A4V(X3IP-!V#HWkqWJxJi>|C7|gQ}HQ4?b3|yUW@VeDwlYlR^Y?70f zwg-^WoEjE35x@{d)axwUB2UVeushj$>Cj^}v=;C4&AcO{EX0ew<`VF4T!5Q0f zkJ!u{ZlI1D8i83q0+n%@zMShO(LgogUwiwm@2-PIl%cPQu|o3^ox2!q4LhBy3nFTq z5oxzNV~&U^@kV`GU|cpVIP*%E;dAz@Rs;pD3a37X)&gH5QT`}C$kkMWUAbqV_)4k8 z+rj?+I$&y>I$sbn#pus?$KRc-%LB-9xoa&@yd59RG#KTj_WwTymVoCX?Da?AIcnyC zR5A0yf3xY)d@irg?{8!g94gJY9>oDH78ek}y?x72x7`rG=zMvXd*345DI^tR30%iI?s(IAe2~r%p3ip^aECC zW7YouT3dCCE8h(sUH$np+$dhkMitq7wT!l_oi$Vt&g`hBJX&(YRreD?oC-7g`?-)K zc(q6*D41ew%8tfZzZ84nWbQ(*df};`OKd-j43#?jyZ?RyaB&+^RV{b4`_DR9$UZL1 zh^ad^{cW>c=J@I0wb=fymQvTsMwFWB*}I^x48=5L_W}ZLxNr%GLcv~xc?Cd3Qn6`Q zsRg1ieH%FsCyzok*xd{_cV;&0O8)4&cy2DtY6C%(4M)DmK$$pbIS{6IVXraEteo%d z>+L!Il)kLN*&}h7b5c_=insdJE5*#qkOQ|Vu-VYIC^ozZ1vo_3#f9RksNLyx{xkYa z%6b=;ijsT;F7UNKJH9xgFi<12X=owjHx|y$&xr$2Gqpk(LPU!pu@lAL%o?R$TV|U* zav!Ss-njkS8vfbY{_jfiD9QASzDV1Q4_hS^O*JC$D9ZQ9Q9?TPu%L{DZZ=X*Y^hB>EY8VCxHKd zgiKgZN@I)Jg^|O*!Jln#>ah2va*B|}&ewtyshy8J=%U3ox;FA$i)xy##3tlCjHcU! z%+&Vg3Hq&*+e1FbcANjL_VxCXSsZ|?g-ieoRPX)(Pu3X53e+QOt=!M4FJ8c!x}l-r z+Wxg}dPB+lhu*m+M_)dyRXV!+uP;MxQCVm)}BCV~|z_GLN-y8rm z0%IGQ)%u?gc&1GZ_5$z${-Oo#+ox3&5n`v}NRnZ zeP1fnC`n8(cWTC28f>8uQ)LP4Mc>W*mWzX}|epjQK4iC|N60ER)2G_ zM+Q6)7UsrpoF_&F(m8G`_t?BY(lHo?6jO#aRm}nW2lwx%eh_BE-Lt{r@3R-Isr^6a z@Nyc7_Ix|fpPyvN=n>b3xO*dIdyDcM9Bd9?)_g|z`z?W6PY>N9uZ7*+-JSH?=ozbV z4w!!DmZV{V1+Q_X`ZV-T(!mR*fp{+Kwgu<`8Ba%!7c4y+$pkRm5xzCuoZnj>^P*2b z&b9*kr(sg@P~e={3kxSf4|87^yWV1sbQaAotyhPf=IJ&xYn*j#?K~dce^oX(cJq=@ zuTVWKmjPxDl35BtdR_^Mh{^%^-)fFryya_IHZ(ss7o`h}?*Sk9IF9U?%+m!&d~-`N z(#Q)w;IbUz2-xm{#k4Lqp8L$%voPW;K_BB{#y@gZ#FMnlO#g4NE^(eThmS-$ogQp zpTS^)I)j79oflym%!JkQ`fx2+$Ib8^-3WW8HYxONe1nTbrf)Bd9V)yx;^%t9nrovTC?Jq6`vyw_-q zVdF0)vyo6r<0H^D$|D+tyTGfK7DiMzM-v7bT@4%De}7C9OW=C5JXT#&=lr1VmY3jB z#YpU(Cwk4BOIPss{rqHaXflXXqxHbuhdRTftYl{@?eph;?&sl3TOG(dT?GwvPn-#* zRb*glVG#fuSD{;P6Peq7JeA*av-~>(1#`Ga>!pV11gWs>oSu@nIGJy8T`HUJ#3q4Dx`h#6IvufElJIyzGX9<-02m&py0v4wC?sZpx zK!d^h0bF4)lpLf%24XMIjaa|nmz7*uUjCW;MsyA=^`LByk5(v3O8fCqRl}HA#Xqe_ zFWTnkXZcNkFeT1qoQl&fP;Lc78GMCDOp6H!Y|EGR=|8`;E;_&Gyw6Ex&7vhI#q?Q0 z=E}8KCm_9(L7Q$5}foT@OOn8QB_{MwVvG$Te>&lB1o7EGx3 zi$CJ%a6u}D7@zW9gj3Tm@(>UG%~8nD`a1CmxD0f?R$1U5_%msdw0N2#l)7aT%wVy&Qy;~A`@j^d39 z8ItkJZ%B#z9_N}jvz`%D&zoA}W`A{M;mqH_osbRQhO!O0UsDjxI|yjwXH9DEE|?Ds#J69 z&pD~*12aVZ&iTl27DQ-TGkws=e5Uu*cFp)d*|SfuMp4B9a+fuU&U>?NrxI?uFz#;z z?g;t#u-Z+cH}&-t>tDE&s{x(Fc$ObeT=>{2Q=jDF(M7Itk5^R7+I=(^%!b;)!vLJ{85;`=3lj@FQ)~Dl5C(kWj#3FG z@j(NNv55(I;&p4y1*70_>x|%yLcmn$qFXv(FSNHw*AeiL|He(`w5k1xsas}d8pu9ZR^GaPr!^ZtmyK3Uh4gaVlyC3Mf5*X2?G9$K9b!&Lf(Yz@9%4=hBEwU zdCV;O;pSANhRfY})2|YrWL{Uj5%>K4>ESPcF>(vNCQzrfbwe>OtB;h~_ z7&_~fdCkkoe$f@bmR~H)==sZRXb8EeyiAUT0^43Fir7OJ@4*Y$(~+8R~j2KWR)ms0#_k4w1-@yXc@)yyD+uV6`XXF72ogFb%-V zc6|4|E|gv$Re*^%h`=gJMy2?nohCDG^p`XRa*D=LhjD^Flg@oCZefY_@92xYospA* z?qB{iDsKlaXf}EOURPO4RQoX;uXH4Ws5s-#c^OM9%o#LE8OPZ^jB5G&cL0FJQc^Si zw^hHZkR5oWw;%FOob9HdjtgWtwHIuC6xC z2iILJ=$Jq4oNw20)d8;}I~Yg#91DkUO4mK>C(%y|X@n+oiwDKNUi0yAUC+$DXwb>b zsqHm;F63|(SxLiN-H^bkXBn)_iw<+GVNCC&R*H!kJYA4RXxU> zmu1fVpT51mS70&nsg+b*yr5w=mVKM|%&$>>A+M_rLKzLOg=^O6`u6-PYg>e|)JO#L zm{e>elJKABNFnX&w#oPCfk8O@lf-Yti1d!AdMQ)Ab?{f$kIgAG7qm6m`gpl4OUea^ zJvqD};GqWyG0^7tAIRImAtKMBj4awCz{g!PMrd)wBiWRY|JqMy86K~v{iu5&q z0rlz9mFJ{()ntJ)RG2VSMN3)fY*!D{>ey`j4Tf0u>0yzZwdQGWrC}w>kfN#XZ&$w4 zE91P{^e^`1%LD#ZH9eFF`JulAoO~;cAtjiwBhn~-N^{|k;KBcP96qICoT zq6_f+?<0}DCiCnFbTiy_Z^tBYVr@vZ(lRoA-3<-t88PfK@GDN>=1TR+`xi6xbpP95 znXazO8hg%%%d6dj<60Ve$XbaYzQk1i_mPi8DR~vh4Oa>jC>P}S>BlKB?LlX&60$v2 zD6|4@ctvBu%;BYsxXI=etBH>C2JOpYA3|y*YV>H3o!sazq)n zo`A}9Mp7s|&sUHC`9EnQwH98N^^aYZbYhU2X13hz?Gh9fjPmjI@qPP`UW+&ExPT<{ z#e$2{0X?n1wBmIe7;#rlp48FNe(Eo^RsN5IWu)HQC7>BZ?jTm%j7rWz-cwYjjNuF= zr0!RI2x{r3*TNDK_vp8`oe2Z1v6vubWcT>M0Fx4#3NsJVjh z3e>L|kO*f)_EH!y_4H8zwCL}rd!m(;IISFxD}bKd)%_Rm#2Ml-2$TgNj35kDu$dm- z$l@5Ng74JnJo{C!*^6D>lb*!qgl+y!Zd)wgc)mA~QY>q^aw|L~gBE-DsxOi>v*%|y*Z zBT^*#`)L?TJP4oR*8Ut|0%EI~7RILIm8)C+UcY2~zyJC;x~}9_x^|UK5Z-2XF?2R2 z3y<|jHV2hd@+mU4tE$W$A9)%4y)_AA#(IWzp{l>jI;BiotJ+Kecb1*~&A)d6Y_*;R zOiJiB$uQX)GPff!Y$2BOj##W+@)=2WbAb+$O{K@;%m@BH&lMVk7tA{P&*W@ zksuEb-qw3SvPnodHMKi<1@4@gZZ8h^u6qoN`={(J+|0{A##St^JbhHBRw0;$PggfWY$}rt4tyU~24H_QuQN-)gQw(UFa4=*l!k*&s z+j7u43Gq?}G>);%gU)Cd@UQ7vhw2q%Y?|bED%@-9uJzu~r$4H<+T&mwz zREp=0yF8I>^S3LMp zZ^Q*_Zy*u7oENFtv!yS1HF0USQQv%_N=Bx7!gKb^Y~=4q9rgpPvzJcsfPNUbR!fdC z;1P<*Mi_=N-MUKvBaZ8#E7OHWW-T2Zpe~Ii6K&qlb{Vy|3j*+A1(YjT?sn6!bJ#4PGxoVw6YDc$bgWiKVs6=PIyh-%JU&wmnfdk17#oElgSU1 zy?#w4%|q=mP5VgL#JKp+kZ>6`zWf55~iI$H|4~bLLc_Ah(xe zD1!$TM_3%_k(dyUQ#ggV{4}={v_aFndK8uSBzxQKo@?LGVzu@fukL>xZ9dz2Qm0{U zTGP&yJ8wO3W9ndNW8+GCao2u2*zsuPP~{?qD$Po-h9MATz=T?*N~o2RtUfHQyPRZ? z1Qw^n6eYT{+>t1PjR@nuulMK@C7R9pI2&&WFWdPX4AfsBo>-o3lJeA3ho+SNpG7*_ zI-V6j>zSutWJ*lzx?rufc8-r6J+K$3>qO%d4b=TUp;C1Qy*GRIj?O!l|kyiI` zML$o!cBxlJa&ueUD20hZsT7G72B=69@~gR-nW_DW6Z9%e(`rr>Q&!o!I1G;!=F9O2 za*hgGaa3l&)}FmHQR(>nwC%~Obi4|1 z$gm;lQ2{hIhH#TP*c$7&c(DLdP;sicare$3Y#5rK7V@#3XZx7-ME{e{iRVppLH$bo%yqn@Xx7ff~B&m${lh?ro?jRsmYbn6>&{SgSfD>Swo@*koz@n z-UtWmxK@tvLyvb65H96!$p1anF#r9-V7e0Ml16~Sw(PRf+!^01-pfyAL_)(;{$vWOd+G(rF;KiQXF#b z#(f-s2*l#M;5s48Gp7XjlHg&vXTu8}n@70cs8HaLj7xrN5z9%Jf55A|xU{q}3ETpS zTjxO92YJw8%_Y57Ym70bD$+tXiZh9r~P7 zhS@5IV2CRq!r{M@chzQb(aE4Vi8tzr$e?M9^ylN)yQzv$_gq{UcAF(OGIDX#)Y+?y zRzrPcMF06|y+q@5E%Qv%TTYTj&zGWFlo^A#pgg*IFiFG3OUJn=1LA$-^&<0Hc3p3Y z=LeMr%sSdzM2{w+s6QeKG98^@d>tE@c<=;pILzUkkm;eOfsqf|3ZV)X);bW|Mm+4h zw#}_R4VhIIa-4~^qnr@c2}YS1z=$w>2A{%d20XjG~R{4EAY#R_zKChJ{hI^$ex#~0i)+`O~ctnq3% zu(2WjY;6IhiY;NNU4HXd!exh^=#-8SYRZ({FS>_wH?F1otthW`Idm<%lP1S_jR?9m zqvmEN7K+aV&ga@r$@qfZ-&St3%0m@bFO;YdhLX(=Vi2h`DX4iC<->vfT3ZNC1%#aM z%KrD@gULw?a#jwWR?wHcv#7AG|2bW8q(N1^KfS+ez;q)AkrfFEa1+5_M&`qU$Mb1y zY`)!ML(QPY-?hDW@A9*<1cM|e?wrVXs zDaRrexz&(-e7Y@DFu5op|Kc4H@7VAx2r>BL5~+&Rz>xz(Bg3G#1AB0WN4qqWgrkZY zZj9L5vS&pc{JF9+$Qgbz@70&FYiqWFTPdrV2k%(GI7+Ve>Q7r5N=}*Iz*P3KIN&}N zdbP!!&-Vyo2u3d5Rc2JV;?x}#c6Q9G$o}~~?{PHRfu90PLrJO3tK)Xes#7>!N*i{S zD#&!7UDM3Lg?`()IUBe|Rj-a_{qu9WQ<~sK{qm-Je(4R*^{*_G<^H}pI#NDVSjEs!px!YMRAK6f;WZ4i&OqO?hAHoB;I@a3Gt#_#pn?#ZO(ZxXDlF@rb zjH8~>`?H;`ilMu-T|vKHjSLr3WL5~(nJ4=Kssv`&@w5h=blJtfDN z^`-g(Yz|~Z=}SW68iJxqn+ZX@Nsg=uZ-AprWd^47JbiU+R1SnCZ`^bs!npPj3W8uC z+x#!5DezlLz(NYRgFib;!uPG9zkJXtlrVjo@;3eVLpmT#bWb5h47=8-%gcrl?WPaLQ*vXP=_>WYk&K)<@PC}-Dq8QI3K>XNVQS;p>KHx7E|bBilZ zkB$wFir*+GfVSXG)!dbaz9`u)H^iVQV%1G~rX)I^p?u-h$giGS&t$<~Ksy$bO!MmM z93DMwD?jjD_pIhgo(8ysGbtZ~M#C+%VTllj_?#4txg14#+xEOQYz@;&L?i{TE_J`<1uH0| z$zvHHafc3gf@q+L?Y294);Pu<{(`}w?TJwRmOm5NP$WyguABolWn;|hN8mM z<6Y5!h01j6U7o0e0Mo*Cm`Xp+y5{NMv6&wS&sv%JxqmZ1s6mWg+dh|X^BUfKSSu_^q4MO;K3+k zfyY!BPoNPZAn<7_uU8fazz=A*0S(lr;zVdTc_GkCE_z331zy+VOENSx1d3?a>^iv0 z073_33q}=)fovz}$bs4vW1(?r!iK%!3f@ia}$U{Y9PHlR#1pfB$D9Ju8KXTt1xsY zlt2jy8W!u<+7uTkixil!H1B@>3aPBFsncQP`xt?%HFf&qadQ9Z;atu09+FSP(%Sc< z904-`9Aigm-3_6(a;g~}(6~muTs366Y?zgICo~$vbSb54aCB+N7RU;BZaJos;))kx zJHu0|t%j_5FeWD}H9j%$V3^5!h0d91ZKZc39vi%{ur!pPAI}YcX%2>UG}F`cm7r)i zwNQBEujy%}_(VzPbCZq!9e@A634>f_>^3=N-uRKQb!&L zJ4Ui_?y>whKRNHhURGKff#OS|^~XvUE`l%1^3nHjP|Pi{fEFgp^Yi0SeiX?Yg;}La zT(jgn!id@vC;Njj(+z+H2kUgKbp-tBK~kdN6<6Z~-*)K+E$S3w$yZYcv|fY7Nv=;c zXfBKck-%zAbMz?0dEp0YF6Ff{ANYO#hsM|5F>hW|hX)ZwID2mDlRT;Tk@z7_RPZee zlhZA|FIYd5yr5rI-OcrVRSzwJ&3S33QQLDbCcTjG6#y1K8c2#O*bBX`8C5fFcX@lm}1>T?MU9*EfA8Ol8PzJMA%Zt^kz0)OU@3 zsE*aF#(8Pc?o}o!r*m*rQ)RFem#|W5id2bXR@YB!l%$I}arV*L)PCJzjP{cTEo@K) zmkow88w1cNIx5`@yavZ~pOHV2=gHn+0}@!kD1)T|?g4Jhne-xOqCQkUdZ}+gnu=r+-gJ zYveItLr;=4pvm6*AiSw@Beu?Ss+z#9k8U(f7-EYxuu)f$|}J&RKN9xZ-jYOCwmq@h`HP`tBdzxI!1f%Xa#kCch{(C zalez-P#w#CV(E$FCjduFm#4q}r(fsav*-v;#nws@PD)M;S0Odm1#nBL;g0cRsDbsN z_VL49k23r?x=#l=q0pAp=$B6s!grzCNSt+JV*`@kQ1MP?`T}M0uwm8zDIPQ;a+uJ? z-ThB@npmhZRg7wnik<}s=fJr2ee`JfsuAA>ixv&H+1&`xYfvGKqCi3vl^*@M;AFe( zIci~?bur1X?hJP{yM%q-LE{Rq>*UejiFt49zt;ZP@;!JQxFO#kS)P)1M%PLh+FmGh zgYelJ1lEwKLRy0(um0i*R-sPdLLduaL7f){O>G7}$YdLAYj>4mYcx_)SQ$%UCE0G= z5jz;n%$zc|><&Pm$S#OT)o*{y@BGRsSU0-5*SmT;jpN+8-8{?PqyGE1h}!*{=nGCn zk|A+W(}nV#uO(v|9_$WeMhPvKd84dcg?Fndn1-nYqjKgOH;KftYKXZ7dU$M}JX`}t z=0e}EQPO2bf-bZlYhyFSGOMg_V6iWe;61w#5`D|!u1Q={agw;hWkp=5k+s&$_-E^m zQQ{yRoQHdThkNB6a#y8A2^f=P=q1?S1i%<`<65|D?OuzfkcWrFioAO#tC`?M?&tGY z(M2J{B_uO)95dK=WukmTvg0LtUE9uVeDNGH$6{ftmi@4KtS4#i!C1}Nw};<8F0R|# zO7!)+l5+S6w=q1Lx0&!EN%SKhiX32a_^7Jo7DPc3*Fwkn-1at#veKz8o1zQrJLSHN_t}MEb4!+@yT9<`O>?sP) zmMJc)AOohrr*L>fY~ehHoTT_ea_EzT>B|&Xa`Ur7H};hl7Pvwxdaos*mp5{{B(njS z?sm`NT}l|Rmmpse@Bne*R@Y;Miy^dQB^VWOZ)}?SuipCS`D@ZiQ?jSRvo6z1l;%7t zu0rG&A~bsua65uR0$u})6EUUmfrYQH=kC`JmyJr=- zVFV6A&l{?ehzEyjysNCNtm6}kcinFlvC7Z>2b`j$LWTn=4b0J?p^{6ciVCu#e*C>` zxufwsAHZS1J2(P?jL_cR&X=SC4ZL3oggf`{wOzd;EnV@&yw-L0;|%G;oV{3=G#9uH z=AftAf8*OT2~Q{Q@&u1$!xUztr|bu){$y-8xG4FDc;4gVQ{eK@X$_Iji#mP_zu0!r{yT zYayF;s!3}x-vlKNtrzs9yxmwiLP2E(5?!AM2KuMu?+-J<&VvSHS= zDRZT)4_X|*eLotol5kR}OpxZ1&dyxRIs*X61{0$Bb6zv)7*IL#<40dS!9XU^CVBBmlVqioKfk zXegTF?AdF+E92LWu8fczI;QH^rzgBtro6{icGBsT{gr$2NC~T1-O?lAxmu}TicK15 z)1LG!zhsoqmUm>H1rc{gDn#!)O4l`SWTY14HUYEh#IAdB?;OQ>6Yfd6(itR;kS|gH zy*`~$Rb^$XGE+OTq%8<&pX37T_kWo>DAo>un;nyih?ErM><-tzeahD^IHH@(Oda*Z z7^kv!-klB+5i)`n2>_Y9l5kq(4v}a`MltjPwBh{=Deyijp+0{Ly@;vK@O36WAequd z)Af*WXn84NsZa7>3nhDB$iR@Y%JF9YU2LX|p^*`!SM>RkU@o|vL>t7>xc{E*#}Ke^ zvQfBkSZ5Q*oY`2|`M+Q^`!Sn@X{!!Zu@_9u36Vf)933?^BBD*`;s)jx*FJrNZvdoP zwp&l>@C)`;av|ivIfVmzOfVM)2emMi28n59@Ci)R1UiCbJL2{nyhIV45HeK6QGAjX zM%d=a_TflPO^09)1&+DR|AOx>zlO`3{zf;w9)xAr=7{Z!<%I=!b2J!L(yw2a+6HRtnh2VHSrc;T0ttcU-Mp=X)oTG{SF7 zXM&$m&Eiq6V5GzT#QTn?`)h5?7N_HUPmFJFG_4f{umG9cMYk>SG7#4%y z46@4WKqy;*yTj$nm&xrrMoqf|a3ytz7=?p_10>sEVy>Io=@mMBZ+YSwG?e68IDcJ= zDfKa`%WPc#(q(yIYnhdmcCg~r(PSf?}I|1xW~e@$fG8>!uv`+L!HFMc&lSFLWu zd-bdDOQhGY39qpSW-@k{d&ZQ~;++eK`Vut96to6)TOTqQCk+~oR#wu10X}`#=NN$x z5oi34MG{L7{-@Wm_}}L>5O=7~038;7Ca$&Sa_+$B$if4uz{F%{(WnWyPsxKF2m(?cK0yMHhf-k)5y2YtyWb$`3LY<#Z!XvbO+Dmouiu|IjXXwR zAL;4oBNVwc%)jr$UBb@J4o29UfrkoH2udP+9z{x*$2j)v)TOEL31I%&JNqmEnRZ!^k! zQzMH{!4B_R%xaUIJV3QO&cOy{<<$cWLm>j7U*MkS;R%Tn6=B4_%4r{6Sa5JLKQ~GK zA}O?D6tP2*_mPTN1g7Qbvs4e0YMV=HS`{Xcd^24B8$;35D>Wv_p&wE!TJs0Rw3Rb%Q+`ME6~K<>uCQX>0z( z3wV62W#e1l?PYcS(`A|3*9{sN^%(!j8f&xWt#FqD66ar2DS0bOBft44!K^x_q}nJ^ zS;k>tk@W0dm>HG|tw75g@C5i5!;h_Djwz@aVok?MMNI=XL@1Y+_3YUOcRMWuI5%TC z_P!l`;j_CCzO(cD_wNS4rcO0B4487YbL>5yI-F)cR4;%-VOrC2Z<={ST*l{5k87Ua zw@Ke0+>(Qy(wD@h>aT9^LvD0#p+H{BHyODtzxM9M!NLo<^|kl8xn`00v@+PP9*%E3 zmEG%{UjMS0e&r-bz{BjoY+k=C=DTen$bD28Vbk{v9V}>IViE`4}hA{Oq3; z8Sue1ATuj#cg9-YNU$w@n{!+V#dIW5{Eios^bq+z%V>iH#MRRdZ?it)h!riwmpj8}7Sve`dbUtWUcRe&9>`SWO(Gp*gCl zu0>HlyXw06LT6w@qK5X8q#jlO`P zqU7Xz^@=tq`(s3z<%`IiM-T5mi#ftb8?K>i6{3U%t}Gzg?sq2Pb360wMh6BYjnt%1V~_W%!KJ zy`W-vbz6Dx%b#v)&X^S^&-{cux9E*qy@mX*n=9{`I}!4>w5DV+9zju7?qCk;SJXqMbV9d&W<9i3ddjSIjmP7PxAQ()^k z@{6G>??^_Ry^UaK{__iBnK*EA z@BIC;sKjL_XvcnC^^U?4qhdBE7lv0sm&;+96j`KSRAtv6wB2|=)uZp)A#rv#58P0V zjg3IT%aro~*|8tCZR>Kv8)v=7)AAveutYf69I`xIPdQYnOKSN0MH3GHL-D^>etTf= zF92tN|Mpp}_>Ye{VrNaN-@cW;>ayAY;vng!Z7*Y^lSYlN zSom0z^>6S&&2ph(@&6!{nHd@8rclrUg%EQOR8rk=LIVW7{$!!G~%}YU01icc2Em8=04v@ z-$mTAr7yzsg|cvBP$I!hH7I&Cg3=iG^0p)^fJDfORd91NBvzcAoDM=O!Kk=Wcg5B@ zQS*ZJ!uRVO-ZP)iJ2>>9TorYBvvncmfw2n8#@s@dvQbo#ey}X9r%V7o*~h$}txdgX3s<3Rtk@KCt#wC{=vm=t%$WrSjvI z$w27Ys5mC$>9n*`?D=Jjly(M`a6ZK}mM8?nXD#%46?jvRTH9~Zm{h*58rB};z^3rOz+)&Sx}io7TR;F!Jrl+0dW>!?qL5i3LxeG_}HG z;aC5?X=mtvJ^P&vJ4Gy=`h-afN;E-s! zm#vOAJOz-k93Dc-l+MT=7RO`Ea7CJ1Du(yK2A`~vCObvG7`4-?di@Lev3r~ep!L;EANF4 z$5Vv-{9aBhKvk?Ynap|4ckegVzwOJ&cYD9ay_)__SOSYZPu~Ow8zP+-0S@pLG^^3} z+g}RY87Mp0YMI`fun}evE5veR=s#c%Og3VU~ZJl*uiNOU!g6{j1BK zw^mZsm=vklax75*RoeT;||w2_6pg1k0XSTtdvn^vbTs+gzU}z^8G!2_h0w@Z~w&cKJW3m zuIqW-&hpw-H+}oS_Qb(di9AhShc9??wQqSD6i5SzJs23V2`t*!yV&Ip(2=CRQmEI_ zq3IrI+gH3wbKA7hdu^&d0{|{FP2FCztFA`|GWVb#2JN3r#wbEyR~AM7CY&v(&Fd}^ z0c1XDC{Ukc;8}h`OhrvVxRS0JHzppE1AeCAVKjQW$;&;_5~d`c=UA-YrSK5nyDpi$ zXm888HEl8hxR>R#W}NsgSY)F<5qQ__*vA`5so={nkAD zW!ti2)Iy%zavagJKRtVLu@8rRNe-J;PuC`77u;5tcV_paTHF^pq6F8QPvF5-eIrvU zt?-XI+=M}j$7P*;#;w=muCGf`l=1NT9Zk+2bXA-wU+u(t?kp$VXg>Q=l;w-n<2nbj zt$+e5^JUr}biEpejkV+ZdEGqc=*Vs1UfWMV9-LK_{*44;A?{eo8!yodsQ z;{M?Ts!(3nbar|%LLKm^CeYa6AB>E?=Jo4)>=Ae%)_fM@5{Chi1)%5eUfW1qDIuuW#@slJ<#{QN&`+REV+Rnn=z!NI}3sP_dh& zL3r|KcYmj9oF)DFPl?v!uBnEP_@JwOp);!(UCK-t>WPcw2ee((yo%zXwO@73xLu7= zM&I&;XQCz6kg+7vp5A=Puz;=A%3#8F2Lk<4=Yi(dNe3=P`%{YFuO9?Iq3LF)-m?wKawX3yNN0}ef4uqfXG6T6?0`{b4k(d z5LT8&znZ}((XfbQMjaDVz}V6sTZ|9$HCet9IuSz3m!xu>FOb?5X@%B>xvdeEwOTy! z-0eD*PlpuQHcIr=cOIB}tTwsJu;k)QU!2bUZ16HL`o{lCF3~|-mPt)bQ42nifcd2w zMz~mUC2?a@ll0ItFBaM|r@hwd_cD>`Q8$w;D>7a*4KBxbEkasyeY|>o+8sbqjNs2r zOEdD`9mi#FLv-U5x^ZcHM>_7}`uli$mOR|nr9#}+rcPFqOiPAs7HwF&4>hF@egVy= z0UQf+tw(I^j-EGQ9a)^65@=K3yLYe2b$JLf^3_h1rNQ@$PC6Lb^-8oj07-QYqn%#% zc3GR^J)P%WG&tSt=9Sr>Q^<>oUH8RFKr7Q+AA$RUq&e$O=0@0*7hdkyk06DrenWO@ z$KgEc291o3D<0fsW2=P%BUj*eT37@Uqdsfo=XWu&nVAK|-~+YglT-SO8v&PLtQ#J8 zzsP6#qRc}B<9e5k=M}S7g)d>ueZcFz_FLg{n`+zJzC}|0V8y0leE7=>5&93|D?auo zA$p7mP6p4^883s@1q!Hx1bWu(Tel=Vj$c&jJ?ncC8mdR507f7+sz#7);^$ zU8d=1PxAQRm-GH%JT^0mTMw|fejgVYL&BG(Lcg?6oGoxp?(xU=2wGx6_roTW3iZSV zG3(k1Zgt!4(o#y6?m;u=*tzVSWNIFb%pkRr=A&q-n^Di>pXr2#(d8;?6(9+}xF z?Xi1nEo_8e63?CcxrYm@1tTLiq9?M!zo|5`OF4dNefp>LvTx+1Q{};y9}1 zRJmxdM&zLDLG$z9rwx;jt*96HZhY#mRmxKp z<8q`38EP2e|4>ytXMVRbgIhhV!e_5{L^*`s#cAo@ORis?d~Jzi395aL?5z0 zuYoxkfCu6sRt}v*oEZY9Y$Qc8z5fh2^^jk{#D|T^WXa)-X(V8yy1MzJBkOqM>|Wd6lvjUJrr#Z|XEH1AwDtL>QNS+cfUk}jy7>2S_vqS` zACoF2!mu((UO-fo_HM1TAzZHYR)h)OzAY=SD5DJrV#1H&QBe`mv|e~;&l^9Dj20Xp zt{GmPti#4Oy&C<}hN&WhiDFR%EN^)Haj}&~T&i3gI4th2p2H`g z1f%Yja&^kb9>W!-@B$P*D!L1zv4z~+w!>;bW~8|kWIGDx{;1ek3Yev{p<*})F#e$| z5Wgd<#v5yhVF^+z_}JVG884Ye&z-Kr!-@HM@5+Zn?{!L`S?cfC*e^B83FIY*ZbjD& z)ZhAlm@BJ+y9sFD1U3j1-zP!>KH1<8^OR8?!2zg1Q6yfS^s2X{DPQ;DRpPq#cM*cu&4oCH^G zN`||gwfm@Z(x?qYO#U`qd?5>#B`-}<+nc!Q?VA_6O1k9~lfR;%ovf4qwHKh!et>*@{{~tSsh|f6NA;Dl-0a-4IRD z`kEs7N#qj@MM5@$-+&}_SJxb6dlQYU4Ez*K8pKj1GOt3Q#P%di@9&MX2EUfZMjb91 zztwirao^5b-w`7GFeEol+gycg%B_8vxuer0_(!XZ>8(tD^?S^4s5 zd>h52TLsl!)kMny|ET9UJL-#ggm(6cdvDC`6EDDlseg!pp|LOj#_)A(NKncUo`g({|7}XirNTyLJ0s zLxS1`7U>tLP*Ulj#|S>MPg*De1Qi{Vf<`u;cL3ruEYkqEh6&<#ooNzwOED4C*(k&&nKW8I8`r9K((mTj`OI0)a-lG z@im5DSy4}}OEK{)etum{jfiS^Q2uuZcN2K4f>nC&V~MkLU<`GxSnb{Dsk13((=KBZ zo-66@as)`~AFH+93Aq3q!=Uo8`>KQl{!b7A0pAhtB_~dhE?Q|#sFTi{m(%@=~x$@^7Fd__5R#`rU(@+nWLN8nYNXmUTk2|Sc za_bkMFrTOHB?LU>OMK-VprsNtHO51&rnKH!R$4L`}GyUkL$(<~vP|Ge3# zG_iAqisV7kQYx;`r19*ll*Ag{MHi-8?GimR%z9HOxb6ePUOWZg&h*}l-@n!nAjtmj zfbSt=A~Ud6vVc<%@E7LhUkn9fa0lQ*S!+IWu)VpS0m}vac0)sYc>^EJN3YH9r?rUt z9A=1x)BMaj9XzX_wl6T~FBJ_|_}3?)Eh8*kW7(akQxk9HVX-iU1HYx+Q*X1zLEE~9 zTS+*%bU2DG1+mnMys(e2qc?qVU{nFQ9omTYvkkw)8^4cxsk#u<`Eblf zhw0_ylD;FP&t^uGGr?U>HbL(~tKc940aU7(-+TiMq4Ric?f9q3TU_HHLssbX4tfuqJ}X zYemwQza00#K=(#;DBvr{)q&M?EEfJ3BL4a}uEFr4HVl0uK8%`FHX&5jf}At{UOcs$ zb*k5f^atRSB@AB>=+ZE8aju?Tu_}sLg!gGDXVkKI5k~hVWXN0uBryMl&HPj?qW2H~n|OOd%Z1 z&d#o0@BxH72f`WF*e)pM5_Irb3_kmGaF-u?a8ab$J+cde340}2za0lSTZ!2SKW}b9^?Q_@k z*ZKc`ZDuV z=JLY&2>bb0`f7`|qZP)$!RU;(zkF4SOr>s=$cwpElQefGM81RrOS-n})p{_TfFA8< ztJMGkF4UgLKeqgWv9W;y8RLfC50b?;S6L|u`EoguN_!fco6pAjGCP%%gf2WrBTfP;uGf&G>LSKCp zT2J7%TsKa|DZa0)ywAfH%u!11?a*W{|4cgS&Eqk~TzS2z8lSV@UuzQzdN0rTIa=gz zw=IBO;+Dg76>B*79{|cc6G0R!%k(AdYsP(uUjDE5!e>3xN0qq}fMr+Y5lFZRFu=PF z0g8cXi5~Fobj$R?1xT#~`DUM%*{t;Rw|ZRXov{E$n)N-(FsXRJapmlr%t5F0FP~9! z{a8sRWX|Y{y@SYwMzBe&E0j)ex1zC&JnO;|_i)ZJkD6@1gy9`0A6k=XE1 zE(AV>3NwKT8vL+;x3E?T1^_R>Sn&SAs58{_+P@i~^J+kBq>`Y64xT_v_>}^WADSz) z%jk6-X5;G;;U?{qLWPj=!mG{bf&YJ9hqF_l4@M!u(JE=l<&gw zPDx4HaL0b^m%RtJ36lMXC%)81IMC&V0`V?XgF)jPAGeB}LE@$N(D>7z^85VF#6FpbEzu{&u8{wR;Q#QKVZ^NOQM zi__2fpfW0|kk?n$CpN@{DyYaPBfC6lXcs<~LzI6H6-o*rG6dba%( zE}3qg@B`-<-pUelLWTdm*?FCi#l3_HAx{`XNs&#b^MAJV@BVZ!<+2Fnd4rc6rWg2) zObiF!TE)On1b*mwrDBP05dgzq%WQ!6W2J}_0n>*mwm{9BtQ^VXUXGE%BH?c!2V%-a z{RY6xjiW2Op3}Y)jFSRx3lqKEwB=IZ7})W=<$7|zMXE(?@=r}XK_!Fj(MdVKcKxH} zy+Jch{augS-ygEXeL^vJd*vF`Q&W)y+7@&qR@z6!ZoKaIkrWj6*$2-N&{yu4qPb}D zI4CKaloSbG^}HUJPqYNQ^Z%;1|4#WmZUK8F; z5Jw>e;s#W@SMf|%nqL$=OY_@uOzSOlKFtZaaaaSJx~sXt&j5?u+wLhfPDO)hMh_=G zx_T|?oY&AkUk}hSoSy-<2B@XU9jAON*`hAfaT4t|Nxt z40FEoP;AT)0AU=G8Q`2naZxg9q4DXz48#bJ&~;lRhlSF+L@=OHVQpzMDJS^zpbk zU^(yf&iUjd|EgD~EbZzMLLgs;l2b7T@bk!Jd=kI-YG>*2?{WMaYBCX)$ooa3YujYS zaV#~@Ek~n`jTjb)wJM0fNkfeyCgtE($$ptar=MVaMQzcOAI49fi(QMQ3r5Q8GA^bi z)Q+_y{*QSSU&SE^Wl69IvCuJ&-M*6VvN{|*J^fY&clh~DZYM?YW0}mZ?9M>DTvGRN z*e!`bkVIU%k%SjwjI8NLiDM4a=H0 zIvBMruKVs67k6)7SCLbDi-0c1|83}a*+%hb;>T3XL9GvFi7IvADc=v@WB^MQdeM z6!y+)J##$e;M)(i);BhK&wY9cvm*c&BmPgyofVQpje7uen;IKCuSER%RVC4~r^E0js>uYV zV-CK)zA(jt4P6X|v;a;2n=y2kv1Plvd)EG=J{*{S%+2$xc>!EpMOaR4J2(o;VHs7aEq8+9M$5ta*+$p0WJb$DA&LVA z-iwJ$3;{0~$2kNDo~WP|g;jus!f{t597XbVOOg<+l-b}=mxiI2)wbYXG|NHKl3suW z22`&??Unr3Dh zQe*-jvXh_DOh6IR$5a$=o?r+tX6x+-FG4Y+*t_2;b4$`wcY1US zU3=edy2k#2qJCoxpB^5XTrC%AiPjl@O#bFs>Vc>Ilydu)6))`SKETnr8+~1bsLAAw z7~!`R8U_Rhe=v1E6PRQBJn-37t7@x0R@U>2z|e9C@jWIKdof-_B-MHr(pIz2rfhaG zR!h9bjQ|;GRAl%X?jD4LLjK`@)FF7~9CEpp>XB1|{uG9N5Dl z0#Tr2J=^S~O&z8}{L(=ea^hFzlhe~d)Ex&3$?3@v1p8u_tUIVGiniyD>x1 z{y{cV8omfSI7Jmk79Sk!bia!{O2_{eSyL-5KCjom#jdKyK@GwesecL}?KdUY-5Qt! z#iC(o3ssB={P^Hx@k)wwFEwz(X_$g5?eL!W6s3W5ETBbm)VX?1P!#fa0Yh@{$f+eU~yq1#!0eq$oze#4+(Pdm$P8uchc z^Sx+^aHm*&Z7{BKF~lo!aFobrn~^JwO|Xb8MkG~CH;M?~kv^Rp$O|%?a&Y|c{WU7| z*GOD2B8c*dED6(vmnw>61{5^I<0XI83aadn^cNBMf(kzy+4*Cm@EnA_TFsw7-#x7P zmhz|GSCod(JW6G(!Mz_?te$h9q;2hGR`I$t!K}1c+v3&*3OW8V(Qhb|ave+jg2%0x$SKF;q4Q-9ecE5gwfe{jodqn*5 z>yS-N-HfNLo7?U_)$3uK8XdTskYe@+@}XI zK&%D?NNY*SpKe;mAx5(ZE1ur z8fM}w^z|)pp6Hj-1n`2dSsoB42@d8MNDp^*{IEy3$jb5slL3PIJ`h<#b1$Clwj5QYl`R%OK1_KP_MBIpdqp*etf04d>F>4%bGVHA zUqJ}yS$bI8*gT)iRIY!7k|#DRgE#b-9+yi5gnU$t0xUcx&bS09YI-pH*RI^5T#kSa#{L=BPp-GjeO>T&u0H>Q5{49b}g`_U#KLbW_C!9V!$2rtPm95}~fO)+sCp%;3oU4B5EwsQj_{AD7P z-j6ZkY6?{E@x^SY~}CV*FYH=0J{c5s?wUXUpqr zjYoaAj5@Ad!R)P03kpj)pLG4IHa*nILH74(zP=~axMZ7F%5B^2k@>^l>}X_l{tJL~ zfGFE+KRHsc*zP-Hm1n2&?L~#18M?~pmyhyQMS&g4gU!=x7Z*4VPWM`5_?s6~in7-B zyijID$x+NA!PdlA^{ROUJ3`_50u90ttB6uIhkm!k=SnQ0K$OESH^JK!qCfzg0wL_T zTSG6VbkMpq_aV=SO${)4Ij95nx=XpYBAh4P?PjZO*IQ2V&K8yvZ0&yk8#v1J`uT_F z{a_>2kOH}GI?n87+M#dio`~p3&P!r#JFbN1IS+Y~x@RsBq$LL|eyEu_?W>zfPJI+= zc6!%u-*j<;#=_<2lC4_4|9?=;heruF7M9Q#6dZ&IeomzKznKdF<&CQJ$h#n#i_Uvxm=zsW2V;7=w&DM?~ z3XCZ%0)1R^doH#^rDpt*`)&2=8DQDKyS;RnqiW_N6yJxdR6gvfx+;6My}q0LZtwz+ zJ8GGQiUjXTb^XM$NZ4>hzfYz_mM1$N<`X4V=T-Z(F%kaS_Rlet+^R_MUE|}+`iCu` zUfwooc3JI8nD*L}-2bjEl3Lir(~m$CGbyrA5^FGNGvmJro(m&Eq6F*`uOu1u_Q5bM zqFn$FYX%h(iRv}-I?cYT9TMw}q7o95cD0*RrO&8oSef<_ZkHupewP$wFj=o zM`o0WT_~Ash8z36Y6-X1=y|bz0Td;#BB2&Behe4rFOFH#f)au|a0ci@TCV%4isG|0 z0rEK!^h-0@1cZVj*=g*cV-{tC*LqXw_|(`(S2Nf`Cl(nYo!A)m!pX97fS$hwa*tlXaB3sR)>q*$fDN8${ z@Ov#;4614aUvplC%zELbAyr44d6Z&P&k*qXrg_;DqTg4v33*8Y^!+lpiU$OqtgI}} zxP35Oz(YHWMYUpd5|RRslHpEtw7>t5y4_!%vs)KE#*FBp4iIy?F}qI}NYJph?6`e4 ze70MW{Ue#qZp-jK z7n|r!Rr}@T?a{MMqm!QXG4YKw(-XDQYHa*qP};1n8R8Bilq*>86(kBs8dQv4YGqZ`;en#ybC8ul z+sKr>A}Sj%2rO&Cp~+x(KyU)vLf~yq=#XCb&S9|@ABcHVMP*6 zM8flu2^&`c7&TN?!NbvQPwMFIastoFehif=a`sVPR8-AW{quUsiKpN}e9z%|jr?!ri5mTXv1>uT4nQb2@v;i0Y1 zbv@STg*gS}tt+;X`=8q{iLzHf+rmm~$bVMSuF|ZDOsyf=*g!md6)2xl(Aw$IqLEDw z`((>q3dR9%JE&kvrTVbCGUHCm#8RGM-Z;z(_^Q8;2p=9x4 zbalik{Mq0&q~dP{)jTs<2P7%aR$Z7^9Y-VWeu#MG>uN4Nfyup6G zOt0G@aUkY@oNf7ie)I*f5)%#KKVAg65re}>OCGht{L9GJW*A@#J>a-#-kx$+WgdU( z*mgmI-_>)qz2KmCDfo$i-R}B~sFd(dm-=k*gj$a0_U~6A|4l!*R&xCBWKZz~NP*wg zk3_AC1;|Y{hEwX!JiZnz~ONN5lV>W z8AhQ!~00g^!5X&KRX#}l2n{>j{f9`o17LxNeRD`h*IZdaA!E>Q8Xr$3kJKfEv&_!cj1ER@-i zg|B~AXGKWHS zw>!azp*d7Bf*By@4la~Kl@g^G8%EWARh76e%$d30oA}OL`pVwX3{EvpkE=i|+5@48 z0HqayqHMjDOK@Ja^~DY_HV86)aN%pQ@e}HDM)hd$HXr}sURg<-Y4AJfKO0RL27ubt z@ejkxzy!DmgEx4?x=*_@0S0>N@lBN6P6}K;ls*@Z%42N zX6JbTM38LX#Q|i@WT>d2t$Mff?O$z#!O#F%G@n7Z{$>pSaq`!(uz?NZN%srvJXhu4 z*)525In&B>B-sY%ZPDJIPH(KVpWLtPm*h#sNK<_q*COr%o9z^s*gn(Ul=BArrm%8A zAoB3U+tnII91fGUQunIAvbCEzy_a@d?AoEKXz^I+5Q^RDTl82iD~^srTCv4l9G1b@zo2fOZNDg)vN6Xowy%z%Ys-&m5ep%2)4pMoaxwSo0y>#hQo} z6Zz*rU45utju!sYuLvf(rXXS%S<=^OH4HDA;CkbEL;3ke zk6jeH2c=B%#Gnuo%j7Bm0*t|*!Jn>0#C$X^;8SdAM(cMY6jhj7uHsK(G zRG8E#`btr~{1Pn=!WofINGNq(V2*IPuhIRm%ssM0JN~N2+&^g69Z{Ds1;DL`Q_J2_ z%U<8*{{6Xcaa;FO(zoE{m&DDp`}=1|^GTM;faLM#{u48c$S25>&@B{`{<~1VY8xaT z1)%=mYNI*09U|i`6aE(`y?5|hrup5+kG0UD1ld%+>b=a6(;HQDk`F7knlB&i9eHIs z_ccsk+cUeUf=?)i&q56DbSE0oZ&j>CCJdd|BuYB%b-eDRSg*J#hv}XTv<*hTNf9cu zm8e;)L{G-uyH#uc&G3VYfYLJx)fhtJ07Rvud&{12pLqY)v9HgD&a;9)xI8Sl*Y~xR z%jW0064W2?-d<~3jHW(zJZbO~E$+@}sPj42)x6i^mY7(9$#fOxfHFT+VxXOcI5j^J zY23rdxi2>AlX)L?a-9w*oi0tkDJrEqg)))N!d}5k5lQJ#NW8>II!`31D@Y*QP8Qt#+boi%c>0&JcsSz$@&CYlhBK zAqI2v)m#o0QqDP~1JkwOp5LWcqYvpihaoaY zm;bxb%pUme{rlq|>UVWW-Df;-aGJ;&J^UcT;RVv9<+vti?c^%8U^D{E`UZxN{_J={ zoKZ;|ChPXlEzyzB#n(n1pg-g6`)B!cm$&|Ye$HF&o4xf&c{Gur{jU_ZUKZ{u@4>01 zd(~+|#d$`iMvkIJ9y1)>RfB)ToI0bk#7@`3%8csZ!gg1G^hzn;SB4p@!o;|a_&DtR zomBc_L||WJp-bF=A~`7bPk)t_8P)1rj(u=4&l`~RIef)?+D=-(J^@&*iDT4Nc$UGIPg@ozW`gnN{~m^Ni0p26DOG)uxrG2d~R{$|a9K zy>fPDe9q3PG)#wPZ?xX~wOu%S^xE&)?(u=e2K!lc)|elzY-KvA>QUaMUd;6_ zn@0XCD}+CuBArdhtc%C(iXJP?IQ@8J_#6C3S&VwFrGuvhrl*|-!M-(r(>KRb9O*77 z3lj7^rc=crIM~28NufQQZ-_=4kD}2DJD-8Mu~74hG#p^On<SmosU6QMQs!UT0^908{u* zvVaBUk!fX+7&qcN&0*+jjPvl_S+0SaGng#cPrT<;60C_gQy~z0yQ|;j$tOKtB46|F zeX>TBL)ql&j#tWuDG5Bmq+W;Q=|(5@HBuHi9d_wp;)S-hz?5q;zQ@0g*z4@3pa0Gz zK%)crJ0?UQg(f%`rUnm@5k?ZZM#F#Cj6B2&B)>W+eQ-sk#iu(O#hcnYGG1-fyqVA< z>315ChxjK=yWyd~&l6F3JKWCR-tx=ep_!&S-@hAojmkPa-EZaJ$q$#uc}EUJDlik$ zMdYfgsi~sx#m3RZ_1h(Tfz^3aQpS7sN%d1=Y>lBxB!&d3i+`0eCkk;DpHP9#ABm4- zV!9d-!QVy9Ipa}`FGL`#(_`oDeY}_yoes$Tfx9=>B5S&^^P$+dwosA{1v^3+CYE+E z4AvU<9@vhWcg5^Q}@f ziZd_ofLCVg!D#s-!NH>&AI@4sWDcikTbxIyk6L!7s@-RuKhZe&ddyf#8EngURP*LLhh#bvpALetjK zdFMe?tLhqBBZV+=nTz0(6FsTifZhETkL_vRy>51E1j&LoLoMebAEODDdzM*=FG7_U3~h++v(ap2)B#6dD)_c`E=Kt=!sr&^+)v3 zG6zcXraNO8%qgEF(ikk6e@B{UF7g+`aLuGbMp~MG|VrFJn)-d&S$+cK7&qe^rf)Ly>!E#yLrd`TG#g3vGw!gIPYsAvx`ZE1?>m4(t zeLQV!uw30e-9Rqe-*3AoI^F1uyQeh3r!G4CT$gO;cz&4YOHXh~L4n7sJG@B2&(v5p z6my$zi_n*`F~v+8&H^!NGvbnrI#F2XYX`KOk^mz(lD%Md?T8Z{_O0i!nX+HIWUE-5Nl~5V*bsPEJLr*#PV|2!fT(uCwrP1l1|GduVtp~M7>U2?|fpd z8Cux`zBrkPu(UY8NUV;b@uQ5VnywEnnx1YxNKB%It)TI&T%zApa_`sR>(`nti4CRe z&3=+k?LTwryYMvj`)FUDAKLF}mO5(wSJeL(G=rB%GL+bt-_zaaS;mnFT65%2*X$=> z!O7+HV|_<~xXE|@M?p78RX}y-t_p_dO^PzOR?){C3~d~r<&2v>w|D-Gk7H&|GtO4r zS4^a4mXGIUPJ=dT*LP`q$b}exMJa#pdDPK^X2?~hPzWb?N>MANi%979#;KbgObpb` z(){c{-Y#;SY$%;HEnnWzm%wdQ&kEcG))Se3D}wQJ3=FO2v$3wmA#@7FoUCZ_95z-* z3zQj#rJ6_g;k5w6aQ;Xr2Q$f!|2XXssr_5e{;T*!bDazDoal=sq(oo-_e7r(v z#-GUaP-hdx$B8|Z!##w{)+uiiA67oWY^|U6S!re+GIbxr#&9#Z;<{#nz4_o!$OWFI;HFp@TMDJ5;!oeS$EOdc zBVLSt>1tc4JX(PmZSY!@UBqr||F3hurGeY}Pp_AR9m!qsHkJZ(8VG!Oc|r`G0D){W zf-f)hW?LkNj#5o6kygog7~tJKiXc3<5vvMD|9>rTfda)JJ&0uFP1qdeDQ}wL`{$>K zq(xO*^)~|%=KOBByg30t)J*TqZ@Uk@w01Rykes2ML$0?_(eoLa%%0yy5*uv0r*WA+ zzE0KyUL>3>gPqs?T-LAE`9AweCdd|Oks8C4>QN!5TUKUv{PN3to> zEB{pZBq+j4NKcoFYW8%bPV<@s`a{QSpLr_Ax<0g1)7vYPgC1%LTOL}vsMa|ZIW+n5 zohwSZ1ZnNR61YqKj_>--+-U1f!}u;0`85u5j(By?uxG_~_IY2*21@56E51*9QGsH( zrlLHyGKFjA8mT%u!_?+1e+2L9q*LXDw#Caw5(y7aSy30#tsoIweQ(SVa)SBsh&woy z)RL6vioq%r%p`eOsNH(RuHcd{riox6xFD2I*f|xqRUQ>@Ki#;MVs*L+7?A6q#>dZ_ z&_+F9CERf-{fJBFqU_PTN2Megn?jNOfo1+N;&(dL1`GOLTgqp${B6&s(g)>HH50nJ zRDE6>+a|y1Z=b&Q%T{5V?`uoS{t^;TA zKdtO1a6eEjRT#Is!iXt?CJDE>wG(JH4C9QqOfl22;R7OYO`5siMh{eEZVhx^Uv^9K z!MG&yXg?(qbiPfHO@iUe+oNYH#01mn8V7AG?f3Njt;_W36Zh+v3L#Ui(I3KS=O_n} zaQep}$mWo;biFF_3DN&iH$)?z2vtk+nnikKrln}{(8JlfoUU5~I?v5niRV8**WbP2 z^9%;L7wjB zuz+R3iYuJ&^Z5f&+-9NpEn+R(8MtQW)6eb7d3c6(qpw~OUq2bUIq5L&=K52O{t&51 zj_i$)9HG#DK6>ZHs1$F@3zp$OFOSx5lC_OJob=FCyB0^^WPv3`^7;G!yi-WM)u=sc zsV&r9<+uA6U`9ccdov?{TtFD=;VDq0^oM#?eltuqBjK;8+;^nb@1F1K{oN~d7|$?e zt=b6tGt%=bdkx)W+xuttA)C;DtTlxCsYBJ(mV<_l#tgkC1q*MSA%R@ivh}&!B>c7X zvwvai(m!sz)pKnbe~yV=_x^X!|3ho=vy9ZZ7-pO-)=*6w{iehwoWB?w8RL?2vz@1% zPFGDt{s);qd5Kc^FN3AFQbPv3HZM&bv@R)&QrkCII_C5gaf)>*RY58WoInms6lVDw zGJw9ZJLi7hdqygy0R!VdXv@Rt*@F`#u!F{UkLUaCr-X)Yyk)u7s={BLPm&+vA;^4{ zb3QIKCJ=NlO`YM!z0{bvJ2>G#hZ7S&=I4V`Qo_EGB#GC=FE)=Lb?JsI4U$$))`o3I z^+!jEz^>iM7f_9#Z2!=#syRihxsXk@E+IPzUA zAyYwqs_Z`n=ND%fSSz69m5rt7RoMy%l60%_sDx{Iv#JGauvPN-1 zsiVJJyrCZ;xKAY1_5$wnaMWX$J13u{dh`kkl2~L{Ba~d|0ao6 zAU_eaQXuN{3SU0;Il`QWAREh~L>Np>g9wP?4H$5~S`pD%lj&1>60x@y^H~2FzPFB^E%Aqsk zNIjw(VIHoe{kPHj=w-w1w9D3R-$UKDuJ0Agna*KCpVGx%wK3gKH4>RVKJ#ANQqsOE z?fn$$bFuxgb_kVM8OhFIvDKtn(xq7JZ ziHT*ERDe?0ODy|Fe1nKzP!^HQzyvcX9mFeo>Z`5f28ocH4imKMoAT|nPph*lUjZE% z-dC!?m!iTi(P4e~f4u-qVK=g|u}kTtD<4N!J=rtdIz2Rhh$kJ``TCwN-sF|oKpRV) z?l1IpcP&@h@TnsOA1+OG)JMUrg|L0S;)|`Oa8eK9yIPHdZ zMdFgwWCoezSTFb0`o*rA?ijt1#cVE`rytnjdV1|LGSUw^Mw^}XjNMlo7It^mK04dg zNaX9e{%d|m=)cd*(yO7Ug5^@BP~{9lZfdAZ5Z~>Ir2eF%)>m&*QCC~5|6iA~iCspf zO&#OxS+z{_;cnU+#l)dVirWK%+&WcQ9*HPaFajr#WRRP3Dfnel{iNIKSy<7i{Omo= z({Hqy9$P!+p=+lKAzAyCA#v+TJ0G|FS|0tFy zekBB~VIi_m&JH@nO_EQMZW*a1%;LDzUW_)itMO$b0)#xRJWIyjeO(sL^OqqDLjCLA z#yw0SmZg^`kcmzH0opZFl(772;Ks%`{k*N#68QV1_j+#(T$J`a9`k~BrU$a)_0HWg z2fTjGZ%4>$a`Z3xlSuu!N20RCIAeuXMfXPD#0Uve+@6tU(p_%U zR{fuFAg59g+wW|yqz8$8redZEub_+3K25~xwxh5Fe{pgaU6zLStOsrk7}*Z9?nli& zb$ctfvt5lpl4XaBk)=?W`In?F(O>dym?If58tsb%Z~0KlyBN1x@vpPN#xa*us6v_xFn5(eaNTn`K@O;xGP1+iu~a zT0JV1b)H@0w+L7%wn5;<2o=x^S`6w|_c#3u2n8l3@;g$^91$lUMe6K-Gf)Aa@@hab z9+D0X1schC9n5F~i?8DF82YV6z=NXXfC z`8!#DI~|l&c{R-pwYBy1M5c)2#0c*|G<_|oy}cl2eo#{e=CokzH3;V{?x0g3+u0uK zkyyV9VRRhW8uSzOtwc0r;B5&Z3N%_ACy{Z#V%BFNO0?x@-n}uYOrrMqi{Ezj%1MpI z6H8Z*ng)}OA!BHDc<9 z5iy;8l9#9uM6Z6{VR&pa3Sru(h1fzHK7SVfcpc)_;+dmd4n5(*9OD1Rk&%3Kk3$Q; zdCl4hM@aIP+I+teLzs`{66D-WH$$j|6RYBdATS1*&>|!FD#f2kqpX~uN0?#tqZ*&6 zxOB$R@$>@w{VZuIerc!v90gQ*YWhjd*~aLTa={Up^~yL+&KM;ome=?A6DEfew8f*! z$L(l56cT=Zd|HSI0q?M0LVjqmjhdQ3|0WhYBXKYT@DzZ74{%_$R**s+NTI~Vxy@m2 zSMjm;9$P(a)XaLGNw3`t<*z~ZWAD}F`|D$s3z=Uoc4HqDVX+s(S#m+&lJ37GPh^Qs zdWjUg;=wN{uKQr41}ge$Mw?qc);2ePyuLEm1nD)#CCv5x-*+7*t0fFH^k0!^nd_+A zkQ7D}zA?bpO5E8r^W%Hh6OhFD ze`+hqO3C!vJ)li@2Fov@PG|x%Lfbl<@;WjZ@yvu6pO6@-jKCr(1op-fG zUyz@yAii;rlNHyd(Jgndwy{96iyp?#1Um0PLIE=oR6Po-_fsUU*R!~@1kR}%8 zoF9YWnAa;Ce|p^yx1Z*CUHG>yENMI8t}4x9gIuN|H1xd9)c-xewVaeW`Zy1E+&WtO zxNv%L&A`NvRPIS~da{j38h^*${pP)lf^$?0GZ@>Z5C{&)u+MgwIqI(Rjqx{)LM5eQ_J0 zlb{h-`32)R3qF=tm>4y_@HnV7uDjv2c*GvvI1;w)`jz`PpGnv6?w~d2ZTvbT9;-du1jq3 zXz-cw(a92Mg!I59;&%v4^B{Uupf@VqwkZkBX5j5=q{`xp5Ym`f1?Q(WCPCk$r3adv z=+zH0EJyeML(_N1Q{nyp-^-1wWWS9_7gvactL$7eyE3veBG<~^u5q(63mMtUmI&D^ zBgzcPyd>M@8pXB!PM_c7%fEVLobx)b*Xy}-S7Y97r$K&QR%GxLX6LrYl-@vI#zZk0 zbX%smEE&Hy_7s{lb!qk383FF5cea`WDhOP8O37 zFXii^!FB<|g!%9YHRSP*Ua^=UT>!)Ja3|`D0Uw+wdU_UXEdfxdHh>bxsn*1kTJ(z6 z?J=+atjxmGQ^2;I$UgAS=395qb;6C-ougq8KTe$T>YMK*2~`Lu8w~v?o_~Wnx+CU$ zQ^zqk?@h{@&r5!JW6yYY3Q}Kk_^plA)a+H2>Bi1R`G|>%?l9&YEfVD6uionqai?+(_|sOnOt$x{bQiNU+#FOF6;jv>e%FW6p2)7WXMdm7s`4s9C9g|8P@c!;LCE#nGdKu6@zD}3f65v)duH=r=tM;0^ zZnD5$h?xsG^?HkU>)EWXu4Y=vyhdH>-DGnG(s}*@saAT0ik=H3|B|EoAd!)!CD&0N zg8-4uPwLn2g4X*Uu21#}0_(~H(%CC{lcw51ljf1v+^V*}g?<#U!IaUDKGq6{zYJHU z|3*faW}-I`eDwZ&tnI|G?NK;!d7!#&+v4P8!l*hL|5ca%3tP#c6sP<#M=}L#ISTb1 z0`84NH~nn`ZS~uQ`K1_UU{R*g3}~JMn75@M=8Zu;l-J;S{BMr2LB1y23t-bA@k=iejBP*n50-d@SWeJRG4DWdEzncMwZV@GfC`| zp=?uHK)o$L;!0_mo%-=3LX*WX__!|k-tC#jm6V**pT|E4=(pNQ8WfK!A$>&u(AYQ;~wbbmwWULY8IZ!q!WWtrd z(4&(n?FVh1&iF9!%4FY87dP&>nx-3`H$VWahS zT+lGZ-yr-$hPSr%z!~_huW!s8biU#=H)~7$1oIH1jAU1{QXcD1;(_$9-pAoRfZ(eT(2L5yn!Ontk7b`F2@kIr(OLJHg2lV{g&5%(Lt(}bqxlz z^!z~x>^}?Q7?xW{LetHDC`cmMd9bPTssV&JQj$S5f{P(7&qMz<3P{4VoXX_RIxgMH zl=4~r_DWt#26X}XcFe0lz;}xxR3YI%7;oQhv+vH9dBA!9x17_%91}u0jla!BlT@$j z;dPRKmQE3WRlaCJqU)=dvFQpbYxb*8|zVC?nv(j*0`1!7GZN)kNu9$SF$_o z=Y4JAHR}%|#p6GX_4Z6Pd3SG$J&{q`Ow*46FsMj7)5=)fi06v*~L8cRP+jY$dPF#dcTDpH)z zI|i79KY4ze{R?x`GO&(KX9`Q_)h3f(QSOS5$h5AW{0q|LDMB4YSd(l-#+JdRI=2I@ zi;j-xW?JD;7bS-p#j5|;@tCKoSxTY>5N9_*Y*=<%t!vLF)}`&Vc8}m?!21jhI>c|a9su@i<+xy$WL%1kU-fYF(z4loxxLD?%L|T# zOK*ka9MlHe_%2lTTr)Cl zD>YFNLs8Pnf98T9onR2K@?mtiBiAy2$kIyQ3wXJ)SFEVil^Nbf@?6!nv-LN;FF3%K>1)CWKbm%8b@9^m}s zCy1bM$nw0>!lX=(*{JkkhNz_2e71hHYrwPL$%YnEe!DIAyNonyzW)f}8Hjy4 z!ld~9sS^90euK)kpQfBic{PwY-X_o={dv=;FqxijoLHT=?G3E5M5Q;aEl3Q8zbfMR8Ly-OA z^|F1Yn>z1@L*Pk>EH#61Mcv$VNdM3fFrqtbJ?1>^KR;>f(7s$sCS(`zi>EI5WG!?v zg2WxX%NHEDIWC1-^ zC@7{X3{Uk&xkyZJ795TN>zLcB_`0o^_$HUNz46|v_m5;~bJ!B@$2pyju$+&^%wfN2 zUGraUFOomguV|y7sJ7FAUVuU7C6mM;NC3No#`1)Y{0GxZfs#nUzV+Uvz5!K_g>ET> zm`a^1S1ljB@gH}PuvLk+?s)}pJ*yRMQ_|L)H5@-{k|NWQmPWb|E1-}+pU<`Zp5W-x ze0G$OYHng?=2CM-^!gTlVq$`bZvp{MZyVy+?`O*rtBu6dY#SsW#$i<3X&2@~i${c> zf0Gi3R?S;|+Nx*xeKp%}ImWck>1;KWR9EcBY;l>J3}$H8L0v2NWE9J?ex{fTgC$fQyUQ zQiozeSSB#FbA|7LXy9tu=_(r()#prWt;$j7o;SKx@4gZU+yei0&5-^d)TJ7_W101s zYQNuIQ9x-ynC&EO%rvx&o1)?ddAhHN&_{`;mz0zgst!kASvQi}($y%vXjC_idSd(R znUmM;lJfEo23(SScmHsOmzD$Fjq+ez(H*mcr=&XxSx64B(1BBqEz}S ztF0HE;EH(=$-XOI9j_QWtg5Tw1*dq*Q|f>zb$~?DUqH~nUOPnJ05Ky;o`Efe- zbZ$1r(jdj9d$+%n3Dc|-;hXjJE-H?dTmQ94--P|*g5Rt(b{R;SU23K`Pmf7}n6XdU zB2BGZnu*F$;IJHg@^0?(`TY6G=7Szn=Y~VzRaa8E^T@dTwSXwwJ2rKC>BM)OlFC# zCR%^MH;cy-5_|B!LoDeL(meSraJzkSfp1R6bsKH_uKH6mg42(9y{8*47P74Oz|DLN z9Sgq)qzs_(Rd1(_&&8uhq+Zb9zI{6pAhCge2J%36DH-Ov)C(+OYMqygW_wvtkBJLWMeR9lQ+3P3nEKeFW%;##U^rv-$+XH0KxUy+3C@u zOu|4|IQPsmvoAIEk-TK!+4@*G>%xbo2xo`dXpjU!*VpX&`=-4<%8d-s&8kSYrkt5p z50=SHe$%mqijk!eM#ow>Sn2naN8=U3G{h-VLhxxta8sSmkbt(1@{dw-N?=6y^*M`0 zz~O+z+@;&OUl#R`i-MLblb6OSP6vESp;_Wual*cH$1H7UfHIqH|EV+Aggz?2^a|JS z%t*^Hfd5S&dc&Wqp|e)9)dW-x9CY*k@I)Jp8N|{fp;tvwjRai{7`n7%UYY^PuUao@ z1q900pm=Et0CujeacgrkwWYh2EQ#&yzh^Eo{%_)!H@mVvzt`!MAE*3xS>E|u*5R)W z;N~P_oz+Ck@g_Zc)q9-Ks2_uDF6x66m*m|s9ViJtZ##bhwn?&m@~5wJq+Kn~{e9RX z>4)Pb$rux9I6>UK0v*uNeQdi|%%-BNF?-y99Ms05)Vmv-`-jGIl7L<5;k&N2gtrF8 zLaNE>IAwZkf@kpPw1(9Yq=5{FCH#(QuBn}B@tyBI-paWfbkfz^8y)$k;2ppB?5Dt< zmz&3+URT+S`ult+@B30vKs=gSzUkq|6_Hz7|2#i!o?_OLLYql6I)UQ*kIpJtN0!5b z)YgNghK9)(*BaWUEuu>F`6JX6|1DG@Z|0SdUz9=8k%^!nVJ>K=scy5y$=~~ECcHXY zQgnE>*3V-Z1*5zBh@Of1p|aXVGz2W^A#0HME)aaTLGiDl{6x?n0|STt9%#twSF$^~ zei)WN9*hY9*Cii%F?Vjur`ts3VOK7a(5UmR-wp#b`}t|jTEGGD)LN*mxo*9WQ|zmCdFPq!aYhQqFJ>^Fujs@!e+Xo>MlAuqG4 z`Plq%%FKx=h*XYOSKp`18~jx3-b?wD&WcP~w}u2K zwTFp?s!E(ef4@I(^2w1QwM%3Ny4f^rO=PBBJr1`xsBAl3kJ)PW`l;KgsdpO}>Lg=& zzLg{8xx=^g!I->5o**#CNEcu=GV>n9nVbuk#U)7@Y&+rGOHNB@cr7~D{;#Q6Hl}Mi_sLcm6s&V zej6>Cm2YWm6ncp%8MfP)^7?c2m^jhk(bNBTF_(k7_pW`5v(FQ^AWWxLwQ*#zi5M!8 zJA@0+9e=^8F^X5dKyIV7XMeC9`ZnD@EVvcq*SXQ(NgJFmZ*&MLSRScm`B6r|Bx|zBN>lZfRj*H+YJ<^9{Cz$Diiwq0Vp+fc<)Kj??oXq3|!% z|CaMMVfpx9nVLNR=$~(uNMUp!Ts4#BFy&?jlw3ayXuL2QPx9=%rL*X);89Gdh0Fij z=xZ6MlhGwSdcT)yap>oJ>o`Rf<0g9>V1v2t6$vTl-95ECkREMBvIT7 z#&^^KcKv1&O}^T&wTV5}v7NwH?6pXd;^=#a;d&aD;1`ItM^?Ic= zFWOK8S`!CtQwwM04917Iz}7rq`J~_v-q~-XFk`hrNb_}i<7ILFB$b{lE+)LQMbyer zdGpTETFqV!h^{G@arY$=3#y_8#`1;{DAIA3oWrUb`y@c54PtGoL%Krh?SV$gPeD(};Glk$A= z{H%95`Pu3{LcX}-#K|NHzq9Xy|5Us0fOpncNnj)syyRIUKE=eB9k^GCS{Wi8w}c-C zJ*|WPg+r*KcoIAubZ>sPd-I#AP)q@xcpr**G7Qnq7f{Ekb5Ev~5-?s~|9#%j zYKx|K{RaJR2L=~vxTwDJhCa$*%(SI>KQuM?V@-n_n0)ZQ3mK2?C1=RYdP6k1pQxf< z!@_66oNc|u9nR~5_wETS0WJCI?yX=;H#cW}m#8!aE*Mqz649m@9)gH^?>-0tTt+H1 zu8%F`p_DC}8IBenaVNN&noP)XO7Q8(`T+U^&$tDa;8X{zZns=5uhq7BcvFZ7I;5HR zfcx6bZfh>H*S)`wFv?vrZ);vFWOoLmENGkdj^w^mhTi14Dpi2-JJc=G1C9^OHe81= zuxh;i4G)d)x{sh@wRuO*Mh6k-h!Gnc=obo@|6?)Jg57c2^0gG7((>EDi723vP8V^= z4LZQLSj}hQN>Uj+o$aJ$vGMvFLAWJsQ9M20(b4}r@Hn~*dcYFxMFb0kEaNQ3BJB?=T2W&5uKGZ&ZX<&lCI8)J^U zT)R0kG6JU2eyi#0BarPIKB+J?14KPDJtyaU+2Zb}TJI$gam*s*Dn3z#NSDs4n%i2+ z1Wp(UhC$oC%gaAEHckMu@SxVG`Sb^&=wH@5*oS(S0woo8_8jOj4^CokHUABGm?Xf* zP&eaFxau=|wn3XM)8^h<`g`x*OQz?dF!J<9uHrJCu?u-JRzgt|w^&p=_fNwAfB+y) znioypx6A-i*?Nlga87?rIx;ZsekjNB%tgXUThpCVnE|#6gWBBBPe>OTQRKtU)f=TW zoe!MvtQbDhiw*qRFZSW()quZSL9UMPPd98ik-uHe7l2TxA0*E#an+dlj#~=24Ba}K zJC7q7whY|4Nq$-Re&wff{(DN+@b7T^7oHq>&m zD`;aJw77LL71#5UCL+W5Hvc8qukxr6UaCY$r4j@9!!tmjk)GeE8M%xiwFH*#D20`c zXXHimZ&Rii~21qFR1E%ou-!OP$F4Bk3UhhrfA`uXO ziL z77cpIF@PK=L5TmidOgCm(yFH>{MsHr$5xqc^y~t z-^Bu)^>&9cD(++2;gs<<)@VU z7Cr}4r<9~*o8r-WrykSkjL>$3J`Wn%FA3EUR)Fy)whMiQ8tp5t6DI>t>)Q4X7A}`{ z`~4pm;8p9)odo`-mceqoN7H`)`382&_h5eITHs92=U zUqA{p(1H@M#x`fT^AqT*fqsE_0L3Hu6!) zF!46<(TTGP2rO+7G0cjenZ70Ix%V)sYomp8zDj8VI0gw#vYA}-TyJa*IILpV69*)O55aSGoGG+aG%>W+r=Xof0-CKn9SqSGP^>4{gdetlT`QNm; z@i@8|;aEG@`RqMN1XY zQK5}py_>4HeSdfTacK@BPH2N;yfV-^e?vQe;O`3Pt9G-_54Hs>GEGdI607rND?f^W zr>^PcwKfkDQAI@i#~%O6<45${g(U;NeqIgb_rURZDVk)H;6XtR4mlDUpA;sb{_o)k zQP#DjfU!2?dP_4)debPco%{yz-Lw1qlo5HCO@yOIgeYRf6??OHUoK{=lO54NZ5Ylo zrka|pW--5exSr)RQ%U+v9QH-))!o2XO9;nbRC$Q;0S*i{%xXL(?;&)m47ftIDW*cT zMq4V;?o1DjwJ5&q`mI(8aNL`H-|0hzu;VB=G4mB*(DcXl`V5($#i02SfyCS;4z9i7~6*r4J%(@887+?QySqRHMc@ zCUT~0V?~RufBy=}jSScH8ck6di)}I84@p)j>n*LTY&~5UECSc^nw6yQ_UB4#31Ol+ z$16%;rK&yZYebHYW`cj?gGA8DjS4YW_Ol7_zKJ8q%6lLp%yLd++5#5#`q~@+)g%1Y z-Ptu}7GbC0O~QH5Y47s%>`{4!%j~(!`GJRa*38W?OFQqawSWV|Is96jo{3XN%{y^M zk6OE{@x~u6#E3@FN$zZ23of&#v|-b|LY!-x*rXV$SwW7|&?c(AX(!_?5K!j|W91o` zkt=|qaftbQGiIPe$sM-Kyx6WrbFcHmz)chZcuSa9IHgzd2fmOtFtpM;o|ys9@JP(9 z?11@(YeGUB(m^K&Gm3T2wdt5Q9z0J)5_A~7>BK%mLa9I6y)D6_78M9~mKG||U*HirFW?L$<{r5mZ$l_mi+ed~KY6z(-aWYxIom_(Zrf2t2ig$g8 zkIlwa=m*M#tc_E$oQ+cwy7u>fE{!c6hEIaT%Ni&0ul+MSqi|f;{dm}gY6#qwi#%83 z-Nm1qBxcTlZD5mdY0IBvT30)6)vhxZS4qb22gkIp`-^kFf~vn1_*RtvOgl?SX!>Ux zX*&=6rKUj}U{uFLib#CSNGCwv&!wY|*n9!8>)5eQRD^?D1c9R&$`hYr1bBVG+hYsd zUb8btcXtb_g!ZpZ(5ktkrEGB!s16#Y5Q2o9s-=VpptQhcpCA^H2On*ned3R{INW~m zv*NLH2K@jA0|F#S7H56({Q~Di`BOZr^=Q6x-Jc1d9RS&`r^(=JGv-b(Qt5@8-c9F6 zug>g5CXNnzf>XO(#s6m3Qe^NAwKQf$+tY0meBjc-e zoxh}r7Cx-}=!&;Q1s#pf)d$$WpU%q2$r&PgZDyEu7OIbP$W}EpnAh>77kNKsx+`&Q z?);LAe85vT@kTA`0&k003)VB=A({dQ4X9?)ZvBpuV#KM-K zdYK~7>_SKwUGzJ;U*(yMg)qr50kb6{#P>f41EZJOE7d$!>)Q{R04~Kj7WT!c#_9Sq zH@ESbjgihdzk|Q*EBiz_*Pg3BgM))V2Oi;{t;~enT-7DZVp7M&LnE$I80Qu&;%5U; zKY^p`_+0SD&O81y;@t5bp}eVZf9K~<5cyJr%dF}PeW#u9g9(yYufb5rYBj1Ou0k)9 zHE4+ynckull+HR^mk0qsNigUc2zEkHkTIi;sJ;?UG|5=4l4DduXf_-~mYB!xC zj)NfQ6-!tHQ{ZTR}U0*!>Ovo~9rS7JHL)%9I` zAu1Dv_;!0qPi0lyOSsp0@Pz2oip3}JNZJ6r+`mS5)$P&jXaEE$scZi#{YTT*5){_ zTO^cR?FQCaXZE?tiJ$GwIr}?4UJ;vq1ry#UoyBIz z5w~7?Ll?FFSE%3vG4}5ETc0`4jbGuHilW~r#fydtphL)Ap`XC$-QEw`E|JKNDO-2L zuNfKpe@vQsLapXRAU^0yTEty<9|RLh7@ai?A$v~*-^`Owjnhk7y8w! z9HPu0U0VK{gOcX)Yr@ItmV711sIRX-sI6RYnRScG1WnP-&b7Pt(%S z>@*SDqx;xu;`$y2z#o(2_p^dVhuOE<&Y@oivl|Xl=T5pW-I8;OD71$Ft1Tc5dQM5i z_Q=fs%vme{aMR_P`I@)pC2%BT+b{YYyxho!EM?YFW`L%;#ayC*LfJSaZ@8HMV&cDc z0;UdrP~?uaSQG|%LHc?#vNyDxp9L&liT_8(?m_q5cPO|D(*rUv?B=#(e0*Lp=EFY0;??TIhdfF?c`VH{;wP?cCunO8J9%+H;4@-S zZfI!u5*}VEB+Hiv2LB}t^X1+2>)h%8J@~8a0{v38AuJ^HU!^oK7X;hgx;qlQ7c!cb zr^sFWNB3ehJr?}2;#0Np1PuBQ9o%>S&dN`@RD(&R%RM6#Y2E)co%Awge3robXk}w# zjcpPYBuse}8XI>(#teFVwl-Td~sx;kXNtIS}!ABC<27u!_S_y+c1j?f1RM428%B8H83i zT{P?3vkVSvs&Jj6Il>?fOMh1118W~#GeFG6h z7M=uSJ|+HMlMoIhdeG9m=uAp~bzU93p3-<~<%mV8#tg4F3L8zr;#5!0<6-DUUs)RQ zYF4HH%J}<;mxkItH8y(V=Xu7>JvIw81wlTiMa$8;Kzf7j=#M{tJV0_m>)yU8;7Ura zvE0hu8uDyxxu}+3Rfm%`)j$A^KA#puU3@^Yi;j$HWTI9e46Vxm(NGfgQCR9SW4dd-?PoZK z<+IKhWe2GHRX6%%h|N4O&4%Q}_@(Pmkwi@Qd$5QOTh&X1Oc+2s{{s~hEH0mFsE_=s zrwuEuNmI$mOaH5q+{^|}c(d4Za+18y`qI)~Up$;2TX%!BF@=&D^|?=x&IVV2 zJTA#cve;2SMN&IUy>&`7p4|M)Cv8C5?d=71IV;ovfsG-Sl;blLE01QRqdmp`@YIz0UgkO6`dda@sNZ(TvSZ}+4@@0c`bf!)lu zbaL*&LFg_()P++o(M3@uVpMe#?}P3CJf9>Ihb%; zG2_1cUca4q>)|r{Rz0D%W=wMdpnLy`iY*mte`o@)31lRe={jITA~xcOWi^YfR&QGe z{JGV3x=}qeyj}S!aPjNq7qygzYF!=f&b$}?L#iz>f$>ahDKq9>5}L_i(lI??{fB*T z3bVJ9vlDoP^lr8MwTg8UzY;+wjbC5Qc*!Xpu$kpETl-NG3;bOrbaG4{XM*4_sN9lU z>|6fmS||5J<1QHVi3Y^JjF78+`Q*!r% z%h}kMm{icE5eHmaS9YiTF445xF+z}J2!W{lrt1hTH|{NZ!hO$a4TSaG`O;{_6XZXy7l-& ze2m!3^x;cII_1wEbFrzp=pj;>Q<#~T`&ehpAXK`LnHI)NXvn8dF4k2xt|Y03&o>@9 zWi)1;oy?rLMvje*#jps|M1JoAbQHc7v?UKBES~!` z6M|NXo$C5V?1YQFA&B-eYQ2X{qN<6B2Z!g|7VI)O)Nx#W?0(m&R3MGf z5CPX0Y4$go$QjNekPz-lr8jio5qbruQzJ{%!o*@!>QJW4r=t})@`tsCmRI)g?i`>jPJ0dYbihAb zm^-GtW@;>Fkup5?bFY4S(^r!Wslb2$8AAtDA-cWoRz;)ldt2Q>#teJhRLxi%OEz`~ zB*?PAx|h2$0|Fjbw&xvP>USbCUgGsrxK;|CBiJ*5y!<`r`ED~t0(pk-pm0MIf*}(E zwNiBVgC}&s>>-~*-^9bzz^j@FQTyHV^eGJ1xCpsiQ0cM#IbkSh`H~aCXU1)Mo`+K6 zj_`|Ix_-L@da@a4NWZ|!MkZM<6`3Wqfrjtzk{9f$im{YZPRW0mkM{M~6_r ziKs+}v0Z?c3!ovf26fZHyWe_%BhoR-#SfrEr!>$o~Cq5xDo> z;_P(pyv3}^C;Y+Jo!>FHPT$KPjkoP&v>krUd-cr8<>b%#&cZjsu-z|>>AZG!mLV5v zO5_0b2c`5i&lT{2v4y6JC`7A{G(V(nk41amC$hP#(^<#TaS2+by-qJAl5C^j-LM+_ z(OTv1cQ~@{Drs&pcd;E9$a{5OzDL?Ho|qVY69#A9da}TKYdURMMH}8&hWM1fk~zHy z3H^^NDIQAk*$hWcBmFCv97I-=(E3>p&Q4y07}}sikT{j)d^ml+DW9IP6-RJ-yEpSF zYs3_Q6mUq?HTv-PFdXnZSREX?S^Gh!#eaEYGUisxK`*fQ?8!6PwlsR2-UbTytH;3y zU-!n74JvC|)*1=~upT?Vfs|x+=0xZhs9~A{>fD!IKikhh$s@0(i=cei1Q07)y44H*J{5rLqJXS;;9q{yUhFQxN05IqKqTt5&nEVt$7^U(dV%Sf|c3Io#ZBBPkP zz*4P~o<_d5TCY^QnhCXm!{3R#`<~KxV8EAGra1jG7xG;73O$4hp)k^qEJ*Uu;8I5E z)H{ZJ`q&9;zz!PgLDa5LG2qgcl8{-FI~y&e+1I+}=Eg5Y!FJ}p`!`;)c%yoY;*7Qx%mspqL66!TTkUjS+C8{uD`t!wuie+z=A#)l!ctuN z*9{?0=`pR~!s$(Y5b`3|N%vu!Srv8BwPYYWpQGPhqrEKBW-z2*h%BBW@u3R+vC42L zi_`nKJ%!OvL^XjAX2x<}>&fFfEqA7z{aenGYsT=$KGy5QYJ{Qo;_+MwaFaU{`bwQkSg~NYTW8 z;z>u{HTrkQ2ismTEzaDk^kHzm$ChN(Nf0%bR3E3CqQ{uGiSY$2}xcqmv1?$pqnBrV9H9OmTx6mft)}>c0jMd%S2PaOEr+!_b ze1nY+@f`~7V0uEvrS!7;)NJnHNa>aA5p0IocwA0*vbR5*sAP9(*#!RT zBpa9NqIqBByGZDdpFfY5myfaooBFszxP?|=2<8jlG81#@o{=FS#0MH|V8`2t^_D>K z*EcDnG~#E3=v<`~9^jzDY|st}pV@8ZHG32vVh9)8!;(5`GKgIomf@Z%`wjCTQy(n)uKf{iXk7F>lrKSGFE{_l} z;8TRQE6w>AbG|ww-jjDf+DMbblAr;L2|fR80bT{4EaV(+*rw~BSHC)^?Hu0kUD6a7 z*Kvwdo!%=hpUy;uqrrEY4iv2h242$mDxv5q98Y9?B$c|<3UY|9uL`M!GfwJ5*$G{Y zc#u?SnB3A{?4;`amg89*`0icz`wy#E25;W7xI#?<6BryCn)4Ib&zS8>B-hY z7|E`pyG%+@ zL6;@ix5PO0{3=;kTYILSF*EU-sc`=$c4=`EKzq|5)XG!3C3u_tnvDC?^YvsDbB`js z(=gf8k9>WWf`neFhWC1V8Q1A~AJVx6IgkJJKiwvA%7BE?mBAeR>}+P*TG0<7p+S7$ zP?p5CCbz9tyg-q^Y`??pCn;}Pm2~WvcHNCrG&N&zNJ==IsR(crxFFw|iXiz(GglE* z43H@J_d-zoAc^tl5F{GSfMBzW$kdCZ=gj^6>p72w|28|pkfIJy;K*rbWXkJqF0*p+ zDSwWIKqb-N2#uW7wH`X+8k1L9{n!aXHWYsBR7*>97q&_h2y%5aF_A-_8$yO?WbEkII?tFp>NBrs+&aVRIW*#R43aGlPFTzX)(SFF zIN%yhI-40vRyhExtEz?;ZKF1MkCOwlE$rOT`In-z0Ld#S<6xWBvuEjdNCszP5O*H6 zYv!r>faKw-$9j`CM7x0ww7z~qpzp>TPi#$m4u>!^3&#F1f2pyy{DTOFoIpu z6l7;NH4S|@y|`1at!-j%&Ph!n(#T{jDlhLdg!eJ?S)F2C=v`XUDQY~^zUP1Hfc<#4 zw2t8Y<~GqghAz$BI{MVX2enLU{c}KSJq}!Q-Ml@1l4Wr|J$cV|sLlU0gT}kj&FGcY z!%t4{9&}lC^n(HZn%_=CdvWC(|CX6e=`q*?Dus5q$n%^08*trtYQ&iy@nwz`HyWKw zP6LP7b@d&*Q8q^q3OqwuVAsBkM|AqzkI!tK51l{r_$YSeLwK>< z2Rb#qSPazE)D-UwOhQY`SH9mV?hR^_51yadJwJ|nF__Z?@_ZhqBzOwQZ>JmwEq|cx z@Ap)=Z=b0vSf4aqTf+*h1%T|fwyw@+(`4QAh7St|T{-uT66}IH1QxG6XwEb&RKJpx z*wk;wOm)%SM;*!K+5!Iu?7n#r$q#u7Oi}U|RW=@dnHg_A(XQTQ37#i!G4CLw_#n~4y*LBmrh0>n#61?K z0_zI~aQtSVIo$TlR@4wP;c*yb#177d7OT!QRTQWJ6bvkoDdZ>JGH-s0Io>Do4EU%i z!kHCCE-|V+WEPDFCssj=Dr8$vEn=sh=qXJgIBKJ2Yp_wu8rrc>mUcm|ssA9=XTUyK zSy^^>5VkPCN*zHgEgftPJnpUHh^>7Q+TQL+6Ynq`q5t}|DMC{UUoEI9#;QOSQYC{( z_lmv&>tKW?Qjk$R26oWT z4V(W-=(jLt58SzA(d7ALtlGJ0bD|=6!?5jm+X5fdqy5yo@yqwZ4S{48p=h;qZ^@jX zQz;6^T|4X3k(p<=r{7<+o)%{!3%^S9fb1!m8SL|WB-GXCgsBk< z(Q?-B$Bhrk?)@0e_8i}trZuk)mYnLHtv3;PE-XbB{jRK32M)EIF3b#2OcYe_2-Z1Z zhaqjaUOf1|@XTfC3y}4l{a}&!Sx3P9T?XcL8(XLAUo>sqovp%?Owc&1C!O=Y-k6_e zQV-3Q2>=E2+Z&VMJo;HTlzmr%a~$tnQ(5V@v78Zfm@5DAlcTdNX9FKsgYIA)_97Qk zmQh^;zm?f|>MaZ5KKHFzxsWDXNaD5x*fbPM@=_ttr||w*Bo5dxE-yMw$3J4Cx9nAC zP#{)ba3%d8>-WMP0lD} zd(|UwI}t(|3uP33WYcCpqIW+_q#8)zd#JroWax_`QeeCCC_38z7v`W^zzyR zFo~oO@dP+n+0|$1I!q^dc>8E2bkV5Chh3#Gimh}a(2+&m855lX8wX%s2Rt}QDK^j2 z3!O63CMV}Djk+M8uV$5Icu;(-X{o95m#Wd;_gw!W2=csOk?({un04ue;(zEP6nM(C z8E>k`4=aNGJ#WgL|KkE=>6Bz%M|K%?8NCVjF11gu{g&RLpHX-Ff>_vh@y(5m*j!N8 z=O-@ryqfdcPCrc?_X1hX^wvfENA&0_=kQ-%v%R0?pJ(5_<-20KvSM3TCqdbHGo55xy198-kPOEPFin+*idq6iNi$}8 zx#WP;#So-iuc2tnoVSBe<+11Yh^F+m_(yWv>3Tgx{UVRK0o zje%z(6T*FBVeyGp#pzQq-%TISkfusTftlF2VT$3jc#7`+-?y}Zt65tC$3K6n;$!ol zDPYtZ65Nf$lSY2-V}dc|{GC(l$-pNU^lg8SQJ@Hd!I4T23Fm|1WXK>x@lTnf-^G6y zck2B{r$%1JA8mPIH6L0`Fwuom&@(;F?VALN5Pq5f5e|UIiUN_wxy<>_{J>s&&G_Ts zxfa@b+w{@QFb=vPt=_45?a@z8uieRDl9nO`0H0hf%s13&y}nkM;an_T@V=ckYT^k} zNkkn7(V$`dMTBtV_AQaABTSG2fEc=gK!|-`O|(q_@t=cP@_|4X_o)PLG#6PpQRC=i zV4(64h(`VeItT200gFs|c}|JD7oPtkKL8&Dv{(VyWP~BLYQAAx%%^L$M?JClOm-jI zc14kI>S3(W@4hx%jZLIYdFIRRDnMh%c;Wkmv9naa+KlNA{EoztR-PWpl1b5iiuM)+v8N8qJcmEq+(M#36hbWpqKIp2dzFJ5wJ zq^;bqh^-||rk(xPbt$wJ#i08YIFYZFzFK-;2gJPIqHPOBK5y1v0A&Ixe)qZyzToGM ziFp+*XR3ASekAPd>{|G|B?@ag&T~b#{P@%ve@DDqK&&3?fGQt>iJe^vd%wucJ*Dr{ zWMK9x#2}l;!}ff(6L2#4azN&7P@7@O{68VnR>LtdZk}CxRNuzF-QAn}lasKO0TbTb z=j@~*c_?tdeM!^NX}Ws^WL)oooZq*mE=_)bb2xoR*I7?n2@W5gncnez+U;DCfv-O9 z?Y;QC<#<2MSci=cu3jIV4^_p*GvZ)W5MG$z4DY>%Nq{ZYZPX>qrVbHDF$mZsaD#ysUMKsk#xPJF>s;J+`J%N^mQhcJp(X)+xI3%25d!()5~|>$?^s zpw=mp3Gq=reAQD)&CLH|k*k}o9}k6Q@<&U`x4CZCjB`i__y#!>BiJh{O5fekRPd6! zd)WJr31Lt%#aU*1UzB^P(4Ih7R#rOf3WG&CWihjO-xAu;hy!e{<0(g%XU@+krvgc{ zK7T4rA3Yk1`;(q@iJ*AF;N(kA;L+Z=`TYhwpnF=J+&@2=IULP0A5Wg1@xGB#AoQJ2 z?E1mt`{1!G0eno{n5Ungb>W=F)L2?t^7eVdH}Ra~4N_ra=fa29!F*O4$`agrg0zpRYo2;+zZyL^n!!U0 zK%5C(lwq_5u}tv=xj$dJRuxe6X=a?l&WWk#TYaf>7e3b3?k2nnSd5Y1JJls#+epZrS9X*e<8UOq$X zrNf76`wzxkHrI3O%A5B-hq6r7ihs~NEz3}Q5{`sXQAn#?fbgYvPmd+;u${`*y?ON4|f4K(y^_zsRchiY1_6Ee(kvO8h&z`YfRjH zYMWs>HnKmdOTsxQkok2hY3)gq7uLnbZ|U!HE}M>Kn#$k7h#PP|WEhSK$u=+pa+Wda zY-gOIYEPq)XkInGjRW7KpQc+I&$i5)4}KNN@8N5@XV2tZZ$yZ3=ZRkkL!ihI+96$9 zRPl-N!y-Lh98^@nN(T>m`(gYZ7**)S7bZ4RO>R5;o7lFK;Ireqrl(~rj>at7yf;;qoy&607K^gaXSc9#t=t0wL|CaY)%G_uE5FVT zi^faiDYMmj&k&2S`OfCI2Y;OiIY?6|)jX|4787{4- zvsj7iJ+GNGP#c&)<&;9Y*kVY3CQ=8E$kl>!3n&ZBlCoqJewb8u+lj9qJ3NYIekeTzc*$Bldh zpo;f>Ewpbe#;Jtm*E*p}=l;s@6FmlZ#L`PoKyH?{g4IfK)vPW4y zn-Y64d&|D#x|5@``}JB}EeVb22!Fs9PJW_K$&Ie(?5jFhXVE zY~}oLNOt@4>FDHB5eHT45IKHG%_H@b{bYF}6Md*O`{t%rci!-NNr$^6YxnT*?1*c_ zPHoNws?zI-Ohi<8f08o8|Lf@79$?S<__96tn|XdaVQ%Vw+E4o(O!HL=hViv@YfkJco@c zr>t54?-1w}P=5gNKDb3^>`rDCSc2Y+?KW@jr1!{3wTh$GPZgc@R?fy!e!poZ%*Wr~ zAIM%CLH+ehbTwN>;7IM8qN0$o)evsgR90q_<7E{+0wNl&O45?YQE^Q1K9hy!*sI{w zBPVQ=gCHH&P@>Todm!r?^f`}U)coJSKDW-$Oc`K9y;d7IHxf`HD|aZsRw*_DPo0!3 zMYHan@k-|ty4DbObg7)PNpw(m#r*Pu0M*o$X><8fisI`aMGLf_ih0g~fp^X)=Q8?u z`fNrHL60~{DUFN4NNdf)+!L`GPb7~T62gSPKZ6i(LYTQ8kxC*TR)kBgc4On;ku=Y;y2Lddr(8$A=Y%-Ukg;6c!e`w0oRe`hLF9y)gXFx8<^l97Fp} zCN@!<6_cCW(qb&&heA2u6cNMuEtOxsg_YUOm*X8g(ZT%FP0!EBlaXQ5l+tjy3T0-w zK6=o9ID*)u07X3*sATd~e<+tHg;LdDH~QW;XZEJHt9aFa6@fRMZ)?fu^Cj7N6uUjn zWl~9PEmq1DVl>bh{&eqy` zpsF%xJ=49?nzi%b8~YCL!6yGJ(ne|$z|whZ#9i43Ev$< zPO@@my#aPEg-5FvSCH`!_DE7Gka&bg=P?e)EJfe_%S8DXZ~N^x!1^LxK@%yvhGXJ~qJo4vO-etq$d)BgxE!5yJvtJkWRmOM_*_$dfw3P2IANO_0| zT@xd@1$fQjKy=Rot)$?q2Y6vJ@4~xWQPU1Pe@AO;!)s^8KXkD&DvRyw>uPIl6OGuG(yWHX>2mVIgIga zPynB_|A4ImK|q2)xU~veE@u3z-@Qwsq2?dJgBTyppZq?iALD2!RyPH65Tt14$4&?t;94QI9OhWIT1Hb_f*A+ui*F@kWNHm6J3=Z1uU0q$>kACI7Ba4W^kQUbk&QfQC#*3lNlTXp5VerHjhm));Y`n=r+JCojpc(oGe-93w6q{~ z**Lj-KgVNx@{6z4-P+zb;a6OewE-HBKjf>O?FEsudGWIj2psLZj6f#=nG6y1rrqZl zfs4(6gQCf+18jYOogLqjlWD4BGlv zOSu=$vC=dWnFw>sWr~EL(nQ!Y_51Wn6EPeqsET z`bn&kJuJPOFJH4i_L3rqCgYJB?qmJ0C`2@yY#N}5kT?Ar4gcPRAVdq(anx78hfQvk z#zYx0v^VWHH~OE4ve$cDPLfA_$)b1kZEsjP-vd&LK{%!l)+!V(r0@{rfqg-)HjAtt6KO zFUN7GMU8G8%qY}ZUDT) zjg&y@C!1;2jdm45>ZXhDlR$P8U{og+s*qMZq+yxB*hPg4$|Xdc688gEoi>{*(@@CkaqGWbX6@nSb-+_y>R-n0)6DLu8 zUO5%g+w*dvx82=mr|z$)h{oM<&lIFdHy!lrutM)f`gODbr=J(+&zXf5MX%yh5ZFT@ z(v02Bl5wAzt7>&$SGWB-bgl~C%nYNoof4oVVkfSV_3>nwdYR3~7|t$aK^y1Kie}}? z!&n{ex9~4Hd7P&*wU%D5PoVs5DQuIn^74xecD#Y?9W@$)&=&owyhD;2HVKd^jH-i% zIA4V+D2W6)AI2!fBfEaRaU(vgs>~U`r8!s6jrD#59_8sCxy<&b8rqKfUy8N)Xom8U zk`iJ95@BG94IMBQ(`bRhB7{+{A+d9rBOh}VSM?51qCGMezHN)X2R33VRznGsZlPCX zOYVj&2&HjJ64)bs!{CkX8I|GEp^8bS_~@xn!ysp6No=}fJJVH3K`Dv!%_XrCBwQ(e(1_pWK zLGJ%ANeXJ~gm`EyDPn*1sRjW&uQha4ZbT=OS-0KhUcVC*`nIgBvb6M;zrPciw*Ea_ zG^v>{{EnO3FqV#Gi*(n%y)w}hV`qwehEbHVaIv-DtiDI~(~|P?_U5qJK>d}KlarJA zBlky+W#WR#!WgwO`9DrFt9s0We?H>>x7}BqmU?Gm=}J{7>w873rP3Zx557okHY_YJ zDgS4j6VlSfz|8p~ub*$qKKiA6s=scm$-*#$tqFn-yLSeEmFz((ws*VXdRX**`|#vEHu)ZZB)zxpU{-=0L~N?e68z zC-TDOT}J*3Do9R0udGLqpu9z1e+punl0143_edhXy#aC*hgtpG4uw~4=*hnXs9@pG z_5cW8SOU{n56|n=9R2D<4N_5wIyvg$J(gkWvS0RnnluS&lu=SL6>DKqB_gyjd$Lpc zmV_^$pi*Ieqn=htX-~^bsh1AT)duma)vs-ob=+V0RUbGP5V~5QHnqLKoy+Xl{#mto z60}D9F81vX&<e6CKY)MtnxvEUJ|Wr> zeCi4tb*Wawix~i`Wl9xxqI3@v?p2LDuBOxMC0QK3lf)f1kNI?q8mzHS?__l=U|0f z&2066|H;hT`WcFcgiLzglz5-vuI))Zx3V25V+;a&MC`bQm)(oxLRUyVSBfw%@?M7_35p0DiG2M5 zmXv$pt1-{pJ;E_|RW+4#|lnNn2{yl13U!*}G=G4J75R z66FV0LyAK1)A)r54IU?Sku?wD%3(~hbuv6r9Y<@6Ns1vKyQ|+>^$dJ?qb>6^`1D!W(Nc>3V`b!tD9Jr?3J7WBc?nqbDQgJ{m7bZt5zq9l zH~Qq)=y0Lc%&RvaYsf!1ImK=|n=GO5vhOz#O`XVNmtVF5xsB+yA}Ru^B>#128KHTR z=GPSxv2D4XGB7CCju;jq7t!??-c9&=dX_OkpKocMzV)^EWZfB${=CmN2THaJLzl-& z-o)Hwo?AUTwrzI*he3YX#1Ob;dyZJ!95{M3cD;U^voje~$MGvXm^1Uo?sA;_OLU=y zfp&lj^{mhM*1`gAKy%V|%tSfJRyN~22_O6FS_2FWBz(gL#xnzot558gdmpMLvl1eT zLdvtC7U9WP7Msx|L0mM%qqtkhw!hbAB(pghEWlja2@`4IgQW5-!&{oGFHhm9No%GG zxMyN%;=Ln-c}pQ?T0g}P)1TShUz@8`3!O3A@pYel9<=LwR>=In6J+qO%mDDXv(jkd zT}d#?+Er9M_B8G&^!?fKQjYs&qAwVAEA5WTQOVkB0cq0$e!0NAXJi7(be_`+)nhBBTp|_irO+Hdj2M#hP?%j#uO6oFZMxLg&kkK4N(DYi zP?i|0w$&m!{C?fbP2plI(2{6Gc?}~p`OaOR;Pr)H|9og#AHXpmT4U=@) zKWu!gWxi?E2|w~mTcMhLwLkhL|JU2Lcu2jBi7o4vqA*d`MECze7>okuJV+ZPCJ7}F z8d=6Y1M^^dIrp*lkZ8Zx*eG|=yKe2%p15;MEs--GJJWYdJn#9uA6q_QL3AU|cZ1Mx z1O>rKjE55_uW`_)XTmrrapn(uBnWauy-DiEhA&RFzjw+$>R<}#miC=K_1xH{r@}Ke zHFd<6^fiH&08Rx@pT+^vWFAx|8iGX$b|3tKUnHkIF(knVty`%eFOh4pZ{Wdpceley zn%K=R$iS0zf21;P&g!^c=5E(-hVJ|{tE;X#!~OO-i#ys;@3X<&@WIy1kFvn!D`0yG z%~ji(Ol{9(aI&_(#f=VDAGUf+CZmgToSZD1-QC@r_($HYge=|Gpv}==OS`@<7aV8P zlV&_7=}JYMSy!#mp`rTw+Z!9rgEO%hJFs!Gj8!DW&Qa5DL?gs*waL3&KX!5CY}p;# z{qc0b!A3=ejn%A=MsA*LwL6{&CU!x}L2}X+CLy+4{I-^qN&dEj`tVo= z*7<8ic%B>Q8t4A9QGK9ykdd{)#CZK$WLD_!?nLFl*)qd`*_EPMFifuVn{wcQ&)}Z| zxBuqcW*w}>3g3Rh#Lve^K-{WFk~F%uumFMvt2)bH_r#r9X_;&$$Fl$ao%XpU6Qa@* z{SJPZ3gtpbgfXVDJV70UoFXiC6Pd=(#VE`O=m$rvk=nlR)HQqUoud8rArs4$=eU39 zD(4nj#=A`Iy`3lsBvANqCpeaO2?KZoWRo5!{_ zJ6kirW&P-?WR!)U2yCT2xiEjS?=oe2gO+P^#F5>^gy=9TgQhvTyMg)d4TOT&&xH~o zpAT<3Pe=jYZ|BBM9W>A&!L@TfAarHV=d#S4RxfQ;j&1$Ga)_Rh(L{OqUUj;wP24LK zVM8#B8pnC&@~Y8N=uO*bNA&pV0Y1bMK;He*AupY4ZW!iM7V@k@FEicYwB zpcuTS&->0ja^*(ZZ)D~5*bIkqvv!<%0_T>u7PHQM%L<;oss?DOn>&nq6YZFe;6JS@ za*TVk>GzWO3hZ9wNn@RV_EoTMq0cM1lucNNroGm~uavJ)h&O0x$iG{|+#Qh4T+}@- zT}siH~6;?`(U} zezj+wZxqRF*T;!5R(X18oTMXxAE&H}a|%m;LVTIFJ0-Pm<&Nk{&5na}p{(OY^9iO{kaqDVJYV;mN ztM0Yc$zbJ`uY}Ag+`LFo;1TSUp;FX8e~kk0C|cD)3iIb9Fcvb4b|S-I(e<%ObjlB@ zlB{YD2l|zC6VHtU+>JB(SjLD)w8M1jXh1EagFMpLch(RHoSHZAq7=S@ zKu0pZT(|6!$NG?3y|p4p>*c()?&mz%b45yMhI&2)wsekayysE$-#xk3L<;HBjc*16 zql1i<(W4mcQ1;fs@6ucQw&SgzerEk%aP7n@FP#`=+yUrb&*#=9xAzSgS-VFL*QQk^ zk-ED_iX?3;6fo{Z;ujmAF`S7+gx?v*$)i#%he=tBUst44dVm>w5@=gGJ8^abhgN+( zo`Oe5&g^NCPe_O-R@RA+W_RXg0s^N3Nf}};>oo=>;Ja(nq#>4bdKOOYDul|VRcYrI zb2!6Qm;)k~_t?W#K-a1(DHp{Qo-lMDT1f_M$)zrXj67chCndBJ1y4N1PZ3%hB7o%x zu^fa2DORj+DHZ6W7oWyeKZxU>YfBBC6|G-)QInN3kqcaFj03Nv(W)|lIv6eMIJ49F zQS|R1s~=3l>og9;>MYXC!j@f2T~Ztl2)y;wKk{X^=`&H$==I97R&W0_!)tIEgJz}) z25=M&F-I8ML0~$vUrtL?rUJTI1iS&@y7y^JQ5n~u8XiMLDg*^|NAF4b8=WA^qyTg)kI9vDeU7muN^KFykc^Fp4mt1SWF?a#Eh0){@60@VOpKUUUB;GYKb4(C3rs z^B~2rvR~7C6jZitKAQQHU1H!c#f!oiULjXAtY@l4N-I1oE7+r;hvWgjtSa3}8G*@d zJcRu!>v`&eaQ*heti>WNF4XE7tNQG>q@+w${4Si}ztc__0%`63^}vbi>M|89WMpx_ zYmLS!cCl^!%qT!C=gsB;!nS6{ArKq&e17WoP3Hk&3->v{&2~GdYwvyPIQiK4=xE~u znOJnBf7E_WwQOf{(TRP4pk@O#tbSl!wMo%fOel|=9$NnOBz3HAx$Q_v$d8_mH_s2q zn5{I_a7SZX{WYX^pVaI(xKYYOhCSA zd)7{-OGDwgz>IfZ(gZo94Y)VJX*g2!ew;; zWD}>e(%F;xd{}3=__ltcUpq>r?e4o$teu}Xi8gRyCH_R|Y_(gznfsiU%e3N%kXxnq zhDZ#V zjRpPK=7JO+v4kr~9s#7A#ADHy2h1;}n2prkTQ%C5?;mB{@44pE@tpg4XH5uPf&Z)B zo*VdcSKT954Bp_Hd%gwEtHP2|!FLYp>ZLJ&w89iJWa5+Q;$&Zp)d-{RU|YVeq7}}p(6ZFIp>dB-TDvi2d>%9 z(tge;gO+YxK!%bKjfNi)il;JG$R{&RIis}!lT2ELC!i%H5jCR?ldpdvZBC7CrR2I~ zZC>g5`DQG9nS3jt?E3%0D4!5|Nonc`%57U?m9m_i*1K-^+-i)^zw%C3PW+tswC|ng z5GyarfT34kQSq*{^e4XPEU!yhWyrhQ+U?Hs`)@KE;O}sa5HXCdZFD?c=#o3L*G9<^ zs4WDTBewlR?K}GMg|tgK9Ro>UKKhjvgiOqa*40%l3@@5_b4HIf-C12#*!6J!F7-8P za^tigD2hcZQ6KU?661;_KvT>ZAsbio_ecU!!Y^UC*6lz7n-8gQvq)U}1do0TlZdYL z9=o#&`tTq$3jCmwo&&gK#>9%pG>jC;Bo7bj{ch`_8$#B=KWmX{`*@1D`vvk%-B zFh{?0UVeuVJTR0Mk~D7Gr3beuWqHKq*WB|9I(;g5`a_w~jeuF1i`JQZXnF)30gL>! z2?T$_duz*}__=j}dMIB;WZ5Z z(7+`8#)DUY)D#43Gyb0s4>%OuweP-|P4>LK*vFcy51dIRZ3*dYgkKF9%UK?UKQcB% zW~xKt7Q`ObYZ@?6Z}!b$TsnYpMpP9uQlzix`uUT&b=}5idrX;G@IuvmLdQnP+jM%C zDkUDti?ozT7BHVFhn2R@|5?dAYExEG4Srh@c{h!P#BbU7=4-pUrCfjA$Mg@J$jR9r z08t=-;t)*@t25<6CZArAmGuQ4;zu>pz$<1YU%J2$6`ynSXo&bo2 zS9}66q81W}fV9K{V^!pTE9xgdY80QnKUEpZDZgBT_jY$bqO<8|A3Ql>X3MxA>3xm6 z;q&%>Fn05IR`9PMO`BPDOIAf?HrnVRvcsgblt^ky>g5q)e{b|*l!=|dr+KHHzkhMj zRw)%c-&U8w9d#^pCuCxt3OE@w;K$=S@@e7Kd3faEV%HxlTX;Nj+?{3mA46xTnvwHt zB;fw`pUGPj51xsSBaw&%2?+_fhEG_;1AQ$kW_sP1vW(Tx*``z=8f|^3WeiDR7V9@k zLbo2N$a1O&-edrrljvh7vV$(Hf%Lcs!Qz1v#84C_*dNboodN#TYdu)v?d><{+<1Qp zFulKP4@8jgB%%P^Qb@p%W?1TWAb_7Lod6Nhf>0|nN!>*V&LfZjxjrpDeL=Hl*M8aB zt(D$X`}@DPLZ<3x8PA8b-=8nEgHhqp6eEqYV$Net$S_OBY?R?UQMb6dn{O9ogUWE} z`{3XtLteXFx6u28TVST6V|O@l;M|o~{{W2Qp(Kj}CiRmrTv&sic;8>E>i)LAz2A)+ zi(4TXpN?xO8a+-3Cws9`m{OHrWVk$Oj$NB`**;{hAYXP&t2Xe=fM$*~5Mk9Na+$g$ zhg^kQreeB=5Hm(j1M^%xJ>%mydSHa4$7uljfG65rs&h;TbYpS1EDpB zfR?F%m=sBXX0_Y-w5LE!+*7~J(ed$Io#!$KXJ=yPn>IBc7L}SlY4z2UK=M3lxONGO z*k!6^j#SC8EX=nLoh!0mPgY}*ZTp*=n`ic)TWkyn;p{0Jcvo_WO8@2*h&`~|y@ReGcEeJUs9b()m3T;|@^tq#ugMN!d+8kBTF~kP>iG zo3T8~@xy+UGarOWBpFL27^1sI4H6+jXH?kDr>h&=wXO90te{!e5fB!?EElp-kbiFD z+lTR#duB#RB}KF~d0*v>M_D?i0P8~q~_LQVv z&)Qg0(Z7*pEZXoqDITkWh_)i@J1L`3!agshYB@Io0_w?64UCR_Q7pUh%SydW`J#lv zjA=Rrg+L^1W`FxTn)xxcZW&m{b$sW4tY?lK#k|MpX*r?@op4n;0iTP)D1yu6MA*^4 z5y=%ama-QDKNtAgQ6weBl;b70)ntEv_C=K3-IYCZ_4hV!x>=VAT>vAb9FA`F)&AR_ zLogWf-|G(tf5m%WARBcR4Ez(G^HEfw-yykx(A2;Lej{{bF3lvrOxXGG9=hbQn)&8~ za+}}iEjRhlIuxL@}iQs+z%LZ-4q?%0Qm)=6~m0B zNCO5~*5AKxWo7z$%Qx9xhej9y-#u@{ZVZgK-MaVp0Vek1&o{o+5>CgU1h-S9a< zx#`>Qof4tZ^q+@IFi<^bqpo(SXCw2Doh|3$*X%^Ax57M+fte<9Xr|Cb9Q9&>g?^+r_HZO$y1MU7O@ z6BJxc`d@BECidRALxBHXt#v>d3J6*h)$|J9XwE26D_PS29B289otQ)*^A5|y(Q1+U zH;%C*lS1OK>1{g}PI{o+fz61DNW*n2ym7dy)?bbjH&3(p~WCgQ=} zbW>;_MB|a#ZJe%Wz!N)p(_Lt=&u?Uxm|k&=KeNRZs`0t+<+l3aI~cdC)vW>LrdUSi zoM4r->ppR@{QpU#BN>t!09hb_Y}m6R36Up9!+0Wx_u{QC+PJ23wfje(L}%4(PpH*x zg!FbEM_Zs$CB>)l?=z{5XZ3U;6bPh$`>evZf7l5JZ08h}U@&P>Ia4y6c0 z8iiT6oyr(sWoW9|R^#{;QD zNXSisNkX4HElW2>z8)mXTpoCs<9N0CC2_u}sKk=!(tgH0&-?@8HbhVWd4bb#L!$x( z@mn}`RrO~9@T|2sU)w_22w|j}KtgK{Ej0#);!y_h!!==eX zia%j#ezrtJl+r=DIG|47GX3(!$WyxCgpVpwrUV(Mkd${*wIyL5o(qb~x?k5Azg$z7U91YR~#z68d*sMU<_x#gN-(e1{K2|&5U;w1?$AS7ND zdSyxU{bv=*b7LAO(CA5oY646WGP$QJDGxn6euLP`Bwa82_U2m9l+IWXr~XdGDwxPu zRV^12P5S)&7TMhKD7oZ5`yFnEQ9hW|AEzXd@Q?=P(Zu}P_rFNz2pbJJXEo?za-4p+ zuXbJN&Iecjn(FGoSyol00~L_16o$_#K;RDuNE<3VoFT0Z>0K|b5ql;lQeKNWOqZ64 zoeJt5@GJD&{lX&os#=b5$G#+je#>4Y1!{Opy6)>ZbNB1RASf5GI}Tbh zfQ(eLy<%2u7qZ^PK8dW9=axXi0+h9f1enid%Z@mGMTAL@2e78e$N=*olhx~~-JX2H zL~+#v0Y56e$B?D2fZ`P%6O+ObcyVXO|E(}os(`eEm=cT+$e-241j#IB$0{HH z#I`|BZ?enpK<-3bF)*NQediw=s}2g<`Rh2+ApD}G;NIlYfMx!r!CNxNw_bu>$A{M~MQ`l=7_ z75q+lab5!a6);`J0uksAGbWc7uMfChMrreDzHvUhv3^f#%Nh3G_VvDt$%U7Xo!Mb- zXC56u{RA*4V?%tDq#-&FtVv2V6;3$>OzVHq(@skMuBa1x#S{KVeK z1#7Gi8%y)__;-;ElRhJuYYquiW!I}7f-XjZlYkLAUikXs+z6kh7=$>&VSCTS?caRl3J2fVXT~(S73xD=$yyKQ5`mfIc29;vTnY_1JgE!Nt3pOH=Own?DP;PJqhE@5^YBSCH@ zX`GWUc%A-nJhx!8dw4uMc>Y&-1=5+xqC0t(d|vLoZ+kCMzKRE>l;k6(uJB16?={p? zaH{tH3ZNTuf2oDmZu?|7wXO7IaX$vwuN6j#axUJM72)p#!F(-1jA5H4mkKO0h}dx02-d=P7`z`qMw=g zsP5vkc!@`l-MqckrU0JgYsJLt*Q=`{q5&!{?bm$zRdzzcn>9z*GPc9#)+6y5_%#Rh zZzCh_ubb|NKAKE{nd3n`MMK=5pO$cuE^r-f(a&1w-UzMP9L-|y%rgf-yducis}68D z#Z@(28;v0|_IH8VP%H*}`)(sZ*}?Oq&@`0RM_Y>sbNE;6vIZ6~ zNH^LCXUhA>wq}chGTJRv;nbvT>DTAGnG~uX_kXpQp;F~%20%4ZL-)&LQOuv6*&$tWA_LaPOeCAZp-F)ZPtNSa^% zruVnEeQ*8#Yv4iOichbLF3wAAlR6=;&y6?-`5v#f`fXOIBfh+U_Tbpe(nqJt%_l3* znJo=Gs9w{&_rgDu`tSvPWX_u=IJ$&BzaCPo`jS3EHr05D z!Qxo2dL~mdOyWb=#ColE=oi#Md_^;pc<+@Ct)ma9EdpaNhgeFyeOtsE z_*n1svAbjz8qlP&%0`;e#iX{4B)jZ%uyfrujd%`8c8I0(zP`(i&U{pl+OgpMfDNsG zwdgiOxqW-&*B861O2$;Zyt}_3T(f<7tg*5C?fqlUjy@A1Ny_Xe%XQKB3cBI4y!epX zF4g~TO!t*J#W$yz+RaOxoKY{vJ=Q>ynwqLt%gD9rTUp05AM%Zwb$@m5aGMq_`Wl3M zep}Ra`uzo8o^2lCA987a>6y9DHjdag=4{sV2S;nww@M$ee{@^ZY3g)yrCDBCiXzUz z**+uFK@}F@JWh6G;rFkZL3c+l{PIkbINx4lIqm3_o6=ODf~?3GW3Q#}-@k7%WY;z(EE&!$t;e^maGMb@^t`FJ&4p zap))W3ks~OQO2eyVhyG~IJ>Ay=@Qy6&MZD5p|+%Tww~9G#d@`@BK}VPV}I7k{%fsP zHR+hxd20TeW<9ocogSgtK6g#iZk`4@64`{fA@Y#iW;u(i26JR=Ra@9W9XHz=5^uTl zfb>kiAeqA3-NH5R!SRq{K9aThaBFby*AGvGzP_J1SsBuARpSn3fw2ZUD&JlGR(GHK zX2H8lP450NqP~fXMrHQFb#PDzJukhWjM54Y`AccSpk?khvS|6$Yu8*fMZspeS0=n4 zyy)w#q&`b~egAN)WZ$V7n%wQro;?dVIXj$B8pGnPvOhV6HEY&=_Lkm@Di7!NntyNN z=4LLlp2qjLTHNq?c%ovxL(R+~@{vIScVikJX4QxNF+5<=_m3R!#rHpF_5SUz1FW=z zrO}0u4*ti33$qui?{Dfb%2Vka!X@zfdAdCM+HGv0lQuTvV`M>yrOHexNi{WbS)-?u zS9bO4Rg12_8H7EpsAL_)x_7Q0hqK>5)#-TJ*ltBmak~-wluna#pWoQlwDT0>6|#jDua8Y|T%q>ks5A{s zQMenVEsH&(j%^zqb);2;6&@{hhnWX9SRrd`y53t?Vsc|^my!$hdoOr%LSxZ+N|NG` zdfA1d_3PL7TW#_B-eC!67%r2)zrUr?^3@La?%fMMzo4LrdnXm~>b{R%BctUe zCJXlynofWJ^gyEw&7HV8pml2WedC+o%L{r>yPd|%XNT~6GY7lAyZGV7Ef>wBlVS7U zUujeIP1Cz?D^6=%u`@?iT=Hip?E~vdVlS6R=AJOt^{mV7HVbq&kjh(c*jEyf*hG9; zem@!K$)fkd1>e7ZOkU!BwaoQySgOLSk8N09&+@jZsJ6E*H3jatYjJ2X2IvT zdA%yq!%Ea+xFXHwJ`CZx_l-Vtk}tZkty^=)2?k2Dg7R=l{#dSLjJwU}0J&V=xV^9O z>V7j%zw4Llk}~<;p^3c-QU}IeNa}jF@@vq-g_S}3!eYzi1$IvjhSH*7zzCk_n z>MXzD)kLNk)cQhECuu}tj@bt9^H;{|y2n=UKU^(eELOZU>5k8xW~b+WOu!<5>?N9efbARL{eDMOGKxt<>{GO zr9IYMFk2dx*)?HMzgFkbx91jbLrIDvczo+$x8B}8c!yGH>D*ZAsB*L3D7P`` zGb~YK9_W8}Vw{ase-Po_V`*tcY}?dm3$sAtL*PNP!0UdeSe`2z+6>;>dC#xg$elLP zr4>cN$4{SjZMeCE^

    w2=3%$gG0R=0=PZS*@b zbF*{R_=Z>dzdWyz8yr};IdrH5Vv6U$YaaJ64fh_Q)8MCP23!sEt6 zY$s-HUsZQU`~xXjRz^64=$>z+!6U{ zWa;BG9GB;LI~EaQH!Bpc9vmw@bj_Z;UC`yOf5TOm3aeMKr^q%UrBC-OS=;OD-)F17 zmx4Z?I~(0zrYpA%$|yP6?eVSNApu+;QhrY1aI^0dt$V&hs+3`NxR;lM};#=SXCgmPu~^e){x+s><)~ zv8vTgmtPo{)?&9LIu4YSV zT0&`s+E3P5CnqGS>$`dW@)yoVmLnV!>T0opj1cfUCvZ&U$2&`F)t_ToEC1~m&5kj% zuC!8_+34REAV}r1{K(Xdj7)F2EV{E<;PCyUzgJe2_Wtx&U_wHImy`66xRP* zgJg^2MES89kI0mD35NB1f9uq{_oA}rH`MpzTl5E)WpUtxb>oOtwygr|dYS>e2xY4s z))ZSyeGaInWta#+7VOVTn|GP!0}4v2UN+;mkyXWOdoLs{W_^1d7yCaLB2c27=-ihtLL#ab9m5eR;-E1rQ(n_lCYwRN|NF5bl;GYjAL_N-d;g+ zHYZy<<+&Dzk8asuad&UI%}!%oB0T8A)ZJ}*>=ZIoOiawK{%dDEJnmq*Ia6KcYT_nK zJ22_S){iB3dw(umx{f2UZDy9s!f&4gPR-HDzP)Fti2DNKx&=+=_Vb7rw?qMro>xaD zf_bLMhXt&Wof^X%15O89-N$)xH~c8W$Nb9OS-?0+z|_? z+#Bm*8x!j-msnRrSF=E`xpG_SEX!J+%l_>Wr=0WqBa>6K=304VMp#?Z@gV7Dy%v1l zQT1(dNXR?h=>d7od0$MOCZj0=1R&L`?>aWFNZB`_EqRhCQKzAHM~O@%z7qFg6DLl*u)O}F*O_;%r)QPsB{)saPZ>a|uv#YNxSXtbb1GF4 ztb0UFG}RBRyRf77);9G{oHzk~X>Vt@ z6##lY!715Z;jQ)qHQD_Hx;Abym03`S`fdSJGO7={vhKg#Q0*D(kSddXAMsrfw57Mb*&s_D!@TRIgLo?A+`<9$Ap zc%3zG=bOYksQlVRkB#f|Xe5WsRnjOuGf@*m+*t_{ zJBL0WZb(T=vhLWiW1BX$@}p$>Q$?sq zr8wyFr(Z=@sq-3R-GxnpUV}?DH@3|sIfcExKg>WU=MaDdEc{%f;cLI|JN0I3&-q;m zYKA5toBpz=6v|$N6gztjbG6#R&PM6z-9I+7 zex@khBnCDOR$Szj-j|gXzne$V*F5sWO`E>Utfk*ZYcsQrzSO;$`H%DJ7ZjAi2dy@8 z78qh$FRpujety##$93#{gNE)g<>P>CqenmH()S2^sn2rz1*yz5mL>vuADVb=S^egf z*E*ghRfLlHChv&sdb@SEZgZbq-T2Edzi{NYx`eh)>Hi~4B-xP#hRavP2DcYE2m~X- zX;x{&c=4uf2KVXHXY}aNo}NZ2Ix7tF$7bB|8)$1{GOaK?(V=yN71_1ly3Pb)wi}+l z1vor)_x74O-oWP7{QzVoy}!R0Tyl4R>BAFFKi6<>Yin_EUuG}XqkjJlR7^^aH89zA zv+ZqFbtte)@wUw?b5H)0;@im5xzmKp#%Zh7_x;-OgOaxG+HG?PR8e*qA0!-6`}>mV ziuB2)h9&^w{;dn0jeNi+;_2_01uDD+F!9Np^ZGupvVPO9b#+ClXhO&xe{<(A`#Iyp zQSuTo@Mod9l^Z0gAyUe|k}Ph~qKXFvM6kpB`lr%@MIT?@ng8jPdAAu4sYups+*l*i zK}Up+z18JMoI_dy=eeF_O|e_O1qH{{hBm$u&%OU0_BH`jEbEArEF-xFj|bq+IQioD z$7kk?h~aMFyonsx>)YE4tdb}=zkMkyJy~L(R!4iJ3g-?;^%ezE(t3^u@v+~ooBU}1 zT|<@q6EGAwkM7=dNV}*zIe91b`ee>|ydAk#FdDhxzS8?1*I7b|Ao=a3QpjCjVer#K-wJpZ;lNR$5 zb6lFZyYb$tEylW{a8I27hTLLAqWBsAS|<#83a=7!A0wA`WnaAl4P6dNvNJrPzCdL?2w+$4^m~{j)h;R zveXo4b2?iDfTK=m66@S~_3%Vl!sNuMe;p_yL|b&3cG0DlB=z>u=??_?LTUOiq9mhU z)2`9eeq`yitA2kd8n^?HrmMD46s_*36Q#Sy=W2*0a6JAWOFEA)i;Jt9>q1_?oy~O> zN7yGYC10cBO*)_U+rEs)_=?63*mQZC%h{;r|pj%zP4$IPrR&zIF} zTC<)7KernaV&jju8AclErSUh=36sg*&3hPPnbAeMOpDUpWgesc5pOdxVSYr7S8}qw zWcW+0w7A^Tc=JP7Y(2Wo--T*^{KLN zz1Y7Aliu@jjJBLSh_2Ia8?0%yQJxWS>J#aJn?LjZ5nD-n9ull6(kmx6 zi!?$mTL9E#F^Krz3#uybQiKqCJDD0%3$)sBg~g?K;5S#BIXu}gxYyL1JK@R}+&mr< zDCwkHz-eHiE<;*%p5g^Ltds4xZBXl7H`6k^Zj^&lWcpG3?2QDc-LR-jYu4-j@%B)g zq|C0WmFjtpc<_2sQC7J*= zT9hWY-8iT<^|M)E@cYkM1(2Y?<-H&suWhAS6*GwL(0e*jysi86I0v<#Z7XGzOlo4Z z{1}fl<>t;m_MLpWq>g>mwAeJN+IH>g>~&Oq&T4M7{6~ezh2amr1}iu1Hp7yg%_eZCa5pN664ISJwGbyRC+6U!XI8VlNDHvmSGP8#k_~>CDqN_Y7^rTc*7PPk#CGg>O^#ij3H7A0QbEfFuj&K++Mwx+f_-hf zguT2?V5@7<*}$ZlS2Q-+>s`%(9vLDc)pO-QTVTQvSF5=JBjmMT*tTtZ`P#K>SFSAX zY;Dq~Rief=)iNhugfqe5M;pf)Y&0Ii{b*|{ik734@r@ccwjX&&W}uTv`R3u6a75it z8qe!whiId??t%ir8&-ZVT_mdEo)I6S0&RBk`045G(=M9rQp^f~&aN&_z3z|`zP>t~ z=b7l55Ng!uM;!LJ0N@pD=Ax?am#=W zH26}cDKEKO3Mcglx&lfN+$%t=r5e7gzjP zQjP(4y=SS%YDv-0#O;);9};tT$JHk;w*qBL3};dTnfO?0$UT zs#xQH?Q+WowI#7K>DyXB%Mx|QgE(`ile1swX5J$nO`W(heY@1)AfvZ)zUsb%j?K>6WLb9MHG>oK;@{!U(aw@F#@H zTf9yJH-@^|Fl;icUv7AxKIas+Lje*e_%VswfB{#I6)c?pa?ftRpvk$)6X9i(aza?1 z2go@r1n4Q~%KBE6RV1t2D_6d7-+Be9(|=jjcso~^wG}ays|&rha^=d$5hWc+cOPFr zn9Gev@{v^UZxx(xK}b$B_#a6po(TqI76Di=W(YqbzWd*{nd5bK?71azad9%~ z5O42U99IH#(`maD?y|t^C|#c@D*Fe0CrONsc##TPPUt$_A}}3-O1=jMc?|m>@9`8u zuO$FO`p=T-{DARs16npX z=vy~`sF&Be&6_uG*q}GnO}b>-5%nIQl@5(p$gD-dQpX1Heg)uJa_5ibv2Sy>5DLXZ zggrkb`N_wTV+03CXFX0yyRiyy¨ zh$Jx`o}9Pl(s*h{*RtzQ1Lbm3gDB|Gvnt4SW8-SuB-vF9PE%V{*U-i$o>qZ_r17zr z#;;5Kw`$6Am4m9xHE>Y-#(EMEho1qmu3Q}M?c3`u+5&I?k*bYSxXI{wHn*Qwl%A~> zb^ZGF^z?Mtk1y2lAQ%qOUP0-R9}BLPxvG5G@h(BbS@+P;&?4V|-E-r3L3OLld{Q~; zHu^q0Gb`U;>qxQU`rBWfermqS_M6&|bR2&%miq@)|AGs>f`{(Pvu&*<8H*6Y+uOHq zfBnXd8c{xWVI)s>+d``>bO}-m${J8W=C!l8U-<1^4iwV^_LItec8U7+@7rb&D{m31 z0h>Mf7C5QKjT=Aa=z_jx|1mrR=AjDc{oCWyUmndZIP+v>JF~#*ofjxg2+>>=iGT(q z72wD|1n)uHx=#P}>K+7rhkvH*2vx88P7i;20n8`661S9PoRg!|?z}wuUsd%MR{UCjRb&vRyh8Lgyu!*r~B_dYvxwSiD)QTM3W zC-3GtTRvCz9VVC$!LRrH$+?{$F!6uC;TEC}EJD3(aM}5hdM|*C`rQn)#Iw zV4J(n3uenbnFAp+ zUER;-C*83Z0Vnov$fivA(Ys`~dy{u$YHR+NQ}7uC=B(+U-Ob1sshe}1i|cyS{~_WT zT<4yVC6S63P;jr9!sqkqV~LjhMlXB@faR)>`xiyB&1b*8zb2C&1Q@a>Z~i)1Ok{d= zX8v4C0)#VCjuSz}q(#5DW<8D`IPiAUs2K@JQ;m?~;Wk@u7?2wd?B3dK=8TLEwzgdJ z0yqP-$5Ui82@lY|eS2V-=KsFtXNuSKI6AYSQqblf?~H)c`I}1eY~{!O*RKz9wwLNk zK*~bTu<8k$@Zt4?as=I)5^W678T;3PaRRf$o^}20FJr?PB1KIJgcG{u65=OP@>Tt4 z2y>5Z(96ZnM$+?FCjIZ5yVc|-!5Rf5BU5FT>k?Sk?x1?p#*Nfe=bBG~a}Zo-Szhl& z>XDQC++f>cApgi9z_`RspmL-s zgJI!`%VR~+#*QSyEs@`em0ChGz!#^1Vo8{%^jy^d463hz#BmDE*aVlRfaKPO#yO4mpA(qFMs3X38en-5nXVIC3>9>FM z86oD&u!(RFB0F20dAauwqCD!V$RW?JZJzt;uXoAIt#l=MWdex_ZXxrz&j0Ls^K7#X z9xd6el*#X(USU~4E&_v}3qddunXP)y_Y(W|jo5GXZQL5Go?k%;%iNP;t#s{LHdqnt zynqDr>eX)&UrzkaUsiecc->iYy!`R}WHeDN4clMD66BAXjmQJuzP?)$67KCE(;K~2 zPTdh}wz{8o>oL-}$!ib$PE|U%=SLrE6q4Lkm*po9sDJl{8FSIx+C6v?8WIZZ=8j_$ zw{5#-w)B46RN?SRo0gZ@Q=CN-%3#@Qi!LxNw*lSasBw(a15OUAUj>?gnryUxWG z4bOglQb#i7&fYsB&F+St1)$ltZEG!+WE0}0`o<=@cvncfI#ErXpDBj=9h(tJY!Nk$ zMtN#q3B36dNUA+Ph9+Dgg}1DwAakQJ1H?Jl=%?H;E3R0Gm!Nl?L+f~ti{l+U@*r&X zpZRp3JJH8tU2Ng;^h{`ngTB|zS_r{l82<+e8J@Y3@D!*sMwOqh(@`J-RxSonROL$v z*00|(RK-adVTg?)A``m9#$^nX*S2xic-7 zilsYc(qzRGC4w;UWn#waoMHibY^3;)Vh!w!P2kXVC2oz9)(h0KrBgCL%3(v484IvO zbUE>Ky)gA0nfLAq)nX++8TjyJ2)sw&r97IF@tif>ca_=U1z+9+>>lEpqnKQ}cR@k9 zYe!SVFIjnJbp&4rEgu`JWk^aZkkA(``dqXetO|3DvV~&;GK?qu{PFIX{&8mSa(k3w zuyH{$83L?Mnxw*7CXF{B);G30C-LbEhxQE!4Se}ZIPs!P=LfnLGz0X`M+3-bK=-#2%O)4ykT;?`~3 zgl5)B)pElCVIWf9mr0BC3w;+9Xs~+4VXguveu0<}6)rip`Lw{ecagnK4Q-@8?!tl; z0o~}LVX?bcygHm*Q-wzdSIzC#R%`3nSi8ZpT16SE?~_<&f?)Xv;_a`j$WuZqIx_u1 z*B(7i5vKHN);-Q)5;-8pOx&Qf=fVYoNuUR1z=3gn@o$Ouuc_U$#ey)Hee;*BQc)&} zIs%e_A|sO$m~_V7dsT4u?2#irwl%Qb9iDXKYkBF8ZQCBWdYxSuDG{t4g7gvdK#&68 zsIjaZE96X*RhO)LikMGE123;d^iul?_d`A7_{>eQq=hRk%jL0`%T7aJNQ59O?wmxX zkf-AAP#%CmIs5i}oi)XAW)9-08GC^%P{Tv8l|hbtB+)Npm$jbIs1L^RS}%uRkaWDL zY_`H-ECBIw(|VUb40X{+#uCqLb{0DuztxNPh<2!XX9_-+eI<@6Atk$LVvkR_(jYf{ z^k^%~%|?R1@Vde7h~nAGb>7=CRbTJIpu##}N43RI28Xx)$^-(KA!)FKa3u*-CwbsI zPFajDWBmLKB}KuXsePt#xmkh;bk|jvlGeE9ZSZzfC2d6~X^&5WQswo7W6P(d|3G4E ze$i6#(B9%aM{;r5oJ2evXBU1?&y4-MqLR`8MfWg}n3VLI3`X(d7i19ao(yA$DXoml zeC6_GkzMd!TCDE(C`uR>b2iFR^Vbw-H_!7c2_Ma)e`r7Q&{H^wpvR|Oq~{OLOC$uI zT-7mai^DRRe$GyOv{ETDo|d4mc8Ay*$7{kxP!}c`{ptnSFb_Wg)eTk!O&dqr*&n`GdAoj5ald}I6g58 zUqv-KQmkjit?ONx;Am;ox0TwDKqM+#l#zvtYvsCVkT-sK6AFD%H7<&Pg0rUAXXNm;4s)(`I3{X1LI0Qq5(UXG5b$#V zeVh>R&wX_2%I_7Kgd#I+MWZPvQPVIJH(%ZFf({1g^C3zvYuuE(hUA3Ii;6`JAu$y@ zd&_e|QWR^7gHcoRiz~7;;o3wjzD3v@Ff|0X=Q_(29xWx-tdp)#K};M}DGGd>P^{R2 zV$(7|x$cMU0K1?lEb2*#TkAvQ7z8|Ht&hZJr*OM%A@vDogeb%He_YVTK6b5ijd4E; zo82(nh+?Kh&|_whj9p!y0*3!&?7=v6NIg!2D(Q>6CZ1-%1mmPij*Vx za6xv51>~MkG}tTM2?FqH+cGs;h@tf)v1tlN748;exE?Sx9wq`@1pvAu2@+;WXugxh zC9lbX3O^WNY_Q8S1zMeL^#*5jsqYq1eLVLHut@dY9tD8wB2xfUxls=vK15PFGP9r; zasv|kU}0&PM!kOc&L1NLU8|LF0)KLidIjaeiez9(EVv)E|NE0w9qmuQJugf-_}G?O zq*C{e zbfm%uB<}NH2%Hij`DbKm!byx&V?&1wfkY87m6~S-uAoC|cZrF4Ah~a_)+f35CN|zA zT?|z35F691g}pwz%vEauTSoacXnXgMPz|L(^R}kCQJg>ugYj1twq8wt7~QZ(#i{+Y zi$;#r2bE=HmYig(;CSalz;c7WAW$rKw{dQq5r!mS*~ZjR=9uOrswmi* z>ua4b$lm|>0pdFz4+wlJ(P?P6aSr0-+;~G$Md-X#{+)Yzlz8X07<4SL##-Ys7{?sG z(<@@9fcRJ{g_QQ{=B^wNyP(CMCrp;x7DbC+<^8&hqDVM0b?A&4GX%=9_(^M6e9p?# zGk)t@is|YM3h?=&x5U({cWW0puhA1hb0M^X08#j(A5d~rr$DByT(ye-=HDBxkU1uN zh%E4{6Sf#}v%Ue4Iri`HL^7PSru$gfna@>i+O-RM_v8}Ey06%ZsMrI#Tw1Mnstb41 zT_*X{4{mkx#EIA`$4Y1vXcJwiyl`b~1|Gl>O*;5>25S;HbfUap60lz1-qR39Xu8&i ziM^{NJW(vYvpv?Ft6>3YRH=(mO2<(;3;*J6w;JoOvT{v`RtE_!;krp{_SKJbfG$ntbT+;Q(B~_ZDhgz5&IL3-ED{Y z_@rdcxOa#ET=N^szzT0W!DN`z>5@)pBYVVqC}FT+-mYK1eEG%=Z7rDfdHmh5_}HXL zd^{;5WMmK&GO)GC_eXlv0G)Z#>3=4jgE3SlBz)2It_tT>y_#}`&~CAC8V}LBKcQ}x zR(q}_6u?u+7;_(m-EFgDL4HynJ(^>tW;9%(?-Q)2zW+moMu6c8Wou2#(3*&IX$Y*6 zq#uT@2(aEwlnj9&SWGbG65%`))R21sS~i-r1ZAwZ68+IbG(70DwzF$nPq@RT!Buvrmt^ z>9-r3Y+VYX*x#ab)qZ=EGCf;wU z{EF)Zau+r#;q%uC>Og>tz3f*9pTAkLa#YX?4}E9NLEpGg`)G*-*f|njTP6jAip3Lj z+a@6D3Rz*xcahCaL@iI$>dhJ7JUU`3f3)8&0asHM!sYY=)UM5nFKndPTsx`Kao$R~ z{3XzR3m5jnirOb;g5!&dEQi+Z+6@E?s?1V-+L|tj%KWr(#OQc$t`Hp_+FyeAsC1et*XVfqE#wyW8Y!@W3Bp+N553{V0MU2>2wvm8M0~`~6`!i`V*psra9?d~G9Qv)bdW5OJj{R`~Z(hC;cAy?}XJEL8 zg9BkND42@?47VLE#7F4e7QK5{ohh$u9`aUqQt0;HM&G_yKFq>3YTmk43u%KBvqSd# z`#B9+e=+S^75huq>GJqT_EOXJ_3r#`TRSyi>F@C)8w`2V#UA!9v{ymi z>nhg*O@gM#B~)clG5^daoAI8Wxx~9g93SBXr|ZF>pj;=4>ig{|QINNYc3Vj?V%n(D zGdA=2b9Y0Ld3d44ot2?-Tj80B5h4wi2;nkfxhCJ(dIwyV=1mbUs(D-C7!|F}i+(HeM?NVzo zN|Dwa-&NRM;vC#BgRN*N3#UD<+w}V%D9g`oBLGz|vs20m-OubTDM!+7+Nry%Qgcuh>VqmJ zl2ip^gr{vxfsE?0&HuTyA4GQppL;-!M`)YS17P`jl%Brz$B2$;-Xv_-`X)9pltuk) zV+@7iO%ooh0kosX|yM2YqzBOj&_SpzHr+zZc zbqVSqnUX;dkF#YzSx^T$G5|d6l!Hd;z0&x+nO>AYh;L4nB1L_>Hm1@MSQNDHL_e&! zyA&2Ive;LNP+H1)pdue-s9%s|EJF3S;aR16lE66Qe5yS{_ilJ9ubwP%oI@VTU?WjPo|s z(J0jx1nXdxGL$z;_KJ0=skx329t3R)h-O6~1)-EW1f2Y^Nn)dK$6?-^qL4;=$&2)J zT~c8)C89YBM`#?^%s4o=)rJ9iWd=6EUzMRMGlSzaGfHrud3kyLi5vrdoOoyNFb-1> z`19H}#D-}ZwQZ;}8n_#~Cs~Lxg4{pc@Z%c<*#0&K@!iXSg_D-EX~^d zmz16!=kPq-%0>qK`bB0tQTXXIMjrkhYY*EzLo{X@X&yqXou!ucXn6=+%Ow%ZNYhaC z2NoA*?$i6boun(mkY0E#jtZz(k4u?D*@AV5Ie%+9ruYAng-GSR=vWv(lsOc&I46;GC3 zTidn8AyIgz)%^Kd%6iw2^%WM5Hu=eoEXU^j*r!bqqz*0rT} z@b>XhAU18=R>xM5HF8@U{rnA>A8Xrq*)(2t25C`F@}lmrWX z5<~8V2n~b_5a!`ShmssclcOfwYkKRbSPcB)3L#mI-aophtbNw?JU`As_&jNZn*Z@-mnnZ*Q*X`61wt7>dfL%xM+h_2pBZF2uh#F!8-JulJ z$S0o*sw&G7iPIGB7e$v156eYh%}@Tlb5)X@;2vcPGo%caMGpuC6PNkb`rSV7UXxSiH zao*(?pqR4pE6h(8Ur*OSUXN1Ow7Pbw%1{c2x;FX*7>Ew7(@pl2RxbVY%!9t|fnoV? zsr3dLB zQ(n0Dy8@iKmdH-S)>;Vsfd+jH7GD*3J9*P@-Xni{0lY5zmGJq5OT5w*y`*$9+vwX| z6kV($ySNl!8iD!{b#2C|ZfTTCQn@Xl>%4D!H62LsxO-V?zY?#u(Xqix$he||Eh%X% z0D8_ zb?2eLl8K`4kfX6{?lc0Mhx%>{)lSKrN5oF6-_n%Ac~~N1%9&znz&80!!kmY zXpI!7hD711ts+Jpn*mD_y{@JXB&zU@j5{9<0(tuEnGQrKAGds3aIQ#K+=6a2NQ!4| z+@#6crrq}8vGX$5_&X-(M^PI!QigU-%KQ}ByIs3gWE5|?V5ng+Ra-cdB+pOiv|t*q zRt?9-nYd$xI1C=AulFonJ;xqL{K1tI_h~T-G79U-0|z=aUKNu2ATww#e%UeeUuSOi zpEUp%pj6jQTmJDu#_r<2^Lc~|78Y(BbN&C3a);re&_+Q_iuDO#IXF7m+6qefxv%dx z@@(~Q(Vu8yFfQ)gy~eBiG5a9ZG*?IS@cpxEI0i%M&OeH+!Q1dfGKu!7a$xHXg5!-f zXmeOyz2?r1L^P04aZzYxC}`iqURtEPLU!J7RjgFfh*F3ypK@`<_b>Y1jz$^r;&>wZPD31q&;t|3_|3^KRc*^gh{4C^{blue?8V4q!IVwQLY)bSO29 zSpAfBaLa8|-_3KSCdpm=^H3k1nj!k0$V>p*u2cR*Ymxu0Tx#c{Nl~!4`3HWitOvOh zw$lw&%J!pceFQ4`o?z#=Sg%w85XemAC*fV)5J`POTXGgI8quO6`kA_b!-p8?XcE0& z;!NHK0YH+gdb_+gfP6`2SF5#7Dw?i+RKg7)y05R34xcLF$?W*d{+_UYl&|JBa&}rOxkalE2e_7i4(h34boM8F; z26c$Gj?Q+W8NK?r?w#jK9lPI2RkN;{7ub+A(MMzH1Ncd$wP)S3%&v`BO`JTruc7G8 zNm3Zv7}$87EB`*h(U#9KuqpHbYKs9SQ>SDIb2AZdHNCIAk5@gENg8&SR3#(HfGEmu z_HWL-38%oiy7E0#OIX}qe96LXa-rxz<|a`wn8M;?IT%Tq&UIfN8|+BM=VqYO=5P9% z@ha@txUma{6g*OWv(22s-#^88i9CnhO%TlWUEfMl;yqd-a`{{VW_$JY3({(Q_;o}@ zD59>nX)V&otk6)Pi`uNOzyTZAUr7ON9iMh*ujo`Wsa4P7!_{{C4QwP)4mDr6XvFvg zYjGUC<(X=6GL?Ear+}US&Fw>SMQb<+_>UpGR9ICYbdw_fbg4CL7J;yDvT@3|j1KME z!Hg|wXuUJkKHh`-k~T>24@2e276gZr6Rxa>JaCI3z(6DU;o1W|TsK>4XHI>qTH*2#_}Y-_ zz?7;<*LI~IsO6t|DoK820%@wCd{OzSf=KL{0JW{K#CY{4#T`^Ts`yw@7@!1-g4?eo z*qKJX&=%-tQWHwLda5lj{QG?m?u3Yih^`0qJpG?Hx|7PX_d*c_Jl$+R3PIPzU6Ng+ zZ~_ERixx|bb%z~NLv2lP3@0WG?0CkMZ_6sn?ExsAhx^6;)GJ4iJdp2uQ3zI@7p5wN zhA=~GsZC2n4Ny1+SQaoswS}4n-zwn|!nhBlK-@dm`rcR?kARlMpaFVFCSBhW!a$!$ za5z}9oxS}h*O`be%=8c+!6S)}9K?~`JwQIdK%2)4|34SEWvZ#WaMyKv7_1kVKC>W8 zcuQqcWCty=zvYK4G7*$R8hpc;8+y!Zb=M@( zGg!S<8xQ_WGK)#~zwj_84TBwFb%8q~A|Tqd>(HTtt*tquNK%Ado!fMjF&Qw|g8w%U z=#39jM+s?@CUQHFESO-JBc?=UFWSSF5eWpk^Ii!eUiZI5y9qQZ zS8?sCAQOgC>*4S(pe+m;+XjD0{-1sn_;tO_0=4GMNpa^~8vcxRaq0*(Rjhu$5@@i> zFNqD_%5B{}UYz&1pOJ3j5p}e2T{o&~n`l8NeL(&_1^@w^0vT6c+7iOzFP}PybQ?Y7o@Qijjk5rJ};{LMwhZbMr6OB zTo)?wz_^iF3&IikjNd)qHWOdj$kX#eT&=1uG_UN027`EP=Gp3h(n2A`&6JF(*)F?D zJT0UtZH+)-^soI72R2lE9s+r7n{JP0--0|K+Urws%Ja&MP3*|NqUfI>)FqHmAKRGF z);}*KMAkv@7O4q?#u?~>x7*+eJTLKz+#$QbjMbOMQx(45);1NVgLxn}$GFVKwD!V| zF@ItvH9khZqiXfuVRiB=I1@Rmo8CpX6FwQKiL>a3{1wC`8m>iZtg1t`b)9h?qG^V; zGJj@yN-s-(q zTksYsSM=M(Hh3GJ9R~JdSy|tL1))f6g~!}Amdcfx!)>31TluK`ny$Kp98z@5k&QCB z>C&IsBM{tz`C+Gk`^qw2mgBJ~dMFJ&q6Hbl*|yG8bwS5J$SNw*Osa*vvcg5zen1T7 zN>sv!?DIYN1QV^f>%2}h3yOv>0~<`{%heIU5Bl4SQQD~I9%DBV7R*`CvL}beG|5>UlIE4}0X5;#M2u7tMigJp|brIlKy%m8d##FV1DoVh! zL`_I;(Fa>p+C-)$*iXqeo|fkLflNt;rBVBM3TC#F$nB2ffg8Tp1rRoZUy=gjMPj zfpWvCrEkkwAFME%Rx%Vex~uv^8xt2rF_E1h2w`QYAT<7$GsSiHzDgbu6VhURVaq5Z zJ$@jQe%1VH4SLr%iIN{H07XN>Pkj4TbZvu|K;6j%ObD6ankfqM;j~T!Na!hgrD@9& z#TkgkmtIOr$sCv6ysQZTv>Gl;x>B7%i6Z8S@QkN*$u@Zt6g7&%~W(1koW}P=pq?N0?Jr>?z`gyTZC_}Xgj`=IUPjI}#cW&CWi8in= zgBN`r%3K`ldYXr{?9YK#HV;JYC1}lK#M8XQT6X}-KT%omBp|Ve?J&>@07;qt-{);U zt0tr}jIz|wRN7sXq5rXZFmBp}u7lT!e?9-N5bwD>bOw|Gtwb+ae>i`d2`5ph$aYKHw
    78Bu>!%(4NAPkIeMu@a$naDJKjP_SDO&&jNf1w! z?Yc=RB*b*d0eodRQTt9Df6%vOgFb>Fd&&zSPi*#R>BtzQCDqLQzkN3_Y)fI?Yox&H3 z%4*cHH_V>6dinD4SBI_@`cR+W2UgKh(-|tv(uiCI#uRL_ezlUIYziR{ubeMN-{JPF zZ{_-#_Iv)c#H47pFssABS*OCg{e^oGp%?IIN|u2p2kLet?TGFX;+%UXWiNF|HIOi8 zTnIXtJ6Kf{PGb5m*e}V(TE7rZ<=hp)7XeB{6$EzWaohMHtojM7eUhVSjf1rUOSClw za@VM?q&0&&TQG!0OSnFyaC^_?5 z#ntN42$)W&Ko#kDyik`pQ}55!YVLn>wr${VOsvF5)WYW{xbP9tufNQ;Rh{hGKg2hu zpT(4q!kbT8z%U?A>YKAwl|oCNPb+4exVwQQ8Dm`?cY}HoW|LKyq!B`3f;ta`w$fPY z`^P|JJ12k}jU<5E2M5OKNr{$yme%a^(UMN!%j;~S*KtEKf4jHd+pv*9>1~|I&Z5$C z9ylml$X>FvnzqkqUOB^`qg5W`=O%AM@F9Ahfs!F++-cnI^(~$8v~`SbNXbzQl~RGY z2mPLpdkbIV8tl=y|CYY|$z)6hUOGFWsJqig&Gtb%UUMmEa5*n;|Ipn=|B@UumeR+h zC}A(6lM^?81gr>T>I>YjgtWUt`~aBY^>#DN2-9i>Fas0CJ%XW}m0L97Kaz=8DtKFT zToFR405NJYBy@g?f&}bFiN6$n!8+#O78BCj{6`qP2VP56@Um^9zrlP#T}*p$w1dxD zGUqepHs_EhNG?|4Pvh+aPNFLDMc|4_lP9B%y2-;Si6~3O`OSuEZ4r&V%gc5cSRGV3 zKXLB48cnjN&dN;?s$&RNW0%TqN9yc2D+7gp9rY<+j4Ylt=lmO*EIymYNED$sa?i|IecTY#f#|M4e=X;#eMLfLtdKvd5K zNl+q)T9RHKjGlK1;{TK!BnS9(65kD_OPS~dZ}z!tN7ZRo9zYgBhcFM!kTEHbdPI#L z$$UY088^0oUu&EChH!EqO7(pzfkurQ;c-fXSUC1@7F2WYVyvk> z-(PO=4?OjQ{DvYB8Xo1%FnM@ltu|tgB>l%^*6|1bLeHvI*Gxjl6Z)0Z-QwN6(2a1XgHQxh;82f5P(fus!(PbJERNnFp0Z=x=8Gdy7s8iX1=sI^M@dZOr`-5wy zXNt=We|wkXMg~*w3up=&gL*}@UuuWsKbR&Q9=`9gx+d;8#l?)U(a>Yee#3t9l@VR8 z&|WlKr48MkOZygew*H+K+LUko&*+{1nH^^S)IL;6UIn6(!mnChZe-NF*J*+Z)##vl z&YISP6ThLLFu_EOQY()Xtt5@zvuiV7*;#-0gxMn)1c;O@CW!v%=bf`y zbg zu4tntGn01V}GosEYoWOOY)AS+ZRy;k| zgy#AQLt?M;hoO+=htyhEI|?Up&xPd|BPwwMd$w%geHC^Tu4Mu|7djv@>M`O9H%iFb zchZJja4F|=K$+b;cAQC59=>l;KncnLrivj{gjc%z=pot1STxQj@~EcTETFdUgue&k zLC>va14g0c5i0S<(aqKkmQVO{X_*ww08du5LGraqH5J)vGIO{gX^Bv1VQXFAUuJ%8 z&Bc^Mx?VlWAL{#LLO%Z!>OXq==72f(xZK(<4Q9Wp&_zcNA1)fzxiJwGMq=_RwCX>D z<+^?$qUo3u4`rkzBcJm-1xpO;b{(RdB7`tnjyx$Qv2o2_2$vyvLHKc)Fv_4!fA)%I z3~qqe^lJEOho4D@aJ*X&{)xdw^pjAIF}nAN8YV)VZwL(Tg_zz9>Oyi9L-r)?vhO8j z&cI)Zt6mFc1&&#q*;UIF<+> z%y^u49J>AfCuZ?OP|;YP75Q95&jiO-42z?O0~6>2sw%QBQGBlGJ9v>lk!&LDqKup2 zEum)ctKH(`_!A_*S2LNEMz>l|8e;h|T_#57(j&o(!+U-K5U$2xLaOqXyBol`Vp|#xc0I@m;Sp%zJj5;ezbAL+Azabd(xl_)1x#1+3(^_OoJ)a&anE)m!E&J*o0`J^ z9mftt<7ZbDor>Z?anm$oM$eB6&GW!H9EY+L(|KI;b}0}B7;}R~@Yfx^A~_gha6s?M zp}B@}KfM6&*3ywYi-Npb*~vZO+rBHNaJCk+Twvo?p^S{3xi^WD4~DU@F_zqe;|I$-E@RwnoxLSS$s~t z45q(L311D}C)yG~*Nq{F%7c{W;sg-pegf^ z_>IHD0Tn)Ck?!~Ti&R0FY({fB%RiGq#kcP}{$wSw61cR8SV_!S7JA*x3GW`BtOz1{ z6aQcxpQV|fIO7RiU*Ydub%_#^PCXcNitR%ET1J*;3@KSsqYk7Ol>^<)b<%1Uluwo9 zI|-Gdnq076{lpFA!B24iTEuhUPZ;lHoHe49w;doXD5Gz(7q_5g117zQNlzcS!E4N& ze&@jB_z>eK^f|c04^R5lx!I36-J;sbWJ#A}gB4`KDU7><{BG(n9$EUMZ;%M$lYe6> z1D69As~bS9t{%3X`z|?5V%7?Avgm0-Zp+A&Wb1mFXJiT!2mL{n2*VYkgYAUmtzIvf`CmOKAas?n%p)h-m=Fv&^uG;SBh z3*xXtW)of6tv37T<9T6|sr$fL^AnFTWrsicjR=4d>=W~ve)KSKFt8BsN=ZrK3s`nB zTR;phpoIh+M590Uk026*BA@8naZJ`}CIpDRBbpRiI;lhgC&ujPy-4`=lyYhOUqnS_ z5A~}29H{XJ8`DtMlUML+tJtt%sc2RuW?xf!Ga7Zh`YUJq1TK^v;m;F*a0n#dIiDwy8;M>1 zetut(xO=|4*igQQdC&*2I^rN@eu`kcZ&h<~f>F{kzDLnJGLIksOb6tM>dw!Z8Pr~_ zqqD30306$V>Kj;hS_Y%cR`0V8~U&5V|Vuy~hL(`wNX=xm}jd!xB|uG9KVr04e_NFkkpt8?LD z(GBu{Xr6DG^{q7#{p1D{=D99J*5@*U8PC^NhF+PlK6FN$m^6yJ@|M=k9y^b$EdEvp zk`@hIx1a#$Gx|w`n1e!>tnj2+Z6|+c2d5h=X2Jx=FF;KKwF{lmom8UG1LKG(5*VDb zU3$ZJh`-W7&lu6W28cy-TqL?P)@9+S`i{aSfb?}_^qYu2Gs&XzG z5dcgK6mN_D@IPbhZ_fNR0?g?~)g_TV0RPh(PftoCBsQxRGPA(9y~VU2F&UFkg#&=3 z8I`Fnj}*|jhHSP@Mi-4GPGX!qB5``P5|d5KT+=}G80c!E5ewspZxGtwh~dM3&+Nt5 z5yGsKGJnVVq+A*LrrJ4soGB#qsMfbthAu2*0jXdfQwG^aM@{>SLKDVYObkJxWNfD+ z6BKh>AzU!_0;YpFdu+s5nsQ)fx8DlSXjLXxuOkNLa)5C z|E`+^wu3}9AoEe}z`zxp6@RA%3{RciJJC$}TNbLhODqy}`dL70JtR!K zS}~&NEw2AE?NWl2`@Qy^6=rCi2i6SK5YN^_Z|-LYeIw( zjR=&gDw3Bf%R|VJe8NGs6bDGJG6TWmkw?H}ZGE>UI{NkB(9a!9ejjc2RRqPoxuTR- zj3xej;J^Wn^m2EeDb6Y@;mUA?nGffPwe^XzWi5~<{fciIWx#2!KfuTsgo9%DcY3*= z>_t^8$Y=Hbcwb(Az}>QSfINbs*RP)1UjV zb!n4Aoy-W_>kVRvllL$9DF}3ULofY{IHVVuq1-$+rOc0Yu)xfe+;P3+}aQgf^8NL1S z2nSXyU8q$_Za-x|NoPu>6$2pLS`l=d7IlCO_y00pTokJ@b81ByEcn)`@8^TFarjW@ z;eDK}k$RPxa~_I80z-Vnd7TCZ*|P2K9mo+NeH8}-{-mc7Bv9lOy7~$QEG^>ifM>dz zdKvsWzE6wZm$$;;u8d}fzTD;{G+5neg*)SE61JJiSwv_O+YDYlL5sCCDdtIRh=3Xd zsz`}PeG;VbjkrSTCT%~AgewDAV!%L4fMTRh6H#H}pOC)^c_Ov!z=qT&l&o~K$M8Fn zZ2^2(={#IQi~+B@%;E5Utoub7I6oki8)pP zMuF;y98jzR&2p}(z2`ohWS1gIi>-1dLn zEw`3ej`4LDQq6!j6D1^O)0EQMJIXGWj)oD>x>wM;z65=kvu*bK>c|;abYrr+u0P^L zi7A_udopl-YhMw*!f>bDTbU=SsS`w4#&n^3XrtwyuC`dqZRXs1vePyFaKEru*L+96{c5sB%B;Em=KUr%U&mwlS{v&@ z{(F5Qqblj0RmFwnG4`iQu1?M@HZxmLIP<=o<1zdIPKD0F5cb3SAANTr3(j5;YLCE6!T=;$3vG*T7gm-OWn;UMLSDG|r9aL)zuR>p6Utp{;)N!Sy!HNsN z{DN8zNy)anvN_1RzrDI`Rcz_fv6gD(;B`6O@|+3vc7wf}*&0TTwVYG$-g1?pQ+CFP zdess1qO?wghnVQ-GvQ#kB69OUq!Bb{PBl%>xN+kY&|8V^LWo*@w)CDqYwp}Pd<7g~ z&^lEuV&zH1cJcP@la_uF$%Fa`u>oP!mtTCbkCF-4YOnvk4gBu#?2LWsPbwAVeFifzX63#xtH|POkD zW7pZ8!ODNl`SKY(%*>vhbvC_n%&8z^WbRJ;6;1`IVbEe2Ok42pBivMG&wl6ULq*{1 zx!G=TL|?5+=p^bh2;BD+F$@}{hG9>*&L~r9Gh=j9^_?kQvl`oY(3|kCm|tftL`GO* zSfZkJ!8Cf1MvWS6W5LnJ0?!V=TNJuFq(rpOHRRp%*;MjebDd4q$`tc-Z}U*DJzWMB z(&56#=4#v^pAy$bnzwa!M!(-T$$2ad#@0=#zjWVdXR@G+SD~}%s0};n$^;GuRt?q4 z1CO$YQSL5jc-|>8GP10!ETV;nk${(krl_bW!my9VfC05188oo9%`GWurPJ4d5}_NX z9G(vDtO(95F6%S5*EaG_^_w@*F)_8GQp50_Z!6Bzg_st9mtWWgs${^shah6uTiHJ*ubksN&z;;r#~ zKZ`u)p@s3G&CGUm_9|4kud^fi+GsN>r)Em^AeAG6yuFn@FcS?O)u3U+MIf*3hj06{ zs;Z&C(&paO%zzNEtie^fJ89rha2_@1Ph0pwxsGB4X~Qj zuw~KFxSLM^JC^U3+_})Td&N4t#owiRZU~*@oSh+#Vhh};*+@@(Ru2y&zi%z`WpM}+ zAQA!l87vjlYOhIV?c25$u|FkZdRm&YVZ-6WhnL_{NnT+9`e}q)>BkgEJv+Oz=g(t4 z8>^beb`Zko`TTsax3eWB+o!L#P?RP~OGiB$2<5t9K`+0f&;*o8pMa#{=?qqeCBk&| zL7Pq$uypCt9rH}{yv@(?wyjTc%_)99Kww}Q^^k6Gxmua^g};9hloh=TnQ||(gN_@S zf(lENivTTkp)MgaY6kiPtC{ zKB6xf0$sG|Q*v@L^^t(gaHz@gxgY_=>bx>{kE~YN8PgeQLm6(Q3#jrs7aV7g0EH0u z{T@$s)CPZl{@x=BVOOu|$AVy%1;V4)LAPlc^1FpxWOYurLfeAQy(~u;v5LpI4=N2O z;u$HGTj+fkoqyxTjcL4R=L-c}{@{Uq3Vhixjpi+cCPa-iR`zvm>{_?Zc|2p@$=@g^ zxUe^F_P`gJ$cyr;8@ryR}6ao6k}Yf0)!OuhSb)}lp=Mr}C5(!_OZ*Q#2zI?X0e z^#zU?fwonP7BDT1V)A_Wx#{VbzeUw=Y)d7!J*Gj+Cjg3sO4L^;C1bgIjZnUzrWUmg z6%tEXGs6;r0|ET#i-vKiWP4%b#v{J^>W>$56nwt7Z{9F%J?wvu0}xRJyM?&Td-v|; zRH|)^?s0qo)wtdJsTQb}nl*3kIJgnEhGiC4j-`gBhIP)j8;lO=%dGoTHx|@>o!h-H zP!|V_S-rg6+@xU>fEGD+203zargUu)FtiZ&)LxuNau2FHi7E~M0F5JdtzNx)Arn(= z+O(NDS|`~Y#vgWc%%1aN9F-(A)5afuID=egPhqo`E${1#UzsWE+_{n2nL6@$4mm+4 zf83lJW@&uTTNABXHdYZu^zQ^K1AH_G9Gj`E_Je&rJe${u^?JkcI!;X z`+EDi$1_MJKI`l_b5T(W-p|H@wu2kl=63kkC1(l3#Vc1YI1(YPqxFMy*y8(BTFb$Ab1*xs3Cm zaT81w&m%f@3`-qcU1x~z*sn)e{Z#-D3(ORrSxk1?wsB(-mjmbc#%e5Dd&+vWkbLqm zh$+7UJ0f`#UAH{tumM8-4y^Kxw|B7R0FE4Uq_=*aFg&Yqp0l~ z2pzl^UcgozIyDpOqmW218&mk!FJHclrid^%|C^vl_!Rv-NDL|FnMS#zvd58}TGwW7 zMM?7|muPHe@s4?@5RwuTe+5B?{!ppSJ(+AM0P%y^o%iwm+|fllIv+MNGLmJ$ED-LU0_QB?bKl8hQj``VY7Q7l-#Fm@Y^++}i+PPNfZq;dZR!s61low_r=)NiG+4 zG`4eN^(>Q)WROenagG?5MnHLUbD)MN^j5?6yd+^C2cQ&E6b)jJtyicrV`F3C zs8(Rm5_R!&xOo=CB4RO)wLrkKPdk?ZBDnRzE8uCRl_pmp1}Dd54xNU>O~WoW2y zFPiyN(U!@aH8^{rZSu;ZV$Ql=riSAFk?zms=g)%Lr7;?|r!n3MMEu@troiz7sOm;x zA@fa4U&({b%F5zE%dz9KFP@}QTP|CSX{(2}PHJT~KA^=J3`~H8N9SSCXeN#(I z8E~)S9dN_QVTeUCKfWvZ)UIt?b}}Ad+6{2S#Y<2)it+oXedf)ZH*VYmXu_MI0UEQEdo zp%j>g6~ICn@VBJo;81+Tb^r0>$Ffr#PK|s!E+hnQJI`|Enl(SArENm02i5L^=73*4 zpNoZPhU$N)mskA;4P>beOxhbdNK;Ga*6rH0b8`9-WQd5_rGxk8sgXUlK3AX^P?;@o zm-)isNp3D3I_&39a27L2k9BQI7fRah-d&X1u>r`uXyd_od$n$jCv1*0GvDG+GmqNg z{?vgUSxxhtwW@V?q8mY=69i95<8XiKYznx*z{Jz17xAl$4~I3jvNCPhu;LzFhwPSs z(Y&&)w^Y3ZXk#NID@qH#PEW2U|0*Ns*to=YHg-LF0HSQiYAO_Zk}n*VSv+&}#?WTZ zJe6ZDjRi+Dvo>b8v`VWQYl9|{wAxAmHx_UY;K zdRZ%+P0NXEJg8$6ks>9YFE>-4&CfptZoo5XShwy2X1vPINYfPO^4tbJJ?5$%J9g~V z%WA5Rc_;!oai9qf4(75kHUbd~0KO*5nHb`Es5Zysp1j|c4@V!Z}3pnty832bF zYWz2{u!k&#CBHe4Upu00S@rruL1r7*KC)gciP5!_p-7hVGQ!b8c*(eZ-@DS--Rj2;Mo z!F;aevNPTFua#_)G6P%cg9i`tNM{`jLiOU};zIezf08%bXmj#VpP75Evm58)^)vJ3 z$;qv$uo#P{AOW_Dvp)0SvlbvV%rL6(@f6;`f&~k}mWk9XlQ^gAq@=|kwV^EIGdA$t zIpT`H|4cWqcx|bLIHsr!XQzbyO0;0@0=$`HLFao3VTsmj_F&${|4PUw=n{{h$d9L| z1AMZiB8Q?%H;48-SpVg!S<08Nb!*F}O`BRaA(BvvJHMj>Y_=ECtdOr^(sPRyqa!5#s>_4Gers#CBu^G#c!J0sZm-sxA z!X(7-{7@T%Rxc}lx~dO)EsWJd{VBgzgL_#&MdxC60ps5Wog)(4#c zxt%|C9zc>J3n%ife%~g3%fkx}Zry91^q6R!2=1T@z2`g+9=y(5Y4Ez7@33{OzvzCDGFtqGcwVI+Enl(k=jF0bR|(?jCgFE)0j~z=6kuI(le}l{RuT z3J%4^Mzja%SY|W0k&Tgcqo0Z<>l(L}f>`K$M(!n?FGq&z1^2{b!2@ood_c~Yh0R%} zl%zPJGq_gy>f#~DmO?%h!;`CBj2n_w`5KEGA{^oA=%I>Wwj#ox%g!+R6kbQ=j2;FY z@VP+wViC+$S`QP{xG@erS5azon|RG#$>g;#L^NWAkN@`r!dajy68x8BQ~Y!mmM&q$ z9HcQuQBWXSt+u+l8cm0p8W5xqjRv(ip+kf!uoyFs1raYFGq{a7QheSy9elmY>^_`k z!VZbb8bJ@RuIRUEhTn*32mk>2avS{$zjhJi2swSmlbes(4!DJai-V)IA$2mxjFUmi z^z%;<$>nv~tqHMV(3(PvW>XO*Bg|LcaN@bfxAzQhmF4MwD=8_7XwTi7$Xh++ zRL{oT^Wfbnu%zwmJ>dTXMNbt7FsGqDNAuIVk< z+(xHS)870Q>Q$(6>DqM`*Ogw5)lK8#99H=9o&{{O(dr>WMlZW~jVPMAldn4dKHQtR94f>;*&`I=wY>5qv!pUJJQqdPmQ^FZ|ZDZwy@3yJy;dXPL0ML zx^Aie(V?bm{_kpcsi!iM5`~V0s{Qu9kynAqVpH(}57VyYf7!?toeZL{Hfl3{eUXose-~dLDMyc)R zcN4ziyZk#KG%x@9i;X{K78bJz+eA1SwOFxJrmsni^d?zYv%~Xx6~--JF3v(!tbS#$ z=Cy24r`J3HD1IBDN~nj22MiDunnHm>tuNKZPJ0cPpjNF~bkK8AbW_9m`+Jd4>eqiY z@8qoGEs;dJRj_3YJaQkX0EZ>1$IMCGA94!WFfKNhrSKm)t|C_eQw~cUp!~tk#Cp?b zKst# zrUQARr)Su&5L{)>oXs)bciu9tE<#jf6luzhsG_CM+P}4tgQd8;Jjo6`Xr9almK!*>5M`Vd7wDXo$_f zGE>@~R2?2(nl%697~qzM2|Mit^2n(pAAsZ^t9(6;5=)HPqMMFkQu0gMVQHbC&gxkW z@&?t^sso$%{QdV7l0z@iyw)}{%K1<@vn68@rTr;-QQ-hw&Y9!pXQOpCUCO|@fsi3t zbf&;rTw-*N*DGH&LdlY=X7J(6$%%;rIs|v0@dz5?H=4kPdM9y@3GRlokJ?i+hEZ2eH$MfEGN$8 zK+QW)D?NRJIyUX)mr5b$VN_ze^76O+J+i*AVG=W++PW)sDMC+`y0q)(r%yNWR>TvO zr9_*xp>G(OAc*^Ud#h}7KV19I3%E^CLH1%sxdljVnwQMO%*kZffJG7#EWpXOQ5;ca z$pNL5rftK~maAvevEyo7iy}r&%`AR6%^)f)Q3^9UGESDCf2hnro4u@oTRwGSx}ztG zVZ97;6$9&K5efy}Qy&u>SS+A1+Z3=GE?gJ{!Bj^& z)c~z(%uktz53^j&t)Me!T6W8r-JjacW;Z~Pn;UhzdlNk}{%reystyI%gbfuNu@IC} zMizl=K>l{j8(K&!NKra}(4aw_kzHUF=u?L6k*cK7HCjc7ZtZBJO%0P7fqT5s)G*CD z4~OXEH)e|9OXykT@so-&@U^4B^7lV}zrk$(uf94;zy=mz>TJ1c-KI@4nGhRGkzWJa zU$}Is*TVO6{;#ty9VsIdNi3~HfCMmrLxqht==8$-Wf9(li6MMIP(+ThnwuiozmZyM zzNDmkU`Dh+={kNach}kOBmHlcMdZ|KjE4ovY5}~}v0M>RG^D2kpha@LiBs;Z3T{JD zGKzo%WWF7(Ad@sX;X@05N0==G&fvUvryK=B&$fWC@R!Q})=ZE&fzHSLRP=OKQ=JJZ zTRkW8BgxH9oR!0Or;v8ZT*`X&mOAQx7(Chfv6dppWEg{nwkISKSG>E`YGg2%SxHHN zh}iB{0e(vR>S9`sE@$QH)kMsU)2C05wLDbY+7b3M3QrL4`bpEJY&dIpYHqJ>lu49i z(!x7AnNBrRr=?HIEI!k1s*nFG94WW;UGxzJfk7!fE}n#HTI?NQJ z%k$?EX=-Vd#dorg(uRjE1DOxbn(QeYg+A_&OU*oe07TUN`?qW`5W8>QzIYq+7Ns*X z_jGV@xSKt5AN4*2T&Kb7($nS0^wQLD7IpH$jaHEl*V>spJ6rjRaza+y#b!~iA*+b0 z9j$skTv#n)k9IATAa`uBi*cqtef%)}BcLcNz%Mw*QDJ~t!42K|aa7^MX-rCelL=t? z#fqI!jOpo)TBV7}-fvDXL{CA~xHpYv#nZ=n(fde+yT|i>g|3qpzdO^to9R-lFASpS z2>~{l0f_T$&U$Y$69KXLvsRg#Qs>gS|NZyhm|@4{QJLUqv5#LZ5d4yuvxi0d;T^7{ zqoV?IGN~Oz7n^c6LSz2q9r;`3N#>28Qb-U>*G+|9K{ca0aae z%eKiko67q0Yh06-o*vdb>+D>3 zs5^0&3hFqLJ4j&KI;=gJ20)Dv$|a&uF>2-NwaX%{YaT(6>vLjE72GSHkX5hdg^U}= z`h#Ct@|)EvmC4ewu4kulKg-Xrq42r|4fIq_*v)i*mMS$ID#=JRdanm70X9(_sU18$ zp6@`@%%l_rDy8V-46NnCkh(x`u`Kquqk{@ zqR=OEAZ{_4JKh`z1{%6x%Y4d&-)M$z-n$2OvjuB(#Q@goAIN% zdc7o*3-vtj)g)?b@mQ0Vgt^0&i|d3~8dn5S5@;7`r)Q))+IVaT<(!ZY z4uD4Th`4f_eI2#l{HdH?|?@W*M|M^2oWmRE**{Zk+?T6DM}L<=KR z!{~CWY4j1n8bZ?P3Yw;guJ>qX5 zMcYqJ72J>E{xxGQ)6?s+RrV&?bEWD5Cqu{wq6RS#-e%XXUB^jCh&(_7Db;>4c)I}?ZRM}E-&ru|%ZcZKSkYHzGb|!|g zHU{{nqUS{h+W2#BlUnGWtrkfR60g~)UONmH-6fnW4sP1m(k;5$vsNpb(&^Kt$^J=w zi8lkT6PZK|cNZ>bAM^lC9VH@&i07n9>8W8bi?iLVkZX7Qj-u`B!ow(k_`sdLx^(Cu zYk?q6jQ{f{6H|ROg@uLCoEsAp-*U=vBIj=%-@V&oo!yqpU-|f$HE9AKb&Ku~%0c|K zD7?(f%%FW0rBzk1eAn35OVx*xX8Oa6P4*P-4GSbemkmRMDFS<3R%{>8W5Kc2vM^WY z08#k)-x30*Oa3)OYF1Y-F30ORy(BI(RKqV4hH*i4#HbCjM2m58^$`=~7ex6_C#kQg zkqAC$p5Q;9Qrdh#AO?5L+Hr4x|8;iU-(+r*&IEJ|+96)^mmNCPSIC+PRJIz2>e5&9 zsHb$!%S;MtCpA_}FGr|`O=$@&%1fot*)D|+g@FzhR|F@fIu*n!XWMG4L3ZS$LUq8v z>szI71ILeAc9Da~!s*@g@zFZ&hmu7sKmUK;Wbz>*C_vSpAf4Px9xc!>iRUfXHK=2e zUjcO*V!k$Lbcnk;ZRF;XBfm85U+B80 z(1g+uj7643QGJZiNUNJXN+%3*obG0Y8kp&fQIO#ZQc@QgE`{{Wsq-1EqR#pKciD>W z>KgyGwzd;c1C=r#Nft_wGkrBqV7vQA>{&h5lI#982pWIitwOET>`e`m=AMUr-MY9rEz_}O742Y(sPH88FRbXP{1Tg3ZF7=dv0;S9L%Re4IY}+0?*4IyqWx|Ipj$A8{JS08UUmI-=gAh@p z+)Azsg!luceMAeJvt$e+eQYcM`3Dq%v}6i*AB^$u<&zYTA=U$2w)Xd5zkWSjixB59 z(C^;7!2@cHR+X6Q!py_-VADJm-`oi4$ocZfV?l@q|AYl6xBx|%n3`&f?N?y(x{`}I z(Q=u9sR#_K2@}FcQX&EX5ED&IOtLfT*(BG^bC$J@I+0GdZkgP5SQbLLowl_tJ*hrP zdT&-e08Q^~+NN8#*FgQ*B>gT|d&&GAc%RKU+D}o1@!vrK#lXA;8IX&`D;EV;hFb;M zl=~)IAI|Jd#}|)+tpzk-99$Dl!s2E^Z4-{lV$!51uqWdF!_@-PweQty0np*{<;y7` zad;XweE6CbD})e4l9Ytmr~*JwSRGbd!0#}NJY~wCBmh}2OF2i8B4u#8aR0O~i*V^v zQ0Bm2KfblEX~0@At%&wQX6>@q=rDv@ZahWeO!HQ)nE$T_Dsf^=r;s1%%I)oyW+pZu zckuHh%wc;9MT|pbOHTLj5RjiyxY_g;q;b=!Arkw()}9lEEa|SSE8#@m=gqzA!xC}Q z6VWh~?wLAk&bKM(9Aav{n2v=9D6@H7FkqG+;bHGJsR)ulV9@Xql&cmIP757|XlCZ5 zRvwO`vgESTaP@I3DRkcK&gFVPetu3fhdwF1J} z(qaG8D{fxDzA@yKg@rMhN1sZQ523vE^ilb2cnD%uT3X6$f?)?HCdb_TaTMbG60!9G z;=b|V!2|S^=%B^`I}8~D&(E-#>E{bPws7W2NS2b4Pdv7>(+2hHNB5KYntfR`a+`&#i&2484lN`g1)EvW!Kr=_rHp01ezN8t5@n258}%J$ zzrKmd8=yAaroTLX|Jk%-v>$KJHXe?RU-VaJd?cyF$e z>M5jj@+ur}kv7!-7HO}oi^~h3aNw|N>ON4Z#fXb*YR1lB0-W9zXtt15aeyk2RrWy! z26r0!Jg4TWXPOB}CpzaOjFH-Cqf&nSaSFHM>2 z41E%+k^Cs{9dmjIhrRTKJ9g|~ANL%%Wf;fOG3K75KyB$I*Z|M?0Iir%rwx&XN{5VE zhEmK8T3={QWS>w#q>x{D0l>0Iz_8J=Zq{rrSQ#~Ivt?yG1O@5`*$Y5ltW+RmlC{L# z8Cl%G+zVrh^FSG7E)mU#P#PRu*iER-lVdt5E*v_+FXhiHuFU~c8P8?sO0pc#ZSdlz0eiFt>J$(=w5}_a=SNGN2SotvigU17BLaR z2A#mKt4QjepLsf~6L26;g<}Eo`=_`ZscSI91+3sg4dDSW$5Pk2*3|M>^TY}Twg?udMt%o?jM?-y^j6@0FanN_j&&8Lc?tz3Xm0VF zeUWS!E2>kxy>qIlk@SnmN8(1n< z^o4n&_tv16%z|!Ow{99&mTnkwlnoM5zIDOCY()lYUBgo@{*Jz*-o0hh7eY6Z0c77| z$Bx4`gr;2*u;P@+t~hLosjPYdMcctDT|EhIf_qYcOzmu7kP>K{wyC$=ZK-(2{(P6A z)h)um_W3@W52i*)rcC>jh*YC2h*r@vZ)cbKj2W(e!%?z8OMxU0Ar4b!aWT&HKL@TB z0x&r1_y>Y8zkL)X5rZ5M4uUq2xA6CQMGGX8`Hl>AzOE{1)v_hbV?zaJRoHLFpTx{W z#^1RP{6;2kOJqj(tFQi{TkjXjS>#nSDb*){0-w7@R>@hSRu;N8@f;g>cS={O(mXwm z-zQ}wsEr+@TwJ^v&Q3f1*{tKEJ2vGk{Lb@%sA9p=d=x&^6!aZncx7Wg zcN2whf(|LY)thASjzml6eU8YVPb#>jwJBs1WLm<>bQ ztW|)B%@%xpWYR4fP&CN=wD-6{@Lki?g|1@x?AYG}P;5Nq^&fxy^XPgTS66f1DnC%( zs(1LZvA_TE2TLE16T4woD5;wxHRO^eH}A+25lPW}<>2d7(7BdNW4KQK{uHizbiL?^ z5hD<2ydj>6j|OlcRq1_R2!&Q}>#JN+Jn}arCA}x=E(8#vE;5J$-M~hQ4!fQL+0+dJ zIENDL#vjo9!-fuJ`rr*;W#;JFJ+^v#0$?x-wQ<7+V+$|?k_c6lfKdw9mF#Ht8d2!V zh=W7)Bxfg{I=+d-x7r<`?P+7UdWpV0<~%P&JDjx$sci$La*&soOkA^e%awnD*8#a= zYw!6-IW#h;u@n~2(9o?yrw7k!oLStPfCTS5NU&RhTIja>f2p6d$=$U(tT|c2lsimy z!*DRFr4r5@&E6oil)dZ(Be5H7SfT?b)kUv3uzONcUR9O!ZP(6Nr`ra%cUt-#0}0K# zO$~xd=UI25Jtu7YOR`40U$Y_3c1c^1PknJs`Qu$%^l!RlAp;o+Xl~oCeS0jyI?(yR z3y7NoyN^2zZgg+Rv}u1qY_N0Oz{0CgoS5g#k&3*rn$J7ca=@TL7ib0VlbL1TCZ4SK zBqmU}1$m4&y1Mg^XXK7H z(aixVauU86iL~qna3ODf@Ve6NZ(pDObdqTTW&+2;uF7yJeFFjkMKYoQI+*q>9x(Te zbhGk~4ohUYT{S9}t$Vi;{tyNsz&h=qtNJLYhfqZb*z@4#NT72)s z+z}fd(kPHcNJr45xuYFcbY@_YY=Qr;Get7ovEl#)ny&bXR&n?DWAOUz&va%swticR zgy1e+no%hqObGD}WQL9b2a*{YA}B>KdV*m9Qfy#Z2;gCy*Wlpfo%V9UpwM%0Oidbw zld87*k}o0?bMtr@I=(C#^v}R{|Ic$SB4-E)$eLOC)td7!85wV+E*_npVbhw`t8G_k^OxcJKkv18PYXgP;elLlUE0~y3DG|oR#70Zw z0T;xxlUa7EPM*YRK=O!)19IdvVf1=P8Tp_b7&Eh}A&Kp5MHIF!qwrX|jOh~SaXr(aTZn-djqlh7VXdFW2 zidFBC348n!WS=Y}BP6hyNJbQ;fXH0+AZjOroTsx;sijTfJJBC=YzCesDpGS|YrW-j zg8^|W*E1UU$X>gt+jnCkBA#OpLT#x_K6=eU#K>i18QZsS-8z_}O{W;Cc@0GEnw`-Y zhA=pMxZvRu$Ip#pVxoXo9OMtJraw0r?Vn&=w;Bdz&wV?)!`^l?cH4)pwQ%oeVlr;F zN1b{-p4huBj)V9t*P35@80~^cc1Q`dHZ7E zFLj&Na(nsPYbg7Mj%$6Jhsaq?2#G68I-XH)u~eegz2&S^okGu7VNVxylltSQV}B%q znTYo=QjF*4UGhc$C~QAuDGCW3J$Z7_!eX4wF6>nZL~aK*Rwtj>GBx|LXw@)oD81MV zW`k5W%*zWT&ol(-L>&cr0?^qeiq)pmpUHme&iRZqYsmH9kk%>j{8NKZ=>eyeF2<3A z9Kb@~Z9M({AxetMYddP$739!Ib9k*$N{C^s+Tnnc-r)^dxm z)GY956p3h&x%QuMnps`WprzO@`e;_UP-1;vYok^MHEVJpyv2jYsC`0A7p}Se7RMBJ zz@NwQUZeCeC_ZX)O86uCK>*RY$U4L`=j>UJG?Rc5QCXKS;j*P$7YeH8(jQ%5rnP`WdfMJ{9=AW+5U=Zvpu?8M?(P8L6hx4?fc z&ZXq_=%Oa-J4fq(Y6)ZlkfT!X-m|CT;X~n8pa}9ef&b%5s0?h!2VYium2n{j#Bklf3WPLVl3YIMbgB*|m7>DwzF_qx| za=NpiRU_vdT#+_55wa5xI)kQssPA4qx-K5YjDs4Xz$tCG^GF{a3DB8!L*bKlcu%B% zXLn8xLne|`$ioDs*y+#aTF38+-x;6VMC7idzU_!O(AkLPT(@rB;HoUwGlPf)kAZ8x z`&=5I4WW0B*59bs?8S^;R#V6O+7GY8=>5b|7HH2@54eQHxiV@^>R(K8%Nm94znauN zr1&4A7y2Os48oIJF_cXrgrH%9}V1Xjx z1Ws;zEpUq>{;%mmNXFP4@ChmfDmp@+a7SQZa}$544{3sMY^hWB5qFvxp@Co} zk)nA>GJAUxd{>tvoWjbudxh=|hKd$dw}Qe<-8xyG=uBZRC_zrkt;wDdX;r6Vbk#dH z>5O1iySVz|b)s;Ccm&gdAq^+`gfaDmyA@tsTYJr&X4mL3PTAB8V7JJG9=i!IwO6H{ zyb4Ee+-%r@(%xbvOQ7S8lH&rL{*Xo5wNF(QDzM5U?tWw>Ingz28qHx5;6ulibqNVucD|HCUrDRA}~Ay(4z~%_;r9BwzGsapdZqlLqrEc&yA1aJh}h_rufAk8B6~qYjSqq<3!Z%~Zp34<4!?1G+SYk|k+{5wG3vka>?c@38+% z>cg^~tczn`SjD}g=zHSZ*W?-Rd_YMP8{r=?4ns46{y%|N7n~D?E(0f-kDxlBzca1& zP*6sM0)$~@4@kN_Dd`0L41dGW9o-ZLxGwEFb?SsGjG-HAI&eO8pIa7jXXfa9%b*@5 zuLsNSsq2Alc7~3MRfe*pj?JzfMvDEfs8`_VPzfFon>=B7Yh(U#rWuEj>-XhSK#6*Ue zTCZl>&$Luf4B`J z=ayX*V1!bt55J!wVc4s0P(lCii|D6$`rFClRGYpR`LlIxuz}&g@iNMZWw~uvoEyjI z!tujMz)*EFOwF~v7iW%cq)<3KgpfZ)Y)5Ive+%4DJ7E?wBT;Q+Wm%dDl&Lpk%ayew?@oR|&1}tJyJ44!msMeIV6^i47uakAneI_$^$qD;FZQ{nuRuKg_Wu2X{jYeVgcQTY=%f)JhYW=P#D3h! zd-7-?*QBH=aSk0j-VXdCC8+4jd^1W z6o%z-H5puR$eMZ$@xcjl=7!LI$p;QRC&W>w`d(zJsNfKvu83Z#POAlLSWZ$u`PKmZ_GZ=vP~^f zz8LHBk@q&=NhmO+_GEOnNVm=DYTq{GO?4l&U?*1XShA8nzk(?4K6J5W_*I zdJpb!0YSAu`nCd(etuuUhNNq;#bR>)Quocwfpi&e=*|%nW7Xf6wmS!LSV*AM%okGYd!_VoL^8K&y#B ztzpNFx96d7Cgre#kD0AsSXb@~F-e;iSP25j;zWwMd# zqoEfd`TM@NrcJyNX%#zM6Bfrq&TwZi2+%)q+cw6mhZh`5HV+XSCbW*;U@h3n;VC&P zMbm`tuj1XQ%IwwU?pC0k%%FuLLp8 z;KUd({)_dxwkc0&{Wn0G81i~(`?B!nzpqTPG+!yYSKhkM{#W=f zuU)r}xndRgMxX!nS}q~_0FZf)tWMr^tTIK692gp5P3P$kPrpOoixEUuKUt7V1`<6# zDu)T*eoM{OswM+191g8S7mcPx8w=X{PR8fyCm7vFb6O#k1??^BDCSQ=Kt7U%MRx{N z1kl_GV-Ok_((*ID;mw=(wm@}d|sTED&vltb-$ z7T9&(uq@B+7}PQ35?|68#V7kFz>{#ckM*sa0yL5+yIN>gCZV!{@I$>VTQ3+I5cZRO zguEU`8k}!q}ZxHj{$yc`tO>hXRniuq-nm{OoAGe?JR7K7I+)*IZX6^^ceUgg5kpUbLE zmVv3B^F{P{TIr`2$OJ37-r~bw^b`2)6TI&2%X!x|E~JLfB8Nj!KV zsVD}0>D1z`A*LD(J(#0xV_Wf_ctE)SjsJ%&@WyrP4)F~D4S1P68QBU!-h6)kU&Vui zkzdZy@HAIh3yfEN#}(5*035)RIzCS74bCpsDLwZ>h z0=&jwdqd)661`4%@j^HWW`nk&SGWwwi5X`iEjs=XKo*(Q^&CFWUDwGY7z5V6xE}1* ziK<6e6Tv9sea%xHtOhOG28E=N3E z7zA-4rm@VZRL^w`24W<8S>}nvGYF6*N0u(~hNMp84gAL%mN(b@t|9+Lg%7luWL_XjaaW9K-TfkS)^+@$4s8XEF<$=obcfcfSmG`o1C*8l2 zf1tGct|+6WUu%7h^UzZl4ROks1K+y&Di)o5>fa;S(AzrYZ@qq6#sP@Q?^tTT5B395 zlE#7QQkjSXKsS>>l#tL?do3`;$zlum(Wj3eM(z)sS-z^9#(~MNo$)I?Y*&}xIoct` z31-qar7m!h?)fXcH3m`TZdw&wIOSG?sy?MW<#I~AZ_;#$oGQ^_k`0yL3U9kWOFky?n`2Tuw@i$(7Pn}`flHpWfkHrvhAbR!< zk^d2Rlr|s@hk+SbW0{Izg*w>#A_A&p16_^3#JKd3h^VDUy)8aYftB>Pd|oFIAP89E z4TqJ$_#I{^ivPSnIwY_I-X8_cf36}X0boUe6f2CDFdMOmABV099U2&(Grc>=)oFed z@kH=Ao+orFpVl&jji?(TBo?!af*Z^@21*s#N=7=?r&XM$DbGq5c{)6Ncgn@skyLw! zDHbHa>~8o=CQTXI$3R3;`tBo*v%u}-hfgmTeH_l(i4^^ZZEWa<0)&6PkYbm@ttaLT z!gpj()oAM4oSiw^!!`fxI2Xn9UJWmH$&a`)nkEdCJIAuW(nm9DgQs$_#=c|6Sypuz z;{$3?U3tUz8YR`5pPW@Uo? z$*R_MzLWO1JijAe-IgtXfK@dWgB1t^z!ZU?lJPLYC|hh^@~^3$Fv>ysc?vd^d-FXx zL?)EzH2HHkA^XoqB8J?wd9#T@+_`ZavH8rUizywfEbeMo z=F%Y4OhMzjoMT!3?v$@1N4^=g)XQG>!$Bi|@Kq~-B-9?U@a!0VoddA&keb_UmoF+3ELP`NPvLe?n zvFe?xg6}OrV$F@y|HGlN2(7X5BeJ;AjdK&E*7=zt+}%U4Ns1eTC>g|lT=NzKE4fKD z21n89Ld{9FuZpC=7S%#s{hx7Ts^t|Qnw^zh8Qq}fv<#tZtOIB?l?oNW$it83c$JGH z`N#%eEKPQkEujPoDGlGj2w)KU2!;GR-H-DHg*;(yRTl#2a5N- zJ~7@1VsRx9;!&1TkgkdK zy+{EZXX%m~nS=_OPpeiW`0};zOa0cz=LeV6-Mi1uypIV)$?JW7d)3OtQCLVn%kG$B zuJ5W#)k76*?V`9j8)=p1&Rz!tg#%m4j)uo}YQ73cWd>s*uPM#lt|4U<%#jL$J1r}@ zT$@u^KL?Tk9*3MwnlAWYMwAXzRT_~dfNnhP8kt0^Rp03T;VnKP#JLI-VPN*OOC_&c zf-1Ss6<+psbCyymK^6-RAv0XAe-E8^v)1_R>kqQjhp(=XvAzGkYD8@K_=S9NVCDZr z#hI<6{tuhFw-G|AMyX0cgugIMDCC{8ta&NUx#RJ{*_~r zuG>lj#qMDRYvJSZ!ib8ESkA2XT`)<2qBE9aXoL4o5<-nmovOIEFjyhb2S)s%?$DCd zay}Y;p&|sRBFb0DwxpLZHEGnl;8s#fkZ8f}hJjv$m}0vTR20pL;8LYw7$pI^xa-*+ zIN!^j5_yPk$SfG4M^hM!O}Xs&!Eb-}Oo zDcwIx0ovt^k#2>@I>Eq=0L^TG|z;cwjh6(9ajB8tGSe5M;UsMvo zYDEcO&%mVbMfy4cIf3Otx-q=|s=k$51T}JO7Vbh{Pd$eDh~mg?0#1LAqM0Z?B!x#! zf95t!nus;irxwq0ZSHxN`A8HuyYojf9OM1!YMy*wfzGF#A8+~QobSG!chigdJ5XFj&GJwem zdZElB*OJ#PfIhY8L*+NxwMbmT7zGDR7Nlw?3lNTHtc+Dayr3iefLuWxjL&7mKGn(P zZi*;@XwVHZukeDAh~bH@CJKg&f7rCC`da^n-^((dd4C5`TObel3v6!@10l#vfJ^u4 z(>3ISEJp@qa1(QVJzb&SoGmW}eC0ij>Ox>OECaS;H2zIGVhB1r1)K1~Fng1+dDZr99!Q?9G>~&oNkzOgQ;5bPkeqUR(^IHVBGf4O{FOyLy~SEN=9VNLlFR7OIP z%R)jtvCyXwXFC6*z@M_CZ4LR_O(8u7w?j!g0|KDx@K3r;|;6IHgep52obrjKs#ZxOVD zX9SAzZZRauAiD?IQ<49RJ3~=)y?>(_K^prXU6f_2?NT;u^kiuh}{24lDHl zQ_d8J*8@jr5`4E+NPPVL;X@wgblwS^AQmJG6CC|TsSx27$A8)>6JtblW-w`7u!0|am?tr)=JdUru7y1mXwZuXq zH`q-}{QOplS&5YjR0AS#^kCNif_uwg z;N(%bQ|n)fwDPz~ZF~5(x3w(@F2RfC_OD2*LpC@a4DZPsjT04 zp!-;P3zlBvhUsnp``q795}=0Y8Io^$^<}%Eo1$X9O(18DP^7H&rA!)S0T7jfm`F{m zqST4-(d*q{_gAjOK=2?s1KtwF{P4-6DV_j*D5jo6|7bf)hyY=4{QwpYd-2nhCVcv2 zDlEvGs~0XH+ib`vv4S@m8^9C|Uy-}0Hoc(|@P9hbso`B5*Iz6)|M&pFzx- z0peg-D>&3YV}_5O4J23iIZ$e)jZ?w6xHBp1eGRFAgwesw@EL=(b)sY(UDoAc-Y;D* zKC!xLBf_m0Zy915i+y*w(7BOTx__nX>fQntvU^YbC$E!NrPv}~G1DvZLrPCn2Y~?r zkKQeW!^2iddPNF%?ySFecYPV?z0GBrRLH#6XrLF(UfFY9G_!1{6eIj|8i*t`b_R3e zR4zQVAAFJBzg9}!At)ZovcSnoE5=rljB$C2ODNr`7BFe}n7%I~kaI?dL|k!Q6O4s55p*oB}4(qf1gK5%jc~} zZ!7vnH`^aBFc88RS|RhZ_9;4eg7HGy%J{K#oQ6648xrNScOOZn2#k&VLhER_8eS(Y{zH~E^%5OgYwGnyu6`yK#m3cgi#cNFyTrmDQ$ysLts2mm;K(D#53UhsGg`H} zT(49>4kgMm8SfFx8(<4;O1p7I(5v;Ll#{_0%>DRy&v=S#I+?ePEe0=u0Q#_w68;8< zz6JS~C9iR?&^I9xSE}A+RF0F4QVP|o0j!QJ35lb^iL}b{kfBSSIo2qIl93`Wz>H|l zqa86UQq8AXMe&-@Mq7>g=mQ$=6bdaQY!&>TBiuL&1-P}78$x&ZrZd~py?Zl5Ue3#2 zRUB+SwJhNz_+oSZVNc%=VFYQOx&}_8?zn@SgooI;8hXNmR>nn<@SHP%9lj{pkA`=` zV--S7+d0mqy&*HEFb`W)J9%?N0LjKwSNtf*6it_WZC)9q3+Cf*fElPiu*XiRBxLH4 zvrVepLqF13(#FYj1r-(OLmCw*K)RWawAOm_V!Gw1+u1UdSc`McTgQ_k8|>Io z2k|$3Mbeu=r~$F_UZxV``|U`$MFF~PTLWrpkfo)6>Em0-P{Fel1e{fmsk+IN?ctjJ`GLXL(jVDO}6avOK>4k(?(4<6)y#Sd`Ycqo-s zv4n9Ekr(|qYJEb2*kZX(ycUeR7yvX28itT|=;|QaS?t~wj0xBvH8oX@GFbRhl{W`Z zR5)?e$n#~z;{aVeT)4)Cb+P9olW!cpElShNmq(+g89dk|z)9Ph>Y z)U@M6j z)6yS(wb%FD(Qy0z3@k`xx;tLbBn4)3XU83+(gz>;hcCl5=?z5$vuhbb*ck5RB?uJ- z#1l$f>KPC!wbIWSkt=j2>|g)6ft3u(oo2fXh7Wv;o;9L(`d~^`5n0( zRgH;($6=>Riibt)mD(LoL$IAVNFm?mhYJ`W`{0Pm3P_!ysr-FZ@r(;ZUID=V`OqPP zCvS-M@_eK&{dCE9ho=Up_ArX#dw{V$fUur1I+L_18(g@JG9E`v=ZmE5*+Z<)4AvF|tYQkdFry=$txin{sn4ITJnXARY9fs~77}Sx6ZzsJJ5oqsuehKS*)1%@$ zTQy)CC}jaRn(+q_3o4?T=2})#zwzp(6pM<|FVMC5Oe>MJU#Fu~AQS@tn@gWTR>PfF z2tDSBx*=}z=d)u=NeqDzppEz>rp?rb;l&YRh9Npz2sXq|tFdAc?Y&jLrH2--P7w@G z(K+9peF3E?ECG3jx>=oioVtaw3KD#0d=Dx@iV#s$Vwo{ih$@lB>H#khtq1(AW8h-U z^fb3mfo|xrT3<&9{-YxxV`A~%=9pd?(&;2yl6^de4jnqBF!eI^2V$u!49v(~Ph{|& z_Wm~e8+0QCYGv_JhZOH+5IP}z#2Tn1v}UkGmF!`XJ7V$w5nr`ZdF{PBSY#dfl=ZThA z^O%D5Yr5~S!%9$eY4<@a+8cq zn4V6Y()H;7De2=~+BI4Z;|WXjl0?B&N)+Jy7=4LNjjZIlChp4+HVf0JAD(D8|#H zdg&AZXND#O^uFEP45&Zq`Ft+H4aiND<9{q`F_lEf77yF1yG6Y|YXK3wMKxq*`#<8$$O(9HC}mB7mN05zoUuC8M&(>b#5Y z9=!eiI$>(-)fm_SGt!anV$6=->ifXJ=J9;RLgFQSNEOxy9Bh02S?~?4q?M3a%Tw(9 z{#W1Zz3g_PZup0t%?lA+Qu-h#d-AT2?HIUX5rPrVPkns*sdJrH*Zln^=S7vwzPfGm z^me@s3{7@)`=NDgv~5?vB{TY+Q;%?Pd>^%BUZ*+xqs$NPxO1>|T6Lu74`bRYwUZ1D z!un|pZF;w_NZNdI!s$;cw@!B2asSgHUHSj`8o$%+6PnfG zs%A=CJc`D8Q0uT*X(zQ#C+JD0Vrj4!6sOyZzET_#kPNjY-Enhjk-mZ}C={qP;^6MY zK>+4m?qN!F9(zt*uEey>j`njnwYT#wf)yaInF!t^1hwlMjSnPInb@x zd+d9xhonDyR$KAnuf@l}WJIFf<>}HFj2Ml@0Uv${Q5#i=uQSGa=?PM9@Ynx-Ib+?` zSFw_KE!^VnraX7?VjE5nIa0iB=(2kk!O@c*CIytrG}qeUWih+no4cEJGPbaBk+$qY`?{O`s5Y5Nnk^vNAHJQ5Dhi zKH*fbyb4)~TUpEiq`?5H(y*mOD>W`>=kGKLCy#Hu21>g;x2zi1@-wOp6?cch*D8Gd zj{ukf{!O1b^V6&>P@@`@4&Qh-dEVK7cS3^wg#(@eE02$GS9=CDcf4UwbuU6@4)6;1 zyqrCzpHe!wTwQLQQ{JO{_wJ}^d-Nzich0SA*Q%5;EIMenZdj>jXqmT}H<1@(R0#+Qn|Kx|uIj==U>O^ta{Emp=@SEN zwso)RV*MYR2o=p7i4t6wwr3~6I)T5(gyKqko4;w@XSQkU)?JaULhRi-IsTI0^x6?v z6U4MPWdLpRzLt(RuF!1fOgQ*6kpIMkGd?u+>f1M$KqKRqg61Z7epcp zu|7PL&i2Oq(1*M+`hD)-U8t9;n#U}SAIw{$1BL)&&k>)hEatUvaicXbltp*ND9H_t z%kheJ#?28Q!!1*^0n?5gHEId%_8W<6oGBYD>w3JRL|wDU=U%@?b}PjVAtau9^FH=N z7#ArFL;OeR@^el_@Gm)(OOGF?!b75g<10{4wg5`f2)}sv;&}zy1J!*J9!Lb+C*Gbj zXAT}h3l|=WOirl*=42L#nRygW{P+LIQFmF;#uD#UWigxd&`-kPGbR^G;t_tzvd?!^ zSq#%sbq~5FTts!gb$&czennelMMK2P4x^O2|sDq?~Gs->5d^?}7N&D!1bUby6+kdnhZu zQX>?<#QTA=e`Q&}%(0NaIOGsgG%rI6Q<29&in*+QYHJb;X;F7ZypzV@L00qF;nXfx zY!Cq{uSV)<1f`+{MinX7RQKBtYtb5O0O-Yy7kL0ed6k157FJ_DXvBFd(Cxc+GNOX3 zAs8BgXNWGR+D2h+lN}v;c<a@Bd^o<)#19RUx3jMGvWqm zao$`L>ytXHeVj-O&|a&4vY!63yAQi&`m}q6xRBnzJh$yxoG00$Sr+3}!k^qP@=C|@ zToL**qfba|=Xhh;@)C2Em^M8c@G{Z+QXL*Vc#x0yuYCuYaDzL43RJbQ_{r^R8rPcsWwD& zZ#ApKPQ;STsh`HMK$S6VVpi<2$qw-&Ni;6WS&jaE9qw#9)JXnmx|2GWv z6vlPyW+o1ap~=V$Q>(PROqYx>b>JD!C2q6h0s{j9ehJg-UhDlvspq4LG*g%E-9P-` zgO$hq>SE`D$4d%`XCHe<+Z9%M(T7O|f+x~i>j`|CNlgTAH=k-J@pITLzJ$hwFyd

    }s|iT-=em}{8% z>yJqZn&A~))*GGYhyjA^Y3Yzrolj9yz%-Rjyzi({7r8N=N2ktF+Zmi%v}m<@2;s`_ zRVfqYpfz(GK`qq>t9Lsp19lEZPyi-p$xJ+@uO@?y2}SCs?@$N!lL{{HPF)eRr5g2y zOl-kyG`+zYa|E*5ZCX(?D>;iz7KN*11V6gzvJw8?G+$^z7<*~zSXEUextL%h^Hnqt zEI&ct={I$^<@@h}QU3OsHF?-oE&hcSA*Y+roPU zb15VFd4VHJWxEf=<$kJl5X%Iku`;E;FRQWG5C@W5&cA&?@kmD_tG_5I7yTGhHl$No zOs47OW!+>@;h2dyf(4!8UAOqpT{+cIFke4pUrA+ha&hLO%6@Tw-7^1BlzyoRfp>`3An@_$3|(5bk=BjM-Fy0Y^eQ?9o1 zWYPU<4JxS;bE=&(=uXUD#a1W%F$_T=dl79DEI^`%^eR0ZSBYmFygf+*K`JF zja_5pJw4%lg>sE1PK0c59FoZt7ILJ4#69Xx7pk*`p<)sbxLm&1eoka7gSDXbT32F*%01b2-%(l5jjFQXUSVU%J^(cj zGT4tY9Mq&Wf`_K1o`90#XXTeEfkxEv9vtjPU%uM1C97diUW+Ktm8_m;LlNWu=9|yU zjz4b@7A39Bg`ZZdSJ%7dxWRNKCY0|k>yf|9J;t}-{{9Z)1s;y*g&@G@e+lbHKXB{jO@x4V^5;$1j5%-U zVGP5ms3=<*5$3ds<`qUH7RTb`EXNJ1!kEx?XX{^c%Y3@@xR~21oL$^9=a%PGC#)w; z!6&nR_Sf>mJ$v=qh|DQ>%&J{CYaZiywN|NBUH1H%!UKrs9V$mY>nhao6tFk42T(sE z(45Cjlj^}{t&$---A+>mJ_!;%UshLoHW@J=avW_iBNmCDQ%Sv|c25&xl8aI^r~Ky> zzgMLkH^BAX0W=j`B2xd_;iZQN^tn)UJbMu?aeCF^_qN!?p8$s!SqLg8IA_tUl7Rx- zI>s^aNtU4Z`7j}2#lK$x14}fvQ4vxfQ>+}~WT@==VMUnNZJv>YJ%Nar8QIE_KpjVQ z(zr!8*Y4dLETz zz{TZh9O4gFwN!Rl&}LZU_^#1N0?DX@@H;K6l+dx|OcRMlABbBl4u4oL4tj7^tTI0^ z9pI&qtPraP4xKRJJMdKz-e8LPsusTpnR|y@zyJwro%#%GG1Mzz1e#E+v}hSTibBe+ zu`_1vEXp?G%z(vzx+;KB8O%YVd%R*Fc7>`9rUQ9-Tcg|2;4z4zI5~Acf(m|cN_2~# zq?h6QGq|>23-jk?W}6iGmAm0Xcx*=odxb4_g`dz$h~MwZJ+ok%iCJx#j2<=0VQf6@ zsI}-0T+5m_5e170EkMw*Lx&b3E)j$QT$|YZbm?Fh=3^&Ef89qUpnM78Wnn@=%9uN2 z9sM5^&C$g&hen|#&u{knk3JGSK(>=Wj5*$TN8ICDwrn_V1N@gVq+aG#67Qji3oS}L zH4fHuYRQF&iY3ZwGch(rWNks&;>xYJ;BCAG(76=L~j2COw>!L~`&we(ak% z?#7=>+(|2F)A| z!z_)qUyQD!A5cV?+JY`Bv_^7QZ}zbfeMm3;WB=%=P_N!#GF@egP7DE=`yz)fUk|)Y z8Fz8V;0kjMiT)0<-%*6EGK95Q^npPDWg2Gko!we>~ZE^fatN z={j)WkDdX_m95$K9n!)Y4kW8bvX@;0(8#KXPT_k&h4@c|WllzGybZI=JrZ8wIHN6? zwVa)=aAp}MD?7k2^MRPX%}G^kHBeelj-oO@r^*Yk#$QSUu*l(VxDh-Aj>dXQ$)0ky z0vPV?Vi48vvW5P|_!Ufw)IncxJ7k>=e>m6*Nvp7fwLaFiIZG-&&@G@e&EAD(=<5p? z$~lGjcrk&&Y>LYpLx)OGCeRU3@JT9VssMkW5JCw;9wF|b1^}z3ENCOx3vaocY0su) z(06IgH9dP{E_H6f%d z7)^20EkoU~SEAeJ#Kg~ zY5gTzn`?&ZbiSQ*S7SnHW%tduMAdsB0qEJ5G967fP6MM_A*plZFlLL;voL5?7hXY8 z+0Cl1X4focMTP1wS@0%((C_le09_ zh7Mg7F+pI0wZo;6bjBAE`O@^I@)c)i5rrA}x@Lo@Q6Mbwr^%U-SgVxabNR3C_#*fol`QNCEpoO=r&AnkgU~JLWvsL$N zpYfB}Z1hF9YCZ?%a{a~U&@2!2^YDi3`;3?XGgKxOS=tba{(8Qpp1Z~ZYCTwt+Sbd= z*LKtxj0mf!OTHmc2#86W0$A}rjA>C)+s2xIKG&Ae+2M)NO@&Kf7qiZ=XBs#)*g3_{ z3NGSs-OD#%-k`U$iKlkZ85++IwcrqAHJKq+^C&=2YX?N6lqKrNI24~qf$y*5G<<1XBYRGovXM<{kL;M}jfN)&$ z0!j^c_+w=2B<#hO3(_l-5q5*;9q1NX*0S69dlXv(l1d@+1eyoI6umcX(pnbbp^+Sg zNi~nNN6((?l9ImBrrE!4>(~bydM*;W8d+%yBP-f@nV`!Y*-~+vYr^yRkyoW8TncSf zcS;|P)ZMfqoq0AVr(W_5kmnBYhXzk3I@Y?X9Uwt!mlU86umA6`>!bJIQNjkq28!{G zK-LA03;dCWLz?K!v8>u4ae)=!^as$%hKc3uiAJ<3eLcZHC7M=dM~VEcbg#7N{yY>^ z5$yIm$bga$yaIP>U1Fk6r<~u$42VZ#Z1o%gFgwq}tS(*tc)aA@uTWbt^+N-DiJ;F4 zNnGhgghKrd%4vO1`(>gcx~WF1MCs`x_=L()Yg7^xKyxuT%^Ah(B_84})=y_R4sK5@ zRGxBAv)5f^b)g;Nh?SNeH!?Zuh&5b}b;$tS2C$(GqgQ!>c1dxG=j?Wi2d+q?0l?4! zA=I`oHD#YDqUc?l(KKl2B_y#{c~R%)RQqGUr$3JXUu;MPe2SD=c{YHL!Q2_ug6Fi; z%3agTbHmg|WnKMsZ%doAm$jAlDoUfQ$ii!ITtKePm9`X;GTzSs4#o3#cOQ26S8z`` zJ0FXOjhNx`(?REECl`UrWSS%yH_S#)DbO;bvW~C4<_%u}ym%MxnBoJslfjGsoP~8+ ziFqYe5u_KzmhyN7LPmJE?@$WSmi&c6<_MJ)tH@}%M<1`KpiIFAhNjG|letX~piQV) zX;La)Jbw?-w&lh7+6MQYr%Y)mJQ+JIEtLzCHZoSosu~%YO0yr( z5zjHkHApVln!irx<%lF|6k{Gpu#>aq7gO=pA{V24JSD~r<`kpUnBviV|2;e1OD%vi zP$bO}Z5+6@XaebQ{-D|tt4Q}mYU*PYLqzMqb5gl*%dK@v`V7%UB9pfpCoU@#c+oV- zZ(-~PF2mLOgxSQTsz=YB!?Tcwxa#{tj)<8PbEmUd@D|b{^D2ev3*v$(O99h07RkSrsP2blKIE z`zTqm%4^V$eJq`$x#x;NqXz-YE0$MSwsAo)m@q2|3$!57hI=ZQW`8&MM-98ydExvg zs$B~kY&gnu*61N2v&YlZmEl$)Ft(6J*m2 zARjrHJ;P|_&ryNl<9u5N6>9K6{S6?V*oUAGE)_bE4)H^y5p$DSkdD-C6byHu1EALU zBgCT$c-iu%4KoR|uvL$bzoF46mcI+{tppI2^K|L?fEzGGEHo45EsR=?gr!}dE>?_%%YO%Devv9_c{tbTR_Wt zzN=J@Axg&~nBR1ASs)mBp=i+0o<7YK`BDT{fUTCLoxnf6y}iG~Qk=>Si0(PCR(nP* zN#~ZSxoEkkfM6mMBt~GVT|vXZ7X+ZdxaT%zQ*7E3w}sv_n?ilypZ>Q5x@(*DBuA_` zS&0PX9+*J^OH#y9jaw?#H(c29n_q3+di%#8$59c>VGjjghUw9g1as@^u)T;!jNQ;z>qh zRA@`UOLIyG;#zZH-fFL6wsF-U9ggDmLAMjtrcIkBg!|3>-&Ztf%>Uqgh&OfPLM{tJ zKvV#K(F6hFj`9EH{vy$nqhp$RDQyTRZ_OP`$*JmVJ?NOeS?IF{Ht~E`_MB1vb?FoxnK4Z5<)DPNs( zos~04wpJ12I;$N(m5@Bg-v8;01T}n6sB5^f4yVA6u*@9Ghmk#+Rw z5;!PG1W>UPi0n47QA=s7@GU(=%><16qjX9<0j?D>8D2{`YIj$B32%WMpnY0;d`eji z=)aF{EE7#_+x|wm%4Q;?46YN7DMiQ{Ovyi5cmCqV5OM=UsH=^XK~ZY~2{Gs3mG*_w z15edVLkGzsHEhJ&LwVCM`4PB@--ZBd;kwWtg-0JMRpDHu4uIo5efl&YNhYF|jvduB zLxC%?cVs*XrS*@6=#BQ3jnoOA!*W1UHPPXY zSCW(?!myyvdW=Sx!KWXNFMGj7nYcMK5@fiFnY|8Y=TAln0wnBcA))`vTWz)aGQU-% zZeR@5VzR&Y5?~|w4wW6bD~=J?p2z;&SaFvfRhp}bMjpr)i|+qK{M*4wjeh;g%r%aV zF4&MA2dJe0nlXh6plhQ zK=$9zHt=Dd^MCE0mm=2LPqIMkM+v914cR=^9b@NOehuR&-3Jfe;nAXb^HNG+PWA&9 zbR6iWKthE9*0v_63T(H9ODgZbhe}rBDB6MIgK4{tV-O$5muQ?63Gj8vAIz#jpYn6^*TtD(znIPQHS)&3$l9-%T&-aZtiYSoU zV`Ql>fSlRB(-WKO>ZTA3<3>Q8QWD}Sg7##uEWt?5@=p4sy1ybX=Y95*AS1XQb*c$` zgjN|)y3+*gl%bzZLMM8mdHWm}P~~E|-A=2M!qUKAPXawji!21*6aIK=Wy~z$cnFheJG!y$lpbEVL8xQtwofLkbW1WNpzXLfOWzn+5zU3Yg-uCvwvn33qu z<9fV=uo&+AdO_myoo zna1*UZ?0!#g0U}E5O8vJKJjiM00)K1!q9ifFmw;Hml~#)Z>t+Nj6)%M?q0o`Y47=9 zor;>O>i&sUGP6-s1X{xRhp%HyqoGZ_b>?MuGL{Pq@pdLl0yK#BS!G!y$mUnHAbS7e zBT7j(i<_O8}t&TRZTaw1yh6YbF}OY;m`HwshH?Io+;8!u?SFfDo1d4hlVa=JaX4wJUP%)yW=3vWgC{ zgI5tw@bFvhAl6b1UTAWvMGishOdE&G)LUSHY(u}xjR%_*W(boA;Y;oDc;et^Mc@w z+>%wfKQciGmr4Tpz-U|!#s||(ioHTn`cz)-9D2?{fC}_2C(ghC{Ocr$=rPJeMm4%K zYV2rf1JBM6DU+>$$yTm^NDL{MCMKI5RzMmzriHL^WR?a|mCT{G!Yr}RfC07enAQUk zlsi{|Ss5OtScx0dUcttsdrY&8lS z(_vwKh)V_`)(kOm?%el%+Ig*;TQ2KzE45hS|ACnWib$-{L^#fu7Ce~DIsi#25+7P7BF;FM6za@op`3L4`M`5~THiQ^NY86!)qXf@V-~S!^ zn@=bKioDmfQnEiD>GfCQDThV}ewEY32lb^!+@zP~!)bO_+y0%FN2{ zi2`R=e2H1+?WKgLaZuI=^Z)JsqPpgH*GU;-<}gtI&1KXQcu02$p*0#Cqfy$q?5uTfA zQ*qX(RGR_Rx4y)G~rGj*2VdC5gZ&lM&3RKX$Hy@oi zIu8#8)22<-J&62ZoY^OvLpXpv0%wTAy;fqYy&NhUW$4)=G{k&DnQDTv=C^?^3DwU@ z4*UhA3dMeOYHI3pZU^0cYV>u0Uzs7`=5Z<)QKnEA(j7FqmR_CDg_8ho)ynjuwgR?{ z@<7VGIRZv5c(|L0S{Y?M#NaGHQ)ZkLY1RD&E)t#Etm{V~GhFtI7lM#`Q=*Y=5v&)| zUy>@;>+uj4fx?O9^+>#jx;3T&mjdQ#CLe`$0JR7*_({CVd<^rtT@WGU-;T?WH{UFV zuew6L!3+Ff$Az!-0FCl5`Ooo&;aMD^mLxeWmKvL_i?Yl%Ael?knbp$pix4oOxXKMC zZtTYliORmORX#ZplWH`njufC`qD0?Cjm-)Y^s(%1ORCPtIUb+hSY|5ay7N%SH=kUp+guLb;GIw9ghMH>e@*=bJYjJl1F83P!=aMn`fAfaUui6qTsnEnuQ zL2n-O;aTS0PvM+Fd;7|3y>7z81o-W^5Mau>12k5%`FyQSM(PLgJhMf#y}VMidB z2_IGJG-n1ETaBw@hbBm8; zMFy^_@)Bhy6@fIgz<3s@yYjd!q~%zRKf35X*w3P;kLCxI;y_Z)#UuVPEvm|v?OoCpfsW%xr3IPc*<|)T%psZTjsQCpjQ|)zo3r=j%2`_c ztCgTkeEHA=)7R>|^zWa~n-@kAgsGOH3nEz2w{nUo`3O&gfad{_STuB*R3&>1cz)eO z@}j8!N!y}h;;At)`xr!Rq+10#ap26S+yI~y0;cZf!&*25irFVnGa}7M9k@Mu5X0&W zzDn`H!@^BwXI7+GwvYjYD5eQV*1ZJxP7;WS*JxRx>=FJQq`5^g=z!G0aAFNw9 zg;$7}nSrAUJVJ>LAa;~RI1R$+|0xdi&E?k9b0a!=2D6+MDej3c*ieQ}?hR-mm}6?3 z_T(F)oZ-%ToWjsgAcY?Zitm+liVc&^9n)uU)(}xJ=aWNRrC%2lYtj+`kKLA$f~GLi z;_ttkASIKKcoAR=;~0MN?n9{T7k%P=PgFl>7KHabSF>f0kh}%AVDe^8c#Av2|Ga&F zQJVEm-SFXYk=g{vp{<34%|YgT`}QoEY|$q~Cm92weK%pTt24AZib|03QCvE(%QKv` zp8A)E?pGQFIsMG_vwuDM$)AyBG2|`mm>ygi*^|98Hz^Q!17ddrUBK~Y9AbNF>L8FJ z+2;e&#(@DX5k!Ys-FFGeqzuv20-bYqY+SGf+-PLJiXQke&laWPR89=|7g7{aMH95x z)_%u=yidVwkHFwSKIga7>Y@!?3@A%K;jaGk@e(vKsZ^Z2ezu#pWjidd5HQHSQ>O?n z7Gt|?j1f;+;h;FJEI^dy$92vW;@ig`0AwV01$VBCFU(EeOgp&i_ciri{QmL#GcWjm zyT$OC(N5wb zUv!38$9=^-;z(lTg#&=VU2#W40ah6cy7mk42?lW?Ykdr2W67&((gZCamD{Yef`X+~ znSk+rymxxbQtG@%k64fES=n%G@T%KBB_FX|QIiif6Ht1HOAZw<%T55_98H;}>)li_ToTKl*{~jX<2uf9W(d$QeiYFg1eWWlu_X(DE%h)uf*T3t&|T z2$ghHk;#8C$P~gD2Cq=m^=R0Ls^*K^{FL~$kIovkO&=V53;gF-y1G>APf94nb?7Bu zJc3Tds5TZ{T$V8uAIWf)EySp833EsbqUc)yQK%mol*;GEaqG8ono)2F?%=+ppLnfzSNNP!kp6s*w-^Ds7Mn*o}G57lh9xsAsU(+~4hj zXF%SxZWnq5G;g(k?w9-bN8ynLFz7#gIO>M>OCRi+G6dPP22af8rUle^(irdwA2PXF zz?&eeD>buDzp^Xa{_=dw=`zll#j0VnNG>mCTxyOzT{L=gEPl3 z*4bR73hi3@om^ zl%JGlvuDp{OgTF{n=Kkg(D2htQ9B~?W!HUMRBZfZ?IW_Yi*Y;NHZyetP9ieef&cs4 zz%k&>=&V~+rgWfayTquEC1?ztJNGw?vI=0n(W@L=_To9O8R;w5?pk977Y>REjbk$L znQxhv-Q}qZg$CsYPFt!*=M93ErGOxf)s3<4*y^*i--p_-RkfTQzC z{Ys6}8g?u@y=bF+7#yPv@^Nz`!s4uT!xD15%t{~>9i~$U0Mvexv?+w~HVDck)qFev8v5>sul0sldb(-c}gM;g$&VN2SY#6E}F#r4Lq#~&Ry)7y#f=lznWzNZ-yLcB_U|Ryu4tf-B zK2*hL9E;pswjk$bXU`@`01dH2o00J#vJ8bDH7{q2-8hTsIeJQ~nO^ z@Bu{0L>)TYB)$DV0#B(Y&-%bzL4zmL>_8j;j;;iLgNVU8u4nYe^-rKkf6f8q`JU|g z1^p-};~<9U|9Ntn$c_O(##VqPYd`$(jM}dQDO$K)AR2U0&pC%Jd#vI2vT7re7RjWa zg=Oi#j?65be=OY$2>8gd2V!&6yLWTWZ=#3hH0X(hTTT)okUdaeTl3M&!@)h`S4bVL z`q&(c-qcNJj%~;03Fib*l*ND}Io0%^OvvR5`#4rUH#@8&dyuG!C!OWa4dqPfrEvwfZ_dj zO(U%+H!CFg8j7P^?6)na9;7Fh`8$wpn!>g&)*wBrQAy2Cs5ZAu<<+ZKpJLPU1LYh# zl*b@%n5%D~o|NrENmU%kC0NvfzVMC-C8+Bsk!`8%`oMM(;`seMn3E;YCf(UKFnaWw z;lu6JQY|eMi>OZ{Tj}gqX(_rc4d-H^t|rd7b?+`#&H|JXQ)?+o<1d8KDp5`|57l3H z;BRRudE<^9g1n6j4wi0R8hxhO_Ur*if%S+ZKX8$Qy=JJHvC|g0E0<>>+xmc-L3(Y)BQgBq4FCCctz_un7}2z32>~MV{a4 zx$Fpv?@X2g?aDsyEgnzk0EC@}0DF&V4)V)lbT`N^nkr# z3!X~vC5R?iJI}ECN@nBmIk-BKZ*q3;z8|+kznIAc=GR+OxPL+-U2A!sCrTVyPc~PE zEe~`X8r0^jz>@%|EX|d{aCEL)R5k&-_w4zSaLn4zob1^Ug7^e>zo2(&fK~&H1y7{A z7(IeE^PGv;(J+0v2a}{avt)$f>4B~gn|}*31YR(JNBmGJ;&2SG z>#>HgDYG!tu&Q%^3o*uN1W)V&$2r|1Yd@D_g+od)HxT6{rB$F)gNcQ8MT=0*RKBY` zazP%M-TndEPSqBRz66ie?iyR$B^52T!!7myNH`mWYM|;X6GrbV@|cet71J20>y|7 z-f-@Klav}_8H5Z8WeE-Vi?82V`VoMt%4Rt>A>dh)Hph@pWq%`?w0n;pAWf63*>lT| z9aAPv0yPUPj-@!D@ZvQ?yps1erKBujvZvMR`RLt?y>-(PHO%sG>Nr8duvC!MF-a!bLHMgHG&(2ou&d%-v z1RL(Kf$|G~7>}Y$UlIT04L@Te8;uMQYq%6O7ZPCXG5{X=`*hyx!z@ za#T5;B%(#Q(mg5|&4hw)K@$1tr%&A_SI?RovS6{ZSC}cR6h)o-Phe<=-SsZ9> zmVUtUNa+lr@$emMU1)qF{-&yT)K@Rv3uXvC!Gsa6)~mgdLu~XkjBF zZjm{#4>2VtXG_h@eqwdF>;+V6=!@7KY|qwsZIII}f9CD9S}o%=kWFchZk?Exn_s+& zUya1Mo%e#9WP&z6i=x0An1xnp3-01J)2&~>!})b%8Y+ecskAxOtyZVY>vehdbHC$j*R8{e(99|CX}A~HUPBqmD+?*hWQ9r^V1YT- z@>1<7tmWTfg(PnEBUuF$6DocJ8ryos-srdN>p89VSncX%X0OJopFwoD;n5C^6<1LL z_QCdVU`wzxs@lNGlbb4#qdli;Y`>^7p1b%CtrLa9L}C)}nC;$*%TQ>r8(?mJ9l^Ai zG-2jg_d1r86#aYm>_Mcta(M3Cx06?UY^HaiL|UHVDl@+Xe(=zxxRM~0-V)t(%W98Y zjt)f?d?}~XM!Zke;q;Dm_s+92_By5QU%&rY9ebU0e&@~|9wN=iHsI|j*3C%5rVHXE z3tBAD$-}szLGDGW5w<%`$f$%L6qCAizlO7XmF(D|j2HWSlR}65G^d)K_r;<&uFSAb z;4i7zVhLDssVW)wTOGzefga2h0YUU50f2K-LA8MQ@Jjk5I~x~BUnS0RH9lAmyq|hj zJ%;@uOev@mGG-;OR;}2N4pw*^%5}oCR*5B@HX*~=z*W!6?xIyDpRMt6W74e9T7?+u zim<-8vU{x#^X+ZWrb`(>7M2vrECN)WSP1cUDhQI)^uK-kc?SjQrm5P!k{E`n4#)K8 zz_br(<`Z##;xGD1)fr+q%gTIk4lx?M%);~a30OIW4VkChoj01Aaa3f$Rdqsr7hzkW zLAHYk5ktoQy|%#AtVccb62c{5<7lbm5t&9?$&CR6zW?(`e;mO=(9D0pK3IkdYtYC$lqnH0imek z;U+~0Gh6bSo%>s`EcWt674y;EWhq>^Lp_bb!MEet`2=;DVq#ckwEyF}O$wj_E0$Mz ziT);BZD;!wyRsnD_uo&H1CpE-mN>8^8eP-w$X4vt;aT?R*6mkbGgbzkh3YZEuWD?+ zu8K`HZPeR`$$H!(b)mK0@Z2tw?pkApYg7<$oG4;B7Em)yP6^)B_Prm{UC*Of7WF4J zJnDmbCx8x+iXI{0foJRkt%z^f?px$v3^sSaFdH^rhaf8#E?LG2Tr{suO@weeZj`As zUyQ>nEk5HUm~rt!3h;HD12-LY&T__q`?DH5OaXV@55L86HK_gOOrHe3F|fw_~)VrUs>TJj@a`5FVoU=jIkTH=iiwk|nEunbSyO~cO2Ox(+Ckv`;9 zcd2K2eQ(Su-yF}`Vat|iG^_Jj_p+Q+f?Jq)AMD-h&?+o(cQ&E+=ledRA;eeJz38x% zXal486S?3eHDiNWV&L@P!2^&Pai&IU(BzaXE)zbQ#sj@yH(G5FlWK6j$z#XbDrn}I z4=H6Y0Q~%sWpEwhnFus{0F|aRWyGjUrvFuQK6Q~{t9n7!LeKA8XcNJx$UvY7KjWs~ zFr+C|jrcjyD{Ay{adFK3hIm*_r05e<&7`WmTnJ8MhDlo=(E>HWf;MIZpmDS>^*}MY zYnZioJK64XT`kc;?_W|wVuR`VXye9qiz@38aHb}vJHi_%tX1#_mR4w%#(E0|n*lRo zDZiFfNFfbZ#YHXgei%1J39YLH)%oyI!CkMUyS2#jRGl;bjAN7_v@AII7>aAe=igI| zUAaQFOW79WPj%#zY94{@yU-6{hUvkYSPx3;><=34h6XJ5Bqr&}P_0i#A8C5UK1CwbIT zwaKZr;Gh$Ytc*FMJ~cEB1QaJ21}}q5(xwvR$|#m3y)tx#8P}`?(}Dc_WPK~dsT+2h zQq7LqeAWv=(E@~^d2L1^TGw~3v%(c@n->v~vdW6;QIz#A0=R#}%M44^9;DILsh2}I z2s8~oukeyAiI>v**Kg}7I8o>#Zqs$*-Hf@#4q};1(DS!!BsnF8anOH#%2-4*u@%ql zkX-{H-7wJ%uxUb?(ot1WBkW*5prHI#pyrPadSc7OiBHHt<9MbsX2|N~RUa@>^N3hR z-w0Kb{PD*hdaQ0y7pNf(nrj37z0FdYcofn9W7iE`A54Z>?eLlnrPLl<=l*Bsj}4ZG zJ3(lKLn>>V<+{^EkAYR(RRXAck+^U|U(f`~dXfy+1WSAzLr5WMGjlzZ3^n@W{xY@< z#ZIgJ|L-XeFSskWhPLCgJ$rgPgi~UGYc2u$3~@52h$WYdp!)BYK1NEc|07IT;7HGV zSpI!#VI-Xg4t&P{Saab9hZk7pwLwc3VPWAp)e=0tVRray;>3LF1S&D{0h3**;@84-8%=UjB!o~8Vz-07ahf@jNmnACA(`TtyKpwF}g$GTFfJyb@)CtTYj5e zJTw?uBag}6KpT0{@}gOAV1YZ%JbWf71QV*FEl^D5r-HFy>c4!suurgpS89A<@rgJd zMV5wzX{dl-K-RfMykeAG!L;JmyeL%+h3x;VVl>1Lt^WvRJfFfN7rY9H~Y9+n#h)`*mhF4leU~I8{&yH%8d-PkR$v( zSsZkfGgJRxC)qQ=Pbr;1O}(2$^YkkWt^>pr8E_3F{JrnwWthHN$A z##!naSJ9B^ag2*c5!1P8TO~E)= zbWe+h2r%Bx`e+5F2n!3Njdpd)*G$EQ%yQd9m@mHE{`tK%V5jh_kytySO`=7U3>C~N zmKuZB8I4MYZw+gQC^x6`+E8_@Awr}?cT!wNVjbB^t88`Or{rNA-h=S`vuqoX9h61i z@(;juG`56d@rp!a44dGRDT_wQS6GNmDXEF_^*`r5&L*kKQn%X~RHN3v}oCKjmPSLHo+w|?nQjr3*QO7;mH&ZRl3+cF;WI&j5qquGas}(bt{nJJC>+3 z8-OUv8luy0?KA<~3|#UkDm3)tx#d(UL1v9erZbggl`IxZ91h4jFF*xX+250$y1Zp|nLl#=G9vLDDcDabJG0$25baM|Mlo%j&>3+DQYIolV7RMd6CQ`Ls4$(sFWs2g~0M zF*{|q++!&ItVr>924pOYX`76mn?al)4mX#wyPMlNM$w9k z5$pFj|1eHt3n(D2dVWDpdA1^{M4pCd&!b4yz{;O~fG>`Pgkh^|m|7S;xw_$dUF|)c z4ZE_lnS8u{C3EB|72!c7lhEj6gK3hWl%Obr3rMux;WIqE$GwvXnCgh3( z5y8Q8MXmZ<{|_mmkfd~I{oUH6DyE%$J6Inr4%0pO_51g`_wF4{1N$F?@vOeZk2%%I zX=ysQuwfO18LNxS-!TK)U#rZJ8EdTV`6Umjg;6mh1Zvl6gMKlXo2`O#VOXExYHg3A zBGIk2hv6nty@dL4kSX@gbONri+@nM5nR-D zK3op=XLqyrtRk|hEkO#ENLb1ibmSxKfh@JGn+X&Ux+^(bBtkha% zhGigSBE!?26ivL6YDBBZ-sp$VsP>C3D?27AZ!~lonr@QUg}<~$zvc?>pN)!xLd#IXqDa*=v)=Ik+ypMQIFoUxpz4#eAWX62?@l%GeDvSz zTuw+yO}7jB;8&A}_^-tXhS-Ml4CSt)MX~Zm?z|uS^A^w>VE9CVS@@sg=?(Lu)Nzw0 zF@rjA>WSqrQr_^>gd)45t=ZYYM@b$s$~O?4NpTMasx(wU{UlB@7UZR?B4C5Qmmtw2 z5i_8Ld8aIflDg5qj;M6Td9IcZ)PgaqMwZ2SL}rqw>B@0PSKf9J=g>i^u{0Rs3BljD zIjb?CV-7{?A{C&F;HtD1`YN9A%jytEG+c1eix?gHzaQqr+khUlu*+_47^Y2MAEt&L zY0q3Y<*%SH<0k))02)_O;}aa5{vCyhWuSMK1w%?>Y%Q19@4-G!L>e~=SN+EepSKIS z&*(L+JiEWt0t|XQ9j6r;ViB=vreGR5)!%@t(8hoB4NCn=T3cdpP_S$OlN<_BO(*$Y zqQ_HqorPb-g3Xq_e?Q~}1)1pV8)jI0sFzI5ZL14H`YLq4HkVEaqyayfpU>XL`|I8* zc>J?SR+~tz@kO_h!NG~2XJ_+3Q9?~FJ;d~hb~sXnbXk+=Wzv_36^tE0@gsyXxKRsY z0XDB%YiSJqY8F|kfPZGE?m<(g9EU+d!urkCt19htbjR%IgX=E_MN$^2bB_KEbpUZk z`K4N+x9@IE2UZNIgMd7wC|qzjZm5wITl^@a5Jl7BK|-ck(G}Mv6@%#sVb`b)pM2F} z9i4xGqxLJ90XuE_CF*YGFCeMMOqo)F!UG@ZJ9oNWIDi9X5nw_49su1`B`GN>DCSWC zLwfDZ%Ie&)W173f1RHgDo-Gv_o&Qki)eh@?Y+h=6lB`c)VM??W7&A#i@ zZQFLcp64^|c>j0rS-zM%<=m|`sDgvVkN-)*I@Oh!AKB9}oF|F??p2z0d1b-Ds2Nkn zFvXmm?P5S~ym{NU*V?z21!S~VejTmA$A3fU=9UXAho8ohicd|0S`HsI%C@eC_-DWc zAD3kN&u5J?N>)0fs{&v^9d=^@R2|0Y(!4EL(97DqT{7OSO%I#}#e--f8KID{E%n^k z7S*RupUn|Rav-7t$B$oxD2N-3PWlh7S)zwqC(j0b*gXrLmT6k*tE|^@mB&0J2dv2n zW?d$fFq+#=Zf?8z5ZvH|jP>wWCVexi^4_9BLV*7z6dyFBbAM~~bJ?1DteP0e?q&kr z$nt05kz+^j8t8ta@nJ@IkDJLP{d>r50F%}X}k zjGY`8cT8r4**EnFapCvq7sLqr(W6HUm;lxrnYfh)_g|j>x`+wlfQZBJh zg>j-_HmHEs&tLePDuCuH^=>W0Dm|@v4o@wNrVP$kz^vho#>41s+jeC7xn_B7tP@07 zDx{{QI5e?xbKqx7(%)@xfQ?xVV9@TrDdbH*Q?n)vM@o)6qrxGpxc|!JVc{>_Z@+B1eIlzfHN# z^p^TnN86PkN81%X4rrwgSEZ7O1o0Ax~iv+bv*6+YMZ-VhD7p!X`WWNkPxdu}(w% z*Q&%0i!UKk6DS0Xo_sq>;s0L?PBRr?4+wq~5Q=*|(Z%sZ678S!;Me zzor`7CeG5-tsH4l*IrUu+mhjoSA4~e6-T0GmI;1LTyYAkcL?hui#*5GBpN|zv89@IVH|VC&BBbtHmel zFbflAVHhtmf&W}Bw2T2I7S@&OHg_&Nb7f1oERUjrx0V^FHXY_LQM5AEK>=N_W2Rvw z5)V2@&>gK38Riu!a>5D?bfbvwBSF%lyhV=)7()yBC9GarJxWs)3V(rr_~2AU_@q3M zv2hsiaWK7QWqt~@y}wXs-Sw4wfT9h&jQ`2)1F&F!#Q5>Ms{3oEBR+9e#M4#E>^Al7 zU6xkjFwnYv`(?mOoB|o9z&PhmpV7g=B35_Q`jqf8_s|n%XG`ox@6BKP_Py8U(}Dt0 zk}MHLXvk4|x6P+HImHLMF_Y*xG-zSyx(`3ZiIs7Z0G>Ap-cMCkm{KU2K<2ZdmO-Ys zn>YZ(+)+AQgNnOp7PAYa$c?PoGE5jE()z;C(IZE`k5+!DZzEXzI(TnZf<-*dPbY~3 zFOBy1hqF0hMHsDhB?uCefKdoosJui#r0wu;6!d>{xyBrpF85sa_ySKlWXzaSuDJLb z0lYH957i}XOVq765E5W~#^pST?!J2eJWp#EEk!?9Y$q)R7nnyG1IA!Fyb zy5EaCe&B#U_!=&TLToap)`uRD^atHY3aQ|qhn5ADV&V-SF=hVz`!EG@Y-~Q!vyK_B>0ssv$(6%4ZlQ34%u46(td=V7@8iZ8Q{8c{cGiKV`h#dKmK$E$jqbo`t=QBnXJ5Buf_=xkbCB z+%m$|Nk-PVRPdJs&bIceWMI{P)t&0ajKW?a0X8)%j9z2*v3(CQAmwfPJ8K=murj6$M9NaBvL9{S{At z?k665Oui8WZZAXngpd=|J${PLe*)+sLfh`I8=`Eu4C#Tpa&zATi%tBT{%}YCnCzW9 z+3b|(88~K4RqY_1-f3vr1H20PK7X+)VY^;%u;mI8 z3((<_f0^9>+Z7D3s@V^r6GM3f;>QXREAN{OZ^7aHo!!PI6wiL?fuW(u1KC1rAjK10 zpZ<7v>3jH9vrK0I?Ox~3i~(Qw3`q3QnQIF&Tp`%PX&PYWH?3a}rNM5ouTkFfrFp^< z`LSMr2w`VN$ecNQTN*$7P|_zdZyLBP!I*#oS zA=sLT8x{`b@CZs53u$L>p`(7nCeWaQgIXQN@{Y+^X;!9mP3SfKtMw=$6(=|m^B9hp zRmWyTH5l%8%y-0yb09wOmEd9LSS|0BWcq`OqPV!Y9p=2WB_P-M*uGfHCzS1Kh*`!4 zzxp3ui3lWNOi z0>p;s8?qh~7Kvy;VLq%V;-zK_0(=PF}S2%GGz6{OKJxe?&av_6zA zHGEj9rw~2@Wx|9C4)}BIbtGP(;_Y6(2?b%`0oWA=J3uE~mGkHQ4XVtm591tvt}TGW z)+38^(tb6ZYISNoG&!!`-mz3C*s}e4b@xXif3YN~7vdu(-r5ZAvHq`#vsBB>o5pWO~ zs_Yc~dG8l5emL1U<-=>wy`Gm$EIF7ubKf!ZwA>4$s`};}shB-{p7*9pLyzb(dnI&q z>l9;r@~)$H?C_4}Kf7=6-#G8n+ZiE65o$xn-lwO|xHxy;GoO-))iukG{Z;+Ni+$V5 zE`C#a`~Bj(&sdy&f##FoXWtTyulcn4ZTw=x*A09Z?6>Ib*)0sapteQb<_8Z8!>E>U z{b;0UpHY`xO6rOQJdX?TKJ@Bi$5B-MH_7;Ej74P*d5}N|1VU0tS>=|fb zzY5Jo0faX9n+d&3_;5HI@bOdHQg*XSVi_2RxV2D)psw?Y-Kf&GHQ=Ey-m*%rVd^evj@Q8=uKowlLBnTYJ$yaB+UWwx^6VE#w?I zm0`>X4kg25okCPPgsDmE)_rO!94Z0wtoIuAp>O=%PBG@Knlxd8`0uk9Ng#qD-gK6& zP#nO~;LbG@p%@RutG(V|%!;q_eOq>)IF|ZT0w+0tjsH%QERc5Yn`!zc*~9MD-+uhE zAE6b?iivNR)L^EgWUT^Oh^p@knz!HRPZ)_o;hR8c7UzECjB@fbA1V>6X>~67o(lS zRiP8K!f_l`d3d>Rmo+`lW`mZ)Al%ku8?+kMdx(eS>m53TQ`_@Ip(*>A@Ii#Tx^RI3 z@o$kcaf%sEGSdOEbY^STw)N`+2V^iW8t1a&q_gQD^H`D$TldRhZYFBTQt~nJ<>#9> z*+P%aMel(F<4{whee#L^*@3g3Z6b5^Uv!Tib1wgy=2CnzceuX1X%5cagK*t6>vbqrtND zNOL1f?V{9lpOo9C-@Fixe5-!*etlSbW65yYCu0}Hk=oHK!hhPdpG8;$g!<;jc6bj*| zvNcZjpRo}`r9=eq%K!DMWcc&oj3x+u#XJCAFga-n>5K`Zxs?2_PAinfk0Z8(enW49 zMEeVFp&YsL!w+kp1#Tj6%jQ$DAK?0M(`yb-J-LGIii^>yN%bd+Uv89)UW!LKfDK={ z`vv(Pz>PJ2e6PHYcVn@gORD;zMGh{r7Uo()qitJTZ%HLSw zn#s$@{W3Dyr1x58bj|d1SgE)7*rk+vqZ5zyPu2~}=cP||Uqrz)VRH;;gE8lUm;1OdnaFdbq^g8h)O;pSBUaz}Hz}-idDW``jkCK;Xnx zlnQuD=)2p#`M$=dJXhoIAE_<^Zk0`{padLh#C&!cRAPO2!SpV8c72=sBV07O_y@d} zcyH56C)QVFI%ORCMnu%Eu!;t~{k6>u$kG0bAvga)RH-renxOESQtdji0M$D>D=!br zuApJA?6LND`>c-(A$NP$Yf9S{j(D@EY&@1=*{U_7i*ClWnzKs?qy}E8%<8fbWUL9= z2{K3CAigtToY%j6?;QvkHo*dkGb+-o=^B#ZwDNZ;NWjE`Nt<{Qr zdEVs7*THaT0~@qt3VP5Ho(NF;`)IP6wEvSm4r1O(8PvFO<4hApB5EV)sELHo@Gqo$ z|E>HzLIutkV1!73XeZ#P$Z@qYGR>dE2D&GJdn`#3Nbkne$j|6$B5@a%<~Ze*&%Q9n z=Fat-)1~l0H{)-lBlL5Rp>!SR0~At61S|wDe2t0Y#~YC$QP0TaGlXe1 z;sCT$8r$L#{%i55Hugv302UB8sDkqB8J?HgPL|ws${RJv7rAq{>+Kz(E(xxUS7|vq z%rZL;Ea?sMW6wNbuOdOTIjP&SVlQ+*yf@^?70&>LE6d;x&AQAvrXl;S<}p#QAH5O2 z#V2O@h;5)~-$f_OlVJ9;ej{_ZnZGC7NyH|TT zu=}*6<_Bd-4InlT=Yxa<$sB^?32=E%-TM=u_eJo-jDue^*L;`zwff-P0cwXQ&zAbT z?Y@nGjAnWcH+RXP_K#m^{>Mo<#1MVMc8jLMqOsD1h&9xL0i?2nSsl(f|BZ+RHn#HQ zRCY{RVX(?2%z@lHX9O@9j$2u=<^lW9IcKoBP>@#cN`TdssdYoYtB!rHaJ;E1fOS!0xq-nU}qv$^6e z6y%@2_|P}0X0|?jzFR`VYJAV}T9A!>tc#){CDV^16mfB52@F!^_wHRo;9||gwTbn8 z2`)UAiP(lA&!s*8X7`vidi&tZ6Faa3QtYi&_N%~(0!rok()Tso1u5!Na`INXP(ve};4nxO;zwBw`Dao#HxrEf$9s9?0-cz&Y%{4ZT zjs8bvX6w=p4>Ov2835wXL-6B#KKC~+(nFTs11X3N6W5NsPj%8b;|m#5^-I4*_@qLs z^dY0ZPkFlpSGU)7EXi30hR!?q4%>LPS%!CWvIl32j!7P;?hiu^&R7oA9W5`aWV~?V+*3h zyL*e{LBC7{;qW`FsL^ft#j>f$EfcHAhn!YzC)rsZeP!Yp|4pc%VZ98eZjde!TAe0f zi7^}fs8VMFp%D2v<|>`t+3l5pi zsO7&;M|u5P^EhoWLav4Q7X3fI-UKe{x@-R*5Oq}48AKh86h>5rT)?eCaRCMeTpA`U z#U;Tdg;bEt9TX8qB}Kyx5dp=}TQnC;&D=mS7u>P3LL?=#+zZWx|NDFg@8`as-}Cz4 zulsdBJry$Z{eC{@T<1F1xlW$4$uj{QlheB3)kzj7f>JHVj2@k-=;f%Mzhz*Pas?8FpGfqp?83>*fnf-4kU6+CZJ39qauUEkmIgEmOJUu!u;V6Lit$7-cDW*>5OF)m+no?|l8EaB|6 zGr8rY?b)%TgPYp|OZ|lYee0GFf1?Gc!CV`bqPyG98ls(CNd#91Y4Jc_$+iQ0BkSp< z%ANqhM`wcjj@#J_ejS}7KL@v>Zi8jpycp}ZM*F$!s}9Rdth@1PpTtc6JX&$#_sEhg z5L=C|W-I01aUIH+SQmfw=PIW08Wvs*@3p)QgWh-?5bpS2UTF`kB6yO30F{5X2Jxo7 zmZbzN6x1|rw0QE3*9a1z*>BDIr3^7NJ#%p!;ij>v9{&;yxMsR)=0~A?VO4yN3~vz^ zcGrX0jqy_|t$(3RC&BOHaT2E&c_dn6V)vEOLe!d9R?Z@3%X~Or6mIbS4?aj{Keg7M zDVh1)QT!6SX((B5mJNvR9shFXm2Q>iH`J|sz&ZvOVn9IS-cPZFK`}aqCIC@dw*Ihb zNCus~3|AEWk;L zMj3r7iXnPg!-ub*e1j1wac^W`S8 zCHJxC8l_yP4SRfy=5#_y2^Z zOVV~Ooxa0aiM}W#7CW}+!c;ikBRDeD=ijp)06BnGu*1EY_lTVuzz252Eh>!IbfNCG zb~v*UCuU_1Pbl-*=L`J`B00b_B}N6}A13PuCj3&m11H-}COXk@l&+ZJ#!dchNKU>-$#Zz?2w ze$BvUZVI<54Y;{Wj9^k>!ieInt z8h<9O`uV16{9lgC9tGNQ3?&JtLc<{@Q!aj92)b0Ll{kOcztxubqpc%r5>1HAykur} zN}7nF6ww5k(uBMs^nkf|Ui+?~)7cJ61HkE%5qEw1u5a!i!Wz-Zlis9WnE~yV2!vrE z4Uv5uEip2OOd5%k7{intv(*G*Q_{3gZcHgV@`{@+Q%zJ}+yoS#<7gAo2GB$dFMa>L z-rX?|mz@zp9sK`Z4CsVjy}p5}!;E2}62ml?VlxCHK(g_rpHoT5YF3|JKyFG229$&e z>T=4}6U!DXh537JlBCN@sEw&7wk5pll5^+CLG8i{WkPF#D)%W*gByZwUJQZGpC3GA z2xEIV0cTdaaIojOAwd!Wq4F_th|=?<&M;>>CdH3EKNx>A3|Hy$+Ee;#B_*t`n!{IilL9gc z6o-^~Dqt3_n3Ro2-X!D<{BxRS^MG}1S#b9BD-s~X7-425y1hr#mdOLju=fveOg7EB z)52f9)Ye|s2RW|NL<>MltstiylDcoWm7Wx_6=TAoirXVy&TY@zY@o=6^ zzh`ZS;p}S?YzzWKHS00JK=~lWB_N&P%RcqSfHQp#8{Nc@7TLw`PoB#qMJ6B6*2dlW z$Xv}N+=7^@-IVZ}k+%{?sci4(G^QbZKB=kS?sdmFg!(o>gK%u=i&iDnp z42=rl4`?P%Z3pNPF5*~9?^r8RoD>nlAP)wG><1iB*d1&86?_t@Sf)i=#l^)Tdhp22tjyiI6(qe2;7R@3$y;F>EM~LDu}*o0?*%T0 zj0bK2jUydbC_d_&O&00YP|I!R185dmLk!F&_GyiOsNlIP-Ril;^x2XYVz{wCI|pom znaQrdUc73|iYkI#wv)+mabZRr!1uzFLD=2<7m3h-FpZM7g{mgSN|nT7F^oOflt-P5 zmt}&#KRsd|iWqsYSO6s03TYCzyIa)NiKIYy>9`Wgnq|RM95~0aBmfuNBu(DZ z3M0(k&$v(^qXJNn%k0hR+^M)$gz(yij2} zPzcH&)yM@6ittF(lecXwSY-gZgK@CN**QF18U5omGE0-e7%4PT&f%e_h+$P_>PjG))308??SZY=PzEi@vA{k!ltymfM!XqNLBg^FuLb#DoI zyZAXVeVmCa2*{Y%XH#joA<)p>v6iRoV~a){=%CkxMzetCLS>sI7osLjP4Q4eLWo_v zoO!pT@hoXlxoRN<7U*h%iY@f_kh|K6(VVzO39C7&1bp#$7OPr<3LFPFQxj;YjpUsY zOdOyI5oA(ER_s-khY1<7{+g@;OTy(2!(xVg46e!GQTPVx97>6&grkGBaBd%teV3d*{=u& zwOzY*mXPv{Fus~*CAM1tk&h=#;O}w(-tFGKsdlJC?o}`1eVAT>ePO(x9&NHbK_Nus z@f?29YY;R2@Ps3f^kdm@?o&8DY7Iuqgm0~!Wt}*@8L(BMe6>B%`Ddq=J!p^rjM&OW zoZvSwl`oAJt{`}Nj6=p3mXPT4aCtV~fA_4+=4ywVZ$Ks-E94nW8edTr>h97gz=4++ zB)ihG3M7Dnnt!G!lC85s?+&`+(rw~Jf;DmuW|b%C>J+)+G!LKU?JFDOe4jX0&V?S} zfc6||AF@sG9Nj6}{O=7JlH5R|6tT6R>zLv6puc5(%;Xy}ck8(+QFgm6KD+UzoTSc9 z1}?q{rNBGLm(gbP!=fhdolEb2_K9z9T7(XDjs4J-O1-(gnA+CLqc6mEj=H35Yi_O} z07*tnFJQ;(M$h$1H?%j<^AS4p@(N>l%=Ztf*!-u*0EyZx&qHaESdC&G^xYSI|M_im zKUXhc2k@b|@`<0bvWuM;nBSfH)>h*e-7zjNd$3q1?tkLc0Vd?U4}+iP`{~Bg^u>0N z`uj`~l+8^JmUHrgMW8MWu_rCRsLhW0N8^)~BP^%4`sAJLT9nJ-BnAq5I$_ zgl?g3c~dyt4Mo8#4-JzQQW<-A1x3QO73}ZOK&h+Tl3_L>I_UDTlYsNo&f9yX=9X~? zH6;KDvXjq>*c|TRi_}z2qs4|?Nh1)C%vnpb0Rb1wtpIRE>>1tJK(%H(5l1#>;PAek zDXV!94QwVG!DAF~n#LOK48+`oaFJxgN#pJ4p2W(C82kfZ8H0xm`TO}?V(niZw&*-m zBZH@urbK#Jmdn&6waLG~)AW0VNd>_^6OgYBkA@zwR{@v@U7;{?M9SV-ah-ctf3x!f z2eUDN%+yr(aMDJkF=n`QCJ6jGv>HG&-O#s*Wmx8*-&8&F>Jap zz_2LJ-$vZwhB1P2mAu%Aii)mY?MMNEZpzp+i;)`X@qt3#Z`aT0@M-e5yPDLk?Q@x#X3_%j5L=K*5X;;~Olmj`!P zlLLB{4McoyF^i*1AzOt|#ErxglE_6TN9-doA&CGik+hD2*!lat7-EuwmTGM3m8}g` z?8|8UR*yg6Ktb;!R|X-BW;PV*SHc8dAAnpG3(D)8nfYZ}Pb4OgreYyNmS-D@zl3jP zx9-NCe_@=od-7W)t@X);5hXrFF(~iF79^bUxN`u1>oTvnIfjC z+7Yl?DLOG}pO=<`y&Md7v@)p(I7>Knc;9 z9*KE*%0pV}Vh)^QsSm~yhR?i2$?srD@#6%VZZ8lEEx;>$?9RomDNt*nEN$HuD!`Iwq>(?OIvWftsF}FMYrC39cHXlbH3L6*pX* z)%?{X9Spf3tPXi01V8%Rqa_^t`l|?6AVAVA&t}ApnnC42$8a{AbEGRc^pS64EvuQU z-7%ojnuBe`#CAN6(uhBD38=U^9O=Xf3M97Kc;vDvoNAHPjzjQn3|m+^t4kuBQ5{og zNDF2>OksR0Eqij>*hlW2{FXNQYMxutZ+L6L9p^HD>DN}dl2-AD zT^#nwMOeJ7uu6>!AOVR|ib_33cjgEV?r@cJsK9t#C{wwZZ(f%g?pfQq^+(jju+H7- z>(E~#^~|I7f;`}oZI2LXs-FHn1{5rkV$HdX>)f`9Sm6%kJ@t{5@9^D-=n-V#}ru&+Iu z9@nvhBds)?gpe#1fG*ijz2N%}XM4ishli(A`TX;A_|f=p@dK^hRO>I!5wc=VU@a}K zEon>$1&YX}!&$u09rPiFhJ|!jl)nW~@i0Ll|BfjY{yXDt{LKgvYZ_{TJ;55i|pjuoH`>B7ywB za^=bk&>F$+lrE#aa?-czrIJ3ei518LNWmko%c}OH&u%ryt50tP&#Ljm!=rIPrvIJL zuI38W0A0X?a%9dt@_j)0G4jaVSy0D(>#aN*5EkHNx9y9DDy{m#3O~cKI|^%EGsnj9 zkPRnBs04>Cp6bsQzm>~!waNK4Q)sZ%?p&$V~pt?c44)U7~e?&{-B4soT(|QO| zoC`!YsEPp{Lt%CP=*UYHiEqP~Q|scr{fd!V-r#mJlV${S3H*UT2ezGeC0?pj!*@pp zQqw?-6zLWY>>u5cGFa=M<&;l3o-hv+G_2ZZ11u_Rq>VXum1D9VNu zop%lq_CMYdt`odRH?(pp;S-~%PC#`92W995@Q@LGz(>zthPPEN`5}8r8tZ8TWi3X zr$064CpQ>KhqV$@RuU#cB-H-1SkNJ&Ctz!Uqm9@~vk^8m5l~Eh34h{zM-|9_(SPks z*$p4S+MfGDyD&zCx9xQP6p1=}&UTXi;N%;S2DFxg-+PY>@QUB?0wS{^J3}big@?BzAD z25ush>G;u+!_=o(%ih28Wn&Z_n<&Q`YE!)PJX{*}C1x=k!bO-mcdl<3GEWS|ZuU)4 z;#7Z=^>X+(JEL#(fO>OXs_{2qxDc$2X#`HDO#Bv6LR7QqFm81Pfj zb_ovMY-MD<-FD>P0gZdJZr*yf(>IRWZ6&O!hFDNQT#*+6gQUV*^2h1XJH>GvLGjq( z9}u>hemHVB9Uz3Eg0TQgM8AWaQ!ux&lAaLX0GrJh!kSPaVfloE-%A4O6nYM$N4HYB zw{I_Yl@z22=n-Jlk0P5SJiY??iHtw)9|9vkc?klKNaP10^K4)q1BB#|&=7WwKW2>^ z$pgEb6X0sNla6^kNH|gX2KsG-^t^&~vM=%}paTE?iop6Syslupn;`=erXnfTSwg5d$Mk<#)j?{KVdP(Y(Q~_n2INH^5*FtSv*>L;2@YtiBxjhT%3Zv52CIGlr6j zfBQ$6zE-VUH}*cT^Iz02r*umae}4{pA*-Ia%FN3&C4$>%niC0o>HV;BlCilPS`lnS z6A|vhL>(|nj?GhR3(LO}DTlGO%)6kQOoxaQbLDO|B0c%RM$`2r8F zswIToD;~lRs5Fl#rzx^B5TzPjxBw;0U(1M_bbWnldLZHVP@h!2aH}If5;>9npLk5L zt$iXV90y zX%Oq;ZwWDMFc_#gqS)(@w$N7GUD`jHraF2D-(Z7mJDYHB9p1GV2kDDr2VJ3M@_NG} zf44%f6Xh{X=<+XSd4}IZQ@{-?JZVGCo~T&`#@_VBa5{pD7?}q3IP^$}hcm?vVpD}r zxwf!|G+=Ip{a}Ujrzr`&E!~9x2YHvBnE{h5fL;HxWg9SE9W~?U@rcK4@Tuvf{I`qC zGXiX+r5mmo6rNkQ6g{YF-n{t>0wu$meKzev2gCd}COQ0XUfyXIVdJ`u=y+=y3Jmvl z?bfVbjTa8iC52ut#q}KQ@fczo8~=WvKBLu?7L6-Er4YZBMnd5BM;A*b$x}F>*c(iBF1wAcjB_xB%5govNU@_W5xTXk^wuF*{hZ&}qW=>!~ zz!2qom=pJc5|#`Y52+#S9PE-xB#)wFz{^w;2$CeOxk&#>I6rgph_Y_`QDID&Fk$rc zYePwB$x!AGuPbZFaD(wg?aIj)9q;=V3+#DR=?)|hlhRYXpH=x40ZWfQy*v=IaZ!k7 zrN+K`kvu{Xhf_*-wGM;Of-Gt7XA>`(ms`%nx*)Kx?A*6+_0o5C8tH}-#a6Q9$=fEq z*V?XP_oPBBh|x?mmF_~C#cBcnz=jD)WDaE}0k-EEx;n;m*H{i=Ac7WI`p&kWZi|Ro zEG@#^|LY00#c7(2w+dH}y$A+oJdbWVM-s^%@He|{2M|VSQ4mjWW-x}aZvFZn0PSp! zlXlIs=wQsFy&V13VTo1{8&&F_C;&nmC~5l%T4cl+UYfs89|(1myysvE5R= zoRU0Q0LM;+VSB~}i^~2fQUzU)PvnW)PDxXEf>ol1NNb}!1+&1mK%{(k(K+GLg&68O z2LQ_0t{*ix22rvTr4OsUr1?r`RkZ4m^0TQvVupaWAb3a6i-Bjf4|UL%cW&NjamTYv z0Q*?;3fd*TM5)6`mrf1#Crq`XNEm4!eh*uxCjhCtKNh_6a&3UAX@n?e%#;1q@P_II z|9&JF<&lW*LrIe*Y;L&(HACIk3+$+jf7Gst_4-ef#DL=1Ccm0f9~kI$3evHyjUZHx z$7-r7*+YV=3xO=aof4}xLNoBP9(5VQ`Zo5;MLVE|&Bt6t4d^W_kKx6$FGfNmIE?kf zLd6ki_rlfw$%G)U3MOeFfm;D1ILS%>OHExHLGQzAM6AQkYvc00ktde|-;d|U^5B4_ zeQ7xotRH?fkP1xN3HbOZ`icWa+YAf~vzh;n9&A|jg#E~l6#y$dv{v6cRF+UJOD1#E ztZExOnp@C=E!uUi$&h^j=TLcsQoR1yZ7|?cVNe6$wNQny>yDD}1400=LOL?X$E0fP zQ4q`T*SIMsLSbg>$QoyM*Yfp7ARt#EjXO+iknLVfiMVQ9lluMT((}`a{BsIBcGDO{ z*j3%Y_S=OTv!mgwBW0?Df0fq_O@!g@ZOT#N;J^wIbD&0qog+-WZ2p)ZsYk!niA1Fc z{m}C%@@7OMZhC>c%}wf93KMFy_tuPO<$@y2vJF;I%|%a^ZsF?`;U2wbvQ>aCVvZm~ z`3pr6Vij9Zh%R_>4}8ohLohZ5u`-&I@kN>irm+n^Tk`YGLnK&Ts9g9vE))PRXt9ax zR6vsW1Z0&BMzw#P?$ zDnBp8>_;bKU0O!y>SXlIr56Vw)oHnH&>|OoyK)$^flS?~7Ky@tv#SMsr5T}QTe_B_ z{f*E){8;Jk*};)K0>>gaOVYg29mSz6XRFOW6cn4laY8>oKHY|1EV{Om@1FQFm?i7$ zXbxVaB=K4b?Sas`o45BRFUP#h!-su0U0`v=ru1|)Avfo~q+FtN`X}lHFrTGP*Y z@_cTZg?sWC{z3Kx#b)5u_=sT%x1?ij=UYJ=Bf;RdU2CAsn@3p-fPQpA112>TYT5Rs zPvMe8k1pomafy8YM6=G849s z&qj-B8*i4wmAP^yEJ;HI;kL?EzN}KGH7pc8WaTW$9Mu0P)*nk_HBZ$Z#jxA;_C7NDL72xRm47_h?f|SNgz2 znN^VAC+4(%YH!XvYK)i?{!Nh;TRSSb-(vtFK+H9e_6m2TFzo;So1Sv3yOYsA!@J-1 z4QcpfV*ZM$Ap&T(9)de^F^sEx@?3Sy3Y%yW$>s*;WM*bIN5y~ZmW^K0iR#uf9@>o>y7FDs%f4|RPnomL-C}>h!()__#&kS+>6qa^7c4k) z;^XGM{ECJ;8!nFw9e3QdhxrodU!!^JTebZM{bo0Ao0?j6|ED=0-+y^D?iU}Q_AX8{ z?HYV@^dp81I-EUZTixk+w4uqdFx7iM=nBeW7YqqnnX&lBzI=eANzSD7htU_qUmTe# zt21IEAsUd~Hr|N^Jj9FCNl2D(ipAolu(sbZA0`xcGbVhfQ&@ny+}OyalVd=LVJwzS z#ztH25Ta#uFw7I1Rwqoj!$t(yFyLHR8#NpMNQz^3Gi>CawaQg(tfbVauct#ZVca+r z^SIASLnBG^?EEL(e@+;!g}xOjU9;@T`xU0pEopm5133jdp#dm${rrwY@yHDIv&p8= zUth#`Xx1R{rnsrYfY)m5dy%>jTJ(aSNw)vAOFFj8k8K$^U(RpxH)vA!Vei=S2f*xG zC})q{H{VgLsZzX+&6IB(B|dhS!m+jRYPRf${hwQpJgDo3=^~$X3qHg?jSFM=s8k{Y z-JMc)OO&U+N=o%|ELZ#1Q_-&j%Ve=ep*S|nlc6NVH@Rt=#ZU8)7ShWfHL+A7xL%3D z9q~i?q5<{XgjRFahY|HJ^FTMTjuHF}$MTFO7~f-Rzvw?-9JzNW^{IS#s5hB?1BI;1 z%%p0qZfeyzEKugyBCL67kLQ(nIbNS$UgYkygd*xU%9~{;Bgty7CVjcF&Hy6sy+bh$ zWmSWPuno2S?tat+%PUmJ7>W5XKl~c2DY^zDGVAJCE6QVKkO&3;;Itya9Z&dbfQ z5V(DW=(B%vVYLHI0s$j2k^4%8xzV>wmO0FIjLgycNZ?RG)5}t>_k3SrlF||Qlk)4y)(BntRt&2PWmhvgU1=kDc!<)QY`h^b zSea#0@wG!JZ`cSi%sFt)_~Z37{_@i3$vGB&h1-iXK|3^9j#!g}p$=We7NHKAl{Ci( z@R7L4L!1Lunia+9SD0S>gnjQp%AE*W&sdsI<)fK%8FWO?`?qw9@PAUwsOF8DuPB~;V?xUD2hp%|@To!#5?Hh4QvW1@AliCA8|oIR!9y`%C{@)HaW~q9 zI-!#*^peR<&s@6uLyjR-yaK#tQj7loAXJU?0&2c0#yM#`+1TK2hExYB>rlUfOad2ba zh3cPzu-uo;9nC#2g*R~Pz)Ss~FAstP=PMU|vmCdKxDbO&BQ1nm0%N6Y_uI@t=0%CA z?9C4sS^YFrRM#H*PDLmSVg5cGJ?mA%nDBizbs)X_k_Mu+VHT zciF{A1FSAP+D*|ip@{|?Ux$XvPs&@*_C)AQCnzS&`rC^m6-Kk$Qp7Zq(vLjowY*kS z9&*Kt*BHmP53*1KAvC+n6#B}zM!`!=x4>F52H#|f30w}nID=;Q_3c9&G{T3)Wk7U3 z>j=>KIVm?QWZbIp!?^+8tN2z$>UFOC1A+7LHO{)(#ifi`d@o2rKx7F9U4)%rWq)eBK{33l_}e0}Nw zgiSJd{3kqWUzTq&2NblRa@Nj!{zEmFs^%5P-ptc@I|j&rvr2Myn_x*|Vbp`T+~wl2ovG|RMmC3d$oio$qMH?MClScBN0 zcJVYBC&Vs;_m7(MARmAX`tn^Hfq@F;yjx^i5sZkFzjy+#Cpg$Kt|rZCV<+mxbQ^Jg zQukJuai^(3D#_A#)$sXRW>)$v#|db&tPDU(QX>Xji2HSnOI^>2`IsujgP&<7_HMR} z=i1Ye^2@C@UBq8A0^0I05Yj?kvc?=E&et>*d|YIYVw?UcGYKd-ahyVakJ++0r2Ipt5sHJ5 zD0D$SfuZ5or?!;OX>OQ5U6)MiAo>@2{hA@6L@DE3iWh`zNrP$TJTM|=JsGLeB)jFN zdDkhX-Zt@hcOE`Gmn25dtV3r-ayj3w))e%`M8Y6;(=D$R9O@*qSiwqcT|JZ0+^&P0 z#Ltjs*1J+Ba~D=|(1B&4^C7o=Yi7&p8b8@ud-k387xo|k1iMcoO)i_xZIq;{nn!>Nxj zElKpQv#lluMk%kzWgy*k4M_~8qeedd;`c*X-ZU17LYiT!eSqz^jP*0+I*TIGIFhw@ za0DoRbt{VZ?%Bh#jK>MpRS6XFG(Y7OB}H(yQv59Xl{`Oluy3o%40I?*zoCi+_o&H;c)%w zo3K*hH`+jyf~#=~fP9is%a9g<+OS3LcB*Yy{mOF(v9r5CiI|GG0?n`>;{{R7E64E0 z){dN3PtNCXhL)Cx&>)IP@f+%U0r>C}ggmq44GX0|2WH}j3I$@zpQ&i8GRJlk zqP&Du0cY5OK^OG7w_~rQN#i8ibxVcZaEV}EM4Iy`BG`ZUgLJNN`CPTHG(y)h*xYoL z!%#m!8oG`qvhI}4N*@8a`4eT7xI;4@XzPyh`{bg)bVZz&MM0$KcXB;)0sI*?r{p5S zX_Qxk)DmmiOT22sh6dg7g;NI7aDkQK#+!MzzDstZ279i&U!YZF2a0|c*(s`g~0VnFh605$mZQ9&*EQ9&Q@sF(y`sk!`3uwYM7eEFj0RDj#56~!SH zvC#@EpY=?l>rEVwvu7)qF{~!MDdo*<6i>YB0o-TFrNSc0K@dJ@yLLsfTsPY7Qtqfk zwL$}B2U!tFS6e7jGI<~ud$R{KVGH|8pPUU1%b2RgW2KIgFoSi;{heHnSG@v|qgzR~ z^km`(K?Bz8wL_i4T!T}crRwRnL}T9`Sw?SR*qOtcJ^Rpxap@DB1Jf*~lpL!!rh_|) z-i2OJQRvEsir%~+ibq4gc(&9o{h}bx7h&E2E*nBW@J>b(|C?%=NTlLu0^@ubafz`~ zR_!68;#dM=+{XK9yiO4aez(EY!reiz&cG$xlM&2MKZyiXPi1>>v_Hm3WNHbX5+MkC zvG}fwtjsXnA&C(9nAoUGp&05sd`;Wjl$_K1CqLVaZ%-BRKx~8J_qgl8nqJ-9fAyAPYuR5xPKa?p3f)Jxo`WhecD= z&(H2Z9~L82T-F6Gx=zUW?8iy8BhQ^ZyRbW3s8Ns_nHlXDpqaKv$(qM&>e1t&Xj3i+Asyz)$AqEYJ6}@5 zh)zQ!j+&Ly+xUGF#j3vv8pd(E?7~5_i%2$}cd&cd9~p5a2gw}>$S7FqsKW2z8P7Vu zvx#3EBal)Ej0hf#WoV!A6*>w~Oii-Vd40yrq&Owe;lc{zF_Hi# zRT{Z;HaRBZ!e{i9(pOraS)P6x=5uum`DRK<9tD*?heCsqK^dKf8=rhJ%T9R!ag7XL zuqakXEn}M-#tX|+^rg`8xKYKr7`MX*gW8|wEbD}Ht`D`blHsp5bu467vAgdDrbtTr z;*m(XZwVo1&Bblyr`Y1RDgUUjtb`2)CSG2GK0B;wph&&iPeV-{l!TT{DxbLAQ}NK~=Y4Hj)F#2QuF=F7CZc(cw9elb*& z-%?ju&frQWa1w4sKx2yKM#CfJN3&CpVKcTwR*#0VA>x^C&}>Bd@P!(@v#} zWxlniVX1zN1LGR60b_JtW-}B!w`>et2pkw?qbasK}YO{*$cFlXJKAacY>3m<|%IQ|-wd9*zNUCBs;G zNafFs7kiZ^{wKV~rL;)4+jd-jEb18|+ojg4H ziH!PK>)&blqE!B*bjJ_E=F3A0Zs!<4y+rF}sDXYqQaX1hX&{r!%4gOSuvIqS;wd#) zJ+}zmw35vpm{F_Xw=nk_{659x;_a?Eh@n|Hja!P{O`64`s5j)Mwk)d>M&=mpadm`@ z_zG8-NiZ--70I_AE9nVwz+coAPW~)J_=O59PZPM(rsAk6{)=;X#bV`eE1XgjAsD#G zOmg+=+_|&b{?t1D1p-({F{ zKVlmmKrP{mzsx1^{QMaCCyl#U`@0GKPoX4J$DXrUYHE3x5bn!-h;o; z*bn#~eKBp7*I;@?L>_8;)0VUz(WQUTuV?h_+?g|7q=Rwv8+c9eA7K=TiFl=aNZVKH zr$Kqht8ZBQA8sV*Mvx6Lip*fU4UmT}xyd-|%IIW%TG0Fm#)hL5TMy-%^g{rukn6y@`=T z4OFF>H5EHav|-#vaI`YBD&#g4Z z_2IH}(pqxamaGEfI=`uyx3DxBPNRRw!HJjjA$MyxAE|M$lbtKZ(eS?vF>v{_IJhl> z$v^9mdsDE&BMrA$a@bRY2EA1qO|ts=IaWKf|5K zP@KjA>h>J4Ce4x@fvl&ULiEK;IdxU~-FMc1EXWo4{O>%FqbQfK7W$R6x5+1tf0o%I z@Dlh#N;DSldXGKz6Awyek`XsvLleg9EdAGqotrJ=*UgX$MkY`h7pG&knr`ZIaDO<^ zo^L5t5OMPMufO&iI=Ad=u{Q~>QC#5H_a#Jn9ML$nrHul~%dDJ5PxCE$$QlP(Q3J|E zRnG9UD8l8Knu4KV>nkl>3ikR66h1@Nz4szsBza&KWsv$X9ruap?c663lclx{Qzzae z@2(1I2|Pvhr=Y?B;DKD>W*+Z6(119`e%w9+R>S*=1Bq4csA7{iOltAsidl+56j>X8QxPSv4S4fhliZNzmtMt3c2Tos~j5jWxvX>cnN84yjeLQl87* zUg7D`LFRMtyPUeIKJuXR@IB*DlA@(xVq>sxtGe?UUit}p9Eobsh90>OHyAp1ChtE$ z7I%rLM1{l(R40F>l)f7X9F3HW#eS$!_ydrm&z?Rl6EaYRw!uh38~S{DLML)O9{YA) zn!|%_hYcq|n)Ce#S@vHj-W#%V06s!wyy!!ZjxBCf=mizFmrcb0_(L?6aovZ@`;7?B zSWhVx4V{v*D!|oY933}IIdqqXm5#_3#;C^BUk=mDr9tJY=1>Yh(K6Z3&=fr_KAg;C zsNDz!Ap~cdr#KHvLC_-D+@yxW_#6~2-BcY*BPXQ;m%e#Y(n}iPYN>0-I=%@l+m_@6 zDYAoOyKRsB{Q9l~)Uj}ks($RSFr3|U(?N)^ok9fY>Wp<Z$2^hdBV&$JBmPtMpfCA}v53ao z7h8Gdp6~Tcb5DZc+&ak;vPeUf!&$ddL+NGa3F|W2tUmKT*Q1Q|G*?jWO}3dN6G0IXwz>46yhtZB*%)kY`6{ zR(hX8O3ia~o|rGOpX4DkBVfOPqW6dR+(vsh_tuj3G@+X`3%ta*=7)fagzESk`^WAc zhQ@}D5>#!FTId|nstGkmgxOHj4VXf)i=z5ad|7`dx1u1? z7f0xDsztH}m0{30*a8Hdu>jzB-V0=gl)4Jz0n>zF4Ju(M z>MR*Bk$Qs8?nIo7nMVWc8Y_85;@!ijFQ5NwR7o@LUalQQZa+1QKVRd(pCMwTBu%KZ zTcmT~kq67%<^PM&MdfR~d-oQr(fxnQa0$?b|Mc#?(Ncdv)3ylRhW>zlo@VeX8pIRE zk4GKy>&|cP<0gsTUr2G+?$Q&Ud?U4sp)Gqq>J%#+zvXW_X@A((`9RUtnlHUtnD9rS zgKntlx~~j!2MmfaJ!Y;x>O_VW9MShrWy7`0E{~-YjX>|i96;7qV_(5qwSOVHLJZD| z61u&sB%-jsY8)R~X#Qpnc9QWI2NaAGmPt_lPd_utyB1^Bvo*OdFa~q`X99_F}wtwKKfm>lL4A!OkLGXbUHlC8If5;^l=Wvf@w0a`PljkR2j^fFy!-dIi*VY)C|W5A(4m$Q_h&g?LY-c=MZ* zBTl15XhX*`OydxK&jTO$P-i=pe!IKMHCT)(+&31{TI=T&jDNMTS+p!iS}d1Q$Ia0mA8Y6ZhT#oTeO!{Wal#(&Moyx)QX8R@XWmUYx7x12yw{Oew;eIVY8JW6= zTg#Z(KVm9`q|gnJEhF(UBa@h9XyTtm^Wp0b@2C^82W6rHlUq!2r;-ZceSlPyG%u;{ z`IG0IZ2BQ3s~hR9*)pshmYo#Z9iT;E$V5IPMd{T%twOUDdX*R}93f|>HBtDN(2$MO z&KM}9dD8!&)R7ic_g^Jva}tj{Xrp)cmd)&tIQtj@6kQwU+gwZX@ZUg@zp>-SqGUV? zgLu#7l|{5$;kh?$I?Ce#h4q2P!Toln&cEGm(ZJB|ypf^XE^W9(Eumf**z& z??NKORHvOhe{V^1SFwA!gr{#aQxZ+Iuzsfe>CS;$C!Hu~NKyRd5cIs29E+>_5h_#q zBH{sQtW52qG~${lC4tK-C` zHg-DlV1v}0>9$VT4dQ278Wdk3roMMGGCamlgP7{h&H zXktN2rSUgFY|^w^#GuI$F(r1cw&r?-E?hiiD~!^fR9rl_ST><1=&JTC!=3lyzpgp0jCGSx?gfm6i*b>T&?6zRnL?Mo@c zsQHc0bjeWbZH0wnA%U7=jNMo-D9U~3{qt$aB;w95$OcGv$6)eB4i>atiM81^sb# z)pr|t{b#}xMajGHiqxX?Ps*54NxO`Q)T9p`Ir1=o8YTEPE~YfH;P*vo1;S%f+V6s( zk=IJwkEuG0N~W+>6_EK0s=KUJ43$uGEvKPaM2+gQm(NYRdqYFD?)BV|L3p!A zrZ~2K{rV6~7=+Og8;^y7hruw5{)p_D&L8n^h`}8;e3c-@mNm+qirdnhvx+$G7X%+v z(XyhDmK=exD}r!1Ds(zk#Gb4ySmvPfoWiRF2uNSra`7nC0dnYVM{%5C6QMc!N=fX& z#+D!V-NgimY#2NU`#TEc?sLmpGcm-TnfFNpa9QH~UGoIneM z9nyP(=`DVW*QI+l8J>>P&u4MEHHWYfAlf0SEqhhSU4Wr*o9K3?e*e`1%WNKeZ~lLx z^de&Gf1E@g+X>DKd2Q$opMLcE@mg{*G0X4FmNYiE=(Z?I)vMr8 zq-^HZGksYTH!Lj7VWmig26Z0u5W%aHF`kxBO_YuMVfRA@_UdSw}pyJ5gxb=$5IFw#ZITMV9mOphR zyw*5?RKklJWzrl$G$VVT==LnIJ=G}bJz7$I^?6IQb##wkx(ZuQevS13Kl|(od`*i4&fWiNHERCHM zsmstM#T86_FbWnE=5IxJLN0B)GN`EH5uz*V z3%%6n(bs-5$#;X)gz*j110wOs9%YEt`|g5bSb&x9;{2zv%PH0wI}ikIWrJ$xAE zMc+lkj~8ZrH-h(5)C{N4WV+$sgRyrnk;x*NzXaP!Q{+>gylr$eh0CTi)w4$2$yRv~!guS9$RNU9z^aqs|)##9I;x;7o9!fZLD$@1B#QZKt zgelz-xR+f`wedx^w_9<`rbsaQ|2qI&eRkw1)h+YAUMqtTn)yd>401PCQo3Vhl@X^x zfdfa(Py)*QtE*jec)UHg?bzX{x_spdPA&GUA&u#t^M8QN=$5g{8+HA5My>hERUuJ7 zxW225nI$a8yqHXpJ9VD+8gRKUOSMQ(Lh)0(|BKTi68KBf$!dBb;qGFvQ;iILtw8?Q5&p`AmSDAGW43&9(QX?eoz9~P?X6Yo_ zA?X3ZqNtCy67Eg9b37dx-(hH*sL0?#GPiN1+h%uJ%WT1%1ZUjr zcDEiKn0y0o0BH)aS2q{iwO_FUjG?$=`g2gG?+?s*WY;8e$qGJ|8GFguGGaP>?^a48 zYJVASeg&FLL72X8AI9sCD4LI!L9)oEXqkD)${K^(obR7})uz}2tD)RLV%FU|{^c`n zfQ)=XmHfe*0^M~2kWl2|5_^d{JLx0wdSHtKGVUN{(m6B)+g!lb)g(jzyQ7#g_3vNjs>!$2*DUg`vs$?Ot&^nBfO1w=$&H#p76xc8NEhGz(W6Hb zrx=Z!fmlWu6Pd&C@ObF^06U)pxW(h})+YZiDit|QN4*@eTa#S?aV6p_CV<#dAJE6U zTum1cCXb$4cXw7_g%~E^7~<{(uSNC5rSP}%GK~?^vXYKLo|{+)1SO&cL*l?;6#pH} z382?P)wn@r7U@zcQlM`>y=#x$Ks4Pkk)mls*`Vb6ibaf3pfg^)?B6#nfKF!#J&@^=#_&7A z>xKO0E*(*NLrs#iD`&w%nw#c^>5{ij!i|Kmr<|q5O8bcFX$Ik(Lu8e04qVxQ!FbBQ zke&k!G((}S5Iw?QYdr-^k{kB%NJ*_J*rYLg@SbdiX*f9I<}`=VJ)HUDb+}QQQByc0tiH z_$JpRDHXl@UOFFdW)J#BB{HDeO~K3}-xU|Lq{5RGu{ZW3{kEOObgn9KTX-<4Hx@4F zv3Iu6d-prL2hhNwz=V=Md+S-huFT2N8*amd_x$XSAf~w6n?e~o?%bPr7NO&f{e?Xg za`fF?y7YE>soln>9FLV+T=>pUen3gbnYc`Ek;nF%%&xG+q1~W$UfeNxHy}|lB&Gdy zUK$m2ILSr|Ro{k8Kxz|xYss(ruc zx09J76!odCXiKbk%r6)IMmlUTQw>qNN*$>1Satle6nA;)cH6;%Lr?qbSKiFnu(ci? z9D5ah%hSJWySBr~0~foU=LpHdDt^!ppKLN7rDIPxct}U&U8}^yfs%yyji&Aw2#~1j zI|uXRJ`@GL%(aOb2jB|tU^c?kU0z$;WC=P{!NM8yd6Cb9!H0nV$;3lY(mc8j=aJ3w zcgTL2?lruMYS9p=W{e*lxGq_-4TuqXfwsS*xEY3&o#CP{2XELv;XKX2N$E_r-@BMy zNZm36kzY>|UX2O>*`UG|D-^;_4sW5?zR7QSg5|K!5jjiwOdKd&yLJU`8T~a5$q@>% z{M(Co=Rn|vA`EOPv>*r`nVGx{c5-xB<}EZczC&lLUUAmQ%X>KiF&${fW~FiZ@0{y; z0S68lnvmLI01t~%r{CC=hlW;~KMV#gg&k6+Qb}ST$@K({)BH#$YRG6N8L`rOl_7OMe8FN3dr<-QpT0%cww5CX< zPWZq;eMV~mr^squrI=zqBr{j!#(gBL2R2*9oV**8CCb z=G1<5{ndZ04*PY3WlPdDul;Gw7Vp{8^YX+icU_7MKUP^xrX}AE8_@8F7Gu{`#%I3R zd${`Oy@NXsb{dsE{Pw4>KH4QiQ+KZn2w7rsNN8&6Ms`3mbEmRW+y>auwm8jcNXM3+ z>v2xfX3qr~bB{xFLsqkgp391%PAoi~SaQ*Ihn08%mi-wENKzs9f4be%8=yb;zYzrg#{^idw((UaYs`~YeMy)J$!X_s}i zPC}I?X;^$btXs>~tjy_wR`JNZIb~Hs+e7Z+sihvWzzUw7Gw?V zvrUT1PC}6bU@if7A5UsJ#9AVTMX8iKI4#+NJoCF@(Fy(W2bTYvAs28Y{9JR~{Y{u_H zok;iVPkh)w4zaPZF^PmO)&U6vL^6c$mnk*n83p0a3=4?!u}l3$goLYDmp@}Ku_dIa zU*N-eecyezios4)nZ00c#gLzke`JXWcyw+#Z}%Jts~UY1{myk(wr-WLkd~jQP}7za z^ibPhpRU!$S3+t?;RWR@YcE(EkD4_-ouzHV%x2eIv9TMFqPv8t-YH$${DKce1DCb} z47W&Qjy&>UPG;TPTMPD=5+J=fv7G(ym>dlmn{r8p3vwg!|C+bSn~7M{XdN9qmlcOH3oLla!}2ZS-;QIYJvc(dAZ3M5g3Pq@wQWPkhGjP2k0nTsYk-LMq9wG!skI3d8tv2Lb_`iS*&ClS$3tR8O zGUwhG7B0=A9SBv*9ro8L4-I}Hc zU4g-v?~~$BjB%kF_?Vs2Mzc*3^B9&)T;`Xr9X)#+mrJvdu-wsf6_G9U(RJNkpb=oB zd8Fua($>kwdcVMn;Z0Uj5y09)Bap7M zx)4Fcy6KGjyYH@zYowx?x#;pcIMG>h&k#S^X}W~N$HZVXN1lwk`0@*MrFDViq*x9f zw6q)URFSFHo1JC@l9N7y8M1_UH2J?SgQwN9)ccf=&CB_M#0Yj%SI#oGyEIXhp9Do% z|GO;+P|GXkB6AX#dyNBhQp>*ab1|k(OZJ|CrUwzruNj;YM;BwNcOCB_)5EoUIjLeK zMlYBfN^yw&hOUC_zXv!JVpxF>GUr!NNz}C{o65rvg*uE!<1Z)VUtaZ0=#KRzF-({T~*PNpQwQj>mpg*brVJ_=oQ@cyBDXeTa-C-Ud`-Mm7v zGn39^2^|UP*&u~j>P7;+goTd0+*-$^SDC;x8H)U=d^m%_AY*)RI=%#BXykqp{|L4KOYCbulV$^{$h7Yrnqq7Lf!e~X%ek0WF|3-uL_HFtf#A9i9qZi z^}<-kGe!T`Ev_HQgKXf2mv+tZUd8cN{`E6D1Y?Ud+yR3&v|G#1O?puViWLSYXXVOR z*e5LN$5|(m{dl=Q@x`TUI%MOIq#TcA?rxwEE*KTueDS*N+L3#}=XrDSw?y{ML_PGH zsMUb!vT0fzU2rzIf8*=UO1L`j)7-z`@Id`a3M-K!%g!4T-HNw+)lo6k5{+vb8i3jG zCwTfgYszi#tMj)uQA#+XqP)z1|{qTJ3ZXtcPnUcGu& zHHPPrDc{m*16V_GohBv;9Kqeb?fYi4h-eus)c5K0nvO>c@5m%jnj@imsrcJ+Nr}aj zIUn-|=)EL`e8vlORYNnkRDtG zED(htWkOUXW}gDGwIFklQZEq>xshR9ld8!VK{u6&($*Z(_Hl zRwDbKIC@d>iL8+C@`Wng70o zyHA|(Z(qlAxy6%i9LJ^g+=q5yeew$mN*TMG3))hA$)OXY^6gyR++<1`UJoYy39Lh_ zIe+X%dvd%rPEN83pazctl4Joxd;?CVXNq@tbgPB*8Hn|4@fn4_CxM#_89&#!cPHqL zzj9H&*&51(tZw^C$%PwXuOV9@9^PI;kDz<^zkqmmY0wgcF=zwtbiqvBaE;1depz&> zG-at5ldLkULr)CzL7nF&9=EK@@oT%c)Z&O}UN<%)F1n*0N^1shPByx5 z{>5P(al)}lhFp;N0oVotI9{C3`5X*)OqD?TZ&b7U%gotP91mK$AOx{b%ovVTa1fJr zWnGZ-i?6TW5<@Oz**9cnY+$=kNK<$P4H|^6asu0U(c+M)^!}4@gp2+Y$ED9GH|VG~ z|KHyW=<_yyDInyg?VXl5w(K?$BjK3-6Z1d!M#b9#3w^b!U2@!OIy1}_1sDp5`#>#x z0GzGA@d4(r>CT!5e&wPM3<{cG=BH1ro_A`Ut6IUW^~59;>NH=pffQPU-5g$SlTp25 z4C>5X!tb$zAf9Cm2vrxAwv41SXiwqr$@gBxu^R0ecb7&@F2VB2YvtGl{O>z-=S94S zvnAw_F3$)q`RG85TUa9J;ayfgK!cJd7e)GMhDDFM9%wS|9h6dGlwLc1X6p0HfM-;p zy*a`|BB0Vq?-m&`m_uggX3hUXzDF#?ZkUI&zv)@W{OM>ISfw(LK0J(06;3+~`$`Eb zIJB_!rSRs?&ggdg{Qdn{;@j$iHQsk-jV5lg+i4n#OJvS|&&8T5dEsG`t=N?2E^&XK|!*cg3ET(8Nim%Ogo8J z&4R-r$yR|Ija`fwN5-OklMAjtvFUixL!Gf>Srz|)A4*1(DS}2*k==+g<;xY#bP&3C6ZDQDA7= z7~f&7i@zUul|R4E#~Di^QtG+gyh{ARw409CU42u zZG#5+1rXC5)G3#8YLD&EsZ%3fl03x{9~O0HubPymtG`_c1)Rx>&>|qwZAHccxYgY&7u9$G-oIK(Y2V&qAM~gE*9hwvC$4BbM z`m2qLK#O3qc!H~R)i@5C&-=F+E5$KLMVxj>EZ9W{q%0AG#kBW~F70w?_iV=h1^AT2 z%BU!20j=uWV!8FE{=k+Z-3qJX$6l0Pq$q$v04`Eit2c&zs5`J0sXEHLDEnr{E^q0x zVTdkX@o9TFb}><>bot$vL7tB9a%xyK)zP}6bm(^-`6tTgB9>nPje9$IuMCnV2=b|C zw9?M%?x8KAHfLn8&X6j5`d|$4gR6|3y z;=4m@>N%s7$T4LQM=l`Y<$*4aM0u*XIKUg4MH+Mqr?KbG)QxFx1gr66J#!=6@-;x) znq;pO7%X~fr#G|>OU2BqmWnT4H}}i5L>OjVtRjc6$Ute5&6A>_4jMS{1)WtIyfQ!!k5ePTt~DPflJp`bd{(vcwclr+ z+C7Q!$?t&p2g!u|_<=w7-=IAG0Hvz2&Aw9VALsh9CFL{7^1|xkw9LS6k9Xb?55`Y8 zPr$sLAYiHx2n~v< ztjAL2VW{A$SKais&g2NN+%W+I+ZwC;9R&=%(s*a|O|y$WN%2lD=2v(iSz$WewO6kf6v{Gc9T^$Po*(XNiZ>u1 zWDjx|Zy%gb?I}Z#&bLZL0u*~R9D7a*5h=>T?}4w`%X1DKHi%*Wv@Qq@GcrCmYN5)@D_nj6W`J=gxui$2<++bm+zfz-s8CDS~HY%pj$$X`>^ z(y{q%^`~@tHY(IQ8vd}jT&6l5RwCcrM`A^m@CoeNx)b-Krg ztH8Q8!^H+9g;$XQ)8njk0xd4%Xo`qPhznjaCT|BT6wSOH6+s3aC39>wrv!}^6tpW4C|Nry+p5OC(evkcI$yVrd zB~n2FExx*AJAJZ%4OAocIfB|+;5!76V~meATTzjxrK=|EPm_P55)pr^%*?=!Z}b*E z`Y2?es|2g7pVfiScI_doydWnA{qtv4t7uJbzVddaspTF@VL0b`{ER6%y0Lu%8O@i0 z!JSzw18DQxf~uF*ok;?RVRdbBd(NP7&$%K~pNInSn8 zH+K}99v|KldWWK^vPKG)hTWsg+M#9}@sI&2`PmfZ{Exb^evwthw_^A)laN)i;AHx# zp85SXC?Ossc0A-YP24kOITdH>2y;RA-uxF3+LZOvL7*JI{`_}b*_-W0+1OICHPlk) zVu{m7nLCNg;zABHBOi=57Ca`d6VoW6s4a2ZzquXW&UF?c$2Yuj=$jzB7ceIjU~cI5 zYg+X2A+^*VBCSywUZgMK@2)KCkfwp4!YlxhdM2QVq~IQwwB;ktU^d}t^=od(bQH!! zIg`s~))E}=!&`Bb#Wv1-DL$R|2V_D;53c-}5jV^9Kd28N=3EZGUV49R~GgxGb1*?i8S^Ur67qMxG{qLvF94@U^q;N78C0( zY&%`Lvmida%uJ%Jhk=mHde0qrrZVLDPZ@Z&RV0Ft(DM+bRi?S$V}31)aWVE_gCym` z8BiBG9tWHYJ38<<9bn%~y)(5|M!m3U_TBzJ4}KQYOdt}R5ZR);X5yJz7)0(Az>5~W zm*y_D0|*;-8J6cK+N)pEIZgE{^J_~41)k0=rQD5RB()4Gg3#-6fnG28r(Z{StX~V= z4@{);N$AK; zhA@w+einQheDHT*+eP%a8H(J;Lnb+EgBYq!gDTihhKh!5;-oM|qS!aP@mKb*dvTBR z(^Vp}s=2zdom|pakOvmKu!L(zfVjrAGnbPt|2zgGl1sR7CO;())T}+7 zyNKEb|(RO-lsCQ%mU#a>a z$^hYXSaq>qP|=VF4$U~dl}4qg?w~P-n+;pgiOM7{4X%giU>QVQ5i!LkE3t?k?^#$2 zRk@Le*&oo;xTTg2Z2&8lSbu`aYUMX>5dI-br>$Dg)RR9hVKYc_{%CV%YIO#%SeQY` zyzvZe8iJI}R5(N>m))UEa8OgtKltvK&%(0nEU}T zIYaYb#d&5R#ZGJ^s7W{yGDXtOBjQJZzi>{;(RP%!;vpc`d8p4eWZL!u>v&stSPvue zIe6lS?_>sOKCl;bk0&F;Ufv>{oTVFv+11>-K8T_!`;rOO%)RTsO0(T+f z&x1jTZQzwR$uMB&E0u_*!Nh~-fA7G4#^G>4RzsY!9^>G_ctbB9AOmN>R@~`dWwFU* zZXUO{rhfM|sp&vZ=cfK)5}TNMoVtA>c-Be6IE2q0$^c6Fn_ywajEB(8q7a4yY6Dzb zY^Vr*HwaP^Oo0A9hi6Su_Uz2hyi@-zYz>Y@yC}rRAt~lbuQA&85{K^qfk2J?Nwyvd z?UIvU?|RO+&9h&2jUIZGkjc4!&7IG4aQqgc?*CzTL;ei{0R<|;|0fLnln;%L+klBv zw*jJ?`!UbPHJ9)tBECkSCuOV{?v zaKov+cX*6>+|H~klq|fS^Snf+UbY-N(kp?NCg=Rp`Y}{pqJ@Gj=+42_LP_+A3@ z1gcIi1to`c?=IIf1EW`|SpVf^nUSKs)X}m1kAF1XV+M%!^1DV~EC}!s)wR!Gd_DIw>?jXUxW%En_1qZxrSkD(Ib$BnMAvW&`lgyc%R5bOrkgL` zg;u|)LI^d)5b}Yz-)P%p622_ zb^g$3^=qLO9jOElHCt26mNb#w4))_Hv1x>)Tw9OcW}tJRli$*<#=-rmW|3j?t&7g< zOm%!$-W%Uln#U%SDKC#emOh1g#^e_hM87fEL{V2 z4|gc*{45j$@hfO5yV%#@a9|qFc+mocnM3_y<)z_+`7-Vm-pdHQ6#T;XORMN}Icm7F z?OS1-M$I%P@!kjaz}TYtcdXK%bn1BmDP^G+2;&J<7brB&Gs_GvLbM^Lm;>|Q`c=!% zM=J3?t5VFGWOH?z**jXCRun7$GBl>DV}Xd!zomLa~~k;09IW_Jpg**JH42fr#NyMQsGmMq-C_^%)Eq-0%w1kOUO~#n!6L%90n^X zW#OB6Qmp&DgvkJ#DAPq;GMSkL(ILQLb%{zgW1EC%#fL>DwYBwFRohM zJ2i=gl~X8F27`Mh8VThL+WgtwSY~M4fseg6T)ZSs6wam5JW# zlaMm=%5G0Jfczr-7{I+tA}wrde}%HYnET-?k{UMuV8y!LhO!&5>pDxWNW#ID)ApMZ z)6F3&|00fNpote#!7VqW0Y7GpBRmtnG$SsoTPZjAYQq2xv_=M2kSWXvup%PFOEcI*W(6~hnuB=yejrjg_DSr=Ww1{}qJnx$I)R-YZ(vrz9<`PjZ!9T%J(Is|Q2XOn~ABt+v+G zr)XKuVlGZ9cikrqlOJBMskg?{Cj%ei?$_vVok9ANF=wj2Iv0o#$xIVmeRr1dL=Ejc zcvpN<-rBr*5$p&-|0g=;u;`xxTRBm5{U7zxSe_0JXgPK)+R3_P%ru~Bb|Ddlr+OU{ zmsh(hYlr7$Lg?JTY856yf?~g>T}Dfa{EC1r zdTQE$P~W26M5`CYErnlPW<=f0C$+*myK;rD|2fNSU%!43iJQ-q7Bh}C3tVQw!vT(x zK+@aXeQ9Qajm>izlv+c(j;FG=yu1``nQw|VproSNo=LoHW0(z#HGm(zt%Cp=axMvj z0nLIo6dXZ8K{9L`P!fL3L-Vw+M(?GPc20y63N>MHe$sjEzYH=RIK++A*9KqO_@Sd^+LGY&v_LmI(71SqDK)49S7kvxE3 zFA%b57Rkb45o-cm5x~&4321Fr56fa9y*Y++0I*bsK0=s=!#F zurLN}oUE)-Il~r&Y45yw;!gH(8!qaVUUH$-8-K1^Ay%rLr=rD2jW?Z zeeT`{*V)|F^c6IqURiG-CJ!9{ICWl&5)swsWeB**`)7q}CSuSFja0y;L=E&=#MTjg zzFW}KVM3YZUK1)pK-zllM@r^B$+=@u4loQGjd664z%1u@q%e?Q)a1~oom$V}nYi~7 zNAZ)N$+p+wlw{4kdZ^}5^t)zrwX{NXrsOER*U;GP0(X4QF4Agm>YTzpfg{t>Y~|&T z5K%D{VkCGlo}g`QRS#K_cHNpt#ko0b$&}sFLBRoR;rm^xrrX*bNBs%)I0cKHJ&2+w z8|_fhLr^8)iJTdbXR6HLRPnRV=V_h+Ubn*;T>KBVxGBveo&e*)1W0xYN^j z1G8x+nJTqebtE#3bsnOdy~J5@S08jKq$Z6IwZIF&Ag>~)302T~VD6Pn&0mq7prWsA z62W6;D+g2VFzgfW(PH~Waxkp7!Zrk?V%1a`j@xwgr_$9TDAyBo)!VHZNTopj%a|zu zQ-XQwNYxgP-Ny(GlJ}12)1+T7U7ok4-7PK87*Pr_L;}8y1EmW1S!e89b;&VgZEq^> zNQFq?p;_%A1{-8^S)n2DwXg3gR_)%Veaf?#z~8&Z?IPbnt6yjspqQ#Y!bYFla+oTs zx8it5%}M_5nk3p{+lx_crAboMZ%a%W_n00pg;(RP2&II24o{{_?v?^sXDO{|@N5n% zND+*#P`^~wiBqRoQva!&&AG>>%dSri4%P^%O0s^q6c6(x-g$L6%qaaq!0bkVXz|f@ z*o#Zfa7r)OM=ae&q^Ga^EJ9)I2aaX?9?l)&S`mvmH!_MVo~Mr6$Te!!>5P2j<%fR= z(%HQf`oNRsoQOgW#v3T)qLiR%2Gg1@vk3()xmc<9c;-L6m(u!{dg0~^?%Hd;k$zW| zJ)^So3RN!#Sfi~K{)d{nax04vV9g`V=$i0ov^DxOk4*;=S0x;H-u8Fv7-!my(r@Qd zdC;r!KxLUadbAJgJWG#KbvDYu;El4bG9;@`lr6AO`1?uQmpT;*g(zN-Pv!XF`NyH$ zL_lErxc$BP-+C+~=q<)Y6SQ6wq_+?%MazkSf6Uan--A4hBEr`AMt{Wzr*h_}5<@kh z?H9CB`J!AZL>FlzM-p(h$dIfgOkQ7GLPz-B-fk)CilnV7ndh(>owU7+1BRK^hE-$e z->3lMu-czzmPn3L`SR8u;X074 zP9!RGJxd0?#zh7>k?0a(gE)rrGo(2;0N0@o#o1wEHDdqHsEPu@CUWYYKVB|m(u~iNm^c(sN z$88Yd^As-ZON&Ccs!EWA|Ghp4kv4oiW@mK*g*tWh1-Yp)%AD{n>BFJY=uGM=O`T$_ z%llmETN33qB2SD|nl^=a6Mh%}g*;3iOYvvVjHTjtIr%bzjfCKJpuyUUxcpBegCK7_ zJtMfx;8z3zKA6;jfs<&8N3(e6qT^`J3B*-6<>{z?6Y=n(u^4oE-1td%I1%tiFiV%| zr)5D0>+CF z_)eEL$9PC;#G!8$c3WE9nIux*klV}}XgotO@y+MZbJymPUk9&U!Q49^dkG>0HWUhX zocvLzP_iu>CzE?{Vay=?AKm4`Ht@D6nOQ4D8-In`?sqIf9083r7^Ny>hj>+cyH7)V z9mIle!TVjJw_$1cG0Q(!1WcvX84(=N7`l#)^kmp4^aCRj5<=S!!W0s}v0IPhx2Z=| zRC9}&r3)A@F5plS#JEke26sQU;$>1+OZfw%C)4cB&5*z|;$l%>HRjCX2+;~hpNAyeFmt~c9ZazE*M1KaLkpj=T&E#tR*LlbH<-TUf{7RoT?wMqZDSdF_iW3S zIcPvRtaeqs7)WC+_$AZ7B-hPuZh3zze9_61;jBO;09Q0q3?manSe5OR80Fx&>%$%(~P6i(}$by_E!6>(^na%kugP@ zi*tZIu*`22)VE9oa?z*w{5 ze^-W^95Dz4P(wVs@`+yWZ`o1~V;1 zkL<TYf&>W`unCkUN+vC7DASfTmZM2~<^LjiotK%( zOeP+Wl6Vq{lqgfOSRsN08wh}Cy8ss3cW-aM_HE}p&y$OFJmb#?ZGO{s51Q%GES_M7 z6mrvGop)A%BBOEu<&;p3P9dnNpcw;YL=F(tl4`5cf<^{##Dok$RZ|y5?nUd_49w8+ zysM(sYY(sY@_2Id4V>+F<2_H>``D+iWUD`X=aq4FcVUe%H1l>&9EyC!#4RqYIkJpmR!;652GA)&Ah;sC4Bsgm;S7Xs{<_S!yEIh-=zA;Q|@7td6f52C?+IjCqxQj z8l{vsL28aC*i?Xt zGtSG>IUmJhl$Zn&gZBi0Xk?0DsFI8ht9tY7D1%)+x|)uzOIz{6d4KT>m1QHL9+Ei>9x)j=2BW!sCCgdw%lnyTV=9H(OrI7B>bV57k!v;{O(Jy*jgA zEH`==pIv$OD>m3XzOyym-?ipM+7s0n%CcBm&&p9sWQxq}oI}JerKW9*vd<5gff|?@ z0N^PAL^J>uF*AGs0GK(Y)O8&Zg%Fs$Dj6E0D5-)dv?hsZpb@+J#50c;&hc=&p8d_y z(M_<0(ZYuZ>mQeKZ@vd9Wyj;`aIuG!#3BIsP%`&TQJ`@Sh$y9GW<&%J5D_yIk(sG# zjM0*z7zIndu~b3Rx|Yz2)<=*&v+o`_2>_TG5$OT@ufQn;LjwR20W~H9fRqv=nHiYD z1BeJph$|Y3x3`J&jbJ#Xhq5|1>>Cln&aUD)J{@Ew~?V>zXVm{w_ ze|rB_=q6>>cW~CU40(hA>U|;~!J>$12eBsYICavsol()!y3KA=kI! zE8ld-Z&E2Iwp2XvC;5ecGC%ay_TA7PMQthgyyzif8zm(LBzKAl4FCjHR1`HOgXpu> zjpelccHI6hc2|71!IypyOZT<5dFGH>?M-d|7d|D7L}d-H{hkN*#x zf8_Y(E2%vZKdF1Z87>djp4?np^anpoFa2NR_pS*RFnlP#^ts~cuV}VcN^>d zlIp9WAR>rpW&q&5ch0Fm z7cpdx1E|HQ$*@IKvH_@TtNqMntZTzZCC0xz*?KLuS?14;R-bXjW9fi*?@ko`;?mG4 zCF#VFxj@WQRKu2?0GO&05i^@vN(m8t2*G>DR>;z)L(u4 zsW>PMyF#YeP4wQi@z4Ig+kTViq+4DuKl!JFNB>E4_fYru`Z9@SKIsh;niDA`I1K6? zXC4u|t^)w)96VrVs)~rr1c0h4D#&PNB7z2v830mB1gNJ(%nShV1K>!_qKW_j5t&(R zqKIT!?wASb6f<{SoXxAj>Z(B2|g8ts659 zId|RE`)0I+KAX3@S10%0!tMZY=JVD5`9I>bzmx2tgZ&P*8}*AU_Xr3nfzD*_?fI=A z=huG{ZodYzMpB+aVV0_@it0jGDu#<@?T zcskFE-e_r6iF{soUl~zUo)co%wlO6;rR2Em^$WyV z+Z{=qwsl43N`$v1jnIuRj*Q)pmjY+z=+W3JpzUCzo2kBwF?%I@~Ppa0eQ^b*KkTE38f^q=j*ptj z#75=FVl4W_nP;BR&5Z_jPQLZ;SMFcwP4`*~viW%Vg|EZnhxV>*9o@OJR_I`$HO^eI zlx61-b1-YAZAB8Iu*bZwh5!^83xZ$?H6}v=0zg$wDd{OhA_gQ8AtFHPx|mX8hfAv~ z-gAtxscSSau)3~Ht>5c0!elZDnOj;}0iX2fhiUgalQvf2(X}VPo-aLnyrZd#Fx?%x zHp522)P;)uJf;kSGi6Ey=uNGYbSVXfr;56kf@4^ssaELfkEBO+qUiHd07_5W+rXhYLYC3;Jlf2O%r2O zQP1q1H?tTcJ7(tqAjYVMrv%W^R43} z4VV|b(O?M_F-GSSaR-VJhkydjt@h4)d)vF!{k?2D^>MPj_a2XM-pwBBt@@*5w|CF$ z_QFyJAwXm}oPik(`q0a9cH@oq6qYIb6JlpnhN?>kQ9Tue$RiItrGwO=4xI&kTn|HpuarooBZL8sL z<&XdF_%~N)voszj7V76^IVfmlSUmM;@G8IlVf*R}ymi%OIPWd;<M`-QxX*-VrDf3V03JTYT!eL%uEi50Kh(=shhE5A{K#^)PUGI=e?03132qaQ?>J? z5eXK$lBodYwwkoFv4_wr7C7(GQkVQYlbsiE{$8(%EGxMAJfDAF;%J_n^_(w*qA?X@ z!GjS-fC$QYbDOcir5&yW4Jm3*%PEj$<|Rk+KAg6wxXM zy!O+-bM4Wn%oQCv$1X$Xi~a!7C;Nbim?)SrBeNr7GXnrKQ`MA`s)i6$HKhaq?g3RK z$U{ako+OzNv~5*s1Zh!PFiFcxrN6Wc$Jh67z3N@;r0SNklZEV8+jrtcV+Oi9b$Ao>7B zhKNnqCJ`h;CjQTmOjTksRflw{Jvgenv2YAa>x*a3x*~_PYj6G~q&syy>B_UkBfp)k ze5T#A$=$bEW*nAh4HNf`H29iy5=bHX$ymshD;L+?x@!H-&dcA@b{1u@eD>+VL!W@U zJlUCvIiH7lHAWMY=n)H_OJn)sLiX61gQH*ex4xZM$Mf=wy^nsixj)`{_cpsc1D{do zQkTk*Ru|4c@i@$?^sDdBU;o>I+)Fq<3`_l|zc%>TH)KB8yLm6o4@#Q3EHk&rF7pnN zK|lpC5`hay4uDdO7F#wAOzb=WimHgDlvEX%iP-sogx+~}Ue!bd5y8Q9I#HFfCl-RflK7MIU0TwJB`8)^IRQgt(w zi?IG%xbZbmhwUNE5A4>}ouB>v{@t5vm!4jE<}2EM5Kty7U#O!^B zj@<)hsAfK7Kx_svB@rcN=ecWY{4dPV%n*zSRg;)F4+heuI;Lofb0tQu8tAuk7`!R9(HpuP9w>iD(T-AIVV>PLI$zXp2o@cKKk z+Ut!5bt3@%ljD;jx6HM}(py(lV;HV&_)9B*SMI#>*VOEy=0*AF(xuOtUz^_Bb4>Gk zR`&APnI?;M0u@4QtEM*^4L|y5-M**q|GTW&Y4XpEp8SKl&UapUV_|XRg*ox8sS?9f zbmQXX!NVVc`Ifx=|8}>(o3+Gx+Kn2YZ z6A%z9u&J6PP(w2`a}N-ah_qeT#%KmUWX$ZGBX+8$s%AD=9L(qQlwuZwXErbZi*47m z4XQCyRaITrEw3ytoF8^_Z+7b+v$PkIQ&`K+ejd*~)s1Hd2h-}f3mS4_=V#=i&1j2tr^YV_;ppbG1G`tOgfSx!!~5Vh3RCJbS0A zF-8@&Q(#2okPwlGn9<0pdN!X|pqgh{nHSFa)U~Q=51@gbGEE}nP6Z(H%svZdqyWUu z3{sL)YT%q>X6IZwB?-V7(M&-SqM9T`V@G6?QZz6`obeE-4^-@0poQMI^>Z#LoF7VrGPBX7T_L<$2D`stN$~0X8K>Xqscu$~%iqo7&{D z0AUd8+G*Dvu5a{UAkFSu@#Ou8G3JX4k3M^MUT!yotw~JO)$LYUju#d(H9VP`SlP<# zxVh6i6SbHgjrY1^+Mvh(^t1o{s+_Ct9JlxG=RPS`mDH{%eOL{}(0MPWYKlaL5M%7R zPGcgX%m-$+m`*jitCi!H!&>)#eDCJ3oX-?i&wb>phU?A!V`6Kqim4h57o_nP zy>x;W5!-onLRmg~;$ukr<2U}75N}2Iv8792Y2Agxx84q3s-yWRTR`WJCP$8$^3m#t zKgFvHIK39H{B`^OcU;_WB%k%4S^ng|DIa-$el#E7zEaJ`<#53eiPSML12X{tI-g7x z*g4PaMWJmv&)}I5Kvh#pc8Ul9k@yrMnxUGhs)%I03=mRGrdnjdd!JHj+Xl=CFs0OW zjjED!#p=>%qu=fPBHn+gkRyx+{mcBs^HyG(pU~lMXY;PGE~gn`71aS{=sc1WLj`2# zo%75L0ICXLXd2tDYby`rjWAiFW}2o{4puLn$Nks#ZhUWTu-~@S`e%yEzkP6LF6tQp zkXHwJu|jbD*Sjx#XFjj%eD(6@eUuh!7x(FfeDHhyl^Dk1>i0v14{f zqz2A~wv9110O|>u3@v5s7=VbtBsE=(ts{2M)dT73YBsCd)^onFu)NeC)y`ds+b^V( zce1dM@DX17vbe|E6P!%ui<_(Yn$7Ia)!kp!vBEU;X>F99d1Uiak@qC=WKZfYnM*5c zOCdN+Q{8^|@cozPakBFGQ~k{+0nfyJ)mc=j{E#3x2p$ay3{bV1;k}o>=b#p8i(b!X zCHWAtGK#1n;3=R}rXs29A^VT0*YniV{L$(?&z#390{((+JeOqzJ@B%wj4cDJ2sn z#Na$3S`t-lXdj!N>vE_j(oMtSAU}78)>gX1*W0}x$?;p=_#_OT9bEonUV7@_&b_Vc zKZ9=X>{37Der$UJJ#&T2Xn20aUH)`feL@bJ=I8{RbTUVTJdB#T z_gI1mK;?Z~w-X`Xzx2sa#=Y16r=Gsw$i;>AFLlGG@BaE_#;I%3Ye7D1y2e?G%Cvl8 zbm7v%<%i(-%JesX)xPtCk?UsN=$I~@|LVW>n~#sLU){QU&-;RqoTtol@XTlc>Ku1T z#E?Vb^IihiwjFAh5qReiQB_4Gsv?r}0TER-iJF0`rj%UnLkMOnDF)|42qKbVLD8C-{O~*TB~mVsH$$WT=Q42cE72u!Vu5e;4NL~I`b zQ3U|!gLBRhR7{0ZN+OZaoI^)OV4#X%4hRvYNs=V<0llA#)Tx@(^Jw|P!s6OSABX$t z#$Qbie(hPZ;$hA|&Wq1B-KsWjI;;9?{o)L6Rj=RLzapqkR!Vzlec|HrV3nYoj>pou z;4@||%8WCFYTNF-(%gT&#ab56EnWUJWFOwWy5AnRouuB%kOOJzoLcUg9X6@Kt(U&n z?_t-~dC>=Uij)_Zv5A=I{e89%<}TmvJ?Q`WSP9#l`IM6U-;w!AtS}&vAO+V3~%`p%V3ZQj!Cmj<4fIXmy#Oz!^#IEaN5<~)k7-P}z(J2Nnlb8UE zm`VoAUh%)~kcp~iaJtGmWV+}q6K{7TySp=)nB3bkGAJ@Sou zoOR=>DV8VE7VTuHlcsKa=O5yNnpb|HS6`fuk8tgg!KeONcIh*n`q}YGnoe1j5D^T~ z2tGiFL=b?P6z8^W|Z4@g!TAS*zG`06!`!h+QA(qDAzCei=XuCk2h1?x_vL}s=_h(tj1CYOT+b5 z%;PV2|KZB<&#oW7&B=Xi^;3WFp|ATbo?Y2(_V!1MIWKV61IUYBwkC;^2r`B&bKZ$s zOp%BJJ5^0xR1pVss_71E36fmaOnp0MlvMV0^O4c!GQ_*x-Iws-Elktnx+pGvWAM;( za&qtXn=jQT_s*?7%y`BP&K2i2BEEOL^MmT}wIFen&b#8N?D5}`&Zhf!>e&I105U}S5(@qn!jhp#s;{onHLi%yz-?X5of+5A(_M;z|HzgN#Y7xFC2 zop)_DN0XI>fnze{2(HD&-haTHY%1Qt#2TqmSo2 zoSYnp?w5siP1m)svUIuhC18_weqFuy_uO0yInMKQz0J?^;OYBs?he9`@`2^K!;a$| zO@L5UV_W0+H$QeB$T2aCp%?%h^&Ts$_xSU0RTY6wrxcO5di=Z zLkL}p2F7533aVfV0;T|JXke0JY*ZT2j!65%P?YWL)~{o|O+~=PbNve+r*MAzo!xG@(xw4!s=WibW>_=DrW@~<{}IfBVgogX4w4+RDm9VWAIrP#wH@a`LOBM;-^u#k1L&FPOW~9v&P| z@2Jg*!BOAw5UnsV=PdKqwN*8rBcgCKsb}kJpBSCr)apN8`^|q?4~6iBMsXYF8Z}fk~)_ z7hH-~J!%V|&L8{jE*p&x4tQ*NgT$R-6O(jNBY^WEFG_aa%m56`Ohq+;XjGZEbx9PW zxqPX-urZ&%e0={qWqdo6bTYko_6vVr9hJM+4+flJIZVMjsY;9~rm9W8x71%5I#-Qf z{O0(*Uv-iOmp{Jxm4D*~7Y}dTfhhHCnt9jn6()%Y5WozOSOE>ln7b%l*AbC(j+p_# z%m4rpqY45b5h4;1Gvg_CiXi#{_khL}V?;#n9TD;asv6tQ8AuXjM(3hR)wW56oexf4B_g1oUpVcP$;?<@xq>wxc;Vv^F^Ng@w)MF!uG}mb8bpl{0i3 zAN|nI$=h$=|A`xRinQ3jyfOGlj~AtDrtRIG-5X8aEsQP<@(-O`e}t`SwqL5>|JxAX z%X8dqS5_YSt+4s|-PdmSeVI6)CCk||j0OfoB9gj`gRgPEzS zX;M{G0aE}YVqy<~a0(IO|0g2$Kze|g%d!LlKwv-sGZRf>qHsz?MbH#aL5iu1Ne#3= zNZ8$~cV8DAYnF%M`O$^vx_yu1!qKRmH-2TY4QM|2)&3#f{nn5FqV^|c*8l8>zqD8_ z*zI;%vK}*MU;%575s=Y~A~E?a3n3tpm;!*FO3Bm+kq}YrlxLc2tTa+vyZI#VDqy@X zP;OjWKKr47v-b8sw%gyy{9daM^)|oA7d{c|a&~|KVYHMJ--|mxZVrAec2q@Qj2>Nh z_<3*_Cb#DnyQC8!ag-tSHHES$Vw#H`d6y(YY&}6Q;=D@ZrT)YHht46r_U_OB{gO<; zZ>&D^uco!_zV+*&mU-&crXA7JVB`M&!NMbJYmaZ3jOeCBuC=nrpgCoVAbdcD4OZO^mDM%5tXkPlnV+hm2a3{q3qP1A%BMxzmV zFQR}XB4(xrF(wfqL}P~tMC6zqk%6fS0hk$>n3<}m8Uk=i(kU!#=4aPKc~T#|)ZP3J zAKi4RtodyD;jd&5eX^Om`Sy&Pm{FHf)ijM5kjt{7%!&euQ~|)u1Vlxmii#>QIZ#Sn zSXj^27iT-)o9+BVNViBbrOzyW;v18@WFuKjfU zkAD%`!y3c#@BMeh6JM5tYU}oWl!PE<9s(1AF|z?6IY9zsC5};IO5S_;FA&iMe`;P; za0&s5n3x?Cu>u$p7=W2`bSiZ*r4)iEA~Q8rVqzjtgA}{A69aT!kXlJmG-_fd=a>mX z7JRSBvOt7j2Qt3e?Z3v&4#a62g^Hy)EG%q%$}K)ivSP=z%(s#pPg|S=U-;DH`;#lL z-uZsE)Tm2ji=*t}VYVVoH=gYzZ5T>v7Y6?FhcA9KP;9qfoWJvzp}SfXbl7gLeC!)Y zk5un(7kM5NH0lX}R1=yatAa$uouB`G$TOD(c0mEefY^nQnVE>FL;yfdrh*7&sD?z0 zhyb9f_JFD~GXSKNM8tbvmL)noMFwV;J`g1)217Iz0Z>8&)s!R}2vC+aqhU4OemPFB z3sf#2<-^Cy^PkuISvO_`R*Kx?)@M2_@-_PYul}}zNs;wG`^1;Jt|HnR1u|}c?E;b;l`80*2heg2- z!N^e$txOT}f<(tkM*`vQgzD}D}3?GQ|KSOb*0zk zHiOPXM9z4rzp~zcV#5`O-OU%{e4MgPKKEr>cp^`e^v?I^FZ}Oe=N%W8nrwj|eP-~{ z&n7Dlwob(L*<}{f(jZUuJf+U%J?f1b%w|p33+ydb^I42B&-1}xfX=C!8i;^sqff+kn9t~Fe&i3@~PrG|RcX2CPMysDF9{#dr zmnOT_{P3uR4z*1&i6L?DSw zGypRqVggBWDg-vQn38F7e2Pp3RZ~n+z?gx(F&mm#Vh_DuaKoIP07RJ_wzJ9M!7ugb z+7cZGo3m%>tslq5<@2BSOCN`{A-hd`d@L{p-zM-Ub$jud4_CbN#@6?xIA~x}SEy}| zEiZfy5VNez+)6Xit_g3w^J^*=WtX z%#zk32~m|$5cgmHp38y)0wA&@@166=jtC`2NgbWiWGd{4IRG#cscMX|ZQGO*0OWaY zW+IYO0sus0=Df_25P-l;lSqmp5m6ZdK}{v5C{fMOh>Z!QSvZsXbZ>V1mzuVTY&y@* zKK%#gpQ!G(T_<(5U-lGxqZqP{)^bXSD%bMZ!SFg2YlwEhxd1`U%#>1A1?F;-sO@U zW9hI|QF2jXVqE2gCkRdD<}(!R@?5Q&_t%!)x&HjdPm1lIL$BAYJtO7$qbql^8Ot=$ zAhSHr+-ULXr>H+o`!65A^L=bvH@MV$?2qfw#{;=6ZOe=QNAuPTy_jZgJIzN6pZcxx ziO=j^-yfeOUo7;?A}6(2qek)p@_q|h6*c$dEH-tms?NEPWiA9F7PXWT03a~{5|Q^l zs;R1oAfTgD2w$trGu?~IXNg$z4L%93PwcEk#j_h04CCPT~*DR**wO$vbctsgPvPhFSWXHa{cc( z-5v}U8r$f9^v~ihpB#*}Yco|2nIUnUOIwjIVX$(d{YllVFXhW?P`&;A*)P8<(xzhR z%pd)?e(9-Ozq-=Ti`Z3#qcRVvYs@qyRX{NWpZh!q3Toy#5HmX_LRIS|ohr)0%tY0| z0Pq8Zhzy3NDk&kN_YT1f%ri-fUF-IkIk_{I>()wM$y*Kx{=XD&ZiUicEU%XVPh(WI%T$+Zx$Ec(-`UVHq}6sE7< z`R-A=;rb~l)^iP<_3~^wJ63Vai<~QNw6+lh-GySLkWapQ6 z4z~9fdWOuS)lF}NslzOASps^PC!DRfDl4T(PAP}6iu;ZCM0J- z%nkrVB*tiFMC82}k(3eugb;`*rKG3;fXE0)KxT?2W)U$lnTmE@8>69-AynO5#a7O& zjW+V>dp`~*Z*|RXB|(eJ8=w92<~VHKxJ`1B^BhC31vgmkk5(3t0$5(3q=W6foW+AW(0#xrEzyHHRuX~-Qw3u*}vom?WY`Wd){0=)MTr3x!3THnHV|wrEJ1)b1&lP#k zQ_s|c24+tLfFjx^OU^M7MbWm60^mTgI_xbE+~!#r-N9v(-pum_Yi<~8JSs;{{Vk9DXz~_0Em-FoZaEoR5ucH|%KUH%%J z`9w8=yAtJ|hZFYK)D#0?Or?=2bK6x$exx1=xG{KJ&~M z-N(N^y>&7jACHd?d!C2=0zk9i5m5wNF>{&AG9VAgy`rb5!0-V9JEdlDits-JL_;88 z0#cE#>i{f-;26OSR8&$*(aZunwN$q)d1r`f1n7#Qm-kD|8FB?Vg6Ult->gn9 z)(1#@jBz#Rb0;(4ay0nxlhoe;+e}++ecU2QvUx4Fpf2`DU9{oGL%5vZo4$49;LWM* z3uqP!=WIOLYrE;0^>e-Ae0$LUs%N?{)Aj5xrpNn#|8peN}x~?Z54`?Em0(gokLFJa8B>P^0l|@vewG*1Oog#Bv~u( z+DTxqL&4$gzbe26U_eHQ$O@ol&bg8k8H7NV%Q$ofW(FeQL&eNy1_1m4=TyYZRF#>V zrg6@dQpP;0su`LgDIx))hzz2UP!Iuy%m|Fd#!Yu(Qq7x#<>f<;x8>%SHQrH25Bm1X z$Nx)RzVz_M9qS*4aw39bB6e;zn@_5J(JGBJj9oi3!?noTl3;GUoo6@07A=tTo|p_k zOw|kk%!~{^fCi>Y1|R6c{Y7rW*7b>d#<5nwK5UL#R4t%&Gr4}vFPru4Z_CMln&Exi zW$Q=p1e_HgI)9|?3)71q_p@hpYukIrwn^Vm)Eb+em?&3@5AZqi}KjP(qN;#q#Gbzz@f4_@4j)mCG_m9uXgb9 z!>fNQT)YgpF$TLg3_Zkx;&P#_*vMurSB@qF?oBQn(b7Locki6Mw;OkWsN!3@p75J0Vz>=>)yRb=ct5oKm1$LtVMRYa7Cn2DLqKt#;Ud+!{J z6b@chMO2D`8T^!p#8L(`VW!|JW^am;hcs?VR#CTq+$ z{94!h)7x+Q{Ky1Ta$s&8i|1)6{@~n2a+YmJp*QVh6qaV{&sX(gG#he1^9x(Oi^GiL8YFhfy6M0g4jnJA8ag$`ox>;@S zOJ$6+w>$4$F!VZnqSD{{r?ajen}yR>90&K{l;)inxn~+dR7kt>gqyHkh~8Q zWS$QA~QSZh{&Eo#FP>uswyHjO#^`B zxrmffh#WHmSSeXeKtCV|fJ6vXO0k%s?}zbJeViO!oL#)k+Xwf*`GvjomalkMzq0t* z-^uk0n+NY(cZxoy%sT(jMYsivqQh))9(}mX2(3QO9kPAvecX<87&9W-r|3CWMe=b#} zLJbtyA{a)wL>!n3;3TL@F}I zw8?3g`(56}!@Z-P<>=}HHt#)n>&tEE>cgL_U-(_+LzEqcV?FuS`mHabu12k+yRdxz z7w6YMwY@uR-hWslgINaX(Vx3=ZFcoidiO83U;dX1?AKD$M}A}Rsoy0F58uB*IeN=2 zmaR5reznBTr76e~xv#06wx3_V^pEa;``sktau2rK zU8okSnq%)uY&^1-VT^(e*0VmTlzi#x`Punq^X)$$e)QGgs`}Z_HlO-6efaSB$-|5# zYQex&RW;4TvCmP)E}>u*8XwrG2+EM6kTtUj2j8c}&I1sbBVYzk=nzSnz_VEzwi`|3 zq-t8%qQJO|B^Sh!;udh6&b@2fO|Asn!^>Cvgv;iJtbSnKJ3c>hQ~+y;ZYUwTAd_0W zJNL{#1DbS$x2FjECw!s^WfN5!B-VKRuq5&mMM+f z^|sq>Dvwit$=iWnW=Y?SCtuiZZZDc&tCyeGI3K!^8_TZjhV5i;uOO?i7i>%Rsl(yT zuMLuwkp2cDni&8vGa}}khhY#AW_Co3#LPrwW&l7>0YE8*nN`)yLI|Q7s;a2uoXw1g z06;{Dh?(uFQc8?5#Y9P}EJe?FrXx3d7oM54eEiM-chSA>d^zct?K7WmKlFFw`eZnH zKTzekO{1{${g`)SobB&h9Tw+~+@u9Whyr6N+kUq@rM6_rD2_E?_8{O8gJ*+ObWjpt zm$i&3rkty=L>Ipm&jgmCrpt4DN{@GWS7bo!UzqJQ{mZgiu5GMeKe)eMZ z;%C$!KDhJfWV@*d8^wkC%2j9MSj}d2(;8Ay0A%u>h~O#5jAl8dVc3r2M$_oE4irY} z&s}U?6Q8{CM{~I8r_aE}&+F`hS#O)S$6H?u<$(+Sv@Gk(pPWDUnPEkzH;+q~bQm;Vju?$Xp(cxV#rJ!45+9uGlH24gE>@_l48_MgaJ4v z*nva#P2bUawSMK(KjZ!BaO*F3C-2T%_EgdASvdOi$pg7}<2GqoPN%gaQb7Y1iMaqV zd9TRD00ANCtev$N7Cd|W;3r?~$A_fLYajZrLi^G6kABkU6RuBoyX|yx&buZKJ(sb@ zVrlI9epCn5RNcgT*HGTOGLzfiJA3_4D(_FL>(Bp_|5jpo^!+!eYL!R&jv%KL<3NClKnS6#%!FB`#FUC66~&ZA4MV7yDaC}Qj(`y=Vyv{d!gdh!$jxQw zzP3C4zsGog;Xl7P_|>>_Q3-0GnhND+S{tBgMaA)$aO|+W`|VDm5)vZ(XGDaZ^Ujr0 zVvMTlop(eCKtuqbssO-G0YE9mIj2uK=R^b$v&shmfQSGKlu-}>j#<1BCFNr^f7S)g4(wToVuZu*fh*kM0(K?5RiN>HpY^(&UnfqdDqp1fx(8Y zsZywgtK_H2H9h&|)vJ>ODL?tw{Nzt?ys!PJe12Oly33!Ledu%P$*_C8>5C@CSrx*# zX29MYhNfz2=PE-|ARq!n03aeJB7l@q9Q&9?D>kKR>0@?dJu8c6_txM4zx?=};G0a( z_YzYV+jXY0Od5mC)qVjKvutt;BK697cKJ~kAl-<84TH)}C`MF=&J&YLI%;IX| z8W0r}kY}ciM$2Qw^!B$C7WR&aN+~HP0C4P76#x*?J^;qVA8^bFAR=Z)Pa&e2Az~>7 z5%nqWy{eW{6n=_`5K&b{#K0Uoc8ma}NGTZ%oGQlAAdQxWXw!B!KU#3J>wolz!}`YF z;xNiGT=+Pid#*d(#dX&xS{hT=F(HH+X9xAgXZ(e0f}todm{Wt@X7}Wg#=$YwjR(@9 zU!~MlEo+IO*)ahUD1#CJBO>KB79P*W+SNW#>7Iy=)!x2nSP!iAtUfwyE-u0D4mWE&+z*r_|-+qmREZ{^2tH(Fb zq&Q2`uTG{O+Qx6kZk44yfBDi&uS^cA@z(3>Fa5hFZ>30CT-*D5|D8K}DgETFlZW@Q z*=s_bwr3y_0jO%jWbUe_sK%_wj>(Hz%88H=z&om{$}<(!Bw}O;1_r1Cs$}XIt)w`N zlCvjdW+DXjAf&P`c?Bp~O-DFfXeG3^58Ax==N>n@#=xK?a`9=DspXC(LFN*p77PIN0je55{#c~C9rE3E6N8ay;1&#z4N{twSy|I^+2cx?7ye&v&MOwCe?L*Fw( zTi1@TqzE9PrcpYH)jVAGNA+g?jd=P+b{m&IzJKoX>qmVxUG!z70OqwQ5I5`>h>c`4 zUGrO{?c1N+wt3@bW8-Gq#$?;Z=Gtsqn`_c$Yuj9tHruxS&htHv_YasK?m6!3y3g~& zloY4OX|69R%035r{zwo-283=H<)J9_K?3BshTxgP2BQCTRTP({0|NJQpdgDdLkMJH z?k$7(dB@ZsP@$MOkg+5JF(VOMRz-p9ZL z`t1Cj6@>z&qjP1P8f7kd=3F8FCF0C5>hNhptYn8zh(R%?&uUzyPi^|_!phc~g>TFo zX=h8AoZDT)Sh^6&#mNs#IjTTYP2Kv2DeiumaoJPRH2@EXxP>q~8^p(f&dLT58RSO( zO;@mKR?D-_-+9{>Kc@6<<@4}R_WKVa;WFhv`(lUuPnrRVwZ1c$`D?z7OIXlSNxEg# zTn%pRx{fHT>wVkTY*LeYGqVJ1njb71&x#RcMDq9VTRn)A@BBIZ-BKCrWpeyxR z+QY29#C(R~P&;aqUFZ%YcnKsxIeif8mvUq}b67*oR8!bc)x|~=w+L!gRSlphJAf_} zn@BinC8GsSWR1O}e|jRmrbn5Xh7f5BFmEc8fwBs%2O}Z>nLH3H!Gu1^l}<$+LWM^ZLW{Zl$Qq>rZ*#vemVv5Y>(sS-3uqcrf>=f2lq>9dyz zO+;Z{hJZ>edaoASz6rFbGXD-`Yefagta9TJI$XGxH_{!8Dq;3#TmwD5tiJniSLgW- z@jYu{H7+81IV&%ec^?d|V=D%O>|y_$6#TxH8yMHUn!z- zP=V^M;1WdipMep}YO3FV@{%hJi?5S)%$((=BwEfrIr+D*_y+JleffJA@~*-6vfC=- z&l}I&Nq@>J_z~ zd{>gOPmlT;I%&Qx?WyW5b8XsP7cs7@sg2Glkr*qp>Cp619gY^WM_YfbHoF4?xvI%= zRg8wl0i;UWbfrkjQ|2Qbk3YgG9+&NB&X){d%)8$9wx)4K1N!X|igk=i&w2GN#{VPt`Z}F&Si^f*Ru`3V}13zJrM$w~DSgj!-s{p7uFO=zL;4fS?g21+|?hCpT?k zWU-dRax##<*oJP;nT77}W|t{7Kp5Ihfngo^1HW zS#kgo`R%>0~}kBa{P2;Hkj|PN@r*8!`O=2(ykzM3G`ZL+(`>a0%8$1{A*<_D^eKS6rK~K1R9C zQVsqO;G-g;iKpGno1UMKc2V%B^?h!vM`0)!J_}i_fP%Wr?Z^9v5ErJA@kctgF`j5d z3|2OXZ<+jiL)2~#6vW<%k0AkBX~ltE50KejTwOL3Yyn8fr!RrXs=O{T@iCt0AU<`Q zb8S=Ea?UzqH_Ver=B7qwLqf*@)0=b6Qgb!QD#KUbA5ROD=MQf?$ra}L&&^lX5i2YL zuZsulGwEg!LS+sPnfSrl)%d!+uWm5L zXTR@jyg0}c@Cp?y8*{Q)(ad^({}P49Wg@VdD@Z<=+S4LPtU20t}YPq)Gljch4LH70KpWQ^DP zpK`G9dA)rcbzj#q9r_97t~oR7z0!RAVa_*P6Y@Lo*=SQTv8Flm<;?wuLS_|37YEX)mt}=As)=3vrwq@~)h^r+ zY;)0>&6I07i1_r^p@((-Y3p}8vuV0%$|BJ?D@vKwPwMR1FKC>fu&r4~bdUc$wzs7)@5^O^J^sBc;T!MgXWIr+n``8#!4ZKDqA#-_W!uE-yqa9uL zys*aQO1C7gjFzcA`>N5W^hpa%n#q9M*GWGl>d(p{(7&oen>1Y+e*k#o-Z<|^kTMc+ z>c~|kC5?v>DGq<}Mn#!?ITj$%p(7O~pFew6pIPrKw9%vYTbnw~{H%WU#`WGm6R^;S zzgW1Tz{4-pb^GfyoAKH3Bk`7)PGiW&s>l?BW&H|gDT_^lg%;t?$Y6F|F&ZQ_TYKQC8*W!S*~s2*;fu# zZmNr*mA7ah7ZnF(sV1cWkQsmuPBZrLp8dS;bwcefPnUB_rE>(3JG$kdU#2LO9bg!o z{$bs-EadY#MOu)tJ8lshjKuh`a%LeRpWL-4xp~#T(c}BJTv^+;XZ(7VKW6yuIB}It z<*{;fH?Z+^@XFScjNtux-!itd((e7Qc5?saAnWb3L$?wbmlZ||OkkoyL4HB_{@K3*+}oga{1jIq?bPs6tviUQ$cp!l_h-KEqZgYr*U`0D!OcMe+f>zUDAN^>T4C8fyxWkNaCiF8dLn-832VhpDNd5g zyyeQQvJ%csG?k*uHCbc9RT%4lft(2kEIh0@6M2#(Ldjr^H4%eG@-Ht2NnBEdGevN_30T`}d`zv#zB|Ypdd7h9tH*dwrm|d5qt}f#_LGDFTc} ztIta|4~>a(BILS<$j2dCiQ1E_NOi`&6j!E_a(ePV|BdaY2k64$>ZuU)`#)4)6^xJ3 z^&nqWT7m`1rRvRxW>bN~CyPH(fVZ8zn6TBX!JW_)=8Ij9ngQV z<9^JX9jfzj;eUvWD$ZDbE872qopF)5+^QR27VqRaQ_Og{n2t38CeoMt6s96dbo?2C z-%`$2psh*34>5sS!ATx~xbz#!XaqWn<7UR0?HtU1F(2RU*bk%GytCvj*fpc~OsMzH zKF$P#?G%6dsC(4Mm6-G!isaZc3u_DV0&9T@fBwd}($k9;n#WkTtmmyZ)PsV7 z9GFRFOfczMi5$_|x!4UEPD{4R?a_L&^FpeBdpJN_gnxu)^fN zQU9Be#9c``6v}a|V*3l*<SatMv-@anl%z(m9ZboKj}XUWO9G4C4+lF} z@s_{|DUv%)|E=3r9-mHKWwd^W@0rOrHt1>?Fos+Td{E**1(FDiiHIo|5R_P$y<_m# z&7}ccCI}DOU;D9M^C2mxglco}Cxpo#8rA8WGMJC`GIR!Q#^Fh^^k5jUy$E2;r1OH zRe26LM{kV5W<*Nup`ibQj!rg|u^j>EGd^92D3^|67=%`Y*f^mAbG|^f0D;^lZtK42 zk_MNL!6mdF{EN=I#^gv{>t)#ts_fcZrz$3OsfD;azwR~B(CX`3{_W&vP(k^Tj-ra)`;KK~O~wIdlamQqIG{q;RqbuvEgM~(7Y z_}oeS`P)Eihfj?GXE;gF-cW&;it&;?XPu$SsaMQYB#v6zc)#$8$@I#%^>B24vI2Ux zc`}x5ydk})0#GIyi>ti0cp~i&5>RhMDb@WBw)8%K=_uPHm~bV5kS| z5vQkGG-M0C)XtNF1S>MJebPH92G`Ql$%x$bk$%A1HtX)y9~F23LiJRAar*ZiA{E z$?d$FUR-UMw|!i*M+6-c6hSsmGt8Q}f_W{^kL!`vB}hD}o2&^e#SVU|Vg3QUxlL?! zcyCh&g>@CHCeBA7-PYH`*xB$6X^+qSVMJzItQtma2gh%9RC+32T1$gGVovA-Ig@W- z5<-u!e@VcG&sE!0C-Z$@KdBD`S75(y?$M1H6dHkMO#ETFS zHn`{Ay8H5hL@2M;|JvglQIJ)fvh1E7

      0CZ-XJ=Sn}*IO}v2x;I7=e06?&xAAS` zrHHC})IoqL-|+SRBSKR!jgv;`JzB_& z0|#$@^H7kR8ct#F{InA;xQ0cd9h2zyQ5z0ESKJ!ucmks}KR8UY{KJu3)vBJ@nx@bl zXYzORKbv*if-5ikMO0ijCEA$koT8qw6q?m31%MTU{Io)OFEICN{usp>r5W}T0AKnG zeoB}LkefQ2q%;j^`c82fw-}s=Pv!-U5T>C%6fv#^CoF0~8tV8q^zi<;p|IOGK#?#} zZIWq2SohUA&t9aYR6p#F={A^RFiL86yYkTYLe$mC_+$CzJrwQcba(<>kRJ#X=4fOi zMKDvQ+Jwau`DBJ=1y}L>-%+vYZ>z&Q`s^GmYZ{0Ug!(z7LhAFzPR&)-a!W0U5AVR5$ z%t(IdvqH5GW!k16Z+pxA!LR!dySoa8LZV-T#QJ)rNcQD=u=k#_H=gEakhJh$7&Dp_ zc0^e=1xxXgAM((t$~N`gub$rWpD2wMAOO*o?MIDv7sbxJ{tq~z`}h;h01C_2kF|?O zHX#nL;24PlmKyq-nk?Y=f}Y7xcuW_+Ay6gvbgc?o6QZ*C|UM zU)$CvkG795dR@8?ExEi~FclABOT>EJs`}o|UR!EmQdGED3vE5)A>2>IVt1PM^5}n8l&F9y?39^=*mmE9(g*3Wclc z6J{2}bl;Lp%~-zCv0}0k6ejkU&K(tJDqQZz?@kDj5c{?qJ3tLuF>xNe-6^#OA8?%{ z8v}litP_(8@UJVYy(}5{I7RLwV3sa}?LG<_YlIsRQ66;? zBqdnNskllxio}Sf9s6=K`Gs%3*3RsLGCpD5Le~IffSO>gUb){mRZw<;{G?E;VaDSf z`Xl(6c=!Nx-vg2aJjYQT06j+BOsVM(*!l-a2USZ|C4qcXW|u+{hd4a-H0&XihI## zZ^7#61})&nLVL2zju;SzwH{%Yq0j=d=1^He8&S`QuH^2$QZ_~(Ff+x2IUV0KyKV*x zmp=&_Pr@rWC;!u{uKlRd_1&I+=vK;3O^YZe<2Ho575waGD$m3A)h2N7zxh&2jrkFX0gRx zNJE%($`*I{ocC-I_jG;KLG$3)t$Sl382KeHty`w8R=0ea^Aj>%Wugon4^RD3Blesi zl~Yh9HCbp^zw4wv{l?>;HK7+SpB*tdXScB@=2yj+k&Uom+`gtM$F1AEbuUw&2gcS1 zVh_s_UDKW&{?_lZP=+ESJbaG!Uq<2s_o?H+Y|MVKST0*C+9R40`gHu642Y517-glwAO@{gUQ-0(dp{k~Pr$N4rtniv+holKF8(B&T4usgaa_Ral$~bIc z59q(B*9m2vyL4X2=x_-z1e}!paVU#Xb|}Ttvc=Mgh0@LmSydLEK=+9j(D@Ir!0ftD z_1#B6Rw(yI_%B3&4SAA;D<`Rk`56cbZP2(8CkkmII6*7D30N@!znhv9gd@EjjUU)I z3WNS@pJ~}H3C$q=NuU`&cyr{$aC&~U&;^WvK@PHsVLd?p5Mnd&07Df9ZLyITf-aFU zme?Q!0wn4Nu{?{aG7B2;CmtUF@u{-$c?4RRP-jZuX(_8Ernet1OT>dz)`ct5P~VzE zpN%_T;Cep9Qt8`Vx3+!$xH5~iBG166X%Q~HXHUty&Wamv@u~{h%$0cilxf<7S^2eA zpJ%Q&QE9yd`MPg01aC04dNOllv1GGU1wE?SR@U*-BxVKQ-*=BZKT!)9)}%>H`#3vo z!N`Os(}Y{JfyhdzB_eW_uXnakouQg;J?E%5^7tP=i&lB8GiK+z1s`lD3&`bK!&8!n zt3$9Fa8k!2sZK2|p_+rn@2rY}&MuzT#&yM>r`=lr58sCJ@?Z{5a(hNs0sEK!1OF1< zmq>nXruELI9HQE46yL3^nhEI%R=cKW;KR2fnjWZz{hjyfzkEvr|69!-2hP> zwI;vaN&WYx4-9z6lejpV+JNwwi97b@ubO|g(4NipKV@W*VUP_h4lrfXLa~rTK?mYX z7KNNfwYPABB(c*=l^lq>o@1BZNS^P@8x=YFezbVMo9hJ>v^;eZ*nO65@NU;4Tr}CD zGy(x35I8P9EMo;7G%s#O*Vn(CAe#mEq;>=SQV*)6=Pp4gV;4Hj;Io@O$&L&^%OycP zM}3AzeV>+&xg+Zy(IGi$jy;aS!O+wUre)eNbKn;pMItTeFJ`-i!XzQB5rnfit#4(OHEwOzU~@(KEw|6uK<18 zRoF&lHOhYeX^Ms=`r0wWD7U~;NolX6FDnd5KGdK(pjY#d80e0$2U|;YRw0>Tgu`7e zRyi8~OEvfw$Q#6lxv%%aFaBA|X~jp$ruaDWldx-?ewDWXvOItbq)ZoI+)|ouLw+O<6OMXCf=hED0LC z)U>osZmzffF8BQ!94#HAl5f3|mMMlPp^~8uUK-C>0*DU)4)Mj+fj(gom-wRWY<|&n zzX~ya6%>?r!eK;?)ZO&4IVVx7OogaV$Yacj!6#z*4f5jN9LWki6~xx4|L#n_@I_F{ zx9ZSB84C9F`wA~4vjv?Y%%$++Ib$8H%Hp~*A+cOa^?5S4?YCTi|Lvh`bhsg{td>Wx z%YoY4Sia4={4eh}jX>+i5!XNrdV^_>_Tt>1oS| zU-0+6kNzt2%YpCRmv|DM{21*d#;MU>Q>pzNahajyikkr|_CF+SvsGDLmXyaP^7Mz5 zq1X544qbdvT-~pao*!s72fEC@t0!<%a54i*hf zjF|FzYY_=~zb<>~<+$YeSP@Akb4H6N0yq`nI10&@JcKl7IHn61#0QytMt5aiNb4?d z3?kS0zFU3;$RhjQp~_(~({a>AS4m(G64D<^u>iz4nsPV@NFk>Ij&wwK91>C! z6x!*R2WZEfg?B*q$_5n+`6$m2-dSc&LqJ$2kmJD4LOLWwTO0`0%QG|%*|EuBe+-Tv z;tPwxCZ@P@vO(0P7zH1HA#{ZP!d}X!0;dph$tpmhg$!$jT-HjecGL_qvqOk;TkD&j z|MeODTKo>nnf{XZLO{4L_M&zU1Mvp0fSug>DX=?NsLm~gSGVKx>bF2rQ7!YvYkYzO zJ#Wi<_wi`0%hMk>e;218U$);AG-G$tsQvZM(WG>Pa~oC<28w$8Z#T0Gj*ko11wNR{ z4I*B6y?kxbq)z-);Dv{f=Jyt(@Qk*6u|YGjIo0=yBz`npo-cFt?XMVXkGjcaV|&w# zBpuxZujXaMr5bwkNB7u@~)cG$2 zHUaI>A7pyZSb8rZ4A)m{TpF|ee|!vq(1C^6kL2Fkbli>t0tIhJHcj34t4l3@0BFvD zC&#Rw#|2;>b=@Lgu%=-172C(~@0=bl)B1p#BW8arUu}HoJk^8;9X&*)8>4C zcFohbi88I6)XVGK4)m{NIEWhRB@Y6nMgZ0l;L1Hh5jm_%HAq%MKD2k7lCv`BOX85S z?zExLyF_Le>(j%BE^m8>|9j|V-3K)D+rMO*E3?F5GG-FPUt-^+tk3Lg44C=b0s}v_ z0iEk?s9=y zI@nXW92}>f;ZSJMan~mxg)bK37x^03$vQyO^+f^>#IYVlKuxP^6h7V&7o>x!cvRP5GH}8gbcx7 zf*4Ok-1YuMeD-PRlbxO5gJF9#2?B_6B97$!^43VTL#3xm^X8KX^67j{&&Hpt zBeeH{-9w-L_J6((kE_f$*%zs^KiYp3cGB~Ref#ZJey-BuxxanWpWCoGv!>bO;d^VN zeR5|ziEFFL?!fS{JjW3F(^pt*@{~|cc5IPBO{4fbmH;f0t$CYB{lnV8yJ0ea+V%CL z-^UO4-@N{>IunQ046Bm=$Qz7h4vTHGvZ64#IT)WdCu3j{h7&wB#xkJ}q>`NnP*_m}7Iu_T$sJ)0t1Q_{V`m86dv zvxS+AvwwV0$Kl|ayR!#I?3&)T?@Y8}xx(?tiPuiw_s1Ie0{W@PVj4ZX9)k0?8<_u& z)Z6nab$@{o2SBpVF{WEG=*cZG#LGdvu=%QB6?8m|zuzHl1q=EtDv9tAYTDxr+?!A- zBndi+iIX{iL4R^>F?Zj!C^AW#*S8LHWK`dc)VJ<~dWILe5tB9~a~{IDbcJM9Ley}2 zP!e7&hU&4&%5L%L*edF+K?kCl7=w#@p3z5DP_?Nu8ZW%+!-o$+hY3VbRQm_Bm-iyqE(! z3f=k$u1)4Bfs_Z)Nn*;u|IEXw$Z0~X=(M9tv3X*&v(>{vc-4LLI92i0w18NEvh7s2 zb>y(HcENzh&rk%z%G_`?(>`B}kYi-;?Ztj56uQ%6HhKRESWBU<4e31q^ADgwp+{t7lXKz-{zUslA zn+Ii;Tgy(SKJqYSXx(m|ucO~52n`ok-{srxlU?eqsC`Tt-hWdIWie(0S3ufHjb2CI z0j306Xbygpea70hepg8oMpu-KW$1cm{8jBd9ld>tdy7n_9pbynD58heSfj#0_MIOWeJ%+5aL6x#2n{}lxkAs+EE}=W6g^M(TPp!joPwAn18-6Z|Yi~LU1E58(a!Z5PQ=zak+sY9)@0WW! zmqUFvLfCje1d0%jzVGxogL~|`aa;(3Q!czpH;n?T>+McKVQ~M#T0>~KvK#~a{a^Ut z26w}QPe_n1o_MOjL?q1Fvyn;-$|=UJ1yOWmivt;j78p}kPB|R58YZBVcEr#q(9g_0 z2I$eiuq-ubbWsX%bqSTpM!hP2HoU=6!?s4ri-(+>IgYWt7=MPz2nzw@h zlQ*^=sIG&HGe!<3gwCoJn&>%Wyx4LE-X`;L(e*hodeFO(9$HvQEfhM$?8vTrEDXmk z4DN+y5Ap?kWvvS8L2PEMAVn`$bF%21{*-7w8JHoWGlkR0YF&`oXGT&gg{~5VBy7;;joA47$E_HqF&89 z1R{V<>_;kLcm}dKSJ+#C0iU*$=ht?g8fx^}KVd|g+;4rFnLMR97?HFB{o|nHF6J>z zfa<8l=(sq84TQu7^IUWZ>~v`Yy(Pt6z~Yoi8B08t7LY>$393kf!^m}wz%#|dUtQlmwDaUEXrQa>X3s->E*Jon=85{TA1z2Evk>Mo@A6jDgB>0E>vrHo-cpVsM_Ct#y!A4ddeQ-;B+Y&IS};d6Ix z4m>)e*?20nY4X1}om)z`o2L#nqr2@Nnf{{QWaiFc(DbSN^m|(W`u&{9>dW)-c{&*b zwN{?b3ys%H>e~V?_fDssN6lGS)6?zxK}VO+@yIh`qw|O2Nw^dGx__{pq1)TSMIEGz0opau=Jv9hDc|Mc8rc9J9 z`LGLglGq<3m0PLzWhvS6gjW&b6C6{o#e8e&@UiG@lAA*m?k#QhW`LZ;W5;fjWCV%L zxZ~sFmp@}4nbn4T?RP%}bq!Y6WXF!KMr2s=>TV*+Z3>~0gf$+&?`0&D8f&NZ`LLm@ zV8DsF>}H}U>@l)>pg?6HSupZ*Rn9lS^kcWL4@_Y6puQN6JAbvVTzy>f@$74AGYn;+ zUF`U0jX6dh5tk#UT`#Tw5Je6VMw6BQ^+@eN6-KOclh`Il;q)}%Z)yKHOWyckfK+3j;0;2C~2hMr6rv8@>rcF#A_Ods3jA$C0gwNrukqAIuE?05iH z(m*ITMp9^2VOS5qufi}hK%lsMLiG}CLBWLm>`m9V{+olf(%{Q~w~6kqE+>Hty^Y3lmI<=cPH!;B(k}iBY`R%3F&S^j z-Z&@r?`bX?INI?(@%~r~SOJZdy_7YKkg<gF7=#6|;a?JJ0KQ9(A`tBZXiBrHGWIE9jy+}aM8sdkZ*2D}dM z#>}E(;3$G*WqGV|)Qx~+GxH*Yn)4Z!$rk}sE&6Lh3w$?utH`*yW^r9m3^-D7I9}FC zbdga~=dptald1j}yWu?tGu?^IOg%mR=Vc`8)<)WByjF^eKDs;asZdK@`&T4fNLuj|?dbxSnxw#QY}dzcCMw=&O-vHP8+$tu&*y%??4I(>-eSZXD)bH(j4C zd$gI?^%j=}?L$vUIv(YEj4K4Yp9YU+`P3Vu+KT-nP1Bz-VN^o9rvmRJYq{CNmV+ei zHN2cd9s-8lu?uLKiNHrIdnQZNC%|Xm>`+9t`WVFz71trVB{Di1biIKskGIiQastcsFLBP|3@`HiP z@tgFHodueJTiy4*mQj&-Y`y(bTH;r=a~(%{!N}LefCVstA2W1=-+tVRiX> z3i@aO{e9xn_+0?$jkwCECi_$0v0uM@j@aOqoe2zNghxwKHozFrexh576HEdCcG`=eaB~JGZ z@V&tm6~h%wzTIV5tpRBvHijvWa>@uvlw>Bc~RH z6P^J3K93>)_35gb`S#>WrIVZgV|wj`L|ZWwM z%v#jEBsbLGa&2D}0Z7WgP&6oHaX6I3I>gYR%&hWqS_}wGn*+iiV;f3oUkr?N1+y1r z?uQhbU)IHj-tde;TmQJzqpRKT=yBxK3@BZE%=CFEkI})2p@KF(rNrWZ1k4Y!XXb&7 z16Y(Xh6wqs!92~>`0|tVswZ4 zLo8#$6YAJd=osjk!zuvxFw(Socf_Bhv~9W!DzQt5m{Oer+QeMBC-FcFS zN`fOZrJKyYz5K!^&z9N6MtjFjmD^&T_vfp%TG$NkcHu51RB(V+aQd{m+vPCFU zI6Ox!oWVn#qUcf_wk0EGJ zC1xeKvIm`0@OC$L$ee7R2-i!NXQGTTy?=cm+M#;Lsnz?=aP0QwQ_+QCg@^yLV*tA+ z0nH1V5-wWMfq>KzclFD}y^%(2m^HfDZyXP1l$K^vA^o@YkL~kUZOhP=ZeHh=j@nm& z_S@;FX*2JGaPu5#J|)6NJd5*c$6TVAc|CmLbno^BfmUblmzA3$E(~11qKzFF3+^ zR7DRZWEjROX=BtLtQzjAYVf}|7ujtUW8lf_?4{@K!r17+-9Pk8(GE=ezHD6U4wiOh>1-FdT(1Wfo%qpsbcpl!W>=*d4T|B6l_x47A=Lil>sbM zweMPS4Nt5;MwFXX=YnlsOcb7)=K6&gH5?y(qv+6MQ-(gfx&|WdJwK;<@4(gM7rlQr z>c9)Q9AKgn6BGXN8RC!lNrz66{AGgYb70+#v_S$2#3`{f?gCC4=-tGJ75~!$`AFbM zY~>_dZf4e;i2sFDc6mamz)p!zF$uXkqhBKfH^jZxD8?X|`HBXjbVE9OR zU0o7{JHD@w5zkkcc+Tg(050_446U*|`a8y?0&t?V#|ze9rMvF&=lZrUCuZkPB$_V2 z7dw2uY1UTW5YGH1?uJ-_E+hU|nkO5H=YX8mTkr`ncELE<-(Erky6xVV`7AtXe88F>Y7iYOLu9W90q-u~6fd}%U4WtU^D z_Ua=|e~BS=_w((&pR|v88%w6n0#GACqmt0*?DX<=D(`*d^`4~g99u%^$k+Y8>}YjJ z^41nuhl`JB~B8?7Qubb0*Fm*a@na{*qPn@HF*-A&y1esVr7}{A!wiu=B(dFt@ z>ZFpy>2CSG%g5Q}AG4UYdRVcn_$GQFx*tFs$N{*>fiyxuphJisQ9>Lz5tG=32KHe) zF`)o~3n)@riVp#Ztez@r;^Hh>-%h)Cz7AdV6-^HOfF5`Nm8{J4v+ln zeF_vO3#no;WD-N9qq4XjZ?o<27_f>-Fg3Xr1=l)O>36iYejFzYJ<|{j)wV0AUpy~e zCI^tL-rs`Js9JR5sl?Eh_=eUoih|5#v{iAO$LY!}<{~0Ysf%-}i6102=S$JL*9m>y z*@wqc@4$YYt6t{aEz(j_?s=>_U%*;j*c_D>(5~Wn7zzwD|F8%PWfmAX1~&b+h{zbS zhsEI|LUsknKv8JsHXY6O*)5GkUsAj7SRi+(f~Lmt^qj;JGfKfoRjA_XF!PPN)vymruYWn*7adKmL7^0OTG z$JhsrH75k|1G0&cTToL{0>q}PY{1Sc>XO|PX%gcxnOzU#F%jDJnL$wGUo${iHluAd z$Mp;lzN3mB;*S2#_JGU^6<85O))6SL?E;<_R;e!;My#_fyTN~u<)R(CQ!&YFvF_|{ zVC6Pl>)Rpt;1qaUp9^Y9HREc`yx#{r%)PJnwAN@@&OiJ{~HhH&u?SUq^0aiUZ2Y4;WCN}cQ#m3WpGx&P67CWk)qI~+dRL#1w$sNxDwYDc(Yx6zba^umnfakcKIxO~brc5gT z(Y>MX)G5IG;f|XRw9vdzt5-St$JfXEggM^9KQ`VG*?D_g-UJ@h7teP4=aJA}|66Sj zVRNlm-8`|<#%rG;Uu5=)?VJ&cSoI;w6nnP0BrH4R3>*-WkFrG|0?3opRM`N?Oz2m- z!x(|)BdpCvvJq))nLjiCB9f0+X{%}5cROk0Zp^#{l=Jo;^pjIz;%>@&J8Ue&dfk08h=KgL6Rouel2E z#d5NMg~zEMhObJXc2pv=3z$63^|+l@J5V1<0xu@8LavS&jcYP@3&ic9xX$0&b*T8V zQ%E1k0nZ|QdIi6-@9`ml1-q2L@$4Cm&?7ZQpc@?1Y3+)jzY!&fZ5Q$to@R~LzSHq7 zw?}%;-1m7PfDCX-h>=}UfzjaFsmB1-R|m;#^T_LB{@zxODDCJxxyc4md;F*QAf04a z_>w0g4p5%UVZ&f;_^&qZnoSz=%qo!CNnQlYB~G6L^Wdyd=R{;8x1}t(D0z0IWBqEY zfseUPOK)9g{n3>7y{|liZU7sEBDL>L*&V~4{ahXY0VCJHx4x4s<%z!E-<0%?xu%RC za1O)Ge5_7LOAf}!(Y!Atr-PE&Yo(8x8faUFrmKvIqyf#5@tUzliz3OF|1tqtA(8X! zGpQ#1Y%86E_?Y;(y{mP;P3rju==Z>SOU_jiGg!p0P~RUzx~A`%TOMvFK9muw?EQZ| zY;R0oqF##$^Yi!yBk^R&yVrdc$Io^K%OR^iPPF6~?B)7iFx$EGZ_>8&YD~@@2&&98 zGd<*;cU{3amW8y|y@|TEBQHCv)J&nR-*?-X65)7~_?_pYDLNc(E9)zPdjekAKG5fD z+;hQb4=S@iY_ms*DPH`$Wwlka9NG=zI)T{Hux8Ota#?vZC zj!eD_tZ$IqdKX<~G5g30x_;_b_OM&hogtKf?Tx?#j58cSG)5MF@EDO9f#T}o5mN~9 zAvW4n!Sq==;InFiE{&6R8Lfj$&DjRUc3m-X_c&Wi-9A3reykI3AbN=ueS3?4`(a-D3k}(*9oy z00DVy$U-1GR#J~d0D3|`YXg>A8k1{!RWw~BeK^aa4#}w<2h)1ys(>D`Fje4$jr+EU zkH6mXIUaM5)4o^&dfJ2gg=+&sz~-4sXzp>Gob5aod=z$uRF$N)6WnCasiz>K1JT7> z_=a17+dCr|Addn-ud~;MF*TtShXll!A!4UwgZ2jMLSGX5*a zZlguAP=s(8Pxugn8ie9t1F{2P#R1S_>J-4CMfb`O{UQ5$k!^=?O5?fdz&lR58XyK4CMsJWVVhu%deVcv_imkYm_i`m$QF`EJ8|ruZ7a=Ec{` zqpCrZ-O)c!#aJCo3TUX?Th6IjS@qxDkUN;WheMa%E2FvI7uy%gBjl>}J_L$B*E+es z-_GYEv>56e5~SX>!ZL}gf^Y2Z22O%2Ct>~%Jwd|0G*7?&yY;O<^piJNZHlAkwm z^E-Z8bztDh6V8u7=KFu}FXylQ=~i!13}T8??e$J+sDtO%U-)G2{L4JL4CTPmDj(j* z`H@L#mfg|GydG`z1|vojGj$bIBPn{$#OI~NRnFPe{y$&{;JkP208G^o0g*MSh~z9{ z!c3uX-g_|BoEbrL>Q+s=TILu{6p@B!FZ3>M!|Jc%-Tx?Q2IcwQrC&aJ6#OcQw3!k) z&H~J?s7h53u`DVg{lQQrmsM#hlB1?*B9h`V3iWo*Ub@Hw>ZU(>`n&&Uk!Qz?wE6y@ z-}&gT0rn5>J*+7gb+ODqt{`LrLr^d^%U}wo&b#!ME@cq{_Pz*#{BCJ>clG2Cba`Lf z_1^Hq;moIE!qbDBkYj+#+m_@IWu~?ql%Xg*`ohdKs{*3)Y8bO2voC8kY`cg|-g{z* zT^GB^Ohr+ESl4x?iinQbdq;$lbBZf=U9&h@%@%Fb#gwYiVE2Wq#hKA@I(~5aa1xKH zNX!W>qV>{zeal~d_r>=@*QWb_BTv4e-OVRYZw6nVJ^NwaeF<`5$4~O|Kq2}5fHtqd z`FBHo1u)>#Kl&{fN@T}Ghy-9NDyC?VRW#=$!ienO61dl=st?GB2mpvc#E95+orstj zGZRtHImYOm7m=JZGxvJE5JJv5#%N~v3;-aanIeKONev7ff>QwyV*>(-sqq6kZVwLI z!}})>jP%7zFAQ-#$YxqlKa`_$ocF${)7JtwY4)Uxa~}1?p9%FR!nL2vN2_KzlXhA# z7F@+Bvt@%7apl1k1cAk~M7EYuX1GyQ30?;!o+Ky!qYl4QemVWUW_W1T=_1G3Y6sYN@A<30AOaSiiplRKtMn<6Oo*=h-wzc zj@bc77Ew@UA_PWsgqCyex*St(yOfdv40g{IyK6Q4Fy8z9*qvB;p?ChXhmVWUq}(k# zjIIbw1u^^J%`nMZEQ|E}{ghH&*KM=xnx*CB9C_wU1&=SU@9sdcia+?Hr(gJ|U9;db z@7Vd|f784E@$Ps!d%9N_jAW}UdDjP;w}aPH^{nSF;qJBv|`8X9W$$$nj*3D1tLloHA5mbGE-u9 z&aHs$$Al1>D0Q(}t%m&pBAP0w0$9#DwoAyfk`1Gt9-pojjjM}dW7xa8Q=J>$JHB)C z=}jnNZ$Pn|FXza5;oTQsy4dTdM{g|N_^vJ=r@Ts3>|A?axcIUz-TdhZb&I+JVv8|# z7;v}?{j-DJ4LtqIZ=0d20+@RS07V7Vl4MC)Og+0$79o@xs_cRo>NAMwpAnIilB)7E zs+v+FVj>a|GYiiE03xbtd`4B7IfUQ?a=@Gw&?ER9L6bVbW_haEm195Cqt_nZc=O

      i5a$3a&c_7C~wP~SQ(N=^@q}<4rqH4)6h=j2M9i)y4Aj=YH=^Qz#B=vI+7Fr6? zDQXl-0+yq8irJNHq+m$k0v6s15KYUer6abdIlXCc5PAb}=fS@NaUI8^r?08qUEKOn zU7U08`md(DuS`x7t+K19{LE4(}e`y?HpBk2klS z0p)~}7PD#2x$2LK{)l@6Dr)CFvq|nOXHt`#k$y}?RF#>DNS`4hGfOFTUDRwLgt9Ej zVa_?mPE`Pn5eY$4ge-)Js$J8@nB3aB-yCf8?#bRCOPp};60d(|f3K*bsk9M0AQVA% zzV7#kov4Z!08~}gwknY(YAmc5?WE0VmRjB(Y(IHsS+rM=uO2mblPt0>hhgj7+B0W| zrOjS#-gpj=?u1-5{doBCZ}9pfCWGT?Cow{d{d5tEnnTs}4Fpf+_|#M9aQc`3EGfho zO|>YBx*mk!0f2xN3`79{5dpvudxIVji3~th0f3!jW+I9)tEvwl0Dzpc8F=rBDCewZ z?A-(SfB~2xqKIe~k*t`>gNQot1|cO70gpHulsT=II$Of*g?D~>*zBJ@bNcMy!Vc|? zh;y6v4;DM8){Arg`1R+O*I%2s<=O;Sc~PAFsC)A7S=>H+=lj^Nh__s^(RGq?Hy8yU z3<1yzGZtmR1e^@DDlQr>Q=Xc|!WE1oNz`=_FamYX`QV43gFa!#mP7K$n3W9>Riw`l z&4HT6uG3_tuS>2_5kZ^j9gj1nYkhn>>k?@=96Y^T;CK^{4qlgdtA;X6o(&)QgR9+z zrje0%Kp`6*?N7G`bZ#p^$v`N~8PS1gj*iNm=eNw>b=-~E~PQz}lb@Y(H; z{GQ+V$gNji*c$Gy7WXvyX1eOy9>?qLVDt2^d}Y0C@z(#{{o#LCSesJLldS_jsq0T< z1z6miEZ+&U+mlVFu%0$PU3~iY;E}IDSQAlM9>>G?=QrLux_fQs#Hn($*7P6>j=5XT zGtFv@Z~xi<^7N+B?&J8(@4)%b&RVAj z_i%n}(dt3X1B|AM9?eJv6#>`)04??l2K7_|gskX?RoH@qJAXF4_1*PxFj?O^`DGh_ zw0V1p$;v`Hlm+|bC$+2AB$A};UG#(sY9=ab1^_uG|A2F%iipm+{-N!Xd*7n-7ZoJvdEll2Q{R@7d;`TFJee^GGvq4Q_Y zt?k}^^9PITFJD+IYbelm;KJu&{b@UfyYnUyfv80-u|Rc_)tBVTu+rkx6DRTDxj!NN zfTTFqoQTAKF4m!+!n<=_t(4SdzcSKKF4<2v`5)cXjHE~Iyv_RSpPzj zOH1WB9iWMUsAnNI6Q2Z7djjJ|#cnvh#WO z(cd!k`&WL}^~WVpE#4Z8MR7n*#%CUV`UxN3>i@5QNXJ(RjyhY!T$RO%gpOe4+xLBl zNy=vH^Xp&!ujSNd5)_`>bpOrO^;gpT5NR@8+ndd2p(v{1uxTSAnW=M3&WCb9t`tCU z%tR(pvM>_>h-k_=Cjl@6AYf+aymQQm1OWB`h-y+1FnCBoHRqIKZz7Bz08wWeDC@)_>!Gk zfH0_iH9~VNjLw<039_mopaG<;DJ35QvjYG`1OPQlq7PJqiAXjP03}c}0kyL5WPo5q zhz2IA+BNO{rkgL9niCWNgTRB*W%9JXJvevC>PlecbqRStAN=g-@}E*%IGyBf46rvo z{jqTRDQ&emI$Ffemz4;_-bUrPG;*4bmj}h>&dQxRap?pezwqZd_TGEv91$_IDWpE; zoXw2L5fUPpS{7-VMb|HgkR69mR#g?MikV{)V$NbBg5-$F%p?mt$IbzvsEUdi0GO$P z8Y6mQN2F?*M4h^9t~W)tqDY7_b|c`vTeLnlMSA(&SNd*oVQcTw#--3Yi3=k;TE$k2 z(-)uIJUPgBewMHNTPJtL4{7J)?&;q{*<8K+pxETyXz}-Fpsiz2uuI${1l!)*t7KA4!Yl`|n&XfYzW4 znN|SzHPia``KO*JsgFPSm(yQ_g6)1<3IO0H&IA7BfR+A~XXt zLu4XiW<){&RWs8*HX;$sh{*Fp2mq!cl9H*J<`^TWc~p#j2FIg%ymq5I`X0w=@TX|+ zH*USLYGy}+B5bW~&~UO46eCvk(l847VGg15kgRkvDHG^wKkN0C97%QNVF2iAITx#JG>Ha-Q7&}FmDUlqB`zfDvH{o z#GE^-t9p21V*cpx#&amw&{lPIt~~WATWzM>sc#vX4ReMboe?<^GAo#UQK4A|Ktw`f zAOfV61ptX15`ux52_QVcq3^pCdjboA%TRd7j9{jqW-69*>SK&;lV({O%}P0Yqr&;3 z9JJm>wobp&}nb7q#!K zE{2sM=Wdbaxth%R?4@Te;q2$%S}o?zIU+(tW(L3*6B>XSk^6T5Fy|a&Be`eC?ASSn zM1}|eS&WDQiHMmUGO1bHw2mnh1u}_QmMmHD-vJ;4G+;zV5|YlMS11wzdkH?GrI=hw z1ldNkpO1d>#`CFPK6dilxxu-z^O%=e`%Y-l)B5iD(~q9Y-MjIPKj-dRCQjA)(X;;n z;~BfX|IW)VDy-^Z*xKG<9#9yQuMAB&ie*3~D$pu5GDw<}4)LUmJw;wX0AM zQ7-43KT0=$9%RMf=50|u`WbiPSK531?B;QiZRoI(bg!MpT6gw#cFup;ZoIkw7yr{h zZc&_4%7q_D5-iJuw%OO>$>02a{_yWWKC86e9^OB`^Tz7%?E+hmXf_&+b_IJPsws{^*JaO$_O{&K!JKA2SH&gLc$#?uTU;0;4y z7d(VAGiHilfYCzMw3>6si7~ppt&8Vf|Hixj??0*9wU*)`VnL9vkZ@Y)W>^rZefrBUcvM_w6!<&Wa3vd$$~q=lRZ$SGRx8!;0&jV*5i> zUufT+&1N_pY!ahU6zGw}0CUEi8Nd%mC4d2ds;L1ov2!U45&KXektqNI@&^<&#+Y&< z0Pi?BM+BBda?E{{oHfe>S+x-{jkV1NkPBA>4O<+peC;;ZCcEpQ%(lF?eE-Mo-51yn z%YkcJ9&LZ5+Yh2m+vu7SZhx3=dMF3`& zb5>R796N7nXrQL1NJPvG0FuQl6Dctf6CkRYsVM*=8vr695&&j>Kyr*k5JJg;kyyb% zR8#>B4NSzc5g3ybmQH(@wMY!ki}%TqnN_Buy^ZijbN7X}Us7o=Y@RqbIKM^fUYphO zC>yupeZ9AHZqHA8yY(YG{6)@fkE6kbU!{|uhIw`8?RQp3@2?MOR8bvV@f>$c;^^VB#S73F%qIl zR*~eLoYg>~?zaI8J zwYu822ZuFhbaK=lG;UUmhG!r9qNUlrZ~nK{@^aA~aY}@q(XFt!-iNJE{>IK<`&|ep zEe)ER_vSa>Ggz&h zAfk7{IVY+B2!;S=0AL7UIrjic1Vn^jl0{NP07fzq05jE`lZtv&?b~F|PsZz;chc+! z&>bOeyY;WW|Hh(S%-4q1)_6jLQG+4JY)QDRv8>EHB_ZoQ_8vQFSC+9$tZp*gy;N?y z{EL5b`15bC4If|H#jP*?0c@Oy0!8l~?_cTeA6KbxGJry*ULrsR>jQjrpp0FtQ_VKsKn zArXM3Bq?PDLn315eF#O#Orn5@&Uqur{rmCuPnUOJ=6D#2s>h9D?P9h2p&Zv1*XGN^6&L_U#0b!p zg&)=(7Lg6?3^P6FwHrsY7z}a zLF~lPfDBMXih_y2%;X_LbnFlyr(~u8K!|3VV#>JzYlHWxv(zn0UIx4)&0AG1)St|EbPjS)b&isp8-h+aLb-MbE8n?#KBdLz86Ig@%WtljlDT zrOvH2Wc?nR9!%@s(R|HM#4?l^?huzUX~P z0G3t!Fo#M=!IDo+fwSP3i^T!?$$T*=sx#Y{9&_=^{crylgYIByA76j+cf+&a0Ag@W zGk<@2_g!11iU$r03}QtqS-ng=t!XCJ8M&okzswreFW{)C*Zb!1h1r#FO{O=-64Kho z!c$+T^2F-qRQq7!V&D71LLp*JmfjQ{myT-#Zu`WJiO38jtC|@CJMWx-01*`ok(~3) zlx(GH0EPx;s!2q$L;+I-AVf41ktC{I4$HcdY|Eo)9dB&V_9+;xJ7=)G9Pj_MKYYpJ zeIzHmQ*M5|+{+g74f)xNHU z37soV#kg7M)pw7cyE=V7`nwtyRXXwE^6xyd^;KAeG@tc(6$U=kG2Z{-?CPIS${X!+ zI-O3|&V6O_#BWPmAHR2Vb$G*5)FMbV+`060wZ{F6-`s!xk2l))1JJVbZ7zxvPfot_ z`+V^;Q0y-69o+oMckA|Oy{Aj^SA^gT z15i~nRTJkN7^IX$#JNy}LR3sm6%34!h?s~(qJn@a5iz2vstA~ZnyDZnsKyvIXGWE- zNfvlG7>=&Z555cCap6u(9{*bh?OUHKo(+EU?63cQ*m~SJYPx@P>z&!{8(#gO8nI*cfShAe z!a6`*2!r%d+vuIt<@n4AEN9ZaczFE>x_^0H>dHNWr+*dKpJ|TM@x7VnK~YwYzI)m^e=Q!;^0@Do>Zqvd zDy23Q;GoOhqFKyS8yyv+dQw(p0-0G1;ViB>;q~j zAQ-q942b!lJ$~u_t)DfEJHw)!)F*v0GRVEnJ6lAzUTuGTefO*C9&cgbMpaow0%dd} z?a}hR8}k>A@QoSWn8*7e_(44P*}eZ{Cp?pm+M^*+E7t%3AOJ~3K~!s(yWAj-w$5Fs zN7L^5pXcfKbag#12nHAV^si3Ne)j0{(cydVjzYk&v*Pm9M;)?!W$@H`})g zDyQ9WY8!hW{mS5zzYV)jY40w-{Gva+I><|BS&MOBPBhf9>$sne>Z+LRU{Us6N6rCI zS=UHx3Ngm4LQH0?rp_^-r4$`85TOAOI%Fg!#H^;GW(EMvOhg7Eno~+<<`9X9i3kDB zOq38*rSE%9!jMtcV{hr>Dc3oF+LPoKW{Y#~>Vp8H?x`Ol75dE;~cx&M{lUSd#Km3nk|<=w^g zeO6ahC3-81Q2M%8>(#u%2pkFZnQXLC?oIq?uKLFPtACQ`?+(;McY1jCH~i^OE$;QJ z{yjZU4%w_n7?%ip#b5m8k77`wjD zB5Ht$!{M;32C9mP&U-{6X6Gq&eT)eJnAtHClSpowhKNK&RYM3lMUM!e{6O$Tq-Fp> zL^-9dX(eR`$V8x)P!zQ$Uz<+=OVExD9oC5CWk$`9-ul@T=R`8L;_=BdJFpe_s0|ltMz9l7r$WDW9`kw{`)t&_OS3BTk=?z ze$R(BV@z(z)zSq;IYmTfreKI@fTGIImsN#Ceb=p4O_t0=-ZL>EG9e*4P*XL@S+Y1L z(;Q>Rj)-8n>dSJ&c^>VJ31`jCS7-O$TF&o|>cRSG+q+4Q5ve7=Z2H@)b{|}w+@-

      7{znjgz8bW*~4ogV${ng4X4+wI+J_piN%(wc6L z*DsFGtW$k^{?rAl&8{3JNJug%Y!9^M=pN)(MO+dp8u!%-nR>{_iT9TcmK=#TwjZai`mUx zw$Yr^%`QMF3fIcQp)WCa97^v*G}ii(JH?3_cyl(XclW&l8B zgzQ5>=u#h3%m5&wA{k7aBj+efjBPviUX*08R-fFYQK$Xo{`T{5c-gP^t?P_xw|)V3 zp25Krn#T98T+f{r#h|Q*hG3|^;HH@&TH(3yh38;Ou}hXZ_H=VG-#)QB+THGc^ew#m z+&4#MX<(A2>-)CvMAZP9IfTN8LcoZ~JMWw)A~nr9i3k9AVnifDM2Im0fSDnp_g*ED zf>}mH^3Kde!~h6URZRpHJTW2Wn0iUVI;5h)AVe+d3bUA00NI*jSpNL|SLeP#OgqK+ zth=<4Hr6UbnOWDExW&R{H}1XPI5XLObS(3?7VrNQ58rcS-EeQ~u`j`iFY9V}`0kB6 zx8L%7TxeHADDi~n%`h6`P*-%&n1E=p&nDP{!n zzGNa1lPqW|IUXJ!wB2HFZ+kcz9v;k3o_QJufNp{ga;cHOPk*y=}$jn5As{TjI44i?Aq=36&@aNNG_2Oan}!!f7@+1n{T{*hDv zQOM=$_M3~lzwk1byxHgN$?22h^EIrVJN(7JDra}yK<~?P?er(cC%)3&s{7l8!Wo{d zPcAwb9`rx{=l6c{C%bx3xWUq$KHU1)_E&$e-aZSn#f_go?;wHnG4`F{ccM*{7Uc@I)jcDGMSpvzhgMubLf`ftdmT5|Q_wnODmuOD1IR0}+`S zfW_3iGK>d9c1}|2yH0Z=A|^By70t1av1g=`ae2I7j<#?#sz*1v*Gy z5g)%=VOww&8&0@eo&OY_c-HQRcV4>^v@L`4p`Z|4S%jh>&k7=v1i-N;W635lIh7FH zz0_~*Y!>6N{5OA$cc1&_uqez-Ra4Gc1rPzr0Ej3QC3~-`S%ip*$R0vOdH~QsA7DU4 z$T=|)Gp7_0ffYmq0MN0jW)%P+A_PDMM-ObTBEMI>7mYE zyY=S1bkKM6y=wiL&5v!{PE{D_g0%PGqxioTHp`N|}f&Un64Q_c`ajYx{0R1fo5nP1Xk0aLw(V2D`Jo``pbdKV_xUXFpd> zKDxRtmOaoa=VOVpl3iU7uwL|wUo57t3ME%Ox_;tIc>XtGI66$%Upe^86L`w?6B}Fy7rezgzBhcKgM{=fAhMlVz>0uR~rz zoWSU>&F&X0Nmp}>9aUuvApxl5!cl-M%`~>DDo*lvcaB_cZ4?`$qU0Oj`WN=*A8igH z?flx>H~!?6nsk-=8+qg8nKcC*bgDHCFLI{Nq&N%>5Lo;Lw-c^X4qKP1|`O*|p z&RHaT$Idwb@ZJ%EWyv|KimDXgnE}8yh$Y z=2m+6_VM+XX>nyjM@(HCsVg2Gp8cxd_@wOH;q~{mT_B{%cmV8@X;BZtcnHjZ*tT6v z!tB5>#zX)m026j~UGJ>1&gS3z-*Nupw=_lgcMy?@y=Qh=M8V2x5UM(-xLB>s%(F)% zFhc|)1OOE=Q%CHb>$=uCW}>E95|N4KEP%w0%s^ETiJ8nyv!IzH9~?0{WdjG+^wec# zFQrc&1q9kwp*hIYS8l$3V{yCdrdxjWs~5g}syIiKdzm?lwF|le=O!zq!_=;wo~)l6 z>+$=uw|?fjedia)(?p}EcAxqpoqP;Z*WA6jynh#)`t?!xSe(hNH=i&1Ya!n*i(!V1xztjGGmmY$k;yN9 zdVJ&iMsK&N8LxkM{P^#aJqxe_WH3rPeeuTs@%MLORkUab-FWlpM)Com$^EPdarN&sn&?)5@eRVUA` znBIVXW@(+*zIgu@Vv5);y(B-VrL5UkecSZ?G`l4JKb^t4T~$4hPIm z0f8Jj59G3{cLg&8YV5nzcLWfE7fpab=u|Yf??Er98g7*yUiMy_oEWvwba^4XU0N6uhhzJiLs7Q>l_udn^ zwrx{PK6vkooHL>G-V>3T0ihu%DyShM1Dcsi0y8FN1m{?CZkr}{9p}EA-cL$yZEf$= zd@*}2HOJ%OrDFK`ci!#NY7wL#d#XlbDe5YWHRXA8ccIf2S{RxD!1dgG)OJM z6pcs4=ION%@7;O%2djHm&zyO@IPp=~xYRXv_u3VJzGBB2ykjIV07ND#kOP7f1p`ns zu|x#E2nI;bF%lxMBLtM3O~p(#r5K~+q$)&&h=Cc20SJweNCDI|#g-kUyh7H|&RW5C0UqSHIJ@jhO)eG9i%xiWxH-p#f!6 zGb6`EQ4%`IDk5e|@B!1Tssw{Z&Z{NI(X|-7vl@^86 z4qUfYvG+g>>^PK2Ud@~pr9^5f=LZ9}gI_fFer|4-%YwEq z4Ill`+~DT%(c!AgI@}#!I8JaU=b9J6`MR7)^yCKWD69{P^IQJ# zwdTb?f&N{sxEX(F^0B{NO`ZV)yYc;7fA~L~NQb;?jq4s)t3vJ6rjaaFRTf1kiXuHESpbZY5YbElR3&#^ zV`kn5L^K0LDvDA>3CTHU2C51Oz6@e2Ih!gWm}*W*ayC^*R1|>`V~jaQmbO2-x9Zhz zY@B%{_RaIMJS^+;RDR~2Hy7>vxU{@pupbN}6;2B4WFdz~Jf$<6>rY;YH7$?grf#2G zKbdb_IeOt=F7LlaZglGNf89Uv>lyv+#p~}Kyy8cz+JRe=UkvgAmsZzBEt-k^u-tIu zB}>#`VNk6X^~sv(_~6#%e$k#f^`w=1veI@sT`Z<`U9f_*Q8j1FV2I4@N+fT_$n3mB zwyd2(WcF%-xNt;>z>W|g#mG!ds42Hy+qaFGg%F%`fi;VET~x*3LnsO)Uq)`$qb+vD3dQrWbV5d zqj^^rp$0>htP%;MX%}OYqKYf4^N$WT2kATiT;BZ|E?)Q+sK5h=!~}$*8gm9hUld5L zOHtL>IYa^=1OfvjB!mYnCsh&2ImN8Nc_8Qn7#c%AKok<6^$UlTDql z&}@f%QIjtzRIVryT~=deGu518>?J2NWk&BDAu519AgtL`R6)eLsu?cL>kb_46S+9oY5NfBFzx=^=0-H57tUDhYmuF#b`{RFe__1$5 zGkEE_7t2XGUtHha@TEyj^|0Q}G?<%fs#=)FrlZ2gm_#Ln0A>b?h&kodM+9(=iAW@y zsdprjRh1ty!<5o|zVzN#Rq0$%RWoqT0fA^vDdn6^G6E10f@u~6bL^N%a?&iUeRp_I zso?ds-7^d6Ua)q`{uB;B|L$9hI6E#a)*$A%SFUg^w{~pDbf&JKKG*O5e>A~a%&ymU z80NLsp5Eb`{`t&@hlhuxM2V&(QIO}b#%^8Pu`9=p=8>W(4kE?r%+vp$fBNQk*n6+Fdc-2n6OQsxKaZF7{MEtE z{H1S9fAj}!f3$h!v)f<%EwUR&r$^KF;jP2B)UE1)+Zk<}&Y3n0>=-i5W(x!}D2AXU zLel%vO{$R#d%^5l^rTwGhVtox7Yj};GdNcnK#4KtK64_p z4FW@=fWn|+2niwQlymmp79pr|*EBh0XNrOI+P==yJ(ok9B*bOZ>j?2U4 z$wTfAD!o~|8MJXdV^d!%ulx$^eMXB*iUZ6!9zSRvUDxKwVK3w|4UH=RNkLIb)o4ak z^3F+4sb2>xAwZ0)wr8p~>!+UeLwfKp{^7>zHZH#XuiL(}j|K07LxWj!%n1znq69Ks z%pyQ!MN~x%5-1@8f+8s@s0tz|XCf44Rd&uHq6i?8h%hq%7-Im@dvC23X306nlya8L z0P4NB0uBvYlTee2qNJu#%A~vc?%`nFZ>}2Zx^{~p z3^0r|48fLU93dHDXHZ4D9J`z%Du5PZ3TvTKAcHArZ(}D-j$wq8Ghof5?)aT&?jnOcBL!GLF1OTFy`U*pGI0Ph;wRc;Vw8SsmYg z_>->;&ttW*J-qmw#rpW`e>!{fPcBkNhf8CGCdHcbI*g;=-Fp5nmY?`5;Lg1E_3w?w z<^1sG?ndbl3p8~xKwGS_IPsg=_;GGFN{@swrLXQ9md`xdSe81)va9VMw5Xtre8I2-D3uW)C`Xy5%ktd8SDV9W6H&rH@+vD zYx6Lk+=+_=k`6<_a_GtRFm#(A@;e_pka&{(n{2ndLPAgU_D2x<(0aLS39iO^YxgoaGcImQS8)>;6tA5c|L1pr}T zVaS464We_-IFm&ZCqU@?K65GtMHjp2Z03WnLhyo^7(qp|Qer_jIpjiVoYrI6WH5xV_FS(Db>8@noYJK5NN>KBU7{&g5$y#DBh^C^!U)GWx%c?=~royi#$BL_w4iIr!TMZp~42Y*y3q5vQ&0ulj{8UjK^$T@YX0|e)tA#$#AwqgcV zAw)oB&cb4xHHHu&|4dQF_STwp=sK| zaBRFYWCa1xsA`PS7!OD}XJ$5tWC%bB(GosJL@Jz80#NTwlWB<7n7@l&1-(+NgAIcKLRWP zN&pWK00$Wb9^7VxzprAsiv|;>6{go%$X3Jb15bwGziQb`>yXJvk;c!vuDDY z;^e(=Pv81CVR48@Km1*np)k(6fMi4=voZs#D1b=LnvDf(jj`5+f%A1voO0sKKwyj^ zA^<>Zh=4z!s)%R+`mReUA)<&dvvUp+MZ{Wbj3FXK1XTh=K@|o>1x@j>9za7`h>El3 zF&4?3`>rRJ(m761Bs-G%$#HDg!>T|KQjLArwylU%WnGU34fZ?NuEOSq-h5e>Z&P;< z+Cz>hOObHPZ#@^TeG&FvXku}Ey4H8U6%3Jx#2$dHH{?A9M=lUq6e0%cQ`0mtz+f~Q z*)gyBX`Y%v7;TTOpY|uOpPpRL6eioB8Vs)Ddeu$m0;Tn3FKOAX5->Uf(9(y}dY1va z?7;#$Y1T=WIWSXT2u-hT>Z(#l6Bum7e*ewoqjxDU4P;4NZa){U{tZ0;i;J5#SM$TT zK8pPz@S?EdO>kyV`i)R-^i4uT#rey4_7dni-g#sCy+8A_+tA)jauSO$*nVm>`Iz*) zy8mkI-f(^zd25N!T>LBlO}PAmPM7a||2uoNO)L<`0z?E35~xZs4)w&NNhzkB6$Kn3 zfq=NGX?=bRS^_FV2nZGzVDm$y6ZYsw7%ZBaH-hyhj08@cjG%n zKgYNKkH24ywnAB#Wo3*Pft-XhC=h}pw8lDXJ&_?IQ#e}%AQa}<_lem)=3Pn&kpvJB z00EH

      l55>zuPOhCkq(GsdVY5vi&O1E4X+8bgXIiUcCscU|ANEIb$tthK13s-hZW zpHsHRmagF3NsNwUc67wCsS3BA&q8oyfMe`qA|Uc^JlT?sa{R)Tc<0si{T~nHzFXe| zR@3w#-I&Z zJrk*lqJlxPNCp8A0b-xJb?>b!e3@d5oQl!|D1SgiR2316qVV3gZQJ*~`G9lQ8fx1n zr4&NY%*}cYAO=x56A|ZZ3Cpr{#&rF9(afs7^V`oo8~490H~&;HH|E0R!~dBbe*zN7 zdfBW``?e#(a>vnVb$|NK{^CxQm3o7w8q$RiZGF=1|8)J0e?-%Jt325JwSN#M&s~4> zyK%X{H5lX){FTZ3>wB0}oX$9BRRtnZ^`WY&8qg>q zXUQUDoiPRgR0)v~QB_5MX1w&D&-=TQ64g zF8g|N=Hj(__X1!5B|v~~-JCp1TRGv@Vb- zi@h^;!pE=uDc^sk%njc77yrGM75c(C0z?oYBtupiMaY^m_<=Pgs6{eh8H0o}kfD@w zAG4|g8AKEW1p-7eWQ-w1NinA=B8Vs=s%k!fh^oMxQ%V5foU_(~qNo@`RERO=6jjAq z8$ytrM1+V^N~(ZB1mp-vGIDAbQ|=pY6mp7vlTuVwBv65*v|{hiji36JXBRiVwY>T5 z4S7_jB|r%hKs|(z0ZxmHaODewv(Fak%JkNoi-Q|Q?t_wWh~QdcER{T0#*Jy{WfR!R zP+FVXX`7q0u{jA_^ZDYN^XZ#a@T1WS;oRrJU2YyO<|ijL^}2izo24s8!>tR(kNaMG zRzd7zlk&1CWH11t*mkS=n#B&wVz^#*^H~E_ksF}#n`gE!JiW`O@2sx>xlCUf`bWZY zPd{|^*ZwO=lm7jKyEpE7BSoPK3Z`TnEn6_d`iT!+bZ4Bd?yi6M=SScDlR?h2!>9b z3FWW~r4h6>SLFBG6;yw3;;x=syXKng7?1b zx|EW&mVYK$V^WIDY>d&&IVVF{hJc_sXH~I?0HFL>?4_yCU6?$1rM>wTe)u&soXRKg z%$G+OKZoR%GEh_%1?_qIaQg1ulQ%n@p^?~&qsds#%^uFRsn5lMogL344TzI4T(o8H+!*?(k->bmwJ#GFN` zt_KR_ir`&fPz3@25dlCVXN&;==9FSm&I*EvhR9h104XI<^`?j|sm2To)-@3u^%|`v zlVcX-YO5Mv+=7h~FlmnI-nZi7UVnN+nuiWKRNGpeU)!r27e8&bKa>`HeCzh?(E}rW zRh39Ki2+;I8@n54F1zs-paJHzoVL?rl-A@3+`1w#U}9EP@2s;%L}H98f(R%oKf}h5 zb%FfQZf>AG-T&bq#fNWtPPqS--;F3}6frY*%B>~!&VYhsB?#UQ5DO7Y#-mfA2&h0v z#sCtlvVwI^0l*j{gJ=XmML2c_;W1`LL}QGIsH!oBh(sjktg6;p=bW)F<)k8@%FG~a zjX{8-C}P(FKfaMnqxH|$_Me)6{sLw|5Gzkj5?I9p^DJ9KI#L&OA* zosC86MQg|fVi?v%S(}dAH|C3Px4f9_eYoEJ6@X`S+OF5lQVmk7;)z8yzBaxV6S@R# zpPjL>Z!!0U1LQU}3kB(Y$iB3QdEIfBeHev$6Ma?gY}Mz+z>o61?={!IR=_>wcw9Vl z_UHdY3YWMor+21Jo0h8;GZ$q&7;cOv!}{zH{jxiL`{1SD_wRmdvpo#XobNLUy=cDqwe@%ZNBij2oN=-H;<^9$ADH@y<@-06_ujXu3D!g*^rdr- zG-K`3 znGgX$gky}7G9q|qgZBnOMVxcOc`={It|J05I(g#C@WO8U-XF>FHrQ z%hE2|Ik%cSl@1}2CL$1K0CF}USwKVNoc9RS$3Ahk&WExD zGC4Dn1#6HD5GkNAXU^RB)(`+Nv$fV3!yiCIV@O0rL{*)0J_H|%w(oN6g+)aO)LK*c z;Dc}1D^(~$k^7!mfNbm|uyAbCdO0e6VYOS%KvD>{Yn#*QN!zt7EcK?IeeUU>zb5?p z^qt?|u1`&$wHpC%u!IO}(V2JIhm5K1`ewcN?{8iF1f{L%JIBjMix8Atj=ZWz15~T( zEfp%*b?c+)p{c@|YtM~$hw;&CeDY&UkFp=p_<2A2xGsm?;c2Ga4T_e#z%r~#0BqY% zRSREO4Kc~TbnqjJwk2FFqFO;LOB2*pf12>z!j`+uW$Xx&TloV zW!!vb*ng`HSDNNNg}uj=nnKjPG33s?mvXL|GbXrVe!lp|M~x5x1Wzk%e!yoiXZ#*b+!T{x^jpD-ADy_P99eik`k}Jo1Vteag1pD0a8x z@YVS{U)R+^N*1-htLxa!mdoiB`re}EzFp0yIrpI;Um7FxpiI70VSx?4gW=+{B7pM@s)XZbMvKAC%dUCW_&WDpxW;TPZ%YWf7Lp@);`A;$3 zMp1@=uP>VNJeW}%^J?`F+jmMm97<dlW^729HhB$oMRv(TF&pG4>iDDe}9cjOIrLPKuPP370 zIDuqT%mRu&o1#h33EE=dMs+b7Yz}Jg9i#~BC8wt24!mMOvfxT%EWqrvSu}op!H)MJ z7y!pu0FATIrPu%@Crayf}X2+Y8GLwQoQ=I#B__<$&Cq630gyVF6<12wr zL%rvBJ^|(u$c@8S{ulG|A8jtz59#vc3xBKr#9z&wd-tX9R_*boF0@-l1}!(-XdA6- zQ*PRR_slK;^j&K#3g@O>JLiKB&imPHF&a*+^F>jt+b)S%XCG5lW+o!%+%lD6O?$7To%`%M3m?g!$Zr2)QI2rj=6ym%{bJ9)1g^xb*+4+xt+P?Hh8}(|+ zu=$0*=C?og_Sb&AW9{kuQMETL&rV<%s-p6t%3xV23pS@swU)eI#oRb=e#SW;0vXRN zNH(hw8nRXZMFbI@^&lEk-}hZgNmWtR8Y)5{A`w;=Rn0l~UAwcf(XQuNqX|Jwp~c8= zZ21A9S#Z8}a`QX+(NDIhs|+ zTjS+V{$%m)H!8|ZBb>hbKaDpp;AjWf>55Z}-6AdzPEwzoBQUv_MyU5Cgubw$Jlh>)WrG)9Xgs=nlKQ=LbJGy81cOm+!s&qv^rD zt$`gB-nx*;&sd7xEmH(pwdXIMa|7rOUW?tkj-2yXP%f;GeV+n`Dk4Q}xH#!kpZjWK zuwA*JG3LI<%m|`@zN%n2;G!h&d|eg8fwcnd3=SW)j~=CyV_Y1<@^G2wTmV#7eW*s; z<#^ABu`M>C*knflOM*;fl^wU(FK4Dblt(|A-+R^fN4Ck(%T+OpA4%>{p2sf-lt)J4_^I$$g^S z-nJ*#shx=e4bS+k3lQoqvG?e#iG3%WokbNPgI(7X(s(j%+P*9YqEHWqSu~3x5df&F zhyVa0>IYIv%xtao-VK# zuN|#^@CPHjeK-+0_cUFsIDb;UQ>S-A2VKG@}$N#xpob)#LppPM@vkFj6b#NL$Z0`2^Km|TP63dC(#!2EQ!ULIOA_pS*+ zjBzXl;K+qhN=uav(HiSnFbSe{#yU||5bKN~$hptC2e5`JB1?}U0;tN*7()o!wT-G4 zA+T`D;1o?m7Xi0;uFW!W6T9VXomRF` z6EsVYQA!Qoc|;Ud1wdR5_}mLGY<%P@ z<|BRit2r*B^XtKx@zY#AF$xM+#*8gZ+;Dg4YAHjg1{p>gDt&-7Ej7TEA{hOvOdG^m+fxC#SdHYrgfbHjm%W8rs2?-M{qPaQ20M z&L{7_zP|ZtEo+OI!-mwm*;YOC=A;D8xsS$xGn7+A03wVjd+%e)gWBr_L%YA6 z-o@1q|1hjynNJ_=KKrTg`TtUm%Eq#MSbDXNQZZ~@9a;DV#1EZTQ5c1^o(rbiUJ z(Xd7UQT5&{XxH`jG4B9SgcSh^RX~)iFNjD)0Dy=9Ktuq*T8oIPDk1<#gw{9_7G@EK z#}JUv7-OyN`ZmT0swpRf6r3kj>3fbn#a2?p6hTsq-Ktrg%uW{V>f)1Ep8V`DxJ`h! z{uu7OC3a(N_UO_l>noppc>U4ojoYQNF(lT6-M!6oTjj`r_UZ0d+xhJ#PrJn1TUYC? zPsC$$^9MgBXvf1`u*a?TpFR zW>K~QRDg|BDspzIi8O1hTXNU(?AW&opYoRW8@r#GpFRNt?L?8=CfJfw$_rdTAn#KzPQ)j z{D0l*`{d#hck<>Jcb@q&GJrQ35(sF_^K|%N_1-buW#5-Lqz){1#!4tgPi_8EcrclM z_jmQ+tFS(uT>GT`)xQg{bMNb4gS1+#k6q=+xB^1$hO;I{N5$@hAP-q{N)o&c0RRNR zI%i#>3V^2RI|TAY!3sI&@R)Oi2>Sn%$3PeW5Rf@DXJO`?V~Q=uSm^GBGvn4wAM1U$PB4AC4K!6DPGa^|;41%>br<8M6$tfmR6xG=a#>DBj z{+WC5BUQtjAHth|_*b_t*vPE~Pg>;OAk;;@7j+b>y|8f+24?^($%Z2@_wOzbZaD*? z2*yxKiJ6TtL};A@P?ih;h$IRzfenSRmYIz))>;uEBIg_ts)C3xGXNkU0X_zxBBH7S z0tl+=i@=;j1OU3&qbP|Yvr&PZF!s4`HT9@0l8>h+^YwCLcl*L8U#!lZ)w@4#-~N|H zp~s7X+5ObUN50(6)7>{-oA2NAi9Hme*kKHt8)u(>cKh5psCqtry*YVJs8)KY5c}p6rZm>H2Iz?c(&%>9h)`yBE*n)<;htHnUkfCXbi#zjyqTAMvesH@npaMCw)vxG#M60eu11v2yAf?%P7y zQ$mR@7!zz#K|{Wzlv;}75fA}@04>-$vRg=KtF7YFv!fS26V6`)d!avogVl{wzK)C) zkI$7C>)kDJ`*`$&?&Oul^g&Ud8(#Q=+51fQ;Jtg_`Bz)Z_gug1iu2_QzcKjb-;(I# z$w71X{pIlim|)9M)3!%PhgBKIlOc$J9!^hZq*U(>+In_3y|IGBf@)q1^r;?}#c+6O z`03&7%;7iw_vWX+SNHwq)lZtg{P!T7zyH-gTOQqSx@o9FT@43Rjf%-^-7S&pGvgu{ z-?y{bqK7aTPede(3`e7~8pfE`O=m+eWCVeXGsZBpx7LyYkjGS&nL$`pC3DWHtO^x9 zIX)JVjlC^@<*cW*wD-E{4L-eY+QU*BYZw%u*x>WeURz>A)*u?Ph?uje0vW3+tO}^c8Uf8oRFTL$Mo6G4$|4LZ z)|iwM=PaCoG~zy85Lua19`*%ntmgWZE~+lN0~ukPl&3W1G@eOxtt>#MN| zTedtGhEKYUYfzno7U4iL35 zRyTKw$)tYr#cCqIc2)2I03ZNKL_t(?`Uaf5(VV{9E@$J(1$X%uoAb+OKL93%8Ej`B~XY7-7F*7s}R<`DPWG7p0bJx`)0|DDOyK^`63t1l#Esbx58dt!$ z7^YrXDsmNj*O5j`r=6J5xhv28N;vmXGdyp$&M0a7{)6`V{nPb3xjY<| zZ^ynz#C|oKPLGXsMO8}9s1lqdRfAB~m37vIaynZSb*+F!Rj>P$)l^ljsv_c?L&O*( z0Emb&CWL^9B7&$nrJR$hT5Am;b5>z*t#Do~m&TYuRT^Vb-*f7b*zW9A7k2p8ALI1f zbmv{~B@}j0jSBXq8Lm@Kp3HWc;u4qh)hdb` zSM>xCvPf0eRXq~X`C?Vnl_48B8|xp7F_Nkw)DNJlh$twiDhq%bOPo^Mwu8scZQwZa z{nt+q-_*PxXyq)EEzxfI$y2!d5rFOXVYis3q8OI-usvR)15+3w$iODJq9|g_B*Ym| zDY!sLDW$AEk^T&`HQrmRBFsu;05Js^7y&TG4pb2o z0IH1*x4n0I>nHHW?~dkg#b~P+ejRmj3cRoJ2xj;5>~@z9A|E&HNjVBGRH9|qS43yW zJI@q5S0M~QR8D5c_a8RPz6_NklVTGJgPLQCiL-OQENT}*5+WZIKvhEs*89F|`@Sbc z=e)I~iYX;w=EVJ~cgBzfKt)7j&0~NjNq#gvZc^h$VX#?mZg19Z*dDKD5BK}oaVb(D zaEvKuwYKFre&WLB)0cspJFmWE&55D+R!OU!&!2nx7n@uA>GpMKPuq1Hd{Ls+E;_JS zkLK2|g_FI!eSSE)GJyH(%RAr1{1AkVo-aoq6aS%j{ekpTfk$`mzEYGl-ntA0#c-?mguAf>>eb@Ek>|hJ) zO)bW5xINgtRGfbj&R>Sf7K9qb0t8^IDM2%bgBvit1VFVu$!`PP> zH*{|c{LsJ-&>7GPxJf@>9sl(0(dmJvyHLyuDm50#6|ymT81(5+T+7}5>AQb6iFfjJ zg~g@%qyL_QZ~yiG?C<_yHec0GzHqPp=-$VFZG81(09GYK?0~acR3an~iDj{FSL@@W ziUf^#uC zjwq#w-gBfZO%bSB%n<`yTFy3?>xX|C&%VP%YxS01{c3Ufm+MdN?mv0z?4nFN)xvkK zJlA=4>v8-2QM{YviJM1R%l^_}f$e7T${K%u^uvE|-~M+!WBK5^`X~P@6kFAUPoCcS zpq~qBT5KT~St8R>J#$*{GF?=&LJ&{WD07XuA{~iE!5~pW>u7^9mNAm4^dVU1C6j_N zAPN+HfEXbX0stZVzj}UU<5-X3dUeW&IE9gEG@BKe)`e(^u52%=8vaF z4u1M;xcA-vxOVedR1$>*x3FhB^T|`|kGwmgFwP`oQn`7gmUose;DwtoIEPTiQ~UVi z-ILvumHyJ!*0K~1sEJ@BA%GxIKr%2g-uf7omW=ZdU5J5yjwyi6eQOG z2F>2-(Ve$>bF$n?B!Kg7Cj5i(VI@Rwn7{fn&%yXXxcjE?M~!uC<@My5FT=^BC;#!^ zsBo~fG1wV3S#fc&^{Tr5Gq`jP5P@?5Mx;>nfEU2hfXWl|&OtkeY6Oep)5mv@pWI6s zEDZ-*Cy_Iz6-DL@NRgDCE@LpSr%Zx_Ktc$W5hTGgB2*l_t&K69F`cBGp*JQ5&mkZL zjsVe{rgCiq5PftjH=f6pfqU`|Hv6HmXB7;F7k^Wq`|?}A|NAM$<>elk=z_|xJm0%@ z{qFpoMY3JfECDX!0bOu@Pzxm%;_s0BW_q`u|>vA_K z7sSqj6cTeByYZx5bh;Okv~1(lXOVI_z@<)H1(pOBCc@U>Gg8o+R0oi@idA&nH^>nQ zV`M@l-N=&G5io{87~7?OlBNMfOIYFAL3QwO+@8#9gHW!lTpOHw4tlG=1=US;a(p&A zHH{T0hTUPA<`ki==AI&P#uCYtiU2NLf|prq&%NH%=0Lu;b^0e(J>Aw=c!E9!ZgMjp@d2kU=Sz*ATrLm5R5a%fGD~c19?Xj z9A{oJ!r++)j>5FTGCFnh*q3fVr!+pUCYOe{o?Ce(WBlN=kH(Mh_Y<9G1qo4ZuChT! z_SkH{*X+M9>;c!EGksH)7gsJ_jg23_{o~R85%^ekd#DnWTIU_cbhaqxT^D^%7!fMoXw4mBs0|?l*7yC zKth;J;^eIQUI5kut71@&SX+Cw(^uq^^} zz7Y~Kl}Xew@Zh5hu8l^O3Dbfl8bAhz98{L%&elFyiU5F&Apjsn1`(q7wh6W|O=X$| z3nU~YW!}5;Oc?a5hhNX_2SOUhm-Ut30=xe7JKtq(Rn5<|)JpZTOD}X@yz$ZK?Y20= zJ{;{mU0(3@wf=-xNpkCa`Sa!7+wO;d)E@tM8u|LK{cHa0uQqP};~#uugS+mG=)iC( zsHBCM7=Vtxkd=dw*g9#0qMj+c^$<|DDxM{_Wic^~TB}3=HsF~YN|)EItlZmW_k?1mWnUD>kKX=%g=$j5SuJctg99_R*U-Bxf$mqn9S0y zWT|t(w9`P536Z3^$}%Z+M5tQ>$PpPs#u(>JaAcg2F#?FzRxVm#43US(W0X4SL|~Cf zr+QvZBlnpO`V z-?Qd4Ph%z{^8pPgN|eY*h|07s29+jKYY*T;AjY`Vj7tOzfkKQ77%>;H3FJ7TAQXXQ zB#kV3KVQrzrcQ?aHj$#=nYDJccYc_!ag`E+n@vtm57U$nmU0SHKi@S^-gk!|7i=!2 zaaK*%ey(@*by;@Xy~DHjKSb-mdm$tWDYQ=Vf^%(J(^RduVdANmC+K`y^zyZVz(uI< zPoMmq6lYaj=s}OA1+xZBo}T|&HQv~NunRVHdVQG}*~*|;?*?VeVmI#It{=W@4?mOD zv2tEH?N~9FgL$?Z*RL+W@aobFuRxah7;V$i$ylCM%0#en0W=pFks;%Za{_eUhu|ng zXB)*?qEv9EuIAR-jjc<)^$VbTyy&r10!>ESKRn%eQ`2Jw2N=iBSYW!>KbJ1QB6~j_ z>Y_TWOf^&Ja6X?L9txy+9aOeetd`x235D(1?gwl>8?C*zm3U<*+ z(@xT15$mco6j3WyB$fg(l#GiA3RohP2O!P>zq>Os!mtX(sd3x|@_F+?4 z?@TrgGC`9Cscv4%zqs=Bk^TN3*1JD2Om<)TACj;9o)zJP@BeMyj(Q6aXOSyz6Yn#N zsTN^5E&Gs%3M!I3t99Arz_>|hks8N5o0G=G2dI1tk_JWD?F?Aa1tkDmh*N^OqY2=g zVI3Evc5-5a^PUz}!-eh)R);I+0J`3F-9)x$)U*IdD82PFhDIksFqP<%L*iWUWLyXl zKq@T~Eu$U9fNXaIo-feRBz=rr$_EMY;?VsYw?;|LM zi_Tihg)Fj8xxTK71gL`f4o&WcdYfnp&XHHfB^LVW)=TN?HB1N5%!+MM@a4*o;n(BE!HF zEAr)w*JZiPMag9f0MRXwd(@W9u^&J6Cl8wAhjDh4fl-1u7cp7pH~$M*eKyRillR^~ zdGw^C6^kKBv{Z@^kTDJ%2%?V^=|r%SXVNn16#}Xh#j2=A?`w5BZ+BX#P-~%con0xn z{xMHqfYE5Q{Ro*E4AT%NcJ#>YescEYc01n7u`QJ=1Ugw9FBEkyCg)!0T>CGplj-6!+fec4T{N>5VVo@M_#UJAL;jX74dy9CoRZX3C?5gjdqd z=aW^LqHS4d5h5@Fs`PR=*Q-tUQg-1be)(3pya_5bHgV?0=olBeCS z>=xt2qV+D7Dwj$|A|C@nWQ+h~49cvcOOtd0ogKN)amoKzW zzR6}kl*&f2!k_ut{qH@}(^-nPsb?H;K5;Gd*I)g@%B}vPfAp~0Yn)l)9UI#jYm?;q zweIU{#|MjV{Q*083zSkJafwWH%?y^Li^A3^7fDFm+$@mE z#OXXFOfaW?D{2o`wycw{ju$ko+s>e~ywXtxgmB~*JJ?Q?aKTRJ(<21O1e-4^M?z+O zkq^BryPY8~hOB96>Z%DewIV8|%7qd_2kU1DmJ5U+Qr%G^_ns^ZAqGNVTrj~w2>5## zBLEObF1WzY5e5eg8B*|}jpPu>hY&d<$&y~dOF3$f7h!C%86ElJiH6dTKQ@Lu)aU$W^Qq0Fv+Df!Yr!o6?*JBTrmLqS~f5WyJ;US?^x zGgvBCJ5X4fer8TSBy)&u3w01eT7U*cI@o}v%UQM#>4u%f>A_iZb{5(>gI2L9Ngy#M zrA$(kIttE|W-_h=K()j7y3tI>rDr^NLw;lj-=d=yawF7esG(@%eJ| z83-B}0Cy0_;E(L=K^))r4Qrtm|%?VDwrE zrDT8*V`PySAcXk2X&R#8RI`GVjLgM|xzy)|shofuL4DW+X9gF__1AQI6MO+~4lr>i zcV^q~yE{MdyLVDMQQilKZA8pE-SvxZ18o6ptt1gI5c5=Nzv zDOVhLV{By|Ad_0^B;kyE@11F_X%opAP&J=UMkmpkOzUo%N3M?=uU0nn+J+u>yUQJ& znrQah@jaY8g6U&F+m}=`DIBIQS?0qV`QVnT%l6@Ry}d`178$jo%~scq>X+;1`&$Ec z`i?((yLOZE+;v=g9g1gR0`B<9;?Y}d_fr@h2q4Hf({qRo%{z)nXF8mr^pW@(b5G&t7YHz7_WWj`4=)oATOkJ$`$ipN&E_ z=IGn1G8LrxmKv<|UtB7#mHY1O!R}7ZvdT3sXWjC~wazQO#rW)R{%yMZU5ZX${)gh% z{spOIa`1R|@Clua@|Ni|H#}etSyA{ViIG`WSEk{RCM-#~1V#pH8>bJDM_5 z`PP-qB&likv6;SEo4YYO#WkWPFC{NMn23O-bf2gbN-qvW~3Gz4gQz|V2UgkXXLLjv&55di`q5fU(D2rQCd$dO`jEksW- zSZ^$ZY`I&km5)ac?;PBw!g|&8SpQ~rOV5;UKsq6a6UWG7;~FHdx%2@S5!7I*SnD?r z-|`>+t!zdflg_KZ!LI)-9)9N!Avj=>aS9Y$>z!qcWk@MQ(dngw3w`KYnm?>|Zo9MN z#D8w$;*5l6S~JmOa-DUr=gZGSvg*!eCwsfoY9zT^);hF}u^xorD&bmlod9x25P>2A z5fV|1kq64Slrr;C8V5umSU_l1NaK2k5BJ>fBNwoVzv*HQCyf*<^hXz z`MlV=Nb8&B#q(@+l|$a^qk&?`rww_IbGpUk^*4@rhWODoTG^QDJI$p@K*XIJ$gm?N0quNh*&B6UJ-FJS+ z!#*e(#FFYf(>?dPXjUG*bANWQQzp>u3Wp@i70k|Mo0qfxG#tLs?7Wpo4*7L)>6c*X z6>uKf-MD+tAMd--=8T`)w0?8oyc|E#Y?`^mHBZewU z5x7s2Bxgei(7>DkIc8F7@DWND(t2N_Hwv~gZ86?4n zkTO6Z1Ogxgz`sW^a*iA^xIjKIhJvdA9Fb#;(HR#0UTc~bZ1?;!AMiJCzp+z49A4|3 zwEJ-axB6e`+HRM!5>pjbbmV0^9FtTZE5CSb&Ie3E-pQT zA{0ClT0_nw=cy0Ddox@rx|f$gyXxsD?a{r|pSt!)ikhjGg9A`Lb|bFo z{tdDE92D!uz~RB+;of#Hwr)OZt;>p{?Ddl@Lm`O>7~`DB7>u>f8U#p4m?$Bl!R^hPL(2F>NJ}F&N<7MQBfWy$8?>d(N1m-X5uy}FEpEWqM$ z=aD}+2%{75twxN-VGw1uWR2je;6=x=IFAc2Y+CA4=Q5}m2pLmK0-$S+F)am0!7Qc| z*Vdgp>y`xo+Mu&;|9Er+5@n{V)>sSPfEHP&KP(45z0?IXetu+5-kG0#*R;Dr^2pO- z<%RC~e`NgD;U~A<^mM3Eu`p{|NY1nF`R>&s>z;&<{;b{kI4Ra`_qu%Mt77>I0iX|H z+E^{>$&s5pQPrV1*<&#T5Rq66-nWa`OqiYddW__gvS>gwpoW*9%U=2w*m#v<5*CZ` z&h}{csc?%y&bp}}Z#^-?vYM4f^tjGCIxx2|tqm~UE+-j(tHrbj|EXf36;Xy*hh3=GU(N^M4J+d0;NOT{GG_xpTjoIl#o&N+I7U&k2H- z7CKFWXP}iqs!iih)vtn(c~AF`4E3_=Zyou%~#{z;>jQzcB-X5 z^@qG1h+YAOasn-8vg2AOWMU#Myf0Q(vq8T2^jmQ6P43!|E$6@V&oEub$vc0M3hsj^ z0s!V+@WB&;^=+USJ_odV{(N!%VspG}w%^F&U9e-0k#mAzAXpHJWJY=^stp+26iYX4 z=pR1VneE)E$NSE^yzHnX;asF?rnLefhykK!3x!nlgsA^FZ~=}yQzvxtXu}A0TEo)9Nypk>^6)~WN0~S z6BV6Vcqqb3!}@5cOy-k$?HHw9wxn0DuWEaA`u#tX^}fh5+rQd-`5*ZHOCEbnO=%SsI9l`0n`3K*wc0L)TQS&fc%s?0F{7;GNzmi;i6?Dh9(T=C1?Z@@$ zc50^?`a~x!D65BjaIT45xVh$*AqycQ<3b1^u+BKsAVmg|ypxJ*#mrS6Dd9=hh%a9s)A`q{SdV9)YIi1Qi<8~i*>No*^ki20tkl|2HJTg? zm88qdKGDWIznEtPXhT-?=aFx`_8Lp;diTwG_iuT-4Ro>G_=?(k23Q6b>$zs_@fzW?bPd;X~@7nPh0`u($~^MUMl zSf1Og8_Fd%=&`;GnO*oK={Q77qzC;ZW%CdIGw!_yK&*GE_{HDDY#paR`MMSy0uk`& z!8ser2oW4q)|=K^<8XQX*}=7!?b*ma{ZHDz1!fA43#L(UpoXZ%1U**^pGSSMSbtr{ z85P+803ZNKL_t(7y%J&(nyK4=a&&m;oF{@vBp6qMXIYwQY1;*OTjn}=*HotL3~Jj} zrmn3uE-*|p)lGP2n^q+_d}fvP+;soL>FK?`+fVCb=O~H}6}DwIqTVR)ST_AJLxuRF}mbO^A9LB{%Ntj&BrfrVVO9dCgwRL4G8zNJA#xe}iD3XOP zCMUD1^&-i$<+b7UXOoS!(@)UkVzSrUNb)EQ`*tvgJ zAJ0~GXBab$(NjHdr%5M^MaLy+BxuLeJTOiw>8{9OH@UuH=eI|9|6G`lQgq0FKH2n$YDj7d$-b3hE>Ogjv{AONgDQ@_bV70iKc z4y$TBshwKBdgDvK0PTGG{l7l^=sQr43^~8FeD(ETEnfI4PcDP)fn(4Sz)oR)cmDJz z_52`B%W~}^cFxCExQQJdj(puD2#S0#vwAjC8j~WIc`^6QvLf$qM5gO@4&6&748ow%*Js_ur5g`EdvI{~$p#Fyb12WOn^|LHK&7*?Hz>N@bZe7!Gl(;K|2t3L z`%V@oI?Ob~whFd)F>Jm#{JGy&%hzm+QY0rIzI}54{Rzy=S% z80P>i1aI0JDfT-hhgj8fh{QP$jw+U}yzqQ3pTfZ#rWui1)ffL^djLltf5c;jPzwO? zIB#1_1lQQh)2{5WCd{YPqr)?6xmA4Q`Da&Nd9|G#jNki%B0S}Kh#RlV*Z=vQlif+U z!~J2>ROf~_c-ud?v%^Ns66g*`;}?;ce5o8eYIr6XuSaJI$ut=TJy?D9CX^$4@U7|I zHxsr;B-PsQCjDQlCg${Dmj$bl1O>$yMT`M_KtiQdrt^+Y3e#5B`v{~{t~3~`eDLc(ZKoKB~95sFZ*vXu*LYn`nR*ebLdgle5nGMz5gdg4HqEoNyLO=wo!VO$rXkEAR4K=v)GHS*;;$=@zWN z2K|>kbgTpBAR!kIcBcl#&x*AOQ$5 zhAH!5Mlf-9G_Pk3DU}Yc-}+)?asNO3o1?ow*j!J2p7mb&Lh;(q#&j)=v-vpD$!6N` z0IwK54%443cHT1P&>2gZu54VFYd0X>#F)hjk3ZW!c(R{LnI+8HNmi)5n>8K+q~%}( zSX$L}04Jr?X%>kVRfC9WRtS!5(*ngrD=8Rx>zzT0)V2^jcvnxSP1A}bBjwD1;ZpG~4xf_>xIfj$(n1_EuC-<~w)A>TL-b!Bky(l+lj}B+YBRu%a>SUX#C3*36{oJou>OOeyp?!3=rZ~j|hzoQsMqo12<&x~K zOuZOfypk+;u@vFKPqyFsdSXr!bJ~+(Zg7&Hi|1~wzx>O3^CmbRD!YIC{l)&14)>`H zj0Glz6NTpqqKE*%I5Gyn5Fi96IV6scTVeg64af80L&YwKpJyjVQ{ zyM7OMK6n?~NeopYMW)h)Z6TFDwh6E$o>Ai)+dO`}Tc#^9;V?*7UVgo|(p`M?N9O69 zQmR>UZS6Pz)q`p><@ddN3iGq|^4W94m)&9W_(va!v+Ba?GC?!1M`<@5w_sS7DsC53 z4Jk_oymw{g#fwqhU)=i-!hR&VseC`Z`d^#y%>JW2YMU-+!g?KJB2*0IJQ+eu=!FtG z6pCN!p%d1APaMI2rj-adMN%ubJ*-Dx$FTBV&1L&a;+553K}Hf#r_ z?}OKtm~p1J)Xg`B?UOt9_BT_1Qj0Qw@mIyouZEE0{F66Ps_2OU2!d!EYZnk(=W4)c zVss88re$Y&xOJYf6aVNtlYkYZsLif&p05WM!vZT5lk89n5&G9btrGUE1C0dM(P+QA`~Ko&M{o=%T2z?GGzZCv6GPw(xrgK6R>h;ni!;e*w<+tN;8*dq4h$i|yJguML0c*TVWm zzkjy>V5geLEFZYQ7Pjtflp8mOysX;A!)p4FCVM4VZQIk+ig(ZF%Qw<***j(zAJMP+WQbYG(z)>5tnx-%kCAk^yYI#4mkmaf$~YJSZZbPWH8g zR4`76AVB6(cN(6J+i>yP)#2qWmZLp-y!ZXDtCKt3c9$z&%i@$WKD@m3{8y5Tw?Hqo zyQhyo{nXD+`&lTIW8e*Dj%QM(N~cUHK%mH+H`ba|YlhJ@6%qyKMx*1_HQDO9i?6&U z`kezCOHDL01Z?tAg>4^mjncsKjmuZeSCo-Gj1K72zK z-QYbVCn18f!59i5STDG=F}B_~3W0_G>QZ-ODV}a0efB+Pp7zRC@p)`3^b$j^WzR=$ zUCpG`d0O^q`Xr?S%TmYeT<&K0vT$~V6+=1 z$J3)70kJg=s8p8ym=?wQ)qL}(A-xzW1CR&|gZK5qp6=Scdv1E-n>jJT(+*2}EJ-3* zqyU~ca48iR+{Ms(%OwMH;4GT9nT!=ezbucqlw_*O8On0?(#>>r3l^vIZ~pQAPrg$s zT)laV-TI1Ie|GfvP>(0g=$H#86JaULY~!^kmV3I?owXuM+Ufo$)#2SdjwKi&WMetV zrDSl0uijwYbDVWCi2d!o$-$9yP6L%%X(0k|k|~pl3B{NIAqkj|6k`Oy&&3#mcZ{J* zg=1}SmMXv&C1@oyadhY$cM*N?tq7z&kF~2}6?&|(ypx|Bu3r*t(Qg0M;^

      c3L&Z zQDmK!SLFK7i~Ks+WU;+nkB+3~O{CL0KKsHAy&~*q-)autQBb2O_2n<(@cHS^{9yZ_ zJv%OyNR>un-cuwFA~BI;nmfSNt&Q^XMO7xTnk+v2X7lN{aIufvWko(U(I*?5uYQ$Z z{u1bo=5V(2;InG9ox-$Vih!9%rF52MITtz*5wPH$4^B(zy=fK;&JklgJvlVKDL2ob zfAuv@kKyop-pnlx((Avoc;pU0x!uzQRN1y>#7zt$(*a{MTS()xEHP=Q=3yyW7bz^T z$)Ek{u=lmY}Lx z#UctOIA2Y1pFf>}B7UX?nY#qRR;VPORSNmgk6q0uCN2|Rx z?fN?HE`rC%FZ9lB;#xd#(xe=c1y~#Ay=9#b6Z6sA@#%XB+A;RaU-_qE`KOM~98Nxc zlc~(u7GkR~@EDmVMlx6~m~L(Bsg2Ui+Y_0>aO-NC^~~gnIsG`y?kaznQH3r*5I_pj z64Hdo24;97kjvvj#8Bj(qfr)mniRXRS2FCa_?gZmbD{V>;>0A1dP$!HncSh zRx&UqdR|htnJqnAZaxqBM#K&X9lQ(e%vWb_epH|A)@KJ~t3+_Yg^;OAOQws+1e1w# z-qkJmm`J6R3>X>uR{JLR-aZF+VxU1X~?0?eZ`WU6yQ}+qj$$OWgUf`R*S-`Rs?7 zh|aa=*S`E4PM_QTPET8LLzN`y7e)?U0_DLtsxn5#hKShHV zpFBDayZ1{XB+*)GO+Wx8xj+(f+8p3BStBBCLu;>9I-IwRap#qtGS@5 znf9){zIEf(#T)+@e*C9dIGD1bdF6jBzw)zpo41|ZGt~*$W#ukh9$p`IHrl(79)EHh zRZKa;!X#p#byv`6G`fdc^5v`Ne)hkOvOfLr|45qmm>KilFQ(`Jt9UxD_8xfeQ0UeM zp;I9fq*_tT3?^ejwj9OS#{LHoRrCXYOUDp z`1LGXVr8y`QkK)PuXpPLJ4&TS1;?7a&+(+Q|n5rC|3CSTUYgu$k@*>f_z_Vho zsRmn6tb!f@qySl<3>f1`?PT}($w&2Q8`_zOPIJMCGm%J@a*+TR9z{M}a@O0~%-4-Z zrnK@97tM^&DiOIi&3IIeCtaN_4F-=$*>r2;^2>u^AD@0`zW#sK_urYY`2Vv6pRt;z z=V6%d`>AjH>iJHeGiUnF?Cfw0xyvF_T9UHZ#E7z@P?jP{VqiFle+9{(zy^XKzvCYX z9DufA*{~#oQbtkWk+Bxm@2EOqq4Qy>7M8iE1S^{HwUKLCKw|(o(OqiL$@`! zoG!nQ*r3^))d!1#*Gon+#>~VSP<^8w5TTE~C^^`{ka;_BT;QTM=PrnG=6>t3X z(azr8`^=R^!XWr8&xDZH2H*m@1TKgW5lmBI^hz*qst~HV3s1|nlau@3n%?`GPF;8P zIdSrLX(!*icC{LB8n?#*1f@D}$vjbs7F>jiZ1lr8QJK_Sg$R?0i4uy?IpM3+9-Gf`|F_?h~tXPw=7Nc>5ahC@F^HApoR#ig7l2 zyy3>!pm96A!pI6EIr|({$?B4ElJ1F(6vRS(mfCu10NMsCv zkRoTu7(^gcA|et1q2MazA`8THQZNwKnx>w5UrP}a&ADLB%$Ejv+H0?@$Zkr!HgW2h ztAYuHQb-D>HbY}4O_(AD3Lz5;LJ%BcbhC1@y}PLs$r0+RuBPSsiIel$au*hWlE4s5 z6J~X+gb13ssI#O37gAj;&ZYjqzVcUWw1J32x!n8ImsJ1C-tH7r=R zj|7B-RgGwjCfspp>xKSixD6OQzn8KQXPrwR7wd107NnP;E|z9 zR3LKBA#!7^GcIAkg9{NHNzW8ZbZ5SuEoQtGsC+ctzvXtXp*vEn_92AsTI=L5p}jD> zRc`HU&D=zH)#B>v{D~zVHzph3x77osTZ#T)dg0T~@yY(s-rKOFO30Mu7*tbDchHqB zo#~`EZc+oHe_|zHJ1e{M672ESA63`CSxl}K?y-=m^>dTXdh*OilMBy@?mE=%{aZWb z?wvw5!PcF2E;+X@fK(>1$P`xzAhUHTAW8wI907&FQ!hZPH+%3kcl6g%muc@3KlRUG zr#HI$t}P$gupM2H*hyP$mI!3XA`gucD)HP+%zofaW4TUN2dADZ7FXfu>izHh+x6*f z@9PJruAKkJU)+uM#`ar@tT{t)YCbu4X8vj6dhh<|WiDa@(H$RooMdxSf^bLE=H7#~ zi&yj)elNJ2dq4RWWrSviE$&XF)Px)BVKn%ia@*8wa@i>fdBKL4+71 zQREDPg0mK45JCWvwFUtgqOs1B=BlNn$U8b6q?i#jhv8^rw0TWJ1#XI=6e1`Nj3Pz? zNzo32_l%`6G5}$MGoEp=DCJ6;tzwo2JT~6S?sAYR%0#Lb$K01V9+S}X#r!JEI}W24 zKpZ^LaN;AoU@dyzBB1LB`GL~mqu;Fn3aq!d{^e|6lyJ#&hibBVF7>^&0wr)T;=3oFo zBpuOP7wt8kE=-T(;iH54_#kJo-)<*KX1r`76DpAcgROip#@VFRPSRHJF}T1uL&oZ+ zeh=e3&+{zL2w4bG2w{vh#w3ho46SpO3v~bwAXA-plC&k$fgn-(qg(aH+p&DC&^FU5 z>pZC!f0MGyqob`yw|?SjYiVh*(_Se~bZmKdvhgExyt&vvCwfo8`iDuMoZWo9d-Ikg zBL&Hfd(qUk5!7m>Js?*#CW<5$gKYWa{K+-4hwjezr&qtt_O5j^9b9JGgZ;GCx%B?t zlON;R6+f2ayKjznZVK{6o^m816-sR*t36{^7Q{0w|m38?}lb4u*VQcvmVo_#UKSwMCvMLOt55Teu!x_QS_HDtv>MqR0%XY zxBuqfEI#^SUf`p2srQjj$qVnhb8zpt+SI9I9`kVW;>yQVT)OeC?-X*(ZDps%vRO8- zB}-@9BiPz47FU-3=$~49-Cp~@rOavhGfC^&$*qIw&b@lJx3s)0gsy6*lVVm`#&rNp zvy4d*i5O=>N@8HG6-o)E3AiUDWK5{wBLXqbF@_i%1s}-+5cvw#af)! zaC7LPpgHgO zN;r$a49KyIm8%5RZPl1+wzWSK-7~9Kex8E}t z%&qL-e0Mq?wFMWJ&{1V7;GmO4D1n?uAV74^3L)FAb~T&TWtpWJLpB~AGBmYE(Oygj ztL?c#+LG2E((GQn_10wgP-zA#dx;6=;RH8N325=E=1Y%5T#xd;f z-FxQwC)q+8jyJ0ZH(;`pm_1%WjV~l?ALHjwRLxfP@U`JlDcDN?^y$u;YBs+;y!D-V zjlrgT{o`Wgmtt{oa({Dt>#Fij2_gEe5=Gr8%~eJdZyQUhA|8_T#M!g0m3g3jcl)Q) zcV6;GyZyA~C2dzDTsSfR^gn8y{tSpy^~Uwvul+a`RAdS$v|4QxGN3F?48S-S7@cIG zFjmzRxLA7f1?u&u55CT-?-yfZ2{g#+|1KVvRh001BW zNkl1t)qIY2~q1ok##86&hHCe3(VT-JO+{R z%r&9gX)yu7qxXg(_oZWvY_a}azN{K8D-~--2C^7)wlhxW6X+Kdb;@VKNf?h_U}Bx;alH}F%Xe=@3D-b6oMhd7-EdUS?3&QOi0Nf@HpjA z6Y$2%CMcfu=a$#<{v4!?;w+ZC)$Yy7@qHF2g>Z4WmxE{2Flr+B%7fSQ>A8>SlP`c? z1>UB{dl!6T<0P29+E>PyG58W$V2Wd+kLr5i?CJS)r>7KdA8p><-zZ%rnZI=E?AgwR z9NOGS=6Joav32JiL6banQaZp$AP9s9;YH2}r8PWw2F#-{k(dB$r>+?r7o6xUoc+M! z`48|+g}Z-o{JpP@-hQdiVNzMQaQ=yZ{=Y)^MEPLn!L8f#-JS^1H&!xU*$OzRG*L=L zgg_K2mSt(3>vwyS^Wa>J6s)slBM2Fnpkx&TDY3YAqF9~BjK|qtz46Xycu(+go;xj& zt0!3N`G}qJ@aVzz=G07zBxEY0ZxWesmTTP)Rzr|=V|gO7B2h}aUtpXw&ZSaPDgO&X z=@`jcD;Y&I^WG70#&rM|0=(zw=<#@T&~B+KAAAM|c{H=}yDzKlALe*8F5AbpJ$La^ z`}r4xX&>D5NBhP6a&O@x47dJb`slk|75&7zCRc;^_1^z^qPfZS`}NL4Zff0Gb-Gi< z#`}uZhDTCbgWwH0nYH>Wt9oq?SQX!WW9yBd^{Iwt2j%oQ1X{d2|J)y?%O53MK794Z zGBjFHFioE4o`9>=MqW3TfG{{Euu!aV))MQTd0%q!)a=o>?Dp4^)ac$tzWRGd@50{A zYpJS>Uf_TbGf-Jgk(^h^?QGW64buq;T|(%eT3fkvHiBmeOk`&B>g=U|4Ub-zqEO4v zCLj2GbLQN=+4k<_E|TrA(^pnr)PC{JKl$>Ce~XvXz~-Q(XRHa3r`TCcS~1bduYdM% z^LuLRt3GIT`Zp7G{^;%d``h=Vu=9%xN~cn$p4jnl5>e5axIDYl(?DltCq7-@O7?;~me_F1;uyNx)j<5cps!9Ox&RJ_211*){92t4< zgYz+Z&bfFG2Noyf#v!7O+IVHXMA_DPzItL+q#V*fqNXqkvE+U%VT!!; zB%wGZ&wK)ki-$+e;dC0JX~G$gm8oW?hC*NZ&~swYxw?1r*1`Qo zSu0#q)eFVqr4!Gb(wA}=sGw+AHhWvcy}Q92DA_O`%W7(jOOisXJVXqh19Hij5{zM- zOh?D#aRWS`TRM6Aa_7_~L9OSnv1;KPeBcB`{568^RJSKS^h=#I$qt@cz;6T@{*Yc#KhS*6w##H7jJm*?2mO zP1?5R7rgxv}OwLg^UEIV(9~w9XoaLdleXS>v5``+Iw%(ecvK0^@P8 zw%T1kLFTc4^v%)c_oAcD{8}S;EtUqSKPv{mM$Hm(gKFdO`oE2{m)q@>D$9>+%$DrJ zQ~Ak{k{e8K-15U?7Ft{vtYs@-He-i`xz<{tB~x00q}^VgFHWC87UR8}lehlfJbrDV zH=WkU2hg8;?n~V(zYRK@-M&!|_b^!UO`;S4a+L%SWo>-$!PXK(rbLW1bwMwlTDtU9 zdHBQ8jXy;`?JYl@ocn{(UEIBXElW(&^1+8-l`J}_H7A~O=IXIChFDq$Ze_ao#Co!% zjz(L=S*Np}1-tpJe!Fs`x4*8lLgx3B+|+Wj`NmRSFdZu|1Vn|CIM+ewOAD=u|bw0wZt z1{B)*;0dHo(xMPjh8RO2Ap`)v2N10fL?nb%QZfb{fg!~hy*1955ZrOmTUcG!t>VG( z_TOLoE1z#akH+KKlw8G3?G?v`&U^<}x_luRpGpl7^0qoI4;`;{TUKu7qgPC4 zA{*{cbd#;?(>WU?tgRep4aFbf1j@b&LF+i=c82+lbGkWwO|l#(b$7mx!(h6sq@Tv<1x;DTUEqOv9!<3flLaP`co z_Sy+(X#@}CAUc1vPqTeDyvOX8fPEi@Xk8F%pR{3dj-qXCvK&g5l2#AfXnMCKK z58iqLfk~1r^iTcLbB1QGY`${+@LKFR%bgH;n5h<9_|UmeoRH^rOtn=IA&w4aJNJeM z8>TsmR7r(Jsj-;NJ%-~Q^qTvSvz z`*;EipZQ(=x!(s_?BBjV-hPxDU{UG3m$h>e(O4H^B%(ku0`T`Ji2#v^0Xl0bMlB?T zXq!eLa`G&i(Qt1(9jiQ7-L8|0q?%ut>#ht~n9|lAfB3*RTU?hi?_1WF{d2hX3{t1s z86WQto6*=z$DLFbTBV6L-lJB5VF=`XKqitT(@DyO0KmpHjWJS6?|og@oTHLxnno~@ zB^d|S)W+1!{{DWNW{mT+$fvVe(dn$b@2m^grUx$zJJVz)lLsI~);XuLr{v%xNB{>{ z?cHyN<~A=B0qC?7Ae;C?p7>C4=HvD-t?wO=@4uU~D(xmUhDl(EX$DGSVB7|f4XP=! z-r9-5`AZC3eEY|Avs>Z2mMHk00H>8BCdQQUbJ2BJe;g5D3AY zsiLbBjznM>cS&#g^5s~*?(Tox`;qFLQRn~LdV?L_y(4)USzT2%LYnpGWmZU(8Y$W_ zr{IDdRV-at@0=MNH}?;!tst;foIlY!sUE*``y2m{-1+&5#lewj>t{cmfABM#O|>;V zT3I-~oGiC$vHQ~>`Fk(5{FDJJ=DRi(pa*3sHt#+<_0$u+&%W^RwXfvEpS3#ce&JI^ z|Eb+qu8C&W?&#TU8VK`NyD=VxPKvg%-V+F|Rgx005MxBpLQ%vJBM>pciK4ScDa8>1 z0D*vF^v)RLy$=^Jbr(8QfB4GvA0FEKF5PP_LKDZw;{#g<@TspAS=|;3E8^rc>rW5b zy~*hC)}8Ajp|mGtS48c`%_y)S1m}p4xA%HDx6DrEY@yKeITqRraLjwgq%57)-EO|p zH%Iq}Fa3FMbX~JLigeHQJLg}_p8M3^tw*@^4__A?rId`Z5CRb)A`vO2;1>`X0|?Q_ zNREQ_9)ed$3W=QIF)+>=>mrj;Xi;>sxkb_Lk>HF65lXXttvR~k%UjiC%JoX`!lzY! z{&0V1G~FVzN2N*XL6Rj#j(~?$q>3fBj?-yn4LpZ2dSz8Z5 zwdCA-|H4!K=N9;C5(_jOL50!qXyexCXhW+;CoYu7MdKV~WwsJ@i;++4P`L>)74jv1 z;_2SfNrnw=zfpbnkN20If7<=xy+}D#wo{1I48=O;wf15fx{N@I+-(r!reV zeO@e`z{ycPd}U(a!Dg%+V=fb7DO-9DmM&AH%7f$mtxa-Mt)SIuAqV7QI;)zdL12Jf z2%TkxRGM+&-xETXXGF28Dk5^;SYs9Ad73E3UDH@&q)=7eaHW+_YUgWXyNli46J3^; z&HnE2(aq`b>YyDH8OuYjOfQK_Qc1}O{VtOcvu7k=5C$%OB{itUz<<-uR31oj)toacyHIpX@yMyUC?b z0MEDIeBDfrH3o)0OH&__kaMZ>ERWH+x)c;5#Yx>%EM30*WD;-D=6Ads8XOcCzgX{x za(7D$@0n?g)4HwN-N+OR3|&ojs3iukj%JuFp3T-fqw=OtXO%NVt0xDS3$4o6{(AK4 zzwdb=j3B5!vNhhrBgZM9J-;6f#-P)Q&pL?L8! zk%(f9j4_>PK&r};BNCA{4G~Ex00;pA!9ICeYjbtu$8SG)DVs-85YOYd+IMjV(b*F1 zG+Ssrb?L;1-q*X7Mm>AHTUV1=dB}8lJl+c0^-grBacZG4t|9VuRiEsh40~F~xm3=# zWUs(X1{MR>HX7t}Yb&zD%7<_4{qWD0VL#>8MSei@ohM$*pZo0a;U4b4@~sdY=UfQE zIY&eQARpNx6>=Fh*Ijoy{R z1MQ^ltntAbW(=4YkaE;SXoE$@rIN@w00BS@(Ke0uK?@<6fKb_b-#f=-iae@7c`msiDn-Gm#{hp+RU`<-fvD>M zfI`2Okq_2-YrWuFskAYUB4kBjoioPF&Gm&4li382aUrAgjEF}coB{G$Nbh~q*nq@@ zvN6`iIiUVRzjyMa?95{`938y{)lD|K;YSCO5+w`cy$j<+IW2q);ke>b^NdxbTC8_P zFMa|$&&?h@8b7>Ijdvp$E4WsjUbd9wEdmP0MGB*)I&4C=eD3^(E2>-gqt_?j|5vJd zSAw-+iO+vHeen;meQI*=PCY&ZTVix+q5>fyCtylx!N{39xCUdGma~|)`{&N){2^@r z2xAF)33?wneiWv=+j%NfEAa#bQs!-;GqMp~4SwQH+0<0WBJH1;JKbxNgQI5CV{8{s z_PSSiY=hl1Z~TYJ)o-@kWC{hl@~Q3zf5W9`fe*Oj(mM*({n!6)bmz6s^s&}tm2%id z*)@SKec=-_+!{Xkz8JnMiZg8Gb9(N{!?$jj?Onl;GojKXAT!Pb7b?qj+6sUuB$JAO zM?l7yV4^VwFlwm<=R|}E#u$pRX&L}Xv#hLUK-lUO{;4PTXYaiE;BUunvpt{lB%d`V zVm)mhJ98YZNMP;x^)H^8d!Zk7^>E9~Mv8}~9+I$8xmlc8=|d7`eo}`rNkx(<0-$MZL{|7N}Bq2C3v>}u+%pe*7AA%>3F>nCQFa^*Nsltg1reN*) z`CN5tH@iD}e7~tw|LjNeWO=f6KyCt|)SQ)#@j8zP(Ry-`p=6kZsA}Sa^)va}GNi(& zcwi479^Ky@-zsU(`I)y>D)gy^3uk)oAINiUw#uzw0njz|(SyCs*Td{_AGoQV5h`$w zg6BoSxh|H@=>7>n4dchh-}>_8m9LzNhcF7Wc4xu|-B0~N_L1L$!TRpr!-K82VB=+7 z9!tn&XBGOZSO_kFoDi6DE(n1!CbdS+;xBMyF$9W{GsXymZ=x@qv&f|oGI)>9WQQB_)2-}Z`(97Be3#9 z`?LSESbw2>aQ|TYzD6&=OO62;GD*mVP@GZlhFrsm>ZYoIw-*;W@DL7O;mk!bN3CZz z9+tDmk9(a~+V2qKQe`r0Md02#YASM*;EeNNqvrWsv6xwPY;ml!v|XH0*?BHkAv6?k zmH+Uk{^m=0J8Rl2;_|P`bN>kCdMK470Q6J0ck`#;Odq`~(S#)NF$39NI(uf}*%P$$ zo$=03aJ<2bi(>r?IzRpRmA8%`KI*kQ-EOZo#s-(QyG+V}ENgXzP6MGQ6e@`XRo$d% zN<^G91PDF=kW#8FONNX9B7k>pT2@87Jy=*cT5H|e|MAxN=Z+suZQbjinU!udJ>qIM z8a=dCSm{6e@hkuRvV6K_V0i0JGd}9IWbiW^W+c4j)@$%O%>1kY0D$3Xffc zHin#8Oqz-X?{s?_#fi(8sNS`&|E1q}RW}C$jESPk&lKl>Sw8hidoaV}H@?l02#A0I z0AmapM`Z9G1R{(;|3xHHfqM{<^MFKN^x~|lnrWt_ z=&!fbvYTzcR_+~1z0z9v0JH7U&Mq)p`+a1R%Q?XWL`%^EMha*>){ZBgdCa@A)9oxR z^E{il(VgMjo73y#X4}IAnMF!+d15KMe0lko+c40Pi3s4QM|WQvZrxgGcMo?S#aIKU ziFLBGv~cE1ckKzz1RU=kf9F3R{q!pfW~=QiYS`1~^QS+afAV*6?U^R9zyG_xd~z*Q z`!|%CA|^iVo2(NwGRb@e0#YF)Auz^dqPgJCd+(eOf+G{i-UE?BBrXzTYb3+TfoaeM zjWSvY5gd_YF>0{f*1q&*>?CuY6DQKef>m49!8>C2%{Y4`Sd6L_@-;TNChYk+!?K(~CvRr#WV+OjVw9E^8Ym)-)Ko@C7wCiedfuRT#ci_#+)d)E(Qs zNb8^H`Gwj3or61Xbm|6ubS&k?07RjY3D ziT?OT`O~km(fyGt+3DxzKlTTz{b8!}!yQu#*L1568|p{55ANSOoK2IYzp#92@$v=H zo=&d+`!IYpjQ3b^MW6X%@ZASL{t1<)m$%Y1C6362OcLVEMPMpPTOC3knMm_C{MYsNVN^Dz=~=e>2IGdG_v%-`a7UcL1VCpKI2Vp^MC@BDb;d}xk_ z_X&o_2jjK*=RR=mpPXxdxQDsj*q$9c&SfAsv$kZCJSQv2E2v{-sAMt<=|vFzWSK(Y zV*xRff#r4vwk&zxsABotg)n(A{^1{|!@JT9g@~3X6MeFC@e}g$$K%N0^zFYxjED%p z0Ra$+fB*>q5D6F{P>e(X1j0uVB61c5b4U$&>rJ4TX@%Z1XN2?IIdGP|k!kdSYFE_8 z=kr}9ZS|H` zdy9*zm5%vj$82nlZ|+U*&%$97d{fH=SDrursq?+}wPGs;#$$B*o7*?u(B48bbY?i3 zjhsrCE`DI)!n0E6P##Zy@U{K#e`Vf0YGW0Bh|KL>{=?N@{~cUB582$E>o<1qTsAB1MeEDH1~voB_qAsZ3QO2PHWKZ%l&} z5y{le`0-&oNf!o7&V{|vWI_<~RJGIjg?6GyKon7@vM;h#NG0Uc=(pYRyL|fYR*QDs&dFdtCd(_Qymi94gd6M7)_YT~&Y3e4XQS}y2J=J|`tvdMm;XnMR zY=}{yAmopJQ&ZWO0~N4OQNGe zY;OJNf1kq#(3FjMlCAxgGx_!_uNJ_-*chlg=p}hxTML4TB#VsmBx6FO&_bnBYGT|6 z&jmvu=d5=Q0fi7!C5;P>b-)EMq0+21x4>Ghmq%ZJ^Ue=29k=?4NHWB(bI3&8d~~yD z!RTn3u;qo~nWxu2aiRN!u9-XBua0(OGi4Mw$0!6z85HyA9jh64$Sn(?LPjySF(pV- zCW|m;W<0_SyGz}*b-#OU^mkwGnjLIrj7KAqW3f7T-)Ge2k3$u4{KmJD5h7#A0Wkvk z5Mv}J1hV%?WC#F6K#>Fm5q%&CfPsks7$HU?1Y#5fctM^86Kq4)VAWJr?UIC_si zWM_^|cW;LMEvQ9%{-RoccDi%0Gdq+j>B*izAZQ{rgaLq@3xK+;e283#gbATjo%MUk z>Z&c|zTLRG{qo(zYYjIfbhO!gcJ_t!7uT~hZAesZwo{o&0D?foWWsey$U}%o#2_M(0IUHkvUGS2ci&>piek~`CtLmXev(;7 zH6~0aARxpDL>wXq#z_*950#~GY+RuYo9(0A|2#iVTVkzXqy&wOJg=7nx;PunA@`ajFFJ@KpePm z#5}RiU?HDh1i^oF^nV>qc8Oa@E^D{T+V=Xr{e$hsPV-C;4=2r(g*sd9T>jYk&z|g_ zXXW&0;||niA~*&Bu7%E{6p=$P|*H3){EXRYNe?v(29sneO5Gh28k$^EKxDZ+hfyg6Ki~%7c z#NY!(;3x&-2tY*6IbabO0Vl#>qeVk)lg)<5$849{vL>!DIk|QsfqmF|4a$RNX7iIT z;QYl~H|{f@_0txo7^007x#V0ZAZ{AxU0@KAyz{ddYg7^!&lRUH@;2MBw_khov%O~9 z$rvJoN?%%h`uXJ#FY{#`b2M^#{hem>t=-*wjg|`+E-gKAIqCPoRdDa>y+8kQy7AVs z@Kx1V-KM3ptuyEFzy3cV6-`76cY?hSz(}Ds^F@+K8~TX z<~oX^aNUOnNUw?qzS`BhR_&{-f8wKDqz$DZvspuRi;~u=Nj3?%p|k zbWf6z7^M)Akm*b$IU#pGAVnZgkrJ6%E`lUEz8f}Qt4AZ*UX1N^o({SyAyj2dEFxEk z9FZai5-1pDF_MpCOGhpYF>*gqyi&?}MF&Z0xK3t))jX|Y-Wr_jFXYYM>;AzHY_s1! z`(pa+AG~p=Yl;)70);vS*UF`mEaM{6LS)g+UKJbvTKQWrw$S?}IQ_-pzJL2$-wcO) zYlD7KWTVNX@piDZ&|g>pE-L3xB`6YN3b@ibl}Zx_Lh{Z!YltWkcptb>LT5T}n*biz z!pccjw8+_S9{x+Eb1u@_S`auh$0t_jU%&ctnxu)!j}In{RInk1!7pF@olEo2V^i%v zxGQawAjiNE5@0ED1(JaXfvP|yILkdr*)mbp4kd<8+~?+K$cx^^XDRPK_`z2?x4zZ0 zhvXx1Xr$g}%d0Q^X7c2VKnlmNd>42G@G*u+k%%H8Au~1r6Iy3N3C5734>1r!Vi=ug zktrrL<2(WZgcv3@mu&pf$}EhW&V_l7<&^JQRIZ^yV2Iyiq=QS&KMn^7*sR z*Gm^4zWlDhRC6Y{=Zp!V8R{5$@ByQ9)zma2CaloGKpe+j|IE|NPn>DAeRKTQ_5Evy zevhO>7c$#=@${$8wJsOb7dE5EJLS7SoXn1FZ>fLw$@a<`_zE7r^WZQ44ZHt}Iyh>{ z=ymTi9>mCm6;@p}2rtP`V+NZi^&{#;KY-ugE;($=U z$27-OYE!VW1qw_O*K%-nzm%<(9(2pe^{u7kqN-^WBL$p!ySAQ>Hvgu7_{WlMhH+@p59;&3&swL< z!A_h!lB{Oc_}<-HkN5Xgl5nmClkh4?e;tEPTAR=tt`9T zCAsWH5=luRWIM6t65A0J$Z=vo{$S)w5Ci_^ZwV5>vSh=7WJHP`tHqKiQ|wx{U2d<_ z@64S$xBu(=zE3+R%K;o9zh80X6F?3R{_M|^UM#JYp__-$SZiXEC`zy(+e2jqvQbGv zjK0aJ(3Z@gk+jkZNpj}QNSH+uWENo%K~OAa5s||p&lZre?74DaP!Cp$-hgF(r`@}G za(Lj1a`nQcuDG!MRx>`@ukd8GUl=rm{kpdtntALNaXuXk1}(=qhU0FkvgKqiedL+) z;?|Vh_YZ&a#=(!dJO-SY);_cOnJ1P$F@y~pKu+%8c;OGXE?+v7dh^i_BM|Ifzx%uY zn|b%^OLC|=qORXLDEpuM>t}!EpTKYp!f~D+?_PiV#en3B>3oKeM}yL7Zstd`$#IM#sF^wC zTxwG~E8d4@K_sSdXcQmW-Ew?@MX#p1L7 zh?btZ|C1MZyi46wD-EWiqGG_p+OjH$VBGkLXHM^UOEOgkRH%(E zK-(-3bCl4L2%9=nl`}{?Ro$-6$Iiw@6J`r4>@p;3#|K44(b!(uD`(yQ$s*LFPNwUR z^jGI^q@R3UkIvr3i)a7FKfiXj@=ae=#ydaj#${m@)nPJyY?G?#x9rKk;gi=Ib*fqV z{Q5Kh5b_E@2lDQud28?Z-n^XwKxq8r-U(0mZ140&waG2#ApPNz&uO&2wqW1p41n*; zIV)8Cs;9MM!g&ZDWaH9BwY0o(`{W{xR`5F4LDj2d#!$l9|Hf8lKJ zkrD?^6fxp-KDl%Ek0 zNR}lj^p+xuPogpwSpX5$1BeI!IcET1W)T4Z5h2K`Yml=~yhzO2>as+mw1LrT?M624 z-@1SO)z}=3dd@99>^47oa`*np{&khR$`uN1_An^=5Hknw>LO`eV4C`c4Pux&SDpRn zC(`iDT|WHr?sxAuuXViL!}{XjgHJ7eVbyMxXil!b74E)q?_mF#U;OJpB^(?a{_$_) z%YR}{ZdP`#)|TG8HXVKVmo|R&pUUb(u_(;FA5L%IKDd9MnR~rnQ4~b9Xc_>}4+sJx zY2{2=lQx;TZQHKvh^VS6t#wL?nE`TteMXW zl`O{4%mDy7w{6QYfuh7x4ToOD)V+mg!LfQA$Tc0M*;TqGt$~IoyRkc9e_V6!n_BBtbp3H!(E8@-4?OMP`t!vP{%uT0u=&XHr~i>ze|rCw z@6lwJ{1j0|s#Q@NYfDX#yDr5)f+0ALXiArYOUMhYxVNIo+eqn*wz_mz(6=$8(R1$yhDr_|Ei?L10lt(daefT5Q)?+hB zH{yG5?tXXLT%#ldKK=2npFcNzLW|pe?I(+!tIKCMH=p_dbnW8%-`@Yj-yF@~9hwCb z9WH9vdUo?Ge-EDeB$%EsPG9)*&z{aeuonO8981+oN`_k;_FDHxZ^QOJ<$QODSzKVXOxqEbc zu$|hSl8h_tF2B29NFh=o^0bI(Cz)9_Zex zE_#Tna+LhM3qjQb>aPpYV!TfhIVY4Hx-R;zDvH870LTpaeSnChm2pa}(b*0>o3?G^ z^uRTHCQqYpju&YvJ=@l^E{%#){_gebuS}L}IlZy*(D`#R&F{Vlv%~$Q z*1qs}>=R!)Y1j9U!8f8TM`#T7&W;AdVzKzizlwXmF+8PD(m8kjuhv_?B+4C(U*Da) z==E+^AxI1%UpB38yJqFm zR{z|Y(~|5mNy+EdTN#uM`< zog5#A@gdLVRqAsz%9UN54f>$Dfe@!tAIO@eo*Io#J@H&}#gu1njeoGc|5EgA#mgVR z^z&y1k7=nU_xJDLzJBHDC%8M2z3az+@PCB&UKsEZpd5OOr=LClSAGp2ei~4Rn7aLg z$?YGsZEK8mt`r2NZC%$*+bLt6E0r;snT3_s%)l%lAOMI+53qk+0dwRM%gYm2mK}!&fOcHX+9JNx;IYJ77V-f+Q z%hH;HMWT->2H>a_TZ_Unos65NDV-|{hbS>bKv4inks>7`nIT4HjaKBHET&VB}XZGLy}c;{V{c2qi9bdmLH$7}A?BbT3lPVW3! z{PAzKi?OUe*?<1m)Y9WSKm10sa~1ux-&@kX6|_~%To`d0l-6R(Xa}IQpC1tZwDdY@DTItd$qi~UR6Om(3VNt~sm74Kn7W4>*TUc$L%;NFkA$Pu= zPS&XT$ck^9y}Jg+z24@-53Pp-b>l~_y?+=JKl<6zpZ%|+d8`c;H;^HTO|>=!5c*xX z_V4`B@0c}v;xDW``nP%T@hL2>9enp>^19L!aGW8Bm{g!DRco-^Z+rf}AE==clYzwQ znDSt>RFowHh7bTiqmsywL2K)oXW7^5tNpFhnQ-1NzOnm9MHxdn=+d5;RuuaPrCE#f zdZf-hck$C3=1h0s_pjf9=Fq8Rj8oPs?a(+=eB1OYgwn38r5IYaUy+%b!G zqxDsahxfkqf0xH^nAtteQCGc0R$nz>Hfy5UK+^J-u%|9YIa?ZmT>Dyz4-|0{^DplzPAqx@8=%SLP|@uvUx__j2oFm zDu!mkY2*CktB*Y4f$#g9Z|r>MXnfB|_3T4GyV<`|sTE|~c5MZX%x=%W{%=oy@CRnL zo11Q$YrXa1i+}YWm?u90Yi7zpeqQM&PA;e8g2r8@Q8lU0xK?$vbdWi#D@B2NVH^rM5z zpFnrfAJKICFiuW%9A{~=0RhlPE2VN~LgifTeT*4;^{78sj*;in1)?B&qyWNQ*8)JV zuC1|v3?jbkI42N@DYR|7@Lu)$J=fEXFNHPukooZL#1(rgc(W9DFWvddABx4sJP--gPAz78v+dVE)blA!?lg1XtIvPR3+rAk5wVyLaMz z&*`X*C1Xh$)J|z5s05LSa?Zd^gai^Yqbm@Tq|W=qp!%bpTh@~ozj6G=ch2AxoBPR6 zOm8JpPvxLZHSRqz_?cfZYY*?--^VN+rq~_s9cXP0^}4!Gfy!%rL9p#;gE1LpDJUQw$7omaB?H> zzdW7Z%VpW$dfcu&jAlJYn(p5}+B*!BwkFd;frucd5Q0;>EDB`y?KJy2aF!TzN*sga3<9ojuB-v6 z^`VO~W?m4x3+tyIx>%J%xOX#O{XWm%C41aqwwqVX<(~z2WpSwd?zr8*)y)pcfU??E zB@u-Xh_F}pXR~<-T$TO7a5V&+&pT3@lqd245@RHyvM2~41fNn87Oj;c3L!LY(t;4q8y~En|5deg<<1NL$?x6h8yGEbWYbINri&)F(_zo` z27S-80B4Ira|b!(6cvKxlw+u?Qdj_hNDBZUWdUK}>@&xNIs-xQ+)QA47`im|ZbEBn z^8?&Fx5&mQGCC{Qxp460vR>T1HVe&QbE$G&eD53n+IKw9;?n7j&;N>h=u6#n8A!Qa zj?`sfo3hFczxAJH+ka86AI-(oXTIXje1UOohi|?<{ig435zjING^Dk4>|EoP(`a2* z58gS%h1y&_>&i-$n#^V-s;X*T6p3>PNdXnw8qz5w764=BoTA3T`f9bbl!xui&u86y z8pa2Ud&hpqtMR-$#4H=tnTG~XJ+b~t-EJOV-HWrknp)C|lu_D}v8W6nAt@qaPQXG0 zz!F#@P?ioUgcho5)ZeJE+1~z(f3FX3Y$_(4<#5b)kZ47xY>HvG`7!s2zfQ~N+OR+` zQ)2lri$m?H_JQX!=TK-vOmVbQ2jVTLRKh^Ul8M1DYPjfg~qhycLMS%gVv zW+g(*sa<5>Sw%)`L=wc1IApPPH9U1%^@UH~S?s<#JHF*?Jy^eDPJa-F=VC|)+dC(> zca}^^ZHVox3k})6t$QgS_%N-i(<>LAtS>&6O?zYZ`b&4dKW(R@`rJn^esQTh?Xp8a zbNBV;U;R&V?VH$3N6^RfpIHC&-*pdt6iU+`@9ghf-@UV~(DizKnC-ZtbVX^4%DRG# z6;O+=YdW8qY*E^xP}(RWjzJSxYY{P}lyer5oU@1+V*r4NoO3zn#bRM~p|wUrK~PGu zaO>OTgE3liY8H(WD2oC`+W9z#h1CjKI3>1teX!Yrf4}D1M$>RFIn;ri9Vq~(tRQ5kv_nuq4ySLc8ugh@z;FedqK6Cl0&;Fd; z`%(J-Z_khRc;(UI7yf&_^61TP{m1tHjiFPcm5mOoOa&tnhsvULCW@M}X24Qqj%`lK zY9awnu_}ukQ|2r{NTiezL}u)|c}kvak%j&2B+bU!H_Ub%`}=v_oPAcUY(=Gv(mBU~ z(@M=g`}irI>~fsyc#_`y%e?(V=bv0TotZMeA zKmHFmzs7Zn`qb)&{tlQ+fOeN|zcGJd)?DX&k};Ce#@I^AvMqW|wHlYpqyX{{B2pfI9v%05XVz39f;L%*-L+tZoO2r$9OU+dYI)Tuv6{~WF>kC=RadV`inRi0?ly3w=Gx&f^E0hy%$bS zq-(VZ5v82HWFQ4-iHy+(2^lf~;C}`Hh^Uli<oYT5AA^Ig8PPfH{e8Ax6pxIRi`E zc8!n9m8cz)Uf$g3pI*YE%LnhYH+~Y1?<%4^JTtubj5_^PH<#lZH=2V(>RO8~1|nU= z)Rb;s*qlPG`e&CPe_B?}jm6uq9{l*YJ4p-u{3D;gFnDMP2D;hJ-}>jHpZxKV580{3 znJ4XM|6cXv&(9CS?C?&Q-MxEwwVls~YB1_A*+Pu5f(WFFvRBkSrR{9dwjm}#ZJah% zX`{8uzLgY+NNWuMDW#k<5m{@Ah?zx1YaL^3+pb>^kcc^FVL)JzlwwYa00{+HB;}kk zaE`u7-9jM{NKP?@P5~ONtug(+T1CngeNkl;t4xKIC3lFR zwINL)fQW$TyRK_nAA%z73TKqcn869MSg)y(Fl)MalH45o;Fa@XePj9J+PMv;Ym@E& z%ePkpK#Ciuw|+)7tA}syjD{H-Qvu-r@!&!BnNTECYLxGEj3Jk|Pt3ir(SP{UJUoRCod(}}SMcW0KXHzsyOnOd;%~gI?r-PW zo~j%@^mw}P!RpFqgnN_i8_68q=UXQ!FZE76ytce}_xrg0f}if1{+ZsnPwMqgpIkj~ zYyEs)-RR!Db@WOb_s|Gg(qu|@byp3$dZ`)ciBfZ=*;a#*>h;ElheFzxRZ-VM7-Etv zr7e8pHBeR5plK1~Jca-ah`j-sa*f=w9Srr*9p&v?i?FHYw>EB$5Lu0FB)xvkOj zi@Tjax}juDq>!|r0`)!vq_ozGFviF!5&;4D$crGYA6u9DZmC{7h4Y(-KmOxhcfZPA znnZ20*hR{UX)Pt!;i!J{=ZX(}68Z%3Hh%5JepzcJIA`Rk(b*`tsj`XMQ2) z)x%r+VSn4I*)i|suGv(BzN_cXB4ElafVQlPvPNw}f{=0+AZ-wppi+dGy`%sSgb=*< z%lu{_!w#>Kty_7DB+ z9jA_*(_l`;>XDT*pJ%f$h&22A8WtD`BLNE0Tr*bzRYo+UY7|}F|&{WoFWCj3Z zj36+xQp#Ej0Q1>`nTw*d&VmTPPhtqI#9&cb(uun^Ohx4^m~)L#4o9Qj>6+p8bnk`Z zgI5r#)SJueAHi@s-ocY5@6Y$#na#(4=JRm#yZL*+-Ocx4?Q;3~{~_j$gLi&nx)VPi zFRh-6W)Q#$qEl=jYfV^`LDiWB;#^70F`?wpw!Uo&=Zw}qgtqls>!PYNiwKsbMT91_ zA+`lZ2RYBX0^C~PJd_ur5I4`p&g%Hc28Y2MqZ!3@h6KLua>Pxk8Os*rOVaF zJ_E~J$t@*r53c{XgWWwmU_D%RXU-XMhwrr8FUI+d%wuaG`Y#vn`WtUwt54ONAG>@# z-MM=5YO*I{S!q(FD=0>}SI->pL^D=B?iExnt!?PR;P~Jmim0MQYa?@FHpcbJ8j~nM zqYM*vDYq&5oD;~BcBFfeN-j#fT9^&?c=YPQx31lKtzY%DA3b&EQx}(?o7`FC@s5>+ zA}xr5gi0&p)B^+%f=@9h1tb`fv=KAU3mXT^o4Tyy+uxaAdjXpR17L83l)x>tDVmwI zEo8SodiodLW6wd|rSa?dyWjnv_h-}7Yp2iF8xJpUO>geYv@KCPt3aVB0BuM)(w3A3 z0hR<0@B@el0A1I~1N5H>0$Qak5irC=oGE7xF@+!iN;@<*12!SGA$FPuXEruAmI_?7 zZ+=7VzM}K-@pOU9S5_YX9Gw54pUc6GJK<>F6N~b`HqP$F#q8AjmE&Zm_3-?spS&7x zeE;6}7hzUMdu6!w?3u@^yVq|1@BeIRa=_qP)nEPeSKQ~n%F;i)b21+{CFQD=R>lQ) z0~X48Y?cL3fU>*~O<9&z9YT&-0EvtNBo=s|%8?)=VhCZeScKrMD+=d`2oafCM3hoQ z1OP@CZQF(vP?2>`X$2_2l5Bfu29jyx9d?Oi;3 z`BP8x)vx()|7Pg+%$diF&;5GSu1v1KG1Ad5CPi;4*%1|k%#ga7q{dlO42DVfLW&gI z=oiU*qlrXP2xZ}NN}MwTX|0iT&MbgN8>PUfu5Bln8jCs1{ozEN$XPn|+^o7Z&ZG_M ze6nF?Pd&1v-}%#>YyYkacN}8mVRq;0M;_~4xe%ACyWx1+%`naL(YC7MLVFEMBUxRI zi(x+is^ zDj?NCZbGaEBQ#d52BTPMMM|O8LYM`CkO-7!gb0#_`(YqTdC3d*+>_D8K{>Q{{q}p? z?|>)=^&=Zk_SM?t-U&`8R+1u(L_!LcR@xE~z7Hg)$T=wxVGcy);r3nDEd%!~;9zRa0303aeWiwFQPbIzHWQBhGB%8*f-K$M82 zoKwsp0wO6DLQKp;%BMI@l3lg7xpL~vKu)fUtUBNkH+&w+jhbAshzOC4c3tRVN~lOFMG8@&RVL>QoPdP@6`(>4 zP3xORDO8Gx1WAZMgqy_z5w$kXIA&?vP7*hVjlphx4WXiwF15v)S-U(syXmS$*!lMC z*0+lGUe8#b)5NbVKl4@SpKT5oH{QH4p8KWI&_IIbL~%E$ir#3HZP9{7SEnv&QO20o z`;?L~Mk$?gjwutVvaYnYF-EQRpx>M9?Fe8H^wK1lDar-eJ}&WsQ9P(Hk8RdVMZHz6 zXgAnt55Cs5Z%DHk4W3jF{WtuczIFSkw{>y-sf&E$Yw3mG@Xao)KT?13A5X{q@wL~_ z42#&#(bmz9Om7)UL+U7ZT7wunOS);Bp26f7DFmmLCX}4ZstjEhLm+L9wIWEQSg>6* zF?LD=i%-pQXy+PSn@87<>iW{B_ISBN)30%4r_Y=>z1dqw-}o1Y``*W=SfO_1exzjcLHWLP}?<1Tqhvl`89jD20Vpb&1w8OZ1T= zQxXJ4MA{YFTCy4lRWnSX$>fs`UUksdZlzZamM5tZAp^Q+>iNldzJI8iWPu12D2=3) z(x|jNfFLN0{Jz9Fb|D|n+NDvov|O2H)%t}C&wm9jT*!ypv+sQ^ z?cXSQ7P9Go@UPg9{uNjm3eEA?fB)lK7q(n-)uMMAPn|KR%f^;$H6khojiL#)X3~P1 z5H%?P5D{k1IRgL@DWyc1NFid*SwytfSy%{-((fY%;VhY%GZBhN(=Jj9&KX8*JvWKU zo?SmXEQST#dCR}^f{{Ih-AQIx{qX4W7h&*JIGP{dxe*qVc6z*I)TkUaGn$}oH;2WQ zaO*zFpbtvz$;ul-usx-#G1ak1mnoV0Ua^~$QJ zj%Imr;;L*Md3T1Cvet@7=Y!U!KNu0|E{2>L>8B7;DTU0yNko{r>$(_|QdAU$)*2pQ z=9CgMBVx+%K5aBC|n33$HXZ}W<{h)kwEf+eL#f(0+^X&$|0qcb4oco>k3l=?;u!Eeoe|-0q|5&wm)?5@C=Kf>)^2cy^uHEm( zd-HbI%#Mym26Splht+VzMZEy!MJqvv3Pd{Zkc-DnC!=k_D%DOb5C1eRc%eaHicdNaU zQ|FslOiqptASo=j4$`UO>__+V5S^|} zv+9l?J`dyH`)BKNb3*%b>Wwabq4(r3!pg%*&t5$+J2eVT5DB)^S z7j@a)yI-TN%XNL}>05vF!;{<5@dl6thXy>dC9Iq zBt`^lJmm~9tVWFw9cQt|*0pwyND(6eDZ!j`$c#$qvNXmh9wk3hI-<#4S~QZgEmtP@Uda075>*E){ zCX<7<^|3m2{>y&@PhSC0&`#4^--&Pkg_+-tNz9|as6X~MVYE3Acm zSO^h702m-g-=x$c0_W&`PLV(pIXLyu1>M)(TiOZQtJ_pNJ{G{8v z@kV>NQzj{?8uqp(il!?x{J{Dh)8QK4yAIBj$2x~@$* zD1!i;IleE%XtW_DrA<+k91{EB+XmP(d*GzBSw!x#>8)%opFi)GG#2(0JBO>p{W`Ur0Orwbd1QEI7t>}QHn@w0LmiP6@%eW zE8}B~DTa`u52djog$Pku(HbB@ZlshtwLz;~^voj8<}pTe1gc-^;e|@8o$WXOFo(TF zy)ze|uP*;QsLQ~EeEl2p;=hjFy)-&oefqyUx{rHry?k!DX5Wdaf*w*eLgi`;O1cny z5cXIya8CgyA7doQ(fjDTswkXuv)N3MAtIl0Rrhid4P=mJ%@|D}XeTGfi&^xr8hekI z=bmldnklK)vo*7~6tBtmekV=dIbJUYkAJHF$XB?y0=Wq4{u}qcc4PXNYBVDS96_@g zxmB9c1<3W`y>@rpD^Cr!o}2Bq*M9W!Lu(rqLbK?mL0rFgJf5_^Q&uM2CW?P}iTDwhLSl0wlrYY?qLX(2;I8nq%qMEEIGiV!h`(6+5o$~l*Fjxi#l zQ8p#cf}|`U0gyIED-ubYsfSM)sxGj=uK0z2@ZD zyTK>ExbzEuZG3OhOmbme=%yXaS%s17m#U6Iv8`Hb+8irR)>$M%K&2EC=9~#BgdieH zDF6@wBm~ZqGZ89n5C9R4wFtOq7ERNDfGeEQnuwIvO4$$tAOJ$=eag`~r-=lFLr5uE z(n_fuq6X!ZZo6jD%vf?!T4NMTN;x5svo^*=NQEmW^F?F`oi7M22k6EIA`!G6=bbV2 z`uf8UxpNN2uN_?dv&rGLLYJaP!!u9ywmw3Gi!$Ts&7Ix%-YFziR=ZwbioVxnB&{GR z_KK7;hM7C>1<*KGxKbHyT!Bd5`{2EZF=~*d$+#~PBpdJ*d)F`P=x3Q5Ww=Y8DWWAn zO;VJj_1;E3-v0CCU!C)Ifa3ha|3!J~%ODr>tsmqc{#NYnsnsp_@xMPmDaO~|-W-^2 zHV0FsVhP+J2^3l=cPT|yly!}SCFIa8Lf09E$P&BO8Xbe5FBWAzLZY^9`hx+Y?q+SF zG-(cb8p1?!NI{K#e+p;o^Uulflrp?lcN@LK=}UjmzxATe{^SSzEA zqMjNkDi+*!Dh3Nokg_PTmF^oVdZU#_QqW>XJhC~?JMGkFcwKa-KvIrw05h*Q#i8F|B&N&9H$SRdn zOff{Qs?(d*XxQDkHhcX~_3T~fqUvq+e(vv6|Ki*Z5vn3~>geU><=?x1{q;#I&OY(^ zm5+QGnl!$*hrj;TN1DTvQ^n?{KKGF`9~;h>(%n#bTVzrQN)r@18_mX$b%YujwbFoy z0)#)sl4r9;&e0lM6b=!Yg$Q#FDW=2(WB@ggQc7#3L9)b7a)9h52gONAkmzH!^IWt_ zuUtI6e5R&md;ZRM#emSt&;>AE(> zh)9dBWo2TBM!@8Ve@S~X1yxzP2Rt@`zuQF&p&)Ax?AeV?ayoaUIR99}54o~Gr? z=*_LyUR@j>=mg9CHDi}M(OIdgB9T@=s;ZX(ri(d%az)`oh%pq_I_GkXIVNpOpkCQC zpr*}Yl06z4S?p;=K1^e3i3A9=1yISy4D3|0)u48RlVE`0lNq!PvE+929+94}g>=A;wL9+`OW5gduh9*-bQcJMYRO>j4AofjbbwH(Yo4t zzP(SceDB4TBIr0t-K;-cbG>!a)*0upN)hL==_E!aq5()-Q(EnE#=1YqnmUfzAZPAV zZM0=YK}57RW#P&Sfl~Z`IfBn%&ClyF?B|@P{mWZ#zjyBzV6gxe3xEJCSOk(H2uUO* zOQM}bb}Va>(Ik`cI8mI;M4DtWnaMY2@+lcd<5;p3D=M@klaiu@6e*Gb3rM0b>Mj=B zZZB{Dm#3T)K)+v%ArTpEi~uHP28p`XWH2d>&Y2=6Su7gRl;=63MBj4oPHSNiqnHQ@ zfdEmMQ;HrqaSR-iRa%pdJ|Q5KgM9k}@N|0Z+u{1R`fxgLRp*{h*bn>zpruq$)Ruk9 zo9ol(|8V@~OF<7;Fa1>av7fH)9*+0+@t?o;;d)Ysak_VK|5Ryv2_ZK25poEe4kbdL_+jU-D*WfYo!zs0)PMuw}28DVnRR-q+=3h!IUI; z;$Tn=0&&2!;5cu^jv77ZEFZ3Hom=Y+6)xUw_Ft*4Kj&a>HMCV@mM++bKG*gx&knJj z36;I>*3vPbyt{vOpu+vbrQ+7z-M{(^Ik<&1@7?!M?=$}iXUhjS-k2;-6vaGqW!a5M z30p%QZ9CfJQK03R5<|BQJ{VG&cF2-~mlTcCB4Um8AvSHaHU|VBYnG_Au~`nJV`3yt zL;`|01;>q;e{@WaWyx_(4?W&Rg%E-X0Cj>Tqc*FR{&>Wf4?5%L;8RDAL*}Z5XkQ;!{l& z2}ofE9>csbu`LaU>HfG4%%+G&A-;>d+UC+->eRC z?f&JSo8I;ZBh{2;d7mCWc=*DN@$MnF6Hbew(1WE_z2U$*JFBXcSd%rz3SwkIrA?M=W3 zt8An9#NW4TPl8AG*J(I_Y!l`;>KFgCef{|mT<3w$=8rvf`0k$Oh`;sn$Lpres3=pv z*$W@P_{3Se(cYaE4XxyZ(iI_r*o=y@W=K(tGKv&{5RtW35ixTNA*F;M)|&T-NJ>#_ z6p%K=)+Yf(rBf0F08SiQ4eT^&kkHn_PgrUnRpK(FJc{jfJIiaGY{LSbRBwE{-hZt_ z^Ef{wo$yZ0n-RcEOceDUtvO?`T4rQB*xX5aW~{pwHJ*`)Wt!~M_xJuJ_U z_a{gDyG>hVxh*=mHkw6H8)I{2OTsKMMMh!JdYlpvS^^UzrxXB~lmLMM$H+-YDQ8Wl zFedhhWHO87A}1EoS|ecyQ7Z+^RkctAowDoe7=6ey%aB57jnM?q`j%r-WHOg2T5=~brsodx{WLL!WDK~vmlcZ|f-7%Qz+ z5*W|slSQSR>kfulQ34eiV&!#c3l&s*bi8Q7{Z9_gZWMGNi(^S#P3!6HL$gTG zR$vwkX>yV>lUu9We&1bsc;mj0KumD+{~15``+oH9()}OD&-{0HuI<-%Uhm8*Cz>8! zyR~)veD#;$j+ah4#kl+M`N#8SYNvPosI{|_kmB6{n{<^@m|g7#6d zB2lP}cFvK}L}aWLfJI#ag3{U;Lqw62ZzCD2wPt}B6DX7Ag)xqi1d()RoE4#%A^<9- zGSY$&QcA$6l@Kwoupl7{iZHMc01_oktO!tZ5{`l~=oA%4;(#E5p-BjNvAlVX2J5h> z=Wl;~^yXK3VWg6lvsa1_eKyS0>|}pYziC$Q*|`4~)MC>9@ZW`ZegdSkD^KYMpS*SL zcA+)?i&wv}NV7q2IZh#sW!-I_?`+$OTm{RvS5OffP^Ku#r6h&{jMD&+QUU;_6e2P+ ziZo3VLaViQ&KYBf6ekgZHpLJk5h|sa*=SNIF|-6p6AH(+uA5LL4ieaa#h{uxvS8ND zvgKmw-erN~_SOsW;5At6SmcJ*)%s(_10TWurbxF{!#m@JO6?i52rvHi%?(>+w3 zm7o95^!*KeL? z6U5g0`C@i*vY3p8nF!jpL6F{{?^c$#E}l&?UrtfSQm!6dJ1GD`! zzP*plehx=rHp_HTl%0?y0qU}&tn=R2ZL74=#u8CtU=biBtpQLeWsG6w7$Y+)LPTH| z=46ajO2zkiP7xcgQuI1{9?9&+#>$4i^wZG20LHd=pPl~Tce0Zk5_Iu%|JC?N&rWB~ z=%Og9deQ53>$WA*E-#hM5@3uRK?HnCGp)6v5~5B`RG}@P_M@9)mZeYra=AW;JI_sb z-!f&VEH_SWPyEq5%*M6|t*6eqcSI5=uSvpL`@_ zgjj=;7Sj~cOr&j-R6$&CZDs3B@8WhmcxQU`n>Oy}GG~v;4DFT2=)T7V&$hI|sWj~* z-u&Uw-~OAh^L(b&@WD^!PySkSXF9q5p%D<89p*UipTH12D3Z1Zj=`g5Fn+s&I;umk_rH*EF%R0215P5 zvdBY-N|Dwk#t>t4&ZC96R{#JY07*naR1s22A;gqoAf<^ggjiP#U>+7FN8d<8rU|3# z8Z~$BADsVy+uDwYKRN#Hzoz}y3ti@)_|?N>bGUy}=C16NDW#Q_mDUF&O~#S7jN}tH zJ~CH`3u8150Y9e&~$%H_;o`^L%6RUk81yK-`X)!x{~Cd=bwdQ!UO zPIp+f?Odz2?45t~W4-0U?AhO|uRp6@zr6Ru=A*x~f9K@J)fcx{yUS;?H{-Qy>3TBb zKEnsIi(6Y~Z@l=o?R1fc?o#($@1Dm`Zk*nE?sd(EM640(5H$&Cq>@x8C7qSlOT08)}9BCM1Oi6>PpMlWw}=WA=oB6qJ=-~GRN z{0ekh!e!IDY}PjcP7}TzX?F_k93H**L;quXYd<{u?^JuIGAV!b^Y-zd-M_J$syTl1 z<$rc0M|X~P5M8G;>~@CjqV)@(lgoncVRuO{XR)+xQK+7F4h?E!QK3Smj0P4TgNP6j zBBqo=2+T=XY1`GxX##|(2?$g44W|}JP!S6^(I*jw+OXkCGFba`5adMV91tgS0UWL@ zZEt??@i@9Y`r%hC?{;V+i-z)Hv$~!?@+nyQsE17(t?b>H{>|@>-~H~i+FQBw@cL8# zP~knV{D0qFD(8#YaaOL1>VfI0tOLd*l@diVK!ylWSVG|UU^^th)Q0364ar(ID%gS; zg9iqa2e4I(MrS#)kqCmIlybSTju~0RhtRfd?p&TbP61!5FP zh`_8#kpRa8B1Rid(YKAYCiwd3@BmSkSC*C0v)L@9h)ON078Gt?c&K;z6O^xjvLYA* zBt}BeB!rSe9mWTw^f`2ESlqY4C#|av3l3`&BR2ddm z|J;wR8JlM-kMHlfdVjJ~7^AAm=tQZqD2EH*hAbP!u=c=}t*w>AZ~l&(-Q|39@X(WZ z`7_n1Io!LodDiSVSD)Sa&M_PhRQF2v+~fCt_~6-ZEYdpwS;_YdwjL>#&)xdLtHF-GZvR9C5vqFhv9^h%-9I;GUMt-J>yq^ON?nTs)|l#DSV=(5bZoRp3! z#l#Gl7>vsVDMX3F+B#z_3#62?B1fW>5;H6PK19@7r}#chOn^iLNInoESZyP5*e3g*HYn2&jkw zyg+10fJI38Y(d&rs;$Vk0MS4$zXpXIu%(tBxNr|{4|)IU;`MKEx|y3QO@Y+Lem+?G z$kTS~vm#kGS;X&rb@9DFn#R-V%EtER{=@zwpE>@~>+k&J1=T^c+$<*D+%9#yh06&o zk|Wmv*R2Ikn|dBwRssqyFWpBZAvPg2C_z$+F%U{qRmLc1v~WTcqm7^?l?hOc%%qey zNg%N>iwHYwjny1Hh>+230zmS!v_5l9F$&)iL_f zXhaHngQ0PDQPn2PlE97Ica*VLp88^b<_hZ$C}4yHAn-n9FaRU~sTDt&-*|oh&JCTW z+)kh<%I$N5v-jKB-1_#PY%h&X`<&p6aXAe?XfJ*VmLK#}fB5Q~)y^)ZR2D_yG5~PS z*t|roB2X1Vof2w8)(B81b16ndR9eT#Aq1rqA`+1xF|$(27^8?#Acol1P2v=#SxgQW zr?=KuRu?``ZrI(}T-|ou#diOnT&wcdumtP$WdRA%FN-3+fQOc6BKqd&Yi9N1yE~of?SrAkSRWe& zRmF*nDLTRES!_2i-@m5)!4LjCqxJ|_Fa7MV!OG(xj?;KXZ@h5#&yMwOLU4QeQ;&SH z^TxI5-Ya3S>tor;KHA;-!2D=_^ya(lMH5L1O)~|QEGx3SpV-AgzTVEZ|%}ibD-FJEQ!M^k}>XhXYqGD!5(#8@IGiYP#wuvz+ zQd%1UNX)?tz9$8gXbFr4NhwAjSr{oHCDcBos%>>W8^j6_Ls3@BOhQtchTZ(!`3>xe z?7UK6|32ags)45 zdUUhB{v(%XC;7c+e(u)+wt=XH{nrov>aFQFxNNynpB#St+^nbWzPmVieeCu+OP6}9 zPmA8T_TBHF9G$MOu1Vrvw=fn(q$oNr@3#%j=LwYwaqhzmK!}LnBdkchhu)*8ZW^t% zh{PDXolc0+I!8(;7C=(Q0BKSNl>wy0pscf*L!gwH9f6226Ol0nSYqpyQYl7G2?Yoc z0E7`$4nUaNnCdn)4XM`TcDOQJUCS~>GJ_jG8o&5AYX6O{Wl*~6l{>!e-FvxUQny~q zX^ib1=yV!5Z#O>{HXa^-<10PfQ3>ieEI#zh=FzA3Z|pg(aOaQyhpdyI)>AtyPh_^w zqucHNKA%ouYD%-(U&(_Dx2p}cdagWo&&mT9x(Y46Pm$Kb5)ya2-KJ?%Vk8m-05sYF za5bMU=2K^MuTyHmwr*mGq;(Q%V?t$Z(QQMl#)ol!sC9{UHDaeT7_M&jO*!SoRXBJq zjoTZ{zj9{fkxA zFeD%AB%X+Y0Kh29Q8I1v{;==Xd(h()PUQGToE@8!xkn!y>g55gpHtm?joAX;Ortct zy;mRH(#>wy&9V+ny`4vgq>al2D6lAP6)6DJS|^TeT{Fir&x_nn#)n2LBE>8TKq;%O zL()wf+8B{Y0DXucC?YW>W(E*Mj1pr^A*Ds*QJJhLhihx=TW7i}YvfAc97Kbn5aDQ? z=2fhlfWTcx!<>3uP1Hht)V%ZN^zNN3#Hiw)pYJUE!=HL`>)y@9)vw2!U+t!wRL^{y zE%N*5?8ENDV|L}?`Y4X?9)!AukTPSnB8kyiYpfCEHZ&mxP>4!}mW#4$wDuuHW&sqD zZl?!`AtoXMA`#F^8$gJu3TY8MN@Fo)kP!IjbXvuu7(k-|IQ+7W0MDrs#CF$rz~dY+PooYpS_{6jBU84TCZ^x0)9dne5F%yZq75 zch^+?qkrX3UUH?&ANcaDy>#dKm*aSE*-=K4lu5SSpZm%;o0qolz0j{;e|B=~Roh?B zu6(h0^h<&(G0x_6{l~js-DzKnENis!ne8XktM3%YHz$+3aoEYW9_wy>cJ%ViTkqUR zF?Ks;r!2EfE2T{4KvdI8hzcPCBu*7zO9}yinGsQIZLQT>d+$Yr5QQbB#3HS4Nhzf@ zDMLyrW3_cant_xu%4i=s#-#20Fn7LbVvGc+wKk*xz_)Etl$=siRVZMLNhwzCoI$KB zK^IjE9&~?swYM}t6D1tM?#tDi--(B>^z}?St94x8=T85j%e~dk_}Y)l`SoIU8_+{6 z?w+h{fBfg`l*Z40W4)}Xz>77}cm}XkmuZ-Th zUf+4+F>x^+Ba^nM%aaqy$FmI-&Lx`qduJyW0$`LeoW#>oD{M8We2+b4e z1Or{3qt1nF{c-Bthvhkq8k*haJAYh#^A9q_S$?MYsejP@=$AlepwsTl&*JP57gGhu zO1BJ6LY$n+D-uD77;51dBZnkFO4;0)EU>Ur z+FDY&3BGPT0E#kTT;Ay}FE5uXE2s%T0U-zi5(olmAPq^>9c@g6RJXU@KED1Aj>g6`x{ota#p>4Z!TZ(x=A9q@&cMIjO%t#s6x+cKN7&7_ zp6H(aNPRkg{<}Y5&)XZ@hP1F~#BP~8rv*X?bqFns_@pzJlcEqKAQ|h7vCPtjm=cpx zN^3w=q%)-~sY+y#5{63o8hlI~icU70FN&hj!;a#yfB9=^u~&5-UiP0=ib0>N) zDb-c2l+N?Q*eol$L3kB5nAWaIb*F=M9jj>h(M%*_sk3eF@z8!fP@qQfQXE9#%4-eK}2N*5lErZ zDM|vdF0;;g5@7*mU?BhyKmcL3#*!itK*SVdRnJ4LY>@>l=AK->vb4IIm4=%mIeeRM zy%bNc8=8q}BsDR1M#Yul!iTyS?n`_$yZ+72_{D7emQ-_GdSL%}ef_B~SKt3ueRxC1 zX~(#z2KxTb=|?|*xH~q4c1^rTYV2b*NI%$l;p*(#4jj3SV(aXd@nj~l z0{voYt}H#ao!@IAOGy&5HpW_qT7@JrCM0F7L#09pDKrumxmCuwlz34!ZRZf?%ihLF2>}GK zna@YUtcJsWSB0y8N&ax0J-GhVuWF%o_s;nEG`4LFfdEAWQTGN*d0vt>1k^SyMAp^> z;L11Nw@SD`X%FvAT3&tP3%#>>eDUAJ@hg-md+F~j{Qdi{znaJKlF~ez&De+T(gcdN zbLUo9v*wMj%ifDN&t|mV`@(h^m5-jI<}l$d~&Rm!rkF(43w_ng>h?VK~l2=ijT zNGZX4SV9OXB~pM2MHo?OW3_dF6j?|aASI}PNPv*YI%kY&A!)4@5{O7*5JABZLW(g7 zBO(xr2nc)MxU$f_b?h#6x_$Q3aQIHT@gv-MSyg)^K4`m8Md+-_@M3oML;Z7)t8%%W z-x$69SMKiLl=XEE6X{%-$Ol#)`>B(^{z^&6OFqvy#{Kkw-&yBT)o?vlH7Pj+9SOGFX@WnJcSRH|xy zVg^vgT5T+Yq|g*fAo?c6z!HHHON@yK30YFe40czRJ1ax5D)DR9X~ zk$|ot&z3Ln$^*sle4=jUmCO5PxC%B`Eb;ma^Z)l>POkr;TthrEmt|y7Yl6(^PSG87i+&Dz2JK#)jr?>Bb*mLZ(GhK&a{vmI24w*iAb~BQ zy9TNQx(tcNGv6jH=zwgV<+&jRVwDiEU(6P}Hx{?wI=%B|tfwo>+pbtz`tS#hIllGc z?`G+(ve|d7H?aiO0XwLQt+`w4u3yN`JP>AZca3{B>)1{DWnDj|l**d!In`zV&U(%tmW#j8;0u)YP?z5RpPkDTxRvNSu@= zr8J^qzy!iV#%5#;kr6~eA|%ur5t|f@FJCNWvUb3c@i)p8^pTMXszfoigh$ ziPg>V-TBQ|!~PqcW~U4%(kxJyzBsce&&ld#y>W4P?jqPBBnRnae(TxM3xA5!*Rb2p zu)lfXmpZ+T#WP>+DwS#vX_gc$Rvzs=^^YjH(e5t3{zv~)b1*K9WhG{q-JI|Ic<1Vk zwAZY_y-!>oHItS8vW!BzJMB05L-_*_miKo}hm;mT(wdZEfyr#9jI%bgE;H7#Nb-&4 zgee7vmbqn22!eu`GN-!3qBF=;p`jYr`?ss{&4u4VnPlR*s-%S?+fepQT7Rs!`Vhmg zZn++xoSg0z-F)rxBd$}z&YR+Kdx^)*N(3FG|$&J zJ(S{6h3FLPuu#*3I6H{45RI63)6yBea>;eJ$u1{R0!IdXn(fQMbv}NF7e`hqw7PAf zqCO1owHsHmr($<9|1*hn=wr=R`8PXjhOy2vZ z5lNs(XG-Tf>t(7i;1op9;~km5LbF%elRKfRl(E`cNFpJ)yp))Pl#oq=3`(+oGrTw0 zp(~fH>jPy}EJ@Y}G1}xr1_4kQ5I{IBM%C$#A01bRCzg77xl~>{qvluluKgjUw{09{ zkz5=Qk|YtWZC;du z6p|od?n^r%SU;6U+&D-s*H&tpPCqW=>SyUS! z%R0v8${0WdV&>?5(|QjAT5DsBHAa|Ih$$r$NGU0$w9>-w0}vmYqR4IL1TaKqKr+VK zTp3HsCXpoX3rUzc?-WFYfD##)K?D&)2!fb^BPSrry4_+pFhvd;VKJ(9u8nWMo~CyT znH1De3{BKjp3xhR^5&y<5!DzkEk z9X@I8seEv7<)S`YsvMC72#KOVh}^b5>y%kmDs72W5=q|2$vh*CS&@iZATY}0#$=Rr zjq4EllWPCndjAHsQ!6uC>_a%5TQ5pmXO&VIQ(_@y%WSY= z`rD?rg?dmga6Sth5do!aoh>?pB`q<|_T<(Jv*W7~cT4A$fe4wvlFPSMd6t&%!D0wR zDKQA4Hb_bY0R#k6Xk**5urfwjXRip)QA}GXQcx76d^6NJCaa zF@OZAiNKlC8vH@H^{w{gn^x_C_*he_GXvT>6pKElBwexVv48*Y(kB^KszYCm>iMjK z7&0vyTB|~4EsJV>3?cX!nZad6Z#axee24(3vrH)yQvwE^Jh#(t3RoMgJF7Jw40 znPk*p2vn|+we6j6rutU1{;AEM`bSz>$TA3CCgbX0e{{GX+ctNu%nN1#f%hz`8UXT+ zWAsFEIzBqSyR&4n?OreFe*WQK;2z9={I8+C?)qhR&ljfiGdowGH}&DVn0hjuqED;a zy~|H*o;yE&;hTKpYXh~@V%M)e();YMgzVgnle=&2J>#=C9Kk)=g|ktocVD-Q*R6ty ze_-v&|Fq@7_3wUf7;6<8AhcO#Y~iEKs<^UzCM0P?U%DrB29`A zV~nBoL}ZNt5${8cK_C=mo);w&B?bXPtw~#@4U!3o8Qz02a*VO)lmY@Ql2~GjF{bx` z2uK1knd>Yq<;z2I%AekCPi{9mZ^y%%S(+CX0k9S;<%U_mPp{tRmM`FN160P`jE-(% z@Tz8ltQf83 zM}>0)j7IHG51+qvbyhNNb>=Q+OFfQp)%9r_!rttYXC7avi<~vQ4~4WBYNJ?J=2<~V zF$R$&#F8XciA0e#w#>3#X?i7a-Ffbw%Zd&u1BggE#3X=9YfcG-6(JD`Kmea~4APQ_ z)kw&(T{QJXQ=-&xHBMokS#*wKY}zIulOcs796d4{0z<@!>qUh?navW54?$tdVIJzS zpg~m#Se*?(m7ueTmPM&7M>K8QGAeLOAzSaRUvO(@JclqpuJ62=&933>1(FjXXIu|l zmmpC)^^1{GicD|T=APEf^8LNDAI9|u(~M?&r_GzB=k%a}xXaH(`j3H(K3es_E8;g00G!N{vOzWbk6wiG%kC25Jar6_2d-cW>XMXzE zwCl=vw0~`g_7DI7AOJ~3K~(#VQY8avd^)QuHYziyA$mpFgm^q2t*k5!mV1gAp*=ph zb9nRmYNuT9E_u7u{m>V=E7RwGm(qT=wr0@dUOQ>tTq@k9r89c(?ZsQqbnv8YoGO22@Tq@X zAMIWJ{xf}FS&^bFv%Cli1C!E)bsZ#^I5oav@uZkY07!%+aZE{AwAN*oTWdIRQ#VAE zXBh&tf2VF{F0)ydX{`km14dA!GqM?wPRv??GX^=u6h&(hK_L>9l-j28-bVoKa$DrZ z%1{rx*MQscC?ZyokCM5$k+7QNA<;z=#`6@4}laQHzzyChqs$*thik% zd&FgoU1+n;nN_tdNg3o#Jlb#n@?W_6#Q=BwY^=@tA>JF8A3p!7r`6^b#_=mLW^rDR zk9Vtjq;rC<_PM$~+Vf89GUpVQvaAEJ*gMF_GHi7olS5S6M6#1)7SUSU&vmZ67eBMs zlZy?cCKaw+8uVN-%&12gr|Ib3_V{*c##&lKF*WskHW7iW-0p0C5SF%~KY+l~!{gEM ziJvc4iz2pu(F9LMvR-F%bK{;f^7i*mzxi+B?n_Ej-1^Y+Fa8(2@zMQTcX+a+!#Ky3 z50$FsF7Tc7(CQ*QI< z|7Qulf_BT&gD}5gt+mq^{_l?`_KAJE&*`Yi8Zi=LkU+M~5DR1wvW(4*DOb6C?@Jfu zE890z8Bl==kN}MgLlQzG&5YEOx_hQ`Jo)qqfBf>^d!_evOXcTzeE0jmRmhX=ou6X1soIr#Uuyy77?zPLZ|8e^8_h9xO_0we%xbouonV-Z9 zpX>X^uelu7E4dupK zD1(-TEx~hII1SdoObL`FBLj(#x%bu;UBJ)<@Dg;>hQ7eS3aetv6GFeG<9w%%|p^$o~i4-GdR8mZQtMd z;r=WCtf4z5J}i;hJnhrz=FB<#(ods)@UP+QGhj>62oiuY+N>lZ0LU3^gzSKzkF!sn zOdsr18ygam-dZjO!%nK%QUU9Y!3M|Jw@1M11gpch#{~ zyZ^Fy@cL?cD5Epmzxa3Y>Q5a%iAP6AMR%}WWRv~TqF*I5-Z^vX{5fK;kg;sCkIUm} zzwT1VkcE*9qT~>KmvdlLCbWDKp)l3fI@-fos3+Uku0P{O1Z6L)yXo-V_4LDbaS#1+ zsFjH(r;Lbfn3xqnR76!&0g;%Hi2$>rh&pEwMUp2_CQ!{H5JJkzebgv09BmFZPQmVV zJoPM=H4q|*YS7R@zk-8D8rCQ=hYloyO1qj`Sy;|FOY}jr5|T z47<;2y{%LN5(tAw=%St+^(RMJGh35X7VG77F<-7)c6M`Xw`m4BO6qftG2#ijt{~@P zIZBg(89X|;OC{K0F&I~-J6gW~t&@`n=9w>^`}x0Znr9%cx45}HC5kXZ&1OS)~5sGNcsjLPu^caId_*7C(RN2v1#3F+lR!%GJXC-)Nu`5Px z=ZVXrXilcf!DQ=PvH3LEOXxRYRfPTN>S%x7 zAM|ok6nW?j2az@-+39MHjnmRhS2O2|YfnF0ow)?0bLr|M3rDb=>jB zsn7pB|Lk8$$MJ)AJ~oCOBu-uJEL+zF4Pc9Az=bTA3lVVE)n(&s*{#|f6C?CwX}C;i?$j_b67lv)nQ)GVhnu@Ax1eQLE_mxVQkP%}aXm7Ee071bbR%tC{W?P9VG%>>+@(k2LjifRVPfB={Y z6(9pBNCZ?MfY`#xZO|3On0udN2K|(1P6Ps&V`#f}(Rb?RfVd%+gf_=EMQqSV@@vUU#WhfnoKohPoa6!W#8z9w%{|i$wJKouG?d#q+C{D* z7D!{D5nu&U!8)v`^O%yWEC96aDot1MWa{IADSJ}!vmV#b)K$6ZdJZe`d#47@Kg5Tx zV4j@}pV|J>FPqWl)c1Pu{neXaPqPn;!MSGlCw<(S9ky26dOTdwaFr6EZ@A`YC3Ymo z{qg%%CBAy9I(vQm6EFLZUup0Dk#$XV^=J6(%LgAmoZbG&g_W#Mn!G!SU<=MNxtXOZ2!dY*{|W~4B+hG=$rHD4~N<8jIQ(USB`$~_uu>I zn>)J`NtJN}SJuXrz}A*cGZ=*|UF&0v*1As-A}TN`lOm8v%2BdJ6;M@FU}ja#DWw<@ z39Y4O+;)BHJ618E2E`JUWoa0JNmPTRBpHc`!4|td1}_rbpyh@~JLk@ysRy9Td;YC& z&fffXnO37gv-HxrVW>9F-}o#({XCd~nvr<)^LE{b)ok7^W*GX~;ixLAq7-!r`d*ef zMvhRZwZx0)*XZo_)u(Q}45^c&H;>=_#^T`J{^)qHsL!0bZ2iM~PwwEsKflV_6=dpi zj8tZyqa+>_$n+2ip|hjvDIQ*w%~J?+eE49U*LBG@#q{LB&t@u^93SVHDmr`R z+^KV?85P!Z|H=L1{ZB}uV+F{F1a2_cK3AN-4jbolYPxxPbhug`?Z<nIW>)fux+HN-~B@XFt{VQ!)jb0=N(`K0p^@^jTtf z>eA)GxpM#tpnzFv4Wv4WN4PMy!slUrRUp~2YbCBL&-1!e> z{~mMAJ1@Dd=T?WlTO7NpiEc9}hqfQOp~+5Shk3eq@^(&befq`v-1Xth&-WjHr@jA& zTnxrHejc`;d-C4B>BsL4q%+;TG=N+NTXj4dvX`tdmPc<+Wh?C<=iuP^%_pFV$Ha1VLF)(M!TNTw|6fdD1} zL}Fqh$~mVHj6rLe6htJYlvC0yDyotVvnr$zb4o;HoDqbifMl5sBNe2L#n{duc|Z}i z+1Ay_5ZYFJu_e1#w_g4-pS}QK zlh5l%NAq=HTl(IEb2lZ9*rTtJW%C3B%=t+sOIkl6WkjO)O_0TFi3)|a0% zx%}kLzCT$EVuBcR)K=7NPPQ-a4o?-yf6_mCx12x3^(smQW-HrW9Gt5+FWJ4TnH#@o zQ`asRi=&gnzFQTkFT!eAu`O&wqzI^vbZ-?dKrHNfE7g~-3n7;RreN{Rr8ZT59#(N>IG?RHMmt+uXRsKfYgA*mxRr51gjsV;8C2OAHmnFa zi>mUc3^N-7;0!s0EKwyR2mv622oz=AwXyTb7R_qi&QE4V-!?gtN)kyqg_vWE0$5ZP z5|gnZB|xm|8c^0@x$2jaw5qB>Gen{gd`_tu)H^$yZa9F#ishVB*1!&#Q{j|3hJ!op z&DZVX69da)Ym(e(zOKg`&*9`L-Z=~8z_+m8Z%-a9rgt&S8wV8wh7kE4C#FS4(`qqZNT@@z84IN!`yU(tti`Akps-3Qf zQ90&Zgk|#migno^-?Xg0ykK`Po%)Fz{gYRh_r68daP#?Jz{&N;@7_QD;O&vNRag!k z65GhdvFDR)pqXr(J#*&iD{ffF$9E6E`+Mf#y`8<~ay?tXZu9)lZ@m2T$r%FSfY9l! zfA*WQx@qfsuByh{FA7!y?4!0m3$iO}Q`YPp6N^AjlK)sl6lP!~0F{&_XA#w$b4(0~ z0H6vAC`uSh>TKc6U|a1Vib0Ulf}ie()k&5Bw$Ak=mK)vhOB)I$DuoxI45YM_bS85?v3I0GpjY8JehUN$Yuak?p-`P+_B3i zZyrDVLB+@0E=lX7j@-soyY~V#7eyys%Zr2g@&106u4%|{ROyS{RH!Yqwi8N#Bva_NbD?Q zGL=uzltu78kwGL-w9bhrvmqi;$vFcm5#S#Kra{}ToI_)vT`yDYilPiYI8&=w->YV8 zxDv_hexFQN6czwNN+QZk#uy|L$pFZoa@GK6I;*bA_Rhx~`uSM>f*?bxJJ}8aCECCI?6$9H9X> zVe2I4f`@kN9FF!PH8k9#(KW(zAhP=SyZu|g)~w#?=flxw{uaOd*B1vzt$)jQe^f5M z({St8yo{UGnV0LmYsdGO2cP)8opU7v3QCX|dr9-v{>_RlY+Qqlv%A;N<#>Dc(SL+$ zJh}eoXyeACckk`L^Tr^pn!MT`l+K!{)MB|(I}O?cOtyDUU%puFox-DK`~Dvm^Zx>Q zf7(*q{mkZ<{zh^7x{ATb`ry&KzxA6g-&b>soGGgd$PF2n!9*c6MNu_EmQ4WwF=bF7 zBmfae#9)~bP(?I}il8cFK>$)j1r?E$B=?m|>@3xrYMUq|ITn=BFa2tobK+(gib-pR zG~BiI@YJcRJgz{OI=j_>^qs}s?-w$&q)=?EcuR&C$Cp1-pT7ph7^KP(`@_S7{U@M; zAXQm7XEa4Z)tn?p0x_0LE?EmK)axqrfyFtsDQ9nB$!0~H*I)XKrd3|Nlcqm5l+DId z(C)>1N9%*v+u8dV_kW+uO*9sA0?A+<*b3Bul1L7+R#;iL$nj{sdXN@(X#O~#v~fwB z+t1Wjzo>(YPYx2A?eTC@In?Q$)x95d^AC!mEt`s(4XU@vY(*UV*2I%AJ6wh!);YsU zCOZelh|9eVYj1}Os*_(}SQ<7`ZLjJ}7cXC_VBdfDH{jiWPZVZ2bmu-d{K>z>dp8d5 zA3lEYph)X6ww5%ZDeA_QWsI@&KHIXaM~yYh`I6bX!sVnX=a^zy)y7)*6d@3Tf~u&B z!XWq-G&mN5sJT;3ecv|CAPe?BcU@@vSeKQPWFb3ah$)L^$&!VcjJ1S_L`cR?|Lt|>|DlksavTMp_n3a)@D5|P8771evqKPe9Wtu+!_>C>Wb zJEN{dn{!GIT4Po?yz=bzV36&= zm>d%k15u3WkL7HOl9&~MtYNkQ8dJ(S$80PkNQ4v&WP@2X#MrsQC}{@u$@jq*t~A~{ zaE?vLImHM7Ohn8~%!UamrP%kqh!{3Zsv=o3A{b}0fLS$pAs$w!oXr0Shdfy|lHC9xuD_xw=H6oPzgDkXUU#b@9LYdtAlv%HQYxA1J^~&+?0Z zb#mj+01jZ?e(#_B!?WydJU(39tSdu8s)THfE6G)4DqvUC!;~c}5HS<0YL*0$fyFX2 zqGZ(+NeMwEB!iSgXjg65u2n#-DYv#ljt0bGHkd49RaOzH73RSX47Pi2>g}`Ra~DlB zj5q)3`u#Wb=)Mb!)U857t+xhGz2vTb&YXWvi!HxS>o)j4z`8Xlq2$6qUe{hUH+A(|X<{|JuO-SN8b`c6_8=OM4v^hHf&ZP=j1tN}P#j+Rp4 zs6@lFFz<}*01ECow}3p_I<@oM=b=43`Pcu4J9yJlJQ-f8zVa)h8$Xj1K6&d0{^Us? zWxR7fsBJ8|Fe|__K`>R%WhM(qLu)nWn3ISofC4BWF(WZDqcKcYKx0T*a)fNiI3feY zq6|PN-mi%zgHPa_n}M}OPU5}Km<3bLsjvoA+IA%&7)F(xqt~3RVdt!6Mnw%0x)^do zPz4~wqAZsf`_Dz95v+3~s0|K#ZGo;>`ccR%>Qo6*MQm;M(y z!1n&FsLnK#+|Kgqq$-QfM`Ytg2BW48eUubcRMC|+vl|RIgurvoY{-<>)y`Cm7E}Si zS>)P50pRC;eUhaIj07GeYF5k^$*QJ^q*OwEVK{z4`xqX)n%?^-arXNsFzYs-zVWsH zOU-9vbUc3?-uVU}{-D%*Jv+7hQLH;~X{5wA|QT zK6TAZ-~XLr=c>8z^VQ_);~%}(KRFoGRoAXTnPzL%EkgS)Ht(G>Nds0L_?q{yz0 zDKXokD3LIytda$yXf(u@85MF)3{0S*?NKC!82b=I06?`i*G*Mf6W4xm1gW*IP*=Cy zgkpl@(`K~0edfaGsf$G1AD{H!`a5uPNFgEB%QT>!7l$u@b$IqUtT!}asL~?ZYuAyU#)%H2O=)4wJ7c41SM=KUX?+>krdr97K6+NRR^|^5JUwKQ_iAdtP=$w zwzgnnMKR{ASp_h{!jQF8SSk%TRzrv>hM2rh%d9;)RSKWd>v*5E}$UAVOqPP%kMNLm=6=Ym!_V3cl@D zi`e(h(4Z;{XBAC$gFc}TA?27-LICGn(+rRilmKD5XceGvmioEQpX6mEyVZ|&cW*pD zcd_lj)7WO)x69@HsIG=ZIjEY^aOX8?#6DHPkF zI~r5`hu@>M?U}4I(`Zf^2u#De4ma!T%^Y{nx!&T21d+VvaA3A zAOJ~3K~$}pRjslcleTGkvVOdn?>8ZDmwS`bUyN>pwxl`}7axAp?Ob=4{%bS5aPrQF z-NBJ@<*M@;aOLB8yirx9bJkfT5@sK{4mp~WkyT3NS`=h#^10;aNh|XFj$|-{? zE98(;2%5z(gF^6r-TU#W-MT7LH=myziV9Z46;_>_6q~1a&R*Jm`byn62&>tTzPo?- z)~WSB7p%OD=V@#7)R%TX{}OAO3dl#Z>9 zf?fb@>6#H0br6VsDu9)uP_Hp*pSX`keCDp#5V$yZ^@0!k)9?J+q<8@1Dvhs~m;W~D zb06Nkxmcdyjgm$q41S(uY-MV;XEu*o95LIBsrAN*=#}rZu zpkNFaMF9#aWf4tDn4L51(kf3Mgn1~dGmCOOyl{T<%=xtc>PH{_iz`i=~ zWD%H=5lNG(qH_fiwd?sRETJH4YZ9y(nqg6ntkx5;+dLZU@!f-0e?uRAf7|Hd&XfA= zi{+Po4z4{9^#){u)`RbIk#cmTHn5V^x$C-ZAKF`Zq;^s=gu{I+h~Xg05f0)1OSE9!_mi! zSHC{rzf;ybbn5ei7yqI?{X!Bn@#u};`&VZF&Ym-V?w>sVB$=qBKn!G%EU_bF32m0l z%vDuaRY?SzbBcY6or+pRh@66tAz7xv7SRU+D9h3i^<6((ttMyA#F(=9oTV2@uCb$? zoeS3{SDz_rXRwv`zdwEBJ8*cXaX6P-o!MEtr_OxtYs0HwG4)wk#KpmWcf8-uA46U{ zmy6OARjE)A6wCxFA_)MHiHs8q6)(^EL+BiSF^d%mgy7|_-(+3~y6kvMf z#9i0-KA6H)gArLPL>Vy?v8%upNg-tcEK6=&UTb%-&T;S3rO{Jo@#s$f%DwTM)8>+UNvMyN*24YHxQBgq%z_H0WGqZIjOO7cU z!$na6V#*4@#uT8Gv*w(k?o<)MF_wTXC(a3S5X%-oBu9XZkh27&-a56`AbH!04gcEXZ+~ZX^4-B^BgFviKoY-}9gMjg)YW9YPAVoRZJOHmb7!+N z!XO4IciEXHDz22IU~4i`QV4{JS-Y-{J}MXlCy7-|Val2ybkkWpNhOjUXySpIN#g|C zN5>~xZe4l)GdQT?!yiw7`0odIJ}zhb*u?n|`U|Hvu79CC{TZmA1vm{}>8ma}^7N(!+8N?FvxAIWP`1#d{yf^k$rWWHAIR*Y5J@rLWZ&zW`7It@HfB{QV!@ zdGqbK$dY2vHChB@MFeDK%WOyEjTBRi9svzAfl5ksWeIai*$}E?@O|)6BuNqwwbs;C zT^0@$+YGp|mt8&H*ceX6Y^|wlv$a75qpabB*XBR|W;46VtB24p(BMa#U);L#`SHs? z#~YWC25@|M=k*_!>IZ|N8tX+&!Bv5%n$am*MB+aoA|WLOKsJhu){%2SCJR6oE9!GA zoKPvR6ZWw*fJIuxcAaUmJ#03?zxo^2zdOw#Z9KPq<5%bR?EO3M)urP5U;q0fyGw@E zcr?B!)Z`fF%hIcjx;i>;yW>u0hpR_Aa=Xv{%$b*evD&%;p#)^a6?7lT;~&lMzuonr z+BiGD{6fg?=+UD)H$NVsF-at;WmA>Is;sRo$hrj3OIB;Mr2r6BDG{urg_Kh}+S}fK z?pXuN`FH+ZzV!pjd0n47{gYp#=l&EJg!Qqe4qSokX1DJ@xqH8zFSaIIMLDVln@Su- zQ|PmJN9e3U!`}NCqe8aE7-!j7B9g2r0h^+9HKEA~Qc757Q2``m2gE6A$QcDoR~odM zGN`hmY6`MOo1C#K34l~3#~i$8qPnV8q-)z4f^&s2q{(N=$Rxxe2{BiLK~dB(rsO>U zJ7Wkir4$sRVwP-)opYetuUEnQsw@#yQwrWo&W6|(mKkhm472xZ-?upjm0UVoSeJZE zQR=Eu#lGzY`VeLXy6nq?PEK7tHGVow-}#;8!Q%_h{bd>d<=JcB>(;OGz@~DNz!2L( zvoo6q)zZ3hb91BZW|G&0kx>eEsTYH;?IM)5tF1K}Qror*AD61p8fG%qI%`T58>6C7 zrJ2KWq4Ty>wIhv1lg!9q>HOjJXn!5*(W#v)&u*OAklSy6@;l#fk3THwt~S%<5ZY=Y z<+Wk`{Lc2v#l;)2cM59;5;&Rb;l0J{-xPh6ieoqSRh4Mkt{;ZJJJ-QTs%|)5*LDe$ z&zVcVRGfbC@RKL^K6rOyP+Yup*6cRgP18p|KDzgjZ)Y(CFpkP5v4a@S)XeP@(gS1S zY}GIG=H}CXcKqB|q1uDmf=!S;ELxx~zzp#OSb+=>0U00zhyVm2pb9ZU-$UO)w+^%8 z(5)m15r9%mUa}g)byYJFu>oVjGOz`B@Jd3$@@3{v~nZ|VHCF2`o~<>tmO zKY4c@)(7K};``tFr-gS-RlA`xMFL$ym>R!G(r(GUXhC zM*?QaIp!2GD|Di^rt!x1<#Y9h$?tvZlUM#j5th+T&j0yeh39?-u+o0Iy8U{4a1YCB z^1@Hq!QT4g5AVJG#_3_BT&Hrkrz$I1?HzOs2~f$FNu_JoecxG2Y`E_{0vTIaQ@Wxq zT|>yKBqCmOh71g*WVDzy#q6DP3_^aCOuQ%o|L(Z;Cr>nLkcFFArz=(E8x`p^uxC`{=pB$JZF zm~vJ^R8>GF29caoM1U$O^}aRT(xski%yrqZ3w>o)rlu#$bDO*=82W5nfFW}W*#+?@c3}g?mPU}bcz3-jed<|ERhNdq~VrSG=!lf4z6AWDq zei6baF&y;WN@>zeUMQ}8l`edSnh~IabBc||0ro2>T7aN{ps0YL2&&NcSXBtBnpG4* zK$5Be2mk^ID5_*61{FyOnSl@i0TciM1d(#+bbf@#4|V!UJb9324_sQcvtwjeZk~PE z+Lhfr{}W%?zIq*oKdY;KSv;KHers|3$#^`hMq>|1t`syeBXVJj22H_5nN)L1ifD{Q zA^?z_L4-a9A~~sM1~5dFGZ^W>hoG3O&7_h825jnC!pm2lQaxF|@mp^F25E4^tLEC@ zy#MB`F1_J7&K~@3(fiV{7>NCHJ>6f;_H#RfZox6Oi&n)J)mD zhS0|xnV8W^IT@U}xN&YX-+y!ZoqyRq{6O4r_?fS6{`tQHya~YZa@96CPzT4lt z`a*g6MT?^cZ+-+mDODb;2&FT{hT#f2Nz*p2rK&P>@V)mv5$2dqPNvqlrWw`suqp?} z6oeL$0ia(eMKKi@1BV4B4MBn}T#8wuGT4F(29uJiEy+0~1Cq03P#^{T6FDXCJ*Yb8 z2rz|Sg13f|S%DNkMG7PegouQiCFhK)j7S#P0W*t;4K1120+Oo&7V)Z~o4 zkG>7Y7ywXBh=3$S>YQ=P5OOkUjlruSEvQ3im#I5+4Yw&mF$On8Hk(gfs0Jgf0FK^H zw_jTy-;48QUU*u!Cbz3JZA-%43wxKpFn;D2pqT(J;rN4i@aAgvV~F<#*4bhY)?=Uw z_&COOlrm1fRA2igyLAm>l>SMa-8y>pKQ8aRb!Ox^w@A^JMo~hNoRz^jTZ;f-k9d^R zF+(bNBZbLq(YW!2=G-~l*%HIP6UYOC?E51kQB@HYRryqm08p1DBl@n*F{0+25+uQ_ zDhh}>XU&nBM5Jri)){6%0zxEIR4G{w9zP7eZAxn(Sm~RBV&6t#t+v)~C!Tulsn7nL zJ^QR?jt{%`;fMY4Et6-KlDg6kCy88CwyrFy0df(QG8sh#B19x40D@16s)(urD53&n zRRIuI2u8n`3LW=_HXxo5hQG!ddi%7u5_EW8U%F5$MfZMS!68)@@fsfFAM=_>w7R{tGZ2s z)p+OfwT4!U@BDW6?zbz4@$`+I|Mq`Y-SNS&u{Ooo$FIY^|6FwMrwY>W%;Zadt=qS6 zyn6fW`HKoMt-VRqsI{q!;c*A^JRU{129XdzR8meU6B3gpa>NeNps|J=5%rH3rn1#! z=!Rv$>?I1QE6V62B3n}d8Bs)HW|LA@z|vU&_1?!2iO@NR2r0!BlVLX2GJs#LK>q{) z5}8l2%{dbhGyi`)!CA20_jwrRclj;<<=f7V1AqhwlHe*)qC`ow94TIEOLfMsGill+ zlU&rD_PW!HPNo-~UbVgI^rF+wbkZztXVNSkH?~~MvMgI0B~cV5?j%So1VEgFvwhot z`z`NVka7Avl5p%B+d;6cK!*AKJtRDK3JoERDZr-fn!6Cl`0-@wt&^-diz*tnBHDMo0wl){lcv7uo0VvA&KkD;5MoS4QQBex(-BnQOD?KP*ZpvCJe(co^__6` z4t95k)JHMrpZ-eu#ovMQQ9y?I`|-v%`upE=Mp->z$t6R&Cp12bSBgh|b9CibA(?Rc zVgJDohC4s@>l;3|A|{v`H+JpD#sE3>Jr2P%(WOK-F58cM(Rv;*MaSdZxPC5dD>o`K z#lBzVD9%*MW|{k@?%$TP`%wiiJKQMJnpvG^`CpYk`Q^ zm8KYVfm}H$>!~S9C5|dVGY|tI3KEiILqIu8jydIwjO+|BMoA)Sk!rBLaA$nXJ@jW~ zJTiHW_4o{mBb|Qk`RCH5WicwmjDm4;eseUz+}vx9t`F<`X=q(G zlX}~1?cw&m**Fi?PHMSZYquEIXN%Z3Mtatca1d|T7+IRE%Y_fN8 z>(~EI-ne>pCdczdY2@7A)TFcc!FR*GS5iJQ^~7yI@1OkI-B<1|SB;w>GB7!gR@wk* zX*h)pWmOf<=afR`EXj>cML`+Z_#zoI zFl0u|SyLiJHYVrTwOx$SIagJss^*+P)mn>)nzE*3hygT)m~uAE&U-{aqz6PK#?bde z2tfde%>&LkYYh=<&LUY=!!Q5{5qa;Ov0dM0NriI;Z3;=U0#YK3AXzgpSSFjY_MMTO zQBM~Ow`@m|?c>kcXC9ir^H1pbd(h0MPyKp$^gp`$+O6vJARf1@6_^B0>)Ey&%@X;H z##&<;Gz}m@H4Z6uDUxx%tPofPa!g6YvUxyNK@|Z36p;-v04QiyQB+V7$)I8YRZ;{btn*LHVw zj1!53kDQ`nT<6> z1UX9xQN$9+5ZY#qfYw`5z(|rXCe1)d1-SxD8G-u@=)5pzWH3e%a!RFlB1+biDR?|{ zn|tW0Vsqb&HlY|xmzs6g9Uk33I_<+S?N)VN0!fzad{Na?cGVD3xnx_gFVM1}CKVwN z5lf~l3MQ76a}re$03bxhAUWp9*437%ZHCOzjdC3F`k?9$D-&C^XFNOdyPyB!3vvEV z`@Mfw-G6zFIc-0_@%i7Cd)%Gzx{G-Dr@vRt9fR@Swf5{A(9s$Nsv-NOp=>=YF&+n`xsa8-p%6ljtgrc#%h|U`?B+RvHO&nJ+5x2 zk2tiAEDyr`wyf_ZakC3gkH?a3zqEe$`)Bhb8SOvx%fI6 zxe=~Tm)Bpf%;C_T6tr7@`nS@0oaC*2`VEY~GSm3sETQ(MN9wG(0l)r261$Xb(f z5>P-)qEQr?z4yjilTH_sI&WoEi!C4^x4OgQBBDdaqKKvGJZFb8^qeyx0zmjg&e?lc zmIWe8&H%v70H7%|p(PfPzVC;j2SE1;A_9PvQj9U@3;;t&F=cCQQ54=;V$z&NG7$kN zAq;&ls)a8UG^wyL7EnWilnDu#lEf$xQ5ckC)?qLz1ErI=c0;Pfj6VImeQ5O25B?{( z{}bx@+?W1d-2WSgKYeebIkCwhRME5zE(0(ZlVZAUi#o@gV=S#9%qb3i2pQ4%$~p%? z%nYhAB~Tzj03ae2i7^2nvjKpdld3QyXnH_WRLPQJ3ZZb$5Ta&~3|VqcA;o|u2uRe) zcsw1~pitdQbp6_o4z9gADRQ&%*yX?d->TU;z5edu2QOE4wY9rtH^$5L z-L^R?*>CN9%JLOxPW0eM{q>iqy=%<6jSUo&WOsP-jJx#3V*e@dV^GQo6ifD7m@*u{ z-rssT9==8W9g|PkMzJPhF(i`{J1R(}>Dmm@Gf?b8-x=nrt_-21BuPNUGUXKG(2J;| z=8&u_*_Ozj-3TY!yt$8~?QH7+Ubzr-$`05mP*!wgk&JQP7&cV_WeI&3Pfuglw8zJ* zJ9pdl(mOjDkDar93&c2tK_u6cQ9YUgxePW42(t0sm7a_dQb33?AYfUPfEYtmL?RXy z1yInKbChJQ8+(B6BxTHIB10UGKl07dsN^2p+;1M$d(XZ2xnXtf?EC+$K6@2VV|8Kt z-0#p)b#{pCr`W&!zx&w*P)<$Xu2!)h$)4a$IX%D}Y4{ z?|(nP@yEmb;0(s~Fa6!=XMSsWnySB3)cjxkG z_j%ZSG4*EMoJtYZi3p2W!m^+dG=PIZ3ZPL^->etQ*gFmdtDyqGD(koFx~#j?}hP;cYplT z?e3tqRm3XWkZg=-0(f#`>qn?8F&a=ym{U$Uqp|EuKpsNpePOK;Q2<3E01%OsQcf8O z4I2drVF1X^GDyxj@TI;H@38X`)4CJ(0wD*S;%F$#z z*{Ls_$KmYwrEhTiK~wBZzx1EXuKvp6u(^BvU0a3=m-eddG2k-ArNImV@_ToicVB|z zpV`<%(daQ09yiZ#KKY{Ed=~xrc-o!b{V0T1UBRR6$@wSh*$%-OoW2)+@$LBsKeT#S zZg8ml3hD?OwLLc)Utn9Mz86SjL{r~)4FWpLIi(aM0UAOgBtWpFRjp+qz{ZS>ACvLS z4vGqj8jOP^(Du-E(6*2gXod%{0NRX+*)po8q3xShb8@skxT~Q{eG}TI_I7(~V^miN z*p0VW&8i!EMRY|`RwGkXWQrlCq-vZis>*naL;#plLPS@1RUKjgVq-0UrkwF(B&q=5 zc)&bQV1zcL%iY02(VUHIAJi_~=(L_b_2RR!dAs@1KdqK;DwNS)DW3T)UW^XzhGMdX zdiSScIbW^U-D)MG);nWZRa8Mh6*P;eC^1>KB&Z1xNmM}rP-BQG_EqH(a_H8E)esoQ z(cT{WGU*UcujAdf(#b6f>l9*Cuf?`b&Y7Kye)}BPWdaSM&1VPojqkhbKSJ`$>e2dl z|7&~U#W!AkvzC6mzN4$f#%OkSwhm%;o_)^jjaG{ve{ka^*#?W=04#ANvi~&yV zuv(n0jjPXp`E%8@Tfg>y+4ca6C;XTG{y>ku|HJQWw(ommdZ;3#YEo6>&4@l^OI%s@ z5@TqZ!dUMtvsL7fA>^c*t+zxZk`d8ZOU%PCq?7=Gjj`4uVoEXR2$~Uu5I`iSgp!F! zb25kosyU|^hN17m&@;_8cZ=-8*`jvHWe#cH#@JVw-@PV&}O`t5&+ z7r*${D?h7oSha@Wm|T4#(vixlYlfZ8tI*G2xqurlch~>o^uwRD zt7FLC@Sd|9o4XsE97y$x7P-#w^)&0Z%^r+G}aRAaS z*JoNVmM$3+h|m<)myFg3u_B1Xl!(Y$3jjH1X5*YoId?-30N$0(m=p#?6p<8TOi4um zF{k9bD~pnuvq;Vv0Eifo000q*;A0~BV=06|C8v~(G2Z!*;xYsznpj%`Xy4_w1rp4myW>nsL=<2yIeTvh);hjH*^~&x4I)3VJ_QU42pZ)oyeH}0l zJVMpNI^!yEqoUsQ#k6nxZndVANON5lRaM7~Z8vl&P9|exNC0zAfIv(DFvO5Wh>)4d z7$QPKNhu5+q8eimG^fO>&f30jHD%NXWa#@8BN^&6)stzFU26K;F>zQA^Ysw!pEZc1 z{q1wR=Qqr*AAa)xT>r&S_ct%iUifWz^4GwP6f=@Q?jSDV?k^TMzJ2HV52l0M!Tzg}ej{KnQ?<2!MbJ3c6mmhli`hGUY^w%otJ! zkR|25X|zukAa_GQUv!HFrD#EoDCEGZg@xSDy~V1m1xOHmQ7Q39_m88fEh;2qiefyO zOr|qe6e25Ni^fHvKIQ~O#*()J2!M)AXaE?M`gLCxRasR+3Wmr~lAJY*h-NXyI%7dp zl0=A0>8PBhKD; zWW4pQe=d@&cZfI)L)Z7#+VNykS5?eu2mt`tFcRh@poY)@s57XV+io%R9T7Oo-Ksfv z?tF^*?0D{-Td$kNdclq++uP?J-mkZ3V6&zb+;}rzdsUVn8Ci?=i)KDRHsu5}$??s- zDnS!d^$7p1e~9P5(5&LEYp>h+`%_9e!a%duo|{~LesjHegG*{+ zit8qJ4FQ_Z>!u5Rv}`RI)|PZW0PkGBI(zDTckpU@?=P^=qo@93xbhpria&Vc zFYD$PL+q2C)wc9(hKLc|XtrCAH=0$`ua>2uZh7Xc8P#=C=t5K^V~e6JtarvR5sK;% zLyR$NCWVX{6v?197KlU?5DXKjhG8I8?>&L^ZKqj8a@RH@G8&JRL{x`1u+VrkVulPU z%BhZ~ zv(%P;^E1VBzkyp1Lm{i<>%VyAhw*fIo@ez+&e;M&H$c4AwsP*$l`ntYpMNB>E#N-9 z^Kam-Z^3ZCx1-hM@%rjls`Jl6U^^;J;-K;Jf@A1w9F@dxL2##J?1v|R=o zO*eyLFB$|h8e3N7XkvVU%!;@}>pp550JtDuFWdg$^my;wIkJY0Co~{dg-FQ)jp`a1 zm(3atjHY8Y6jKz*s9@MIqGm8i$=XHEuAcT??v77Qvnqx)h8}#;yRw_kp7^ydrS8u1 z%|8pr?@_rid-kup=@Y;^KobSP*MI-N8Ex&EqPE85EHMcY8S9FoCL&M*LLx>a03vG< zp&vTXgp?!=IR=GHpa{%pa)!_+%~)9&4&NJ*@gB_(^){FHhcjP3A{aBZV2zXJmvfqTSN@N@^QeKLMbmNCFrYqM)G3WQGj380}wv z#GTud-}x_TT0>zWu21gWK0Z1mRO;i{`3f16vLF))QTDz=RHULPthF)altmF9Pz7Q} zWYboO4kWec#6z%d&LNsjB=tIcND;22e&MBJZ6@PBFw70l*q- z9V_c{xv0=kl76wYY>2T-sn2QEby3v&N>c`baa|$eNf&09E?)WU?uW1Z-{s*e+{ekq zubbz7r@6a&<0pT*hj+I(wwqix>%kY*bYm|luUi>UH_F1tZY`mcp#cfV0L0dNUyZwv znJp72KvsDGKysEW2?59;A|**VWkCjG5XtZ-5LHC8IAbJd$w@?r$S_-`IJ5xL#;|NU zL0?xB$Av+F+@2oY(cFeGTz=$=|I8Q8{>?wCKK$lcdt%$qTJC;Z9wamQ^+7 z%!q_2NxH6`%{G`#+cv1^tW7Brrg7zocz(9*nx5IFlqKtAJe91fxhM+;ZJH)%0%O@b zM2wOJKmbz88(Uj~)DHtXGa5~hsO`FL=pWrML&T%gj*97^ZnC|5G(S84(8Z#vl4#!q zNSq=z%e8@2R|Y_)vxzS(5s;-6gJzMGa~4#!W0{w~65esEfhA92+vtdCgMP1i1A^TG?iYd-b2ptwK^paVdsU=*wlbNJ}}{PUkI z-+h%%Z~E@Ugbvgy)yrP9HGWh^iKVNCrtO#W!eZeIgOEd%lr2*j($Hr^T8}5hX6R!E zVKz7RpS|?gzC3#21vCaMNz~UhY&y&0Fbcog)v4|(_e|ILI8-!Od>g_ zm~%!%XPtA#IBnL;$`l5uU#wHiZ46zCYFU|VSx&~|u3ayV=NhSS)6Iu275ig5I=u7q ze^H#g>Qa{CvzuT22g6}|^Yx$Z+c2!4?aJk9#Rm2tx>Afc)?G$s0MOi(Eba0XAvtfr zAX{J5lXVkCP*hYE8J)A%8bkmU1kI``#*l`bGq5v74M+$Gs+x03Dd#+N9U>AaA{k?f z!dK4at^v)1kwC0GvUcjR;y7q`BEzBgY2G%gfgb+USINwe{?&h#;(NRaQR)gVmc!I1 zgB}Lb#dv%BnXi}&pM$MWL7u?r{e##3^7!Dj(ziA@Iz&tpZ>CL~urfO3^I!P1-I^B-4DUJQUG%j>nsr?Ls=Gp*tP4Ze7aU!jErSM zGKP&oQ9;CyoB~?j%-;n|$TH^pPgvey8vR0v(BQv6gW_dhxOXKY#;<+b3v+?Bf zP)e&GBTCtqMHf<^Bt{)o<<9nG^zd}~ z{XYl?uUGjvtQL?h+S(O`OKV-7Y9evFefAI8--tqIBMHWIyG7K5B zV<|UN{diOD>tthke#=f>o5JahTNj#!kB?K+Xbd?-P0=!0h17=>l3@#gISC>%a}#dE zcv@Y$TK)B}`OmzFv-9BUgL}v8WjidFrte&{_Hn2jCvT!R);Z%HWK1e-9UGfPQWj=o zy;lVh0RZoP2qDG@0LB<*1^^LJRYXiF4Z{EcMNwE|RsMfjRR}&tgd#b`kaI>vXRLL^ zCg-8ATt)1LRkv>1W(amvO!u~`X-%UF3Wm_bYNZ3`&YInAm6P?sUmoB3<|uzyS<|M6 zcYf(V%x3TCog2$L$7xZQw4dTx%BQ30Mls$TGMb{8P9~tSIXM97%hD3Vs%x@nJ=^xx zMoN%Ej46m@P(@Heu+~_^s*-b35JXbsgcgVh2>}p5RYA3DJ0=2!l#+;8Yb)=x>vA4~ zSEy>W6VS>-U22x*FsyF^t|Rej$Mxn@=N{cz|Kj)Cd*3hl#15I3Xp`gdb_+G^KWU%- zs=NAvx($UHMW1foJp0*qoE+C<#oYI8Iy{cWY;TdHj%4ps=VuR3*9SMDX~(nkwD+tW z-oE|af4t-4dJ&54&rP2F4`B20yD$In=ojB8(+y4sU@VOulkT zH4G}oAcBAjAuxlgNKPWMa+duxK)rM6sq)H`UN;{X^lzdOqzAAOLWp>WP<|EsWea<}g zIQR_EKxu%dkUZR*!_g@$=9&{~f;2!1-QqN?SGnu*av4reSIebpHpCZBej3EKQ0B>g z^_edhU-(LW=?a{`7<0aR@9yH@!1hBKVqC9$U7#f(GS(up00-!mk7(z->RV^Fqh+qKC z-c$^{UUjRs6Qb=)=VzDBfr+s@%fkYOHA6DSq7bAmEk0~dUj@8f!5J%yxeVhc`09&8 zQyg4d&~U-7i{|9*KHMrtqsjL9j4mlMGe`*SiZwY$UEke1zMnE|?3~-$eHf4pGZU#w ziZO*jbF|hv%aXI?Xqb&PKvs|yP(OhHh7B{Pl$aP)hhYdI5K-Y=$sA(eW1_MYu2g(! zYNs+R?xp^)A5K>xpr283el{&f)AiBM{y^^ke4CRWa_mDaxAKM0*U$b6J^4%Eilm+D znA`E!!2MqttR7ax40ZD!7xNJrYH&kh#_T>s;E}YIwkSW zBVkGz6ns&ZRc+V~!;rF;zG7oziZKO5NI4RtNF0XVp{sd9Li#bul5>nH#j+}`Wfjem za*6=Jh94NpaW4*wt-WVH?{@d0G(df?3&j>OA)qE!@u1c_B2-u}nmc#yesC?W7W=a) zi{u!Ic-^%_f?_fv<8vRUz91wqW?+oYjP`cxi|0vmzc}m9j?Ders}J5<-?=`{&899K zbWqH|){@g&I=uJlzbwIO(v)(}q6)|l7;9}x5<&t*V+^y+s!E`wAmWWN3=-nd_c=ug zDdl90Ey@C!QqC!B0vlqeOd6U~)M4E;2&U_^DtMB|pMIDR-df!LIkpGoga4ZUTQnA1W5w``l2w#34$mBF_9r-d|4XnvPcYB zRgE!-NJNMT0P=~PGcy}w=o2E6QVL;^oXjT>K~+Hht(9(u;?Kj*5e zkRFB;o!@(9)m<~zRkJ8fyz*4sqz?fJBIv*;Pe_nir?{ z5ff0ncX%Lxo7?-=7w0aXKYQ!ji?_eAXW9Z_l_+mNI{W3n$B%p#s?pGYl+uTV+3Sx+ z$FINY!{PGeZnId9>#gzlTs7H0X;!n#+q1`J{o?w;J3o(S>#dDPW=}muN3Wf|`!d({ zNt^5QPj5f_RhmB1T)%(ghd<)g*~I0cS(a6uZH*QL25U*-0VHA~N+}yQP1l2hFH1xU z!;mtlFHJSF*5xE1;%vdhlCx?C$tm<~kO(xV!Z{d{qzr(>tO_y3m=gdalLCYgV@}Lm zmbG&(5HDKUzV!6gr#_ElU_?jD+egg}F>A8X5Md@whI2Wq_GaTX0h_Z+RD1fAFi3w0+N<&1=Dw1;| zB3oD_Op-t)hF}N*CB!bK0VK;1H6=WNF(OTNWO9x-FP0Y`DfiF8XaishItFDJK3LxU z_WI~&7@9&Z%%1wX?7xs{l>6@f-4EOONo8r|D5pU*S<6M~>$--bfEXe6XW#h4{+)M* zTOZo_nd#Oj&#KedwD*qM$Afkw=(spT*pgf_K)I23aMD3<`tlczO&nO!kZ2 zr;E5f(hVvon{4VS&h~&tAO`PA&O zr@(M9?YDpON9A@Dx5&5x36`Aaiqh1ki;wJmYNMJ#=(_i>-M@B?)=kait&1u9QJt)t zcda@%-nmroU3P^7Z1wDRIJzl!-(TN-AKFt6t(C#3paLL?tA=t6^=2_SpQh*1XzFGY zJo(Ny)w38RVk7`iKu{EB0?@2kL{zh?h$s>hGAb|<2x!a<=#0rJq?8a94GKt>#E?zy zy`%Z6392Edsw`u(reWaF&bI4fXL94mFQ2vR&;I7uVzqnkgX6F|)#g6BGFRJqbYXAr z($>Zl86fo9u43P4Tp=bH?a*k8y`rp!^+)Sfo71MT`}Op^AFY=+|9E-*TO*m9wX1hu zz%Ty;Fk9jH{_Xd#g|02V%W)X`j);sk&iS$))tj5uY!eC(EA8&xYF_(E^P_J!Z@)6_ z&bB87lBDr8?4H-ho-IH7rQ*rY=y(>|wVa(T?w`(2&-!LC#N*Mp9*>Q4N+d)n=NOZ* zt|*JFK!`{Ls-g<2iXfsytg0y`BJ$n?0I4EKN-2b>ngPHWLm$JOQw&2&NmVTyYq=<` zs;(CeqC?{4dgV*A_2|CevT%BR{{By7`C&ngNo&y|5^|0ldSe(w3B3#hvm^?wm6dg! z8O_8^#b=syG{s_;is>MQtEN>k#!Mh!kR^*K74?{=o8W5&lLa)Zf}#Q_XiRy%h8T0( zujX?An2bhjjU+*2W2~wUecyF$2vJoD$y(#AAtY5zIYkk1mYug5wHqA9!hvAyMNK)I zFLK|dS?$`zoxRO$-6-U#-(7Uy`|q0jcZ45mCtun7mES8LehkV1!p-LWKbv2FsW6YY z^2M`zXVuhs$IFv57Os8O4PAMm9A7QdweL6KG*dOY_?#O*vV8d!zVTA+_^#}w{Uc0;j*M~Rmy#9&{sXOi|`R(0{i*^k**CT5b!Z5(cFoc9eRW%}F07L~v0)U)zOo2E% z2h6NWqU>zxeJy}p8$yU71n)}YObUsJyz{Xi0MuFwDj^IxMQe<;!~i*mI1H*{tu>ZE z>hB3p&VTl=jV@jRPRHGcKY0C{c5`hfz2G{f!LVa2!m4!L<4<1r<%=8VA;s>EHxAx@ zlba=hRO5-Mrh`xdoNjOM#XURPLbuW0xv{$WbG-K^AAjK5!%{lJ07;{A3w3X&#n$=J zl_$c5OE}ps>OCIqf~$cHp1t&K_ADq!Oau>Pl@w!^WQ=jniAV@TOaT-D06#_uK!DCz z!-N1SMU@A#XwEr_WYA)m&*9ZoMj{^(bKtvNWm zdvD<}Q(UGPR^8AHS`_11Ro3-*G?^9kn8s76Jg@=do33x~UC&3ixStESV77wYEXP|r zmqx?!%d5Bl#D{y_4Om~AeEC0zou~Sf<2$eYg0eCwfDjW9X8D+9=dCmBGUDX9U$-Vx zdoERQ*wriq7*d51`s4mj49_Vs>T=q5)}k=g?G;9oC%ar`>q$sY?z5P=aiB$ zW*CMP0svZTtTBv;kO^SuV+c_MLkdyj_NDW)%lklmS{>%~F?I8yU1SJJ8a%tkC+~U_ zou#mD*!rgQL5srd1gu+T)@7j!Z@e>gj1UusM2ZF!Nzk)302&hm`l>=}+XU7Aqu|GY zPLrq-mJ=Lrf-8Z%3g#%9#TbjGP^myhXbJ$$IpsJ=vuajLL=;IX2|!gvB&Qt6WF&L5a|LW{Us{fC|X$h)qh;v>g$}5Se*28G~TAYMg+C1c=sIVvZ@s7|PNy zfwQb>SjA`ouSGUKU7K_}h>v6UJ)NJpnu~ji~SgrG|_m6)5wp*Q0e-GkG3JXmg z6B=IyGb=BB-tIq}rWed;Hr)H}>j_<#A zV^y4g?w4nK=kI)U=*uZemc9w?Vrb^EZE_fL%4I$F^^{zV#Td&`B&$`KCDQSMU7VC6 z*4L@tZnzql_aB*YcVqePcWn3n5e1*Ux@PBLnD4UIdfMA|IlY(R98Tp_4a*EEic}#b z(RM^xk>p6Q5yx>11NjjB3FnIq7y+ChbmD+&G$m2COj4xSr&ms&)9XHG*S9@wmHW<_ zL5y72)htefJ5W9RhuJ-!Znw5Bzx1*Zv4oj3fDk2y7$j+i>`cZ2B655Gy$AM<*H#DC zsV;WnOV8f<-go*d=f|-hl7NOLw#i|)fB)*2|6%#bUxC$=spqign+q2fTbrYSD=J$@ z54oevh7=@5=NxcG$bbk6B9K%>1ptwlhylRR?!Z0(03ZNKL_t&-!`7-QsUU)?;73Fx z`EZwh1QnPW08~U`kPt0nN~!NXh>~GNHMy%MqjGgjYb#&?Qk3Y`5`-CSzYdrG4wsjS zz0Bq~np{y^j_+N^Gm2|k<(lnKIhE~AnKhwpd+#L*p)w{+J@~eCWH4c9F}5I4&_%n3 z#R_xg6Zu4B2c}w4E;t+5!313n2}4X#F!97yN9CfjS7e0722TvQl&b6^32hRKKIx0&YN9UWS{+?-N$}o zHl15sl>5}b`5(-!ZzXdo?*Hw@jcE6FhaZ?d z`Al)<-s>;@2f6+7#18}x%!j8>Jo6P;IWoO?@zz_fQ9T=FE~_THO*iYq`jG>}fvx9z z5CS9!QB77@mq$TnlVt^?aZH9-qHpWEsT)8b%S1?b0Re%60w4k?fJg*TV=W_TAE8Sc zgoteBlrW^Es%%sw7(~?2HZx73YwM<2#;m3M#EDP+Ms?yIu#4y4{$?CpU&y6=07wPW zuxZHUBO}9cIDKyaQ#q8^e)eL#c%|RCVr{c>&rv*lv^?>NY;+P6!S%N{-uq5{?Y&~! zl;8&g#M0G*o^3u}FCKhci$lEj01b~RJJcnFP2dc80E)}2mzs^M{d5x-Z~lZ>MMPEc zBcLiOeb*}heFPEV|ED6!`=BDm5CEhU2~_S%NmUSlh?vM41WjGjESGaea9IY-O`o8h zuFl@{cP`(yhfh8Eg{BL8bvs_&2co{2`+5PPi@t8_x-14+Ub4--azKkFS7RYJ#8gCa zeaBr33Yt~HRy~`w6O+pA&M*9(U0fQX?^O-h;NEVDMVN!16h z0vVc&okJ#~y)ey+fsa@XRz_#e5nGwh<0~(`_k+KgU3}wMu4~j`y$dLNG?2sh9Q)O; z(r3Q}*-)b_ZeG86^&-bmW=2JTO*tC6qKJ}000ct%5F!GAi1fYBT;`k$=|jxK%pw9R z)>;4vAHgI@goxG{Yb*eylwypMf~Fn;QjBfeY79)o%VTq5)8;gkDL z-UG6&=fB@x`iaU;Y&$L2=*+{zd!I&s1Y`sZ0Gj|?V8+U8pbG6=_cq$;&2E01;;xZt zJH3{gJDg?~n!-q)yCGneJwa`*P`?Q2yIMTWC_I$iEg=d+cgrw^QY zbbpcb@4g=thC>ZKT#i{)PQ z!ubH!RzLCSbKT~vv$uafE|0s9{|b!{Tz~d!dHr_Yd*PME%DqQ_<-hGa-gxcxe(P55 z8&1I$qiFIvNj9p+qfAorP1m;p*jQJ%qGIEEA1pcVedv0LfdB|VMF^0It#j70VFRk7 zA}NKw7fpr@0Cas1lJczZT?jrBlXb3-A*7V$xv``gA$r4*S?=5Aayd&$w8Lp~Cx7Kj ztM?we6Rx~+^KX5**`=-3;V?{7MI-94AVw_@AN<9G)xGt#53aoY;{4|JvhEI^I(g=? zhpQt8F%i6fp}%}#XXCxS#e2h1QSe&V`m!pnu0H>4zjZ4Yj~mbZO;HvqNmNu7{wqWj5mhB3=Nu6sV*LLE9|EcxV^mX& zF|#(M5Mz`i2+B;%9AjVw(TFO>5FvKG-(4)7G^0DOEN{NQ7@wJ(c{CyCgE70DiBj+q zy(5$umdhm~IhT>KAz~09>$0LCOF(GEsgKgm#dm-tTqReGPK-yBf?1zjlQJq+4xhRwKY0eVhko9? z^rK7P`H$(+I|rd3`96~jtI0Lrgk#6f{Qf_JPdtHkFx#2mI)5q7=iD`=v(<3Ig9#WL zV?-jucNrp#F@_LgNbVy(^f4r4G{k^#7b1#C2qC3pkc=?^V3-k5K4O@iGlBsj+|}2O zuN#Sx0h9L#C@C%5h8bO!2_occlQR#m9b1PRFSqagr_^8XyvFk2fiM0Rx+CfJ&7Dh| zb8C>M!z$|VI1i4G0L?%$zgJewCZI&9J)=|{J?LV@8>rmOd&N8JF7AHAPJ1I z)@Gm-qYyC=CP^_yl}OBaZmbhD9w5btK?yJ?GelEOmoZ|dRIn{=K6LrOnsJQ#oIPNN zt1wx`ssM~2H9!Yp0kf^?%^OV{+;C-Q(XAalw|?d!+4?~K_WwxDo?kgt{Nf*`^#`xL z@xf4c4t&gSJpX^Lv=`MK(__Cz_P~`l-n@G4s%3ZY>HE~Utr#Bu#8F?rbLXY!3SJ*R z@TDwYzxC3e4dcZ$->%k=r^Am{pZUt(&Dr}u``HBJsznN&%SXjzUn9_`keAk3 zZ)^rg#%6gjsGBwgVZ?Y>-+>4MphDmFDqsy+YmG4sACee-?-A7*CZZUE#E6E2QrCN8 zCS#hmi;@PzA)+#3@C`Gp42MlK_g$A~w%_e8?k>*$`j-zsbn3nNJMS%C?%XEul0qtd zNpqO+K$~`Ta^mRmuQ$UIKH?Fi@njAiP{DDtUM!I*id*%7Xdv98dV!|BuWVj;P z;j>SC3XdFDEp>^D>$^9v+#HqVk^An$@je)5p}V^M>Yw%3Uofi=uRZ#^#mbS3Kl-8W z?G~zd=f!V3=Kw%eMMPBr01>UVA`(JiW^1i620#^5Kx2#{1XN|B7(?$nXRL~XBn82b zFj3!mP(>8WWSK-_-Lz3)ZNP(#7w>%ViXMKr9~>r|m%~x#qqU9@5Q&IGh|9XpoHN#- zQcN*~gh+Xw8P=Fm8?z{6pmCIPL6NKnSDhT@lij@w-zjF7MqZ_!H0OS6^w_Vp)7iBb zUt&oNN~n2NfMEp%rP%q{dIGe@_}TTg@p(41`LIqHTv4vC9Xff$4s*5yw>M@#`N`&s zFS)JVLDT7CdornYly13HKK}INnSWr8KfLsA>-@#Mo(~X~i+U+}xw1x%Y-Y18v&Miz zh#>@zh;)}ij9vkW5CDPhVno1?h=|5?R|tWLK{duGBGwp}8#ECxq5{N_+FpF5q@is| z)gY*7k>?1otecrS-FN)-Cmw?N<^KFPQ~hoWIjr8h`qbZpuGspkpIpDO-3|tM=0`5r z$w4jG$rxfJg3MA;*eoL)KwgJz0?vjjKWe}IZzPI2@l^HnSL5U)ZBE(W(9!#QFMK^;-d5hPM?Wj&sf`Pp z+naNVv_9V7c+cyjPkj1RfAfdCZ@-M4sZKvr4GzrS`cB?n?w8Aa^^`gNDf8H`?p)b< z|M?dNsar9!S{8XZTJ&krrP1nIQMtNb2&O&;Yh8#b31(T@^?j8W&N&IOSuSG;hS?h1 zc3mF=0wACvuw*QgAw+-_eBX7bP-Gb~_C9!^E+!&2*2bhrI2aC4gbn$&^S&#c?R_Ij z$}*qtUfgQ=_%D5F-^cHH?dr={x_4nX2RjYTywD;KRizUb^V7$lw8N(?tS;VpF7Dph zf9x2qt*V1~>5av+-_~2_$5qym-2*C5pBkNgz?^!luiNJ8<=Ypo>~76+u#=*M(4M~U zemryxPaWy%>l-irDeS)O&C&Jye{=1`eK($a(JbpcA>MrUTSZY4F(Lwhsv;s0A!14? z#s~oP5ddJrWGI9XV?e6B#MYNMnO{VLyXL1j8WAjsz`UakBEqG zySwaN#xjwJgb+joF#(4p9V!|Cj45_KhLpPuLuh7mXV_+WKcCla8_KdDubz4QN$7X_ z^M4ZNFE{!6@YK`A>1X1de)s#&CLzDFl2bD6R820~K#2h`Du`$TP(W*KHJ+6F*4%iE zOwe`EZbyF+v>^myQkBp)ZN22=L3;5`2sLVC5@(1piEo?bJO)n$jyW?#hBfpC?^4yI zl0XG8LIt3r!A9>SSxE}g6ZEcdkPo}ATy*Qh{f`em@ny)@6{LRUPrH}ChCIw3`Fn#W zz6|9Wv~#%iVt@Nv%iAxn6?xE+$HT>`PbGI~>eJg^BVk*OZ!isVOGl2Sjfa4mE~xC zc>3hQN7x=UvBIT?5Fj^zi|*QM%a{I3cIUlJTeNmJn^YfveDH~9lBb=E*FJdj^~LQQ zWtI<%(I78Ys!Dx5*?%yuA1)t#sGVQE^Wry#;o4lrqmxgsoqcHY)wkR-I5l|r2Y;Gn zg|V5nmWU96KE(2o7^6s11yuzAHbhKGL{eh>P+iw;+YGAG8sm&5MpcP1rX(>)j0rRu zLPLtEs^IdX8gTu>H^RmT?&K50vyaWEvqfDe6(BAKW0O^F)R5F>dDr!tl4Z&nFhz~t z5;^9Suujl}M659-?U|)oTRSki$2R?o%gf&#Ym?1Zn&wdX**}B>_jDV#Z=OFt$THAm zj6q9D6_|*PZ+us`rOm6NxYfzXnE?y?W$G3&)E-kKQS+*p94JQzIa|xKRn9Vyt#tl{ z?N^`OdH3aVe*NGOkira0_wlC&PkqH4dT_oM{N_&8PKjXZjHxP@WhxqjS5RiQOezxm zT^$iQ>yStU5`Y2_kuipuAxTOJ0IacwSwvDwl9Fmn+O^$Mf@DmLDBfdCtm@l#zO$<- zj><}6?7jCHrb%`7$Aqm}@n z3;m*5&iZB%+c~szhCX*%I0R`@zYP5%#g0*|1?5gu04j?E;))3vYe+K*vw7QNey~Z$ zyt(JZ(|-VFe?;E>>Hk$+_^Xtym{0xQ;QlWFXa3r2bm6<(H~yx|=7VY!Q{IQM4o}#l z54zQR2u3jLK%(x?yXO6H@jI2yIXPJQIK)B!-V4@mfz5Bu>DV*B2j@P!*z#9ieJ$@7 zRjRd}F*{eSw#kU{csR1TX|x3b5zX?Pkea3i(Y9@dWo4~J5GGPd^Z7im3S$U91`kOI zz!EVcrWE>)00=;008wYNA|D1Ho3>SvyeOHuYrA@}gp`P=ZE8(2nT!!&xmdb*djVN> z;`FIs`=u>^=SKYjOlnVC0G?vOVXe>;NA^FqQXMgE4Z(rA2Ra0f@y^fpp8pSc(rrfzukI#(HJTjdv7WFcO zn3q*KTCvsG3z5xiR&-s^7&6O_q+iZb*Elwej>rj18<%aGhlHW89FLA1KQ=htwVU5* zZ~P<&#rYAB=f=PKhlAP98{gPwki#Cib*5^f~q>hh!}k5y~n!%*|4#hDEb&wm6@G$nX#(6TrLrSiHQjA zQY8dQ{c=9*+BUN`caA_&MPt;ILf7_flUeJGSu7U2^-QYl-e36aaHW(hU$3`*uveZv z{P^#f@%>l7^ON?~SB9hEyefva7zF4g_9(Q=z<-@_Ku3H6N zJ9Kn666K{a464lJ^30SuXNDMv1WAxYA*nzlp-(%g}?&>NhJZW1k`M$J}toAo9g`}i||0E6SP>83yYKZiHJAIf!n>UXQt z&j9k~kH1##K8yW(j+aQ3qy)3pa@L!&DvxLRA!AA~)aiV=`~HwOoirdhtvm>R*uD3f z)4A8?X3xi;`A7EtUz*-(KX~QUBFxroTq&8^Zcp1;t)tP}s2V4fPJ$vJVxDD^Qd2Jp zFwb+4lwwqg)>^~d_q}iu(&&BL)F~!IXoyfWd9O)w>kyz>E@DV!o>#>X5-b*rwr%q~ zx5n0sMeKvbhvz)5t;G#nMG4K=m6??LCMQR{ zy12dTwy(J1A+!E#kX8dNZhimX!=>+xWTwn?^lbIellIg-yO%bnuUs1?G2KpFZZD?W zm>1&%N4?;Un;UGn1~WYK;6uOtRo~uTJojhW{5@Z;6!$+S60vKbQwah3YDa7DCpfaH~hM56CR8yjqlB7VO zh5$ukib6ad8h-z8!|n6)!KpMk*7mXK+RVA(c*1#wuIduHtP~(-+jmWoS%=!rb~SXl zb*crMEXlNPHzS5R8ZT?BYe$aXdko~Ac~4Sn)>wM$mjFNKA)z|#)V7E-JRT+ zvdoi;5F`XJF3WO8)~FWP8tcOx5E7z*qAEr)0-y}_6p$Y_xBcx5fm_h;o= zx^iju&I`rWmuTaiuHKrP+#bJg{nNj0)=zETUUX5JIL{p;0f2QD5&OOeRb~#M3n3Cw zOo@rD%c4L`QB|4QTFZa{&~=@PT4R`5MF7AVV-*(DX;U}GnLKkyfFLPG0AjtC44?byg_3wYJ-u`L5`q-gQ{ekI*FaGggPPRAK_pQ`L#$xiwQaT+P1sx13 z4RN}+S7y$#G0dQ9i2AOZ?(U@+++Z|~n2jcRo{MS{#k&ZNwZ@Wh#0CL0#NLO%P?m0u zz=Y_LkO!qY4xu%Jf(=>A#6Zc5ri2l=39(Jy5M>OYX%6AG_-h<)W30VosXAlVKT)kc z0z8hht=aefU4H9FaqXD>)bEwYo`H}yfBLT{^-GR-!u&Q_19qHJ8MD-BZ{j!$Ll-q_ zm}LUC9cO`K44tEuhfH-^F1|;LThp*PFUKnneP#5-SL!{u{?0qy=2cv7>>Jw2%F3cm zv!&+QXjqKdIS--$Ob8<0cd_e4VpSBHqKY5_5vgd3UQ!1dQw(igrzDv%hK)o?Ay{J= zDfGVUTEk{g4P%H*v|KC~vw4xZ(Qv3D&0-n)o{5}wDMlY+p5;Z6SH7MZnHCfe?K|+u zgTv#;cbi(V*KSrpJ2D~Fd-bgw-R+w^+Z+s!jXw1+b#P+mo#*cS^iS8rwIpl~+_(A* zzpMw3ZeKmW`}W)UMpp(IuQ>IK*e%gIPuYCgg&-mN25ouzfd~HKS7X>-zW5*A^8Mb9 zvxmPxHEzFmxqvb(6W;mhpR;jMMWUz*vvJNDYkcq7kY(4$KKhs>rYJx_M5=;F&KM#T zNfMKYAgW<@))G;OzVE%WMT{wg9wZO|h$NAOxVl=xJKy%VK4@3(?T3d%DTR*T^n8DPFCo0t5}H~R~(bZcn7((Csq9{^IZQBwPATk-U764RLMAAnf2>@7Y5rB{oF{Ok6xp5F;Y}y!wEFnQm zA*P@p#1`0VJ>--#D*zx}-*@Av(_eJg30 zL2{wiG_-DiB@#pMeceb5K;o*3U1l|WxwZ>zLVZ0o z8E`Tv|C`==E*&~uefAHlgP(z}o4x$6%lWgG8t`+-Gr?i> zE^w>VW^rUXgY_(>`65fnMk}$*25nw47tFQGdi%;=KW&GH1|R?O>L-6I^<}ra zySVxO{Kh+ezF{(#SCc;GmIsq+1r0@th?-&`kRr1L($-4}Q6+*Z5dvZi!FR0*or46D zf)65Ui2*2tm|`sQ(i+?MzHJ&pDh2~!MdHwRUDGf^RTR$fay}2fA=S& zb|deb&YoQT4i@+S>h$XN)mPshno(&hy#1p;E~i^I5eSmzZ>sd z(8CXh(QyF+M9a46Izi5gLEA+n3&!+qXPC=8OTmY}Ei#jttoJsg#IzN4cW>5-T|IH` zlPf0<_**Y5FMLnyOTbxg4zJ$-8~N!^!MxeKxv{sk#YqZljWxzvH4N57q!1IM$!!J^ zg7*ey$=JvokR%~_wY?0~l=3`&peeT(vci-PnZct@VP=b6}Q|B;W9{^zrzH4g&SY2HaNijq+Mv`_uBvqSb zW$x;oo$+8`Y}WUo_hM|8f`(W_wxK-mi@MK4ArQYYSvmRz*)`v+%^&YEx^6tdJhp3FqU41b3Qcr_$T$^ zyRdOh!PePfIPv*|pZ$G^10aagoBfS9?_7SP>Fd$T{saSO#yJm~c0qYU5|CsK6xPJP zo$hRphE)tcrGy_zclBKnVkmDFmeb|8Z(n|)-FWoA1z7P4@ zxzA6RcGae|7le?^AhbcI(CmKl#t?^$Ul}b<8PF#8TJqZc>Cv zwHg-f?W@HMFeJphyWmxLW(Lvg!UtV04aL!L+?|HM99pb8dE|<0AKgeHB{@@3?a|Mq*Vh`OnuNxHrq8%T2R|xyu5S#)PpA<`?R!I7jOS%m|ZL^CUeLg|73B`C$ZSK{r0={?r!Y*!r0sx zX0n-!gkWtV_8}2)nH8GA_dR7GpiyE9KJ^~@o_w%L9h0#}4E3xn11JqzS47jq1&{Jw z4ZB^Rk5(;GrE#AV+`Vz-trvH;Z=5)DV*j~M2p>pP5gP@FBApMtk8JG9>KY==7Bw=H zv8s|{(3Ff}B2rZVu*5{O15+Y(|y~{`GItyfsK?WdIkOa{=s~VTHS=-c^Fa6x&X7haG=jalQ4bSSu4UCoRIKF~ zyFPT2l_41Q(F>sxCPG1AYaDaEb$c=#I-7M}h!I>~menXk@$s${B&s43AX74sSP>CK zP{A@;vLq54UpSZB3;?tbvFm+`o%!d1001BWNkl&1}9o$XrL`npSmiWOU$= zV=LP&Y;TzEJF2 z>|B(^Znx+zUD-jcCe`|~S$b`(qse5rG8#bgv)!%bY&Un7P?<@%07+D@yCm^&)D%P9Juq}`d7vL=Y!^&M%RxY z-2coU($Oa&AI15upKry@&5f&@nwF#+R+imtD&q2dT>|#Ywwvvit1DOP`b&TG&r^Ng z|NI+nao*!ebMJq%yxrV*>s{z#Ra7|t={J%}(v(D1L{vmnRr0(@DFmO`kTp(0RDl_h zAciO+015yxMu}ckVhEB15!kS0gN$w40$^sXF{~hMTQ8Q)cy0gwk>krh4m;QM&_kmK zpT2$NTH6Ix483ROmB|DVnORbbQGM^NwamuHBqDv+m#*@$Gm~Bmv%3TLKk{iBaoThRmzJmvzI8k5!;qv`&JAvV`e`wD9 z(uF_&H@2RGj_TPCLk)v<7@x4kK7>4YUsVMgXqrV)8YD2ei7GqOy~g(|>-*OB?L*YQ zS&)hfB660O&Xuarzl=Fr4na@O9pJ zHb<$`es|!$^4?#-11BIL+}hRiui@s8fG$JT2_VS`U|h>!hes=qJU-aEI(y@Js{0;R zmaD&T>P!C=s$(VlcW$+iYc>3e5{wtJ|sX^Hf%FA&SXV3Ud_t^uqC#}S|Zq+-HyIykldM!ktLy~ zwx0X0^L_8VXEu}7)s=&XU^vvtkOm3E9smBTyH`Ib6o-~k+BPm*NcsMIi*sMZ)hE#( z05gIcFTeiHKRP?vTHLw8tLN4~`;Y0t&vsyz{XC{7E}GTBYF4eKjjLCm`$4^Ng`zKq zt4&XB8xO1>XlC2Ob|b+T|HVI%=1O|=FYWw1R3C?reP#RN#??1|jy|kUR&eM0Ur&?_ zv#NGo*Y`aDSZlK^S51g)Edx*p9srn0QDcZANmXKu-uoDQSrmo|kyIt62%?IbQWA{- zU*Nukb#bRMx zmSv@n;$w_H4y*$Vi@fngzA`>{`0Rb@_Pfis{w&Yl4?akKpF8(E`GF^Z+Mhi8w})(L ze8P}&=0RQ{L)-VAByi4FmCXu?nxZ(ecg@?{s8|uB!X#=m8EjJ!V-*NILMz+?#<yxV%rv<)zE2 zD2i-MR>UYV25ZnVAbdzw(_KEq7>USPi-0L5Liv*R_cdc)ixiOV< zzFyX|sR1mrtg}_vclgX_PA;!~x4rf}rEGZctM1I_E`Q@+QN36DaW~s5Oe>=`*moKS z6LywFhgDHH+f3)ny}jMdti52`Rde9!f0EzxTlJ0WL%VPXi_KU5!fky&Q?cVm%(-V^|EVMn z(NP4r^h$j9Pt)=>9Y$-%VL4_x$iri@eu__@!Ho-BFMMkdE}A^QN#{;H^;JCmSlrv0 zUVL%6`KE>q0Z*=2-+yLs@_r}|U|+$al1{tDte)+5%PB-}S-YlohKa%Z(6n7j378k& z*TEyZ$;#@=zWvpBk`Kl*GeDc#8{wVb7XSkDd6z>U`OGiUYCSxh73Lr@%nKJNV0zn$#-h18d~`XYbi zAFO`qpKqn^gXue)?PZh6+HilE`+?%4`|k^{Z(n`srN!3e$+$pL-z`=rLzcANrh0Vz zk>CA;n3}~a-^HExp*UFH|M@g;XV-E=R>l^vhiLh%L_>j+vGWF zmYqKR0B6|0`@{K-9}V-(y47<36U76+4eO82e7~`ABW~PSx0Y2xTSH2giI@_q8nQ)Y z^D=m8n$8eA=Kz63I7Lz+1T_#C>)1ykP(-h$R~OJA2G`eVx!ju%v!b#YC$-MBG4x5% zppmmOVT7E5h61g zW(DZ`u4|jNZH9xPGd86J0E~nx?R?IlF@~s#83?rRY6)Ft*+>d?9orgHLcp1r{Omnv zAKy2<@U8mR+l;F#$9_Be*ys0N`s;eOHE*3X%}U8IScR4S>xWme^#QmXYzbg=Z?W^< z2bbS^D@UA^<@$I`Z0n{c&IkMU`z#BFB}od2kcq4+G8sk!RS-oKCNPYEps2)*L{Y@2 z7*!M@iT2({6`N&wUI0MoYYtPJe6AUQ>0)ZdgGnaI^wuWyfeE;v!Fq9P_sY?=ap}s< zSH8>p%E^=e*zfzobmQ{=eUcA&_R?R*o$qs=4bS{K9(rVPr@p7Ng?i#l{uJh=Xw z|7<=weSUg%!=Lx|c2=dn)qc?*8jQ{jA3ms$H7~z??S;RQ_D)r3X2c?pk2mH5=bnD> zH~)Ur#q8z(BHI@@8x9_R210q~gDc&g8#zVXdFiixSo+ujATz5-iU|pwbs$LukbuY_ zf`}~ZdDAv|QRG#bl5}nDayJ~0M3SVGV$_rr6cKX)H?5^hb62J;Q!=*Nzjo-%V8t!p z`Hp|%Pf0ezkq7tv`afOnWmm3m`S~8j-fD0fS-eAa)`FlUN|>RkC?B&Mf;F|y`!Jih z;l6$Q$SlIu7p5DpP~0n+QmfhIlzZUwaPaZQoJnA1>xS;$+S$Afq022Zq|B0aR#X+4 zZN@f>id`4($}NE^s1SgvBuPPnDhMbu8z7Ad1#;&?^ljT{O4e9N5`%Y{W5ZntqQJ~6 zqtVSPS56!~^zP68^GdvS^oh^GJztzp{q}NZ+NJd|UpeG8WVma~)s~JV@j2{eh#J}Z z5QAq+S(e4*o8{66&qRb^h^;Zvr)F7Kwh*8Cz5xL1h*^Vg`);YxFLt+3LX}xa(HgTG z^qT()nNXYVf_`0c&-r*iSO$+D)j`_A4|PE!BF z|5fk2?v9+hF&)|ipFVW|FT(0cH7g>Cww~Si?*E=mZ#ogmCwGd|r+?>BLqgM$hg&#vL} zRzI8CsuCaOv%RXwqVF72lB7szGc{RMhS1||BS()U#6Sj9N^RSrl0*?njKC07dSlQT zZpn3Qm&rt&WcJ|U!w)V~_U?~=tSRM0E8|tK_TXnem*oUM{$t*Hf7&adv-fVi`6vH&q&q7E9p+g#Yh~KqiPgFP?vDl! zo$=d0+k4@gZgC@t7LR?gT6_HUzkA)@xdin#%7w3^M2#K*(J%mlDiBIYAPIpKRTWhQ zL^1upB*A&Gp67KK_H&-?-M;nixEDJJfFMW^AVEr$NLmynYq4Z4iLKbOBg>MPxJ^5q z=D&8PlW9F^r=3hDaWal$kL|eeNUAJrp-3&JL`tN%lOjO?#J=8pakuY&%ey|yIR)k4 z&$0I)g-lXZ5}X5t5XZm)LICH%+YlTD5+R6U?7bf+UEP~Y`}3IWLNzP6E>C^GdF$`k zZPp9-EPnQXV%%F5wP-8EIldX&r?? z5D#b51Fx zl|lvz0U0<1>l+6Xb|Ed>QAkk=594uIZT!Tr)O8YLJD!@JG=r7;>Yh24?>tj%T=D&- z&dEQF_J10p0OE>&pZzh^;mOFVK|;_ z6x9T66?==hl{N%T0fQ)jay8rxTlHwyy))A@lIn@Wj>WbP6BV|{qfwfsQmcHl9VwLT zjRb)JAcIh>44PCa5vq|y3g~U{EELL!zzCTk#0&}<06efm@Bqx&f)gf5x=A`)7h-(j z)`c^dnPs=z6~Ivv_xJ4SA3HvH=auNwl>CMr`nZeaUPlCz`3PdLb z3W3BByS?`>{#tutuK(ye%dh;fXPSk6M|gIFYA9w7eer)0yIOAfJEJ$g6_sm7N9yqV zHuBs7Opkxl-6H^d?3J@Go2-;|26o){8 zK%h_p82}iVh>33l7i1AqU8K{HPNn_barcPQyTOO*t!MpP-=$_a>EE;SpZqHjdmvcw zS9x;7jn@5WHH=rd9w?|09biB$g*K?8fHJT^kti=j>9Ed;w}LD{6EX-dG&EEWIO)RD zgL3f`FnvD=!DPobuW#O3k>nHvV4o(56p|T0X=Nf7niz?Id<_7ID1`tbdz))w6A6L0 z0WgFB2wH2&(p%@9V<7Lm3r;Jom2}=ICA8L6RcWo0BvEqv(%=4H-I>Mi`#%>Sdhc*^ z;x})Ja_nU$A|1iVp{dPc6v-$IxS3!Gh)Dd8Ab29;G;JXW?}D?Ah=hv1|Niq##P<0>`c$gD9v{5&kpU&FFomQez(Q9nn|8?j>!3wxO5Ui2dso< zGmPG@^A~HrEJT}NA*ZR0GK;zg?|IjGEuur%q zta1t?k`ro4NU~y!yK<_PbXHa_$~j&-*cyNPPu*k4iin=8fg z3XjTiP!(>t|M*O&HI8@?ICD5Xp5$?2l-63HF**c~;K|iwYiSHBLnxR8O2bN9K$gM- zdjO0wY)xa-H)dL@F0T1)BZTrBkkN;XT)jPL&?s9%k_L@2jfmo0P76Ldx9r@X#3m@B?9o#;1 z{>k_|)tA(i?Z~oWbFD zKOX5Uc;*lo0Dl1(oVAE3Q7|(RNg<5V3Iy0dAqas05P}aOpa3Byz6$`D>0KT}DN2~? z6-lok({3%yEIkl+k03$$=1=@vPYR!xQ}@n&@?V131KvV?p}F$2#{9np#XYzV+|NqwVaT5A1mK*KLzFYd5eQI55J*it0LW6ZNCW zC_nMGU?w3D5P%qgB?yVgo{#~E*@xh~bIu1}x>9NsrgCZDkZh@OwBJuQKW@LW)9??vsEpemqI#e$TqqhYc5peZK{W$#$)V7vvD1Uo7Z<7 znvT=K=$XI9dQ7do@rgf7@A@>r)$ygTlvkeWce>Hhe?Gopwy%#A)sZZtWO~%7{yj%B zxe90g3~s%&DSK}5!TI<7wy)!@%ggc9{@#xLDC_){uf)q=6{9z;Rn5$U;=~u*2Ok|? z-x$Ah%9Nu(O3Juxl!=YkQ5lOm!ALq~b6*wBcv}uPOj(B95A*f;gB@tjwagY{$Lqae z=5RE%D6Oxzw?c4Ip^~Ts00l@ANHQ=n2n8$%RKNtJ0`@|HOfzV8K_w6(00S(cwor_k zd^jF&HMZKi?x%`89j^QBW%R{3AGX`GlU(Jh8}Hq>7C%& zBS(J!{{Y--UjMV|<_oc?o0_AA5D>v_ z%pnjk2_dyo0we|&hyYAPA$UL#0z)7~0AOMw3hyE=eFN=wnY6u(r>2*tcb<^h0q}P6 z#t-Y)zbV7m&EGr!$^Rb2J_rQ$4ZnS(DYpgXsu{S+YF%tnTLK$#2paQZEkEVUw5`rKt@Vq6eAEJ0WfM* z5`_XG3`#^KBIg`YP*NzRnzB+#0igzKw!MW+`q%+ce%f1Ss-JnkM;p zyywtdbN)wHU;1&pxPShU&+FM^ZsiJA>y-nkvsh>^WUUndhq7?N2MNrCz(|A?jFd(Q zTbAsc09JrZ6uhUvy47onvaAbYAIR0N4&+T7x7zK_;%=38bezSlJ~Y<5OXC|)$nlxX z50r19cA(V+$R^5%2<(jHSt+_4GbTPtdKk@cwxIgEO>4>Lym5VHdv!e`-;GTtOQlX4 z!kU#(0Dhpgh)f4%>O5HMiM=+UjSzxdV}oY}M#`9lV1=k8BQO9+5hygy5m97}mI@h= znL_Zjg~mJU8winxwqZ$Cs3&6|wn2@Z0%_k>hd%`6 z)5~xDCqG=?b@yYq_ft22aIqb-KzWTr9Zi{Ju6@^jcjNhJ`5QPqJ8Uh5oe%c!|Mcj} z#_-0i&fMYt-eV$?&D&49Q-5ZLZ`wwbQ}>w%zSO(xgX`z7ZNKwoJCqV145W-(PZA$+qH+#JF=s^_Txlcm(e^f{u1naWbNj7aM+$OD~5DFH~FCuZLvufsgHa|K~89nLz&9@-u7x zwMH(ZvZbA@*6Wx)*!1_odTArOF_1El~F7?>FtZbJmX+aw|a zFf%X{A^Hkz-K zqtT9!cMd&{QgBm@SC)rcn@AohC@G9lfCwxYfl-4JQfd&w2t$Da5paOpm;u4r#%PVq z&N*h5QX--d0;QCQz)VEIgv=5V7@Df0;9b*D2*J9Ycki;}vp4?!FCfzCiGMPC&!_Th zXGOhEAQ_Wbc4Qnk+S$g1(gp^P;K>VQWMbbSfJO|qq2L7yDHRhSfKYm~C@O2yPJe!B zw`uo+(5O`uNfVVTE?R<*T0@Xn?YYOXapqZuXEA=H5a2x)~BTALVz@}3yb#4#{Qi2{YU zP4GdY6haXoYpEjxh@Ju=+!jJ0BBiwi1ZIJV#KC!qvMH;&ni#|FRDiGZ!LV_H%*;uzBznwL9Sh#y!E8#D;87Pe`xyt-@)l6zxg+7*S_xE^sYyK7wh@eS8q;J)`YT- z9jL6cv@dSc_|%ix=5qj(t?r@z(Z@ovYxB}gZAtg{cMhCXNj!e-3H!=lPVr5`r0yJv z9{i%-cXI8*rRvJ5E*6bvM?nh6d>mnz{#6QbTz?KlRSW)85>2oJ(v8&VVIw4RQ;SyV2ge=07<_$E$N!-}&}` zg~3ay9#o*p-hmJN!M_192tWI`VR%Xyc8xOgC*;9TpL^wc^~N(@sF9rmECB=D#teuM z0@qEE=L`@jZIT4y7;ZxVfq()4m>Cg%fq@8w03ZMcCiq7lpaCENi6A^6foKC~5c1I* zPgHMz-Qd8_-7)toUjn%sxb2+XSYF=VT;pIPEsYieG0R#A0#PZGMoC*o85jvX1Rem7 zISgU>bbjL$7ppOiITSjHCyns!L#@Lf)ANstXb058W@}|*^%hfzjq z$tZH?%FK0y8}l^S-^iv;Qc@i$d)Yeh#@0K0vh%lQCF7DVkAXS;PdW6lO6> ztbocW0-czEob#87001BWNkl3e5S{?67L*KiEw%2q>O&SXiiJ%41c zzy1baeNl`r7mTaf(K|o!h2r|g=Echq$Pr90oOrA|*Drtm1N-9t+f!RaY8!TB@BdPK z;N;-?_4?{tsUMc!Iu2O^#)wH(SG7${Y{xfS5ktS`9=_-vMQUs*PQtLwYP4Sul{ISdF175z+)f_ zL>z*%wyx`@uA92?-a`mV>8#bt(o`r#T6>9}gHkF|hC;B;Qt$w%wXlt~bt9BeN`M8C zb5+!(1{Pj|o7;O&G_>kWaG_b>SULBqE4Pukm8EGMS5-6K z9>-A@JPOoWw*a+s(0Ge27>7}}-`TS`truEh?d|Qio@(Ki;KBtHqFwQkkDA5zmQ6P= zY3ssUEkz0ia1a8u6hb01AP5vvNJ$_Vff*Q4f^4j1Vq^4ez`{q6ri!%MjHvCci8A8xPJqpR&K zZLG3YibkrIRZ2^1REScODJ{Lv9ZgXA!cK<8Sj4G_GLNyxEbYwA%cf<=HPLF(2#!E18Zhh>B6FZ(* zw+*Tkj0jOc-2`+HDXq=BRAQvSK;#%fXbn>NpoD8}4TqhcG$}MT2NaXsRwW=LY1~O7 zv$eGhP)$u|6bRVFNv5>&A=uzi2&rTU0RY$siNa_N3}smaa61;#r0M> z8Vn|4vj6y8cc!veU(x5^0xH&pucl7ydF1y*H)}5bc(VFTNX69Af2OA&y!4~j>h+Nh z6r@fUrk3tqLVLM<^QnZ#D!|Zo+VA-tn=G9F{*#NXRG?n=-5n1+HapvD&iv57{@?WA zEPyV1ck2hgm>qfe=G&+3)iZ6Zw~M?9Axl)Nok|mfmtj&HKWt@C%V{TjMi#@tDnZg+ z+|@aLB)|N<)tf))Pao{<|Agw@aqan+*Up|Qwr+Mb_Yz~PQk%H)tdh1gNgSuGR*M5w zD#`(*xR*t5bZqq&;M6wR`}(A=T~20$w6kKbI6?d z{KZ#q@adn;8N$uyza!8y1ip=kd~m-Y5u2t#hIXf;r1Zff3YMY@0T7MS%up8N+aS=~ z+^l!5u4;jhCNVQl#(5`h7meL)#zi%j;PxIox$CZnOgnBays-Yle+%WR*?nyBlfO@8 zckA+n=GG}+Y&z$(HgTM2ZIIA5A$Ua8N=6i9@Js@I#4F=1FXLW+>e%tSuwUD^zG+AA zXr6d(iR>5BX5<)UUuq+gS_%Q)fF%s1egO~yc|Z&jYjW+`elpdCb_TIwfdC%H zBYW%W`tn6PxoK$7(nUM*(vN{k)Di-L^?(XwX^f5#Kp;Bj1F<%dHnG6CsYTV4CUGna&y_T$ zX}GRcmd&e9@>Ed%~U91oE%v~SV$A4q_)Ma=5!fdQOs#WaIKk&%( zj&?ZxU3mMea&(Tp$g?BjfiD2)Ko`GcM}BGf)I0U1w`XD`VH_i~mqtZtE0rx8+j4Ln zMQQa^g-N6;qr=+Tu)k~P+=EB+E8kte`E<9puXD%8b?46Yw=b`qd%N7cY3wkSq=jnt zrbxxxh0}2>&9dOVV(PWy<>d=f1fmd}B^R_Xk;*XWBtH`%mn>>we7S)=$4yUHC~fINxq}MryYG!QaU4e3-#pd-8ifdh(g9JAL%t z`}d!?H@Ra8TM$$}aI2@6-yHdkjeMmu6+wW+PCat?3oUn-+A1$R_0^42U!R>SvDM!; zOAmbUe}k~fFaJqcd68vsn5d~E=EQGadvop9)8FVpjpu&+mucFf07L}Lz)Zvx0ufbZ z87VzIGeZiPIKZ|fo)XDlM;sYOYxmvq<+4-7TD;>#qi71M+)PWcU zG5|9Mx($dK5EuX$gpeoz7zCn}LMv&TMo1aF3*ITEq?FD%0FY85h(JC#?;BfHrFYh7 ztx#Co)K%5gRlD8Yy>C%1bc%oY&*9QDRsVSU=pQkN$@2L`VHCB5nzH0;JM`WOA$40g z*%V`ku4TBdvA;08S1jxR?Z8YJm&sk>@tNV)neo<@c3!0}Xc?O*1C-nZUkA{U)CPkG zf!IzVO`$G%SO7>&t)1K=y=abnM(q66Yv)GW`5+S8Ew>uEJn}|~)T8z~ShU)hPG?F8 zJsy`Kh$wDpoiGdAcx$~t6`4ru$XNgk9wv1dGg^~GI%;K|IW@f#WDMjX-?o!mlkpaK zP!J2D7}y0*%*wnA5rLUPpb&tV0|nb824qZY)fP%2#$j?}9G6nC@9dlE9!TBQ=ZEK? z({?ikXZ1Age1Gr04?-H#*=OL^TaAcu?s#>}wF~vb*r$`==H=&0F6tUj3_{yG{-V$>I2+FL&;K z{MOlv)rGgG4NH@;jDZ6okT3um8WMKwnxQjos}gFqWN6CV&+S?4KX{;i=R1Sz&qUE& zcIa2)T@TsogVR5Gnn$aB<6DXagJWS@)43IKt7oF99FKfcW?8nHmm-d0iRf*pD{8C^ zAS@3z2K{z>ZmMJJNm*_Q8M>X;_3e!<*V6Mx=kI-F>HY`6kK9Y&Uwi&raXlbpxpZju z@qb3sM_Kh(fBMvgpL}n$HR`lyss`fT?EZW2oj-OsJv0xgU#YIVcICw!hAe%mvt8N2 zd*&ZEZYOL`)}DJ}>+F-AtSBvvlcfj#@Q)#^^Q(X2ZoUXqhp4URkEwe;H@Ruge(ler zY8x;A?7#GTJDg|ldPB4Y%A zvyMVwCSq@GrDGWq2$U;oCNA#mKEAMXaeVIi>cS5*Rl453{x5y5TIJKPzuiX{D^Oao zKn7-H6zIKm)-sb8QXo?ZiYc~@Z)|CLBaB;9iw7P$>d*gRxcY+R4Qu1}%*phQ4>fCb zv3?~=b?$V)h?#{Dahzyv0<)A75Q!i#0U;qEA^u3rt+hoI>u#?@ZMj~KCZnp~n%}qki0UqY1+K?Uxi0c+w0Wv7&U;=}W)zDm zD#q9ZhL~iBRNsr9hc>CUjC(rin52cR45WY}4_j+|>oSB*P!7{Q^7udXbnw!}&5|}# zlec+GS+A)h)QlGi>mZDm5+zDz_BJ?AD0G~*5fudvfdq<3X%lH%HX*pi)egK1PQ|jn zYblzU0VRPLLIADp`o@immnF+i(vec35Dd%$rPfNR5P}dwB0`|xgSU=c6M;7gUaQto z2wl+T#apI=g`Lw=$Cmu)?DF&9YSAQ1^k!|_dyaQceuk4ItiSCqz97e|PIk<`N7X&Q zb@tVZa{EnbVRq-EorAN!d3AK{yF57)llOJnIq_LBfAY$Y&kR@A_je-+!74RiJ#*JR zz5R>Tsejmh@z3YPy0<)t52o+?a__Fk*3MllFP>^q9M`rgtr4=H>g~)`JA*nIu-Z{{nnD%pt+eKft}aTtkLzxg#7txV~W{y&{qrC1rc!{0U3aw~`Y7x@5vX(X)z_Av|5n(z(v~R)H5%1vZzh{x6!TMa z_aEsU*^4PYcka1TPKMRi(#+D)9ml)0B#U-_`t6k$p74|NU^mOk*PVS2|BwGS$N~NQ z&%??~G87@|h}nDO(O-u!bMbHgRE%%o>Pvr~Wi!^1cRqxG41fT@S{i|jEEotFg+L)> zu+CMrKu|&eaBu-RNGZq#rKA96A1Dw}2!V-&<6w=ocDtpiq_nl~zJ)^v^0Uw7r@pOW z*mU+Re&n~^K)?Os8-2Et0!S1}Nu#7uLP;sGZVCt?HcCr$w((^h*TGe8Vxl_9AnF`? zR!7Og zzV*H8`fE{4sz7TgVXeyFs_xt40-v`^d^3FGR&hOCu6P|8uUHOJzds){*5ihiNKWOfF z6b5kVCoe<{8c1j*;&|fh^sYUfyY6W&zn;JTH`8)6RCW*@NZ$L!*1`7QS0iJ&I zn_uJ2D>`568t8TVj?Ef8%fd1h#JC==Hw`VO$8_69Nkq zw;_TOipU2?L;-&R00Q~j1fbDMOX+WOUN8v+?;H|IAtVatovj=-RNKb%wQUBO4h?qV zUH8r%ykm6c`TW!qsVaPL|LjM8+YZ!gPd_swn?!<&BNaucHKSl)6Pc#2IE2_}iCmXu zGbuYFb=GfS?h@%)9{`7uGWrrc7U`QkscU0Pgq!ZGvYR#D50>pg?+U0h*F&=K` z`KVH$_Uzfy+1sx2Giz@?jdeA%>sYpU{GAuh+uF^|Y2k`A2!UDS(?V)$C4n)PkwPlR z+mYni**+jo^4xk)fKp2>kX#*HgH%MEm*YB8y8x$)N@TO`?$J4n*H_LxyEVAZEblz> z0X=)XzEqUsilNq#(orO(1Ox^kU?Kt{C6&>Jh-_6;NqGZQ#z`$vuB0W{-hcgHZ8iFzkv~ui<1(L>cHrU=T`ToC@^yaEt3YG_H;)#Ha#dEy|I*^P}(ccy;jF z6S}-5A&z#OjPCv{B>Ug^##hAFwWM0_Xh1-f_N?ku9Lcz?rQ*6U;M-Y}7oHg;k`{=8 znxZbpwO}bl9L4d*+O6%$hSY?DbfmIh{q0=`mkf-W*MC%8JrxToY|wKDd&fTjyYKd; z8(ciMa{Be^*5wwB+XSLWVoD-ZqhfO`CUq+vCEX*x`h~^A4^R}Hxp`rJXOak`YZI1l z-F)_`>!*G)mD)~QfwQ6_?C;z6FaHhEX8!7*hnvqQ&2}YPxZ`B|zAwo3{%e2rC-v$D zEZ+Eu1s5oUKnNhky8uB6RTg=0AY4Jwk0ZTVODPwRXNNy^?QB_X zjEuloKom(Klt)0Rq%t5Sg8)Pn68{kc0|SF6r?f z2<#n`Lqs8j^UgXeq$K7LLKH_rN+K$&N^3K-bBA7<8GrY`m{UI}r}nl#^*@;2{&IOM z-&%K6gox5^CrkSY)V{ju$`u^lu#**3jn5R{3DN7><>Y!05f7o1gC;p0!iWVC|Y8_owb-?K?#jxkmk%XnWW<=_34_$i zO$O8bnb}7_Q?FmMr~kTZFBOAH(Y?F<@RzfL4?)qC=T5ox8y-}UMhXy01yq8pY;vEM zwr)l|7H!c@JI&aShV?z4|A^asVe8cQTYkh~RPS(f*RPB2-KT%>gdQ&A@J0f*%=6C7 z4o;?mZr5HgQD#&kDR_rEBjDg`-!x=BJ5)glCnj5YHOh;83^IU$sU34mcO1|k|6FXZ z)Tf>hS6&r$S*ht}{?6X}KdIVt)o{3R_O0^DS)kI}Nxij^dR?tk8?xQ=bA$1XTgA;X zjs|+__^1A0_x&G%Bpul@NrM7!x5`W3e)L@6Z#gb+B8R8k2k1%?p3b;K-DNaAudic?{$G5E%rZhP;M>D_aapZ}mb^|Vr0 z&K}$O%U=kgee;!{!S>Zy1{NxSV5v=<#Yskt@Ghhfnx?i@O|C&-LMUZBu0UAs-uu0fUm# z2hW0qK~NYl5F?;)4I7NP;ZQgOGEtFWXWb^s8U+G#VDi9$m=FOKNF}wgj*GlXvi8!h z7PPm9-};NNeARdMbwBil?BK(`ifmvKWKwUUiqmkeRon6 zabuwflN%e`s~Z|92CHnNJht1@K0p&1$TX!bj$(-zn#$J|LeNSIsTxN%1Q|tADNn?} z7{+dNz8fbR=BkNuq18Ef((IWZU;kRM{2ej6DzHVf@11+#v*pF{Xk*e!6BLL_ff585 zh&)ld)$+~>KrJy?TTSw^D%ohwwpWcL$QzAlFZI%XHGKUEIl5#~;ne>5_k3C}ya!+p zxD|WhPu%67rsafr3seD-%qt~v4~i+NxUP#RjVBOuYe#Q>kD1*IRrl6~&6VrdxEL

      uaY5M)y{q4K%ZG#u4 zQr5MBn5|P7d}Eucs+xf^zLm8==*?k%*FSyCpZ)Im(oa(uHz39Ik?fw|67A!sfAFMR zyPVkVm@6iiwz@&b5Vi6qxWKI}HImCw-dF87(vxyf`ii8f8-XFtIH}eKl;@LtwC(Dp zdynpU_~G`>B``&E`e*s+=e3=XN!6}<(}z9`)4MjWUf(+XCU4wq3+F@#LW(LFCqm(b z^<5=hJ>J+}o1j_c^xy|RbNEA_<}_o83N6}6e(~I?ul;pYZyG3@W?~sz?Vc^&9gqKN z_rt#h^^NA#e|0yXZQ;1)c9=RIpZE>g-hboUUvbNqu{`@zW+ozLVCE2f^De8kQc_7N zi712s0742T3KXOeh{ymG0y6`EF-9pRg#dtX8xasAVm=&b@<>hq`KX=k-QS&-(cC_`*YY;52B@^EwRk zIrsJ~@AIzTiX9+9kRZ4VA|;ZdNQ#O!+mbBXv1_}H$4O?|dL~UW?R477G|j)ZKQisa zshe@fR^*Jg*s^5FvP4RhM2Z`@fFQ9D1VDTMzI}PuXSug?N^z#wrM*RGnahTok}^&U zk<{bKUR5rix_9x(C$qyxKr8#x|I6LHAw#SK<_B*#AOEzN+qZq?`p(rWVSTlyxRom_ z!GWMD2oG8X@D*02bYZkJn?^HEd$&FP`J<12IwTn&Y6!HqzWwZ9jW521v5vu+B;B3V ztP;og=s)>q;`WEZ-il}c(B1q|CMI=k#lZvl>E95Y+pql1UnIj#EHC{GC`u`X5X|hH zvs>l>yZ`_o07*naRMvX$g%J8901#s&A^<=DL=Zv{k+n92AcW9b3n8@DQc6Umk1#Vb z%_c(=Bl!l1e9~?mIoipq>1*HeD{ryX;mFfVpZ%@q)ao0r@ZL?yUg{)k6-ibQDi;DX zfD}qdBJ$pO?_zL91?1qX*lsWE4DD@CpN!}KDDJ+kB|D$N(I=99pZVbZNwaq|(V*Uk{SYr##bW@b*C_@-;o$`c$MD$e!Y9kwEHEeGc(^l@o@WNpA`#tlIkNU zq?uj6IK286PgYf?lexvTH!nI1pbDuvs5_uq012^*5u`K#VmKP@-TI(AT36G(rm2}& zY9XayrVxGbF2*PXFmnuE8Lg56R4YkxW~yhCx|&LXd6p=pe27ic6zv`gMGUBv%2JZ( ztR)|`lzEb6Nrs43T?;8yVj^<{W+9upW(pD*Y{j7wLUm3&Yz{20zwvML?eDaASA^PM zEq^J0_}ARko$<~nFQl_akNeF>rl*|$!G*va3)=dc+MBB`9=A7}}rTHUr z{OTXfZoG_ICAWXE|L8x`*)pUli<&lGoW1j(%xoo-3Rrm0UaAOWs7|;65!svC9La9` zG#-20*M95WcPH0YyCP|I%y>MlDo)Yc;k9faCqm5B;X5At>fCLI+=b`HXTGsOTQIgw z@9z4M-|Ri~Spc*9#w+%{cR{Hd8B@{k^;0WF48)F^t7>M)+u&v_&;pbU_y5Y1^y+{1 ztFIWvtWrlaGHkz3*X>x2dY!bjCmYA8VORRGJ?+Hvh4QMW;{KZk>Pe zHSIAGI?Ij81xx2SP@OO-l+Mof{A8T50IRm9-u0I5{QNHr?!LPsMkzC?+~sqZzV*j* z!nu0l>bf@=Yz@mMiiY^H-}@iL!TYJXQNQy0V(Vur?nX6`i>K9tzlxpP-ulM>+pQ;9 zUV2F)BO(#S7@1iJp|!563K5Mlh!8>~A^;Eq5q>U&;Jqgzt+i5$nZ-u{fQSG9ktz6c zGS@xZs&J(K9!T=}08iD|lAQDgp7$7nTW`XP-4!2>rRd4MKCnIYs;t0S}LWnMS zXHp{s*S6707Fpkj7NTN`Avhl_011i0C`RxxwtE9YEZv8^(V0>SMG^ps(up!kN(83h zC4!Xbyd{cC;LI_mOO36-4<$81VE2wYO^?^k{y}H@Vr#mNwCoQ4rn&c5nk$>zn;Tlj zqT4ok<|8*DvQ$EwJkNs~HEve22zAPPy5O;t6M5j|)4x7{Xvx0w{o!k0pL46z)gc`Igm~h2dk;PX zfoAW%IlJ(-&Ra3jUQ!|vW;Ez^qpcWVGMzNzT?GNPY5;a^^U&9x<}-g8*3W1)j>s^7 zkG%gML+6pVfACzhalI$K_EX^-B&r+7piJ7z^Fm4m%t4rO(0ju&@!r&&{Q+V)!N z42#4|2tv;_QQ9yo$2)esSBNCRY-bi*M^7C7)DynjBWA0{KxR#uR{CSPk#U3&V>@k@BTD3iin(Z zP16vOQpyaX?2RC0Cs>4ryk@C!VYX-gVk%ey&WdgSy_9Q z${48?2((o>8}BHp4cBPLWG4x7k(p@GWZK1PWm-Vqh51D&3IIU(h%ihACS5=VVDOHH+s)2aJsDP$Jy(tuvLfHq zm69?k=130+loX%@F!&Ix^L3FYLd!tDD2hN-HFeckh9ohaB+ax`NJueo43Y?=g=jT0 zxe9_!wQ{00gyn`}k(I4PNRy_Amr8qm{NA6<(*q8J?7-?^h-pZUi4!k^|s}Xo0@?4wdNm??ZX^qJKL{S6mEKnNixJJoT|LRlrowT|8X_*Z(1J$K=`(d*ynHLH6!cjU3hv#0-Qaq2Os z>f!4@o4tRbm|KE8chG16p1FQ+-~vaKWz#g%QS?J)QpB1`$EKev|D;N z%Ley<;a7{(p8=CVJqqVv9G`zd*h%0tE*+Tv)Kju(Z@=|+dEr9&!OHSrNff=2$x7x{ zs+JPW5T+uXkYE`&G&Gw^N4|>VhW6e6vB9Z(Y?inB1E~|<*g5xuZ|$6YA&l0R=lh*J zwLXk0J8LLywIBWG|Fc*=MebJp(!WbbuY=nR*p&+ps|SA-ibFs9!++mx#<=tLj}GL+AQeCmswB&mPNdSxXf2f!CU*Dh&SHCR9{YVva}*kc2BE<^7)|4>swd@i zJZY>$ZPGj=V53ByCW%rpG|pBOqcO^PYm5o;=ZLv1Yax@O=qQysPtJLYAO%G4LR05j zVzi+tvs5Q}A6the4bp z90Fqi1R;exe}pVA2!=Fsnq&h*x`fsQ%ERB$4-cU;%5sU1f)S|?JF2s5rsZl;qdut@TDlxe0f8Hc=h|=5<9CneD?(i9)J*0 zeuSBcs4Pn%gfT`45o07G{15;lNGTDKh+>QYz|7uz{0K7>5da9_M6xd@!8YZ1B!p1C z<<4!#lX`XX)^}j%l8>02{KDK*|BxFozJ8_Ly$R6)ppZ&PMSw(<7z4lpSO^eI!CPmo z^Hen?WkD!wQ9khT`+~x~m;O@NYa%_+I`vCaF4k_W_65Yf?HoyKjaqvYUa6$hEe3O@ z=%7x)v;Y-2;>yOx5i|KKY-LlPSe29G}bl^BPgjPGDIh(7D+DCu4&Dw?*7=@&+|vIyI&`BGU)=g zf~D!Kc9ZpL=OWn&5M)V`n-m#?^F^zp@*Hhoz^bmD^^pU|+89jI7V6YR=~;tJSm?TO z)vPR9Ex~a-+|yDn^t$a%D~?vGa%EbJY~k*?2aeCS-t} zdhogb7FrACt?N6l{;x|nTlMGnsMVRjHGPLSST+>Wo;Jbm+rp1cj68ptX4PH&t6Jwnb0hj zLtjsfLMau2ZUSUQXZcrt8|Urx6VhF$z7lCJ^st&fO~;3n>*b2Vw?96cl}ofr3{8 z6(W<5-XVpiaxQAq?u=#iz$2gFv_F04$K~!jN&k5J#OH0=-`rTwnnq41IRhvmGn005 z*=s?rK}2Xun2ws^UYLyK_Aah(*vXh94Xc&tYIIgbufgS-(+nLoO^lqiFz-{o0G*{Y zX}8l{B7=-hMVqoSTpQurh3qdTNvBA9c`_HQELS%6u5XbSI@L)_CfzI<6lt1?tsR&) zP*%`XM0M$gWxXB4#8m5gye=sUDU>ln2nL||A#bz*iqY0FI0R6D8Wbiu=!~MUQ8b)1 zm|EEqt+`_1kXbk+2K!{v5-hkH+39+)b?_unYMG%(Lg1?AZf{PRmN1#~lbQ=oY9=Gg_gF~s)yh!sF3muuYN@AoK0}(M3g%CZUOY5pyIMp-znw{tV zL$!6oRl0lk=N3IPo9T34diO7G*@J6uz0vW*PVfmuuRN(lrc0?Zz|-1}*C%7WaOc5?KAkTl+b{pQ zzV@TcZdV}ZTYclj z+2#kSh^VL!C)aR`hbZRB1w!)1(*=)y=JoRcdo(Sb(oF7)ffYljjjr| zVpl45nuEb8IB;|n5O5&V0Sf7@jSyvGP%4rb0X)aRAe2&xQCfp+3DW_Q#(*Iph?FpG zyl||$^ZWZt2SjHOO^cN#K+;<0nKA}|0TF}%Vu%4avTf{eXS%sokM}q@6-7Pu5@wyQ zcWN#@e7b+EKf3h2@cxgIut^D5>fpZ5{%bo_SKoPElkEuBLMWZ;BvU#;p$H+k2#CxK zzzEC~o#)7Dh<54p5|kG<|MvHha0>hT5B=iYy^ro(`l-GCT(^3wm5#{=5F%=W<|HqD zaXMSvdh=@S!i<{Efx*3Bd2IB<|2yYlRt(^_&rjq7+wYu9%UfM?28c}z%GADy)>E|y zI!=J{<&#SfJ!V>N^~ZnGT6?vFrB4_5=%><8{HEWns*A73jY~RK+&?R)@Q5{np%p!yiirw}a^d63kYstIu6|_0KxA+D=r~ zJt6l!Vs3kilDP|C|363TAD|o0&3B>()$I#q*tz*4GYRfdwJO7Aue0WDRt~eKk|6te zx5r7+u$cJ|#Y9pkw+bc5Hkf4Srh7w7WRWN2rhxWoge32627nL(5%Gs&5W#Y2G_bce5RA#>hi_Y0QhP7|XaC-d5k%|c7rKxC za&%(lr595-RX{>Yr44Guj1+;H5E+TRx3;N*cQSfWjSC}3&fl#4!b2ZBar!9~ix{Th z)<9(-+Kd6Agy{yX-SRV6)i%~sF&oF-&FS{48*iIfCDf#34LIQ|c1}yBlzcz$=yZ^^ z58&JpTs+*GTg>JClo7_=0%zmS{W@BX^DwW@+5B=VGziHt)Z!duY#{B zG||_#9AP;Qlf6()1qCHoq5{&)B8K2>>3uCACK{C@DWVV&Da7bvw9HYFkumj_>c&SB zLM9Pa<2dgOOi`qrE_S-Q+cQN=Duq&ef~1wU!=A9{k5))$ZN60vrW`K%sP^O{#T*LNNdn zPbL#UZsi#O*G=UjTWJ=L?Mr)(&wamn_lFJX+5G+cp7>SOU)VbTY`pP&QC`S#$Q(QY z=$4v$Oz;2d%DL^0i&t7jVg=1)^4PC`p5OZx>|NA}f)l^gWRI<%JqueG=M|)iqjoi8 z6MG^G6-to4(L(l*F5Lf!6nm>L{^`Q>GFH1ZIIQpboH+T5d)IDlyzqB=vXUD}_uuW3 z#d0)JVAIr3T%5#g{=l)U=n`3}ur*l7d-KrgBUIsom$u*ip&PD~jLLG&mp8P(RqzO#o~wJ2a+#0UM|boO9W562 z=Y3b#Rs^3*uMi^`i^S6a7($3KN-4Bbh)6^s z1ZGwr!H*D82!V*087LZz>@CLVor{1|&Wa)(=9U);(Y9f9h+|!p)a| zX6#r*k0^xFLTLs;3{nV0h%q)zVI>dB0(O|+6qGKzo{1jtmkx}7x3h7UfevcREm`bWtc^XOaYBf^Spz32ht*KwX#;OQw>^x0DuS-sIFW& z^|k>fg{UwxSaP%I9FdE*f?%aVp+R5}(ZX!Z!|gB`2G^JfX_T?7nyL;yA^>r8-WBbF zMD*k$L}7$9l7S$AmRf4#7+l0?QjxVO>&gE9_VST*`3QCvLFGV_OVNxBPqzcF?}0H( z$CnnNzV^LvblVK!!^ybyp=DlMfJLNG&&1jNJPE&z1e1t3+` ztmarH=Gf_bOnGbcy+6r@*J{op;VxS6(Z8si^nAy%9hbNlV05&U8|?7SZybz=t5GL9hT^XoIs~ZPPF$QZOv(B3sx@_ zx|2s2++Ll{Na<{Xs1lh%nCxy=(@ByR1TxKwUD=nZ5S_pp}wR5K)Ygi0~sq2(2{{ z#Tbbw#>mXbBsm0IVTj&&5^9E7`^fD}2Q#|#qv4sq^FE{}Ki_-w%h8FoGcV_HhQWr& z1V|tl1%uGW1n;Z5woMI8S(>!+cBg+N=?t((qCjY6U<2P;Z7!X&YnMZ_TUSGCYZ;q? z9h!PiwRAZyDTqWT9JPx|n(j29m6;hVcMcv-jvT`S2UV*OO5$J%IHO9Ili&iGjxlqv z=U3jm`LkQo_q}PX^bH1zGI!lD40R~;zDWwK;<)yc5UrHL$b>y4B9~D&GvA-I?rsjB z9NeDiR4@vZO$c>#RrH+bBx`Av%BX}FA_&hI5M`1`twmyVo~K1y=eg_+;O7LO06<^> z2%u`<2AF^uVt^1p00;z#5F^+I#$%pM$a_JIHiC2HEV+ifh1dW&nJS>tPIpF=&8C?~ zwh&zwd`~N*MO9ZWgshc8l30>nB$)RpAIR?VVBZma;C3kXLD&z`6Aqm&Lb8;Iae4Iz zaPxav*sS@RiQTo&lwR)}X!`)-H`Nyxg|yN(e6&Xz5Y0|H-wN&d%0XB$be; zq3k^JrO(K4dGy+M5`+0eUxUM6+#w{SuAFJdEn#?49NTKzlby-F#qNoRj;I3*Ixj$I zKmb?5cn8WVMlp?={H!DPR2+hvK-zP9K7>rNQHW9yXbD09F@Y3m0Vo(4C}8x!4hTkT z+mXDjN73%+u$zZT0#WPk)L z*kH?~I)Re(B%nyt{M@V@t61CV$ksDsau;B6dH>ZZedb^NKE%y<_UrD0AIY#++cdrX z>Ewa0zVf3tdF9fv7U0&)--;-d(n*qNt%)ec2mm1j0MJ@XDMJV`Mk%FMikU(PL?oqD zO3_E8lpzEn0s#7mU~;yM)@l?)1gM8>ItLE#KU~1-Yr|LmHd-(5_)P!NuSCo1Z@xC4 zvWV7(*f{S4Fe+hmh_R~cx~imt=4D{ zRUKMbtHOC~hq9NjM>T64krcWmOxqL-+590oaUaj^$9$mLbE4G+W!$WqRh8Y_j6otL zD3U12;iMK@bGOOY-~Z`2Y*w-v`^FR9NMy^Zo=)q!jsSV9Ktzp*(UWbE ztVZe#+R)26gAhupMtgujur4iv3HU__b+z-}=jEdV5!3e6@^a*}pqk zyl1(;&m5df`T=wW<1PEa`{T7$n(jb7mMC?rXLY-p?i6;XEz3kh$QLKjj-Ewy;4E^~ zQfgyR8c)~+kUB9&ix^xr@#QoI?(~=UCc9hX8`{)^L6WD5P6oTPLU!(4IQ7Gqz1<@naxJi z*{qsQCUsr!H(>HUsn(2OCOvk79Jm{kbJusyS7BRa5`|(&m{gi4F$M;iCPiI`>8wt& zJWW&YosX6CB~epWLm!)dw!9>6zjxmQdM6BQK960^2}r$F4r@iCNYXsXh0zYU_QZr* zv5=9e_D$V1jkg4_u(0eu6o>(}R9a~zw6!3m#t#7_0yD?x%X$_lWNDgaMkx_u48cVT zQZf^1skP7?fru5z>2#WR+TDIn^gGZ>0GNm{3M6LbflF{(^v(;T%Wu$Zvuz><>zdkn z&n!VI%W2T_{lmw)$M2-0r~TY%2|YErRbKgKtk=@RpEFCRS1z0bJB3&$fWeU#D$&{~ zEdV)q3Ng6GHYHF%$-!GDFY@l-?oXM13s!%y`qMw|*=^N(Ao;}a!TyhfR@2>c*RQ_N z-`7pbjfIXzAb^2u!F(vPn^cx%agZX&C(VfdnCR03)|=4 zAD?;IOomEWr|TIL!BRWz%%y5F-EJ@xOGoDKI;r5+@U8E5t1Xe{+sXXGBfnlJ_iny= zCb@AICf6#q;^-$2JoH7ga1ex}y$hquFP1mX$Jve|KbLYM8G!PA9f0B}1x>PFgB0P`7;TeAAGv!PmJ&*~)86LNoJ3w>7p}6Q?FPX9g$d z?|H&3ABTvLB*E41zw!FH^Y1)-^_9F|Kq5DWLuGO;TPDe6Vcs9zd}H(Cwy75GyZy+6 z_r%*06+-A%szM@ z0wM|_y!S+8l0+-T0uev~3MOLuIp9DLVXX?&3UdUu8gaVqQ75B&Gj_p1WJXSv}~D~p3D0O4j$RB4j+f*hrsjz2q3Vp z<7_;g3@^U_o{!XPwFR>b+%~3{7e;Hld9!ANt$|sb4?VR98yoetYg=zQHQAePOCeIz z@|HX8uE|AU9|IyJLS{_TS|2>2U=&^(Mr}uv?Z!>!iv4rRiQ~OfW(yDCplc14HVQ!i z2|@P0X{*t)QN+lGIRng51?HNfj}&7d2mru>iKv`RTX|j-MVch!LpdwUX)Q&OC2b)@ zq^Pu1TDjl=2^BCf3qWK7j?n>AYS7vSQ6@S=P{9MU&?@zTYzTlN%`%l}7de>sj7%nEKD2kP>F*Nb|3hK&Y{zw5`a|*732?* z7`*nA9}KdXhDjkMH69p*kRL*Uf&hsz#@(GQ0WoWtrkORaN(Rdd_kY3kT5#!)SD*h6 zJ>h(DU+>X>2?rkmfbGq9cXuuvz32A&gEzYup2OC>%kHg@p1S_#D~AWU91WXcZHnG3 z(FZ<$H?F+2df{c0W^miXi;w=pl~>OVUwwJm=s`d8%5P1l)5>Hj>t~6l%Cyt$_B-Po4EbnE8OFD@?Ri3htwI zb`^pHV?Za+%7U$CB$|9cy~F)G9?EXJ2TUtmzO;So*1o$>ac9nQva@n?^AG;@!ofM! zHanw{)Vbi+puaRK#}k}gDOavE8{+WX!P5`eEEPsVz&sY8y#3?zWtQ){cx%siPaM1n zL6TG|kqHJxr1oZZdwXlTw^?Wb(T~T|G;1lPCYapzPkq3-)! zy8n}}{NVMp9Km#mYd`yTujmqykP;C?jDez3$_0;zfXDz!DWPQWPR5u?!Ayb4adeS9 zMFLh*YpE0}5rKRl7h?#_!8M}{e5ANFwPyZMd*6}e!@cN2e)^-=zv*x<@8s5DB#mGiUz-%AZ~{Y`WocUYh;`!`5CjJAt*eL~lZ~-S zQ`JkB^>pE>dwxOhrhavl1)J(Pt)`I8M>8OkONl919lY|xU|l!PS*28(rid7V zmp`WvAco+a{}2k5COI<;3C0+T1OUn?qWB@D6j7Yjl|W3ijxnZ50t~?i06-8Bi6}Ay zFe4%}d+!_DOsC^^t~Jd9(bC*MF;yKQu#GXW znqV(GaDVH;&)~rmm@RlbSO&R!?LD!#vczK({cKi_t5RmEX|+6&mdRYZH{BV9s!EKM zhW2JVGe1-F`xhVjTDzU%PyY>^|26?u{Rhp*f7cv24Fqe~E-IeP9bLTj{9hgn@6pV} z-`B`SNmh{0Inl^*evGfA`HyzzsUK{Nz7Ur=FP(_jWG7(GxUx_z<+a zRBq6jzu7ta6Lgem5XvPz?a*=^s3c~UbQdRbkazn!jumYP+HNLfVS#iKyzQGzGlsp9 zB?=~$SzG8#vzCz|I0oy`GE$;joc5>rlASx+I(lDm=s31=pbBAkgvuFh`g04bqg|WhTAXZ3s}9Yzj_i+FR?VU$bK>wF_aC`0 zk2<;t9xxJ6M8SX&fPfE}y+BS>x>d3lJ#!z`%$|M1dk828u@i9034=lnQ{^M~;y`#36EI zh>U~)X_6uXL|{)GS+J1EzS-N|UQH8~wg)%%YOjlZcieICXg{9+QGDkIw0EOo1N%;O z9{&x|o)@73iA)fJkHLza)#~Quu=N3q*RdXJiZOr>f>loKCDmK*&CTn@1sE(se-4rk zr~>jXh!jvlB!Y;NF}OH$8yC(u!!52S?L=g$aui6bs5A+Ms5F5Hgw{fcqc}Ip|z z$ibqz{powZ+Nqc7o4cYKCB_D_7TQtuS+Q;fzKKx~?ZiIma^LMsITF$Q2}qTqbd%DnTzHAEy3 z5s;b2quoT2inH1}wQ#6zEz7wB`|xbAUdC*)xvQolJ=$`kZE}t0po>E1Eyv6RnKl?=Ju3w=O03E1Jn0@e zflK$MCh#}^rMUJyCHZXe!Oj!^1eZ>-NPJyN%~H7w-~Yzk9 z+3r_(<+HEiqc0xa`7<>H96dj{_DkH=i<@_1+hvqpWR)t` zv*C{2zJ{AmK)ng10V2dXxWm0a`|Z`EcZSBZn{RG!*fNhV{6qI(@ASc5IGr1xGGkS4 zI}R>a^9ngx=o7=e>_|xfP|5Vzb84MsX6EZ45V1^W^D0i-!(U!6` z*&4DDBx?4LeBTXft#^ue^4{|8Kc{YArv*}GhZpGbD|GHf@PqloIl6cMD*EW1izy)C zW5UAB0BnrWTC*@GCPhjaQ8|N-(MR8;&~oT7I*?$AIC6?9F%TM?m1RcY4*GV%`OsyP zgGO{-oxi-hQTyime<<&L)4CH?)YA^t`IpfYRc=+0#Z@yuI`G{}r=I#%T%A?c8k+|! zyj@f4m+EuZvdb^Pa05bM?^54O2p|M`sdvs%kwNOaqlbjvWK5Io<*oVt-n77EIb@ia zL(_L`6dMhsl(so)6%zM-3ULVwHJFSppWlxsZ$EnDD7+W*c~&TGDu}hF+L(;NkrKsu z42lzwQb?3U7)6j1dls)WC+=6x%=uM@)n<0-=RW+O?&7okgGImp$UvhlM5-bU*py0v zMQ4)eq(p&O1cVTR_Z|=wDI`>+1pXGn-}2sTt-bdkVyp!KB0|Ivf{19X5z#pZ09qTR zGywttqJT&W!8>2%HpRp-0DvL_fRs{5LImPh#GSSJEF_wo+rDxIv0c9L`>XH#)+9X4 z(Z_0c5ey{GFj8zN_8LTt3E8kOH{wP&fA3q_ z{Q7u(JKuf1-G6lVdw&w<_Y`q4xX83MC^ol0{vtHrdHCJm(nD%sD?k6AT)6tP)Ay%` zx9;iK4K-Nt;=2&MsmhkI*Ex+hx1M{c-afy$_h$EC`()BqWUR32S>JjJy#LN6qfA6i?;g2dcuX6TaTO8`qWtm)4 z>rYpci`d=#jtDyEVvIy+ltz%05)pt%j8Reo5T%HeNveowMFPZ5TqABJeFMqo)+((* z>4Z8mML~cl-Empvts0zqWryqAyIWNaynnrW`_J*E_qb*VRtou~B1rPgcT3MHfvl6Nuq7(*06MWgjebzuXrJ^Y*R!s=jPL-F#* zmV4%SCX*sp9L0Aj`6wJw0s;^kZ41&AnEO73c$!+fKHPrp!nfc5_RZ5DnjP=;LI98p z;-SGxlR|O;kzgoX2$NEZlwwIf`H);pUErQnWN=--h^f<*mulnhyztA2Sde=%}<8f8^Kv9#+&SsA4z1YRwmUm04ewevif z!p$D8j_$a{oZDsuGT1)XTzzqJ=@qs43}gzhgQy@G5Q3}%sKFZUkK2Pc+~J#9HZIS< zPUEX!$KV3E7LtS5LPlUT=mI=I1V99Zpc#|~sio=s{+;FR>&tt$Ler5g>g}D$D=%g{ zBRRajxbsapy-r~t`m@vg<;vz1Sw*R{LT3d$W_0qMN0!pYOgj?B;8s)cU6GXH%%E=x8C%pw{uw( zPrfYGYY!i`nuQW85Ty_`iN+u)rU=Yd&;V&c0yuOqxx8j}_1E6{^3Ag!rs0w*0k9H^ zf;KD^8rYh^=!pglMM@wHL`WK0l0XcpZTm%%E=u3~MG~iVK~jJC!r%MZCw^6TgVpVW zbh@vVQ(4AJC9MP*AyP7!a#RR9fiMuFKoU`is7N6JJ_aJd!jf1XOUW3^DFLEZD#XCd zT4|*e5rr80t_v|{S!OfqLl6-~q_qMOP6-mXZG#|0XtgG!6r=Mouwo#BpuwS^X~XsT z^Ja6hynl1?SO0O;J>cb$Du;0KHNNtSovdfJ7Rh|$yOR?x3#^o~l_@qsZ$PZUH?aTJ{_Wp^qwDBqpt6-&^P^`b zFMT$@_Bxci47mU(!w}~H2%!MXcscj&N#D;BDzwAV=z=P9;C*TCb^WRLMLu~pA8dl8 zu$<3tzk77+W+`EPSO7-?>;-0h;Jn^>>bb$?CqcQ@SN?7L?w5^w50no1C1pkueT=6% z15x7;2IKXs#nZ3hlP_|w-L#A3n{JxAq?68VR;+E>ovUCe9KXN!<`=u8H`hj6>(BmO zefg)L*j+t%=#CyyST^&6l#54*s3{O7RG^qJPz(%pF{xtUgFDMxH~92OgHERM^;(*& zS5KUK@*__|cGf<4GaTJWenGP(CdQc9M~EpSQ)=xK0}2`gRt1!ZA~xrGs}oz7Bb;oC zF10EQ>zaN(nPCYo#=S#E?Spu1_IqLXC(Zq>zCVN28P?MJ&+;-}f;kAr+C5 zQj%Fy)#Y%gtD!NK(FO=WT38**-5)g%Z}x|G1~zGN7&`B|d{Cv%uS9iJsCq5mIER}T zWU!GBHq3AW`5-RZ`Ps~^x^CIHz}DnO2}BQxm4E?4q{PUaNTsT#s!kLR+oN}-KjLgO z{K&5!-I_@h5+WpKj*_x61A-V`bWTDvK!wST)@Qsqx?C@d#aI6OQMwrS zmht!@gt^T$7)XkR02CnS$R!an`ji3^5nvJ~KxLG$2mpuxfPjDi0sxCKhErk@MHFHb zW~CGnA!1A^hLD&Q5h}&<7!#2q6lP%2N;%hajGO`yX;LVVSU3TaLW0h`0rDmO{lIPret=uGbmIzC|I-Crup4=vsOH zLuTz7jdqex$`DWlMUV}l+5lAmdcY3EgU$eI00sUGj05a|Gr$Qj017DLrtJ<7vFZA@ zou1ARiAlS}*4|#x9O@>0>)$Tk{{2#)kS>DS)}p1Is{(@3jX7UE@v-8{hajKy z^ZD7MS>B_Ee%c(zl`{b=Yla(}v~_v-%$2bJqmv(eQFrg;x-52H*DwAejGuY%m)~04 zd1s*d+5AzjT$h|Nnet?kF=Uvqfz&2f53-WLv<)m5y7P)nVAEsKs*LKo-kJ<9Z(h2# zDI3DGR-}4&!yI*OLO%$gpYLp#Rq z=C`|$l(ithF%W=4fD}USBqdF#mEz!ocZ7i8ICVsXXgTSS(1qk9M1g8NsyEi`+JK5o zTa9EuO7LDD-dNpv8>Y9@$^C*N`($@&WT=FQ6#)nDx*nov)P~fVTq!Q9>|*%J^)LQ#|F4RjY!zHaWAynX+g1^x zTh#@CZV#G6F=C972*9XOqkw=U2|jjY0X4Uwb)f~NGCNvRFa6vzzi}mdMa^ZkcZ=Jj z!V+j^lSBh)1yG?3i6C(sg2NA_ln_v9#mp%sW(EKvQvV-7t+e+(rKFTfDFFZiFf%-c zsE7d3dmlL!RVmDb1i~=}0?e)Lx|UOt6p2U?fdI#-SU{jlya=Kv8yBu@Q`(Pz^CkD! zepUm2f&vKov?5~Lpbxtr~!;~RMAuTJj&AgLIO z3PP8=RUUmItYVC=ivXDAP}ND>2q=*aU^Qj6%cS8!KH2R% zmw;_yk47VYk&{num4Sa>kpJo95YXAg)-328MvdNT>N2rfE zFsX?PZUZk}>RX)^p&noT2cJ!cf3x_je@Cmo=@y+7&#nF3KhJhvyZJ}|adq#;6Pu+E z(_ZzKhnB5XIcU==>7>)fdDkKvOC=?Ry=c~$aJhC%dH?_bAOJ~3K~z|otfX?# zfzH;qHm^Osv3m~AuQ;U?10*Iy2H=zk5CA1cXj|>PBz7rvO*1<=Nj?}<^Xa^4T$b0> zXkw}%*t{H125TESFFNPCwl!t7wl>yT0YH%xd#_gW)Xlv=EhZ$jm!liu-dpTuz(%AF zQ0JGPGnb!3sx@ncI(7|hT}a*@(bmRKeL+9@ zaReI|XKs16I61)3YhXwmBeNjcT-ls~Qi>#PMnR(j(26xs?wJxGY8BE_t2VbS_Xlpd zw_GfX$#d)5PtRw4lw8|E5HfkDl=yx%9@WYB)1zsoErA9RSHC#AYTfYg&wu#4x8^rS z7lvm|t7Mou9NBS>$|{L&PI*}3;&5@KNe}WtH}93`K{ZH$S8XF836ia{a#(hKdvtbK zmSrtZfBM?5eR${7l`obLZiU4jfd@=rqArZeEvg~#Af?FMAqWe{5ECaw>aiFj5h0A_#~e078h0h+`B^kP;$_i1$9U zZAqw=o{KpR>e@#>VssO4{PFVJzcuXcHc7{|7e+t(U#XoJPwqZQhllm5GaKhlA;Ycl z)|G9P4wUXOS71$A%4{!mN8$Kz|NXno(T}S3y*1O5Z%as+n9$5u0kVP4$^=oN*Vqzw zh9V~mR4<&*i(G>zU{h2QZQ?Ru5k%WEYr2)nNm=sIxnPnEZJ8(Cbzy2ULof_Zfnb)Q zCeJ=;$&J!LBw0yzWJg>1?p4^i3fUMUfh{Bn0HM_&49D-xzV^S2+xNkg0;P{SG^@0l zgIR<1=c>>A=X&=km>pjK`d2cOqc^p!vA|9m6Op>q&ZeurTaf+KKl(xl52s)Gm)5;w zKx6en{`x=F+aJ6Bhkr;X4+@?S2E2^(KJ|o@Lta3RU;<*VBv8yuaw#>zP&OWnHdRRT zM-S`R^X$|zE6Dby&a2^I^9ftlW@m1)jEpX-a=f+%ik8b|*LGD^9_=6at{+#GgovDu z5AXYaxxT&@L(~^z_2UxsCCf>m9QIs?)Q@s$B{4 zyg7N{rK{^Zd3|xfd?xp9VlN;A*|1Zm(-Ryh0NS9F%e7*mYGLI{LN0tA9064OtF z$Q(E^83qkWh)m_8ZXB1zaBX8FUmH>;04*%`!=v}k_HNA%9#Yp&RGO$IhE?*>tCH$9 z-!1*={ZTqGH9@`Eq&0u_)00p9a!l*<`D%G^4^}6sYKiZzEM*z-l<)S1$BE#lUUTpFX+sQ=fV6zqvMkB@4zKK8W*&5IUBSFo;32 z2GxM2W=;fNYZ8$dBQw(nQc3_oMEC&!KoMaf{0RUM5&VGGnwdigh)6`tEFyp)z>lSr zK$sBKV?-Pxf{-u~iHLK~w@m?TY&Ml@^XV51d1!9Wzw)nf@67`Hx!El~_AB*=KDYmH zw!DAqQdMUQka{wslx=A&7iVYpa4@WPUd8M}2B4d%QXT>)4-y{9!*6wW-fHJZwZ>*P zQ^{ymcMV5Iz?f&=W=nz7=$7bmC6x=_W|Ud7niLrp?b-HBULdP-rlc}N307g#;JmXQ zA{l41V6FCj<~jmxM&rs-@T-oSWHD(rtcv2D+WNZ{q+qb9Oqy~R+~ICd7%>bWm!hoKcwWN5U9(6MaUrz5Bg9PEFl*~9FS1M# zB2ffdhDdn<8po5t{{HRZKyR-X?evgBB+;O&WuF!+PGGRT@wE_=_ue^|Qqn|uW;1KG z*3P-Ub%}?~RQiYdzT4=ZByAwd(0l`%`~*_Z~NACaiJ@nuFD*>0Cr@ z@}eA!$r?_{$Iv4tt?{u0$fUIuQJfMIXyq|2EzT9sS4X!V+|TCheC zQBl`1bn~-gi!pfTT`bFiBBPYy3r`Gp>E80KH*SCJsDH#(wa!mQTkUFDStJZ0wk!!q zFFH6~I2F|>8<$j{AD_E&?&|j1g|%u^NyaG0-RZ5pJGbuMp3e6+w#^GyKl$SMU#Ml9 zBBry4-Si#=FEK?936od_ssgG=Kw-36A!162ndt-k0Yo&$D5YYGF+}y)&td+7#8)IDG0e}J#<`|>vd*AiBrU0tA^lW`@7u&nDKmFHq z>#New`s&>1Bfprx{0mE;AKbpXCT$UtrQMa7uIAnIvUvFQqoa4SwT-QpJ}<*(Pxoi; z!QGuWFNz%2FTmP5XaN-f9E2YBAGztOTl6;BJkKbjcK%@R=$)n8!!TP%dg$#0F?=_7(rvge|8bz)@Yy4T$ z&i8<)RZbXv@@+;kC^D_7SuBBwv{89!vXW7?-Xp34l5s7E)e2mrQ*Q@2er5ZU|7CIR zB{?{}@n^q%VYGETEsJtuvItdN#YJ2>X=3VHvSx<%@vnIP17e{1h3b?4 zo!$D_U;pkG>F{CZPq)?!hi!xuBOB3`smgN5S+({g)?CyxQJBI(qNDQj6k{YZZJ1Ws1>;OOOza)(R7(P9%9-#jFAV2|)=M zWfiCxV`6U&Ls(?6)T)ou2M^x=kxJfHlkICC!Qmw@15afF;^cg{ER1k;&asFV(0Mhe zUVJu~)3@(_G#p&~^}Awo(i#)ycCSws|(QVJ27ImVb0BcW0X1elo=DMj9O!txj)XhlY8 zMXG6*06@Ybl49hPgawJ%;di~M=EN0K_-9C1Y9;|iynG&eC?E1xQgH)Awd4d;N4z^=B2d%FU%awH!G0 zTA|5vQihQ{&v^h#;b?K)!Uj1dX>o>mf)%^G!(*>kU)nGjzD9*!K zH*HQ=?yO_yY*oT|^ZAdxoYwsEoBs#T-ejMod}jFR|28}SiJO1)fV%02HV?74Kysm_B z)it2aXnk~eeA0H!#`-36iXm>SZ!}H6Xj13l;>GhJx^^|sbCVagSuT|(qg9?|igbuE z#l)F0Yr|!`$PJ{>trjyv%(5yghgCH?oh~eB@ZK*M?fmR)d15P*6=hkErnBW_V+Uv7 z|0D4(I2U6gMcP=>29T6C0vHqb!N-_@NSQ2VMYXxLwl!8NfIAJ#L%#pxvzu?lW)_>d zC8&#%NX5jFa$Y;XcKIps&`yvy5=IaSpemUe}Azq|LnKZ~x7*{FW<<2$c>s=d2^ z@cwO$0wUJtQ7q=Q8LWFyL}-+#)T*#R2`L*SI|KoUo|vuHh&pnLDH=-b7M7b_Cte;+ z@84MN-!L{?zxrBn=|e8oQ4c$x5F)0&w3tG_YD0*SmE-lDU32Zq@#@~2H@|)`e~5)j ziG-l<&xFp%&cyV+_|~y=Mdr7Pw7xsp{m3(~T-&Ob}pb+rpRrTO*Yq5 zp-Fkb5yCFFDfXw$>TYyrE_>zy4t z%;fCO;UE4BI=XJtvVQ8L`s2U4vQHk*hEg!vW-AOGgY)`^!3Zd1+Mu9S#^4et+2yMB%FJ0p$ zU#d}~x9TT8IeGo_RBnCyi@!6Py+h0CXt+BZZdH?wm~#^rZsGhqaPY-&B$KVpYv*tq z;`e@2mTx7WqYNsLZ4~)4eK4v1DYrc{@EiEAv5- z54N_p+r3sNbLCYSY;m{f z7iY)!_6}#OKz3_;fyZDz7k6@!_> zsH`okA~%YA_6tZJRDq^M0EvzSlre%jFeC;5POjCdFDXj5aMSk>um4e|V0h`n!)qUN zGVy8{gft0(%N4k8)pXHE9BiIjf9e?+Y|OjE`^WEk@I_S<$yWwfI zF>a$tejrox;_fRiU3vceWH&A2^5F?IsQ}A9DW!F0SVQ0-8cdPr!;0)?mR)pR)Aa|= zKP+rQZ#35mD*#T|ClVp0Q7J%R`C9<;7;|DaT9Z=zSV{swL`cYl06;{DNJId@A}K}y zP>&HMW)aZ{2m;K)k0p*V#mLMGfE0lw@0{;F0w|m5^_}|Mmhz8Q-~IR9&2RLxhvj&4 z@X}}OtDir5&>xf!0e;oXxp1KVmE zD9!AUSPjrLtXI0A@%a4H7p-0O%iH1IZ}&%cy$ku}53hgZ^I$GTPl{G}`>X9A|Ib;w z*W}y&(x=vc=AUr6?T=6T*@-Rl^3r99O>_56Vk*yl7zUf|VsY^3Rx{m))72O%^cCcJ z9C>G(6jxa+2e^}M>=frV%&%1rZ zs_9L_8q3Wvx;*^k7mAA?dH1W|J^lVy*V3|}G#qc+wcS`Kue{+5dy*JzJ)BWqZVc)t z%J%#JE-n8W8SVN@`A7c|Y`*yJpZs~fTBhl7VIV-t%2Mf^L=h7!O1X*y19_Ib#I~c* zTS=G##z;iIPq{7Gr^WOnEN6Z>&ycG!UutmPXVxmEy1uu@tgo$y5VTSuMi4w4z{X;b8t))@gtg)uYru*|ipvZ8Ohqy0lb6M{_EH@s^} zg62M_2og>j7fe+TMn#_Y&XY2D`iMcIWkTdkDI%6d?bM!KrVT5S#G z7NienkJ?A?`u&@HdP^-I=5d}YK%`#sU^j5>T6W>3?EG`Meid*tEL`*O-S+5iYK|qe zAxS=3AD_EWTzNwF?;gMX&8k1p{c-WxU*QX%o<2G`x^-iyVyz`pngPL-QD>>BDbIx& zf>V+dYNd=q;S>OXv`wg80+)ydK*R_ei0C@qJ#crwv^u_{>IgG8zN>oJ8s_j{(E1#_2`DG%Y~!0;iYE=S3dF7 ztJ=Y%yZ3qSC%Vp((g_uy0z`vikRdg`?Lx{2Td3BI-Rxs4W}f7PurFw+Wk{)DNkKXx zCap;jS(H-rfs|5=F)?eU1OP-35dZ{$A44FmhzLG_h)O9$j33Y+NGWlQ2x6^uG5Pk zt1Oh2UvF7pVAn2P$hLPdFMt4~3*DJ(P89dxTNRcDdc?pn9XveEmeXo+ox9V>lo45_ zW^A(8{(kxFFE#h$!T0`(AN^RbZjIJ9XydBSjbt#$Mmk#OBILz1k{xB+&uz@#_$`0> zhSFJe=@aFLe?h7z-umM|8}%-0yTYnA_NFL|EhPvh5TjC|`y7Kxm?DNiKByQ>WSx?V zDRxdHxxNjq*C?yyj5$_Sbrx5B(^q9x*TWD)+qEb{EQ6w|iz0fzYF9CZ1i;F!Z*A{A zdQ=U{Ah8|~&*pQJWj-Wk$cuU~m?*N|h2+sdr2*VhgSyBw&`sFF7R20LAdA@nYoPS>LJPYH?poXEB=I{_*+b?F_{8*=^R1A_Juelfwu050G z>hybmD)+xXa`*JpKLsEEbr;Rat?RK{83ZF>iR*%rR!v?xRmNyCAFCKq6IcxhB8&h) z3P^_}&L<#+0ti6D5Q7RQy1hQV^*wB6qupnUtDg+zg~+)$r&3VLBo02hHbkn&!>yg_ z+=oChU=)BT2tueppkr7aH+SFPdv|Yo+$Vhc;AX^f5wf6jZ50wQ zCrE7QD>25<$W_O*9dYBDy75_NrN&L1vrUTN@=YS86<_o!i2~o z0Dy?_0aB`uPH9C-At2#T0007}7@czfV5}je6l3C`3}{r8AhaHtjUtxheFwzGY7ps` zEhNb&;U!yK&yU^!da4YJSIUTRTkmmu}hDo5R6Gg?P##jO*crb2%;I-LJyQkF1}f z9jw&(?Am8>@Y3n2?}D6v;#!`s+W+%^kfV3Zh3D1lzmlH#xwG5vWG=GpT}YcPWJl!AD>R~NAwlP)>kF;ArVYWfQl`ik zO*d~Eo9D4T4D+;BZVoqhPW@`?&k%T>igihknL~_uIW&@#uc$9)R0x+oj2B zU5whOdoESIHN5y-zWbC~zXW;^J8*4?&BEw5t@@XY{bpFc5lTYyd zw;z7(H_wH;QeCp2_zk-7?BZbWVDCV{l!&zs8O$MrRXOhU5K=vGaTr3<=nV=X2naJE z5GfH!At7RnkyBDcgecM)ed_mrp!R-{muqnTRlV~{AIj7?%>Zbl#1uPE98D(LoWJ@p z)Cv>;U}6>kCa`58$Vp-w-Mm=};H0c;4&iX`_~1a8Gh-1@A&EeWQ7NU3eoRC{3_d1Q zmH`o!QlvBy0W({h2}1~+QbGWwwb7PEVq!#89{>PODKQfwGZPUKi3lPptwZvHARo}A z9%E(@Ng?)qpHi~gXrno$z=5n7(wdc9Iq=bFilHxS>wKFy38F9+MO|!;vFh8KUvJ<3 zTDCk{&E5F5pD#Z4%Pv&YgDG^Uxj)SzD4n%9^kQ_3ROm3ojdGU0^V=PHb?NEy`On^Z z`?R?W7Y4&Tyw}G?s5h(OPTymw^x(>*8p_F!zYe#*zKIKn($YC|?dReAPfZW|u9;?8 z+wgM|@7fD5t^M?``|VFpufJ*Ue2)~JM!fLRm;J*x%7Z^gS$3l*tB?HC zvy%%aZ+#{2Z?NaV@Dk!ULP07Eb!-PsnepzW`*2~Ky+8Qh#`AY58@Y?09>4bY ze9RB-9Xc0=hIKe2SV^XRF<~>(P}NCFP664I2qH75ltcsp5K&kVAjK#wM*jqmM>Wsf z1G)FTezo9gw|e?hPH*=!pOIBa{;?F3#t0ml^Xh^!8kG_O&na<=AQvuQF@sW&08kJG z1UaVDBX@k*ELTdAF$Mq-iJ3zPMr)-NBJoco7Dyt1KS4xFDXp#68j(^;F(zh4R9flB z1R%sDB1-GbT10ftg%GsXF-9UX#vmdyClEvtgcu_;DZ*(kXHCyVwRYihxmLjbHxK_`rrg5_kYDHT4(?vZ4n-I`m!@zcLp9G^-ULHZ?_kp|Ee2d~Y{v{0?y^3473kG8XO`kBe< zYaOnes$V51n)iQ>_B=kkb#e8TuViYh$P#4ijm0dw9PKMWcc&Hr`1z+ zzAt8M3Wvy;$dD44NIO){!hvWpiWr z=G9-`oV+!iY;_trq67}kJ1-$^q#Qd->3#VI=U1^iBF6~ zC9)D8yJU-s6N1N+O+|fJ$ z3!;;#dqk-fWkeKmK!}8QFmt>M;XgB46CeUAA^?b70*&&951Z#l=U>%C*`bHk(nG@` z3Y%2G*OjM4C5B_=T^%u3N}(cVa3R#u2j;BVT0V5hbh^L{9DoRdFV@%Ga3sve7(|RQ ziU{7NwFZC~V+etnL6I?501%OdIWi&{V~I42aEt(epzhFG3qWK+M125h62-2mw$Gm9HpOj$K)nB&dP3$HeBO3}u;~ zpHU6#2iM#yUy%zxjo94s{R8j$T=L+D;xKI9S}$GM?KDWdD<&AcMr1~UwxrTo0$hJq zZag>D9d*y|=KJ3B_VefJjnRC=gy{{PrmA-!rX7{#oy9i#>l?5CKQKL$8tuIGdjGg;-EzDx$u`jv(ADvz}lU{$d^d5V2?T3yRZ~llc z|6{7gv3tnu`z&{#7@T=wc_DaRikK8(kg6K6pXH!+p6Yax=>m< z{O_uyJ@f32+f|v~Y4w-#?!CQx=FHIy^>po(T((U!m)63S-Qs(fe^BOY+SMIMVswC@ zw2H!2s1PY{Ypz)Zn(R()UAeKlwY%Wb-`)SvzScsXG_}dc6Q^vhZDx`zFeiyN zir7~eeKnobwM+5_ntWXQGD6mBp!f}d2~;EAyj87Too-(B!&NAEX1ZB1T=#C;=`>1L z?v96z&J4AWsP^&p$^$erhm?Y7Pz?cHt*(y;g1cgj-j`_-?0oLS?(`SmZn*Wz_RNWoOlePDsx;KGa;#e> zu__e76-lFufP%m*&WAdxYCRd*BP`T=t+`{_~f8oEC(o8ou#TRuoQAtuU)Mag?Zh<4uQO|~yd&}s~ ze_e0A=#ztV?;j++2RF}N+qiZ?b2;D6BHG&adk2mra~DfM+fV;{ede28T@B4r|AYSuj{jbL^%7luby~W{p5^qu z{pGo*<;r(cQ;el)_I)Bh@Z|2BuU$X)%uKV@X)PwnY~;+7<|Y(&tXyo@2}I|@u%R?c zGRWpuLwVvu_fCKH)$GRisM@Xd0v`XgJ^lnpl#NrvSHF^nTLSr}JFxG={{}k8$5+o! z-u|wc{>t!hT4Zxa{?I(|c@E8;S6&*9u4(Wsn`vegDZy?H2WjeU%kKT)yW<-_z^&81 zxuhR>Qup39I=?o({D!V>QoLRIEuWBXbn|Qx>)dc|b;1@3Ro9`C!W&|Qnq$cv0IjIz zjm^o@Jtvkw@OY`pGn;R|wQ;7-N(a?$DK@(M7FXW4@UfZNUjE)+FPRZbk)C|$!p!VH zT>pum9cGostzff`N^@;>02zBRd8Nmn=LO3rJ{^V$8`k;h^29smst0s;cCwKd$_5)nfxhEP{d1k7E|S6XXD zhC>Zip~YK`tjuo3lD32J(t$Fr&$zwywQTSq@oY;5jceJ#s^*JCTyVF6^wR4f9uLB}kYmG4g zAa~(iBEljZqlgd@5(SRTtnV-;_!vS^N^5Np5P$#xe_xJ9-7x>zx@BU9SYtMD9pQg*r_xxEn_Ir~{7x?NM zUZ}HjG(FU>&plmT{4`x=y-g;LxtxD+T*q*$T26mM}SxEFU1ZpB@S zQ{1IErMUZ-=biZ``IX6JlF8k>yJydyqZ%H_`g8Q0u)?#W$@{qHYI?$L%B-^0Or_I_ zk&m~%p2sw`#r&-v+KHS30By0FtFhE-C$87&F1z>OWx1=;fxWlg=v}B7u2dKQM$}97 z^@xM6mD--!&6#+xD6L-(|Aeoz)0z0eWMS~y%Iw(Xe(MX-jZc%??i^=!u)tBla8P_7 zMkc~qWlXbFV76kK^Pl01)-;~Vba9=*az;e%kd~BK z!%|7&r(Fj0lyH&>5ikc5lV9clDuw5@__bK8g^A+vVpQ?Ej`w#A`y|KO6=4wEg!ICF z;_(_Kb4&Q;VEu-9-i2hP8|CA1``*JAe^pOI<$mB@yao3aS3nK~5ZMFlQfCa;T7vOe z68E|YIP#n(X@z4opv#aOJ1ak z<0XH##@hh_Ce|<;G#X-{Rj#b&s^h-urIhDMZ+p_O+(ueW2;h^J{ks&rpDSjT@=o~+ zp?!KJtOloGc^e2Jgt=6UN=lITpGGjCr{Gs~yW;DU*35EeTX7>{VUMTuip^00H?zC^ zRSdCcUEgm{wN(Q+ead_}O!aAPT7`2kOJI@)j0G|p$$m@O?TH88rlue0woGiC5)IwE zy|44SViwc>EuJCvxJ`7U%qO=L21cd@cEzF}eU5}6%OiI|xS*y9WPw0BFg8o!6nmAI z89hSujkOR4JSK?yN($I;Sm0qDAwYl+^r$Duaf;KC^4-3&r#8Uw8EQnmW@e7?KH1Aa zEJcQ~tT6>a2U*sdK>_q%%9$WU5`boGv~BA095s{(;LCWVTn9fn1>6^@El4Y?E%e{sx@u1ZV8u zM8wDEaEB*>bl=gHmmPrvd&72h<&R*~;^u-W9O0ksjrzxi8CefLLSpI5Is*C0>&aQS zI$SvX>uo|+`mDUak`!;K9V-3>MkRAToxX^aSH_2bCOzxsZ0gM>H)x40BZV%`O(vPK zR;=BhZBN~l+sduZaG%((-rP-U*SP*sA(R%jD{8@pvs%4k{q`Xz0-ngi^f?oaT4}-l zIvxe%e#E)$s_o^jle<=r|9T_Lw}M1Wi5FCr+uU}Q*~w#?eRZ=jDK|Q_j@Gd6zP2KC zh5zkAi~N(rn0w>EPzT1d&e3=Gc0;_64)N>$PSX+tVyB z=z?LWh*~L87=Tni2Lr}Q1J|0DLc7rG|A`9G$`<#OI_Q$UUtq-d{?W>evHVX?OIQde zl8s-1Vp9itil+hXgN$Y{veMIoAxOr+T)4G%c)ix8O*jldkC3{E;X;PZ4UknN%1R-z z4ili(PxcTnye@2b=Lhfuupk4RFc2G&APH!b(lIjNL=@*_z9{ z*LNdas#9(BHM2&4`SBM9%knQK23DPMsr(to*&9z@7_4Z%U0AG7r0h;NtG%90D=gf3 z>|$Sg?60tR_P}3ZG@5ba`o100BbuGQ_UU8#JS6pT!*Kc6{btOsWM9i~7%YX?VRP-B z9~~Q8+By267^*del-%*fs@B>`=4XWbrN0I=7?utMlo5gx%qQ=KaA`U;UT%G3&!yt7 z{|&voGkBJ2&?@r~UN0{D=xb?jgdA>v(*3xa9Vvj{)#T{&MCyyL?_hQ?gNe4n?YYTq zepYjEr9a&;;@FnkJf8Mcu{t!h(l$;JPnKcWHCgHye;_Bm_{nE}>0&P&JNYnb_D(hY zhb)0L9f|04>Olc6D#znOs^45tSUmwDyyA1qR(twfOV{xvzSv^(&7Y~RAoz*VV{7BD zD&_r<@jN)UhDQfC?Z;lZ>nss2w#`G%)X&~nf3AloqfCEgQQDH4q)FlCT5pGOg~-6+ zit&9Zj3M&!Av~B8#>UYcQq&ZxQI+;fTw?Vuc}EmhgKu~*v^&v(SmX@3I%Qs5rOf%G zI+@!vnvD7NJ%2vZQWw-^T-z;uS=FAg=i8+`V*1M|J%y&|@6T`x=fDX3>>f4D7618* z*3w(uWt1OUxIJM3K?1qPeT4I)n(26DeP1i2zR+VCpK{U3N`Ozfg2?u+IZZoB9Uh%7 z{~0B$M_Ex`udMsrepsUU)LO5QV8V~`(U$2bV>l988 zz3gsZk$j)J6wpsTD6YAjI<|Jsx*|*-`agQjS5gQ;oJKedRq$=#2K5=W6cm9PpwfX& z{(B%ZLjMEk@|-z>{+p8`99s)D+puA%WW;Nd@^mN0=0qE0NL^%s$m7i*Q@ePn;-_cZ zWxYN?U^;*HOV+wTg62FS6}gL<#;|!!LumTQbyu(Xome&XDWgsL&R0@ze_#ruBr_6k zsGnJO`*7xp9B_o4T@@8fquug=!f?L#K78V<~+(sgSWy=;sK^%|M?I*h6^ z`PiVND$a$D`;DbHmEAU^A?e8$6scIl3K}Wp-yd~s99o60GAGN{ZI83+$PNdbww{cx zF~oRvS94djn5UM6lR4DeZWA(<#H$@ie^;-r3*Rv|#*mh62`mK<>Gb!Ri;jP&LM}B1 z9QH(gDxHp$qhUSC63E@#YnXg1#>Dw@V!xN9PPFil`uy}_?b2F4kl$?jp!wbT;h@vX zxZCrZf9)pd!-eajeDLU;%~sv}sLD1D5p8Y9i?1i!7A!_&25mXarcQXSe5E6*%K>p% zQV}1wb}2hL#Sw;}Q~gPG;vNWt1Vs($`JWU=#~xgKM^wCws9}A5pU094gy;gMv7e5O zpN3s(rAtCS>~pMl-ZW;-)I9`fEmvPmjnQVcT)Pz77vQol%=&9A|BSn?zN^E?)_ED2 zzYfl<&G^TD94aU7gYMbc;yC>0Cs*b4@Nn(^*kxm*TUy1B$uReEmSAKoHTrXEjsRzY zimibe16olY_mf%!YenJ0ALDvSe#0N$>1cfjqwzW#QOHY-l}ry*l`{ME@Tc?aso&h8 zhPy8Ej@=lqTY?7?f)-HqXtrP63nx>NYYn?K{6YU$9zCAQu9r)D9L4zaAX_yNj%NU{ zWFQ_*!XW02XPJC#k=AboMW`!p#fa6><7k%X-E*%$C^*=_@mq+WOk+uJ!gmb zYSZVg2EC)*m9{Kho_4e}-GK3|lACXq(t?GnDirqqRep;o)hfUBpvZfDg5i=xq?miF zZgaN3_&a)As}2J3d!N^rT3Wu0G_{LO{cL{8b(gLxaS-Qie+-Otr)ntie7Am~Z@r5| zcGjFN*12NK`zBc6O+Cky_SVALoJOn9-C@3wcfMeAnx)gC#{HUjf@!CCM+0|@8$I$k zwcaRcpzuxL*_8!_b%50L??bUuT|JMN-PxhjrJW)H$^^#4er<{*#=f)?_!A>kdmwo# zb$MCTE#^HTio|ie=Y_+sy^i;+iPzAFXYuiPQG2S{b06xtpV`mr|F(aoEiQXqhN+~r zy5?u`9`%z??Nl_7W>-37+ck`^jlsuxM!_|eiSTKpxdogw|+F( zOYzmEtXv-lxfB#cMR}Ch0Yks>}(Fjq{vEO!QV?Kye_-tJ$JX+1Bx`k3Hif>+)M~R4Hpb+iq@?U7RevjyJC>8Xug)q)Uf> zQW`{(@z$sV-RU5pIH~&vGUU)(o1hX+J*|-6NDi0R4dK;XqEDKyZBgaxykqv0Vg%;D z&aa!tWQ=p^M57@CAjm)f@EuHBkCiC^BBf|mh$f+?h9EeDWrAb?ey7xbI1t|xv49+Y zN)0PXBtZhxL!eBE8W4=sZS*0C?t~73b|X+~1ONa=%vu}J0brz_yo`5<5h|qOk{TL> z+}+6#L>DI$l;}3Z?sDC@{AwBn*l6VK4$`WVslc}3;$2U-#0s2{PNxrhlPn=Y8 zyX}Ol=)@%oNi8`?m?B|KjLe^5A?Rn^ma66UBGt%;*_-;#(r6LwE83Lu<9g`(pN9pr z4w(WZ{6=f-x47jT1>4x(InC#(w(ErUpP$B*C>=75-d$+-6S#$I5`S-XzJ$8xG8A`; ze&0!7ybPJrROj^E#{bj78O>i5Xp8#hNC`+~byJVl5KjeODWeWUjUqu6b;*~Dh>p6^e`zt;FI*cd0-qF?3N zf9xDzk73))bAI4GYD{ZS^+DSRF3eCg=&!Zh8w1T&Yh1*LPqyAT=JXZM#p!2ed0t({ z@bQg9T7>kgq^eD4RDnK{L{oe%m$UNagLgm!$Qex3rbBd;oEL#OHR~E zS|ajmy9gSlz=rsJZuqGkD6g(;z&ks7fDmEzc``dZo!m9iH)l+h`+x*D&m#<;)Hg19 zeeJqt>8CJhhNG#?JA99pdha2?eu&H)q;rDf{u4u=n_JX|2WW$;Bs4oT_CBW7}TSKHGZSqSUGzdTm{<*b?%#fa-XdH9p(TP+%fS=z#p>S!IG4*+=6{ z5ffFU$&MiQ>7?aBbAr{)$-=#vU0rIMB+iAT_3q#V6FUTK$7dxxp}+GD2!qO(_{rxI zAe*Qu*5trqwGjyhYQm@y4pIn0J0>tTX%5sySZRa(p*EX?e)968J?t(R@h~Wf2|83t z14`F}kT^m_*MH1tL{$B80K%%FAV72v!chxLVHJ&?$`nXHz!C?JlSeA#J4{to{f?S} zO!{uc-!BD$Rh?;QR+f+SBo+2yIT^2h&DSQo!C8q-k4W9x)9&rlV$GH|j{_lx zN`CmeH`dZT{c5~gaf`>f39HSzf=^LrHtULI%d!XILW}uEL4>{ni|p=I26G|zubsm> zxO}cCeNJVUg&f67DziOHo_=T7m9KamF)g zyo6lP3|Yeyu8J{yE~3nM|G`erbLzqOqw7hW8Kxtd(VdYTsgHk4Qn?r3xc9fOHr~~4 zs}9jWgq6puBh>>TuFtlw&!nL#37L z$es4d*z|>qtF&=W5?EVT<85N`q-YT3(0bJ)$@(t=zFeOzeCB^dn)TPnr|4Hh37W{+ zm!=c^pH>f}$Iiu-PdrC&O#mb8D}ozPIk^*3?Q2H2dX~b`qm^P`xMfnyY=)J@uZspT&VM zX%4DairNn&)5I)LQPq%1VSNkgO5U_V?Pf%oQl86qHKt-g+SK90+0zIt`y3R0PT@?V z*73W)=(@MdM>8xMVE;W(858 zXwX^$_(40QS%ckyEA)^qDVSF%Hl~d%&7AaLQ{xI&eq%)41k*Hbf8vQJ&U>GrFVEMr zyq8*4vsi^FP${Seg2^0EkSJRSrTbbSoJayDMFz1I0@VSh9OiiR8wOvKVF3B~G=yCo zM8YiEAAEoZFeU+XwIcjvOo2e-NF>0CcO)1bCeMoIj#y1Y{lmzG(=*B?OGJk#?j(ZT zgFt>VtO)H4-9QP31oo?*#04@kNb(kDGjLokL|!v|hKnUJQ6LO2lYuUix6fP*{bYdk z4o6f5PhHp&It4D~Zr>PIYAw#PvxxfF{oaB3^-hJBFvTbbZQi2DiihLP(uAW6jb$~LKsiK}0{^`=fxo5)FyT#k#kD*n*({q&CAF7@2JUbcX zvZ+>S@a+x9E(+XB@(&wBs=QH#F9ee|Mbo1lsJVZ=$h6$XZ7wxe@Ea+%Te+Ek7RLxe zXJFf*3t@{Libw2mW>>NB8b@lX*&*4!=Md!=dU`5alMP%P4!s=y)lGv$HgwRLlJSs> zQJ5^YCiED({85{^v1-W=OO4&_hOx8>QJUqvU%>>qW42Nw~5;e&FsIq!``cTPFutF_P32GH?0kn zY1U;6t4k+rAO4>U!0ukgeq?bZ^Ou8HRV@Bkn8;2WEclfo;0M89E0=x}P@Qt23t3tk z9)JAu#FO;H-7v%chaH_ciy5CC;dL2s)`qjA*f zWbwE>j7WG+d#4*||I&0;xwG%_$%lLw)_KEv*8)p$a-v-QZAjaUQ6ZV;V?~M@oH_N135mdV#FVQbvVlq$8cRgLrL>`g zmTWy(7_uL@pO(hN2Y4GitgP+Wf=1R@Tq%!O<*jnL9&Jr`P&ItXCC^~$Y^MD3CyX;i znwFLS>%&q}X^}3KKjxaXgGSQNNR>nl#3nJSJVHkR%*BmlSt!G(twm$@_lYAEYh=mAQuj{T861pp8lpvYaF%6fxI920(*P07O5?WT31F0ZUm#ZDu~F zhk{t%1OuAL;`^|$5F>u9jVdHd4ajDD@*rY-38VjZqQ)wrMUuo7BG}~dnXsRVP8QY9 zrO34itbiWG6j0grhS78x)f6NWtlslsgctK0-xv8qfb7M;PdgZ#IGmkn#dQdOixt&l zOq;`1omZYDCSSi_{l%|nT`6&^ar{L4RQ|V0xiO^Qty|`ccmI}(65%`efJo63GDRlJ zuNKdx^MQ30)fWcUc{S8@rMrih6;1>*X5jac{gub}j+L&=sZ zYhTCf4)GsO?t51jM=6v?9fwPxwl^sGiT_F>2a1NCewo~*!9rDDiEjOPSCi5vuV66G^ zNa!NLCJ!`o!qwy?P{fk{92Gy;HeO9bGnDX`2z{mG#L0O{T^>d+5BMuZi+QyQ59?dF z!leq62tYr`7DM-g^Fgou-=+>+1yn_@^ZIUn^?4gL28uMpEheViRx4{6H3jBR7O=UL zVG7A)zWYnYVE?k=OXIgM;_#~3JiKsTx!I16?Ih6D3=%pBRmif+*VQ3U*jD*%MJ)hi z`I2gS$vY5hEl)&;LF&Z>Q>;~shfYT6H4JcJ({JnW595At$kkfjvd&kf#P&?Sev{64 z+;-0(crjs6C%Wl0C0Knku8Lemscf)j2vUiN_fo4<_&iQOsYj1!hm3Q z0xGy*ELvZNdvenjY_~CF-Jm8Ql|0B@x5$`zcBqJfP&lqBXO+yP{YG67n zxJRfmY!saS zEN5!u5f;bP7bjo$7%5rYWiVR${maqw_k@J2llyb(YyOvJ3%c}9Lg){u6~!;V@LzOi9=5)v zzB1Pz%JW~Ih#dEN-Jf2wG91qyPQ8(r?(1~jmmGOM-Dvo=Q7+27_-_&YZNVwH$t)SQ zhOGvlDyh)hUr+Yy*06ryReHO=F<#{}ClvPPZ^(DsOKl(jZbp6lJYbd{Y85BZklWxVMinS^R_b7pzNUgtuexbcB%v*PxST&GE-oojy26Gwo%l_jxa|( z{*y79dsD$%)Yo{{7K9u=52G)KUWG~ajUHO+m3GoA(9~J%Dp`V8(Y(GgMsf#pqi>w8 z!TX%dtXprf>p!mZEw%b>?hQRuui@A@<;2L<&h35H<{*MRiA|NrAXL`c9To&05C9zd|v=@;H5Y8*HBo8!g#qnoMnonRXhI$W&3O@xIS3sW-< z3-fIAW`Ka04|~7-;)uR;cIW3<^Q7s%6m_0`+*+<89A654zxyDL`x$BO&#?Pl4>w_w zrnB7G+@%P8kODn^W+!s+M~JlC(4bL z#k=xAr``6z`gIei+Ft z&qDtYF|5pm(tuJvQcjC7RgYr+oBlbX;;erfqoiM_k~S~1Jh|amw|Ng{n~l4d71E8H zd2RAX((Cd)z`To*D>Af|AMRGRc#ww8ne5QsGc-CHh@blp&+yihykjlPf9loQ2F7Uj zd&WC&dtv2?4g&*0)3QcNmFM8mozFfM`riOmKXNIgL69B*h=j!7 zeJsIC(SCk))GZEf<`JJ1JAGL6e~yNtxBeS8XXv>;AHSH}^32Ma< z&xaHe70rYp7vA~%WaX?hvig5T(_ zJ#8}LkN+Ik8KERtrGpVF5nwb2mWm~#Lk$zVS1ZvR;~0D6mS~jTc4_DJkc_avNKv_d zy8aXMg!%DmV<5?+sUooyrBI==0SusH%x`E|dL@tQ*Tc>}2w)$~(J={T)cTzt7R0q* zFn##O)%Lra$1#T26K}uqE-eqfZ;SPMolyB+6|pOeOr0t)2@n7YR=1&t1XD;dSfb{2 zv6Mq4pa4KzY~l(UA}|6VU37Hn4DXyH)uE^SkzCIl5JiN?$5;=-jTZrPnVAFVAcaJL zKC)DDFd~v5b=p`yD87NIrjdxs4-p-7GWpN|Q`*lve?JS6N54uK%Ia^AG9M|>1;Hfp zcw^tHqM=BItV~TwRipY5kt^;oBhvud_BIrt{`<`+u1!}-pP#f;Sa)xjpXA;;j2vMf z4{(l53c3AgJ-HK@Smp2FEuV8AEl@-$7Lv3X08Z~$XuNX5Ls!;LU!f5*_wcxXd|`6% zDI22vptmA+R{XI3RQh+R@cjM@=p6=){Xg*_eNJVgd&OQOB;K%1VziRXd4t6ZG3S31 z>a@-0!}z8R<|^EF^=j2j6*CR($%;zv=Bwqd9c|1buVh`VTfW!r)r!{1MXJ~vJ=?n; zl?Ja;HqXe2(j|PE!eExDnW^~pud%j22G5=V*M2~s^dT5tv$p6kaxK#PsWp|I>R@Bz z{PyxC$4<#J^`|nz|DJK?0JsMy&uVVw0xl?##{BRms?%>E2GQ@ z5cl`jH|?BuG{MW$M&38e-`kSN9WIJ)#u{_wd4@))yM zl0d$wXzI-J-FLjd(`$GB-kR+aO|5HX-W*v%d=VWx%cDSOd-2eN*SH)M z!YFALYsBFHH53&hMYIbe5JWZB2KGhL%SQq?6+RB^KH1y+Bp-h+_qt-`!1&T9<%;in zd*O76(!Vr5H+zAJ`PNKV+6o&6=t`5fno3KA6b8$r1f!8j1O*W&ON-*Xg>$JQt1TUI zvcJMLYJa9iSZs@=E2Att#iV+QAssv>H5Rcc2ELUf{mYeS7R4bgoD&7}i(_PyBtWB( z#DpNxF~9)WEB-JE)LT46asaCXM%mqwAb*5mgX_VtIlT(r|3Ci6J?j9#BW_0o42tT5 za)J!#P=dmMV5kHg9V$W_lnf$FYhb)9GM2<8!3Mx0VCfyq5up!c>>_tW&QXI_o3l!> zqly6fShzr62{JQViw~-NDn9v6b`>}w!%O9xr}952)XwO5kW%?HeXYHCaYQSYOgH-I zzc3+qv-WcRZ=&_G^>VG^_(zL=I+N~?H{>Hlk(gwrU49l_Y9{ZLONN8e@P|SfwMxAh zwKO$&m96P|l{MHuR~wMo{=r?=E3atKQF8d(zV35#wD`Q-zL!yNsK^?>escZp#}^Hy zK(2SH6|W;nSZW&hV5M5Wot6}1GOORL-TmndzUiEGO{h`k7rzl7o(X$Amr29(Hrc1n>Q*nbdete^S;jR!cuF^s ztctJ_$@TKn4bgzIOCg0F-(ksgihoM@5h>sLbKTmoCvK*n78B&B9%_A*koCbc#wLSN zn@?^n<%#>qo7Rz}+|{gvYt1y}{JBi;D6=AU_RdbPGiI)@y@f}C#YYF(0dq*XMFA8v z98b3=?(3rbYins)>B6^R@1eQ|2AA=Pse7kR8`rxy~OVxj`b<> z(%3uD1;j7Xkl4l_kG7301v(O=4(h1$+H=qUup8xMr_vK?U+_kZ z-dZ8GQYIFeu0_cHvc;mE68%%B4Hgm0qzqYPr%}@Q=@ZXc6GsDMhaxMZI0^ANuIjc7 z7$HRJvA<($@HDkFi2)!aMC}yrg<(=2@{5FlB0;1WWsJcjGEh^5_>B($^oJI+ zjE$v)4RLV*bZn%7t_CQ64Rd5DFGejG02h34swfQT>4ML~!t&ocKymO8kR~zsiWaG? zRoGmUUwE7y?RUvyq|e#~vW7++SISyFP@SKit{wioGq+IoroaYFcmxQLZR zr`%DbAy6)@*r(z9U*`?0qfO!5m9MgrZ?vS)gh^}Y!%Qv5+}`_+GP6o!>Y1+v=zOI) z-8}mEQsDV8t6h_;%RX$$s0lPrV=cP=y1coR4;ts)XZy#Il<;+$EGn<-==+WG4Q=87_!*$s7Pj{ zQr3W8J951hHqo;=P4{$!?O?as5_?`PNuNkqCBP;^u{V|K^-W~JglcqG_ahXG*(fTUU$$D{4CYE>^3e#Zx^(%6YR?4#Ap@qX=#J9 z?L6Z?zzWWLGuXvnMz%n=>)=B;i1wouAaMf%a}%on_%hy{$1<>0QzENCVxdAR1IY^? z7j)8=iE?Kmbo~!v`rC^WmpRJ@`pq4$9(Y zGn7k2=3RyJ?w&gW!S=T!zHJScvu>WREwPSmg`7XpKJyd6hyK2Dm`}A5N>GK@Sg{Hd zyP$Jp>lVll8d}paNxQRxB4Ahm2>C)j%+C{$sH=q}@xLcsv?=&(t&9z!v;-%JL&(Hz zNay9{xyR8ql+R#XdJW<*tzvC-9J9UVB`tx`AuJT824@>%WN*)(hmZV@f&xqcI_nz!BsShmuBsTBn z3EuI@exTcS*LLW*&REp_E4=opgUfZI{peTL`Q7>cxwu(>R3gS;k^Q=KvCkxjPyHHe z@GWsM`Ee zbV^%F0nx&w2Zr;aOThCIH!|s!pyfUEnn}0uvAkAFHt^OLKuGso%rjMG$M5;fRf1aP zP6F}s;FZRoRYnCBlw&NawLc*qc!oMiDpZtvU1VrzsA$NHj8MP{ilTzZD}=9|H~&n# zIbZsyT+?*}<=%5i(%Sx)3a6Q!*dV!=^fiA^BoCitroEQR2q#-p$#Xv>5QyP75nXLa zq!vV4-me6JoP&jxg9XQeVfn#=U;sEGEb`!aSa5YBB)<|mx_|0g3k(p15Denhhg(N4CoTFJZnSgQ}$N*ZMxItM(^dTM6T;SWl zJYaQgIL0ZQ*w`)-)#yP85Qv2-?Q1Q&6j<@`WpH~>|DB69xt`dO^M&!&%=ChA-P!oA zrTf$g;{ZAOR$u>TOm+X)bucV-7Kb(sa?DjiL!+jTFnn08MLiy_B2tX- z`?aZfhb9GR`_Rkd9ixyeLbGlmW^d#H#N`q|c0HN1aNCZQ&ina;apJA`qqA7^*7(sK z8SDWYT(Y8HVn-xdR7M6rG7ZdYD#NDKG`lrydEf%pKRviJ>&f4a$&qF)FE(-bC+tdj zp8ff^PxxB^;5TpN+tJ}=F$rY&eCBa$yASaE4cDs}ThUJfh6J%uN#hCZ*>+K0juN)zfj zZ>t1F#TFMzjz7UP69l-&StURuYCL$EGB(7Cl4xp3NJs#GuDqP9%G(b` zmW%)N9Iq%7mc^|<6FUyjoR7=tN8nF(V9=)%^7fBkkI()1;;KWLkZ@%jsiB`^1!G5! zV}dXuOUP&fw20BbS^zbf|9FZ3Klre?NhA`q2Oj}6?9%{@&7q7CXrgF61^|jiG)nWt zyde!OfFnYoNe&5FNj(uO_LU<+v)V_3Hs0+FZ1!;UC=)dG$WP^?8z^29!KiegYS^Bd ze#F1PDiJI?GIKi>*VszCm+f`e+m<(SEKi@VyJzCIFSpG9?k_cTe~r>#)U2E2A?X63 zn=Vi=cBzdtZNDoKN=P!z)|p=ukMMTho9!&)@bw*zk_-I&V&VIN)Ysa{E)*ky$3Bux z{)Tp#M8Enjf9&JShk=h&9up)z=5vGe%s(S2&3*S6Ix~(R7O(j2TRlo?>QXY+dG$Bv7iT_hq1T3Wnnb?>CBn^am)j@xc6CYOTQM`V$vLuqoE+o-rLk4T){Rklj;uZ zxR5}4Sbd~h=Ek=`=H&{vR+3MP6w%?e-sj&QPM<1zi%WE94R0%TeLKQXPNu7GgYNdL z+P)oPh%emAPO`mug|VHLE%e;Kwfa6kdpFK9sfx3cH}#X!7FOBPY~NN3Rn(OH(vzD6 zgFghuA}hIzT&g)N=O5u(VOutzoq5Q7=<%>z*x7sLBJ@%?s}G(pJKQ?dX?s91X&9%^ z1CC&5B9yW`X{F@j8KX@BKq{TMawgMl6yr#G8$`Ph$Q3e(oCiq}?Ls0(y+kQMT&F+@ z_^@pluq#={;5+ekheqX~tlP1UseLydXHu1yfqmzP7=GR(^B6BNpAAx-mD_7#@r4F} zBbB~Q*#+P^&Y^3{fWfR9ie*eH)!*+4hEk79cg8o`iC7RPfg*L~#zJi%JAgXL{$? zHwyS~?7hMO8U5F8VNNQ8sCE#DLbvEWJw!tbfz6uYfDdSHV*?-?7=T!ySdb^8HiQA` zu#ADoIRg|npr9mj%_uHEm>F@LmX_b3F^EVO6<|Wtl>>nfyT*2*hoMUEB+d56LDL5B zHkV#zapr5vQ%JCc2t-d457})i@Iw#9crO(AEaF3yW^}7)X7mv~m5!X`h~L11Y?2Lk z*t8GM(DpEX)=*Vvt-v(9ciXLVCv|*+zQekuhOKhT2djsT+=0*N%M&LZXBM~}_Fw*q zCg7Cg#>ugv2QMqXZO2dH$?Z{6A$;Fgk?_p)ksZdHJI2Z1kZ}!RJ%ea!a+_aU zm?g(}Zu&7|qOSiKO%}Wk9eRhAR9<{+y(A+JN{s?AIxh#7uzh_G)?TqDlAo}L`vs6C%PRw6o!J1&r}WKxGIAkMi<$2Hm z{}K(0|K|b}PT1eykjJYgh|>cWkx=+DCVW6T48;0y@+}oPw!aC;?>gHGo}19 zT6*0rchn4h)7kjU!QjwSwuC2k6qeA`!3?SRIiT zwA9tr!C_lu05g2RMkt~mhskRp6ud1f&=5G48fqIh05K9ry!-Ofbu9@%uOeImi!M?UnxcywOM$FU8azku2!=R3 zH$2acoc6Ei*+Y@xg4YEvVa{|0GDbti!n~{DYy&NZ*zI=lCkMD@hufZLh>E;&YvbF@ zQS-Y3uP29{rPpNee;vgexm5sn6vK>0h2OB?5Xgcf~ONqa`;y{<+|IodZ1soS^GAWr+WwUrh(rdjwGWD?2( z(@fp3brI?ddcKFkPv=EU6h*)8V_w>>V~7s7qJ$|;>eEBoWIkhh0eFA1d#A=wp%Q1^ z9~jk(kQ;bc=y`B)a1Jyjx>(5V+U`yI9$1L`6nESYWL9=xtuUYFK& z&NRv`{T^-9uFQBiyB-_CxPSUF@>82nomGJ_p??83C;%dO%@M&~l!l=nY{JnXhmzJG4t2E#s4UmF33?b?9f*{Xsb5{l z_xGhmF3rkgnfN}jQtw#OTu;qzU^Z8=c;OV)s&1BTB^0Xg12H2brwn7GV1QYJ27wYF zNzPO=Dy;Vm05vW;MZUyp;kdj+S?<+F0be4Q)~55PhBEQR6C;v$-3xJ_O(9V~xSg#Frn;J@z2pI~F{4SSIZL!-GsuTdvo{=DsUus>k{Bkc6P9 zxKeR+W%kSD{?W<5{HT;5Xn{of)@m1iBsVBHX;BK|HlZR#6d&r2`VI>fxVRGN}Ih;X+;Am2jgsEk;V3Fz~f%Fla*oW@x{gGj)LW21!z)>I>@^gcC2OW?t~g8t=l znoLRii7_EzHZbwD-g_awIVoGVSkE1r{{E3*R8&CMfR=Ne=p=!$WSJ5tLtAV3PH027mF@#dkYM80DMRI_17)iCmDcC*>AG|~J_gGR8Vudg>f zZY{Fy|JHaA6F4hSr8c14cJ;G5FrWIZHy}_h6dchtGoV3QgPTVXvOTZ+i^hPSJjJby znBT+XFv%h>$=yxXm3(6TVrTuM>PeephgF5C`h1r0lwOL}D1q(cw~H%__-eB+B`{*w z>SiNrysa@*Ib_YgU*_UZ!bH1&%a*T>Qxc;B^D5DJ!t9u|_O`i}#A%y+t{!igbjeTU zw+`|@#8BJNMsPl}_&&61i5-aE5vM$V7QG(X^IfsUEfUgioqsm;Rvml)llBo};QjQ3 z?NE$FQo{Z~j@522wXMea;CSw1b^FVp!I)>}ROK2X-b z*K^uaskAe(p2zk2tEsA6zq==o^;2JnFbK7xcX4_61zmn{ziH*wc0A z<42t@bHOiayzWy?`bWRx)}CT$?`FJLx!+>xlU7Fma8PdCY+;vCIWQ<&ud1=+(=Tz; ziFtilWAln)$g&LYu5!+HOE!agkZ))FrmIS7ruez|cqPnRuqJJ5zv6_P6bXdDQ~n_V zI_01l&I<9MIQ%RbA^@nO!7)Q<4^|%{7)4TBsyo03!oCTL4x` zI2N2u%n~?ft*e^&x;LR<5r&sB;D*6Bk^OS`Vu~gA=EFSBB13iz&AlLvW`0uPkYx}c zS~;z#MhP`>5H$_}kq;ltc_pvUPC$ZL-GCm2ods9mTI=a^S|U#brj4q)ZmD7wv^-y( zWn%ZvV%J2sjwK4}(kfbAQwv?Vxa{Y58Bn9r{6jbTM(_#^YKn7=!~@Uq8yB>B6ARWt zaBOu*dqWW|G-5%}3LjwzkJN>*+NDQDm_8u1x(MT(qf=#|T8=TW5;%-558gwwf|3KU zjP%Dx)M3FnITGlmx^NI(DIh@TEGRO}dB;rd`|lK| zqFfC_4tp;Ic49wNuNfh96Sm)%(AxX<&r-b2gKQ5MFuC5q{LqZ$2cDF;Y)%F0T`IHdnZto}P7DpF&@-olmB>W+mI(XBmeY8?og}>#79j9h4c$U%nl# zeB7!wtFKoGEt*IRj=>5YisE;<$TZh*Fq!Lou^988NJ_@I+O_W!qdn55Qrwj#2@F2Y z?cd)H%kemFKZ!hZ0uyh=ju+#L{2xtU9Ta8z{k@bR(p?hk(%mWDp>%gQ(j|?sbV^Eh zcf*1pOPA6uDJ?Di-p}`)AAc;v470PdbD!%v=X|R9Z_?z2!(H}9mhwgBP>|7nZ>kFs zd7E*Ruag%WddltS#F17@o%bKLHW$CkIR4K??0>jCUW44;e@o?4T(NWS?%`b0#pL62 zAM&F=bz+(9`{(z(erwx}7~N&fwiMLr|0q$9xwJ^O4lBKL{%Nc2IbpV{ERd_{(tCd* zTD{b)#)sYZK}3Rk2(DzXJ0DLZh@6+cE`8uk_yd0XEr2>F4{&qOgS))%0v)*uvM`xU zQl5T$3KhJ!N)*h`U{)1R*)j0An=*bHa42$DBjB?4_+&PdbAOD~yFA$Obzx%#C?oz~ z+QMYYOxxDNPk}Wl0*VmRf-lmh$^(ArT}PvH!=LJ1t$(4k9l8YQR1z*^@@piRbWK)O zk(0h!^}9CUi$)kGk&*_sNAt@gmZ4BM$$#wx8Y$O27-*%%a7Zl(BnYJ?q_q&xlF)D^ zNC?rSae+UOB@kXGC88xFg)x-7ok-=pTktd@0q%UgUm3!drDY+Hb1siV2j^d#*O{X6 z;@{6aFS1*#vd;5)^Ye$@_We|DVzGmwRYg})gGf1KUqc01nR%>JAru{pOR;kwm`2=X zD$Fwy30N3;OS2vr91dp5u+rge>!a!HgV!IT3EeqaF57w2KdjjhQ}X_@k&QpTj}qMgjy&Ai$m;=%@h3 z;5T=G*#Ue3l}uEUKxL7FA;7-^#@s-$fW$4K@+8062*5Zv+EWzWbq7e$U}`iF@+%n$ z>1JyJ6cq3ed69pW&Q`9g;*LJkPQ6}cw|hz&d$O<|>l3i-ZC2RF>;N0D)(F9m80PQ^ zO#`f7;sgEFI0}3Bi0`N3RQ)l+!dt7W-V`Vd|L`g+H5fe6xz4HUeDoTQx5|6aNu@OE zge8Ab+oIS1py()X(aE_mQHrc>vgG@86lH=?LzAua@deBhNH+UGKBcw)!j`mhq&oCK zm3jXs=qTOwx?d(Mwt;2&*Au$dXV(1lV~^XbCDYX-Vif(2kYcZ>2)-3|ND#SXQEo_nf^^nkopCG|QALQqE>{&e1AeR?f zE%^C1=zG<^{vf)vs?Lm}-_11pi#PZUScN6@JBFd=X1Pc9M$h&57(Yzw-^v<~{q`}% z`t6`xP#e-i+j>W<`@vULHXA34LKX)q34GE@0c4YC2#%*ln8N#V6;25H7nFj<(46^_ z`}-#K+KxTtQ>=~UPrP!M6MW9SH>}j;p}G#+0MIcoJ=vlyjwo;u z64zzqp_UX)<%l?7+|@xx94$#4H4qoFbTk!*Jo1kaiBz198yH1Fo=>d`#aBKb^Bs_F}met}PS;b2~o+_O7-4m^nUKjaYoBJN|a(5^G?A%Jb zx2M26S!5DCAy|8&Q@)FzaQDP;t?S9j3JZ$I5%%r@XX+4&c zf}0*O=82~j2ZL&SDRTk$<*0m@I9v*vuk%8s@z|Iq3!A8nj=DO;_CwzwYfmS1POx+D z`{yRT#SigfPLxl0W8>E)Eqn=C$wLe+b~~w7O=}*CW+yG*J9-s-^z@Fd#2=!97}q`` z&hq&5Jdc&E`*ap7#JwV!@e=G1nt-`*lA7D}9 zV`b^J#CzLDCAcn>W_-84+2exgU@UTNCv-hED&c$dL`?20y4z^m(9qp!ci8rdcDw*`!r?!Kj1K25znAVGi@#7Q5VwQ+M3GpRh=1`4HH>`1Rzd?Y@C^ zzSi5o4#kVW(}v0q-BHN*_wC>L!RpnY(mgqKA0Izl7O?LXtm+%N`26`u717RH`uhjw z`XV4T9NVBsBgU`nvc9*y_{%Q(*j0O&u-@Aga7S2s7R-9j{l?x}k8xH?E&|DCy8?Hx zHHsHrz(e2`nx$4XUEzYkE=C?5SI(r^8;>T1(?~bM1wjN^TUk>>xa5J!6%!AkpfZ#J0s0RI`E^drFbM)7uBwbUA+JaJ z3{G*bJTJz$WNmd-;c(Ne)!M=FA3Kb$LGNc)_FhsohGf$2vtK9NdB2x;l@{OzRfJY* zKcQ+CJF|MOQT&-qiIw%lCavaU`A7wdgJ4TjFg5{3q!BVH{Ik#)?iFVW9GjRwWx>VA22If}qi=vHm+#n;HDdP7=RNI~*=? z6as1d`B!hEsbm5%>sgf5%~rFrKKQurm(=Z!oiz)s?G5!R*JuowEmB}~$!0_JcT3En zTYHa=tM2vBr}xYz4(D2ySaB&6^g(sXl&|r!_Tr6SCU-8{zB@Y32?U+hwfhJ9eRA@C zSgs*OGyP#;N`xg)-rV-dc5g?4>V&N(kNjVQ!}$2^Q1|)pGq(r}TlOs) zjpjg>)o)9;9auBf*mBpk|5WEh%;qIvPg9iVAty%Uneg|Mx6d{G;Gs&z*eOhA!Rg0) zF`?V)3+)nKzOt^{fS;Zp;#`jV>p8Y3{2Gl6cGizq2R??zp-w&B`doi)b!_Cc+E>2e z4uURa&R9NNWV26|p7xDA&>Z>6NolNQe0w?V=v^i?KHx3Pb;`^1--+@MB!YYSc-nnB z!aHXZ=jG*2Cr(4SuurtApfzxxfXqX%wq|jXcaD!bBPydWN@|YSF<%|kRAgobL^9^; zlMn7fUH5Cw48VvrN1c`S(j0J*cyh5TMTq2y12BdY(K;A?gE9q)pMf2q@&pG+L{S71 z(wcMBuTgPnB^}-ZjC1PX(Emga6_p%e?0p|ermJLt*n+pknq4pB?+CPhPt>{eT(m?u zTG-H0_!QqInS6&!1U;<%zGzY4!RHlfNR8Twg9@Ay&F%r|%%S$>hL)ftT)hmWuu2(8 z8IYFdJPyQX>R18=tZAZ=eDm|e)D5`!#O=wj<6ix}FV%owtYcVQeo2l0-+#o)FEm8> zuimY$fA53q0{faq1UfZSsVxk!r7ADZTYXt`UWDm)ZmQZ6$f)KtB&ubm_CGhLg<_Zr z*ixk^mS)M!YR4pHFiBNGD9uFMy1$X`X@GA4AcJr>wag3J#5Ig>hT&-if5nx@QK^B6 zV@DNh(ib42h|`;Y3DJzIigL>>Au=x>UmQ+9(mDDX)9odgqy~{Oip|t~mrbX_T|Q#e0@{df;f|Z0go@KK+X8BO5<-A+T zIymP0VDAd-`sqi_EiqN>)br6u&DKR*uHJB#UXw7N%svb@n|>iIb`U2wIni&?OXmYI zK@YT9%RtC-rIg*)FDzeE@)w}wf0Pcn>=UkiYmIe{P36!+;oMWBlUtX*{u+L_u9o?J zPUs%$aP@R^djD`1sj%*N1^F}HLqF=kjC}< z=uJWZ#WV)&MQkRASiiBqwk2C+`sMK@!h_3XrTy;(_Pw3w&O7YySCSkxuS14%+FZKp zI~r!Aw>zv~{ym;6|2iMlhIQI~o{(`y=$!CUo2C3}Q9t=(p1PdFpPfcLi!Uj^Qt7o- zsO0tJC24yLIIEouCE09&i90D+8}79m(@9}0{j{-EGYEyC9`LR=pZ zu8=^%mT{a!iJAx?LUG*ZBng7FE}R))-wTi^>W4_epkTaiViO!J(^3u-$m!{WB~Jm_=n#Sg9a{W>n3J6vaG9oUWwsW=2q zM5lE>f3yA=lATm=j$eZ^9sIpdU6(mcK9m99)Uk*NDcbK#J_!g#jZl+NCb5syBUlzC z9E6D&>b9vGrf3<*Ei3ccC=4-4OI1r69Q_Ujh%Tkq_N|Jo#5SV^iQ*8zvnGEIac1^HX+R} z+Fq;Nh%59-&3oZveIL1NpL1i7@YK}#G&{Nb)pl1%KKIH%jbZ^MK~A0fhYEL+1XoTt z9_vk4O{OhV&8bM6*RC+GqX)J~s_3H&T!)W6=z)EoY{J^VHNL^On0)GJ-d}9o*+jAF z^z`ar9Vzd&=yV6Jk{U9KWv0c+1hLFw%q;&FZq87w^>e-CM{Ae+194#>V%W-DNqU6C zf;=-cdj{sOPfr=Sw`J=ou(YfoIg#RbxXGAQa{l#&x|2oK*DD%SH)Ds>N+o(A{xhmAjwJ6Ot4(ExqD;Moia zlX)>sDDhLFB`Io^!x4Xa`JQtTVG_*@&xg@QX`6uX`D7U_6V$Uztr?Jv;;^TRIzNSO z%~04x%{hkyZyA1dWXkKw#XXEYVq*?ae?cYFS&utgyamvD`<%)AAQ>26_qT|P!{_?& z8>tc$Y&%R+BwqO+sR*ro2s}awfCb<}=>O-HmfNF!_s3Q*N$Zo9h$VQ(8i9kDEx*Fu z^TjTy)w2q7Li@k%=aDr zs>8j|^>2~&x$DgOC)GGF)DHoQtDh{TEBnLXwM)YtuVUuOBmr>ycbDX57wB8emH^*m zbUjK-@F>f8Az+(@W{ZIvgGimM20}qbh9HK&P^}{Y_#c3L<05VlW;h^|XUm2=6}48r znkTf4Fs6@Y!ih9(A=61wsOrU;8kgXmuTkP?$7!7+zK*ctDd-~km>0VxIQ~`~ci#Bg zz-7f=s_Ry+EYRo|(%j?^Y!ST+r+In&5wOCD#^5*vYo?%(eet2cg+~P`VY#NU`?-JK zfcb4)v|#Ypi8W&#wVYzGe`dv}ex^)Dj}>e=xY3xsAfhh_p(!#xG?MYwQrTKqYTx|c47w_71NZfCf)yUJRjR6g1~NjjP$?f3X6fu|!E z|7FJ8oZmjLAq!v05dS1A+$A;Y%WORC20G*I&i%#-xY`{p77Z{7JchEhuC(PIu=Rk} zLMpUZ4-$5<0}!h48&ul8i#GBajTq1LW^#JZHtxSa{!P08SgMv6J5(8tZ_NG9o-TKx z^yJLD%attTFHd46H;prQA=RzSyP{rLc^9jEYymP3=uwp4N zVu=u~i$<677H}%*cMPA%7NZfL-3h?Kb&rISSVWlN-~zUs%}(Uz42Np(vlxOaON+sX z;U44$k02x(YG6F(%7+%G0((}#jt#(}HMOLFMv@dWd`rAmYY^NqI~1SZ>k8rj@NM(; zm$qCZ*g2BDONFcJ(ZRV!@BV!Jn%^Zwvyu%5?ZlXVY9?!w8Z}`%CN2~~O$z~63wXCV z;7+@s0rg;lFjmSZs@G_<2^dlMYui|yh?tN1!dNy=YTxs(1n4~|k-LWU-%C?LO+%{f+>iTT+YY@hNp(owOYE#0>9Nf`>68) z20^fbG{K^Ea5Xd<4H}JHj_yYeDrfrh7GND#%2NT9MAbO}1`0t=fhbKDhnl~ZM0_tL z?fLEhxB%%joqAL@qO#M;>P|gwU$djsyRk04iTS6le;FywTOJK2q1s-vsPpClihH4+ z(3s2LtJwX&X$=D)LH`myeePVzemK~SjbqN2ZPFEBq;>--64l5SAv{uiUfqq`T$O#F z-!1m=+)H+kFn=a?AH_~ncR-Om3>sqy9Z?6Nt1%+SZ$*FIHt_nfrnI5B(3`EA)so=y z{^`2@6YAMSxuHSVEzioy-N)zjLSKt{@0+WAx{psf%kf)x-WF})6k#ryAcgtXw{FJ+ z>pmzerE9&MWuk9;Uw#Z59=UYe$8u*=&Cx$EeSb*D-nf6pb&y?}q0zeh!AundX6}Bz zVvjtyBOh>fef+&m_4Ixso^_*_^u}fQ_e7Q%PNV_0LrW5*{DCh0&K-FAV+<{qQ~v!*WkOnFZak-c3zkB&!;s_R6SH_{L62|9M+%pG6$;D z=THNCeE!6!u5Enq-=2NRb~M&uD-mGd2;voI(waa?%iBW zvSv8WXWJ}lRR;V%HW!VA992~r{Zdpe>ckR-0+cw1%SOj#qNPUGYMNx6NV;&W*DA)r zu3!R5aRt&)6t#`p?@ip9_tPxqg>boVPls~JU`9ak^FNRDzH#XAINulqzU$`UWo)b#U7_|27 zrns&%*CGDL7Ly5+`y;|2R?jA*rk0DlApN|+t$E>e!?qMV`)=zZ%-_j0f>6*7N-`ID z<*1>$JdiVr`}^(Rmx9W_G-@Z?{bT)m4B`Qi4BLxDRoijr%Or>8pOmoHbq)O{Prfl* zF58rjT(Fr;Eu0w%UOQM{L2n!y^B${*cyzayuuRRxaZu#Lqx3TRsL2T9z_?%`NjXz- zo=gU9+@xSk4kXp+EX^+&vAD=;GGOyp;X(gNQm7C?fIv`MQwtX%*fx0wosqC#Z~PPW zA0FB$3L5fPhFAqO`J*aa+^@##kuzQn;YUGnekCMJ;wk1A;w{%aqe;8hgTL2}In1>u ze3Y5#nSJkE(%Ot8&)@GB1=-G@8atm2hS4n0HB=J=ISZsCEC7gau4 zySH5T-mk0?_o7^@-Okk2<~;crGF>x_+;)Ow-+YNe6GeV2G8pXD2urF-A7Fp+YJcQ^ zkCt=S4=*xF&0agcpT0cYxf=w8*>x{diRcOH(z`E{+nXwVpftbDXl*Fg5V68nT>i{Fc~vlJBHvq36-bd8+Ez z!%&&>vD)|Qwl4=+-Y(E=|K!Xh=w)>%o1eO^=k42Njoqk^34rDy*6MM|-T$mdYnFs- zCA;%{$I)p?mk-QE7I#r7AhP(8ao2a|;kzYPrlg|y;#~p5Pz2L}^d@a9qgUVXJVIA- z23{~)nKWnRZFCd~4c4ZA>f!^|e%*`DA7S~{r$aW;1>6E&A$O252bzcJ^dL754zeQ{cCe%Ofv8d4O4IAqs-$$Mr(=O*Z$SjKn4B7Y7Qo)Dk{xbwK5-7%*FZYGVNd)K2Kh8l+LGIrO@BvP$X z=#ojoHi;+3wdeMhy3DLnvDiH8o^#gy!m{6v=tOgWJjd@vI=W>`>f)(({}5>NyxhA0 z$c4Y(hWIhecOAlbglY``dC6tplHSiPwe)G}IE~CC#Gl=<#GU@C>JpxMvbFWX$DG^a zs&%{8H&rwXLMmN*M zYYv|;{GCCK45f*(DNR+kCH}$|g4epAYbK2w#aYS3jTC$T^s~r0FH5h*A5WXq0>$P1H6<#5@!xAF%db{V)&`w z(|`IHQ)+so;c{h6PVB+JF=Dq4_N)8m1ar-(*f2iG@#5|!mVSsx?4_Z#$?^IJkG6WX zkQmj7VUjSfIl2ykGG5q6#!5tRc_<*9;68r~P+RU1rWdh|7x#?zr7)~=-uRZL3SRV3 zWohm@%)yOxt;P90ZoeMv>R1L=L@-K4kN6n1$We`)-XX_-Fx|G|ygX^vyYCh)=z~N- zLLfM5b1Y*?j^ONIq)(FC)T!cl86-WDwoFuTydcw)Hh7z)BO#w*UbeKH z#xwV4FyGjPpTn2+XEpb8gPc+Lub|{Z?xzk1+4+0Tx1~N;4K-VTeqY->f3;)#Az^j} z=t>{yw?2-q_rwMsewu0Xhba`7Qr56`uAMx^R2F#1SY5ilDi>Zhnp*zS0c0><1^I6O zEIF7sLjkAHZKmT3uo?6R4={e_U`I2)E zN$f4=VO^e%Af>dDZ;{_M4_VS;%b z1;UrDEWy?>IX1rMzuU4}=}BOD(^NahsZkAeG3~HmuufgGA2&Ykt`4=jh|>j0L~zdx#DZwCYDQJ z(Fwf@$dhgq4i<=pr%FR)J8H^D?RgZ{fZbLUX{IJGyqq(0rCLT>MM3j7pB6;&2SD*7 zvj8aLXIBHtBNtrb*|HVdW0lcZVrNJl? z6z->L zVRF(jmZFw2ScuvuG#@7!0{I}Rz^zf8zfB!GGGsPyX-ub;mh(P~O{}f^Mx!FZ2KzIk!J57E zThjrerUJxIweo_#^Z5wKx`wX?+Ldgfcq!`E+%Ya=5xoc@BJYhMDWU)~c&$q_e!{+|75Z6t$i|6YZf|Mqov zj~U-7Z{EWh_HFt~y0NIbr5?vIzSbNsi=Bw5`|T?VSkLF{y7C?Z^{}B_vVfhBKkG$< zZtY=<%y0clHB&jcE6oYflnA$V<^A)hKefv5XjQs4bZV>C`1n|z-zcH#tXpYjr#~cb zJbe*MJAd-^j7F|lJDPkF`(5Lbww7&4j!fRdv4o~E%^{U4CCJ6z8vl8#ZOmVkRwzwr zq4xPPJ+M<_A;LZ;v#FKI(Wzd3UKRp8CR72jBSH?Q38 z!+B$jXVWoOCBht0da0s;<9@NW)kk*J@omDUO5k>l2FpdP>;TD4E;b2zAtEQOg`y?i zJXz2}W}&W?|J`2;MO=$xQfNOp7?4Mk(pdxj48frAA1vT%iADo+HB}-81H0KSNDb&H zacF)pSL%%vxuos86UQaOp>UF=ZmW`P=^GE27~eN z)@7xKe+;9Air($u(~iu5ia{`ZF>ys{Tf?LT%c9TIV(cqwe-dj5bgLg(`)mX0?v!WQO1U~F;?M=bVu-3EDnv3YQ zMXzlF*~6=dc~-}d`!=&W!gVwHRdJUC*FBWZLm8cO43(Ocg#4RCuM-20r%L(L+t_;e z8l8745hEn-kKmYmT`o>NBKpP5>>q-josx}mR#P@^zh2DJ6Q^Tu$2p|TsS`(P3Qb(d zS8pP_M`e_tV8zI)c%&exocRw_jCUAUHBKl9wRgP0r#cPxbv#~G^IN!1{R$G76IIwH zBAaoa_WJworD zk+$Vg6?u^(@2mKDf0g8L%y%@1WDaO*gyIl*Drs0Sqm0)zC=<%%7YgDEU&QA05Y;YH zOCp^3j1{QM+BC~b^uUjqO&cHjGr~?)X!h3RTqXMyCn*(=dtXKZ@YDbqE%=_*wCLqF zxpUe$r8^H4bssK&`!ok%l5#~|RVu8LJQNv^aD=Iqu)OH2MDii|FYanzE`GaT$ zSc5|8Yrs;VR@7#oYpYJ5T!_6dMM4K%V+qEc8g4!<+LsS8<$$1gpwZf&`joINAnDzvyJ^J4~ymoOlsp-@o&iWbwj(EA$q(~Dw3(ljPmH;Z*2|Fv=5W! zvZtm3&rg1aU;LgLwlFy=v&2)|j}u47a0b`(j3%rM%peWZQ!^U>3POLXb+rw2QHmkp`OO+n?yU3D!MYJ+>wMiDmp z2jZ!Kfsa$J9hF6>^w=-&+=kM0ygu2Q!i)$aD%BdbcsvU+)W=)47k!6$$mzKP7D^Y( z(e;IeS~F|rIC>fdZdnZPd};lWusC4+wNHN6eftylob{10%v0kg4>wuIT^!SHQCaFi z46}=&Sr0FfhYcSwm-c?g4Gi46#AogOJM2s_Tb{s*lp3(B$&J0lobC>rt{}!WZ=DCz z;1(d#6jTDw{+q&e)X`{hLFz==`CyzBX{zntj(l0Mm4#O)tI#@b{p0lvCzFY9*}p4E zovPhzI0|65>f9!X48W)W#Yq}#-0T5B1w{pbu&paKkH869|1KS_3}QeBGZhx1hkr(e z0Ip?HfVf8sngIottXEVZWUej4S`|tg>cXT>1XL=HW^^v{{+-2!Id1yx8{sA$7;#;% zTE2^~+Ya#Pw*e1H&f6O)e$Du|bVzEdc%+;}aWR~DT->;L)PQ!Pm;@mt3PC~|0VD>J zd=Ci@XNZ_3@q|+J=s*#B#LE_$u+XB^*%&VqD_EWM%;LTnB=?s3*WKzE)AgqGuL?Lu za4@0U8l)97L{W1iK&2$syz)ju`kAq4IdRfKOX$GJx;naW+J0rxnT)&$f~nsl^S+x$UE^cwDAGO%UJz z?qNGYk0yOfwRSydf2m-nv6!RpqT5(71gYGjZFNj$G<0*`L{!jWx=s(`>OI#ePawn& zDADg7I%Df#mA|C>I1{Zf3T8-x*yCw&_~O=huCCudh}BtQNBcdFY&egimZ269ks*9i zE-WT>pe&MxI)c?=B|0s6mkiY_>G_QOTK!*KoCF(gUvMb{x_i2v!c}7FSci)%s_1Xm zQBJ;+Pd%@kA4>*a1qS@Ba=xDFX=5AOyC}wDf%o|cdb6=pA4T$DS9~cKDt67`o*<5N zsa?N?T2r~~DOS7=33kiANyHks-^u?tb`;aapRho`Fz{?}$=^FwK`N47mRC*nBxyKZ zV$!2`x1^ZVhTSC^_)BXayhN$iZRTeCm# zNJC#RJAT!rm69Y!R0?H${n0My8AYJIS?|@?g6t0=P1Q{Q_+MITa~9V#d4;=tKI!s~ z#kEWj#Z8$`m)!f(C7z?3_54+`YU$tx(o}%GI3kIKyo9-%BM;o{?;kD(doU!bc!auK z66!j`vLvo2kcP00*T3}_zRR&!1DRaL0b_(3s#WGLCIW&rp zbcsL?Q#k36qO{+K>3lV=_>L%_Fgx(+ddcg7mgMae)uVlb7vHf*I}6SQU&4CySLjHU zPc#By2$w_L+VH)%aR%&Ms5&XKlXC3%?wf9b{`|oyc?CLFf z)oq}im+LY`_sPHM=mw#S6Na%jqkaWe7%@9Y80I|DEH^}Fd4YeT!f)+NBWf{;j-y}u zM_{jn?kAbreVU&5HPp1N_b{LE^fkR>>DRsP^{mdssMOix*5?+H3<53fn!C?V46;P1 zDb~1X9AgZ6aX3vo8+w)ObH>?}kuHxsV-bsi936H$zUt+Ucs5+M@o_EC z|5I3J*w+zz{?4g=1G@V^?|?4utu$;xFcSLQ3S>t@H{(-(a$r>I&ubZLTC(6&pn*so zLO2HhNFj=AK^b2&;AXBsGev=2J0i$OPLUA~1t0|QIEx-G=Kk;LJ0l!2OOFg$qf{Y^ zO*flA)|&HGHdNyaI_Wy=e*({)I-lPhr_c4|4F_JD*n4`pI#3aH>9r+D=e`XF(Qy(j zGUcPM%X&lQ@yzZ)KozVORDw1yac#v97=3^CfgyhckTy3{sJcUeO1K#4OItKmMj$cD zrAdPS;Tnav``mumG}L2!?YMyXpstbltwWSxouEEa*t|%Sha0zV@;P zYR#7*fhnk-xEXe)am949tesigGws}4KIeMdr*m=rU^z7)g2dPfzGL}>o+uQR6fn}A;RbS-1^>B_j4FsmefrN3iP zkyNRa%Iovx_e1L5tg!p^=F2xOZkDrB1qt~JahS7UncTbXe3*UN(O89j4r$%UVY!VFo!%LS8QF0m|58@wfA!Z$G_T?xjLFfM z$X*_8q#oxUNZP{Xjp8NJ3cJndu*{75;ZGWhAo;!atg7?${!1zCNa$8blAiu)@ts%F zg4t8jTD^YOPizEi<7X_=vGI9*#J_=PG<|OwX+fU=TLUOH9tS;&n#>Ot=IBbv{sJm< z0*G`U1Y9}p=xp&0T&XAxM7%N;g22h@V6fKpIuf{3nLGPS#T(Ro>*;&dA)5Y5HsUrm z0-{%ztBcFsFCop|yPIV%#67pGXc1wWR1Y~XYEz&68oDw}x^!Dt=E*#1xfnyZ7_%Uz zM$R?BC~u*tAe}+_@&a^N<{c4a;(mz;mYW3P8k3n4*WQQN?HFoXIE+ zVI!or({b8GO%Hq}Tt_@`t;Pra*mct`>;{jW-&;RsDOUK>Ig&J?k)2IH564%<4y<@$ znRK~lX5YMF=fc}`lrMcv+Tlr&r!Radp!@+bH4rf3O&qqIj6UPN!Q+Xl2Xh-(E6@z0 zVTdD3_hCrmN~Q`diNIkzhppZc=3c0;n#f-Q(YxI>2Ms%6GLIg^Z4gv81Y)6q$MM71oZl4P z7QFWdCH?YXxsv;#4s!vv(EsE8RbKiK<(1CHK?KRWy^1N?0>;6#hcL0{MQxvxx>6mJ zs`%XTsn4WUa&;#EI!uh$^$m)?*HaA!nr;)OU4|X4nR7BJsuYkfuV=Y1bLHst5KfUT)o1CeVB-dox|+9Z5BXQ$C_KSmI=sinrb4<$D)i><~89 zv}mBL=C~@A{eN75W)<9OUYYoCQ6DV{+&Cb$J{g;`iG|c+aTv$)FIFa~3uZMSy%j4j z;=#e}C_G+!cTfYaGuxi2(rANq5{hj7-MfrZLBr+Ila*EG{DFfIj+V&+Mi*CRj3PT4 z&cMM3TkGw8Qv#-7aA;64^gkyhM0Ah`Dj?@u$F)!=1Z#f<@VLqRut`Zlw7c*DOGZrz)77d7?mDJbt8G`Kuxfu)V z)sBMS;#E;c|M)&+%%X0jkjt+YX1P6b?w4HT7vr@!b42PzI>vw5 z05y{Zt#dvjgD`RTL;atW1cIem@>m^{)P>#z66ejsD6vQ4?+Mu0X&h@UQY@ zywQq0-3EVOeC>VJTTOLmr0;*YSJFoFcJ|w&M_QG^@%SMNRUCcbpXJ?tBBJU^;>ZVo z{?p!v1F1@(=7@E-;SX zdoL_A9!l&>E3#LUT>M!XEh>v5DCA`Y<&lRmxOgS6ZrNBj0^Z!NG#ch<;5rRo%6xxI zci@}S^zM$Mt>HvG9ao6MvZ-H4&a^PHU~sw#JzqL1B(`EfUHk({7m>P)z=yIfsf(cm zD(}|C9?uF&dJUF+;EZ4m6>4+4`DBKD>(^XGvJtRrI!{o<)ds(HT3{h9U_u8;NFr;` z6=z8kL@k2U@en}nk*j7kbJ#RsT!cb25Dh?%xTom|gQ_bIa1^IvNF?b=%V$Z4qhW&S zlBgT7*AlV1*s`lBde4m6)Hd$SUSfK^T-%NwpZ~0P!Jap4y-EcQZ*(>opStS_RB)Z5 z=A{WCZ^S=E{>Ludd<)>%pHKlQDTK;GlFzcSn7RRc@nBy*jno+&%@80>^Kw zKF1+lVuHU}XYs=2QRO42H&S!>(-ur(e_ei|++!)E@WpFNIo(OQxsu}*6Yce_57;%I zq-%SJg!Qh$9?nppcFo5>;`Whm?+dxp&fsDP;!o$!o6p_{a?{`VXHoLQ3Ua^QFOCM} zeVOzB6`IupZ+l;EBcH~KkCaHKK!p<(g)`b%uN4o)5h+IaP+RgQh`;B4jYUi?=h=^m z>bMjWV_~d%+l}HoYwFt!CR0cmv&D+xv`HZO4IAZ^>+a=CIMws&=^Sl@E@l&ppZdOU z4}VKT7%lq@oI!q6`(0}&x+1Br6HzNxvycC6e}a%fTEgSx@*0&xEB4lBJ=#wLAV!&n z?}QBucs$H<>ON<8pLXLOkN0i24^A8wBD~n&4o4h_HEIt>(^{l<1Q2W5hc#TDd zPTCbM4JX0m-#@5^SDO!NrYv)aUnxjRqU@)ttoX-iW{B{Q)0GNjQ=W!HWH{H?GHc`A zgvkJcN^VdZE`pqv=V$M-4KWP*(*VSWHsj+W5*t!2b9u9A0<}33NuUN)#U;V!Z{*da zecCK z1DI2vb{)py@}y%2J_gPDyD0u~nSq~wd=9+XbOAyPV$L#ljVHma7`64jxCl6;!8o|5 z)Blwj;9H3ZTKnBYtYs|)hgL#4OgB8C=4vFV;(COd5#POyj?l)0&dhtS3Miar9p330 zztIU~I57y&r}O@Na(q_OB?f!n<#&4MAl&55A&e}1*;zk1w>x8&q$e1-_akM9|FmvA zVlZ0#HBv|+@?zJrVNlOT5YnTS&5fikm{7V5dd4^}YW+d<6>0zX=bIamD8?!+^V9nh zc@qLUb~hSf4$_0k0gBB?=!6^eajqhw z5Q*2MNt$Y*Kd1|%<&*I~i(AAdBjP%VTqKI!=7fy}X(aGfKJ*g76Fz!N5)r>!(U|4< z_bQgLsUJ@_%(J!o-{{}Tsl_(HWI5pUW1pjO?;JrmzMb-+IK+(ilc4Do5n2-gE_DIn z_Yb(LBcUNMR=A|Uiz5)AwQc{@AjZ@t`t$hMVSy0O#}=){&Wf@{q;bv@RgV7k*2MFi zjql0#o1>i34XGd*2LD4hq^? zC}c?UB0y_D!(jUeYXTvIulD4`hnBxz!M#YZwl0M32Ku@7@C!x}s4J<_3m70&&9@X5 zujGRzigEwK71fAIFQf$C0h?fANdog4p7zJP6iNoTh$wb_~7 zG5@%!-22C%*oh-{(=>$8QcyCQbSTxmF%JzQ;r=oLWDy79~liW3*#OlxyAxk z=@uAVgABodco_}khYGB%K=qtxI2OntL}Ws9yhI4Dgqn0fFoPYMr~;J+wth`bo#R`x zg(>5I%sxkFjXduY)jx>%UbMY@2`}vO<2~N+-~x5ozF}du^5T;Nb^nj>1E3bbn**_3f8H zHqs?)tPa()g>H~(;3ZM9syeurqd10*C#iki6q-3M%X4BJ6gb@odnl4$dcL7-u;RlI zAWPtlC^$1mcU&ThXF>QE==H8yrN>LTp>~)nJfP1^;#&8MDlbCBzX9;w(b<> zZ{gtf?*d4%(lQ`ufcamKy%=@9#jZ1E)})icf|@!a<4LwolDrcK#P87Ztov4!s5Bs2 zy)e>#|HTUZg9T4dEfQy*`{@PShPDaono*AnB-=8DKqflb&b>LdB#B}r)92fHEH07) z4z+k7omlAOR4+9`GBpC;I7wz7<+}{hj|3~*Dvc1OLTQE6;k}=hDaR$9U6q}!E&*-+ zXM*%KZpb^n{XRZht5Mgm5m56No-g%5e`m7i2C~h(_*0hjKcWx)WEJEw{-~wP=UgLj zof@=dCEO|RTpqi2W!vFxa#)lbvZ}7U`u}J;%b>Q}b_)l0cZcBa?hxFyxNC8DcXxLv z7Nj`Eoffx3af&+>C{X<5{btTg{wA5($+Pz@Yh4SO7RYl_>DK<-|P^6CrdefrjUIM(61Si%r0-xhZt;r`YC z%ImltP+|U%N1uu-j7x`yXWwI>gC+=&0Jdb;^RJ{g%YOkw3Lyw~qX9h037KAkU}1Hj zrGUeh{-}^+h&4e7_?-#ic1OWAnB%2^0ACcO7uhJ8QRqkWsh=G^ZMaGB10Ng49zRNV zHc>)j-lw}lo_7F^J^@Q(v)L$0z$vzjK*|+7F=+tgBVCmtu@zW4S$R-^ly>EnbV*7~ zSXnc5?`S=2k9fuw8b4)D0l%B~*WX(W zofBjoZs~`OXkG*sYb0Re@?qjR7O!^Li}=FCid@p6^|Rk+6AN0^2x>{KXcj9Elvg{6 zODTH?(ps1Qv^NMfk(FW>tb<+4H@{*3YSau~?BYF_1(EYWccju4(uo8y$oVW@shC_G z@mY&vKvUtP6_EzN`?$I4xLR^5d6~gxHO}PI*}`kU>Ci~%z`~hZpU1J#A#r+HmHxQ1 z*#CJkGq4vUesPcNbK2_ve20*rAzHBd`6IH;kJI8xrJD(@F6-XU=g-Pe%ys9`*FyiJ zgM^TsVc+ggwtN{?(Hz{EiCI>uaFk~D&j-<^ur+4s`N@J~YziZSv4UA6BPA!h1!T#$ z^ufYOC52AcHC2l+<8YFSW*MwtyHC%RcjQ^WX+6ylHcd-OOx2`C*XB&1RY2VC!HOgI4~t0MHD z_z~@1o!!ubl&pI2HHUWRC%XY|{yRDwKULa_6h8BR(OQxtBvo)JE;%s{?C5=UbUDP8 zn7C^c5<$)AV^QY9sSf8QwwxC(Fx;15l%0|qW~8N?pO$lBR#`lYKhSje1zRFKbY<7f zjGHt!|2&gXpr5w>*17j~jYWE}Z+kjg*ZStnm2#d_LLugXcK#Urv$h8LyP5hFur<<2 zCu$Wtjh7rNOdbjsjVQtjYL^p&Bm0lCmaC%!`bPkwol@laFJ=2594PX;_5vZ^{{$OQ zM3h!|8hilRD9uI8L<`g~4dFvoYu__%mrGn8ggcjy>)@B9#9^#@^nrgR-P|SUXlxx< zdEQs3@m_@(YgYJSn5Tr~FaVt>OYr10gv$}TT6Q;EN_SwU&I(rK8jp3wMrV{c8U-R- z87nT}*}NTKmLWgx>>`L~_*W~DHJFf!y`BC1>r8e@I&lTO4A=<+Nf@vdjLu&t=``HQ zAWHHc!ZGoB1+03vSC~7iL1D1en+iO=a@&d*?8|55&Y!vyoCnxHXmozCv0M>@xs?>> z<5__GdmKAIo^6AI7uU;pXYJ7Lz4bQF!A@u4N-|dqgV5%2UFPDs)$f1S31%kLB;Ang z$lBETHoc8zINHIb0B}ugJaViZB*juw-Z(w?u>Ycr_5AJnUHtTFrhP%6=Rr{5W2{es z^DBNbfkUnPg#|A%dV)v#kX#1E$BpN9_r0xZ@LAp3ALwt(a{S^K0qo5>Dt1t)vPo1t zQI*4fFrs*{uuYuyOJkHsvCXyH9T)6% zDZh<13jX^R@aJm5liyI^So95a5R6*6{$8$dsEDDgZU;pivxmfJf416PoG-!%@gu2_ z8I~QONW;R~EfCGn>Yd{DC|c{M@XtI=S+DFW2 zTSI*jmaCg@#8E>9@M&A@ckji^JvTw|bE0t<^w^U#`Qvpk3qt27qYa`9#0fpF6+(vv zLXKk8+VOd0&}5>`x;u&G-_!s?#S9;vL}MA}JhblAc6v25g5^bu3stdTTiWwPIidS- z{Vo%gZa-#v(^tGDYNP%~>Na>x&67;aY(W=>4yP@aB+fkc!bgcO$k2o3(@dq1Drd#u zn3QOQaflOZcYxZ_DLT5o-4pdaIlKmPmxhGLLs)zYsi7Q<2@vjbDUD;ELRl@of{wFDYPaOYt%ya}#CM=Ho`Oq{D@wtKd3qG;;09jUh$I81A3_ zennC1?Z`G(a9Saw-SA#%t1`mexu(0W9@+2~8u^A>nBkI?L#f`5tA$~1*W5-ad!$

      ' | remove: '

      ' }} +{{ plugin.description | markdownify | remove: '

      ' | remove: '

      ' }} + +{%- comment -%} +{%- if plugin.image and plugin.image != "" -%} +![]({{ site.baseurl | append: '/assets/images/' }}{{ plugin.image }}) +{%- endif -%} +{%- endcomment -%} +{%- endfor -%} + diff --git a/mapviz/CHANGELOG.rst b/mapviz/CHANGELOG.rst new file mode 100644 index 000000000..df62cd39c --- /dev/null +++ b/mapviz/CHANGELOG.rst @@ -0,0 +1,306 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mapviz +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.3.0 (2023-08-24) +------------------ +* Updates for rolling and removing EOL distro support (`#785 `_) +* Contributors: David Anthony + +2.2.2 (2023-06-07) +------------------ +* Add ros_environment as dependency +* Iron Compatibility (`#779 `_) +* Contributors: David Anthony + +2.2.1 (2023-05-30) +------------------ +* Updating maintainers list (`#778 `_) +* Contributors: David Anthony + +2.1.0 (2020-10-22) +------------------ +* ROS Foxy support (`#695 `_) +* Contributors: P. J. Reed + +2.0.0 (2020-05-13) +------------------ +* Port mapviz to ROS 2 (`#672 `_) +* Remove OpenGL warning (`#667 `_) +* Resolves segfault issue on ClearHistory() function call (`#651 `_) +* Fix plug-in config panel to scroll per-pixel instead of per-item, allowing configuration of plug-ins that have config settings that are too large to fit in the panel all at once. (`#646 `_) +* Contributors: Daniel D'Souza, Marc Alban, Matthew Bries, Matthew Grogan, P. J. Reed, Jason Gassaway, John Reyes, Jacob Hassold, Kevin Nickels, Roger Strain + +1.2.0 (2019-09-04) +------------------ + +1.1.1 (2019-05-17) +------------------ +* Set main window as in focus on start `#630 `_ +* Specify default configuration extension on save +* Contributors: Daniel D'Souza, mattrich37, mrichardson + +1.1.0 (2019-02-20) +------------------ + +1.0.1 (2019-01-25) +------------------ + +1.0.0 (2019-01-23) +------------------ +* Sharing tf_manager\_ between main app and plugins (`#555 `_) +* Contributors: Davide Faconti + +0.3.0 (2018-11-16) +------------------ +* Merge all -devel branches into a single master branch +* Add function to lock canvas movement (`#596 `_) +* Contributors: P. J. Reed + +0.2.6 (2018-07-31) +------------------ + +0.2.5 (2018-04-12) +------------------ +* Add clear history functionality. +* New plugin to send commands to move_base +* improve text contrast (`#550 `_) +* Glew warning fixed (`#539 `_) +* remove copy and paste of Print... +* add context menu to config_item (`#526 `_) +* Merge pull request `#523 `_ from matt-attack/add-keyboard-input-support-kinetic +* Add keyboard input support for plugins +* update to use non deprecated pluginlib macro +* Fix the "File" menu actions (`#513 `_) +* Merge pull request `#481 `_ from pjreed/threaded-video-recording-kinetic +* Move video recording into its own thread +* Contributors: Davide Faconti, Marc Alban, Matthew Bries, Mikael Arguedas, P. J. Reed + +0.2.4 (2017-08-11) +------------------ +* Add basic profiling to mapviz. +* Handle GL canvas transforms with an invalid target frame +* Add parameter to disable auto-saving functionality. +* Contributors: Elliot Johnson, Marc Alban, P. J. Reed + +0.2.3 (2016-12-10) +------------------ +* Fix mapviz kinetic build. (`#456 `_) + Add a missing rosdep dependency on libxi-dev. +* Contributors: Edward Venator + +0.2.2 (2016-12-07) +------------------ +* Migrated OpenCV to 3.1 (default in Kinetic) +* Contributors: Brian Holt + +0.2.1 (2016-10-23) +------------------ +* Add a GUI for controlling the Image Transport (`#432 `_) + This will add a sub-menu under the "View" menu that will: + - List all available image transports + - Indicate which one is currently the default + - Allow the user to choose which one will be used for new ImageTransport subscriptions + - Save and restore this setting to Mapviz's config file + - Cause any `image` plugins using the default transport to resubscribe + In addition, the image plugin now has a menu that can be used to change the + transport for that specific plugin so that it is different from the default. + Fixes `#430 `_ + Conflicts: + mapviz/package.xml +* Fix icon colors for point drawing plugins (`#433 `_) + This was probably broken back when all of these were refactored to have a + single base class. It looks like the member variable that holds the color + used to draw the icon was never actually being updated. + Fixes `#426 `_ +* Remove unnecessary include +* Fix warnings in mapviz. + Fix several reorder and signed comparison warnings in the mapviz + package. +* Giving `tile_map` an interface overhaul + MapQuest has turned off their public API for map tiles, so this plugin needed some work. I have: + - Removed the MapQuest sources + - Made the interface for adding new sources more powerful + - Overhauled how sources are saved and loaded under the hood + - Added a button to reset the current tile cache + Resolves `#402 `_ + Conflicts: + tile_map/CMakeLists.txt +* Adding a dialog for selecting services by type + This dialog is similar to the ones for listing topics or TF frames, but it is + a little different under the hood. Notably: + - It relies on the rosapi node in order to be able to search for services + - Since searching is done via a service call, ROS communication is handled + on a separate thread that will not block the GUI + - Unlike topics, only searching for a single service type is supported + Conflicts: + mapviz/package.xml +* Adding a way for plugin config widgets to resize + - Adding an event plugins can emit to indicate their geometry has changed + - Modifying the PCL2 plugin to use it as an example + Fixes `#393 `_ +* Adding a button to reset the location and zoom level + This adds an icon on the right side of Mapviz's status bar tthat will reset + the view to the default zoom level and center it on the origin of the target + frame. + Resolves `#371 `_ +* Contributors: Ed Venator, Marc Alban, P. J. Reed + +0.2.0 (2016-06-23) +------------------ +* Update mapviz to qt5 +* Adding a Q_OBJECT declaration to MapvizPlugin +* Adding signals for various plugin events + The MapvizPlugin class will now emit signals when any of the following settings change: + - Draw Order + - Target Frame + - Use Latest Transforms + - Visibility + Note that the signals will only be emitted if the setting actually *changes*, not + if it is somehow set to the same value that it was previously. +* Contributors: Ed Venator, P. J. Reed + +0.1.3 (2016-05-20) +------------------ +* Implement mapviz plug-in for calling the marti_nav_msgs::PlanRoute service. +* Adding an explicit dependency on pkg-config to package.xml (`#355 `_) +* Add _gencpp dependency to mapviz targets. + This commit adds the _gencpp target to mapviz targets to ensure that + the AddMapvizDisplay service is built before the targets. +* Make compiler flags specific to each target. +* Implement service for adding and modifying mapviz displays. +* Fix for `#339 `_; explicitly depending on OpenCV 2 +* Fix for `#336 `_; Qt event handler exceptions shouldn't crash Mapviz +* Fixing blending for GL drawing + The call to QGLWidget::beginNativePainting has a side effect of clearing + GL settings related to blending and depth testing, and that was causing + alpha transparency to not work right for plugins. I fixed it by manually + re-enabling those settings every time beginNativePainting is called. +* Fix for `#319 `_ + Previously, the MapCanvas::MapGlCoordToFixedFrame function relied on + the transform\_ member variable being set, but it is not set if the + target frame is . Instead it will now use the qtransform\_ + variable, which is always initialized for the purpose of QPainters. +* Saving & restoring all matrices and attribs +* Moving QPainter drawing back to being after GL + I had switched the order while debugging things and forgot to set it + back to the way it originally was. +* Removing a leftover debug print +* Fixing `#317 `_ + First, the model view matrix needs to be saved and restored around + QPainter operations because Qt clears several GL variables. Also, the + image plugin needed to explicitly call glMatrixMode(GL_PROJECTION); + it does a few operations on the projection matrix and was just assuming + that was the current matrix mode. Also, I added a function that plugins + need to override if they want to do QPainter operations; this will + eliminate unnecessary overhead for plugins that do not. +* Removing extraneous calls to MapCanvas::update() + Now that update() is being called automatically at a rate of 50 Hz, + the explicit calls in many locations are unnecessary. It was also + possible for it to be called in some of these locations from a + non-main thread, which is invalid and could cause crashes. +* Adding the ability to toggle anti-aliasing + Now there's a checkbox under the "View" menu that will toggle whether + anti-aliasing is applied to the canvas. In some situations this will + make the display look much prettier at a slight performance cost. +* Cleaning up documentation. +* Merging QPainter/anti-aliasing fixes into jade-devel + This is the same as the old version of this change, except updated + to the most recent version of Mapviz. +* Fixing a compile error +* Fix for `#298 `_; right-click + drag will now zoom +* Update map canvas at a fixed rate. + This update adds a timer to the map canvas to repaint at a fixed rate. + The default rate is 50 Hz, but there is a method to change it (not + exposed to the UI at the moment). 50Hz was chosen because it is fast + enough to give smooth animations and we almost always are running + mapviz with at least one plugin triggering updates from a 50Hz topic. +* Update mapviz.launch file to also launch anonymously. +* Initialize mapviz as an anonymous node. +* This commit adds a class called SelectFrameDialog that plugins can use + to present the user with a dialog to choose a TF frame. The dialog + sorts the frames by name and provides an edit box that the user can + use to filter the frames to a specific substring. +* Fixing an issue that could cause the click publisher plugin's publisher to not be initialized after it's first added. +* Adding a plugin that, when a user clicks on a point, will publish that point's coordinates to a topic. +* Adding color button widget and updating plugins. + This commit adds a subclass of QPushButton called ColorButton that + implements a widget for displaying and selecting colors. We've been + doing this manually everywhere with duplicated code. This is a simple + abstraction but allows us to elminate a lot of duplication, especially + in plugins that have multiple color selections. +* Remove debugging messages from SelectFrameDialog. + These were accidentally left in during initial development. +* Add documentation for the SelectTopicDialog. +* Adds SelecTopicDialog to mapviz. + This commit adds the SelectTopicDialog that can be used in plugins to + provide the user with a dialog to select topics. Typically we have + done this with a lot of duplicated code across all the plugins. This + commit also updates the plugins in mapviz_plugins to use the new + dialog. + The new dialog provides several benefits: + - Reduced code duplication + - Simplifies writing new plugins + - Common behavior between all plugins + - Topics sorted by name + - User can filter topics by substring + - Continuously checks the master for new topics while the dialog is open. +* Contributors: Elliot Johnson, Marc Alban, P. J. Reed + +0.1.2 (2016-01-06) +------------------ +* Show full path when recording screenshots/movies. +* Fixes a bug in plug-in sorting. +* Sorts topic, plug-in, and frame lists in selection dialogs. +* Contributors: Elliot Johnson, Marc Alban + +0.1.1 (2015-11-17) +------------------ +* Fixes mapviz launch file frame param +* Marks single argument constructors explicit. +* Contributors: Edward Venator, Marc Alban, Vincent Rousseau + +0.1.0 (2015-09-29) +------------------ + +0.0.3 (2015-09-28) +------------------ +* Fixing casting issues that prevented compilation on 32-bit systems. +* Contributors: P. J. Reed + +0.0.2 (2015-09-27) +------------------ +* Adds missing qt4_opengl dependency + +0.0.1 (2015-09-27) +------------------ +* Renames all marti_common packages that were renamed. + (See http://github.com/swri-robotics/marti_common/issues/231) +* Adds missing dependencies in mapviz package.xml. +* Fixes catkin_lint problems that could prevent installation. +* Formats package files +* Cleans up dependencies +* Adds required rosdeps +* Saving/loading config files to the ROS_WORKSPACE directory. +* fixes lint issues +* Makes mapviz show a warning dialog instead of crash when it fails to load a plugin. +* includes yaml_util header in mapviz plug-in base class +* Handles loading old config files that still reference "mutlires_image". +* Adds an RQT plugin version of Mapviz. +* updates cmake version to squash the CMP0003 warning +* uses correct operator when combining quaternions +* adds option for rotating camera 90 degrees +* throttles log msgs +* removes dependencies on build_tools +* uses format 2 package definition +* allows plug-in selection with double-clicks +* displays file name in window title +* displays preview icon next to plug-in names +* fixes issue with coordinates displayed on status bar +* fixes missing organization in license text +* Adds tooltips describing the various mapviz widgets +* fixes GLEW/GL include order +* catkinizes mapviz +* changes license to BSD +* adds license and readme files +* Contributors: Ed Venator, Edward Venator, Jerry Towler, Marc Alban, P. J. Reed diff --git a/mapviz/CMakeLists.txt b/mapviz/CMakeLists.txt new file mode 100644 index 000000000..5fc2c1460 --- /dev/null +++ b/mapviz/CMakeLists.txt @@ -0,0 +1,210 @@ +### SET CMAKE POLICIES ### +cmake_minimum_required(VERSION 3.10...3.17) + +if(${CMAKE_VERSION} VERSION_LESS 3.12) + cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) +endif() + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(${CMAKE_VERSION} VERSION_EQUAL "3.11.0" OR ${CMAKE_VERSION} VERSION_GREATER "3.11.0") + cmake_policy(SET CMP0072 NEW) +endif() + +if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() +### END CMAKE POLICIES ### + +project(mapviz + DESCRIPTION "Mapviz is a ROS based visualization tool with a plug-in system similar to RVIZ focused on visualizing 2D data." + LANGUAGES CXX) + +### ROS Packages ### +find_package(ament_cmake REQUIRED) +find_package(cv_bridge REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(image_transport REQUIRED) +find_package(mapviz_interfaces REQUIRED) +find_package(marti_common_msgs REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rqt_gui_cpp REQUIRED) +find_package(std_srvs REQUIRED) +find_package(swri_math_util REQUIRED) +find_package(swri_transform_util REQUIRED) +find_package(tf2 REQUIRED) +find_package(tf2_ros REQUIRED) + +find_package(tf2_geometry_msgs REQUIRED) + +### PkgConfig ### +find_package(PkgConfig REQUIRED) +pkg_check_modules(YamlCpp yaml-cpp) + +### Boost ### +find_package(Boost REQUIRED date_time system filesystem) + +### OpenCV 3/4 on ROS2 ### +find_package(OpenCV COMPONENTS core imgproc imgcodecs videoio REQUIRED) + +# ### Qt5 on ROS2 ### +find_package(Qt5Concurrent REQUIRED) +find_package(Qt5Core REQUIRED) +find_package(Qt5Gui REQUIRED) +find_package(Qt5OpenGL REQUIRED) +find_package(Qt5Widgets REQUIRED) +add_definitions(-DWFlags=WindowFlags) +set(QT_USE_QTOPENGL TRUE) + +### OpenGL ### +find_package(OpenGL REQUIRED) +find_package(GLUT REQUIRED) + +### GLEW ### +find_package(GLEW REQUIRED) + +# Fix conflict between Boost signals used by tf and QT signals used by mapviz +add_definitions(-DQT_NO_KEYWORDS) + +# Need to include the current dir to include the results of building Qt UI files +set(CMAKE_INCLUDE_CURRENT_DIR ON) + +# Qt UI files +set(UI_FILES + src/configitem.ui + src/${PROJECT_NAME}.ui + src/pluginselect.ui +) +# Headers containing QObject definitions +set(QT_HEADERS + include/${PROJECT_NAME}/color_button.h + include/${PROJECT_NAME}/config_item.h + include/${PROJECT_NAME}/map_canvas.h + include/${PROJECT_NAME}/${PROJECT_NAME}.hpp + include/${PROJECT_NAME}/${PROJECT_NAME}_plugin.h + include/${PROJECT_NAME}/rqt_${PROJECT_NAME}.h + include/${PROJECT_NAME}/select_frame_dialog.h + include/${PROJECT_NAME}/select_service_dialog.h + include/${PROJECT_NAME}/select_topic_dialog.h + include/${PROJECT_NAME}/video_writer.h + include/${PROJECT_NAME}/widgets.h +) +# Source files for mapviz +set(SRC_FILES + src/${PROJECT_NAME}.cpp + src/color_button.cpp + src/config_item.cpp + src/${PROJECT_NAME}_application.cpp + src/map_canvas.cpp + src/rqt_${PROJECT_NAME}.cpp + src/select_frame_dialog.cpp + src/select_service_dialog.cpp + src/select_topic_dialog.cpp + src/video_writer.cpp +) + +### Qt5 on ROS2 ### +qt5_add_resources(RCC_SRCS src/resources/icons.qrc) +qt5_wrap_ui(SRC_FILES ${UI_FILES}) +qt5_wrap_cpp(SRC_FILES ${QT_HEADERS}) + +### Build mapviz as an rqt plugin ### +add_library(rqt_${PROJECT_NAME} + ${SRC_FILES} + ${RCC_SRCS} +) +target_include_directories(rqt_${PROJECT_NAME} + PUBLIC + include + PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR} + ${CMAKE_CURRENT_BINARY_DIR} +) + +target_link_libraries(rqt_${PROJECT_NAME} + OpenGL::GL + ${GLUT_LIBRARIES} + GLEW::GLEW + opencv_core + opencv_highgui + opencv_imgproc + opencv_imgcodecs + opencv_videoio + ${YamlCpp_LIBRARIES} + Qt5::Concurrent + Qt5::Core + Qt5::Gui + Qt5::OpenGL + Qt5::Widgets +) +ament_target_dependencies(rqt_${PROJECT_NAME} + ament_cmake + cv_bridge + geometry_msgs + image_transport + mapviz_interfaces + marti_common_msgs + pluginlib + rclcpp + rqt_gui_cpp + std_srvs + swri_math_util + swri_transform_util + tf2 + tf2_geometry_msgs + tf2_ros +) +set_target_properties(rqt_${PROJECT_NAME} PROPERTIES + COMPILE_FLAGS "-D__STDC_FORMAT_MACROS" +) + +### Build mapviz as a standalone executable ### +add_executable(${PROJECT_NAME} + src/${PROJECT_NAME}_main.cpp +) +target_link_libraries(${PROJECT_NAME} + rqt_${PROJECT_NAME} + ${Boost_LIBRARIES} + ${GLU_LIBRARY} +) +ament_target_dependencies(${PROJECT_NAME} + swri_math_util + swri_transform_util +) +set_target_properties(${PROJECT_NAME} PROPERTIES + COMPILE_FLAGS "-D__STDC_FORMAT_MACROS" +) + +### Install mapviz ### +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION include/${PROJECT_NAME} + FILES_MATCHING PATTERN "*.h" +) + +install(TARGETS ${PROJECT_NAME} rqt_${PROJECT_NAME} + RUNTIME DESTINATION lib/${PROJECT_NAME} + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib +) + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME} +) + +install(FILES plugin.xml + DESTINATION share/${PROJECT_NAME} +) + +ament_export_dependencies(${RUNTIME_DEPS} + Qt5Concurrent + Qt5Core + Qt5Gui + Qt5OpenGL + Qt5Widgets +) +ament_export_include_directories(include) +ament_export_libraries(rqt_${PROJECT_NAME} ${YamlCpp_LIBRARIES}) +ament_package() diff --git a/mapviz/include/mapviz/color_button.h b/mapviz/include/mapviz/color_button.h new file mode 100644 index 000000000..af034240f --- /dev/null +++ b/mapviz/include/mapviz/color_button.h @@ -0,0 +1,73 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** +#ifndef MAPVIZ__COLOR_BUTTON_H_ +#define MAPVIZ__COLOR_BUTTON_H_ + +#include +#include + +namespace mapviz +{ +/** + * The ColorButton widget provides a color display that the user can + * click on to select a new color. You can use this widget in Qt + * Designer by placing a QPushButton and promoting it to a custom + * widget. You have to setup the promoted widget once in each .ui file: + * + * Base class name: QPushButton + * Promoted class name: mapviz::ColorButton + * Include file name: mapviz/color_button.h + * Global Include: True + */ +class ColorButton : public QPushButton +{ + Q_OBJECT; + + QColor color_; + + public: + explicit ColorButton(QWidget *parent = 0); + + const QColor& color() const { return color_; } + + Q_SIGNALS: + // Emitted when the color is changed by user interaction. + void colorEdited(const QColor &color); + // Emitted when the color is changed by user interaction or programatically. + void colorChanged(const QColor &color); + + public Q_SLOTS: + void setColor(const QColor &color); + + private Q_SLOTS: + void handleClicked(); +}; // class ColorButton +} // namespace mapviz +#endif // MAPVIZ__COLOR_BUTTON_H_ diff --git a/mapviz/include/mapviz/config_item.h b/mapviz/include/mapviz/config_item.h new file mode 100644 index 000000000..48de5cc1f --- /dev/null +++ b/mapviz/include/mapviz/config_item.h @@ -0,0 +1,90 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ__CONFIG_ITEM_H_ +#define MAPVIZ__CONFIG_ITEM_H_ + +// QT libraries +#include +#include +#include +#include + +// C++ standard libraries +#include +#include + +// Auto-generated UI files +#include "ui_configitem.h" + +namespace mapviz +{ +class ConfigItem : public QWidget +{ + Q_OBJECT + +public: + explicit ConfigItem(QWidget *parent = nullptr, Qt::WindowFlags flags = Qt::WindowFlags()); + ~ConfigItem() override = default; + + void SetName(QString name); + void SetType(QString type); + void SetWidget(QWidget* widget); + + void SetListItem(QListWidgetItem* item) { item_ = item; } + bool Collapsed() const { return ui_.content->isHidden(); } + QString Name() const { return name_; } + + Ui::configitem ui_; + +Q_SIGNALS: + void UpdateSizeHint(); + void ToggledDraw(QListWidgetItem* plugin, bool visible); + void RemoveRequest(QListWidgetItem* plugin); + +public Q_SLOTS: + void Hide(); + void EditName(); + void Remove(); + void ToggleDraw(bool toggled); + +private: + void contextMenuEvent(QContextMenuEvent *event) override; + +protected: + QListWidgetItem* item_; + QString name_; + QString type_; + QAction* edit_name_action_; + QAction* remove_item_action_; + bool visible_; +}; +} // namespace mapviz + +#endif // MAPVIZ__CONFIG_ITEM_H_ diff --git a/mapviz/include/mapviz/map_canvas.h b/mapviz/include/mapviz/map_canvas.h new file mode 100644 index 000000000..faf9c4c6f --- /dev/null +++ b/mapviz/include/mapviz/map_canvas.h @@ -0,0 +1,254 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ__MAP_CANVAS_H_ +#define MAPVIZ__MAP_CANVAS_H_ + +// QT libraries +#include +#include +#include +#include +#include + +// ROS libraries +#include +#include +#include +#include + +#include + +// C++ standard libraries +#include +#include +#include +#include +#include + +namespace mapviz +{ +class MapCanvas : public QGLWidget +{ + Q_OBJECT + +public: + explicit MapCanvas(QWidget *parent = nullptr); + ~MapCanvas() override; + + void InitializeTf(std::shared_ptr tf); + + void AddPlugin(MapvizPluginPtr plugin, int order); + void RemovePlugin(MapvizPluginPtr plugin); + void SetFixedFrame(const std::string& frame); + void SetTargetFrame(const std::string& frame); + void ToggleFixOrientation(bool on); + void ToggleRotate90(bool on); + void ToggleEnableAntialiasing(bool on); + void ToggleUseLatestTransforms(bool on); + void UpdateView(); + void ReorderDisplays(); + void ResetLocation(); + QPointF MapGlCoordToFixedFrame(const QPointF& point); + QPointF FixedFrameToMapGlCoord(const QPointF& point); + + double frameRate() const; + + float ViewScale() const { return view_scale_; } + float OffsetX() const { return offset_x_; } + float OffsetY() const { return offset_y_; } + + + void setCanvasAbleToMove(bool assigning) + { + canvas_able_to_move_ = assigning; + } + + void leaveEvent(QEvent* e) override; + + void SetViewScale(float scale) + { + view_scale_ = scale; + UpdateView(); + } + + void SetOffsetX(float x) + { + offset_x_ = x; + UpdateView(); + } + + void SetOffsetY(float y) + { + offset_y_ = y; + UpdateView(); + } + + void SetBackground(const QColor& color) + { + bg_color_ = color; + update(); + } + + void CaptureFrames(bool enabled) + { + capture_frames_ = enabled; + update(); + } + + /** + * Copies the current capture buffer into the target buffer. The target + * buffer must already be initialized to a size of: + * height * width * 4 + * @param buffer An initialize buffer to copy data into + * @return false if the current capture buffer is empty + */ + bool CopyCaptureBuffer(uchar* buffer) + { + if (!capture_buffer_.empty()) { + memcpy(&buffer[0], &capture_buffer_[0], capture_buffer_.size()); + return true; + } + + return false; + } + + /** + * Resizes a vector to be large enough to hold the current capture buffer + * and then copies the capture buffer into it. + * @param buffer A vector to copy the capture buffer into. + * @return false if the current capture buffer is empty + */ + bool CopyCaptureBuffer(std::vector& buffer) + { + buffer.clear(); + if (!capture_buffer_.empty()) { + buffer.resize(capture_buffer_.size()); + memcpy(&buffer[0], &capture_buffer_[0], buffer.size()); + + return true; + } + + return false; + } + + void CaptureFrame(bool force = false); + +Q_SIGNALS: + void Hover(double x, double y, double scale); + +public Q_SLOTS: + void setFrameRate(const double fps); + +protected: + void initializeGL() override; + void initGlBlending(); + void pushGlMatrices(); + void popGlMatrices(); + void resizeGL(int w, int h) override; + void paintEvent(QPaintEvent* event) override; + void wheelEvent(QWheelEvent* e) override; + void mousePressEvent(QMouseEvent* e) override; + void mouseReleaseEvent(QMouseEvent* e) override; + void mouseMoveEvent(QMouseEvent* e) override; + void keyPressEvent(QKeyEvent* e) override; + + void Recenter(); + void TransformTarget(QPainter* painter); + void Zoom(float factor); + + void InitializePixelBuffers(); + + bool canvas_able_to_move_ = true; + bool has_pixel_buffers_; + int32_t pixel_buffer_size_; + GLuint pixel_buffer_ids_[2]; + int32_t pixel_buffer_index_; + bool capture_frames_; + + bool initialized_; + bool fix_orientation_; + bool rotate_90_; + bool enable_antialiasing_; + + QTimer frame_rate_timer_; + + QColor bg_color_; + + Qt::MouseButton mouse_button_; + bool mouse_pressed_; + int mouse_x_; + int mouse_y_; + // Used when right-click dragging to zoom + int mouse_previous_y_; + + bool mouse_hovering_; + int mouse_hover_x_; + int mouse_hover_y_; + + // Offset based on previous mouse drags + double offset_x_; + double offset_y_; + + // Offset based on current mouse drag + double drag_x_; + double drag_y_; + + // The center of the view + float view_center_x_; + float view_center_y_; + + // View scale in meters per pixel + float view_scale_; + + // The bounds of the view + float view_left_; + float view_right_; + float view_top_; + float view_bottom_; + + // The bounds of the scene + float scene_left_; + float scene_right_; + float scene_top_; + float scene_bottom_; + + std::string fixed_frame_; + std::string target_frame_; + + std::shared_ptr tf_buf_; + tf2::Stamped transform_; + QTransform qtransform_; + std::list plugins_; + + std::vector capture_buffer_; +}; +} // namespace mapviz + +#endif // MAPVIZ__MAP_CANVAS_H_ diff --git a/mapviz/include/mapviz/mapviz.hpp b/mapviz/include/mapviz/mapviz.hpp new file mode 100644 index 000000000..e737a5442 --- /dev/null +++ b/mapviz/include/mapviz/mapviz.hpp @@ -0,0 +1,219 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ__MAPVIZ_HPP_ +#define MAPVIZ__MAPVIZ_HPP_ + +// QT libraries +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include // Service +#include +#include +#include + +// ROS libraries +#include +#include +#include +#include +#include +#include + +// C++ standard libraries +#include +#include +#include +#include + +// Auto-generated UI files +#include "ui_mapviz.h" +#include "ui_pluginselect.h" + + +#include "mapviz/stopwatch.h" + +namespace mapviz +{ +class Mapviz : public QMainWindow +{ + Q_OBJECT + +public: + Mapviz(bool is_standalone, + int argc, + char** argv, + QWidget *parent = 0, + Qt::WindowFlags flags = Qt::WindowFlags()); + ~Mapviz(); + + rclcpp::Node::SharedPtr GetNode(); + + void Initialize(); + +public Q_SLOTS: + void AutoSave(); + void OpenConfig(); + void SaveConfig(); + void ClearConfig(); + void SelectNewDisplay(); + void RemoveDisplay(); + void RemoveDisplay(QListWidgetItem* item); + void ReorderDisplays(); + void FixedFrameSelected(const QString& text); + void TargetFrameSelected(const QString& text); + void ToggleUseLatestTransforms(bool on); + void UpdateFrames(); + void SpinOnce(); + void UpdateSizeHints(); + void ToggleConfigPanel(bool on); + void ToggleStatusBar(bool on); + void ToggleCaptureTools(bool on); + void ToggleFixOrientation(bool on); + void ToggleRotate90(bool on); + void ToggleEnableAntialiasing(bool on); + void ToggleShowPlugin(QListWidgetItem* item, bool visible); + void ToggleRecord(bool on); + void SetImageTransport(QAction* transport_action); + void UpdateImageTransportMenu(); + void CaptureVideoFrame(); + void StopRecord(); + void Screenshot(); + void Force720p(bool on); + void Force480p(bool on); + void SetResizable(bool on); + void SelectBackgroundColor(const QColor &color); + void SetCaptureDirectory(); + void Hover(double x, double y, double scale); + void Recenter(); + void HandleProfileTimer(); + void ClearHistory(); + +Q_SIGNALS: + /** + * Emitted every time a frame is grabbed when Mapviz is in video recording + * mode, typically at a rate of 30 FPS. + * Note that the QImage emitted says its format is ARGB, but its pixel + * order is actually BGRA. + */ + void FrameGrabbed(QImage); + void ImageTransportChanged(); + +protected: + void Open(const std::string& filename); + void Save(const std::string& filename); + + MapvizPluginPtr CreateNewDisplay( + const std::string& name, + const std::string& type, + bool visible, + bool collapsed, + int draw_order = 0); + + void AddDisplay( + const mapviz_interfaces::srv::AddMapvizDisplay::Request::SharedPtr req, + mapviz_interfaces::srv::AddMapvizDisplay::Response::SharedPtr resp); + + void ClearDisplays(); + void AdjustWindowSize(); + + QString GetDefaultConfigPath(); + + virtual void showEvent(QShowEvent* event); + virtual void closeEvent(QCloseEvent* event); + + static const QString ROS_WORKSPACE_VAR; + static const QString MAPVIZ_CONFIG_FILE; + static const char IMAGE_TRANSPORT_PARAM[]; + + Ui::mapviz ui_; + + QMenu* image_transport_menu_; + + QTimer frame_timer_; + QTimer spin_timer_; + QTimer save_timer_; + QTimer record_timer_; + QTimer profile_timer_; + + QLabel* xy_pos_label_; + QLabel* lat_lon_pos_label_; + + QWidget* spacer1_; + QWidget* spacer2_; + QWidget* spacer3_; + QPushButton* recenter_button_; + QPushButton* rec_button_; + QPushButton* stop_button_; + QPushButton* screenshot_button_; + + int argc_; + char** argv_; + + bool is_standalone_; + bool initialized_; + bool force_720p_; + bool force_480p_; + bool resizable_; + QColor background_; + + std::string capture_directory_; + QThread video_thread_; + VideoWriter* vid_writer_; + + bool updating_frames_; + + std::shared_ptr node_; + rclcpp::Service::SharedPtr add_display_srv_; + std::shared_ptr tf_buf_; + std::shared_ptr tf_; + swri_transform_util::TransformManagerPtr tf_manager_; + + pluginlib::ClassLoader* loader_; + MapCanvas* canvas_; + std::map plugins_; + + Stopwatch meas_spin_; +}; +} // namespace mapviz + +#endif // MAPVIZ__MAPVIZ_HPP_ diff --git a/mapviz/include/mapviz/mapviz_application.h b/mapviz/include/mapviz/mapviz_application.h new file mode 100644 index 000000000..4a93eecd1 --- /dev/null +++ b/mapviz/include/mapviz/mapviz_application.h @@ -0,0 +1,59 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ__MAPVIZ_APPLICATION_H_ +#define MAPVIZ__MAPVIZ_APPLICATION_H_ + +#include +#include + +#include + +namespace mapviz +{ +/** + * This class exists solely so that we can override QApplication::notify and + * log exceptions in the event loop as errors rather than letting them + * crash the entire program. + */ +class MapvizApplication : public QApplication +{ +public: + MapvizApplication(int &argc, char** argv, + rclcpp::Logger logger = rclcpp::get_logger("mapviz::MapvizApplication")); + + void setLogger(const rclcpp::Logger& logger); +private: + bool notify(QObject* receiver, QEvent* event) override; + + rclcpp::Logger logger_; +}; +} // namespace mapviz + +#endif // MAPVIZ__MAPVIZ_APPLICATION_H_ diff --git a/mapviz/include/mapviz/mapviz_plugin.h b/mapviz/include/mapviz/mapviz_plugin.h new file mode 100644 index 000000000..083397944 --- /dev/null +++ b/mapviz/include/mapviz/mapviz_plugin.h @@ -0,0 +1,392 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ__MAPVIZ_PLUGIN_H_ +#define MAPVIZ__MAPVIZ_PLUGIN_H_ + +// ROS libraries +#include +#include +#include +#include +#include +#include + +#include +#include + +// QT libraries +#include +#include +#include + +// C++ standard libraries +#include +#include + + +#include "mapviz/stopwatch.h" + +namespace mapviz +{ +class MapvizPlugin : public QObject +{ + Q_OBJECT +public: + ~MapvizPlugin() override = default; + + virtual bool Initialize( + std::shared_ptr tf_buffer, + std::shared_ptr tf_listener, + swri_transform_util::TransformManagerPtr tf_manager, + QGLWidget* canvas) + { + tf_buf_ = tf_buffer; + tf_ = tf_listener; + tf_manager_ = tf_manager; + return Initialize(canvas); + } + + virtual void Shutdown() = 0; + + virtual void ClearHistory() {} + + /** + * Draws on the Mapviz canvas using OpenGL commands; this will be called + * before Paint(); + */ + virtual void Draw(double x, double y, double scale) = 0; + + /** + * Draws on the Mapviz canvas using a QPainter; this is called after Draw(). + * You only need to implement this if you're actually using a QPainter. + */ + virtual void Paint(QPainter* /* painter */, double /* x */, + double /* y */, double /* scale */) {} + + void SetUseLatestTransforms(bool value) + { + if (value != use_latest_transforms_) { + use_latest_transforms_ = value; + Q_EMIT UseLatestTransformsChanged(use_latest_transforms_); + } + } + + void SetName(const std::string& name) { name_ = name; } + + std::string Name() const { return name_; } + + void SetType(const std::string& type) { type_ = type; } + + std::string Type() const { return type_; } + + int DrawOrder() const { return draw_order_; } + + void SetDrawOrder(int order) + { + if (draw_order_ != order) { + draw_order_ = order; + Q_EMIT DrawOrderChanged(draw_order_); + } + } + + virtual void SetNode(rclcpp::Node& node) + { + // node_ = node; + node_ = node.shared_from_this(); + } + + void DrawPlugin(double x, double y, double scale) + { + if (visible_ && initialized_) { + meas_transform_.start(); + Transform(); + meas_transform_.stop(); + + meas_draw_.start(); + Draw(x, y, scale); + meas_draw_.stop(); + } + } + + void PaintPlugin(QPainter* painter, double x, double y, double scale) + { + if (visible_ && initialized_) { + meas_transform_.start(); + Transform(); + meas_transform_.stop(); + + meas_paint_.start(); + Paint(painter, x, y, scale); + meas_paint_.start(); + } + } + + void SetTargetFrame(const std::string& frame_id) + { + if (frame_id != target_frame_) { + target_frame_ = frame_id; + + meas_transform_.start(); + Transform(); + meas_transform_.stop(); + + Q_EMIT TargetFrameChanged(target_frame_); + } + } + + bool Visible() const { return visible_; } + + void SetVisible(bool visible) + { + if (visible_ != visible) { + visible_ = visible; + Q_EMIT VisibleChanged(visible_); + } + } + + bool GetTransform( + const rclcpp::Time& stamp, + swri_transform_util::Transform& transform, + bool use_latest_transforms = true) + { + return GetTransform(source_frame_, stamp, transform, use_latest_transforms); + } + + bool GetTransform(const std::string& source, + const rclcpp::Time& stamp, + swri_transform_util::Transform& transform, + bool use_latest_transforms = true) + { + if (!initialized_) { + return false; + } + + tf2::TimePoint time; + rclcpp::Time now = node_->now(); + + if (use_latest_transforms_ && use_latest_transforms) { + time = tf2::TimePointZero; + } + else + { + time = tf2::timeFromSec(stamp.seconds()); + } + + if (tf_manager_->GetTransform( + target_frame_, + source, + time, + transform)) + { + return true; + } else if (time != tf2::TimePointZero) { + rclcpp::Duration elapsed = now - stamp; + + if (elapsed.seconds() < 0.1) + { + // If the stamped transform failed because it is too recent, find the + // most recent transform in the cache instead. + if (tf_manager_->GetTransform( + target_frame_, + source, + tf2::TimePointZero, + transform)) + { + return true; + } + } + } + + return false; + } + + virtual void Transform() = 0; + + virtual void LoadConfig(const YAML::Node& load, const std::string& path) = 0; + virtual void SaveConfig(YAML::Emitter& emitter, const std::string& path) = 0; + + virtual QWidget* GetConfigWidget(QWidget* /* parent */) { return nullptr; } + + virtual void PrintError(const std::string& message) = 0; + virtual void PrintInfo(const std::string& message) = 0; + virtual void PrintWarning(const std::string& message) = 0; + + void SetIcon(IconWidget* icon) { icon_ = icon; } + + void PrintMeasurements() + { + std::string header = type_ + " (" + name_ + ")"; + meas_transform_.printInfo(node_->get_logger(), header + " Transform()"); + meas_paint_.printInfo(node_->get_logger(), header + " Paint()"); + meas_draw_.printInfo(node_->get_logger(), header + " Draw()"); + } + + void PrintErrorHelper( + QLabel *status_label, + const std::string& message, + double throttle = 0.0); + void PrintInfoHelper( + QLabel *status_label, + const std::string& message, + double throttle = 0.0); + void PrintWarningHelper( + QLabel *status_label, + const std::string& message, + double throttle = 0.0); + +public Q_SLOTS: + virtual void DrawIcon() {} + + /** + * Override this to return "true" if you want QPainter support for your + * plugin. + */ + virtual bool SupportsPainting() + { + return false; + } + +Q_SIGNALS: + void DrawOrderChanged(int draw_order); + void SizeChanged(); + void TargetFrameChanged(const std::string& target_frame); + void UseLatestTransformsChanged(bool use_latest_transforms); + void VisibleChanged(bool visible); + + +protected: + bool initialized_; + bool visible_; + + QGLWidget* canvas_; + IconWidget* icon_; + + std::shared_ptr node_; + + std::shared_ptr tf_buf_; + std::shared_ptr tf_; + swri_transform_util::TransformManagerPtr tf_manager_; + + std::string target_frame_; + std::string source_frame_; + std::string type_; + std::string name_; + + bool use_latest_transforms_; + + int draw_order_; + + virtual bool Initialize(QGLWidget* canvas) = 0; + + MapvizPlugin() : + initialized_(false), + visible_(true), + canvas_(nullptr), + icon_(nullptr), + node_(nullptr), + tf_(), + target_frame_(""), + source_frame_(""), + use_latest_transforms_(false), + draw_order_(0) + {} + + private: + // Collect basic profiling info to know how much time each plugin + // spends in Transform(), Paint(), and Draw(). + Stopwatch meas_transform_; + Stopwatch meas_paint_; + Stopwatch meas_draw_; +}; +typedef std::shared_ptr MapvizPluginPtr; + +// Implementation + +inline void MapvizPlugin::PrintErrorHelper(QLabel *status_label, const std::string &message, + double throttle) +{ + if (message == status_label->text().toStdString()) { + return; + } + + auto logger = node_ ? node_->get_logger() : rclcpp::get_logger("mapviz"); + if (throttle > 0.0) { + RCLCPP_ERROR(logger, "Error: %s", message.c_str()); + } else { + RCLCPP_ERROR(logger, "%s", message.c_str()); + } + QPalette p(status_label->palette()); + p.setColor(QPalette::Text, Qt::red); + status_label->setPalette(p); + status_label->setText(message.c_str()); +} + +inline void MapvizPlugin::PrintInfoHelper(QLabel *status_label, const std::string &message, + double throttle) +{ + if (message == status_label->text().toStdString()) { + return; + } + + auto logger = node_ ? node_->get_logger() : rclcpp::get_logger("mapviz"); + if (throttle > 0.0) { + RCLCPP_INFO(logger, "%s", message.c_str()); + } else { + RCLCPP_INFO(logger, "%s", message.c_str()); + } + QPalette p(status_label->palette()); + p.setColor(QPalette::Text, Qt::darkGreen); + status_label->setPalette(p); + status_label->setText(message.c_str()); +} + +inline void MapvizPlugin::PrintWarningHelper(QLabel *status_label, const std::string &message, + double throttle) +{ + if (message == status_label->text().toStdString()) { + return; + } + + auto logger = node_ ? node_->get_logger() : rclcpp::get_logger("mapviz"); + if (throttle > 0.0) { + RCLCPP_WARN(logger, "%s", message.c_str()); + } else { + RCLCPP_WARN(logger, "%s", message.c_str()); + } + QPalette p(status_label->palette()); + p.setColor(QPalette::Text, Qt::darkYellow); + status_label->setPalette(p); + status_label->setText(message.c_str()); +} + +} // namespace mapviz + +#endif // MAPVIZ__MAPVIZ_PLUGIN_H_ + diff --git a/mapviz/include/mapviz/rqt_mapviz.h b/mapviz/include/mapviz/rqt_mapviz.h new file mode 100644 index 000000000..9f83bff0c --- /dev/null +++ b/mapviz/include/mapviz/rqt_mapviz.h @@ -0,0 +1,68 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ__RQT_MAPVIZ_H_ +#define MAPVIZ__RQT_MAPVIZ_H_ + +/* + * The RQT GUI CPP files use the Qt macros "slots" and "signals". These conflict + * with Boost macros of the same name; normally we fix this by adding "-DQT_NO_KEYWORDS" + * in our CMakeLists file, then using Q_SLOTS and Q_SIGNALS in our source code instead. + * Since we can't edit the ROS source code, though, we need to define those macros before + * we include the ROS headers and then undefine them afterwards. + */ +#define slots +#define signals +#include +#undef slots +#undef signals + +#include "mapviz.hpp" + +namespace mapviz +{ +class RqtMapviz : public rqt_gui_cpp::Plugin +{ +Q_OBJECT +public: + RqtMapviz(); + virtual void initPlugin(qt_gui_cpp::PluginContext& context); + virtual void shutdownPlugin(); + virtual void saveSettings( + qt_gui_cpp::Settings& plugin_settings, + qt_gui_cpp::Settings& instance_settings) const; + virtual void restoreSettings( + const qt_gui_cpp::Settings& plugin_settings, + const qt_gui_cpp::Settings& instance_settings); +private: + Mapviz* widget_; +}; +} // namespace mapviz + +#endif // MAPVIZ__RQT_MAPVIZ_H_ diff --git a/mapviz/include/mapviz/select_frame_dialog.h b/mapviz/include/mapviz/select_frame_dialog.h new file mode 100644 index 000000000..50e1676ec --- /dev/null +++ b/mapviz/include/mapviz/select_frame_dialog.h @@ -0,0 +1,127 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** +#ifndef MAPVIZ__SELECT_FRAME_DIALOG_H_ +#define MAPVIZ__SELECT_FRAME_DIALOG_H_ + +#include + +#include + +#include +#include +#include + + +QT_BEGIN_NAMESPACE +class QLineEdit; +class QListWidget; +class QPushButton; +QT_END_NAMESPACE + +namespace mapviz +{ +/** + * Provides a dialog for the user to select one or more TF frames. + * Several static functions are provided that can be used instead of + * instantiating the class directly. + */ +class SelectFrameDialog : public QDialog +{ + Q_OBJECT; + + public: + /** + * Present the user with a dialog to select a single frame. + * + * If the user cancels the selection or doesn't make a valid + * selection, the returned string be empty. + */ + static std::string selectFrame( + std::shared_ptr tf_buffer, + QWidget *parent = nullptr); + + /** + * Present the user with a dialog to select a multiple TF frames. + * + * If the user cancels the selection or doesn't make a valid + * selection, the returned vector will be empty. + */ + static std::vector selectFrames( + std::shared_ptr tf_buffer, + QWidget *parent = nullptr); + + /** + * Constructor for the SelectFrameDialog. + */ + explicit SelectFrameDialog(std::shared_ptr tf_buffer, + QWidget *parent = nullptr); + + /** + * Choose whether the user can select one (allow=false) or multiple + * (allow=true) frames. The default is false. + */ + void allowMultipleFrames(bool allow); + + /** + * Returns the currently selected frame. If multiple frames are + * allowed, this will only return the first selected element. If + * there is no selection, the returned info will have an empty frame + * name and datatype. + */ + std::string selectedFrame() const; + /** + * Returns the currently selected frames. If there is no selection, + * the returned vector will be empty. + */ + std::vector selectedFrames() const; + + private: + void timerEvent(QTimerEvent *) override; + void closeEvent(QCloseEvent *) override; + + std::vector filterFrames( + const std::vector &) const; + + private Q_SLOTS: + void fetchFrames(); + void updateDisplayedFrames(); + + private: + std::shared_ptr tf_buf_; + std::vector known_frames_; + std::vector displayed_frames_; + int fetch_frames_timer_id_; + + QPushButton *ok_button_; + QPushButton *cancel_button_; + QListWidget *list_widget_; + QLineEdit *name_filter_; +}; // class SelectFrameDialog +} // namespace mapviz +#endif // MAPVIZ__SELECT_FRAME_DIALOG_H_ diff --git a/mapviz/include/mapviz/select_service_dialog.h b/mapviz/include/mapviz/select_service_dialog.h new file mode 100644 index 000000000..efa6071ff --- /dev/null +++ b/mapviz/include/mapviz/select_service_dialog.h @@ -0,0 +1,174 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ__SELECT_SERVICE_DIALOG_H_ +#define MAPVIZ__SELECT_SERVICE_DIALOG_H_ + +#include + +#include +#include +#include + +#include +#include +#include +#include + +QT_BEGIN_NAMESPACE +class QLineEdit; +class QListWidget; +class QPushButton; +QT_END_NAMESPACE + +// This is ugly, but necessary in order to be able to send a std::vector +// via a queued signal/slot connection. +typedef std::vector ServiceStringVector; +Q_DECLARE_METATYPE(ServiceStringVector) + +namespace mapviz +{ +/** + * Enumerating services requires making a remote service call; doing this in the GUI thread + * could cause Mapviz to block and become unresponsive, so it is offloaded to another thread. + */ +class ServiceUpdaterThread : public QThread +{ + Q_OBJECT +public: + ServiceUpdaterThread( + const std::shared_ptr& nh, + const std::string& allowed_datatype, + QObject* parent) : + QThread(parent), + nh_(nh), + allowed_datatype_(allowed_datatype) + { + } + void run() override; + +Q_SIGNALS: + void servicesFetched(ServiceStringVector services); + void fetchingFailed(const QString error_msg); + +private: + std::shared_ptr nh_; + const std::string& allowed_datatype_; +}; + +/** + * Provides a dialog that the user can use to either list all known ROS services + * or all ROS services that handle a particular type. + */ +class SelectServiceDialog : public QDialog +{ + Q_OBJECT +public: + /** + * Convenience function for creating a dialog that will prompt the user to select + * a service and then return the value. If no service was selected, the returned + * value will be empty. + * @param[in] datatype The type of service to search for; if empty, it will show + * the user a list of all services. + * @param[in] parent The dialog's parent widget. + * @return The name of the selected service, or an empty string if there was none. + */ + static std::string selectService(rclcpp::Node::SharedPtr node, const std::string& datatype, QWidget* parent = 0); + + /** + * Constructs a new SelectServiceDialog and automatically starts a timer that + * will refresh the list of services every 5 seconds. + * @param[in] datatype The type of service to search for; if empty, it will show + * the user a list of all services. + * @param[in] parent The dialog's parent widget. + */ + explicit SelectServiceDialog(const rclcpp::Node::SharedPtr& node, + const std::string& datatype = "", + QWidget* parent = nullptr); + ~SelectServiceDialog() override; + + /** + * Set a datatype filter to limit displayed topics based on their + * types. If the vector is empty (default), the dialog will display + * all available topics. + * @param[in] datatype The type of service to search for. + */ + void setDatatypeFilter(const std::string& datatype); + + /** + * Gets the service the user had selected, or an empty string if there was + * none. + * @return The selected service. + */ + std::string selectedService() const; + +private Q_SLOTS: + /** + * If no worker thread is currently active, this will start a worker thread + * that will fetch all of the services matching the known data type. + */ + void fetchServices(); + /** + * Updates the list of services displayed to the user based on the list + * of known services and the current filter value. + */ + void updateDisplayedServices(); + /** + * Sets our list of known services. + */ + void updateKnownServices(ServiceStringVector services); + /** + * Displays a message box indicating that there was an error and stops our + * update timer. + */ + void displayUpdateError(const QString&); + +private: + std::vector filterServices(); + void timerEvent(QTimerEvent *) override; + void closeEvent(QCloseEvent *) override; + + std::shared_ptr nh_; + + std::string allowed_datatype_; + std::vector displayed_services_; + std::vector known_services_; + + int fetch_services_timer_id_; + + QPushButton *cancel_button_; + QListWidget *list_widget_; + QLineEdit *name_filter_; + QPushButton *ok_button_; + std::shared_ptr worker_thread_; +}; +} // namespace mapviz + +#endif // MAPVIZ__SELECT_SERVICE_DIALOG_H_ diff --git a/mapviz/include/mapviz/select_topic_dialog.h b/mapviz/include/mapviz/select_topic_dialog.h new file mode 100644 index 000000000..dd7a80f40 --- /dev/null +++ b/mapviz/include/mapviz/select_topic_dialog.h @@ -0,0 +1,197 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** +#ifndef MAPVIZ__SELECT_TOPIC_DIALOG_H_ +#define MAPVIZ__SELECT_TOPIC_DIALOG_H_ + +#include + +#include + +#include +#include +#include +#include +#include + +QT_BEGIN_NAMESPACE +class QLineEdit; +class QListWidget; +class QPushButton; +QT_END_NAMESPACE + +namespace mapviz +{ +/** + * Provides a dialog for the user to select one or more topics. + * Several static functions are provided that can be used instead of + * instantiating the class directly. + */ +class SelectTopicDialog : public QDialog +{ + Q_OBJECT; + + public: + /** + * Present the user with a dialog to select a single topic. This is + * convenience wrapper for the common case where only one datatype + * is allowed. + * + * If the user cancels the selection or doesn't make a valid + * selection, the topic and datatype fields of the returned topic + * info will be empty. + */ + static std::string selectTopic( + const rclcpp::Node::SharedPtr& node, + const std::string &datatype, + QWidget *parent = nullptr); + + /** + * Present the user with a dialog to select a single topic This is a + * convenience wrapper for the common case where two datatypes are allowed. + * + * If the user cancels the selection or doesn't make a valid + * selection, the topic and datatype fields of the returned topic + * info will be empty. + */ + static std::string selectTopic( + const rclcpp::Node::SharedPtr& node, + const std::string &datatype1, + const std::string &datatype2, + QWidget *parent = nullptr); + + /** + * Present the user with a dialog to select a single topic. + * + * If the user cancels the selection or doesn't make a valid + * selection, the topic and datatype fields of the returned topic + * info will be empty. + */ + static std::string selectTopic( + const rclcpp::Node::SharedPtr& node, + const std::vector &datatypes, + QWidget *parent = nullptr); + + /** + * Present the user with a dialog to select a multiple topics. This + * is a convenience wrapper for the common case where only one + * datatype is allowed. + * + * If the user cancels the selection or doesn't make a valid + * selection, the returned vector will be empty. + */ + static std::vector selectTopics( + const rclcpp::Node::SharedPtr& node, + const std::string &datatype, + QWidget *parent = nullptr); + + /** + * Present the user with a dialog to select a multiple topics. This + * is a convenience wrapper for the common case where two datatypes + * are allowed. + * + * If the user cancels the selection or doesn't make a valid + * selection, the returned vector will be empty. + */ + static std::vector selectTopics( + const rclcpp::Node::SharedPtr& node, + const std::string &datatype1, + const std::string &datatype2, + QWidget *parent = nullptr); + + /** + * Present the user with a dialog to select a multiple topics. + * + * If the user cancels the selection or doesn't make a valid + * selection, the returned vector will be empty. + */ + static std::vector selectTopics( + const rclcpp::Node::SharedPtr& node, + const std::vector &datatypes, + QWidget *parent = nullptr); + + /** + * Constructor for the SelectTopicDialog. + */ + explicit SelectTopicDialog(const rclcpp::Node::SharedPtr& node, + QWidget *parent = nullptr); + + /** + * Choose whether the user can select one (allow=false) or multiple + * (allow=true) topics. The default is false. + */ + void allowMultipleTopics(bool allow); + + /** + * Set a datatype filter to limit displayed topics based on their + * types. If the vector is empty (default), the dialog will display + * all available topics. + */ + void setDatatypeFilter(const std::vector &datatypes); + + /** + * Returns the currently selected topic. If multiple topics are + * allowed, this will only return the first selected element. If + * there is no selection, the returned info will have an empty topic + * name and datatype. + */ + std::string selectedTopic() const; + /** + * Returns the currently selected topics. If there is no selection, + * the returned vector will be empty. + */ + std::vector selectedTopics() const; + + private: + void timerEvent(QTimerEvent *) override; + void closeEvent(QCloseEvent *) override; + + std::vector filterTopics( + const std::map> &) const; + + private Q_SLOTS: + void fetchTopics(); + void updateDisplayedTopics(); + + private: + std::set allowed_datatypes_; + std::map> known_topics_; + + std::vector displayed_topics_; + int fetch_topics_timer_id_; + + std::shared_ptr nh_; // This may need to be a shared instance of Mapviz's node + + QPushButton *ok_button_; + QPushButton *cancel_button_; + QListWidget *list_widget_; + QLineEdit *name_filter_; +}; // class SelectTopicDialog +} // namespace mapviz + +#endif // MAPVIZ__SELECT_TOPIC_DIALOG_H_ diff --git a/mapviz/include/mapviz/stopwatch.h b/mapviz/include/mapviz/stopwatch.h new file mode 100644 index 000000000..b6959b893 --- /dev/null +++ b/mapviz/include/mapviz/stopwatch.h @@ -0,0 +1,119 @@ +// ***************************************************************************** +// +// Copyright (c) 2017, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** +#ifndef MAPVIZ__STOPWATCH_H_ +#define MAPVIZ__STOPWATCH_H_ + +#include + +#include +#include + + +namespace mapviz +{ +/* This class measures the wall time of an interval and keeps track of + * the number of intervals, the average duration, and the maximum + * duration. This is used to provide some simple measurements to keep + * an eye on performance. + */ +class Stopwatch +{ + public: + Stopwatch() + : + count_(0), + clock(), + total_time_(0, 0), + max_time_(0, 0), + start_(0, 0) + { + } + + /* Start measuring a new time interval. */ + void start() + { + start_ = clock.now(); + } + + /* End the current time interval and update the measurements. + * Behavior is undefined if start() was not called prior to this. + */ + void stop() + { + rclcpp::Duration dt = clock.now() - start_; + count_ += 1; + total_time_ = total_time_ + dt; + max_time_ = std::max(max_time_, dt); + } + + /* Return the number of intervals measured. */ + int count() const { return count_; } + + /* Returns the longest observed duration. */ + rclcpp::Duration maxTime() const {return max_time_;} + + /* Returns the average duration spent in the interval. */ + rclcpp::Duration avgTime() const + { + if (count_) { + return total_time_*(1.0/count_); + } else { + return rclcpp::Duration(0, 0); + } + } + + /* Print measurement info to the ROS console. */ + void printInfo(rclcpp::Logger logger, const std::string &name) const + { + if (count_) { + RCLCPP_INFO(logger, + "%s -- calls: %d, avg time: %.2fms, max time: %.2fms", + name.c_str(), + count_, + avgTime().seconds()*1000.0, + maxTime().seconds()*1000.0); + } else { + RCLCPP_INFO(logger, + "%s -- calls: %d, avg time: --ms, max time: --ms", + name.c_str(), + count_); + } + } + + private: + int count_; + rclcpp::Clock clock; + rclcpp::Duration total_time_; + rclcpp::Duration max_time_; + + rclcpp::Time start_; +}; // class PluginInstrumentation +} // namespace mapviz + +#endif // MAPVIZ__STOPWATCH_H_ diff --git a/mapviz/include/mapviz/video_writer.h b/mapviz/include/mapviz/video_writer.h new file mode 100644 index 000000000..aa122b2c5 --- /dev/null +++ b/mapviz/include/mapviz/video_writer.h @@ -0,0 +1,70 @@ +// ***************************************************************************** +// +// Copyright (c) 2017, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ__VIDEO_WRITER_H_ +#define MAPVIZ__VIDEO_WRITER_H_ + +#include +#include +#include + +#include +#include + +#ifndef Q_MOC_RUN +#include +#endif + +namespace mapviz +{ +class VideoWriter : public QObject +{ + Q_OBJECT + +public: + VideoWriter() : + video_mutex_(QMutex::Recursive) + {} + + bool initializeWriter(const std::string& directory, int width, int height); + bool isRecording(); + void stop(); + +public Q_SLOTS: + void processFrame(QImage frame); + +private: + int height_; + int width_; + QMutex video_mutex_; + std::shared_ptr video_writer_; +}; +} // namespace mapviz + +#endif // MAPVIZ__VIDEO_WRITER_H_ diff --git a/mapviz/include/mapviz/widgets.h b/mapviz/include/mapviz/widgets.h new file mode 100644 index 000000000..fb75ac544 --- /dev/null +++ b/mapviz/include/mapviz/widgets.h @@ -0,0 +1,171 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_WIDGETS_H_ +#define MAPVIZ_WIDGETS_H_ + +// QT libraries +#include +#include +#include +#include +#include +#include +#include +#include + +namespace mapviz +{ +class PluginConfigList : public QListWidget +{ + Q_OBJECT + +public: + explicit PluginConfigList(QWidget *parent = nullptr) : QListWidget(parent) {} + PluginConfigList() = default; + + void UpdateIndices() + { + for (int i = 0; i < count(); i++) { + item(i)->setData(Qt::UserRole, QVariant((static_cast(i)))); + } + } + +Q_SIGNALS: + void ItemsMoved(); + +protected: + void dropEvent(QDropEvent* event) override + { + QListWidget::dropEvent(event); + + UpdateIndices(); + + Q_EMIT ItemsMoved(); + } +}; + +class PluginConfigListItem : public QListWidgetItem +{ +public: + explicit PluginConfigListItem(QListWidget *parent = nullptr) : QListWidgetItem(parent) {} + + bool operator< (const QListWidgetItem & other) const override + { + return data(Qt::UserRole).toFloat() < other.data(Qt::UserRole).toFloat(); + } +}; + +class SingleClickLabel : public QLabel +{ + Q_OBJECT + +public: + explicit SingleClickLabel(QWidget *parent = 0, Qt::WindowFlags flags = Qt::WindowFlags()) : + QLabel(parent, flags) {} + + ~SingleClickLabel() override = default; + +Q_SIGNALS: + void Clicked(); + +protected: + void mousePressEvent(QMouseEvent*) override + { + Q_EMIT Clicked(); + } +}; + +class DoubleClickWidget : public QWidget +{ + Q_OBJECT + +public: + explicit DoubleClickWidget(QWidget *parent = 0, Qt::WindowFlags flags = Qt::WindowFlags()) : + QWidget(parent, flags) {} + + ~DoubleClickWidget() override = default; + +Q_SIGNALS: + void DoubleClicked(); + void RightClicked(); + +protected: + void mouseDoubleClickEvent(QMouseEvent* event) override + { + if (event->button() == Qt::LeftButton) { + Q_EMIT DoubleClicked(); + } + } + + void mouseReleaseEvent(QMouseEvent* event) override + { + if (event->button() == Qt::RightButton) { + Q_EMIT RightClicked(); + } + } +}; + +class IconWidget : public QWidget +{ + Q_OBJECT + +public: + explicit IconWidget(QWidget *parent = nullptr, Qt::WindowFlags flags = Qt::WindowFlags()) : + QWidget(parent, flags) + { + pixmap_ = QPixmap(16, 16); + pixmap_.fill(Qt::transparent); + } + + ~IconWidget() override = default; + + void SetPixmap(QPixmap pixmap) + { + pixmap_ = pixmap; + update(); + } + +protected: + void paintEvent(QPaintEvent*) override + { + QPainter painter(this); + painter.fillRect(0, 0, width(), height(), palette().color(QPalette::Button)); + + int x_offset = (width() - pixmap_.width()) / 2; + int y_offset = (height() - pixmap_.height()) / 2; + + painter.drawPixmap(x_offset, y_offset, pixmap_); + } + + QPixmap pixmap_; +}; +} // namespace mapviz + +#endif // MAPVIZ__WIDGETS_H_ diff --git a/mapviz/launch/mapviz.launch.py b/mapviz/launch/mapviz.launch.py new file mode 100644 index 000000000..2f9d98512 --- /dev/null +++ b/mapviz/launch/mapviz.launch.py @@ -0,0 +1,41 @@ +import launch +import launch.actions +import launch.substitutions +import launch_ros.actions + + +def generate_launch_description(): + return launch.LaunchDescription([ + launch_ros.actions.Node( + package="mapviz", + executable="mapviz", + name="mapviz", + ), + launch_ros.actions.Node( + package="swri_transform_util", + executable="initialize_origin.py", + name="initialize_origin", + parameters=[ + {"name": "local_xy_frame", "value": "map"}, + {"name": "local_xy_origin", "value": "swri"}, + {"name": "local_xy_origins", "value": """[ + {"name": "swri", + "latitude": 29.45196669, + "longitude": -98.61370577, + "altitude": 233.719, + "heading": 0.0}, + {"name": "back_40", + "latitude": 29.447507, + "longitude": -98.629367, + "altitude": 200.0, + "heading": 0.0} + ]"""} + ] + ), + launch_ros.actions.Node( + package="tf2_ros", + executable="static_transform_publisher", + name="swri_transform", + arguments=["0", "0", "0", "0", "0", "0", "map", "origin"] + ) + ]) diff --git a/mapviz/launch/mapviz.launch.xml b/mapviz/launch/mapviz.launch.xml new file mode 100644 index 000000000..e02dc6301 --- /dev/null +++ b/mapviz/launch/mapviz.launch.xml @@ -0,0 +1,27 @@ + + + + + + + + + + + + + diff --git a/mapviz/mainpage.dox b/mapviz/mainpage.dox new file mode 100644 index 000000000..b06ce90e5 --- /dev/null +++ b/mapviz/mainpage.dox @@ -0,0 +1,19 @@ +/** +\mainpage +\section mapviz + +\b mapviz is a set of API's for ... + +This package... (see sumet_perception/material_classification/mainpage.dox for example description) + + +\subsection codeapi Code API + +The C++ API consists of the following main classes: + +- \b ConfigItem - \copybrief ConfigItem +- \b MapCanvas - \copybrief MapCanvas +- \b mapviz::MapvizPlugin - \copybrief mapviz::MapvizPlugin +- \b Mapviz - \copybrief Mapviz + +**/ diff --git a/mapviz/package.xml b/mapviz/package.xml new file mode 100644 index 000000000..f72b3b345 --- /dev/null +++ b/mapviz/package.xml @@ -0,0 +1,50 @@ + + mapviz + 2.3.0 + + + mapviz + + + Marc Alban + P. J. Reed + Southwest Research Institute + BSD + https://github.com/swri-robotics/mapviz + + ament_cmake + pkg-config + qt5-qmake + + libqt5-core + libqt5-opengl-dev + ros_environment + + cv_bridge + geometry_msgs + glut + image_transport + libglew-dev + libxi-dev + libxmu-dev + mapviz_interfaces + marti_common_msgs + pluginlib + rclcpp + rqt_gui_cpp + rqt_gui + std_srvs + swri_math_util + swri_transform_util + tf2 + tf2_geometry_msgs + tf2_ros + yaml-cpp + + libqt5-opengl + + + ament_cmake + + + diff --git a/mapviz/plugin.xml b/mapviz/plugin.xml new file mode 100644 index 000000000..3e9e934d7 --- /dev/null +++ b/mapviz/plugin.xml @@ -0,0 +1,17 @@ + + + + Mapviz is a ROS based visualization tool with a plug-in system similar to RVIZ focused on visualizing 2D data. + + + + + folder + Plugins related to visualization. + + + image-x-generic + 2D visualization tool + + + diff --git a/mapviz/src/color_button.cpp b/mapviz/src/color_button.cpp new file mode 100644 index 000000000..5042f1d6e --- /dev/null +++ b/mapviz/src/color_button.cpp @@ -0,0 +1,75 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** +#include + +#include + +namespace mapviz +{ +ColorButton::ColorButton(QWidget *parent) + : + QPushButton(parent) +{ + setColor(Qt::black); + QObject::connect(this, SIGNAL(clicked(bool)), + this, SLOT(handleClicked())); +} + +void ColorButton::setColor(const QColor &color) +{ + if (!color.isValid() || color == color_) { + return; + } + + color_ = color; + // This was a very strange bug. On initialization, the constructor + // would set the stylesheet to black, then the external owner would + // call setColor to change the color to something else. We would + // properly set the internal color_ and stylesheet, but it would + // continue to display black. If the user changed the color, it + // would change properly. Calling setStylesheet() twice fixes the + // behavior. + setStyleSheet("background: " + color_.name()); + setStyleSheet("background: " + color_.name()); + Q_EMIT colorChanged(color_); +} + +void ColorButton::handleClicked() +{ + // Note: We do not pass ourself as the parent or else the dialog + // will inherit our color as the background! + QColor new_color = QColorDialog::getColor(color_); + if (!new_color.isValid() || new_color == color_) { + return; + } + setColor(new_color); + Q_EMIT colorEdited(new_color); +} +} // namespace mapviz diff --git a/mapviz/src/config_item.cpp b/mapviz/src/config_item.cpp new file mode 100644 index 000000000..e17eeb04d --- /dev/null +++ b/mapviz/src/config_item.cpp @@ -0,0 +1,122 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include +#include +#include +#include + +namespace mapviz +{ + ConfigItem::ConfigItem(QWidget *parent, Qt::WindowFlags flags) : + QWidget(parent, flags), + item_(nullptr), + visible_(true) + { + ui_.setupUi(this); + + edit_name_action_ = new QAction("Edit Name", this); + remove_item_action_ = new QAction("Remove", this); + remove_item_action_->setIcon(QIcon(":/images/remove-icon-th.png")); + + connect(edit_name_action_, SIGNAL(triggered()), this, SLOT(EditName())); + connect(remove_item_action_, SIGNAL(triggered()), this, SLOT(Remove())); + } + + void ConfigItem::ToggleDraw(bool toggled) + { + if (visible_ != toggled) { + visible_ = toggled; + if (ui_.show->isChecked() != toggled) { + ui_.show->setChecked(toggled); + } + + Q_EMIT ToggledDraw(item_, toggled); + } + } + + void ConfigItem::contextMenuEvent(QContextMenuEvent* event) + { + QMenu menu(this); + menu.addAction(edit_name_action_); + menu.addAction(remove_item_action_); + menu.exec(event->globalPos()); + } + + void ConfigItem::SetName(QString name) + { + name_ = name; + ui_.namelabel->setText(type_ + " (" + name_ + ")"); + } + + void ConfigItem::SetType(QString type) + { + type_ = type; + ui_.namelabel->setText(type_ + " (" + name_ + ")"); + } + + void ConfigItem::SetWidget(QWidget* widget) + { + ui_.label->hide(); + ui_.content_layout->addWidget(widget); + } + + void ConfigItem::EditName() + { + bool ok; + QString text = QInputDialog::getText( + this, + tr("Set Display name"), + tr(""), + QLineEdit::Normal, + name_, &ok); + + if (ok && !text.isEmpty()) { + SetName(text); + } + } + + void ConfigItem::Remove() + { + Q_EMIT RemoveRequest(item_); + } + + void ConfigItem::Hide() + { + if (!ui_.content->isHidden()) { + ui_.content->hide(); + ui_.signlabel->setText(" + "); + } else { + ui_.content->show(); + ui_.signlabel->setText(" - "); + } + + Q_EMIT UpdateSizeHint(); + } +} // namespace mapviz diff --git a/mapviz/src/configitem.ui b/mapviz/src/configitem.ui new file mode 100644 index 000000000..dfd41b857 --- /dev/null +++ b/mapviz/src/configitem.ui @@ -0,0 +1,797 @@ + + + configitem + + + + 0 + 0 + 400 + 300 + + + + + 0 + 0 + + + + Form + + + + 0 + + + 2 + + + 0 + + + 0 + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 169 + 169 + 169 + + + + + + + 234 + 230 + 222 + + + + + + + 195 + 191 + 185 + + + + + + + 78 + 76 + 74 + + + + + + + 104 + 102 + 99 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 169 + 169 + 169 + + + + + + + 169 + 169 + 169 + + + + + + + 0 + 0 + 0 + + + + + + + 205 + 204 + 201 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 169 + 169 + 169 + + + + + + + 234 + 230 + 222 + + + + + + + 195 + 191 + 185 + + + + + + + 78 + 76 + 74 + + + + + + + 104 + 102 + 99 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 169 + 169 + 169 + + + + + + + 169 + 169 + 169 + + + + + + + 0 + 0 + 0 + + + + + + + 205 + 204 + 201 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 78 + 76 + 74 + + + + + + + 169 + 169 + 169 + + + + + + + 234 + 230 + 222 + + + + + + + 195 + 191 + 185 + + + + + + + 78 + 76 + 74 + + + + + + + 104 + 102 + 99 + + + + + + + 78 + 76 + 74 + + + + + + + 255 + 255 + 255 + + + + + + + 78 + 76 + 74 + + + + + + + 169 + 169 + 169 + + + + + + + 169 + 169 + 169 + + + + + + + 0 + 0 + 0 + + + + + + + 156 + 153 + 148 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + QWidget { background-color : DarkGray ;} + + + + 0 + + + QLayout::SetDefaultConstraint + + + 0 + + + 0 + + + 0 + + + 0 + + + + + + + + + + 211 + 211 + 211 + + + + + + + 162 + 159 + 154 + + + + + + + 211 + 211 + 211 + + + + + + + 211 + 211 + 211 + + + + + + + + + 211 + 211 + 211 + + + + + + + 162 + 159 + 154 + + + + + + + 211 + 211 + 211 + + + + + + + 211 + 211 + 211 + + + + + + + + + 211 + 211 + 211 + + + + + + + 162 + 159 + 154 + + + + + + + 211 + 211 + 211 + + + + + + + 211 + 211 + 211 + + + + + + + + + DejaVu Sans Mono + 9 + + + + QLabel { background-color : LightGray ; } + + + - + + + + + + + + 0 + 0 + + + + + Ubuntu + 9 + 75 + true + + + + Name + + + + + + + + 0 + 0 + + + + + 20 + 20 + + + + + + + + + 0 + 0 + + + + + 20 + 16777215 + + + + + + + true + + + false + + + + + + + + + + + 0 + 0 + + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + + 0 + 0 + + + + Config goes here... + + + + + + + + + + + mapviz::DoubleClickWidget + QWidget +
      mapviz/widgets.h
      + 1 + + DoubleClicked() + RightClicked() + +
      + + mapviz::SingleClickLabel + QLabel +
      mapviz/widgets.h
      +
      + + mapviz::IconWidget + QWidget +
      mapviz/widgets.h
      + 1 +
      +
      + + + + header + DoubleClicked() + configitem + Hide() + + + 169 + 22 + + + 2 + 123 + + + + + signlabel + Clicked() + configitem + Hide() + + + 20 + 20 + + + 1 + 82 + + + + + show + toggled(bool) + configitem + ToggleDraw(bool) + + + 385 + 11 + + + 401 + 210 + + + + + + Hide() + ToggleDraw(bool) + EditName() + +
      diff --git a/mapviz/src/map_canvas.cpp b/mapviz/src/map_canvas.cpp new file mode 100644 index 000000000..e618bf075 --- /dev/null +++ b/mapviz/src/map_canvas.cpp @@ -0,0 +1,640 @@ + // ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + + +#include +#include +#include + +#include + +#include +#include + + +// C++ standard libraries +#include +#include +#include +#include + + +namespace mapviz +{ + + +bool compare_plugins(MapvizPluginPtr a, MapvizPluginPtr b) +{ + return a->DrawOrder() < b->DrawOrder(); +} + +/** + * Convenience method for generating a geometry_msgs::msg::PointStamped in one line, + * since we do this a few times. + * @param x + * @param y + * @param z + * @return + */ +geometry_msgs::msg::PointStamped make_point_stamped(double x, double y, double z) +{ + geometry_msgs::msg::PointStamped point; + point.point.x = x; + point.point.y = y; + point.point.z = z; + return point; +} + +/** + * Convenience method for converting a tf2::Stamped object into + * the equivalent ROS message. + * @param transform The source object + * @return That tf as a ROS message + */ +auto tf2_to_msg(const tf2::Stamped& transform) +{ + return tf2::toMsg(transform); +} + +MapCanvas::MapCanvas(QWidget* parent) : + QGLWidget(QGLFormat(QGL::SampleBuffers), parent), + has_pixel_buffers_(false), + pixel_buffer_size_(0), + pixel_buffer_ids_(), + pixel_buffer_index_(0), + capture_frames_(false), + initialized_(false), + fix_orientation_(false), + rotate_90_(false), + enable_antialiasing_(true), + mouse_button_(Qt::NoButton), + mouse_pressed_(false), + mouse_x_(0), + mouse_y_(0), + mouse_previous_y_(0), + mouse_hovering_(false), + mouse_hover_x_(0), + mouse_hover_y_(0), + offset_x_(0), + offset_y_(0), + drag_x_(0), + drag_y_(0), + view_center_x_(0), + view_center_y_(0), + view_scale_(1), + view_left_(-25), + view_right_(25), + view_top_(10), + view_bottom_(-10), + scene_left_(-10), + scene_right_(10), + scene_top_(10), + scene_bottom_(-10) +{ + RCLCPP_INFO(rclcpp::get_logger("mapviz"), "View scale: %f meters/pixel", view_scale_); + setMouseTracking(true); + + + QObject::connect(&frame_rate_timer_, SIGNAL(timeout()), this, SLOT(update())); + setFrameRate(50.0); + frame_rate_timer_.start(); + setFocusPolicy(Qt::StrongFocus); +} + +MapCanvas::~MapCanvas() +{ + if (pixel_buffer_size_ != 0) { + glDeleteBuffersARB(2, pixel_buffer_ids_); + } +} + +void MapCanvas::InitializeTf(std::shared_ptr tf) +{ + tf_buf_ = tf; +} + +void MapCanvas::InitializePixelBuffers() +{ + if (has_pixel_buffers_) { + int32_t buffer_size = width() * height() * 4; + + if (pixel_buffer_size_ != buffer_size) { + if (pixel_buffer_size_ != 0) { + glDeleteBuffersARB(2, pixel_buffer_ids_); + } + + glGenBuffersARB(2, pixel_buffer_ids_); + glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[0]); + glBufferDataARB(GL_PIXEL_PACK_BUFFER_ARB, buffer_size, 0, GL_STREAM_READ_ARB); + glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[1]); + glBufferDataARB(GL_PIXEL_PACK_BUFFER_ARB, buffer_size, 0, GL_STREAM_READ_ARB); + glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, 0); + + pixel_buffer_size_ = buffer_size; + } + } +} + +void MapCanvas::initializeGL() +{ + GLenum err = glewInit(); + if (GLEW_OK != err) { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "Error: %s\n", glewGetErrorString(err)); + } else { + // Check if pixel buffers are available for asynchronous capturing + std::string extensions = (const char*)glGetString(GL_EXTENSIONS); + has_pixel_buffers_ = extensions.find("GL_ARB_pixel_buffer_object") != std::string::npos; + } + + glClearColor(0.58f, 0.56f, 0.5f, 1); + if (enable_antialiasing_) { + glEnable(GL_MULTISAMPLE); + glEnable(GL_POINT_SMOOTH); + glEnable(GL_LINE_SMOOTH); + glEnable(GL_POLYGON_SMOOTH); + glHint(GL_LINE_SMOOTH_HINT, GL_NICEST); + glHint(GL_POINT_SMOOTH_HINT, GL_NICEST); + glHint(GL_POLYGON_SMOOTH_HINT, GL_NICEST); + } else { + glDisable(GL_MULTISAMPLE); + glDisable(GL_POINT_SMOOTH); + glDisable(GL_LINE_SMOOTH); + glDisable(GL_POLYGON_SMOOTH); + } + initGlBlending(); + + initialized_ = true; +} + +void MapCanvas::initGlBlending() +{ + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + glDepthFunc(GL_NEVER); + glDisable(GL_DEPTH_TEST); +} + +void MapCanvas::resizeGL(int w, int h) +{ + UpdateView(); +} + +void MapCanvas::CaptureFrame(bool force) +{ + // Ensure the pixel size is actually 4 + glPixelStorei(GL_PACK_ALIGNMENT, 4); + + if (has_pixel_buffers_ && !force) { + InitializePixelBuffers(); + + pixel_buffer_index_ = (pixel_buffer_index_ + 1) % 2; + int32_t next_index = (pixel_buffer_index_ + 1) % 2; + + glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[pixel_buffer_index_]); + glReadPixels(0, 0, width(), height(), GL_BGRA, GL_UNSIGNED_BYTE, 0); + glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, pixel_buffer_ids_[next_index]); + GLubyte* data = reinterpret_cast( + glMapBufferARB(GL_PIXEL_PACK_BUFFER_ARB, GL_READ_ONLY_ARB)); + if (data) { + capture_buffer_.resize(pixel_buffer_size_); + + memcpy(&capture_buffer_[0], data, pixel_buffer_size_); + + glUnmapBufferARB(GL_PIXEL_PACK_BUFFER_ARB); + } + glBindBufferARB(GL_PIXEL_PACK_BUFFER_ARB, 0); + } else { + int32_t buffer_size = width() * height() * 4; + capture_buffer_.clear(); + capture_buffer_.resize(buffer_size); + + glReadPixels(0, 0, width(), height(), GL_BGRA, GL_UNSIGNED_BYTE, &capture_buffer_[0]); + } +} + +void MapCanvas::paintEvent(QPaintEvent* event) +{ + if (capture_frames_) { + CaptureFrame(); + } + + QPainter p(this); + p.setRenderHints(QPainter::Antialiasing | + QPainter::TextAntialiasing | + QPainter::SmoothPixmapTransform, + enable_antialiasing_); + p.beginNativePainting(); + // .beginNativePainting() disables blending and clears a handful of other + // values that we need to manually reset. + initGlBlending(); + glMatrixMode(GL_MODELVIEW); + glPushMatrix(); + + glClearColor(bg_color_.redF(), bg_color_.greenF(), bg_color_.blueF(), 1.0f); + UpdateView(); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + TransformTarget(&p); + + // Draw test pattern + glLineWidth(3); + glBegin(GL_LINES); + // Red line to the right + glColor3f(1, 0, 0); + glVertex2f(0, 0); + glVertex2f(20, 0); + + // Green line to the top + glColor3f(0, 1, 0); + glVertex2f(0, 0); + glVertex2f(0, 20); + glEnd(); + + std::list::iterator it; + for (it = plugins_.begin(); it != plugins_.end(); ++it) { + // Before we let a plugin do any drawing, push all matrices and attributes. + // This helps to ensure that plugins can't accidentally mess something up + // for the next plugin. + pushGlMatrices(); + + (*it)->DrawPlugin(view_center_x_, view_center_y_, view_scale_); + + if ((*it)->SupportsPainting()) { + p.endNativePainting(); + (*it)->PaintPlugin(&p, view_center_x_, view_center_y_, view_scale_); + p.beginNativePainting(); + initGlBlending(); + } + + popGlMatrices(); + } + + glMatrixMode(GL_MODELVIEW); + glPopMatrix(); + p.endNativePainting(); +} + +void MapCanvas::pushGlMatrices() +{ + glMatrixMode(GL_TEXTURE); + glPushMatrix(); + glMatrixMode(GL_PROJECTION); + glPushMatrix(); + glMatrixMode(GL_MODELVIEW); + glPushMatrix(); + glPushAttrib(GL_ALL_ATTRIB_BITS); +} + +void MapCanvas::popGlMatrices() +{ + glPopAttrib(); + glMatrixMode(GL_MODELVIEW); + glPopMatrix(); + glMatrixMode(GL_PROJECTION); + glPopMatrix(); + glMatrixMode(GL_TEXTURE); + glPopMatrix(); +} + +void MapCanvas::wheelEvent(QWheelEvent* e) +{ + float numDegrees = e->angleDelta().y() / -8; + + Zoom(numDegrees / 10.0); +} + +void MapCanvas::Zoom(float factor) +{ + view_scale_ *= std::pow(1.1, factor); + UpdateView(); +} + +void MapCanvas::mousePressEvent(QMouseEvent* e) +{ + mouse_x_ = e->x(); + mouse_y_ = e->y(); + mouse_previous_y_ = mouse_y_; + drag_x_ = 0; + drag_y_ = 0; + mouse_pressed_ = true; + mouse_button_ = e->button(); +} + +void MapCanvas::keyPressEvent(QKeyEvent* event) +{ + std::list::iterator it; + for (it = plugins_.begin(); it != plugins_.end(); ++it) { + (*it)->event(event); + } +} + +QPointF MapCanvas::MapGlCoordToFixedFrame(const QPointF& point) +{ + bool invertible = true; + return qtransform_.inverted(&invertible).map(point); +} + +QPointF MapCanvas::FixedFrameToMapGlCoord(const QPointF& point) +{ + return qtransform_.map(point); +} + +void MapCanvas::mouseReleaseEvent(QMouseEvent* e) +{ + mouse_button_ = Qt::NoButton; + mouse_pressed_ = false; + offset_x_ += drag_x_; + offset_y_ += drag_y_; + drag_x_ = 0; + drag_y_ = 0; +} + +void MapCanvas::mouseMoveEvent(QMouseEvent* e) +{ + if (mouse_pressed_ && canvas_able_to_move_) { + int diff; + switch (mouse_button_) { + case Qt::LeftButton: + case Qt::MiddleButton: + if (((mouse_x_ - e->x()) != 0 || (mouse_y_ - e->y()) != 0)) { + drag_x_ = -((mouse_x_ - e->x()) * view_scale_); + drag_y_ = ((mouse_y_ - e->y()) * view_scale_); + } + break; + case Qt::RightButton: + diff = e->y() - mouse_previous_y_; + if (diff != 0) { + Zoom((static_cast(diff)) / 10.0f); + } + mouse_previous_y_ = e->y(); + break; + default: + // Unexpected mouse button + break; + } + } + + double center_x = -offset_x_ - drag_x_; + double center_y = -offset_y_ - drag_y_; + double x = center_x + (e->x() - width() / 2.0) * view_scale_; + double y = center_y + (height() / 2.0 - e->y()) * view_scale_; + + geometry_msgs::msg::PointStamped point_in = make_point_stamped(x, y, 0.0); + geometry_msgs::msg::PointStamped point_out; + + auto tfm_temp = tf2_to_msg(transform_); + tf2::doTransform(point_in, point_out, tfm_temp); + + mouse_hovering_ = true; + mouse_hover_x_ = e->x(); + mouse_hover_y_ = e->y(); + + Q_EMIT Hover(point_out.point.x, point_out.point.y, view_scale_); +} + +void MapCanvas::leaveEvent(QEvent* e) +{ + mouse_hovering_ = false; + Q_EMIT Hover(0, 0, 0); +} + +void MapCanvas::SetFixedFrame(const std::string& frame) +{ + fixed_frame_ = frame; + std::list::iterator it; + for (it = plugins_.begin(); it != plugins_.end(); ++it) { + (*it)->SetTargetFrame(frame); + } +} + +void MapCanvas::SetTargetFrame(const std::string& frame) +{ + offset_x_ = 0; + offset_y_ = 0; + drag_x_ = 0; + drag_y_ = 0; + + target_frame_ = frame; +} + +void MapCanvas::ToggleFixOrientation(bool on) +{ + fix_orientation_ = on; +} + +void MapCanvas::ToggleRotate90(bool on) +{ + rotate_90_ = on; +} + +void MapCanvas::ToggleEnableAntialiasing(bool on) +{ + enable_antialiasing_ = on; + QGLFormat format; + format.setSwapInterval(1); + format.setSampleBuffers(enable_antialiasing_); + // After setting the format, initializeGL will automatically be called again, then paintGL. + this->setFormat(format); +} + +void MapCanvas::ToggleUseLatestTransforms(bool on) +{ + std::list::iterator it; + for (it = plugins_.begin(); it != plugins_.end(); ++it) { + (*it)->SetUseLatestTransforms(on); + } +} + +void MapCanvas::AddPlugin(MapvizPluginPtr plugin, int) +{ + plugins_.push_back(plugin); +} + +void MapCanvas::RemovePlugin(MapvizPluginPtr plugin) +{ + plugin->Shutdown(); + plugins_.remove(plugin); +} + +void MapCanvas::TransformTarget(QPainter* painter) +{ + glTranslatef(offset_x_ + drag_x_, offset_y_ + drag_y_, 0); + // In order for plugins drawing with a QPainter to be able to use the same coordinates + // as plugins using drawing using native GL commands, we have to replicate the + // GL transforms using a QTransform. Note that a QPainter's coordinate system is + // flipped on the Y axis relative to OpenGL's. + qtransform_ = qtransform_.translate(offset_x_ + drag_x_, -(offset_y_ + drag_y_)); + + view_center_x_ = -offset_x_ - drag_x_; + view_center_y_ = -offset_y_ - drag_y_; + + if (!tf_buf_ || fixed_frame_.empty() || target_frame_.empty() || target_frame_ == "") { + qtransform_ = qtransform_.scale(1, -1); + painter->setWorldTransform(qtransform_, false); + + return; + } + + bool success = false; + + try + { + auto tfrm = tf_buf_->lookupTransform( + fixed_frame_, + target_frame_, + tf2::TimePointZero, + std::chrono::seconds(1)); + + tf2::fromMsg(tfrm, transform_); + + // If the viewer orientation is fixed don't rotate the center point. + if (fix_orientation_) { + transform_.setRotation(tf2::Transform::getIdentity().getRotation()); + } + + if (rotate_90_) { + tf2::Quaternion yaw90; + yaw90.setRPY(0, 0, -swri_math_util::_half_pi); + transform_.setRotation(yaw90 * transform_.getRotation()); + } + + double roll, pitch, yaw; + transform_.getBasis().getRPY(roll, pitch, yaw); + + glRotatef(-yaw * 57.2957795, 0, 0, 1); + qtransform_ = qtransform_.rotateRadians(yaw); + + glTranslatef(-transform_.getOrigin().getX(), -transform_.getOrigin().getY(), 0); + qtransform_ = qtransform_.translate( + -transform_.getOrigin().getX(), + transform_.getOrigin().getY()); + + geometry_msgs::msg::PointStamped point = make_point_stamped(view_center_x_, view_center_y_, 0.0); + geometry_msgs::msg::PointStamped center; + + auto tfm_temp = tf2_to_msg(transform_); + tf2::doTransform(point, center, tfm_temp); + + view_center_x_ = center.point.x; + view_center_y_ = center.point.y; + + qtransform_ = qtransform_.scale(1, -1); + painter->setWorldTransform(qtransform_, false); + + if (mouse_hovering_) { + double center_x = -offset_x_ - drag_x_; + double center_y = -offset_y_ - drag_y_; + double x = center_x + (mouse_hover_x_ - width() / 2.0) * view_scale_; + double y = center_y + (height() / 2.0 - mouse_hover_y_) * view_scale_; + + geometry_msgs::msg::PointStamped hover_in = make_point_stamped(x, y, 0.0); + geometry_msgs::msg::PointStamped hover_out; + + tfm_temp = tf2_to_msg(transform_); + tf2::doTransform(hover_in, hover_out, tfm_temp); + + Q_EMIT Hover(hover_out.point.x, hover_out.point.y, view_scale_); + } + + success = true; + } + catch (const tf2::LookupException& e) + { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "%s", e.what()); + } + catch (const tf2::ConnectivityException& e) + { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "%s", e.what()); + } + catch (const tf2::ExtrapolationException& e) + { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "%s", e.what()); + } + catch (...) + { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "Error looking up transform"); + } + + if (!success) + { + qtransform_ = qtransform_.scale(1, -1); + painter->setWorldTransform(qtransform_, false); + } +} + +void MapCanvas::UpdateView() +{ + if (initialized_) { + Recenter(); + + glViewport(0, 0, width(), height()); + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(view_left_, view_right_, view_top_, view_bottom_, -0.5f, 0.5f); + + qtransform_ = QTransform::fromTranslate(width() / 2.0, height() / 2.0). + scale(1.0 / view_scale_, 1.0 / view_scale_); + } +} + +void MapCanvas::ResetLocation() +{ + SetTargetFrame(target_frame_); + SetViewScale(1.0); +} + +void MapCanvas::ReorderDisplays() +{ + plugins_.sort(compare_plugins); +} + +void MapCanvas::Recenter() +{ + // Recalculate the bounds of the view + view_left_ = -(width() * view_scale_ * 0.5); + view_top_ = -(height() * view_scale_ * 0.5); + view_right_ = (width() * view_scale_ * 0.5); + view_bottom_ = (height() * view_scale_ * 0.5); +} + +void MapCanvas::setFrameRate(const double fps) +{ + if (fps <= 0.0) { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "Invalid frame rate: %f", fps); + return; + } + + frame_rate_timer_.setInterval(1000.0/fps); +} + +double MapCanvas::frameRate() const +{ + return 1000.0 / frame_rate_timer_.interval(); +} +} // namespace mapviz diff --git a/mapviz/src/mapviz.cpp b/mapviz/src/mapviz.cpp new file mode 100644 index 000000000..17f4d3dc5 --- /dev/null +++ b/mapviz/src/mapviz.cpp @@ -0,0 +1,1494 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if CV_MAJOR_VERSION > 2 +#include +#include +#endif + +// QT libraries +#if QT_VERSION >= 0x050000 +#include +#else +#include +#endif +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// Other Project libraries +#include +#include + +#include +#include + +#include + +// YAML libraries +#include + +// Boost libraries +#include +#include +#include +#include +#include + +// OpenCV libraries +#include +#include + +namespace mapviz +{ +const QString Mapviz::ROS_WORKSPACE_VAR = "ROS_WORKSPACE"; +const QString Mapviz::MAPVIZ_CONFIG_FILE = "/.mapviz_config"; +const char Mapviz::IMAGE_TRANSPORT_PARAM[] = "image_transport"; + +Mapviz::Mapviz(bool is_standalone, int argc, char** argv, QWidget *parent, Qt::WindowFlags flags) : + QMainWindow(parent, flags), + xy_pos_label_(new QLabel("fixed: 0.0,0.0")), + lat_lon_pos_label_(new QLabel("lat/lon: 0.0,0.0")), + argc_(argc), + argv_(argv), + is_standalone_(is_standalone), + initialized_(false), + force_720p_(false), + force_480p_(false), + resizable_(true), + background_(Qt::gray), + capture_directory_("~"), + vid_writer_(nullptr), + updating_frames_(false), + node_(nullptr), + canvas_(nullptr) +{ + // Multiple users could be using mapviz, so its name needs to be anonymous, + // but ROS 2 Dashing doesn't have a way to set that through node options; + // we manually do it the same way that ros::init did in ROS 1 + std::stringstream name; + name << "mapviz"; + char buf[200]; + std::snprintf(buf, sizeof(buf), "_%llu", (unsigned long long)rclcpp::Clock().now().nanoseconds()); + name << buf; + node_ = std::make_shared(name.str()); + + QString default_path = GetDefaultConfigPath(); + node_->declare_parameter("config", default_path.toStdString()); + node_->declare_parameter("auto_save_backup", true); + node_->declare_parameter("print_profile_data", false); + node_->declare_parameter(IMAGE_TRANSPORT_PARAM, "raw"); + + ui_.setupUi(this); + + xy_pos_label_->setVisible(false); + lat_lon_pos_label_->setVisible(false); + + ui_.statusbar->addPermanentWidget(xy_pos_label_); + ui_.statusbar->addPermanentWidget(lat_lon_pos_label_); + + spacer1_ = new QWidget(ui_.statusbar); + spacer1_-> setMaximumSize(22, 22); + spacer1_-> setMinimumSize(22, 22); + ui_.statusbar->addPermanentWidget(spacer1_); + + screenshot_button_ = new QPushButton(); + screenshot_button_->setMinimumSize(22, 22); + screenshot_button_->setMaximumSize(22, 22); + screenshot_button_->setIcon(QIcon(":/images/image-x-generic.png")); + screenshot_button_->setFlat(true); + screenshot_button_->setToolTip("Capture screenshot of display canvas"); + ui_.statusbar->addPermanentWidget(screenshot_button_); + + spacer2_ = new QWidget(ui_.statusbar); + spacer2_->setMaximumSize(22, 22); + spacer2_->setMinimumSize(22, 22); + ui_.statusbar->addPermanentWidget(spacer2_); + + rec_button_ = new QPushButton(); + rec_button_->setMinimumSize(22, 22); + rec_button_->setMaximumSize(22, 22); + rec_button_->setIcon(QIcon(":/images/media-record.png")); + rec_button_->setCheckable(true); + rec_button_->setFlat(true); + rec_button_->setToolTip("Start recording video of display canvas"); + ui_.statusbar->addPermanentWidget(rec_button_); + + stop_button_ = new QPushButton(); + stop_button_->setMinimumSize(22, 22); + stop_button_->setMaximumSize(22, 22); + stop_button_->setIcon(QIcon(":/images/media-playback-stop.png")); + stop_button_->setToolTip("Stop recording video of display canvas"); + stop_button_->setEnabled(false); + stop_button_->setFlat(true); + ui_.statusbar->addPermanentWidget(stop_button_); + + spacer3_ = new QWidget(ui_.statusbar); + spacer3_->setMaximumSize(22, 22); + spacer3_->setMinimumSize(22, 22); + ui_.statusbar->addPermanentWidget(spacer3_); + + recenter_button_ = new QPushButton(); + recenter_button_->setMinimumSize(22, 22); + recenter_button_->setMaximumSize(22, 22); + recenter_button_->setIcon(QIcon(":/images/arrow_in.png")); + recenter_button_->setToolTip("Reset the viewport to the default location and zoom level"); + recenter_button_->setFlat(true); + ui_.statusbar->addPermanentWidget(recenter_button_); + + ui_.statusbar->setVisible(true); + + QActionGroup* group = new QActionGroup(this); + + ui_.actionForce_720p->setActionGroup(group); + ui_.actionForce_480p->setActionGroup(group); + ui_.actionResizable->setActionGroup(group); + + ui_.targetframe->addItem(""); + + canvas_ = new MapCanvas(this); + setCentralWidget(canvas_); + + connect( + canvas_, + SIGNAL(Hover(double, double, double)), + this, + SLOT(Hover(double, double, double))); + connect(ui_.configs, SIGNAL(ItemsMoved()), this, SLOT(ReorderDisplays())); + connect(ui_.actionExit, SIGNAL(triggered()), this, SLOT(close())); + connect(ui_.actionClear, SIGNAL(triggered()), this, SLOT(ClearConfig())); + connect( + ui_.bg_color, + SIGNAL(colorEdited(const QColor &)), + this, + SLOT(SelectBackgroundColor(const QColor &))); + + connect(recenter_button_, SIGNAL(clicked()), this, SLOT(Recenter())); + connect(rec_button_, SIGNAL(toggled(bool)), this, SLOT(ToggleRecord(bool))); + connect(stop_button_, SIGNAL(clicked()), this, SLOT(StopRecord())); + connect(screenshot_button_, SIGNAL(clicked()), this, SLOT(Screenshot())); + connect(ui_.actionClear_History, SIGNAL(triggered()), this, SLOT(ClearHistory())); + + // Use a separate thread for writing video files so that it won't cause + // lag on the main thread. + // It's ok for the video writer to be a pointer that we instantiate here and + // then forget about; the worker thread will delete it when the thread exits. + vid_writer_ = new VideoWriter(); + vid_writer_->moveToThread(&video_thread_); + connect(&video_thread_, SIGNAL(finished()), vid_writer_, SLOT(deleteLater())); + connect(this, SIGNAL(FrameGrabbed(QImage)), vid_writer_, SLOT(processFrame(QImage))); + video_thread_.start(); + + image_transport_menu_ = new QMenu("Default Image Transport", ui_.menu_View); + ui_.menu_View->addMenu(image_transport_menu_); + + connect(image_transport_menu_, SIGNAL(aboutToShow()), this, SLOT(UpdateImageTransportMenu())); + + ui_.bg_color->setColor(background_); + canvas_->SetBackground(background_); +} + +Mapviz::~Mapviz() +{ + video_thread_.quit(); + video_thread_.wait(); +} + +rclcpp::Node::SharedPtr Mapviz::GetNode() +{ + return node_; +} + +void Mapviz::showEvent(QShowEvent* event) +{ + Initialize(); +} + +void Mapviz::closeEvent(QCloseEvent* event) +{ + AutoSave(); + + for (auto& display : plugins_) { + MapvizPluginPtr plugin = display.second; + canvas_->RemovePlugin(plugin); + } + + plugins_.clear(); +} + +void Mapviz::Initialize() +{ + if (!initialized_) { + if (is_standalone_) { + spin_timer_.start(30); + connect(&spin_timer_, SIGNAL(timeout()), this, SLOT(SpinOnce())); + } + + // Create a sub-menu that lists all available Image Transports + image_transport::ImageTransport it(node_); + std::vector transports = it.getLoadableTransports(); + QActionGroup* group = new QActionGroup(image_transport_menu_); + for (const auto& iter : transports) + { + QString transport = QString::fromStdString(iter).replace( + QString::fromStdString(IMAGE_TRANSPORT_PARAM) + "/", ""); + QAction* action = image_transport_menu_->addAction(transport); + action->setCheckable(true); + group->addAction(action); + } + + connect(group, SIGNAL(triggered(QAction*)), this, SLOT(SetImageTransport(QAction*))); + + tf_buf_ = std::make_shared(node_->get_clock()); + tf_buf_->setUsingDedicatedThread(true); + tf_ = std::make_shared(*tf_buf_, node_, false); + tf_manager_ = std::make_shared(node_); + try + { + tf_manager_->Initialize(tf_buf_); + } + catch (...) + { + RCLCPP_ERROR(node_->get_logger(), "Error initializing tf_manager"); + } + + loader_ = new pluginlib::ClassLoader( + "mapviz", "mapviz::MapvizPlugin"); + + std::vector plugins = loader_->getDeclaredClasses(); + for (const auto& plugin : plugins) { + RCLCPP_INFO(node_->get_logger(), "Found mapviz plugin: %s", plugin.c_str()); + } + + canvas_->InitializeTf(tf_buf_); + canvas_->SetFixedFrame(ui_.fixedframe->currentText().toStdString()); + canvas_->SetTargetFrame(ui_.targetframe->currentText().toStdString()); + + add_display_srv_ = node_->create_service( + "add_mapviz_display", + std::bind(&Mapviz::AddDisplay, + this, + std::placeholders::_1, + std::placeholders::_2)); + + QString default_path = GetDefaultConfigPath(); + + std::string config; + node_->get_parameter_or("config", config, default_path.toStdString()); + + bool auto_save; + node_->get_parameter_or("auto_save_backup", auto_save, true); + + Open(config); + + UpdateFrames(); + frame_timer_.start(1000); + connect(&frame_timer_, SIGNAL(timeout()), this, SLOT(UpdateFrames())); + + if (auto_save) { + save_timer_.start(10000); + connect(&save_timer_, SIGNAL(timeout()), this, SLOT(AutoSave())); + } + + connect(&record_timer_, SIGNAL(timeout()), this, SLOT(CaptureVideoFrame())); + + bool print_profile_data; + node_->get_parameter_or("print_profile_data", print_profile_data, false); + if (print_profile_data) { + profile_timer_.start(2000); + connect(&profile_timer_, SIGNAL(timeout()), this, SLOT(HandleProfileTimer())); + } + + setFocus(); // Set the main window as focused object, + // prevent other fields from obtaining focus at startup + + initialized_ = true; + } +} + +QString Mapviz::GetDefaultConfigPath() +{ + QProcessEnvironment env = QProcessEnvironment::systemEnvironment(); + QString default_path = QDir::homePath(); + if (env.contains(ROS_WORKSPACE_VAR)) { + // If the ROS_WORKSPACE environment variable is defined, try to read our + // config file out of that. If we can't read it, fall back to trying to + // read one from the user's home directory. + QString ws_path = env.value(ROS_WORKSPACE_VAR, default_path); + if (QFileInfo(ws_path + MAPVIZ_CONFIG_FILE).isReadable()) { + default_path = ws_path; + } else { + RCLCPP_WARN( + node_->get_logger(), + "Could not load config file from ROS_WORKSPACE at %s; trying home directory...", + ws_path.toStdString().c_str()); + } + } + default_path += MAPVIZ_CONFIG_FILE; + + return default_path; +} + +void Mapviz::SpinOnce() +{ + if (rclcpp::ok()) { + meas_spin_.start(); + rclcpp::spin_some(node_); + meas_spin_.stop(); + } else { + QApplication::exit(); + } +} + +void Mapviz::UpdateFrames() +{ + std::vector frames; + tf_buf_->_getFrameStrings(frames); + std::sort(frames.begin(), frames.end()); + + if ( + ui_.fixedframe->count() >= 0 && + static_cast(ui_.fixedframe->count()) == frames.size()) + { + bool changed = false; + for (size_t i = 0; i < frames.size(); i++) { + if (frames[i] != ui_.fixedframe->itemText(i).toStdString()) { + changed = true; + } + } + + if (!changed) { + return; + } + } + + updating_frames_ = true; + + std::string current_fixed = ui_.fixedframe->currentText().toStdString(); + + ui_.fixedframe->clear(); + for (const auto& frame : frames) { + ui_.fixedframe->addItem(frame.c_str()); + } + + if (!current_fixed.empty()) { + int index = ui_.fixedframe->findText(current_fixed.c_str()); + if (index < 0) { + ui_.fixedframe->addItem(current_fixed.c_str()); + } + + index = ui_.fixedframe->findText(current_fixed.c_str()); + ui_.fixedframe->setCurrentIndex(index); + } + + std::string current_target = ui_.targetframe->currentText().toStdString(); + + ui_.targetframe->clear(); + ui_.targetframe->addItem(""); + for (const auto& frame : frames) { + ui_.targetframe->addItem(frame.c_str()); + } + + if (!current_target.empty()) { + int index = ui_.targetframe->findText(current_target.c_str()); + if (index < 0) { + ui_.targetframe->addItem(current_target.c_str()); + } + + index = ui_.targetframe->findText(current_target.c_str()); + ui_.targetframe->setCurrentIndex(index); + } + + updating_frames_ = false; + + if (current_target != ui_.targetframe->currentText().toStdString()) { + TargetFrameSelected(ui_.targetframe->currentText()); + } + + if (current_fixed != ui_.fixedframe->currentText().toStdString()) { + FixedFrameSelected(ui_.fixedframe->currentText()); + } +} + +void Mapviz::Force720p(bool on) +{ + if (force_720p_ != on) { + force_720p_ = on; + + if (force_720p_) { + force_480p_ = false; + resizable_ = false; + } + + AdjustWindowSize(); + } +} + +void Mapviz::Force480p(bool on) +{ + if (force_480p_ != on) { + force_480p_ = on; + + if (force_480p_) { + force_720p_ = false; + resizable_ = false; + } + + AdjustWindowSize(); + } +} + +void Mapviz::SetResizable(bool on) +{ + if (resizable_ != on) { + resizable_ = on; + + if (resizable_) { + force_720p_ = false; + force_480p_ = false; + } + + AdjustWindowSize(); + } +} + +void Mapviz::AdjustWindowSize() +{ + canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred)); + setSizePolicy(QSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred)); + + this->setMinimumSize(QSize(100, 100)); + this->setMaximumSize(QSize(10000, 10000)); + + if (force_720p_) { + canvas_->setMinimumSize(1280, 720); + canvas_->setMaximumSize(1280, 720); + canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); + adjustSize(); + this->setMaximumSize(this->sizeHint()); + this->setMinimumSize(this->sizeHint()); + setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); + } else if (force_480p_) { + canvas_->setMinimumSize(640, 480); + canvas_->setMaximumSize(640, 480); + canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); + adjustSize(); + this->setMaximumSize(this->sizeHint()); + this->setMinimumSize(this->sizeHint()); + setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); + } else if (stop_button_->isEnabled()) { + canvas_->setMinimumSize(canvas_->width(), canvas_->height()); + canvas_->setMaximumSize(canvas_->width(), canvas_->height()); + canvas_->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); + adjustSize(); + this->setMaximumSize(this->sizeHint()); + this->setMinimumSize(this->sizeHint()); + setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); + } else { + canvas_->setMinimumSize(100, 100); + canvas_->setMaximumSize(10000, 10000); + } +} + +void Mapviz::Open(const std::string& filename) +{ + RCLCPP_INFO(node_->get_logger(), "Loading configuration from %s", filename.c_str()); + + std::string title; + size_t last_slash = filename.find_last_of('/'); + if (last_slash != std::string::npos && last_slash != filename.size() - 1) { + title = filename.substr(last_slash + 1) + " (" + + filename.substr(0, last_slash + 1) + ")"; + } else { + title = filename; + } + + title += " - mapviz"; + setWindowTitle(QString::fromStdString(title)); + + YAML::Node doc = YAML::LoadFile(filename); + if (!doc) { + RCLCPP_ERROR(node_->get_logger(), "Failed to load file: %s", filename.c_str()); + return; + } + + std::vector failed_plugins; + + try + { + boost::filesystem::path filepath(filename); + std::string config_path = filepath.parent_path().string(); + + ClearDisplays(); + + if (doc["capture_directory"]) { + capture_directory_ = doc["capture_directory"].as(); + } + + if (doc["fixed_frame"]) { + std::string fixed_frame = doc["fixed_frame"].as(); + ui_.fixedframe->setEditText(fixed_frame.c_str()); + } + + if (doc["target_frame"]) { + std::string target_frame = doc["target_frame"].as(); + ui_.targetframe->setEditText(target_frame.c_str()); + } + + if (doc["fix_orientation"]) { + bool fix_orientation = doc["fix_orientation"].as(); + ui_.actionFix_Orientation->setChecked(fix_orientation); + } + + if (doc["rotate_90"]) { + bool rotate_90 = doc["rotate_90"].as(); + ui_.actionRotate_90->setChecked(rotate_90); + } + + if (doc["enable_antialiasing"]) { + bool enable_antialiasing = doc["enable_antialiasing"].as(); + ui_.actionEnable_Antialiasing->setChecked(enable_antialiasing); + } + + if (doc["show_displays"]) { + bool show_displays = doc["show_displays"].as(); + ui_.actionConfig_Dock->setChecked(show_displays); + } + + if (doc["show_capture_tools"]) { + bool show_capture_tools = doc["show_capture_tools"].as(); + ui_.actionShow_Capture_Tools->setChecked(show_capture_tools); + } + + if (doc["show_status_bar"]) { + bool show_status_bar = doc["show_status_bar"].as(); + ui_.actionShow_Status_Bar->setChecked(show_status_bar); + } + + if (doc["show_capture_tools"]) { + bool show_capture_tools = doc["show_capture_tools"].as(); + ui_.actionShow_Capture_Tools->setChecked(show_capture_tools); + } + + if (doc["window_width"]) { + int window_width = doc["window_width"].as(); + resize(window_width, height()); + } + + if (doc["window_height"]) { + int window_height = doc["window_height"].as(); + resize(width(), window_height); + } + + if (doc["view_scale"]) { + float scale = doc["view_scale"].as(); + canvas_->SetViewScale(scale); + } + + if (doc["offset_x"]) { + float x = doc["offset_x"].as(); + canvas_->SetOffsetX(x); + } + + if (doc["offset_y"]) { + float y = doc["offset_y"].as(); + canvas_->SetOffsetY(y); + } + + if (doc["force_720p"]) { + bool force_720p = doc["force_720p"].as(); + + if (force_720p) { + ui_.actionForce_720p->setChecked(true); + } + } + + if (doc["force_480p"]) { + bool force_480p = doc["force_480p"].as(); + + if (force_480p) { + ui_.actionForce_480p->setChecked(true); + } + } + + if (doc[IMAGE_TRANSPORT_PARAM]) { + std::string image_transport = doc[IMAGE_TRANSPORT_PARAM].as(); + + node_->set_parameter({IMAGE_TRANSPORT_PARAM, image_transport}); + } + + bool use_latest_transforms = true; + if (doc["use_latest_transforms"]) { + use_latest_transforms = doc["use_latest_transforms"].as(); + } + ui_.uselatesttransforms->setChecked(use_latest_transforms); + canvas_->ToggleUseLatestTransforms(use_latest_transforms); + + if (doc["background"]) { + std::string color = doc["background"].as(); + background_ = QColor(color.c_str()); + ui_.bg_color->setColor(background_); + canvas_->SetBackground(background_); + } + + if (doc["displays"]) { + const YAML::Node& displays = doc["displays"]; + for (const auto& display : displays) { + std::string type = display["type"].as(); + std::string name = display["name"].as(); + + const YAML::Node& config = display["config"]; + + bool visible = config["visible"].as(); + + bool collapsed = config["collapsed"].as(); + + try + { + MapvizPluginPtr plugin = + CreateNewDisplay(name, type, visible, collapsed); + plugin->LoadConfig(config, config_path); + plugin->DrawIcon(); + } + catch (const pluginlib::LibraryLoadException& e) + { + failed_plugins.push_back(type); + RCLCPP_ERROR(node_->get_logger(), "%s", e.what()); + } + } + } + } + catch (const YAML::ParserException& e) + { + RCLCPP_ERROR(node_->get_logger(), "%s", e.what()); + return; + } + catch (const YAML::Exception& e) + { + RCLCPP_ERROR(node_->get_logger(), "%s", e.what()); + return; + } + + if (!failed_plugins.empty()) { + std::stringstream message; + message << "The following plugin(s) failed to load:" << std::endl; + std::string failures = boost::algorithm::join(failed_plugins, "\n"); + message << failures << std::endl << std::endl << "Check the ROS log for more details."; + + QMessageBox::warning(this, "Failed to load plugins", QString::fromStdString(message.str())); + } +} + +void Mapviz::Save(const std::string& filename) +{ + std::ofstream fout(filename.c_str()); + if (fout.fail()) { + RCLCPP_ERROR(node_->get_logger(), "Failed to open file: %s", filename.c_str()); + return; + } + + boost::filesystem::path filepath(filename); + std::string config_path = filepath.parent_path().string(); + + YAML::Emitter out; + + out << YAML::BeginMap; + out << YAML::Key << "capture_directory" << YAML::Value << capture_directory_; + out << YAML::Key << "fixed_frame" << YAML::Value << ui_.fixedframe->currentText().toStdString(); + out << YAML::Key << "target_frame" << YAML::Value << ui_.targetframe->currentText().toStdString(); + out << YAML::Key << "fix_orientation" << YAML::Value << ui_.actionFix_Orientation->isChecked(); + out << YAML::Key << "rotate_90" << YAML::Value << ui_.actionRotate_90->isChecked(); + out << YAML::Key + << "enable_antialiasing" + << YAML::Value + << ui_.actionEnable_Antialiasing->isChecked(); + out << YAML::Key + << "show_displays" + << YAML::Value + << ui_.actionConfig_Dock->isChecked(); + out << YAML::Key << "show_status_bar" << YAML::Value << ui_.actionShow_Status_Bar->isChecked(); + out << YAML::Key + << "show_capture_tools" + << YAML::Value + << ui_.actionShow_Capture_Tools->isChecked(); + out << YAML::Key << "window_width" << YAML::Value << width(); + out << YAML::Key << "window_height" << YAML::Value << height(); + out << YAML::Key << "view_scale" << YAML::Value << canvas_->ViewScale(); + out << YAML::Key << "offset_x" << YAML::Value << canvas_->OffsetX(); + out << YAML::Key << "offset_y" << YAML::Value << canvas_->OffsetY(); + out << YAML::Key + << "use_latest_transforms" + << YAML::Value + << ui_.uselatesttransforms->isChecked(); + out << YAML::Key << "background" << YAML::Value << background_.name().toStdString(); + std::string image_transport; + if (node_->get_parameter(IMAGE_TRANSPORT_PARAM, image_transport)) { + out << YAML::Key << IMAGE_TRANSPORT_PARAM << YAML::Value << image_transport; + } + + if (force_720p_) { + out << YAML::Key << "force_720p" << YAML::Value << force_720p_; + } + + if (force_480p_) { + out << YAML::Key << "force_480p" << YAML::Value << force_480p_; + } + + if (ui_.configs->count() > 0) { + out << YAML::Key << "displays"<< YAML::Value << YAML::BeginSeq; + + for (int i = 0; i < ui_.configs->count(); i++) { + out << YAML::BeginMap; + out << YAML::Key << "type" << YAML::Value << plugins_[ui_.configs->item(i)]->Type(); + out << YAML::Key + << "name" + << YAML::Value + << (dynamic_cast(ui_.configs->itemWidget(ui_.configs->item(i)))) + ->Name().toStdString(); + out << YAML::Key << "config" << YAML::Value; + out << YAML::BeginMap; + + out << YAML::Key << "visible" << YAML::Value << plugins_[ui_.configs->item(i)]->Visible(); + out << YAML::Key + << "collapsed" + << YAML::Value + << (dynamic_cast(ui_.configs->itemWidget(ui_.configs->item(i))))->Collapsed(); + + plugins_[ui_.configs->item(i)]->SaveConfig(out, config_path); + + out << YAML::EndMap; + out << YAML::EndMap; + } + + out << YAML::EndSeq; + } + + out << YAML::EndMap; + + fout << out.c_str(); + fout.close(); +} + +void Mapviz::AutoSave() +{ + QProcessEnvironment env = QProcessEnvironment::systemEnvironment(); + QString default_path = QDir::homePath(); + + if (env.contains(ROS_WORKSPACE_VAR)) { + // Try to save our config in the ROS_WORKSPACE directory, but if we can't write + // to that -- probably because it is read-only -- try to use the home directory + // instead. + QString ws_path = env.value(ROS_WORKSPACE_VAR, default_path); + QString ws_file = ws_path + MAPVIZ_CONFIG_FILE; + QFileInfo file_info(ws_file); + QFileInfo dir_info(ws_path); + if ( + (!file_info.exists() && dir_info.isWritable()) || + file_info.isWritable()) + { + // Note that FileInfo::isWritable will return false if a file does not exist, so + // we need to check both if the target file is writable and if the target dir is + // writable if the file doesn't exist. + default_path = ws_path; + } else { + RCLCPP_WARN(node_->get_logger(), + "Could not write config file to %s. Trying home directory.", + (ws_path + MAPVIZ_CONFIG_FILE).toStdString().c_str()); + } + } + default_path += MAPVIZ_CONFIG_FILE; + + + Save(default_path.toStdString()); +} + +void Mapviz::OpenConfig() +{ + QFileDialog dialog(this, "Select Config File"); + dialog.setFileMode(QFileDialog::ExistingFile); + dialog.setNameFilter(tr("Mapviz Config Files (*.mvc)")); + + dialog.exec(); + + if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1) { + std::string path = dialog.selectedFiles().first().toStdString(); + Open(path); + } +} + +void Mapviz::ClearConfig() +{ + ClearDisplays(); +} + +void Mapviz::SaveConfig() +{ + QFileDialog dialog(this, "Save Config File"); + dialog.setFileMode(QFileDialog::AnyFile); + dialog.setAcceptMode(QFileDialog::AcceptSave); + dialog.setNameFilter(tr("Mapviz Config Files (*.mvc)")); + dialog.setDefaultSuffix("mvc"); + + dialog.exec(); + + if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1) { + std::string path = dialog.selectedFiles().first().toStdString(); + + std::string title; + size_t last_slash = path.find_last_of('/'); + if (last_slash != std::string::npos && last_slash != path.size() - 1) { + title = path.substr(last_slash + 1) + " (" + + path.substr(0, last_slash + 1) + ")"; + } else { + title = path; + } + title += " - mapviz"; + setWindowTitle(QString::fromStdString(title)); + Save(path); + } +} + +void Mapviz::ClearHistory() +{ + RCLCPP_DEBUG(node_->get_logger(), "Mapviz::ClearHistory()"); + for (auto& plugin : plugins_) { + plugin.second->ClearHistory(); + } +} + +void Mapviz::SelectNewDisplay() +{ + RCLCPP_INFO(rclcpp::get_logger("mapviz"), "Select new display ..."); + QDialog dialog; + Ui::pluginselect ui; + ui.setupUi(&dialog); + + std::vector plugins = loader_->getDeclaredClasses(); + std::map plugin_types; + for (const auto& plugin : plugins) { + QString type(plugin.c_str()); + type = type.split('/').last(); + ui.displaylist->addItem(type); + plugin_types[type.toStdString()] = plugin; + } + ui.displaylist->setCurrentRow(0); + + dialog.exec(); + + if (dialog.result() == QDialog::Accepted) { + std::string type_name = ui.displaylist->selectedItems().first()->text().toStdString(); + std::string type = plugin_types[type_name]; + std::string name = "new display"; + try + { + CreateNewDisplay(name, type, true, false); + } + catch (const pluginlib::LibraryLoadException& e) + { + std::stringstream message; + message << "Unable to load " << type << "." << std::endl + << "Check the ROS log for more details."; + QMessageBox::warning(this, "Plugin failed to load", QString::fromStdString(message.str())); + RCLCPP_ERROR(node_->get_logger(), "%s", e.what()); + } + } +} + +void Mapviz::AddDisplay( + const mapviz_interfaces::srv::AddMapvizDisplay::Request::SharedPtr req, + mapviz_interfaces::srv::AddMapvizDisplay::Response::SharedPtr resp) +{ + std::map properties; + for (auto& property : req->properties) { + properties[property.key] = property.value; + } + + YAML::Node config; + for (auto& property_pair : properties) { + config[property_pair.first] = property_pair.second; + } + + if (!config) { + // ROS_ERROR("Failed to parse properties into YAML."); + RCLCPP_ERROR(node_->get_logger(), "Failed to parse properties into YAML."); + resp->success = false; + throw std::runtime_error("Failed to parse properties into YAML."); + } + + for (auto& display : plugins_) { + MapvizPluginPtr plugin = display.second; + if (!plugin) { + RCLCPP_ERROR(node_->get_logger(), "Invalid plugin ptr."); + continue; + } + + if (plugin->Name() == req->name && plugin->Type() == req->type) { + plugin->LoadConfig(config, ""); + plugin->SetVisible(req->visible); + + if (req->draw_order > 0) { + display.first->setData(Qt::UserRole, QVariant(req->draw_order - 1.1)); + ui_.configs->sortItems(); + + ReorderDisplays(); + } else if (req->draw_order < 0) { + display.first->setData( + Qt::UserRole, QVariant(ui_.configs->count() + req->draw_order + 0.1)); + ui_.configs->sortItems(); + + ReorderDisplays(); + } + + resp->success = true; + + return; + } + } + + try + { + MapvizPluginPtr plugin = + CreateNewDisplay(req->name, req->type, req->visible, false, req->draw_order); + plugin->LoadConfig(config, ""); + plugin->DrawIcon(); + resp->success = true; + } + catch (const pluginlib::LibraryLoadException& e) + { + RCLCPP_ERROR(node_->get_logger(), "%s", e.what()); + resp->success = false; + resp->message = "Failed to load display plug-in."; + } +} + +void Mapviz::Hover(double x, double y, double scale) +{ + if (ui_.statusbar->isVisible()) { + if (scale == 0) { + xy_pos_label_->setVisible(false); + lat_lon_pos_label_->setVisible(false); + return; + } + + int32_t precision = static_cast(std::ceil(std::max(0.0, std::log10(1.0 / scale)))); + + QString text = ui_.fixedframe->currentText(); + if (text.isEmpty() || text == "/") { + text = "fixed"; + } + text += ": "; + + std::ostringstream x_ss; + x_ss << std::fixed << std::setprecision(precision); + x_ss << x; + text += x_ss.str().c_str(); + + text += ", "; + + std::ostringstream y_ss; + y_ss << std::fixed << std::setprecision(precision); + y_ss << y; + text += y_ss.str().c_str(); + + xy_pos_label_->setText(text); + xy_pos_label_->setVisible(true); + xy_pos_label_->update(); + + swri_transform_util::Transform transform; + if + ( + tf_manager_->SupportsTransform( + swri_transform_util::_wgs84_frame, + ui_.fixedframe->currentText().toStdString()) && + tf_manager_->GetTransform( + swri_transform_util::_wgs84_frame, + ui_.fixedframe->currentText().toStdString(), + transform)) + { + tf2::Vector3 point(x, y, 0); + point = transform * point; + + QString lat_lon_text = "lat/lon: "; + + double lat_scale = (1.0 / 111111.0) * scale; + int32_t lat_precision = static_cast( + std::ceil(std::max(0.0, std::log10(1.0 / lat_scale)))); + + std::ostringstream lat_ss; + lat_ss << std::fixed << std::setprecision(lat_precision); + lat_ss << point.y(); + lat_lon_text += lat_ss.str().c_str(); + + lat_lon_text += ", "; + + double lon_scale = (1.0 + / (111111.0 * std::cos(point.y() * swri_math_util::_deg_2_rad))) * scale; + int32_t lon_precision = static_cast( + std::ceil(std::max(0.0, std::log10(1.0 / lon_scale)))); + + std::ostringstream lon_ss; + lon_ss << std::fixed << std::setprecision(lon_precision); + lon_ss << point.x(); + lat_lon_text += lon_ss.str().c_str(); + + lat_lon_pos_label_->setText(lat_lon_text); + lat_lon_pos_label_->setVisible(true); + lat_lon_pos_label_->update(); + } else if (lat_lon_pos_label_->isVisible()) { + lat_lon_pos_label_->setVisible(false); + } + } +} + +MapvizPluginPtr Mapviz::CreateNewDisplay( + const std::string& name, + const std::string& type, + bool visible, + bool collapsed, + int draw_order) +{ + auto* config_item = new ConfigItem(); + + config_item->SetName(name.c_str()); + + std::string real_type = type; + if (real_type == "mapviz_plugins/mutlires_image") { + // The "multires_image" plugin was originally accidentally named "mutlires_image". + // Loading a mapviz config file that still has the old name would normally cause it + // to crash, so this will check for and correct it. + real_type = "mapviz_plugins/multires_image"; + } + + RCLCPP_INFO(node_->get_logger(), "creating: %s", real_type.c_str()); + MapvizPluginPtr plugin = loader_->createSharedInstance(real_type); + + // Setup configure widget + config_item->SetWidget(plugin->GetConfigWidget(this)); + plugin->SetIcon(config_item->ui_.icon); + plugin->SetType(real_type); + plugin->SetName(name); + plugin->SetNode(*node_); + plugin->Initialize(tf_buf_, tf_, tf_manager_, canvas_); + plugin->SetVisible(visible); + + if (draw_order == 0) { + plugin->SetDrawOrder(ui_.configs->count()); + } else if (draw_order > 0) { + plugin->SetDrawOrder(std::min(ui_.configs->count(), draw_order - 1)); + } else if (draw_order < 0) { + plugin->SetDrawOrder(std::max(0, ui_.configs->count() + draw_order + 1)); + } + + QString pretty_type(real_type.c_str()); + pretty_type = pretty_type.split('/').last(); + config_item->SetType(pretty_type); + QListWidgetItem* item = new PluginConfigListItem(); + config_item->SetListItem(item); + item->setSizeHint(config_item->sizeHint()); + connect(config_item, SIGNAL(UpdateSizeHint()), this, SLOT(UpdateSizeHints())); + connect( + config_item, + SIGNAL(ToggledDraw(QListWidgetItem*, bool)), + this, + SLOT(ToggleShowPlugin(QListWidgetItem*, bool))); + connect( + config_item, + SIGNAL(RemoveRequest(QListWidgetItem*)), + this, + SLOT(RemoveDisplay(QListWidgetItem*))); + connect(plugin.get(), SIGNAL(VisibleChanged(bool)), config_item, SLOT(ToggleDraw(bool))); + connect(plugin.get(), SIGNAL(SizeChanged()), this, SLOT(UpdateSizeHints())); + + if (real_type == "mapviz_plugins/image") { + // This is a little kludgey because we're relying on hard-coding a + // plugin type here... feel free to suggest a better way. + // If the default image transport has changed, we want to notify all of our + // image plugins of it so that they will resubscribe appropriately. + connect(this, SIGNAL(ImageTransportChanged()), + plugin.get(), SLOT(Resubscribe())); + } + + if (draw_order == 0) { + ui_.configs->addItem(item); + } else { + ui_.configs->insertItem(plugin->DrawOrder(), item); + } + + ui_.configs->setItemWidget(item, config_item); + ui_.configs->UpdateIndices(); + + // Add plugin to canvas + plugin->SetTargetFrame(ui_.fixedframe->currentText().toStdString()); + plugin->SetUseLatestTransforms(ui_.uselatesttransforms->isChecked()); + plugins_[item] = plugin; + canvas_->AddPlugin(plugin, -1); + + config_item->ToggleDraw(visible); + + if (collapsed) { + config_item->Hide(); + } + + ReorderDisplays(); + + return plugin; +} + +void Mapviz::ToggleShowPlugin(QListWidgetItem* item, bool visible) +{ + RCLCPP_INFO(node_->get_logger(), "Toggle show plugin"); + + if (plugins_.count(item) == 1) { + plugins_[item]->SetVisible(visible); + } + canvas_->UpdateView(); +} + +void Mapviz::FixedFrameSelected(const QString& text) +{ + if (!updating_frames_) { + RCLCPP_INFO( + node_->get_logger(), + "fixed frame selected: %s", + text.toStdString().c_str()); + if (canvas_ != nullptr) { + canvas_->SetFixedFrame(text.toStdString()); + } + } +} + +void Mapviz::TargetFrameSelected(const QString& text) +{ + if (!updating_frames_) { + RCLCPP_INFO( + node_->get_logger(), + "Target frame selected: %s", + text.toStdString().c_str()); + + if (canvas_ != nullptr) { + canvas_->SetTargetFrame(text.toStdString()); + } + } +} + +void Mapviz::ToggleUseLatestTransforms(bool on) +{ + canvas_->ToggleUseLatestTransforms(on); +} + +void Mapviz::ToggleFixOrientation(bool on) +{ + canvas_->ToggleFixOrientation(on); +} + +void Mapviz::ToggleRotate90(bool on) +{ + canvas_->ToggleRotate90(on); +} + +void Mapviz::ToggleEnableAntialiasing(bool on) +{ + canvas_->ToggleEnableAntialiasing(on); +} + +void Mapviz::ToggleConfigPanel(bool on) +{ + if (on) { + ui_.configdock->show(); + } else { + ui_.configdock->hide(); + } + + AdjustWindowSize(); +} + +void Mapviz::ToggleStatusBar(bool on) +{ + ui_.statusbar->setVisible(on); + + AdjustWindowSize(); +} + +void Mapviz::ToggleCaptureTools(bool on) +{ + if (on) { + ui_.actionShow_Status_Bar->setChecked(true); + } + + screenshot_button_->setVisible(on); + rec_button_->setVisible(on); + stop_button_->setVisible(on); + spacer1_->setVisible(on); + spacer2_->setVisible(on); + spacer3_->setVisible(on); +} + +void Mapviz::ToggleRecord(bool on) +{ + stop_button_->setEnabled(true); + + if (on) { + rec_button_->setIcon(QIcon(":/images/media-playback-pause.png")); + rec_button_->setToolTip("Pause recording video of display canvas"); + if (!vid_writer_->isRecording()) { + // Lock the window size. + AdjustWindowSize(); + + canvas_->CaptureFrames(true); + + std::string posix_time = boost::posix_time::to_iso_string( + boost::posix_time::second_clock::local_time()); + boost::replace_all(posix_time, ".", "_"); + std::string filename = capture_directory_ + "/mapviz_" + posix_time + ".avi"; + boost::replace_all(filename, "~", getenv("HOME")); + + + if (!vid_writer_->initializeWriter(filename, canvas_->width(), canvas_->height())) { + RCLCPP_ERROR(node_->get_logger(), "Failed to open video file for writing"); + StopRecord(); + return; + } + + RCLCPP_INFO(node_->get_logger(), "Writing video to: %s", filename.c_str()); + ui_.statusbar->showMessage("Recording video to " + QString::fromStdString(filename)); + + canvas_->updateGL(); + } + + record_timer_.start(1000.0 / 30.0); + } else { + rec_button_->setIcon(QIcon(":/images/media-record.png")); + rec_button_->setToolTip("Continue recording video of display canvas"); + record_timer_.stop(); + } +} + +void Mapviz::SetImageTransport(QAction* transport_action) +{ + std::string transport = transport_action->text().toStdString(); + RCLCPP_INFO( + node_->get_logger(), + "Setting %s to %s", + IMAGE_TRANSPORT_PARAM, + transport.c_str()); + node_->set_parameter({IMAGE_TRANSPORT_PARAM, transport}); + + Q_EMIT(ImageTransportChanged()); +} + +void Mapviz::UpdateImageTransportMenu() +{ + QList actions = image_transport_menu_->actions(); + + std::string current_transport; + node_->get_parameter_or(IMAGE_TRANSPORT_PARAM, current_transport, std::string("raw")); + for(const auto action : actions) + { + if (action->text() == QString::fromStdString(current_transport)) { + action->setChecked(true); + return; + } + } + + RCLCPP_WARN( + node_->get_logger(), + "%s param was set to an unrecognized value: %s", + IMAGE_TRANSPORT_PARAM, + current_transport.c_str()); +} + +void Mapviz::CaptureVideoFrame() +{ + // We need to store the data inside a QImage in order to emit it as a + // signal. + // Note that the QImage here is set to "ARGB32", but it is actually BGRA. + // Qt doesn't have a comparable BGR format, and the cv::VideoWriter this + // is going to expects BGR format, but it'd be a waste for us to convert + // to RGB and then back to BGR. + QImage frame(canvas_->width(), canvas_->height(), QImage::Format_ARGB32); + if (canvas_->CopyCaptureBuffer(frame.bits())) { + Q_EMIT(FrameGrabbed(frame)); + } else { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "Failed to get capture buffer"); + } +} + +void Mapviz::Recenter() +{ + canvas_->ResetLocation(); +} + +void Mapviz::StopRecord() +{ + rec_button_->setChecked(false); + stop_button_->setEnabled(false); + + record_timer_.stop(); + if (vid_writer_) { + vid_writer_->stop(); + } + canvas_->CaptureFrames(false); + + ui_.statusbar->showMessage(QString("")); + rec_button_->setToolTip("Start recording video of display canvas"); + + AdjustWindowSize(); +} + +void Mapviz::Screenshot() +{ + canvas_->CaptureFrame(true); + + std::vector frame; + if (canvas_->CopyCaptureBuffer(frame)) { + cv::Mat image(canvas_->height(), canvas_->width(), CV_8UC4, &frame[0]); + cv::Mat screenshot; + cvtColor(image, screenshot, cv::COLOR_BGRA2BGR); + + cv::flip(screenshot, screenshot, 0); + + std::string posix_time = boost::posix_time::to_iso_string( + boost::posix_time::second_clock::local_time()); + boost::replace_all(posix_time, ".", "_"); + std::string filename = capture_directory_ + "/mapviz_" + posix_time + ".png"; + boost::replace_all(filename, "~", getenv("HOME")); + + RCLCPP_INFO(rclcpp::get_logger("mapviz"), "Writing screenshot to: %s", filename.c_str()); + ui_.statusbar->showMessage("Saved image to " + QString::fromStdString(filename)); + + cv::imwrite(filename, screenshot); + } else { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "Failed to take screenshot."); + } +} + +void Mapviz::UpdateSizeHints() +{ + for (int i = 0; i < ui_.configs->count(); i++) { + QListWidgetItem* item = ui_.configs->item(i); + auto* widget = dynamic_cast(ui_.configs->itemWidget(item)); + if (widget) { + // Make sure the ConfigItem in the QListWidgetItem we're getting really + // exists; if this method is called before it's been initialized, it would + // cause a crash. + item->setSizeHint(widget->sizeHint()); + } + } +} + +void Mapviz::RemoveDisplay() +{ + QListWidgetItem* item = ui_.configs->takeItem(ui_.configs->currentRow()); + RemoveDisplay(item); +} + +void Mapviz::RemoveDisplay(QListWidgetItem* item) +{ + RCLCPP_INFO(rclcpp::get_logger("mapviz"), "Remove display ..."); + + if (item) { + canvas_->RemovePlugin(plugins_[item]); + plugins_.erase(item); + + delete item; + } +} + +void Mapviz::ClearDisplays() +{ + while (ui_.configs->count() > 0) { + RCLCPP_INFO(node_->get_logger(), "Remove display ..."); + + QListWidgetItem* item = ui_.configs->takeItem(0); + + canvas_->RemovePlugin(plugins_[item]); + plugins_.erase(item); + + delete item; + } +} + +void Mapviz::ReorderDisplays() +{ + RCLCPP_INFO(rclcpp::get_logger("mapviz"), "Reorder displays"); + for (int i = 0; i < ui_.configs->count(); i++) { + plugins_[ui_.configs->item(i)]->SetDrawOrder(i); + } + canvas_->ReorderDisplays(); +} + +void Mapviz::SelectBackgroundColor(const QColor &color) +{ + background_ = color; + canvas_->SetBackground(background_); +} + +void Mapviz::SetCaptureDirectory() +{ + QFileDialog dialog(this, "Select Capture Directory"); + dialog.setOption(QFileDialog::ShowDirsOnly, true); + + dialog.exec(); + + if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1) { + capture_directory_ = dialog.selectedFiles().first().toStdString(); + } +} + +void Mapviz::HandleProfileTimer() +{ + RCLCPP_INFO(node_->get_logger(), "Mapviz Profiling Data"); + meas_spin_.printInfo(node_->get_logger(), "ROS SpinOnce()"); + for (auto& display : plugins_) { + MapvizPluginPtr plugin = display.second; + if (plugin) { + plugin->PrintMeasurements(); + } + } +} +} // namespace mapviz diff --git a/mapviz/src/mapviz.ui b/mapviz/src/mapviz.ui new file mode 100644 index 000000000..f0b89fa14 --- /dev/null +++ b/mapviz/src/mapviz.ui @@ -0,0 +1,814 @@ + + + mapviz + + + + 0 + 0 + 600 + 600 + + + + + 0 + 0 + + + + + 600 + 400 + + + + mapviz + + + + + 0 + 0 + 600 + 27 + + + + + &File + + + + + + + + + + + + &View + + + + + + + + + + + + + + + + + Data + + + + + + + + + + true + + + + + + 332 + 301 + + + + QDockWidget::DockWidgetMovable + + + Qt::LeftDockWidgetArea|Qt::RightDockWidgetArea + + + Config + + + 1 + + + + + 0 + + + 2 + + + 0 + + + 0 + + + 0 + + + + + + + + + 85 + 16777215 + + + + + Sans Serif + 9 + + + + Fixed Frame: + + + + + + + + 85 + 16777215 + + + + + Sans Serif + 9 + + + + Target Frame: + + + + + + + + 85 + 16777215 + + + + + Sans Serif + 9 + + + + Background: + + + + + + + + 24 + 24 + + + + Set the background color + + + false + + + + + + + + + + + + + + 0 + 0 + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + The reference frame for the camera view + + + true + + + + + + + + 0 + 0 + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + The reference frame used to denote the "world" frame + + + + true + + + + + + + Use the current time when transforming data instead of using the + timestamps associated with the data + + + + Qt::LeftToRight + + + Use Latest Transforms + + + true + + + + + + + + + + Qt::ScrollBarAsNeeded + + + true + + + QAbstractItemView::InternalMove + + + Qt::MoveAction + + + QAbstractItemView::ScrollPerPixel + + + + + + + + 4 + + + 4 + + + + + + 80 + 16777215 + + + + Add a new display + + + Add + + + + + + + + 80 + 16777215 + + + + Remove the selected display + + + Remove + + + + + + + + + + + + Exit + + + + + Open Config + + + + + Save Config + + + + + true + + + true + + + Show Config Panel + + + Show the display configuration panel + + + + + true + + + Fix Orientation + + + Fix the orientation of the camera + + + + + true + + + Force 720p + + + Lock the display canvas to 720p + + + + + true + + + Force 480p + + + Lock the display canvas to 480p + + + + + true + + + true + + + Resizable + + + Make the window resizable + + + + + Set Capture Directory + + + Set the capture directory for screeshots and videos + + + + + true + + + true + + + Show Status Bar + + + Show the status bar + + + + + true + + + true + + + Show Capture Tools + + + Show the capture tools on the status bar + + + + + true + + + Rotate 90° + + + Rotate the camera by 90 degrees + + + + + true + + + true + + + Enable Antialiasing + + + Enable antialiasing on the GL surface + + + + + Image Transport + + + + + Clear History + + + + + Clear Config + + + + + + mapviz::PluginConfigList + QListWidget +
      mapviz/widgets.h
      +
      + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + fixedframe + targetframe + uselatesttransforms + bg_color + configs + addbutton + removebutton + + + + + + + addbutton + clicked() + mapviz + SelectNewDisplay() + + + 107 + 573 + + + 327 + 471 + + + + + removebutton + clicked() + mapviz + RemoveDisplay() + + + 224 + 573 + + + 328 + 407 + + + + + actionConfig_Dock + toggled(bool) + mapviz + ToggleConfigPanel(bool) + + + -1 + -1 + + + 399 + 299 + + + + + fixedframe + editTextChanged(QString) + mapviz + FixedFrameSelected(QString) + + + 185 + 62 + + + 428 + 192 + + + + + targetframe + editTextChanged(QString) + mapviz + TargetFrameSelected(QString) + + + 206 + 94 + + + 428 + 330 + + + + + actionFix_Orientation + toggled(bool) + mapviz + ToggleFixOrientation(bool) + + + -1 + -1 + + + 399 + 299 + + + + + actionOpen_config + triggered() + mapviz + OpenConfig() + + + -1 + -1 + + + 399 + 299 + + + + + actionSave_config + triggered() + mapviz + SaveConfig() + + + -1 + -1 + + + 399 + 299 + + + + + actionForce_720p + toggled(bool) + mapviz + Force720p(bool) + + + -1 + -1 + + + 399 + 299 + + + + + actionForce_480p + toggled(bool) + mapviz + Force480p(bool) + + + -1 + -1 + + + 399 + 299 + + + + + actionResizable + toggled(bool) + mapviz + SetResizable(bool) + + + -1 + -1 + + + 399 + 299 + + + + + uselatesttransforms + toggled(bool) + mapviz + ToggleUseLatestTransforms(bool) + + + 58 + 130 + + + 460 + 242 + + + + + actionSet_Capture_Directory + triggered() + mapviz + SetCaptureDirectory() + + + -1 + -1 + + + 354 + 299 + + + + + actionShow_Status_Bar + toggled(bool) + mapviz + ToggleStatusBar(bool) + + + -1 + -1 + + + 354 + 299 + + + + + actionShow_Capture_Tools + triggered(bool) + mapviz + ToggleCaptureTools(bool) + + + -1 + -1 + + + 354 + 299 + + + + + actionRotate_90 + toggled(bool) + mapviz + ToggleRotate90(bool) + + + -1 + -1 + + + 354 + 299 + + + + + actionEnable_Antialiasing + toggled(bool) + mapviz + ToggleEnableAntialiasing(bool) + + + -1 + -1 + + + 399 + 299 + + + + + + SelectNewDisplay() + RemoveDisplay() + ToggleConfigPanel(bool) + FixedFrameSelected(QString) + TargetFrameSelected(QString) + ToggleFixOrientation(bool) + ToggleEnableAntialiasing(bool) + MoveDisplay(QModelIndexList) + OpenConfig() + SaveConfig() + Force720p(bool) + Force480p(bool) + SetResizable(bool) + ToggleUseLatestTransforms(bool) + SetCaptureDirectory() + ToggleStatusBar(bool) + ToggleCaptureTools(bool) + ToggleRotate90(bool) + +
      diff --git a/mapviz/src/mapviz_application.cpp b/mapviz/src/mapviz_application.cpp new file mode 100644 index 000000000..9c278184d --- /dev/null +++ b/mapviz/src/mapviz_application.cpp @@ -0,0 +1,64 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#include "mapviz/mapviz_application.h" + +#include "rclcpp/rclcpp.hpp" + +namespace mapviz +{ + MapvizApplication::MapvizApplication(int& argc, char** argv, rclcpp::Logger logger) : + QApplication(argc, argv), + logger_(logger) + { + } + + bool MapvizApplication::notify(QObject* receiver, QEvent* event) + { + try { + return QApplication::notify(receiver, event); + } + catch (const rclcpp::exceptions::RCLError& e) { + RCLCPP_ERROR(logger_, + "Unhandled RCLError in Qt event loop: %s", e.what()); + } + catch (const std::exception& e) { + RCLCPP_ERROR(logger_, + "Unhandled std::exception in Qt event loop: %s", e.what()); + } + + return false; + } + + void MapvizApplication::setLogger(const rclcpp::Logger &logger) + { + logger_ = logger; + } +} // namespace mapviz diff --git a/mapviz/src/mapviz_main.cpp b/mapviz/src/mapviz_main.cpp new file mode 100644 index 000000000..c5c81deee --- /dev/null +++ b/mapviz/src/mapviz_main.cpp @@ -0,0 +1,54 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include "mapviz/mapviz.hpp" +#include "mapviz/mapviz_application.h" +#include + +int main(int argc, char **argv) +{ + // Initialize ROS; spinning on the Node is handled in mapviz.cpp + rclcpp::init(argc, argv); + + // Initialize Qt resources + Q_INIT_RESOURCE(icons); + + // Initialize QT + mapviz::MapvizApplication app(argc, argv); + + // Initialize glut (for displaying text) + glutInit(&argc, argv); + + // Start mapviz + mapviz::Mapviz mapviz(true, argc, argv); + app.setLogger(mapviz.GetNode()->get_logger()); + mapviz.show(); + + return mapviz::MapvizApplication::exec(); +} diff --git a/mapviz/src/pluginselect.ui b/mapviz/src/pluginselect.ui new file mode 100644 index 000000000..0086d7fa1 --- /dev/null +++ b/mapviz/src/pluginselect.ui @@ -0,0 +1,90 @@ + + + pluginselect + + + + 0 + 0 + 400 + 300 + + + + Select New Display + + + true + + + + + + true + + + + + + + Qt::Vertical + + + QDialogButtonBox::Cancel|QDialogButtonBox::Ok + + + + + + + + + buttonBox + accepted() + pluginselect + accept() + + + 306 + 243 + + + 157 + 274 + + + + + buttonBox + rejected() + pluginselect + reject() + + + 316 + 260 + + + 286 + 274 + + + + + displaylist + doubleClicked(QModelIndex) + pluginselect + accept() + + + 162 + 114 + + + 209 + 294 + + + + + diff --git a/mapviz/src/resources/LICENSE b/mapviz/src/resources/LICENSE new file mode 100644 index 000000000..7989b1224 --- /dev/null +++ b/mapviz/src/resources/LICENSE @@ -0,0 +1,9 @@ +The Tango base icon theme is released to the Public Domain. + +http://tango.freedesktop.org/ + +--- + +The Silk icon theme is licensed under the Creative Commons Attribution 2.4 License. + +http://www.famfamfam.com/lab/icons/silk/ diff --git a/mapviz/src/resources/arrow_in.png b/mapviz/src/resources/arrow_in.png new file mode 100644 index 0000000000000000000000000000000000000000..745c65134db478a64016d63a7104e585452f2b9f GIT binary patch literal 600 zcmV-e0;m0nP)PbXFR5;7s zk=srhQ51%Gi+LO^77wV16dAzbG@wAMB7&i`(b(8xDqyU&#ij;pOFf{D;3PUo6_qH7 z@zCD%DY)SY{?6Vev}G>5=v^;XviDy5`&RNV6#!MZ;uAv`-s;%-AVco=6~AW@oV#X; zoCz$&Z(d;jHilq%pcXjuFe4{!G(v;>9DU>S79m;;B2ox|%Nj+MJXx5%p2GUiG!j?S z2%Y&cbj&LR9?=RJ#?#^`7Ar|SI}E|PVW`sPXn8=Gxtzq(^&D1yr10dMQz3B4@Y_lP zuSye$7RF#%H`Lg#dZzwixa6krr|(Pf7aR(KLtwFRkwCIM1ACSQfoTSJFpr@l7akX# z@D=Rv9@rED+g2a?Hy@G7U^9C3eb%8a_?P-$1a5i9WKAS#+qN85)~E=vH{A*SvKG1z z?dVFiLHkbgJ49E`%y@DfW=~%tej1}mHwt<_YB9MVMN|yeVJaZ7Jh>K;f_N^45j&cq zYibm9%abEw2)<1>?5kF^y-^EP;Mg%$3H-V=jgh?XuO0tco$p(rOKHJp92n09(Vu4V zFxf1qxGkd?5d9d=dtu7-P^)33OCji3)S!K#g=w8v*PN>ytji{-6HO9rn%8e zSad^gZEa<4bO1wgWnpw>WFU8GbZ8()Nlj2!fese{00R|CL_t(Y$EB1@h?`Xu$A9O3 znb1V0RG}*;k1}>Bb~>3%ZKuhXsjpg!x+oPv5TzA2E_CU*krrHuLWj|Upn|VWmo0*5 z#ac`gb4*Xn*ztAOS=eP0pYvsGH z&0INTZn<^ii5f9tHZ=*k>W#XV>{cUtRsCI7)4wU*1g0t(F2=LG@&0zXaA0e=xycH9 zhR_g!Eh_Brd~c^h0@0+RQT^BXfU9#|1pua3(it}(6DsUbBjbpS`{-8sh;Yr_ALzBo zvpC=e+LLFl=S{DTji7lKIK_ZreEsgt*l8Afgi4P%^=}q07$K*!$x@tdc)W2FPCl&@%s}$JON6ql3Ujx$X$R_>_xmsh zB)d0LQ1k{c+`7F;)?n7!uL($2QY>!UfII1@G3KLQaNsWs>#)MH+kc;k$=+)X-)IR; zR?{rTTkvPVdoN92n>9>_Pw_g`6z=T{TX3@ScLk=%ykrYMXpwExkH z&BECFno+?3fA)Z%#^=~#Jij_wwZV5=aG(PYwBRi-nsDr+f}8@vca~h|5j|dt=Kn}k zGn8W4fm}5J5Yo_R4H}zO^rWJ<`IFA#y6=@n3-yF!Q;KF8*tP)*v2Xn?jm;kbZ?(UW z97X-P(rBTcsH7=HbNr{6`R!19TzqI~@2dU!boG&^_FX*~07z8R{Ga$64&E!2IEBU- P00000NkvXXu0mjfPN=;~ literal 0 HcmV?d00001 diff --git a/mapviz/src/resources/icons.qrc b/mapviz/src/resources/icons.qrc new file mode 100644 index 000000000..bef973684 --- /dev/null +++ b/mapviz/src/resources/icons.qrc @@ -0,0 +1,11 @@ + + + arrow_in.png + image-x-generic.png + media-playback-pause.png + media-playback-stop.png + media-record.png + remove-icon-th.png + green-arrow.png + + diff --git a/mapviz/src/resources/image-x-generic.png b/mapviz/src/resources/image-x-generic.png new file mode 100644 index 0000000000000000000000000000000000000000..68da5027cf1aa23d6ca16eca99fd01025c82f776 GIT binary patch literal 558 zcmV+}0@3}6P)W8+D$+wD1(hb7ZnxQ)>0#;WVhSMx1M~WOW`<`(y-`~O?lW3>LcLKl zTI-Q&y-_m`fH8&#kDju%^KPiHOVtHdSC#>A0E7_i?tf4s(+R0|vB7qwa4%ryoayflfE%+4_t0F6nNx)`Z6qVHi=FPKTS#CU}=K zz{+W!#C9YIhrSlXiNSHls7#+^Yo;a`d;);QTNPSAe+|gJYq?(Q!^i)DrRoA3o7+RD wat;teu)4CGrROk3N|^!cjmHn~jryI>0JT`*mWx6Xs{jB107*qoM6N<$f&tz34gdfE literal 0 HcmV?d00001 diff --git a/mapviz/src/resources/media-playback-pause.png b/mapviz/src/resources/media-playback-pause.png new file mode 100644 index 0000000000000000000000000000000000000000..c8b4fe2251f885e2362b7ef36b85d6c3a178f7c8 GIT binary patch literal 464 zcmV;>0WbcEP)fkXfR0bNN% zK~y-)&5}!Q6hRDzzbd<#?kMWj*ortnatw&zNJwy`D9RZCg*!wL5UgjGNHA&oVHW+! z028qUFG{7aT)%!l;9p1DyPy6&J1w6g;v*0`zpdA6&YwMbzc2ds_4Qc{Lq320^k$!5 zzj=4I*=`dMd4^_&s>bET6_*!RsOsQmtPgN=Ura3y+#M02?|VLd`GAOE?sQ$Z@Y~Nf zBRBg~z|0U4c6Z+?v_MoabGo)gM7V2qh$y0hKP1q!JDR3JR1gu|*FYL}%{SWi2j!|- zoXv6H10NkUZ9^gMh7Gi5vrqV;>BD-9GXJBeDwkV$vM~cQN1dU zzy8jT>#CjwmhIYXH>X4*rDN*a%Jzqz;k7x5ETI&B|H7dZO>0000k2V8nL~zb!m)|pEA$SF2->jn-2hWj=^AH zPL5B%P2Stz^{Pr7#{fi4VAUxi)#JB!S3FMcd3k;2Es0696z@F%)>@ou3v24+*vND076Ixy33;9q2pAv`@ZPsg6f3A(Qi1k* zFkavM@*Aa-5I$9)h)6g*I{0=DB#I*EIzT(hNs`o~9IE3`*}+soD!;iA7_JPj`4{UQ XDQtDP+C_)X00000NkvXXu0mjf5}&Iv literal 0 HcmV?d00001 diff --git a/mapviz/src/resources/media-record.png b/mapviz/src/resources/media-record.png new file mode 100644 index 0000000000000000000000000000000000000000..2f66cdebbbfa20ba0407b3b76e7b684cd465132c GIT binary patch literal 653 zcmV;80&@L{P)L zlD|(=Q546&=ia{dwdoJ~#Pku{MHeYy0I>;}NE{r&iB$*x0u8%^ZY(Y`J1cV&;?#7g zO>7B6jVzV`ttCKhO5S_Cw)Y)})|z55CVZ2#+??~tJ>T;sX2x|St~Cw7H}0`O6x4vn z5?D|`5$VDo_YAze$83)U zl!zY1W@odh^>w}Hy682V@LU%%7=+(6;gm|My1DsfzS~{IU~mX15=8^C*!Q~|8#kPT z1E_WzVD6Xa0ZJj5PUAeE@7A}rUd%JU8!=G=Pj0QQM!Tn{=+*0hWdV)@*fwBUV9SDC zE+f9YtZC8ctG`SXzym#*)Gl^+p&AX4-w$aRAfn+9yj~BzRttJ6WfX{vMds$8D-hk0 zN}*FOgB=G#2(Xk8kq9Uf0RjQA>q6CP@W)~*(7#S|xPoFXbWToKo1BCof)E0N2xM76 zqXDm4g?DrWL4=E1P3pk65f2E+xA*os`pgW72sD65Df=)XpqVB}*I_prl{9l_1hByT z>8x1%%tRc@WFVvj1|SeY7zRR1OQ>hF9k}lEt8y@e zqrSb}Ij>Y+&nflh$|RPELL|gnJ&|}8N~JtsI808hCY-~=AFgdbz0aKcXOw^IBayrf nq!~zfz)ptwY+T=!fdADm63+C+aTjYY00000NkvXXu0mjfh3**Q literal 0 HcmV?d00001 diff --git a/mapviz/src/resources/remove-icon-th.png b/mapviz/src/resources/remove-icon-th.png new file mode 100644 index 0000000000000000000000000000000000000000..d58c33f7bf2b73b782f4c778b9616bdf913eb442 GIT binary patch literal 1035 zcmeAS@N?(olHy`uVBq!ia0vp^DImECr2LE2hFPu6yJH7 z9e8IjF}Blx7t3qr<~TL3?@sAew_d8$n%dTJ)|X#m;&QKh?b)!GA(}C4(Z}N_{Z8)G zlKie}oUzHzK#uhWrvj4TS*E z;V1LDi&&LKPOD5>^^>4KxC*67IBLk~}Q3RQXu0hMR<% z2Ajm`fF8qLizJfHI4d4}(d5)nDA~%hSd&Ze*nf={3Euz?!+$P~4B3`;Uy}|6xGEl- zvFHs;gmXi95Ra$`yF~Dm@Dm>s|4KVLztZS4SR#?Lod4}j>A03hJdgKEtg$hx6Fpk1 z_MK5F(S=J$(OE*|{9gBJ<2ybMHeYT23oi~9@!zZW-|s2U)5TLt<#P?@EHapW?|o6H zQ_Do4-JMPyI4S1EACh=F4)q%fbjkNH2K-56ar@XUC~(x?O<{_K1Y^LX#1M_;vlZvF z{C|`ERdcem?%s3FrXh08ll3EAjvKn!Okt2H3}8z9;m+CdP+ZlZ&3+1_!Jh>@EeHFJ z6xj4n9gwKe=yYtEB;kUSdc>pr?EyoLgQi=!QuHODmF&V2L{WO6+rpzYD3^N!iY zd7_N)>45a)q~Zxi?tgiL&ILY}`D&bH)Bf@H^_vF&V!{*q3%9Ln5=_0*s@I~CyxvC1 z`Q*|B7mb}}{T!;|-a-qXyb4tk`K>*pHXtUaXW4-l4UdwRTZy_ki^TT0X-tve4Y-w{ zu{a=EW6_qQ0ZxUD3mY!6FU~5_?9%ShdMz|%pG4^5;=q`skjUo?ZX|^C#yJ=E2Bz+9 zN$L(X{Uz_k0aO&PAp=yTJ|#Bulfu)5dn=oNMfy*7;!}Oy$F?|2gvo|;!}P~TI|C#_ zuZ5o6p+EDg!9GTV?G5)ftd30r<`dNt*NBpo#FA92~uAXhTQy=%(P0}8V+O^9|vlX1lbUrpH@mmtT}V`<;yxP!WTttDnm{r-UW|f_H_% literal 0 HcmV?d00001 diff --git a/mapviz/src/rqt_mapviz.cpp b/mapviz/src/rqt_mapviz.cpp new file mode 100644 index 000000000..67fd75f3d --- /dev/null +++ b/mapviz/src/rqt_mapviz.cpp @@ -0,0 +1,66 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include "mapviz/rqt_mapviz.h" +#include + +namespace mapviz +{ + + RqtMapviz::RqtMapviz() : + widget_(nullptr) + { + setObjectName("RqtMapviz"); + } + + void RqtMapviz::initPlugin(qt_gui_cpp::PluginContext& context) + { + // The plugin class doesn't really do very much -- just start Mapviz + // and add it to the context. + widget_ = new Mapviz(false, 0, nullptr); + widget_->setWindowFlags(Qt::Widget); + context.addWidget(widget_); + } + + void RqtMapviz::shutdownPlugin() + { + } + + void RqtMapviz::saveSettings(qt_gui_cpp::Settings& plugin_settings, + qt_gui_cpp::Settings& instance_settings) const + { + } + + void RqtMapviz::restoreSettings(const qt_gui_cpp::Settings& plugin_settings, + const qt_gui_cpp::Settings& instance_settings) + { + } +} // namespace mapviz + +PLUGINLIB_EXPORT_CLASS(mapviz::RqtMapviz, rqt_gui_cpp::Plugin) diff --git a/mapviz/src/select_frame_dialog.cpp b/mapviz/src/select_frame_dialog.cpp new file mode 100644 index 000000000..e41c2402d --- /dev/null +++ b/mapviz/src/select_frame_dialog.cpp @@ -0,0 +1,257 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + + +namespace mapviz +{ +std::string SelectFrameDialog::selectFrame( + std::shared_ptr tf_buffer, + QWidget *parent) +{ + SelectFrameDialog dialog(tf_buffer, parent); + dialog.allowMultipleFrames(false); + if (dialog.exec() == QDialog::Accepted) { + return dialog.selectedFrame(); + } else { + return ""; + } +} + +std::vector SelectFrameDialog::selectFrames( + std::shared_ptr tf_buffer, + QWidget *parent) +{ + SelectFrameDialog dialog(tf_buffer, parent); + dialog.allowMultipleFrames(true); + if (dialog.exec() == QDialog::Accepted) { + return dialog.selectedFrames(); + } else { + return std::vector(); + } +} + +SelectFrameDialog::SelectFrameDialog( + std::shared_ptr tf_buffer, + QWidget *parent) + : QDialog(parent) + , tf_buf_(tf_buffer) + , ok_button_(new QPushButton("&Ok")) + , cancel_button_(new QPushButton("&Cancel")) + , list_widget_(new QListWidget()) + , name_filter_(new QLineEdit()) +{ + QHBoxLayout *filter_box = new QHBoxLayout(); + filter_box->addWidget(new QLabel("Filter:")); + filter_box->addWidget(name_filter_); + + QHBoxLayout *button_box = new QHBoxLayout(); + button_box->addStretch(1); + button_box->addWidget(cancel_button_); + button_box->addWidget(ok_button_); + + QVBoxLayout *vbox = new QVBoxLayout(); + vbox->addWidget(list_widget_); + vbox->addLayout(filter_box); + vbox->addLayout(button_box); + setLayout(vbox); + + connect(ok_button_, SIGNAL(clicked(bool)), + this, SLOT(accept())); + connect(cancel_button_, SIGNAL(clicked(bool)), + this, SLOT(reject())); + connect(name_filter_, SIGNAL(textChanged(const QString &)), + this, SLOT(updateDisplayedFrames())); + + ok_button_->setDefault(true); + + allowMultipleFrames(false); + setWindowTitle("Select frames..."); + + resize(600, 600); + + fetch_frames_timer_id_ = startTimer(1000); + fetchFrames(); +} + +void SelectFrameDialog::timerEvent(QTimerEvent *event) +{ + if (event->timerId() == fetch_frames_timer_id_) { + fetchFrames(); + } +} + +void SelectFrameDialog::closeEvent(QCloseEvent *event) +{ + // We don't need to keep making requests from the ROS master. + killTimer(fetch_frames_timer_id_); + QDialog::closeEvent(event); +} + +void SelectFrameDialog::allowMultipleFrames( + bool allow) +{ + if (allow) { + list_widget_->setSelectionMode(QAbstractItemView::MultiSelection); + } else { + list_widget_->setSelectionMode(QAbstractItemView::SingleSelection); + } +} + +std::string SelectFrameDialog::selectedFrame() const +{ + std::vector selection = selectedFrames(); + if (selection.empty()) { + return ""; + } else { + return selection.front(); + } +} + +std::vector SelectFrameDialog::selectedFrames() const +{ + QModelIndexList qt_selection = list_widget_->selectionModel()->selectedIndexes(); + + std::vector selection; + selection.resize(qt_selection.size()); + for (int i = 0; i < qt_selection.size(); i++) { + if (!qt_selection[i].isValid()) { + continue; + } + + int row = qt_selection[i].row(); + if (row < 0 || static_cast(row) >= displayed_frames_.size()) { + continue; + } + + selection[i] = displayed_frames_[row]; + } + + return selection; +} + +void SelectFrameDialog::fetchFrames() +{ + if (tf_buf_ == nullptr) { + return; + } + + known_frames_.clear(); + tf_buf_->_getFrameStrings(known_frames_); + std::sort(known_frames_.begin(), known_frames_.end()); + updateDisplayedFrames(); +} + +std::vector SelectFrameDialog::filterFrames( + const std::vector &frames) const +{ + QString frame_filter = name_filter_->text(); + std::vector filtered; + + for (const auto & frame : frames) { + QString frame_name = QString::fromStdString(frame); + if (!frame_filter.isEmpty() && + !frame_name.contains(frame_filter, Qt::CaseInsensitive)) { + continue; + } + + filtered.push_back(frame); + } + + return filtered; +} + +void SelectFrameDialog::updateDisplayedFrames() +{ + std::vector next_displayed_frames = filterFrames(known_frames_); + + // It's a lot more work to keep track of the additions/removals like + // this compared to resetting the QListWidget's items each time, but + // it allows Qt to properly track the selection and current items + // across updates, which results in much less frustration for the user. + + std::set prev_names; + prev_names.insert(displayed_frames_.begin(), displayed_frames_.end()); + + std::set next_names; + next_names.insert(next_displayed_frames.begin(), next_displayed_frames.end()); + + std::set added_names; + std::set_difference(next_names.begin(), next_names.end(), + prev_names.begin(), prev_names.end(), + std::inserter(added_names, added_names.end())); + + std::set removed_names; + std::set_difference(prev_names.begin(), prev_names.end(), + next_names.begin(), next_names.end(), + std::inserter(removed_names, removed_names.end())); + + // Remove all the removed names + size_t removed = 0; + for (size_t i = 0; i < displayed_frames_.size(); i++) { + if (removed_names.count(displayed_frames_[i]) == 0) { + continue; + } + + QListWidgetItem *item = list_widget_->takeItem(static_cast(i - removed)); + delete item; + removed++; + } + + // Now we can add the new items. + for (size_t i = 0; i < next_displayed_frames.size(); i++) { + if (added_names.count(next_displayed_frames[i]) == 0) { + continue; + } + + list_widget_->insertItem(i, QString::fromStdString(next_displayed_frames[i])); + if (list_widget_->count() == 1) { + list_widget_->setCurrentRow(0); + } + } + + displayed_frames_.swap(next_displayed_frames); +} +} // namespace mapviz diff --git a/mapviz/src/select_service_dialog.cpp b/mapviz/src/select_service_dialog.cpp new file mode 100644 index 000000000..37c3b5bb6 --- /dev/null +++ b/mapviz/src/select_service_dialog.cpp @@ -0,0 +1,292 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +namespace mapviz +{ + void ServiceUpdaterThread::run() + { + std::map> service_map = + nh_->get_service_names_and_types(); + + if (allowed_datatype_.empty()) + { + std::vector service_list; + for (auto const& service : service_map) { + service_list.push_back(service.first); + } + Q_EMIT servicesFetched(service_list); + } else { + std::vector service_list; + for (auto const& service : service_map) { + if (std::find(service.second.begin(), + service.second.end(), + allowed_datatype_) != service.second.end()) { + service_list.push_back(service.first); + } + } + Q_EMIT servicesFetched(service_list); + } + } + + std::string SelectServiceDialog::selectService(rclcpp::Node::SharedPtr node, + const std::string& datatype, + QWidget* parent) + { + SelectServiceDialog dialog(node, datatype, parent); + dialog.setDatatypeFilter(datatype); + if (dialog.exec() == QDialog::Accepted) { + return dialog.selectedService(); + } else { + return ""; + } + } + + SelectServiceDialog::SelectServiceDialog(const rclcpp::Node::SharedPtr& node, + const std::string& datatype, + QWidget* parent) + : QDialog(parent) + , nh_(node) + , allowed_datatype_(datatype) + , cancel_button_(new QPushButton("&Cancel")) + , list_widget_(new QListWidget()) + , name_filter_(new QLineEdit()) + , ok_button_(new QPushButton("&Ok")) + { + QHBoxLayout *filter_box = new QHBoxLayout(); + filter_box->addWidget(new QLabel("Filter:")); + filter_box->addWidget(name_filter_); + + QHBoxLayout *button_box = new QHBoxLayout(); + button_box->addStretch(1); + button_box->addWidget(cancel_button_); + button_box->addWidget(ok_button_); + + QVBoxLayout *vbox = new QVBoxLayout(); + vbox->addWidget(list_widget_); + vbox->addLayout(filter_box); + vbox->addLayout(button_box); + setLayout(vbox); + + // This is ugly, but necessary in order to be able to send a std::vector + // via a queued signal/slot connection. + qRegisterMetaType("ServiceStringVector"); + + connect(ok_button_, SIGNAL(clicked(bool)), + this, SLOT(accept())); + connect(cancel_button_, SIGNAL(clicked(bool)), + this, SLOT(reject())); + connect(name_filter_, SIGNAL(textChanged(const QString &)), + this, SLOT(updateDisplayedServices())); + + ok_button_->setDefault(true); + + setWindowTitle("Select service..."); + + fetch_services_timer_id_ = startTimer(5000); + fetchServices(); + } + + SelectServiceDialog::~SelectServiceDialog() + { + if (worker_thread_) + { + // If the thread's parent is destroyed before the thread has finished, + // it will cause a segmentation fault. We'll wait a few seconds for + // it to finish cleanly, and if that doesn't work, try to force it to + // die and wait a few more. + worker_thread_->wait(5000); + if (worker_thread_->isRunning()) + { + worker_thread_->terminate(); + worker_thread_->wait(2000); + } + } + } + + void SelectServiceDialog::fetchServices() + { + // If we don't currently have a worker thread or the previous one has + // finished, start a new one. + if (!worker_thread_ || worker_thread_->isFinished()) + { + worker_thread_.reset(new ServiceUpdaterThread(nh_, allowed_datatype_, this)); + QObject::connect(worker_thread_.get(), + SIGNAL(servicesFetched(ServiceStringVector)), + this, + SLOT(updateKnownServices(ServiceStringVector))); + QObject::connect(worker_thread_.get(), + SIGNAL(fetchingFailed(const QString)), + this, + SLOT(displayUpdateError(const QString))); + worker_thread_->start(); + } + } + + void SelectServiceDialog::updateKnownServices(ServiceStringVector services) + { + known_services_ = services; + updateDisplayedServices(); + } + + void SelectServiceDialog::displayUpdateError(const QString& error_msg) + { + killTimer(fetch_services_timer_id_); + QMessageBox mbox(this->parentWidget()); + mbox.setIcon(QMessageBox::Warning); + mbox.setText(error_msg); + mbox.exec(); + } + + std::vector SelectServiceDialog::filterServices() + { + std::vector filtered_services; + + QString filter_text = name_filter_->text(); + + for(const std::string& service : known_services_) + { + if (QString::fromStdString(service).contains(filter_text, Qt::CaseInsensitive)) + { + filtered_services.push_back(service); + } + } + + return filtered_services; + } + + void SelectServiceDialog::updateDisplayedServices() + { + std::vector next_displayed_services = filterServices(); + + // It's a lot more work to keep track of the additions/removals like + // this compared to resetting the QListWidget's items each time, but + // it allows Qt to properly track the selection and current items + // across updates, which results in much less frustration for the user. + + std::set prev_names; + for (const auto & displayed_service : displayed_services_) { + prev_names.insert(displayed_service); + } + + std::set next_names; + for (const auto & next_displayed_service : next_displayed_services) { + next_names.insert(next_displayed_service); + } + + std::set added_names; + std::set_difference(next_names.begin(), next_names.end(), + prev_names.begin(), prev_names.end(), + std::inserter(added_names, added_names.end())); + + std::set removed_names; + std::set_difference(prev_names.begin(), prev_names.end(), + next_names.begin(), next_names.end(), + std::inserter(removed_names, removed_names.end())); + + // Remove all the removed names + size_t removed = 0; + for (size_t i = 0; i < displayed_services_.size(); i++) { + if (removed_names.count(displayed_services_[i]) == 0) { + continue; + } + + QListWidgetItem *item = list_widget_->takeItem(i - removed); + delete item; + removed++; + } + + // Now we can add the new items. + for (size_t i = 0; i < next_displayed_services.size(); i++) { + if (added_names.count(next_displayed_services[i]) == 0) { + continue; + } + + list_widget_->insertItem(i, QString::fromStdString(next_displayed_services[i])); + if (list_widget_->count() == 1) { + list_widget_->setCurrentRow(0); + } + } + + displayed_services_.swap(next_displayed_services); + } + + void SelectServiceDialog::setDatatypeFilter(const std::string& datatype) + { + allowed_datatype_ = datatype; + updateDisplayedServices(); + } + + std::string SelectServiceDialog::selectedService() const + { + QModelIndex qt_selection = list_widget_->selectionModel()->currentIndex(); + + if (qt_selection.isValid()) { + int row = qt_selection.row(); + if (row < static_cast(displayed_services_.size())) { + return displayed_services_[row]; + } + } + + return ""; + } + + void SelectServiceDialog::timerEvent(QTimerEvent* event) + { + if (event->timerId() == fetch_services_timer_id_) { + fetchServices(); + } + } + + void SelectServiceDialog::closeEvent(QCloseEvent* event) + { + // We don't need to keep making requests from the ROS master. + killTimer(fetch_services_timer_id_); + QDialog::closeEvent(event); + } +} // namespace mapviz diff --git a/mapviz/src/select_topic_dialog.cpp b/mapviz/src/select_topic_dialog.cpp new file mode 100644 index 000000000..0c9e41091 --- /dev/null +++ b/mapviz/src/select_topic_dialog.cpp @@ -0,0 +1,335 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + + +namespace mapviz +{ +std::string SelectTopicDialog::selectTopic( + const rclcpp::Node::SharedPtr& node, + const std::string &datatype, + QWidget *parent) +{ + std::vector datatypes; + datatypes.push_back(datatype); + return selectTopic(node, datatypes, parent); +} + +std::string SelectTopicDialog::selectTopic( + const rclcpp::Node::SharedPtr& node, + const std::string &datatype1, + const std::string &datatype2, + QWidget *parent) +{ + std::vector datatypes; + datatypes.push_back(datatype1); + datatypes.push_back(datatype2); + return selectTopic(node, datatypes, parent); +} + +std::string SelectTopicDialog::selectTopic( + const rclcpp::Node::SharedPtr& node, + const std::vector &datatypes, + QWidget *parent) +{ + SelectTopicDialog dialog(node, parent); + dialog.allowMultipleTopics(false); + dialog.setDatatypeFilter(datatypes); + if (dialog.exec() == QDialog::Accepted) { + return dialog.selectedTopic(); + } else { + return std::string(); + } +} + +std::vector SelectTopicDialog::selectTopics( + const rclcpp::Node::SharedPtr& node, + const std::string &datatype, + QWidget *parent) +{ + std::vector datatypes; + datatypes.push_back(datatype); + return selectTopics(node, datatypes, parent); +} + +std::vector SelectTopicDialog::selectTopics( + const rclcpp::Node::SharedPtr& node, + const std::string &datatype1, + const std::string &datatype2, + QWidget *parent) +{ + std::vector datatypes; + datatypes.push_back(datatype1); + datatypes.push_back(datatype2); + return selectTopics(node, datatypes, parent); +} + +std::vector SelectTopicDialog::selectTopics( + const rclcpp::Node::SharedPtr& node, + const std::vector &datatypes, + QWidget *parent) +{ + SelectTopicDialog dialog(node, parent); + dialog.allowMultipleTopics(true); + dialog.setDatatypeFilter(datatypes); + if (dialog.exec() == QDialog::Accepted) { + return dialog.selectedTopics(); + } else { + return std::vector(); + } +} + +SelectTopicDialog::SelectTopicDialog(const rclcpp::Node::SharedPtr& node, QWidget *parent) + : + nh_(node), + ok_button_(new QPushButton("&Ok")), + cancel_button_(new QPushButton("&Cancel")), + list_widget_(new QListWidget()), + name_filter_(new QLineEdit()) +{ + QHBoxLayout *filter_box = new QHBoxLayout(); + filter_box->addWidget(new QLabel("Filter:")); + filter_box->addWidget(name_filter_); + + QHBoxLayout *button_box = new QHBoxLayout(); + button_box->addStretch(1); + button_box->addWidget(cancel_button_); + button_box->addWidget(ok_button_); + + QVBoxLayout *vbox = new QVBoxLayout(); + vbox->addWidget(list_widget_); + vbox->addLayout(filter_box); + vbox->addLayout(button_box); + setLayout(vbox); + + connect(ok_button_, SIGNAL(clicked(bool)), + this, SLOT(accept())); + connect(cancel_button_, SIGNAL(clicked(bool)), + this, SLOT(reject())); + connect(name_filter_, SIGNAL(textChanged(const QString &)), + this, SLOT(updateDisplayedTopics())); + + ok_button_->setDefault(true); + + allowMultipleTopics(false); + setWindowTitle("Select topics..."); + + fetch_topics_timer_id_ = startTimer(1000); + fetchTopics(); +} + +void SelectTopicDialog::timerEvent(QTimerEvent *event) +{ + if (event->timerId() == fetch_topics_timer_id_) { + fetchTopics(); + } +} + +void SelectTopicDialog::closeEvent(QCloseEvent *event) +{ + // We don't need to keep making requests from the ROS master. + killTimer(fetch_topics_timer_id_); + QDialog::closeEvent(event); +} + +void SelectTopicDialog::allowMultipleTopics( + bool allow) +{ + if (allow) { + list_widget_->setSelectionMode(QAbstractItemView::MultiSelection); + } else { + list_widget_->setSelectionMode(QAbstractItemView::SingleSelection); + } +} + +void SelectTopicDialog::setDatatypeFilter( + const std::vector &datatypes) +{ + allowed_datatypes_.clear(); + for (const auto & datatype : datatypes) { + allowed_datatypes_.insert(datatype); + } + updateDisplayedTopics(); +} + +std::string SelectTopicDialog::selectedTopic() const +{ + std::vector selection = selectedTopics(); + if (selection.empty()) { + return std::string(); + } else { + return selection.front(); + } +} + +std::vector SelectTopicDialog::selectedTopics() const +{ + QModelIndexList qt_selection = list_widget_->selectionModel()->selectedIndexes(); + + std::vector selection; + selection.resize(qt_selection.size()); + for (int i = 0; i < qt_selection.size(); i++) { + if (!qt_selection[i].isValid()) { + continue; + } + + int row = qt_selection[i].row(); + if (row < 0 || static_cast(row) >= displayed_topics_.size()) { + continue; + } + + selection[i] = displayed_topics_[row]; + } + + return selection; +} + +static bool topicSort(const std::string &info1, + const std::string &info2) +{ + return info1 < info2; +} + +void SelectTopicDialog::fetchTopics() +{ + known_topics_ = nh_->get_topic_names_and_types(); + std::vector map_keys; + for (auto const& element : known_topics_) + { + map_keys.push_back(element.first); + } + std::sort(map_keys.begin(), map_keys.end(), topicSort); + updateDisplayedTopics(); +} + +std::vector SelectTopicDialog::filterTopics( + const std::map> &topics) const +{ + QString topic_filter = name_filter_->text(); + std::vector filtered; + + for (auto const& topic : topics) { + if (!allowed_datatypes_.empty()) { + // Skip any topic names that don't contain allowed types + bool missing_allowed_type = true; // Assume the worst + for (auto const& datatype : topic.second) { + if (allowed_datatypes_.count(datatype) == 1) { + missing_allowed_type = false; + break; + } + } + if (missing_allowed_type) { + continue; + } + } + + QString topic_name = QString::fromStdString(topic.first); + if (!topic_filter.isEmpty() && + !topic_name.contains(topic_filter, Qt::CaseInsensitive)) { + continue; + } + + filtered.push_back(topic.first); + } + + return filtered; +} + +void SelectTopicDialog::updateDisplayedTopics() +{ + std::vector next_displayed_topics = filterTopics(known_topics_); + + // It's a lot more work to keep track of the additions/removals like + // this compared to resetting the QListWidget's items each time, but + // it allows Qt to properly track the selection and current items + // across updates, which results in much less frustration for the user. + + std::set prev_names; + for (const auto & displayed_topic : displayed_topics_) { + prev_names.insert(displayed_topic); + } + + std::set next_names; + for (const auto & next_displayed_topic : next_displayed_topics) { + next_names.insert(next_displayed_topic); + } + + std::set added_names; + std::set_difference(next_names.begin(), next_names.end(), + prev_names.begin(), prev_names.end(), + std::inserter(added_names, added_names.end())); + + std::set removed_names; + std::set_difference(prev_names.begin(), prev_names.end(), + next_names.begin(), next_names.end(), + std::inserter(removed_names, removed_names.end())); + + // Remove all the removed names + size_t removed = 0; + for (size_t i = 0; i < displayed_topics_.size(); i++) { + if (removed_names.count(displayed_topics_[i]) == 0) { + continue; + } + RCLCPP_DEBUG(nh_->get_logger(), "Removing %s", displayed_topics_[i].c_str()); + + QListWidgetItem *item = list_widget_->takeItem(i - removed); + delete item; + removed++; + } + + // Now we can add the new items. + for (size_t i = 0; i < next_displayed_topics.size(); i++) { + if (added_names.count(next_displayed_topics[i]) == 0) { + continue; + } + + list_widget_->insertItem(i, QString::fromStdString(next_displayed_topics[i])); + RCLCPP_DEBUG(nh_->get_logger(), "Inserting %s", next_displayed_topics[i].c_str()); + if (list_widget_->count() == 1) { + list_widget_->setCurrentRow(0); + } + } + + displayed_topics_.swap(next_displayed_topics); +} +} // namespace mapviz diff --git a/mapviz/src/video_writer.cpp b/mapviz/src/video_writer.cpp new file mode 100644 index 000000000..08a59410d --- /dev/null +++ b/mapviz/src/video_writer.cpp @@ -0,0 +1,128 @@ +// ***************************************************************************** +// +// Copyright (c) 2017, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +#include + +#include + +#include +#include + +namespace mapviz +{ + bool VideoWriter::initializeWriter(const std::string& directory, int width, int height) + { + QMutexLocker locker(&video_mutex_); + if (!video_writer_) + { + width_ = width; + height_ = height; + + RCLCPP_INFO(rclcpp::get_logger("mapviz"), + "Initializing recording:\nWidth/Height/Filename: %d / %d / %s", + width_, + height_, + directory.c_str()); + video_writer_ = std::make_shared( + directory, + cv::VideoWriter::fourcc('M', 'J', 'P', 'G'), + 30, + cv::Size(width_, height_)); + + if (!video_writer_->isOpened()) + { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "Failed to open video file for writing."); + stop(); + return false; + } + } + + return true; + } + + bool VideoWriter::isRecording() + { + return video_writer_.get() != NULL; + } + + void VideoWriter::processFrame(QImage frame) + { + try + { + RCLCPP_DEBUG(rclcpp::get_logger("mapviz"), "VideoWriter::processFrame():"); + { + QMutexLocker locker(&video_mutex_); + if (!video_writer_) + { + RCLCPP_WARN(rclcpp::get_logger("mapviz"), "Got frame, but video writer wasn't open."); + return; + } + } + + cv::Mat image; + cv::Mat temp_image; + switch (frame.format()) + { + case QImage::Format_ARGB32: + // The image received should have its format set to ARGB32, but it's + // actually BGRA. Need to convert it to BGR and flip it vertically + // before giving it to the cv::VideoWriter. + image = cv::Mat(frame.height(), frame.width(), CV_8UC4, frame.bits()); + cv::cvtColor(image, temp_image, cv::COLOR_BGRA2BGR); + cv::flip(temp_image, image, 0); + break; + default: + RCLCPP_WARN(rclcpp::get_logger("mapviz"), "Unexpected image format: %d", frame.format()); + return; + } + + { + QMutexLocker locker(&video_mutex_); + if (video_writer_) + { + RCLCPP_DEBUG(rclcpp::get_logger("mapviz"), "Writing frame."); + video_writer_->write(image); + } + } + } + catch (const std::exception& e) + { + RCLCPP_ERROR(rclcpp::get_logger("mapviz"), "Error when processing video frame: %s", e.what()); + } + } + + void VideoWriter::stop() + { + RCLCPP_INFO(rclcpp::get_logger("mapviz"), "Stopping video recording."); + QMutexLocker locker(&video_mutex_); + video_writer_.reset(); + } +} // namespace mapviz diff --git a/mapviz_interfaces/CHANGELOG.rst b/mapviz_interfaces/CHANGELOG.rst new file mode 100644 index 000000000..a7bd4dfd5 --- /dev/null +++ b/mapviz_interfaces/CHANGELOG.rst @@ -0,0 +1,97 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mapviz_interfaces +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.3.0 (2023-08-24) +------------------ + +2.2.2 (2023-06-07) +------------------ + +2.2.1 (2023-05-30) +------------------ +* Updating maintainers list (`#778 `_) +* Contributors: David Anthony + +2.1.0 (2020-10-22) +------------------ + +2.0.0 (2020-05-13) +------------------ +* Port mapviz to ROS 2 (`#672 `_) +* Contributors: P. J. Reed + +1.2.0 (2019-09-04) +------------------ + +1.1.1 (2019-05-17) +------------------ + +1.1.0 (2019-02-20) +------------------ + +1.0.1 (2019-01-25) +------------------ + +1.0.0 (2019-01-23) +------------------ + +0.3.0 (2018-11-16) +------------------ + +0.2.6 (2018-07-31 09:02) +------------------------ + +0.2.5 (2018-04-12 16:26) +------------------------ + +0.2.4 (2017-08-11 09:57) +------------------------ + +0.2.3 (2016-12-10) +------------------ + +0.2.2 (2016-12-07) +------------------ + +0.2.1 (2016-10-23 22:33) +------------------------ + +0.2.0 (2016-06-23) +------------------ + +0.1.3 (2016-05-20 15:12) +------------------------ + +0.1.2 (2016-01-06 17:04) +------------------------ + +0.1.1 (2015-11-17) +------------------ + +0.1.0 (2015-09-29) +------------------ + +0.0.10 (2018-07-31 09:01) +------------------------- + +0.0.9 (2018-04-12 16:23) +------------------------ + +0.0.8 (2017-08-11 09:53) +------------------------ + +0.0.7 (2016-10-23 21:55) +------------------------ + +0.0.6 (2016-08-14) +------------------ + +0.0.5 (2016-05-20 14:40) +------------------------ + +0.0.4 (2016-01-06 17:00) +------------------------ + +0.0.3 (2015-09-28) +------------------ diff --git a/mapviz_interfaces/CMakeLists.txt b/mapviz_interfaces/CMakeLists.txt new file mode 100644 index 000000000..5bcf88748 --- /dev/null +++ b/mapviz_interfaces/CMakeLists.txt @@ -0,0 +1,25 @@ +### SET CMAKE POLICIES ### +cmake_minimum_required(VERSION 3.10...3.17) + +if(${CMAKE_VERSION} VERSION_LESS 3.12) + cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) +endif() + +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() +### END CMAKE POLICIES ### + +project(mapviz_interfaces) + +find_package(ament_cmake REQUIRED) +find_package(marti_common_msgs REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + srv/AddMapvizDisplay.srv + DEPENDENCIES marti_common_msgs +) + +ament_export_dependencies(rosidl_default_runtime) +ament_package() diff --git a/mapviz_interfaces/package.xml b/mapviz_interfaces/package.xml new file mode 100644 index 000000000..1ead0660f --- /dev/null +++ b/mapviz_interfaces/package.xml @@ -0,0 +1,24 @@ + + mapviz_interfaces + 2.3.0 + + ROS interfaces used by Mapviz + + P. J. Reed + Southwest Research Institute + BSD + https://github.com/swri-robotics/mapviz + + builtin_interfaces + marti_common_msgs + + rosidl_default_generators + + rosidl_default_runtime + + rosidl_interface_packages + + + ament_cmake + + diff --git a/mapviz_interfaces/srv/AddMapvizDisplay.srv b/mapviz_interfaces/srv/AddMapvizDisplay.srv new file mode 100644 index 000000000..60bb41177 --- /dev/null +++ b/mapviz_interfaces/srv/AddMapvizDisplay.srv @@ -0,0 +1,21 @@ +# Add or updates a mapviz display. + +string name # The name of the display. +string type # The plugin type. + +int32 draw_order # The display order. 1 corresponds + # to the first displayed, 2 to the + # second, -1 to last, and -2 to the + # second to last, etc. 0 will keep + # the current display order of an + # existing display and give a new + # display the last display order. + +bool visible # If the display should be visible. + +marti_common_msgs/KeyValue[] properties # Configuration properties. + +--- + +bool success # indicate successful run of triggered service +string message # informational, e.g. for error messages diff --git a/mapviz_plugins/CHANGELOG.rst b/mapviz_plugins/CHANGELOG.rst new file mode 100644 index 000000000..610f40dd6 --- /dev/null +++ b/mapviz_plugins/CHANGELOG.rst @@ -0,0 +1,374 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package mapviz_plugins +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.3.0 (2023-08-24) +------------------ + +2.2.2 (2023-06-07) +------------------ +* Add ros_environment as dependency +* Iron Compatibility (`#779 `_) +* Contributors: David Anthony + +2.2.1 (2023-05-30) +------------------ +* Updating maintainers list (`#778 `_) +* Fix Plan Route plugin in ROS2 Humble (`#765 `_) +* Merge pull request `#759 `_ from agyoungs/fix-marker-plugin-subs +* Check topic for type to determine which subscription callback to trigger +* Contributors: Alex Youngs, David Anthony, P. J. Reed + +2.1.0 (2020-10-22) +------------------ +* Constrain the minimum line and point marker sizes to be 1 pixel wide. (`#704 `_) +* ROS Foxy support (`#695 `_) +* Update the displayed distance continuously while moving a point. +* Use higher precision in the coordinate picker for wgs84 (`#692 `_) +* Clear the namespace list after hitting the clear button. (`#691 `_) +* Contributors: Matt Grogan, Matthew, P. J. Reed, Marc Alban + +2.0.0 (2020-05-13) +------------------ +* Port mapviz to ROS 2 (`#672 `_) +* Contributors: Daniel D'Souza, Matthew Bries, Matthew Grogan, P. J. Reed, Jason Gassaway, John Reyes, Jacob Hassold, Kevin Nickels, Roger Strain + +1.2.0 (2019-09-04) +------------------ +* Add text to measuring plugin (`#640 `_) +* Add mapviz plug-in for PoseStamped messages. (`#641 `_) +* Fix occupancy grid to load color scheme from configuration. (`#642 `_) +* Restore GL_UNPACK_ALIGNMENT to 4 to prevent corruption of Qt font rendering. (`#643 `_) +* Add ability to show and hide markers by namespace (`#636 `_) +* Fixed layout of MeasuringPlugin (`#633 `_) +* Fixed marker plugin to use swri_transform_util to ensure wgs84 markers work properly (`#635 `_) +* Contributors: Arkady Shapkin, Marc Alban, Matthew, Matthew Grogan, agyoungs + +1.1.1 (2019-05-17) +------------------ +* Textured Marker Adjustments (`#611 `_, `#616 `_) (`#625 `_) +* fixed issue `#623 `_ by updating UI field to read "Draw Style:" (`#624 `_) +* Contributors: mattrich37 + +1.1.0 (2019-02-20) +------------------ +* Improve MarkerPlugin (`#603 `_) + * Improved performance of MarkerPlugin::handleMarker() + * Support Text marker alpha channel + * Don't use QColor for glColor4f + * Use marker namespace and id as markers map key +* [mapviz_plugins/attitude_indicator] Minor refactoring and redundant logging removed (`#617 `_) +* 606 sequential measuring (`#607 `_) + * Moved distance calculation to trigger on release of mouse. Added case to prevent distance calculation while moving map. + * Added vertices and lines between measurement points. Left click to add point. Right click to delete. Added color selection for points and clear button to ui. + * Added cumulative distance measurements from multiple points + * Fixed individual and cumulative distance measurements. Changed it to only measure distance between points and not from fixed origin and first point + * Moved distance calculation into separate function which is called when deleting a point, adding a point, or rearranging points. +* Add image size check to textured marker plugin to prevent crashes. (`#613 `_) + * Add image size check to textured marker plugin to prevent crashes. +* Fixed typo in string (`#608 `_) +* 605 add reset button marker (`#609 `_) + * Added Clear all marker buttons, added case for clear all support to markers +* Contributors: Arkady Shapkin, Matthew, jbdaniel18 + +1.0.1 (2019-01-25) +------------------ +* Use shared tf manager in measuring_plugin (`#604 `_) +* Contributors: jgassaway + +1.0.0 (2019-01-23) +------------------ +* Sharing tf_manager\_ between main app and plugins (`#555 `_) +* Fix potential segfault in pointcloud plug-in. (`#602 `_) +* Add Measuring Plugin (`#598 `_) +* Contributors: Davide Faconti, Marc Alban, Matthew + +0.3.0 (2018-11-16) +------------------ +* Merge all -devel branches into a single master branch +* Don't transform laser scans twice (`#544 `_) +* Improving point_drawing plugins and bug fix of tf_plugin (`#557 `_) +* OpenGL rendering of PointClouds (2X speedup) (`#558 `_) +* Occupancy grid (new plugin) (`#568 `_) +* Bug fix in image plugin (`#563 `_) +* Fix Indigo build, clean up warnings (`#597 `_) +* Create Coordinate Picker plugin (`#593 `_) +* Contributors: Davide Faconti, Ed Venator, Edward Venator, Elliot Johnson, Jerry Towler, Marc Alban, Matthew, Matthew Bries, Mikael Arguedas, Neal Seegmiller, Nicholas Alton, P. J. Reed, Vincent Rousseau + +0.2.6 (2018-07-31) +------------------ +* Fix timestamp interval (`#588 `_) +* Update path_plugin.cpp (`#586 `_) +* Replace depcreated plugin macro with newer version +* Contributors: Matthew, P. J. Reed, camjaws + +0.2.5 (2018-04-12) +------------------ +* Add clear history functionality. +* Add support for newlines in text marker plugin (`#572 `_) +* New plugin to send commands to move_base +* Glew warning fixed (`#539 `_) +* Added "keep image ratio" to Image plugin (`#543 `_) +* Remove copy and paste of Print... +* PointCloud2 speed improvement (`#531 `_) +* Dead code removed (`#535 `_) +* Ratio added to robot_image_plugin (`#530 `_) +* Speed up improvement in LaserScan and PointCloud2 (`#525 `_) +* Re-add GPSFix plugin to kinetic-devel (`#519 `_) +* Add support for unpacking rgb8 in pointcloud2s +* Use non-deprecated pluginlib macro +* Add plug-in for drawing and publishing a polygon. +* change the signal that triggers AlphaEdited + minor changes (`#514 `_) +* Added timestamp display to odometry for kinetic +* Contributors: Davide Faconti, Marc Alban, Matthew Bries, Mikael Arguedas, P. J. Reed, jgassaway + +0.2.4 (2017-08-11) +------------------ +* Add /wgs84 frame to point click publisher when available. +* Transform cube and arrow markers properly +* Contributors: Marc Alban, P. J. Reed + +0.2.3 (2016-12-10) +------------------ +* Delete markers that have expired and remove error message. (`#454 `_) +* Fix segfault in pointcloud2 plug-in when pointcloud is empty. (`#450 `_) +* Initialize buffer size variable. (`#447 `_) +* Contributors: Marc Alban + +0.2.2 (2016-12-07) +------------------ +* Migrated OpenCV to 3.1 (default in Kinetic) +* General code cleanup of mapviz_plugins + This doesn't change any functionality; it's just cleaning up code. Notably, this will: + - Fix all warnings (notably lots of ones about type casting) + - Move all .ui files to their own directory + - Remove unused variables + - Remove commented-out code + - Make spacing and indentation consistent + - Make brace style consistent +* Contributors: Brian Holt, Marc Alban, P. J. Reed + +0.2.1 (2016-10-23) +------------------ +* Add a GUI for controlling the Image Transport (`#432 `_) + This will add a sub-menu under the "View" menu that will: + - List all available image transports + - Indicate which one is currently the default + - Allow the user to choose which one will be used for new ImageTransport subscriptions + - Save and restore this setting to Mapviz's config file + - Cause any `image` plugins using the default transport to resubscribe + In addition, the image plugin now has a menu that can be used to change the + transport for that specific plugin so that it is different from the default. + Fixes `#430 `_ + Conflicts: + mapviz/package.xml +* Fix icon colors for point drawing plugins (`#433 `_) + This was probably broken back when all of these were refactored to have a + single base class. It looks like the member variable that holds the color + used to draw the icon was never actually being updated. + Fixes `#426 `_ +* Add option to not scale arrows with zoom level + This adds a checkbox to all of the plugins that can draw a series of + coordinates as arrows; i. e., the NavSatFix, Odometry, and TF Frame + plugins. This checkbox will control whether the arrows are drawn at a fixed + size regardless of zoom level or whether they are scaled with the zoom level. + Resolves `#414 `_ +* Fix signed comparison warnings in mapviz_plugins +* Adding a way for plugin config widgets to resize + - Adding an event plugins can emit to indicate their geometry has changed + - Modifying the PCL2 plugin to use it as an example + Fixes `#393 `_ +* Adding default values for uninitialized variables + Resolves `#372 `_ +* Creates and implements an abstract class for drawing point paths + Updates gps,navsat,odometry,path, and tf_frame plugins to use the + abstract point drawing class. Also adds the draw laps functionality + which will change the color of the path as it passes a base point for + ease of visibility, currently implemented on gps and odometry plugins. + Conflicts: + mapviz_plugins/CMakeLists.txt + mapviz_plugins/include/mapviz_plugins/gps_plugin.h + mapviz_plugins/src/gps_config.ui + mapviz_plugins/src/gps_plugin.cpp +* Ensuring that Mapviz won't subscribe to empty topic names (`#379 `_) + Clean up and made more consistent the code for handling subscriptions for all topics. + The behavior is now: + - All input is trimmed before processing + - If a topic name is empty, the old subscriber will be shut down and will not subscribe to the empty topic + Resolves `#327 `_ +* Fixing some typos in documentation. +* Implementing support for the ARROW marker type + Resolves `#365 `_ +* Contributors: Ed Venator, Marc Alban, P. J. Reed + +0.2.0 (2016-06-23) +------------------ +* Update Qt to version 5 +* Fixing a crash in the PointCloud2 plugin + Also sneaking in a few more changes: + - Caching transformed clouds to improve performance + - Properly saving the value of the "Color Transformer" combo box +* Returning "false" if no other code handles the mouse event + Fixes `#360 `_ +* Contributors: Ed Venator, P. J. Reed + +0.1.3 (2016-05-20) +------------------ +* Implement mapviz plug-in for calling the marti_nav_msgs::PlanRoute service. +* Migrate route plugin to use swri_route_util + This change migrates the mapviz route plugin to use swri_route_util to + get consistent behavior with route transforms and route position + interpolation. As part of this change, the route is now transformed + with each draw so that it will correctly move around if the transform + between the fixed frame and the route frame is not constant. +* Add support for mono8 textured markers. +* Implement service for adding and modifying mapviz displays. +* Adding attitude indicator plugin. +* Changing some "unsigned long"s to "size_t"s. +* Storing source frames individually for plugins w/ buffers +* Fix for `#265 `_; message source frames don't update + Several plugins were storing the source frames of messages received when + they first received a message but never updating them, so subsequent + messages in different frames would be rendered incorrectly. +* Fix for `#339 `_; explicitly depending on OpenCV 2 +* Fix route position search + The route position search would ignore a matching point unless it is + already transformed, which means that only points that have already been + searched and missed would be transformed. + The new logic looks first for the match, then transforms as necessary. + Unmatched points are ignored. +* Guard against repeated transforms + A point should only be transformed once, because the mapviz transforms + are set outside the plugins; `TransformPoint` will now only transform + un-transformed points. +* Remove unused variable + prev_position\_ is set, but never actually used. +* Adds route plugin with routeposition marker attachment. +* Also updating the disparity plugin +* Fixing `#317 `_ + First, the model view matrix needs to be saved and restored around + QPainter operations because Qt clears several GL variables. Also, the + image plugin needed to explicitly call glMatrixMode(GL_PROJECTION); + it does a few operations on the projection matrix and was just assuming + that was the current matrix mode. Also, I added a function that plugins + need to override if they want to do QPainter operations; this will + eliminate unnecessary overhead for plugins that do not. +* Declaring types for Qt signal/slot use properly +* Fixing some typos +* Doing GL drawing on the main thread for `#313 `_ +* GPS plugin snuck back into CMakeLists.txt +* A plugin for displaying std_msgs/Strings +* Marker plugin will use a QPainter to draw text + I modified the Marker plugin so that it will use a QPainter to draw + text labels rather than OpenGL commands. This doesn't really add any + functional benefit; it's meant to serve as an example of how to use + the QPainter. +* Fixing warnings and cleaning up formatting +* updated mapviz_plugins.xml +* add pointcloud2 plugin +* Update map canvas at a fixed rate. + This update adds a timer to the map canvas to repaint at a fixed rate. + The default rate is 50 Hz, but there is a method to change it (not + exposed to the UI at the moment). 50Hz was chosen because it is fast + enough to give smooth animations and we almost always are running + mapviz with at least one plugin triggering updates from a 50Hz topic. +* Making the Image plugin use image_transport. + The image_transport package provides support for transparently + subscribing and publishing to topics using low-bandwidth compressed + formats; if the publisher supports it, this will cause the Image + plugin to consume far less bandwidth than before. +* Handle cases where marker topic changes message types. + This commit makes a better effort to properly support cases where a + marker topic changes between Marker and MarkerArray during runtime. +* Use ROS' shapeshifter to handle marker/marker arrays. +* This commit adds a class called SelectFrameDialog that plugins can use + to present the user with a dialog to choose a TF frame. The dialog + sorts the frames by name and provides an edit box that the user can + use to filter the frames to a specific substring. +* Indigo compatibility. + Fixing swri_transform_util and swri_yaml_util API changes from + Hydro to Indigo. +* Also filtering out clicks that are held for too long. +* Adding a check to prevent the click event from firing if the user is dragging the mouse. +* Fixing an issue that could cause the click publisher plugin's publisher to not be initialized after it's first added. +* Removing some code I had added for debugging. +* Adding a plugin that, when a user clicks on a point, will publish that point's coordinates to a topic. +* Adding color button widget and updating plugins. + This commit adds a subclass of QPushButton called ColorButton that + implements a widget for displaying and selecting colors. We've been + doing this manually everywhere with duplicated code. This is a simple + abstraction but allows us to elminate a lot of duplication, especially + in plugins that have multiple color selections. +* Adds SelectTopicDialog to mapviz. + This commit adds the SelectTopicDialog that can be used in plugins to + provide the user with a dialog to select topics. Typically we have + done this with a lot of duplicated code across all the plugins. This + commit also updates the plugins in mapviz_plugins to use the new + dialog. + The new dialog provides several benefits: + - Reduced code duplication + - Simplifies writing new plugins + - Common behavior between all plugins + - Topics sorted by name + - User can filter topics by substring + - Continuously checks the master for new topics while the dialog is open. +* Contributors: Elliot Johnson, Jerry Towler, Marc Alban, Nicholas Alton, P. J. Reed + +0.1.2 (2016-01-06) +------------------ +* Enables the possibility to load a one-layer tile set +* Sorts topic, plug-in, and frame lists in selection dialogs. +* Fixes tf plug-in update. +* Contributors: Marc Alban, Vincent Rousseau + +0.1.1 (2015-11-17) +------------------ +* Extensions for geo files (PR `#262 `_) +* Adds a plugin to visualize laser scans. + Display features are based on the laserscan plugin for rviz: + * Points can be colored by range, or x/y/z axis + * Points can be colored by interpolation between two colors or rainbow coloring +* Adds a plugin to visualize sensor_msgs/NavSatFix msgs, based on the old GPSFix plugin +* Contributors: Claudio Bandera, Ed Venator, Vincent Rousseau + +0.1.0 (2015-09-29) +------------------ +* Removes gps plugin, since gps_common is not in ROS Jade. See issue + `#238 `_. +* Contributors: Edward Venator + +0.0.3 (2015-09-28) +------------------ + +0.0.2 (2015-09-27) +------------------ +* Adds missing qt4_opengl dependency + +0.0.1 (2015-09-27) +------------------ +* Renames all marti_common packages that were renamed. + (See http://github.com/swri-robotics/marti_common/issues/231) +* Fixes catkin_lint problems that could prevent installation. +* Exports the mapviz_plugins library +* Adds find_package(OpenCV REQUIRED) to cmake config +* adds icon to gps plug-in +* includes yaml_util header in mapviz plug-in base class +* adds gps_common dependency +* Sets the point orientation properly based on the GPSFix track. +* Converts incoming GPSFix points to the local XY frame as they arrive. +* Changes the GPS plugin to always transform from the local XY frame. +* Adds a plugin to display GPSFix data. +* Fixes a few instances where "multires" was typoed as "mutlires". +* updates cmake version to squash the CMP0003 warning +* removes dependencies on build_tools +* switches format 2 package definition +* Updates marker_plugin to correctly handle marker orientation. +* adds color selection for path visualization +* display preview icon next to plug-in names +* sets the z component of path points to 0 before transforming to avoid uninitialized values +* fixes missing organization in license text +* fixes for GLEW/GL include order +* catkinize mapviz +* changes license to BSD +* adds license and readme files +* Contributors: Edward Venator, Elliot Johnson, Marc Alban, P. J. Reed diff --git a/mapviz_plugins/CMakeLists.txt b/mapviz_plugins/CMakeLists.txt new file mode 100644 index 000000000..1f22584bb --- /dev/null +++ b/mapviz_plugins/CMakeLists.txt @@ -0,0 +1,242 @@ +### SET CMAKE POLICIES ### +cmake_minimum_required(VERSION 3.10...3.17) + +if(${CMAKE_VERSION} VERSION_LESS 3.12) + cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) +endif() + +if (NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(${CMAKE_VERSION} VERSION_EQUAL "3.11.0" OR ${CMAKE_VERSION} VERSION_GREATER "3.11.0") + cmake_policy(SET CMP0072 NEW) +endif() + +if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() +### END CMAKE POLICIES ### + +project(mapviz_plugins + LANGUAGES CXX) + +# Ros Packages +find_package(ament_cmake REQUIRED) +find_package(ament_index_cpp REQUIRED) +find_package(cv_bridge REQUIRED) +find_package(gps_msgs REQUIRED) +find_package(image_transport REQUIRED) +find_package(map_msgs REQUIRED) +find_package(mapviz REQUIRED) +find_package(marti_common_msgs REQUIRED) +find_package(marti_nav_msgs REQUIRED) +find_package(marti_sensor_msgs REQUIRED) +find_package(marti_visualization_msgs REQUIRED) +# find_package(move_base_msgs REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(sensor_msgs REQUIRED) +find_package(std_msgs REQUIRED) +find_package(stereo_msgs REQUIRED) +find_package(swri_image_util REQUIRED) +find_package(swri_math_util REQUIRED) +find_package(swri_route_util REQUIRED) +find_package(swri_transform_util REQUIRED) +find_package(tf2_geometry_msgs REQUIRED) +find_package(tf2 REQUIRED) +find_package(tf2_ros REQUIRED) +find_package(visualization_msgs REQUIRED) + +### QT ### +find_package(Qt5Core REQUIRED) +find_package(Qt5Gui REQUIRED) +find_package(Qt5OpenGL REQUIRED) +find_package(Qt5Widgets REQUIRED) +add_definitions(-DWFlags=WindowFlags) + +find_package(OpenCV COMPONENTS core imgproc REQUIRED) + +### OpenGL ### +find_package(OpenGL REQUIRED) +find_package(GLUT REQUIRED) + +# Fix conflict between Boost signals used by tf and QT signals used by mapviz +add_definitions(-DQT_NO_KEYWORDS) + +# Need to include the current dir to include the results of building Qt UI files +set(CMAKE_INCLUDE_CURRENT_DIR ON) + +set(UI_FILES + ui/attitude_indicator_config.ui + ui/coordinate_picker_config.ui + ui/disparity_config.ui + ui/draw_polygon_config.ui + ui/float_config.ui + ui/gps_config.ui + ui/grid_config.ui + ui/image_config.ui + ui/laserscan_config.ui + ui/marker_config.ui + ui/measuring_config.ui + # ui/move_base_config.ui + ui/navsat_config.ui + ui/occupancy_grid_config.ui + ui/odometry_config.ui + ui/path_config.ui + ui/plan_route_config.ui + ui/point_click_publisher_config.ui + ui/pointcloud2_config.ui + ui/pose_config.ui + ui/robot_image_config.ui + ui/route_config.ui + ui/string_config.ui + ui/textured_marker_config.ui + ui/tf_frame_config.ui + ui/topic_select.ui +) + +set(SRC_FILES + src/attitude_indicator_plugin.cpp + src/canvas_click_filter.cpp + src/coordinate_picker_plugin.cpp + src/disparity_plugin.cpp + src/draw_polygon_plugin.cpp + src/float_plugin.cpp + src/gps_plugin.cpp + src/grid_plugin.cpp + src/image_plugin.cpp + src/laserscan_plugin.cpp + src/marker_plugin.cpp + src/measuring_plugin.cpp + # src/move_base_plugin.cpp + src/navsat_plugin.cpp + src/occupancy_grid_plugin.cpp + src/odometry_plugin.cpp + src/path_plugin.cpp + src/placeable_window_proxy.cpp + src/plan_route_plugin.cpp + src/point_click_publisher_plugin.cpp + src/pointcloud2_plugin.cpp + src/point_drawing_plugin.cpp + src/pose_plugin.cpp + src/robot_image_plugin.cpp + src/route_plugin.cpp + src/string_plugin.cpp + src/textured_marker_plugin.cpp + src/tf_frame_plugin.cpp +) + +set(HEADER_FILES + include/${PROJECT_NAME}/attitude_indicator_plugin.h + include/${PROJECT_NAME}/canvas_click_filter.h + include/${PROJECT_NAME}/coordinate_picker_plugin.h + include/${PROJECT_NAME}/disparity_plugin.h + include/${PROJECT_NAME}/draw_polygon_plugin.h + include/${PROJECT_NAME}/float_plugin.h + include/${PROJECT_NAME}/gps_plugin.h + include/${PROJECT_NAME}/grid_plugin.h + include/${PROJECT_NAME}/image_plugin.h + include/${PROJECT_NAME}/laserscan_plugin.h + include/${PROJECT_NAME}/marker_plugin.h + include/${PROJECT_NAME}/measuring_plugin.h + # include/${PROJECT_NAME}/move_base_plugin.h + include/${PROJECT_NAME}/navsat_plugin.h + include/${PROJECT_NAME}/occupancy_grid_plugin.h + include/${PROJECT_NAME}/odometry_plugin.h + include/${PROJECT_NAME}/path_plugin.h + include/${PROJECT_NAME}/placeable_window_proxy.h + include/${PROJECT_NAME}/plan_route_plugin.h + include/${PROJECT_NAME}/point_click_publisher_plugin.h + include/${PROJECT_NAME}/pointcloud2_plugin.h + include/${PROJECT_NAME}/point_drawing_plugin.h + include/${PROJECT_NAME}/pose_plugin.h + include/${PROJECT_NAME}/robot_image_plugin.h + include/${PROJECT_NAME}/route_plugin.h + include/${PROJECT_NAME}/string_plugin.h + include/${PROJECT_NAME}/textured_marker_plugin.h + include/${PROJECT_NAME}/tf_frame_plugin.h +) + +qt5_wrap_ui(UI_SRC_FILES ${UI_FILES}) +qt5_wrap_cpp(MOC_FILES ${HEADER_FILES}) + +add_library(${PROJECT_NAME} SHARED + ${MOC_FILES} + ${SRC_FILES} + ${UI_SRC_FILES} +) + +target_include_directories(${PROJECT_NAME} + PUBLIC + include) + +target_compile_definitions(${PROJECT_NAME} + PUBLIC + "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") + +# Iron and later switched some cv_bridge files to .hpp from .h +if ("$ENV{ROS_DISTRO}" STRLESS "iron") + target_compile_definitions(${PROJECT_NAME} PRIVATE "-DUSE_CVBRIDGE_H_FILES") +endif() + +ament_target_dependencies(${PROJECT_NAME} + ament_cmake + ament_index_cpp + cv_bridge + gps_msgs + image_transport + map_msgs + mapviz + marti_common_msgs + marti_nav_msgs + marti_sensor_msgs + marti_visualization_msgs + # move_base_msgs + nav_msgs + pluginlib + rclcpp + sensor_msgs + std_msgs + stereo_msgs + swri_image_util + swri_math_util + swri_route_util + swri_transform_util + tf2 + tf2_geometry_msgs + tf2_ros + visualization_msgs +) +target_link_libraries(${PROJECT_NAME} + Qt5::Core + Qt5::Gui + Qt5::OpenGL + Qt5::Widgets + ${GLU_LIBRARY} + ${GLUT_LIBRARY} + opencv_core + opencv_imgproc + opencv_highgui +) + +### Install the plugins ### + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION include/${PROJECT_NAME} + FILES_MATCHING PATTERN "*.h" +) + +install(TARGETS ${PROJECT_NAME} + RUNTIME DESTINATION lib/${PROJECT_NAME} + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib +) + +pluginlib_export_plugin_description_file(mapviz mapviz_plugins.xml) + +ament_export_dependencies(${RUNTIME_DEPS} Qt) +ament_export_include_directories(include) +ament_export_libraries(${PROJECT_NAME}) +ament_package() diff --git a/mapviz_plugins/include/mapviz_plugins/attitude_indicator_plugin.h b/mapviz_plugins/include/mapviz_plugins/attitude_indicator_plugin.h new file mode 100644 index 000000000..7a956a6a2 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/attitude_indicator_plugin.h @@ -0,0 +1,116 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__ATTITUDE_INDICATOR_PLUGIN_H_ +#define MAPVIZ_PLUGINS__ATTITUDE_INDICATOR_PLUGIN_H_ + +// Include mapviz_plugin.h first to ensure GL deps are included in the right order +#include + +// QT libraries +#include +#include +#include +#include + +// ROS libraries +#include +#include +#include +#include +#include + +#include +#include + +// C++ standard libraries +#include +#include +#include + +// QT autogenerated files +#include "ui_attitude_indicator_config.h" + +namespace mapviz_plugins +{ +class AttitudeIndicatorPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + + public: + AttitudeIndicatorPlugin(); + ~AttitudeIndicatorPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override; + + void Draw(double x, double y, double scale) override; + + void Transform() override {} + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + void drawBackground(); + void drawBall(); + void drawPanel(); + + void timerEvent(QTimerEvent *) override; + + protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + + private: + void AttitudeCallbackImu(sensor_msgs::msg::Imu::ConstSharedPtr imu); + void AttitudeCallbackOdom(nav_msgs::msg::Odometry::ConstSharedPtr odometry); + void AttitudeCallbackPose(geometry_msgs::msg::Pose::ConstSharedPtr pose); + void applyAttitudeOrientation(const geometry_msgs::msg::Quaternion &orientation); + + double pitch_; + double roll_; + double yaw_; + PlaceableWindowProxy placer_; + QWidget* config_widget_; + rclcpp::Subscription::SharedPtr imu_sub_; + rclcpp::Subscription::SharedPtr odom_sub_; + rclcpp::Subscription::SharedPtr pose_sub_; + std::string topic_; + std::vector topics_; + Ui::attitude_indicator_config ui_{}; +}; // class AttitudeIndicatorPlugin +} // namespace mapviz_plugins +#endif // MAPVIZ_PLUGINS__ATTITUDE_INDICATOR_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/canvas_click_filter.h b/mapviz_plugins/include/mapviz_plugins/canvas_click_filter.h new file mode 100644 index 000000000..80291d126 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/canvas_click_filter.h @@ -0,0 +1,73 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__CANVAS_CLICK_FILTER_H_ +#define MAPVIZ_PLUGINS__CANVAS_CLICK_FILTER_H_ + +#include +#include + +/** + * This is a very simple event filter that listens for mouseReleased events; + * when it sees one, it emits a signal with the given point. + * + * Click events are filtered by how long the mouse was held down and how far the + * cursor moved in order to prevent the user holding and dragging the map + * from firing a click event. By default, "clicks" that take longer than 500ms + * or move longer than 2 pixels are ignored. + */ +namespace mapviz_plugins +{ +class CanvasClickFilter : public QObject +{ + Q_OBJECT + +public: + CanvasClickFilter(); + + void setMaxClickTime(qint64 max_ms); + void setMaxClickMovement(qreal max_distance); + +Q_SIGNALS: + void pointClicked(const QPointF&); + +protected: + bool eventFilter(QObject *object, QEvent* event) override; + +private: + bool is_mouse_down_; + QPointF mouse_down_pos_; + qint64 mouse_down_time_; + + qint64 max_ms_; + qreal max_distance_; +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__CANVAS_CLICK_FILTER_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/coordinate_picker_plugin.h b/mapviz_plugins/include/mapviz_plugins/coordinate_picker_plugin.h new file mode 100644 index 000000000..28c4262f2 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/coordinate_picker_plugin.h @@ -0,0 +1,94 @@ +// ***************************************************************************** +// +// Copyright (c) 2018, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__COORDINATE_PICKER_PLUGIN_H_ +#define MAPVIZ_PLUGINS__COORDINATE_PICKER_PLUGIN_H_ + +#include + +// ROS Libraries +#include + +// Mapviz libraries +#include + +// C++ Standard Libraries +#include + +// QT autogenerated files +#include "ui_coordinate_picker_config.h" + +namespace mapviz_plugins +{ +class CoordinatePickerPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + + public: + CoordinatePickerPlugin(); + ~CoordinatePickerPlugin() override; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override { } + + void Draw(double x, double y, double scale) override; + void Transform() override { } + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected: + bool eventFilter(QObject* object, QEvent* event) override; + bool handleMousePress(QMouseEvent*); + bool handleMouseRelease(QMouseEvent*); + bool handleMouseMove(QMouseEvent*); + + protected Q_SLOTS: + void SelectFrame(); + void FrameEdited(); + void ToggleCopyOnClick(int state); + void ClearCoordList(); + + private: + Ui::coordinate_picker_config ui_; + QWidget* config_widget_; + mapviz::MapCanvas* map_canvas_; + + bool copy_on_click_; +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__COORDINATE_PICKER_PLUGIN_H_ + diff --git a/mapviz_plugins/include/mapviz_plugins/disparity_plugin.h b/mapviz_plugins/include/mapviz_plugins/disparity_plugin.h new file mode 100644 index 000000000..8a82f342f --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/disparity_plugin.h @@ -0,0 +1,150 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__DISPARITY_PLUGIN_H_ +#define MAPVIZ_PLUGINS__DISPARITY_PLUGIN_H_ + +// Include mapviz_plugin.h first to ensure GL deps are included in the right order +#include + +// QT libraries +#include +#include +#include +#include + +// ROS libraries +#ifdef USE_CVBRIDGE_H_FILES +#include +#else +#include +#endif +#include +#include +#include +#include + +#include + +// C++ standard libraries +#include +#include + +// QT autogenerated files +#include "ui_disparity_config.h" + +namespace mapviz_plugins +{ +class DisparityPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + +public: + enum Anchor { + TOP_LEFT, + TOP_CENTER, + TOP_RIGHT, + CENTER_LEFT, + CENTER, + CENTER_RIGHT, + BOTTOM_LEFT, + BOTTOM_CENTER, + BOTTOM_RIGHT}; + + enum Units {PIXELS, PERCENT}; + + DisparityPlugin(); + ~DisparityPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void Transform() override {} + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + +protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + +protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + void SetAnchor(QString anchor); + void SetUnits(QString units); + void SetOffsetX(int offset); + void SetOffsetY(int offset); + void SetWidth(int width); + void SetHeight(int height); + void SetSubscription(bool visible); + +private: + Ui::disparity_config ui_; + QWidget* config_widget_; + + std::string topic_; + Anchor anchor_; + Units units_; + double offset_x_; + double offset_y_; + double width_; + double height_; + + bool has_image_; + + double last_width_; + double last_height_; + + rclcpp::Subscription::SharedPtr disparity_sub_; + bool has_message_; + + stereo_msgs::msg::DisparityImage disparity_; + + cv::Mat_ disparity_color_; + cv::Mat scaled_image_; + + void disparityCallback(const stereo_msgs::msg::DisparityImage::SharedPtr image); + + void ScaleImage(double width, double height); + void DrawIplImage(cv::Mat *image); + + std::string AnchorToString(Anchor anchor); + std::string UnitsToString(Units units); + + static const unsigned char COLOR_MAP[]; +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__DISPARITY_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/draw_polygon_plugin.h b/mapviz_plugins/include/mapviz_plugins/draw_polygon_plugin.h new file mode 100644 index 000000000..d60fd49e7 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/draw_polygon_plugin.h @@ -0,0 +1,115 @@ +// ***************************************************************************** +// +// Copyright (c) 2016, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__DRAW_POLYGON_PLUGIN_H_ +#define MAPVIZ_PLUGINS__DRAW_POLYGON_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include + +// Mapviz libraries +#include + +// Messages +#include + +// C++ standard libraries +#include +#include + +// QT autogenerated files +#include "ui_draw_polygon_config.h" + +namespace mapviz_plugins +{ +class DrawPolygonPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + + public: + DrawPolygonPlugin(); + ~DrawPolygonPlugin() override; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void Transform() override {}; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + bool eventFilter(QObject *object, QEvent* event) override; + bool handleMousePress(QMouseEvent *); + bool handleMouseRelease(QMouseEvent *); + bool handleMouseMove(QMouseEvent *); + + protected Q_SLOTS: + void PublishPolygon(); + void Clear(); + void SelectFrame(); + void FrameEdited(); + + private: + Ui::draw_polygon_config ui_; + QWidget* config_widget_; + mapviz::MapCanvas* map_canvas_; + + std::string polygon_topic_; + rclcpp::Publisher::SharedPtr polygon_pub_; + + std::vector vertices_; + std::vector transformed_vertices_; + + int selected_point_; + bool is_mouse_down_; + QPointF mouse_down_pos_; + qint64 mouse_down_time_; + + qint64 max_ms_; + qreal max_distance_; +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__DRAW_POLYGON_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/float_plugin.h b/mapviz_plugins/include/mapviz_plugins/float_plugin.h new file mode 100644 index 000000000..2abee56a7 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/float_plugin.h @@ -0,0 +1,160 @@ +// ***************************************************************************** +// +// Copyright (c) 2019, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS_FLOAT_PLUGIN_H +#define MAPVIZ_PLUGINS_FLOAT_PLUGIN_H + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include + +// QT autogenerated files +#include "ui_float_config.h" + +namespace mapviz_plugins +{ + class FloatPlugin : public mapviz::MapvizPlugin + { + Q_OBJECT + + public: + enum Anchor { + TOP_LEFT, + TOP_CENTER, + TOP_RIGHT, + CENTER_LEFT, + CENTER, + CENTER_RIGHT, + BOTTOM_LEFT, + BOTTOM_CENTER, + BOTTOM_RIGHT + }; + + enum Units { + PIXELS, + PERCENT + }; + + FloatPlugin(); + ~FloatPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + void Paint(QPainter* painter, double x, double y, double scale) override; + + void Transform() override {} + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + bool SupportsPainting() override + { + return true; + } + + protected: + void PaintText(QPainter* painter); + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectColor(); + void SelectFont(); + void SelectTopic(); + void TopicEdited(); + void SetAnchor(QString anchor); + void SetUnits(QString units); + void SetOffsetX(int offset); + void SetOffsetY(int offset); + void PostfixEdited(); + + private: + Ui::float_config ui_; + QWidget* config_widget_; + + std::string topic_; + std::string postfix_; + Anchor anchor_; + Units units_; + int offset_x_; + int offset_y_; + + rclcpp::Subscription::SharedPtr float32_sub_; + rclcpp::Subscription::SharedPtr float64_sub_; + rclcpp::Subscription::SharedPtr float32_stamped_sub_; + rclcpp::Subscription::SharedPtr float64_stamped_sub_; + rclcpp::Subscription::SharedPtr velocity_sub_; + bool has_message_; + bool has_painted_; + + QColor color_; + QFont font_; + QStaticText message_; + + void floatCallback(double value); + + std::string AnchorToString(Anchor anchor); + std::string UnitsToString(Units units); + + static const char* ANCHOR_KEY; + static const char* COLOR_KEY; + static const char* FONT_KEY; + static const char* OFFSET_X_KEY; + static const char* OFFSET_Y_KEY; + static const char* TOPIC_KEY; + static const char* UNITS_KEY; + static const char* POSTFIX_KEY; + }; +} + + +#endif //MAPVIZ_PLUGINS_FLOAT_PLUGIN_H diff --git a/mapviz_plugins/include/mapviz_plugins/gps_plugin.h b/mapviz_plugins/include/mapviz_plugins/gps_plugin.h new file mode 100644 index 000000000..97d18a298 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/gps_plugin.h @@ -0,0 +1,91 @@ +// ***************************************************************************** +// +// Copyright (C) 2013 All Right Reserved, Southwest Research Institute® (SwRI®) +// +// Contract No. 10-58058A +// Contractor Southwest Research Institute® (SwRI®) +// Address 6220 Culebra Road, San Antonio, Texas 78228-0510 +// Contact Steve Dellenback (210) 522-3914 +// +// This code was developed as part of an internal research project fully funded +// by Southwest Research Institute®. +// +// THIS CODE AND INFORMATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY +// KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A +// PARTICULAR PURPOSE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__GPS_PLUGIN_H_ +#define MAPVIZ_PLUGINS__GPS_PLUGIN_H_ + +// Include mapviz_plugin.h first to ensure GL deps are included in the right order +#include + +#include +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include +#include +#include + +// C++ standard libraries +#include +#include +#include + +// QT autogenerated files +#include "ui_gps_config.h" + +namespace mapviz_plugins +{ +class GpsPlugin : public mapviz_plugins::PointDrawingPlugin +{ + Q_OBJECT + + public: + GpsPlugin(); + ~GpsPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + + private: + Ui::gps_config ui_; + QWidget* config_widget_; + + std::string topic_; + + // ros::Subscriber gps_sub_; + rclcpp::Subscription::SharedPtr gps_sub_; + bool has_message_; + + void GPSFixCallback(const gps_msgs::msg::GPSFix::SharedPtr gps); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__GPS_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/grid_plugin.h b/mapviz_plugins/include/mapviz_plugins/grid_plugin.h new file mode 100644 index 000000000..e4043197f --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/grid_plugin.h @@ -0,0 +1,123 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__GRID_PLUGIN_H_ +#define MAPVIZ_PLUGINS__GRID_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include +#include + +// ROS libraries +#include +#include + +#include + +// C++ standard libraries +#include +#include + +// QT autogenerated files +#include "ui_grid_config.h" + +namespace mapviz_plugins +{ +class GridPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + +public: + GridPlugin(); + ~GridPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void Transform() override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + +protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + +protected Q_SLOTS: + void SelectFrame(); + void FrameEdited(); + void SetAlpha(double alpha); + void SetX(double x); + void SetY(double y); + void SetSize(double size); + void SetRows(int rows); + void SetColumns(int columns); + void DrawIcon() override; + +private: + Ui::grid_config ui_; + QWidget* config_widget_; + + double alpha_; + + tf2::Vector3 top_left_; + + double size_; + int rows_; + int columns_; + + bool transformed_; + + std::list top_points_; + std::list bottom_points_; + std::list left_points_; + std::list right_points_; + + std::list transformed_top_points_; + std::list transformed_bottom_points_; + std::list transformed_left_points_; + std::list transformed_right_points_; + + swri_transform_util::Transform transform_; + + void RecalculateGrid(); + void Transform(std::list& src, std::list& dst); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__GRID_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/image_plugin.h b/mapviz_plugins/include/mapviz_plugins/image_plugin.h new file mode 100644 index 000000000..2e65d93de --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/image_plugin.h @@ -0,0 +1,157 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__IMAGE_PLUGIN_H_ +#define MAPVIZ_PLUGINS__IMAGE_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include +#include + +// ROS libraries +#include +#include +#include +#include +#ifdef USE_CVBRIDGE_H_FILES +#include +#else +#include +#endif +#include + +#include + +// C++ standard libraries +#include +#include + +// QT autogenerated files +#include "ui_image_config.h" + +namespace mapviz_plugins +{ +class ImagePlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + +public: + enum Anchor { + TOP_LEFT, + TOP_CENTER, + TOP_RIGHT, + CENTER_LEFT, + CENTER, + CENTER_RIGHT, + BOTTOM_LEFT, + BOTTOM_CENTER, + BOTTOM_RIGHT + }; + + enum Units {PIXELS, PERCENT}; + + ImagePlugin(); + ~ImagePlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void SetNode(rclcpp::Node& node) override; + + void Transform() override {} + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + +protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + +public Q_SLOTS: + void Resubscribe(); + +protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + void SetAnchor(QString anchor); + void SetUnits(QString units); + void SetOffsetX(int offset); + void SetOffsetY(int offset); + void SetWidth(double width); + void SetHeight(double height); + void SetSubscription(bool visible); + void SetTransport(const QString& transport); + void KeepRatioChanged(bool checked); + +private: + Ui::image_config ui_; + QWidget* config_widget_; + + std::string topic_; + Anchor anchor_; + Units units_; + int offset_x_; + int offset_y_; + double width_; + double height_; + std::string transport_; + + bool force_resubscribe_; + bool has_image_; + + double last_width_; + double last_height_; + double original_aspect_ratio_; + + image_transport::Subscriber image_sub_; + bool has_message_; + + cv_bridge::CvImagePtr cv_image_; + cv::Mat scaled_image_; + + void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr& image); + + void ScaleImage(double width, double height); + void DrawIplImage(cv::Mat *image); + + std::string AnchorToString(Anchor anchor); + std::string UnitsToString(Units units); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__IMAGE_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/laserscan_plugin.h b/mapviz_plugins/include/mapviz_plugins/laserscan_plugin.h new file mode 100644 index 000000000..a7a1405f6 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/laserscan_plugin.h @@ -0,0 +1,153 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__LASERSCAN_PLUGIN_H_ +#define MAPVIZ_PLUGINS__LASERSCAN_PLUGIN_H_ + +#include + +// QT libraries +#include +#include + +// ROS libraries +#include +#include + +// C++ standard libraries +#include +#include +#include + +// QT autogenerated files +#include "ui_laserscan_config.h" + +namespace mapviz_plugins +{ +class LaserScanPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + + public: + enum + { + COLOR_FLAT = 0, + COLOR_INTENSITY = 1, + COLOR_RANGE = 2, + COLOR_X = 3, + COLOR_Y = 4, + COLOR_Z = 5 + }; + LaserScanPlugin(); + ~LaserScanPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void ClearHistory() override; + + void Draw(double x, double y, double scale) override; + + void Transform() override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + void AlphaEdited(double val); + void ColorTransformerChanged(int index); + void MinValueChanged(double value); + void MaxValueChanged(double value); + void PointSizeChanged(int value); + void BufferSizeChanged(int value); + void UseRainbowChanged(int check_state); + void UpdateColors(); + void DrawIcon() override; + void ResetTransformedScans(); + + private: + struct StampedPoint + { + tf2::Vector3 point; + tf2::Vector3 transformed_point; + QColor color; + float range; + float intensity; + }; + + struct Scan + { + rclcpp::Time stamp; + QColor color; + std::vector points; + std::string source_frame_; + bool transformed; + bool has_intensity; + }; + + void laserScanCallback(const sensor_msgs::msg::LaserScan::SharedPtr scan); + QColor CalculateColor(const StampedPoint& point, bool has_intensity); + void updatePreComputedTriginometic(const sensor_msgs::msg::LaserScan::SharedPtr msg); + + Ui::laserscan_config ui_; + QWidget* config_widget_; + + std::string topic_; + double alpha_; + double min_value_; + double max_value_; + size_t point_size_; + size_t buffer_size_; + + bool has_message_; + + // Use a list instead of a deque for scans to facilitate removing + // timed-out scans in the middle of the list in case I ever re-implement + // decay time (evenator) + std::deque scans_; + rclcpp::Subscription::SharedPtr laserscan_sub_; + std::vector precomputed_cos_; + std::vector precomputed_sin_; + size_t prev_ranges_size_; + float prev_angle_min_; + float prev_increment_; + bool GetScanTransform(const Scan &scan, swri_transform_util::Transform& transform); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__LASERSCAN_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/marker_plugin.h b/mapviz_plugins/include/mapviz_plugins/marker_plugin.h new file mode 100644 index 000000000..198d31eda --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/marker_plugin.h @@ -0,0 +1,179 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__MARKER_PLUGIN_H_ +#define MAPVIZ_PLUGINS__MARKER_PLUGIN_H_ + +#include + +// QT libraries +#include +#include + +// ROS libraries +#include +#include +#include + +#include + +#include + +// C++ standard libraries +#include +#include +#include +#include + +// QT autogenerated files +#include "ui_marker_config.h" + +namespace mapviz_plugins +{ +using MarkerId = std::pair; + +struct MarkerIdHash { + std::size_t operator () (const MarkerId &p) const { + std::size_t seed = 0; + boost::hash_combine(seed, p.first); + boost::hash_combine(seed, p.second); + return seed; + } +}; + +struct MarkerNsHash { + std::size_t operator () (const std::string &p) const { + std::size_t seed = 0; + boost::hash_combine(seed, p); + return seed; + } +}; + +class MarkerPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + +public: + MarkerPlugin(); + ~MarkerPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + void Paint(QPainter* painter, double x, double y, double scale) override; + + void Transform() override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + bool SupportsPainting() override + { + return true; + } + +protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + void timerEvent(QTimerEvent *) override; + +protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + void ClearHistory() override; + +private: + struct Color + { + float r, g, b, a; + }; + + struct StampedPoint + { + tf2::Vector3 point; + tf2::Quaternion orientation; + + tf2::Vector3 transformed_point; + + tf2::Vector3 arrow_point; + tf2::Vector3 transformed_arrow_point; + tf2::Vector3 transformed_arrow_left; + tf2::Vector3 transformed_arrow_right; + + Color color; + }; + + struct MarkerData + { + rclcpp::Time stamp; + rclcpp::Time expire_time; + + int display_type; + Color color; + + std::vector points; + std::string text; + + float scale_x; + float scale_y; + float scale_z; + + std::string source_frame; + swri_transform_util::Transform local_transform; + + bool transformed; + }; + + Ui::marker_config ui_{}; + QWidget* config_widget_; + + std::string topic_; + + rclcpp::Subscription::SharedPtr marker_sub_; + rclcpp::Subscription::SharedPtr marker_array_sub_; + bool connected_; + bool has_message_{}; + + std::unordered_map markers_; + std::unordered_map marker_visible_; + + void handleMarker(visualization_msgs::msg::Marker::ConstSharedPtr marker); + void handleMarkerArray(visualization_msgs::msg::MarkerArray::ConstSharedPtr markers); + void processMarker(const visualization_msgs::msg::Marker& marker); + void subscribe(); + void transformArrow(MarkerData& markerData, + const swri_transform_util::Transform& transform); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__MARKER_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/measuring_plugin.h b/mapviz_plugins/include/mapviz_plugins/measuring_plugin.h new file mode 100644 index 000000000..9402fbbc3 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/measuring_plugin.h @@ -0,0 +1,123 @@ +// ***************************************************************************** +// +// Copyright (c) 2018, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__MEASURING_PLUGIN_H_ +#define MAPVIZ_PLUGINS__MEASURING_PLUGIN_H_ + +#include + +// ROS Libraries +#include + +// Mapviz libraries +#include + +// C++ libraries +#include +#include + +// QT autogenerated files +#include "ui_measuring_config.h" + +namespace mapviz_plugins +{ +class MeasuringPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + + public: + MeasuringPlugin(); + ~MeasuringPlugin() override; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override { } + + void Paint(QPainter* painter, double x, double y, double scale) override; + void Draw(double x, double y, double scale) override; + void Transform() override { } + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + void DistanceCalculation(); + + QWidget* GetConfigWidget(QWidget* parent) override; + + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + bool SupportsPainting() override + { + return true; + } + + protected: + bool eventFilter(QObject* object, QEvent* event) override; + bool handleMousePress(QMouseEvent*); + bool handleMouseRelease(QMouseEvent*); + bool handleMouseMove(QMouseEvent*); + + protected Q_SLOTS: + void Clear(); + void BkgndColorToggled(bool) { } + void MeasurementsToggled(bool) { } + void FontSizeChanged(int) { } + void AlphaChanged(double) { } + + private: + Ui::measuring_config ui_; + QWidget* config_widget_; + + mapviz::MapCanvas* map_canvas_; + tf2::Vector3 last_position_; + + std::vector vertices_; + std::vector transformed_vertices_; + + int selected_point_; + bool is_mouse_down_; + QPointF mouse_down_pos_; + qint64 mouse_down_time_; + + qint64 max_ms_; + qreal max_distance_; + std::vector measurements_; +}; + +struct MeasurementBox +{ + QRectF rect; + QString string; +}; + +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__MEASURING_PLUGIN_H_ + diff --git a/mapviz_plugins/include/mapviz_plugins/move_base_plugin.h b/mapviz_plugins/include/mapviz_plugins/move_base_plugin.h new file mode 100644 index 000000000..cfe3059df --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/move_base_plugin.h @@ -0,0 +1,118 @@ +// ***************************************************************************** +// +// Copyright (c) 2017, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS_PLAN_ROUTE_PLUGIN_H_ +#define MAPVIZ_PLUGINS_PLAN_ROUTE_PLUGIN_H_ + +// C++ standard libraries +#include +#include +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include + +// Mapviz libraries +#include + +#include +#include +#include + +// QT autogenerated files +#include "ui_move_base_config.h" + +namespace mapviz_plugins +{ + class MoveBasePlugin : public mapviz::MapvizPlugin + { + Q_OBJECT + + public: + typedef actionlib::SimpleActionClient MoveBaseClient; + + MoveBasePlugin(); + virtual ~MoveBasePlugin(); + + bool Initialize(QGLWidget* canvas); + void Shutdown() {} + + void Draw(double x, double y, double scale); + + void Paint(QPainter* painter, double x, double y, double scale) {} + void Transform() {} + + void LoadConfig(const YAML::Node& node, const std::string& path); + void SaveConfig(YAML::Emitter& emitter, const std::string& path); + + QWidget* GetConfigWidget(QWidget* parent); + + protected: + virtual void PrintError(const std::string& message) override; + virtual void PrintInfo(const std::string& message) override; + virtual void PrintWarning(const std::string& message) override; + virtual bool eventFilter(QObject *object, QEvent* event) override; + void timerCallback(const ros::TimerEvent& ev = ros::TimerEvent() ); + + bool handleMousePress(QMouseEvent *); + bool handleMouseRelease(QMouseEvent *); + bool handleMouseMove(QMouseEvent *); + + private Q_SLOTS: + void on_pushButtonInitialPose_toggled(bool checked); + void on_pushButtonGoalPose_toggled(bool checked); + void on_pushButtonAbort_clicked(); + + private: + + Ui::move_base_config ui_; + QWidget* config_widget_; + mapviz::MapCanvas* map_canvas_; + + ros::NodeHandle nh_; + ros::Publisher init_pose_pub_; + + bool is_mouse_down_; + QPointF arrow_tail_position_; + float arrow_angle_; + + MoveBaseClient move_base_client_; + move_base_msgs::MoveBaseAction move_base_msg_; + ros::Timer timer_; + bool monitoring_action_state_; + }; +} + +#endif // MAPVIZ_PLUGINS_PLAN_ROUTE_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/navsat_plugin.h b/mapviz_plugins/include/mapviz_plugins/navsat_plugin.h new file mode 100644 index 000000000..d3baa155a --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/navsat_plugin.h @@ -0,0 +1,88 @@ +// ***************************************************************************** +// +// Copyright (C) 2013 All Right Reserved, Southwest Research Institute® (SwRI®) +// +// Contract No. 10-58058A +// Contractor Southwest Research Institute® (SwRI®) +// Address 6220 Culebra Road, San Antonio, Texas 78228-0510 +// Contact Steve Dellenback (210) 522-3914 +// +// This code was developed as part of an internal research project fully funded +// by Southwest Research Institute®. +// +// THIS CODE AND INFORMATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY +// KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A +// PARTICULAR PURPOSE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__NAVSAT_PLUGIN_H_ +#define MAPVIZ_PLUGINS__NAVSAT_PLUGIN_H_ + +#include +#include +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include +#include +#include + +// C++ standard libraries +#include +#include +#include + +// QT autogenerated files +#include "ui_navsat_config.h" + +namespace mapviz_plugins +{ +class NavSatPlugin : public mapviz_plugins::PointDrawingPlugin +{ + Q_OBJECT + + public: + NavSatPlugin(); + ~NavSatPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + + private: + Ui::navsat_config ui_; + QWidget* config_widget_; + + std::string topic_; + + rclcpp::Subscription::SharedPtr navsat_sub_; + bool has_message_; + + void NavSatFixCallback(const sensor_msgs::msg::NavSatFix::ConstSharedPtr navsat); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__NAVSAT_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/occupancy_grid_plugin.h b/mapviz_plugins/include/mapviz_plugins/occupancy_grid_plugin.h new file mode 100644 index 000000000..f42ac6496 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/occupancy_grid_plugin.h @@ -0,0 +1,126 @@ +// ***************************************************************************** +// +// Copyright (c) 2018, Eurecat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Eurecat nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__OCCUPANCY_GRID_PLUGIN_H_ +#define MAPVIZ_PLUGINS__OCCUPANCY_GRID_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include +#include + +// ROS libraries +#include +#include + +#include +#include +#include + +// C++ standard libraries +#include +#include +#include + +// QT autogenerated files +#include "ui_occupancy_grid_config.h" + +namespace mapviz_plugins +{ +class OccupancyGridPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + + typedef std::array Palette; + +public: + OccupancyGridPlugin(); + ~OccupancyGridPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void Transform() override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + +protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + +protected Q_SLOTS: + + void SelectTopicGrid(); + void TopicGridEdited(); + void upgradeCheckBoxToggled(bool); + void colorSchemeUpdated(const QString &); + + void DrawIcon() override; + + void FrameChanged(std::string); + +private: + Ui::occupancy_grid_config ui_; + QWidget* config_widget_; + + nav_msgs::msg::OccupancyGrid::SharedPtr grid_; + + rclcpp::Subscription::SharedPtr grid_sub_; + rclcpp::Subscription::SharedPtr update_sub_; + + bool transformed_; + swri_transform_util::Transform transform_; + + GLuint texture_id_; + + QPointF map_origin_; + float texture_x_, texture_y_; + std::vector raw_buffer_; + std::vector color_buffer_; + uint32_t texture_size_; + + Palette map_palette_; + Palette costmap_palette_; + + void Callback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg); + void CallbackUpdate(const map_msgs::msg::OccupancyGridUpdate::SharedPtr msg); + void updateTexture(); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__OCCUPANCY_GRID_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/odometry_plugin.h b/mapviz_plugins/include/mapviz_plugins/odometry_plugin.h new file mode 100644 index 000000000..80e3ac838 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/odometry_plugin.h @@ -0,0 +1,100 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__ODOMETRY_PLUGIN_H_ +#define MAPVIZ_PLUGINS__ODOMETRY_PLUGIN_H_ + +#include +#include +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include +#include + +#include + +// C++ standard libraries +#include +#include +#include + +// QT autogenerated files +#include "ui_odometry_config.h" + +namespace mapviz_plugins +{ +class OdometryPlugin : public mapviz_plugins::PointDrawingPlugin +{ + Q_OBJECT + + public: + OdometryPlugin(); + ~OdometryPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Paint(QPainter* painter, double x, double y, double scale) override; + void Draw(double x, double y, double scale) override; + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + bool SupportsPainting() override + { + return true; + } + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + + private: + Ui::odometry_config ui_; + QWidget* config_widget_; + std::string topic_; + rclcpp::Subscription::SharedPtr odometry_sub_; + bool has_message_; + void odometryCallback(const nav_msgs::msg::Odometry::SharedPtr odometry); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__ODOMETRY_PLUGIN_H_ + diff --git a/mapviz_plugins/include/mapviz_plugins/path_plugin.h b/mapviz_plugins/include/mapviz_plugins/path_plugin.h new file mode 100644 index 000000000..b47c7150d --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/path_plugin.h @@ -0,0 +1,97 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__PATH_PLUGIN_H_ +#define MAPVIZ_PLUGINS__PATH_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include +#include + +#include +#include + +// C++ standard libraries +#include +#include + +// QT autogenerated files +#include "ui_path_config.h" + +namespace mapviz_plugins +{ +class PathPlugin : public mapviz_plugins::PointDrawingPlugin +{ + Q_OBJECT + + public: + PathPlugin(); + ~PathPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + + private: + Ui::path_config ui_; + QWidget* config_widget_; + + std::string topic_; + + rclcpp::Subscription::SharedPtr path_sub_; + bool has_message_; + + void pathCallback(const nav_msgs::msg::Path::SharedPtr path); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__PATH_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/placeable_window_proxy.h b/mapviz_plugins/include/mapviz_plugins/placeable_window_proxy.h new file mode 100644 index 000000000..18e9e6866 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/placeable_window_proxy.h @@ -0,0 +1,122 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** +#ifndef MAPVIZ_PLUGINS__PLACEABLE_WINDOW_PROXY_H_ +#define MAPVIZ_PLUGINS__PLACEABLE_WINDOW_PROXY_H_ + +#include +#include +#include + +QT_BEGIN_NAMESPACE; +class QMouseEvent; +class QResizeEvent; +QT_END_NAMESPACE; + +/** + * This object supports moving/resizing a "window" on the canvas. It + * should be installed as an event filter on the map canvas and be + * given an initial rectangle. It will watch for mouse events that + * occur within the rectangle and move/resize the rectangle + * accordingly. You can listen to signals to determine when the + * window was moved, or just use the rectangle at the start of every + * draw. + * + * Since this class is designed for moving windows around the canvas, + * it does everything in terms of pixels. + * + * To do: Need to deactivate the proxy when the plugin is marked + * invisible, or is not drawing data. + */ +namespace mapviz_plugins +{ +class PlaceableWindowProxy : public QObject +{ +Q_OBJECT + +public: + PlaceableWindowProxy(); + ~PlaceableWindowProxy() override; + + void setContainer(QWidget *); + + QRect rect() const; + +Q_SIGNALS: + void rectChanged(const QRect &); + +public Q_SLOTS: + void setRect(const QRect &); + void setVisible(bool visible); + +protected: + bool eventFilter(QObject *object, QEvent *event) override; + + bool handleMousePress(QMouseEvent *); + bool handleMouseRelease(QMouseEvent *); + bool handleMouseMove(QMouseEvent *); + bool handleResize(QResizeEvent *); + + void timerEvent(QTimerEvent *) override; + + void rectResize(int dx, int dy); + void winResize(const QSize &); + + QRectF resizeHelper(const QRectF &rect, + const QPointF &p1, + const QPointF &p2, + const QPointF &p3) const; + + + +private: + enum State { + INACTIVE = 0, + MOVE_ALL, + MOVE_TOP_LEFT, + MOVE_BOTTOM_LEFT, + MOVE_BOTTOM_RIGHT, + MOVE_TOP_RIGHT + }; + + QWidget *target_; + bool visible_; + + bool has_cursor_; + State state_; + QRectF rect_; + + QRectF start_rect_; + QPoint start_point_; + + int win_resize_timer_; + + State getNextState(const QPointF &pt) const; +}; // class PlaceableWindowProxy +} // namespace mapviz_plugins +#endif // MAPVIZ_PLUGINS__PLACEABLE_WINDOW_PROXY_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/plan_route_plugin.h b/mapviz_plugins/include/mapviz_plugins/plan_route_plugin.h new file mode 100644 index 000000000..f2329184f --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/plan_route_plugin.h @@ -0,0 +1,133 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__PLAN_ROUTE_PLUGIN_H_ +#define MAPVIZ_PLUGINS__PLAN_ROUTE_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include + +// Mapviz libraries +#include +#include + +// Messages +#include +#include +#include + +// C++ standard libraries +#include +#include + +// QT autogenerated files +#include "ui_plan_route_config.h" + +namespace mapviz_plugins +{ +class PlanRoutePlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + + public: + PlanRoutePlugin(); + ~PlanRoutePlugin() override; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + void Paint(QPainter* painter, double x, double y, double scale) override; + + void Transform() override {}; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + bool SupportsPainting() override + { + return true; + } + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + bool eventFilter(QObject *object, QEvent* event) override; + bool handleMousePress(QMouseEvent *); + bool handleMouseRelease(QMouseEvent *); + bool handleMouseMove(QMouseEvent *); + + protected Q_SLOTS: + void PublishRoute(); + void PlanRoute(); + void Clear(); + void VisibilityChanged(bool); + + private: + // void Retry(const ros::TimerEvent& e); + void Retry(); + + void ClientCallback(rclcpp::Client::SharedFuture future); + + Ui::plan_route_config ui_{}; + QWidget* config_widget_; + mapviz::MapCanvas* map_canvas_; + + std::string route_topic_; + + rclcpp::Publisher::SharedPtr route_pub_; + rclcpp::TimerBase::SharedPtr retry_timer_; + + bool failed_service_; + swri_route_util::RoutePtr route_preview_; + + std::vector waypoints_; + + int selected_point_; + bool is_mouse_down_; + QPointF mouse_down_pos_; + qint64 mouse_down_time_; + + qint64 max_ms_; + qreal max_distance_; +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__PLAN_ROUTE_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/point_click_publisher_plugin.h b/mapviz_plugins/include/mapviz_plugins/point_click_publisher_plugin.h new file mode 100644 index 000000000..ef1f0117a --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/point_click_publisher_plugin.h @@ -0,0 +1,101 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__POINT_CLICK_PUBLISHER_PLUGIN_H_ +#define MAPVIZ_PLUGINS__POINT_CLICK_PUBLISHER_PLUGIN_H_ + +// Include mapviz_plugin.h first to ensure GL deps are included in the right order +#include + +#include +#include +#include + +#include + +#include + +#include + +// C++ Standard Libraries +#include + +// QT autogenerated files +#include "ui_point_click_publisher_config.h" +#include "ui_topic_select.h" + +/** + * This is a pretty straightforward plugin. It watches for user clicks on the + * canvas, then converts the coordinates into a specified frame and publishes + * them as PointStamped messages on a specified topic. + */ +namespace mapviz_plugins +{ +class PointClickPublisherPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT; +public: + PointClickPublisherPlugin(); + ~PointClickPublisherPlugin() override; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void SetNode(rclcpp::Node& node) override; + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + void Draw(double x, double y, double scale) override; + + void Transform() override {} + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + +protected Q_SLOTS: + void pointClicked(const QPointF& point); + void topicChanged(const QString& topic); + void updateFrames(); + +private: + Ui::point_click_publisher_config ui_{}; + QWidget* config_widget_; + + CanvasClickFilter click_filter_; + mapviz::MapCanvas* canvas_; + + QTimer frame_timer_; + rclcpp::Publisher::SharedPtr point_publisher_; +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__POINT_CLICK_PUBLISHER_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/point_drawing_plugin.h b/mapviz_plugins/include/mapviz_plugins/point_drawing_plugin.h new file mode 100644 index 000000000..4d1b3af04 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/point_drawing_plugin.h @@ -0,0 +1,143 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__POINT_DRAWING_PLUGIN_H_ +#define MAPVIZ_PLUGINS__POINT_DRAWING_PLUGIN_H_ + +#include +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include + +// C++ standard libraries +#include +#include +#include +#include + +namespace mapviz_plugins +{ +class PointDrawingPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + + public: + struct StampedPoint + { + StampedPoint(): transformed(false) {} + + tf2::Vector3 point; + tf2::Quaternion orientation; + tf2::Vector3 transformed_point; + tf2::Vector3 transformed_arrow_point; + tf2::Vector3 transformed_arrow_left; + tf2::Vector3 transformed_arrow_right; + std::string source_frame; + bool transformed; + rclcpp::Time stamp; + + std::vector cov_points; + std::vector transformed_cov_points; + }; + + enum DrawStyle + { + LINES = 0, + POINTS, + ARROWS + }; + + PointDrawingPlugin(); + ~PointDrawingPlugin() override = default; + void ClearHistory() override; + + void Transform() override; + virtual bool DrawPoints(double scale); + virtual bool DrawArrows(); + virtual bool DrawArrow(const StampedPoint& point); + virtual bool DrawLaps(); + virtual bool DrawLines(); + virtual void CollectLaps(); + virtual bool DrawLapsArrows(); + virtual bool TransformPoint(StampedPoint& point); + virtual void UpdateColor(QColor base_color, int i); + virtual void DrawCovariance(); + + protected Q_SLOTS: + virtual void BufferSizeChanged(int value); + void DrawIcon() override; + virtual void SetColor(const QColor& color); + virtual void SetDrawStyle(QString style); + virtual void SetDrawStyle(DrawStyle style); + virtual void SetStaticArrowSizes(bool isChecked); + virtual void SetArrowSize(int arrowSize); + virtual void PositionToleranceChanged(double value); + virtual void LapToggled(bool checked); + virtual void CovariancedToggled(bool checked); + virtual void ShowAllCovariancesToggled(bool checked); + void ResetTransformedPoints(); + void ClearPoints(); + + protected: + void pushPoint(StampedPoint point); + double bufferSize() const; + double positionTolerance() const; + const std::deque& points() const; + + private: + int arrow_size_; + DrawStyle draw_style_; + StampedPoint cur_point_; + std::deque points_; + double position_tolerance_; + int buffer_size_; + bool covariance_checked_; + bool show_all_covariances_checked_; + bool new_lap_; + QColor color_; + bool lap_checked_; + int buffer_holder_; + double scale_; + bool static_arrow_sizes_; + + private: + std::vector > laps_; + bool got_begin_; + tf2::Vector3 begin_; +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__POINT_DRAWING_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/pointcloud2_plugin.h b/mapviz_plugins/include/mapviz_plugins/pointcloud2_plugin.h new file mode 100644 index 000000000..d328bf293 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/pointcloud2_plugin.h @@ -0,0 +1,165 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__POINTCLOUD2_PLUGIN_H_ +#define MAPVIZ_PLUGINS__POINTCLOUD2_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include + +// C++ standard libraries +#include +#include +#include +#include + +// QT autogenerated files +#include "ui_pointcloud2_config.h" + +namespace mapviz_plugins +{ +class PointCloud2Plugin : public mapviz::MapvizPlugin +{ +Q_OBJECT + +public: + struct FieldInfo + { + uint8_t datatype; + uint32_t offset; + }; + + enum + { + COLOR_FLAT = 0, + COLOR_Z = 3 + }; + + PointCloud2Plugin(); + ~PointCloud2Plugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void ClearHistory() override; + + void Draw(double x, double y, double scale) override; + + void Transform() override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + +protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + +protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + void AlphaEdited(double new_value); + void ColorTransformerChanged(int index); + void MinValueChanged(double value); + void MaxValueChanged(double value); + void PointSizeChanged(int value); + void BufferSizeChanged(int value); + void UseRainbowChanged(int check_state); + void UseAutomaxminChanged(int check_state); + void UpdateColors(); + void DrawIcon() override; + void ResetTransformedPointClouds(); + void ClearPointClouds(); + void SetSubscription(bool subscribe); + +private: + struct StampedPoint + { + tf2::Vector3 point; + std::vector features; + }; + + struct Scan + { + rclcpp::Time stamp; + QColor color; + std::vector points; + std::string source_frame; + bool transformed; + std::map new_features; + + std::vector gl_point; + std::vector gl_color; + GLuint point_vbo; + GLuint color_vbo; + }; + + float PointFeature(const uint8_t*, const FieldInfo&); + void PointCloud2Callback(const sensor_msgs::msg::PointCloud2::SharedPtr scan); + QColor CalculateColor(const StampedPoint& point); + void UpdateMinMaxWidgets(); + + Ui::PointCloud2_config ui_{}; + QWidget* config_widget_; + + std::string topic_; + double alpha_; + double max_value_; + double min_value_; + size_t point_size_; + size_t buffer_size_; + bool new_topic_; + bool has_message_; + size_t num_of_feats_; + bool need_new_list_; + std::string saved_color_transformer_; + bool need_minmax_; + std::vector max_; + std::vector min_; + // Use a list instead of a deque for scans to facilitate removing + // timed-out scans in the middle of the list in case I ever re-implement + // decay time (evenator) + std::deque scans_; + rclcpp::Subscription::SharedPtr pc2_sub_; + + QMutex scan_mutex_; +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__POINTCLOUD2_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/pose_plugin.h b/mapviz_plugins/include/mapviz_plugins/pose_plugin.h new file mode 100644 index 000000000..b9163ba4f --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/pose_plugin.h @@ -0,0 +1,101 @@ +/** + * Copyright 2019 Hatchbed L.L.C. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + **/ + +#ifndef MAPVIZ_PLUGINS__POSE_PLUGIN_H_ +#define MAPVIZ_PLUGINS__POSE_PLUGIN_H_ + +// Include mapviz_plugin.h first to ensure GL deps are included in the right order +#include + +#include +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include +#include +#include + +// C++ standard libraries +#include +#include +#include + +// QT autogenerated files +#include "ui_pose_config.h" + +namespace mapviz_plugins +{ +class PosePlugin : public mapviz_plugins::PointDrawingPlugin +{ + Q_OBJECT + + public: + PosePlugin(); + ~PosePlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectTopic(); + void TopicEdited(); + + private: + Ui::pose_config ui_; + QWidget* config_widget_; + + std::string topic_; + + rclcpp::Subscription::SharedPtr pose_sub_; + bool has_message_; + + void PoseCallback(const geometry_msgs::msg::PoseStamped::SharedPtr pose); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__POSE_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/robot_image_plugin.h b/mapviz_plugins/include/mapviz_plugins/robot_image_plugin.h new file mode 100644 index 000000000..71d618e0f --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/robot_image_plugin.h @@ -0,0 +1,126 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__ROBOT_IMAGE_PLUGIN_H_ +#define MAPVIZ_PLUGINS__ROBOT_IMAGE_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include + +#include + +// C++ standard libraries +#include + +// QT autogenerated files +#include "ui_robot_image_config.h" +#include "ui_topic_select.h" + +namespace mapviz_plugins +{ +class RobotImagePlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + +public: + RobotImagePlugin(); + ~RobotImagePlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void Transform() override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + +protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + +protected Q_SLOTS: + void SelectFile(); + void SelectFrame(); + void FrameEdited(); + void ImageEdited(); + void WidthChanged(double value); + void HeightChanged(double value); + void OffsetXChanged(double value); + void OffsetYChanged(double value); + void RatioEqualToggled(bool toggled); + void RatioCustomToggled(bool toggled); + void RatioOriginalToggled(bool toggled); + +private: + Ui::robot_image_config ui_; + QWidget* config_widget_; + + double width_; // image width, if robot frame is x-forward this corresponds to robot length + double height_; // image height, corresponds to robot width + double offset_x_; // offset of image center from robot frame along x axis + double offset_y_; // offset of image center from robot frame along y axis + double image_ratio_; + + std::string filename_; + QImage image_; + int dimension_; + int texture_id_; + bool texture_loaded_; + + bool transformed_; + + tf2::Vector3 top_left_; + tf2::Vector3 top_right_; + tf2::Vector3 bottom_left_; + tf2::Vector3 bottom_right_; + + tf2::Vector3 top_left_transformed_; + tf2::Vector3 top_right_transformed_; + tf2::Vector3 bottom_left_transformed_; + tf2::Vector3 bottom_right_transformed_; + + void UpdateShape(); + void LoadImage(); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__ROBOT_IMAGE_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/route_plugin.h b/mapviz_plugins/include/mapviz_plugins/route_plugin.h new file mode 100644 index 000000000..a753123af --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/route_plugin.h @@ -0,0 +1,120 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__ROUTE_PLUGIN_H_ +#define MAPVIZ_PLUGINS__ROUTE_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include +#include +#include +#include + +// C++ standard libraries +#include +#include +#include + +// QT autogenerated files +#include "ui_route_config.h" + +namespace mapviz_plugins +{ +class RoutePlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + + public: + enum DrawStyle + { + LINES = 0, + POINTS = 1 + }; + + RoutePlugin(); + ~RoutePlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void Transform() override {} + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + void DrawStopWaypoint(double x, double y); + void DrawRoute(const swri_route_util::Route &route); + void DrawRoutePoint(const swri_route_util::RoutePoint &point); + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectTopic(); + void SelectPositionTopic(); + void TopicEdited(); + void PositionTopicEdited(); + void SetDrawStyle(QString style); + void DrawIcon() override; + + private: + Ui::route_config ui_; + QWidget* config_widget_; + + DrawStyle draw_style_; + + std::string topic_; + std::string position_topic_; + + rclcpp::Subscription::SharedPtr route_sub_; + rclcpp::Subscription::SharedPtr position_sub_; + + swri_route_util::Route src_route_; + // marti_nav_msgs::RoutePositionConstPtr src_route_position_; + marti_nav_msgs::msg::RoutePosition::SharedPtr src_route_position_; + + void RouteCallback(const marti_nav_msgs::msg::Route::SharedPtr msg); + void PositionCallback(const marti_nav_msgs::msg::RoutePosition::SharedPtr msg); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__ROUTE_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/string_plugin.h b/mapviz_plugins/include/mapviz_plugins/string_plugin.h new file mode 100644 index 000000000..c664b7e61 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/string_plugin.h @@ -0,0 +1,152 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__STRING_PLUGIN_H_ +#define MAPVIZ_PLUGINS__STRING_PLUGIN_H_ + + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +#include + +// QT autogenerated files +#include "ui_string_config.h" + +namespace mapviz_plugins +{ +class StringPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + +public: + enum Anchor { + TOP_LEFT, + TOP_CENTER, + TOP_RIGHT, + CENTER_LEFT, + CENTER, + CENTER_RIGHT, + BOTTOM_LEFT, + BOTTOM_CENTER, + BOTTOM_RIGHT + }; + + enum Units { + PIXELS, + PERCENT + }; + + StringPlugin(); + ~StringPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + void Paint(QPainter* painter, double x, double y, double scale) override; + + void Transform() override {} + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + bool SupportsPainting() override + { + return true; + } + + void SetText(const QString& text); + +protected: + void PaintText(QPainter* painter); + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + +protected Q_SLOTS: + void SelectColor(); + void SelectFont(); + void SelectTopic(); + void TopicEdited(); + void SetAnchor(QString anchor); + void SetUnits(QString units); + void SetOffsetX(int offset); + void SetOffsetY(int offset); + +private: + Ui::string_config ui_; + QWidget* config_widget_; + + std::string topic_; + Anchor anchor_; + Units units_; + int offset_x_; + int offset_y_; + + rclcpp::Subscription::SharedPtr string_sub_; + rclcpp::Subscription::SharedPtr string_stamped_sub_; + bool has_message_; + bool has_painted_; + + QColor color_; + QFont font_; + QStaticText message_; + + std::string AnchorToString(Anchor anchor); + std::string UnitsToString(Units units); + + static const char* ANCHOR_KEY; + static const char* COLOR_KEY; + static const char* FONT_KEY; + static const char* OFFSET_X_KEY; + static const char* OFFSET_Y_KEY; + static const char* TOPIC_KEY; + static const char* UNITS_KEY; +}; +} // namespace mapviz_plugins + + +#endif // MAPVIZ_PLUGINS__STRING_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/textured_marker_plugin.h b/mapviz_plugins/include/mapviz_plugins/textured_marker_plugin.h new file mode 100644 index 000000000..8e53ce5c1 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/textured_marker_plugin.h @@ -0,0 +1,145 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__TEXTURED_MARKER_PLUGIN_H_ +#define MAPVIZ_PLUGINS__TEXTURED_MARKER_PLUGIN_H_ + +#include + +// QT libraries +#include +#include +#include +#include + +#include + +// ROS libraries +#include +#include +#include +#include + +#include + +// C++ standard libraries +#include +#include +#include +#include + +// QT autogenerated files +#include "ui_textured_marker_config.h" + +Q_DECLARE_METATYPE(marti_visualization_msgs::msg::TexturedMarker) + +namespace mapviz_plugins +{ +class TexturedMarkerPlugin : public mapviz::MapvizPlugin +{ + Q_OBJECT + +public: + TexturedMarkerPlugin(); + ~TexturedMarkerPlugin() override = default; + + bool Initialize(QGLWidget * canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void Transform() override; + + void LoadConfig(const YAML::Node & node, const std::string & path) override; + void SaveConfig(YAML::Emitter & emitter, const std::string & path) override; + + QWidget * GetConfigWidget(QWidget * parent) override; + +Q_SIGNALS: + void MarkerReceived(marti_visualization_msgs::msg::TexturedMarker marker); + +protected: + void PrintError(const std::string & message) override; + void PrintInfo(const std::string & message) override; + void PrintWarning(const std::string & message) override; + +protected Q_SLOTS: + void SetAlphaLevel(int alpha); + void SelectTopic(); + void TopicEdited(); + void ClearHistory() override; + void ProcessMarker(marti_visualization_msgs::msg::TexturedMarker marker); + +private: + float alphaVal_; + + struct MarkerData + { + rclcpp::Time stamp; + rclcpp::Time expire_time; + + float alpha_; + + std::vector texture_; + int32_t texture_id_; + int32_t texture_size_; + float texture_x_; + float texture_y_; + + std::string encoding_; + + std::vector quad_; + std::vector transformed_quad_; + + std::string source_frame_; + + bool transformed; + }; + + Ui::textured_marker_config ui_{}; + QWidget * config_widget_; + + std::string topic_; + + rclcpp::Subscription::SharedPtr marker_sub_; + rclcpp::Subscription::SharedPtr + marker_arr_sub_; + + bool has_message_; + + std::map> markers_; + + void MarkerCallback(marti_visualization_msgs::msg::TexturedMarker::ConstSharedPtr marker); + + void MarkerArrayCallback( + marti_visualization_msgs::msg::TexturedMarkerArray::ConstSharedPtr markers); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__TEXTURED_MARKER_PLUGIN_H_ diff --git a/mapviz_plugins/include/mapviz_plugins/tf_frame_plugin.h b/mapviz_plugins/include/mapviz_plugins/tf_frame_plugin.h new file mode 100644 index 000000000..f167edf08 --- /dev/null +++ b/mapviz_plugins/include/mapviz_plugins/tf_frame_plugin.h @@ -0,0 +1,94 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS__TF_FRAME_PLUGIN_H_ +#define MAPVIZ_PLUGINS__TF_FRAME_PLUGIN_H_ + +#include +#include +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include + +#include + +// C++ standard libraries +#include +#include +#include + +// QT autogenerated files +#include "ui_tf_frame_config.h" +#include "ui_topic_select.h" + +namespace mapviz_plugins +{ +class TfFramePlugin : public mapviz_plugins::PointDrawingPlugin +{ + Q_OBJECT + + public: + TfFramePlugin(); + ~TfFramePlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectFrame(); + void FrameEdited(); + + private: + Ui::tf_frame_config ui_{}; + QWidget* config_widget_; + + rclcpp::TimerBase::SharedPtr timer_; + + void TimerCallback(); +}; +} // namespace mapviz_plugins + +#endif // MAPVIZ_PLUGINS__TF_FRAME_PLUGIN_H_ diff --git a/mapviz_plugins/mainpage.dox b/mapviz_plugins/mainpage.dox new file mode 100644 index 000000000..c5b93587f --- /dev/null +++ b/mapviz_plugins/mainpage.dox @@ -0,0 +1,23 @@ +/** +\mainpage +\section mapviz_plugins + +\b mapviz_plugins is a set of API's for ... + +This package... (see sumet_perception/material_classification/mainpage.dox for example description) + + +\subsection codeapi Code API + +The C++ API consists of the following main classes: + +- \b mapviz_plugins::GridPlugin - \copybrief mapviz_plugins::GridPlugin +- \b mapviz_plugins::ImagePlugin - \copybrief mapviz_plugins::ImagePlugin +- \b mapviz_plugins::MarkerPlugin - \copybrief mapviz_plugins::MarkerPlugin +- \b mapviz_plugins::MultiresImagePlugin - \copybrief mapviz_plugins::MultiresImagePlugin +- \b MultiresView - \copybrief MultiresView +- \b mapviz_plugins::OdometryPlugin - \copybrief mapviz_plugins::OdometryPlugin +- \b mapviz_plugins::PathPlugin - \copybrief mapviz_plugins::PathPlugin +- \b mapviz_plugins::RobotImagePlugin - \copybrief mapviz_plugins::RobotImagePlugin + +**/ diff --git a/mapviz_plugins/mapviz_plugins.xml b/mapviz_plugins/mapviz_plugins.xml new file mode 100644 index 000000000..4412f74ec --- /dev/null +++ b/mapviz_plugins/mapviz_plugins.xml @@ -0,0 +1,84 @@ + + + + Plugin to provide an intuitive visualization of orientations + from IMU messages, Odometry messages, and Tf messages. + + + + Prints clicked coordinates in specified frame and copies to clipboard. + + + Measures the distance between points on the map. + + + Odometry mapviz plugin. + + + Pose mapviz plugin. + + + Marker mapviz plugin. + + + Textured marker mapviz plugin. + + + + + Grid mapviz plugin. + + + Image mapviz plugin. + + + Disparity mapviz plugin. + + + Plugin for drawing and publishing a polygon. + + + Path mapviz plugin. + + + TF frame mapviz plugin. + + + Plan route mapviz plugin. + + + Route mapviz plugin. + + + Robot image mapviz plugin. + + + GPS mapviz plugin. + + + NavSat mapviz plugin. + + + LaserScan mapviz plugin. + + + PointCloud2 mapviz plugin. + + + Publishes a StampedPoint when a point on the map canvas is clicked. + + + Displays a std_msgs/String at a fixed point on the canvas. + + + Displays a float and velocity messages at a fixed point on the canvas. + + + Display maps and other OccupancyGrids + + + diff --git a/mapviz_plugins/package.xml b/mapviz_plugins/package.xml new file mode 100644 index 000000000..43c63bc9d --- /dev/null +++ b/mapviz_plugins/package.xml @@ -0,0 +1,57 @@ + + mapviz_plugins + 2.3.0 + + + Common plugins for the Mapviz visualization tool + + + Marc Alban + P. J. Reed + Southwest Research Institute + BSD + https://github.com/swri-robotics/mapviz + + ament_cmake + qt5-qmake + + libqt5-core + libqt5-opengl-dev + ros_environment + + ament_index_cpp + cv_bridge + gps_msgs + image_transport + map_msgs + mapviz + marti_common_msgs + marti_nav_msgs + marti_sensor_msgs + marti_visualization_msgs + + + nav_msgs + pluginlib + rclcpp_action + rclcpp + sensor_msgs + std_msgs + stereo_msgs + swri_image_util + swri_math_util + swri_route_util + swri_transform_util + tf2 + visualization_msgs + + libqt5-opengl + + + ament_cmake + + + + + + diff --git a/mapviz_plugins/src/attitude_indicator_plugin.cpp b/mapviz_plugins/src/attitude_indicator_plugin.cpp new file mode 100644 index 000000000..6ddf60b70 --- /dev/null +++ b/mapviz_plugins/src/attitude_indicator_plugin.cpp @@ -0,0 +1,392 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include + +#include +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::AttitudeIndicatorPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + AttitudeIndicatorPlugin::AttitudeIndicatorPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + { + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + roll_ = pitch_ = yaw_ = 0; + topics_.emplace_back("nav_msgs/msg/Odometry"); + topics_.emplace_back("geometry_msgs/msg/Pose"); + topics_.emplace_back("sensor_msgs/msg/Imu"); + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + placer_.setRect(QRect(0, 0, 100, 100)); + QObject::connect(this, SIGNAL(VisibleChanged(bool)), + &placer_, SLOT(setVisible(bool))); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited())); + } + + void AttitudeIndicatorPlugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic( + node_, + topics_); + if (topic.empty()) + { + return; + } + + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + + void AttitudeIndicatorPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = true; + PrintWarning("No messages received."); + + odom_sub_.reset(); + imu_sub_.reset(); + pose_sub_.reset(); + + topic_ = topic; + if (!topic_.empty()) + { + odom_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&AttitudeIndicatorPlugin::AttitudeCallbackOdom, this, std::placeholders::_1)); + imu_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&AttitudeIndicatorPlugin::AttitudeCallbackImu, this, std::placeholders::_1)); + pose_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&AttitudeIndicatorPlugin::AttitudeCallbackPose, this, std::placeholders::_1)); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void AttitudeIndicatorPlugin::AttitudeCallbackOdom( + nav_msgs::msg::Odometry::ConstSharedPtr odometry) + { + applyAttitudeOrientation(odometry->pose.pose.orientation); + } + + void AttitudeIndicatorPlugin::AttitudeCallbackImu(sensor_msgs::msg::Imu::ConstSharedPtr imu) + { + applyAttitudeOrientation(imu->orientation); + } + + void AttitudeIndicatorPlugin::AttitudeCallbackPose(geometry_msgs::msg::Pose::ConstSharedPtr pose) + { + applyAttitudeOrientation(pose->orientation); + } + + void AttitudeIndicatorPlugin::applyAttitudeOrientation( + const geometry_msgs::msg::Quaternion &orientation) + { + tf2::Quaternion attitude_orientation( + orientation.x, + orientation.y, + orientation.z, + orientation.w); + + tf2::Matrix3x3 m(attitude_orientation); + m.getRPY(roll_, pitch_, yaw_); + roll_ = roll_ * (180.0 / M_PI); + pitch_ = pitch_ * (180.0 / M_PI); + yaw_ = yaw_ * (180.0 / M_PI); + + canvas_->update(); + } + + void AttitudeIndicatorPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void AttitudeIndicatorPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void AttitudeIndicatorPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* AttitudeIndicatorPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + return config_widget_; + } + + bool AttitudeIndicatorPlugin::Initialize(QGLWidget* canvas) + { + initialized_ = true; + canvas_ = canvas; + placer_.setContainer(canvas_); + startTimer(50); + return true; + } + + void AttitudeIndicatorPlugin::Shutdown() + { + placer_.setContainer(nullptr); + } + + void AttitudeIndicatorPlugin::timerEvent(QTimerEvent*) + { + canvas_->update(); + } + + void AttitudeIndicatorPlugin::drawBall() + { + GLdouble eqn[4] = {0.0, 0.0, 1.0, 0.0}; + GLdouble eqn2[4] = {0.0, 0.0, -1.0, 0.0}; + GLdouble eqn4[4] = {0.0, 0.0, 1.0, 0.05}; + GLdouble eqn3[4] = {0.0, 0.0, -1.0, 0.05}; + + glEnable(GL_DEPTH_TEST); + glDepthFunc(GL_LESS); + + glPushMatrix(); + + glColor3f(0.392156863f, 0.584313725f, 0.929411765f); + glRotated(90.0 + pitch_, 1.0, 0.0, 0.0); + + glRotated(roll_, 0.0, 1.0, 0.0); + glRotated(yaw_, 0.0, 0.0, 1.0); + glClipPlane(GL_CLIP_PLANE1, eqn2); + glEnable(GL_CLIP_PLANE1); + glutSolidSphere(.8, 20, 16); + glDisable(GL_CLIP_PLANE1); + glPopMatrix(); + + glPushMatrix(); + + glLineWidth(2); + glColor3f(1.0f, 1.0f, 1.0f); + glRotated(90.0 + pitch_, 1.0, 0.0, 0.0); + glRotated(roll_, 0.0, 1.0, 0.0); + glRotated(yaw_, 0.0, 0.0, 1.0); + glClipPlane(GL_CLIP_PLANE3, eqn4); + glClipPlane(GL_CLIP_PLANE2, eqn3); + glEnable(GL_CLIP_PLANE2); + glEnable(GL_CLIP_PLANE3); + glutWireSphere(.801, 10, 16); + glDisable(GL_CLIP_PLANE2); + glDisable(GL_CLIP_PLANE3); + glPopMatrix(); + + glPushMatrix(); + glColor3f(0.62745098f, 0.321568627f, 0.176470588f); + glRotated(90.0 + pitch_, 1.0, 0.0, 0.0); // x + glRotated(roll_, 0.0, 1.0, 0.0); // y + glRotated(yaw_, 0.0, 0.0, 1.0); // z + glClipPlane(GL_CLIP_PLANE0, eqn); + glEnable(GL_CLIP_PLANE0); + glutSolidSphere(.8, 20, 16); + glDisable(GL_CLIP_PLANE0); + glPopMatrix(); + glDisable(GL_DEPTH_TEST); + } + + void AttitudeIndicatorPlugin::Draw(double x, double y, double scale) + { + glPushAttrib(GL_ALL_ATTRIB_BITS); + glMatrixMode(GL_PROJECTION); + glPushMatrix(); + glLoadIdentity(); + glOrtho(0, canvas_->width(), canvas_->height(), 0, -1.0f, 1.0f); + glMatrixMode(GL_MODELVIEW); + glPushMatrix(); + glLoadIdentity(); + // Setup coordinate system so that we have a [-1,1]x[1,1] cube on + // the screen. + QRect rect = placer_.rect(); + double s_x = rect.width() / 2.0; + double s_y = -rect.height() / 2.0; + double t_x = rect.right() - s_x; + double t_y = rect.top() - s_y; + + double m[16] = { + s_x, 0, 0, 0, + 0, s_y, 0, 0, + 0, 0, 1.0, 0, + t_x, t_y, 0, 1.0}; + glMultMatrixd(m); + + // Placed in a separate function so that we don't forget to pop the + // GL state back. + + drawBackground(); + drawBall(); + + drawPanel(); + + glPopMatrix(); + glMatrixMode(GL_PROJECTION); + glPopMatrix(); + glMatrixMode(GL_MODELVIEW); + glPopAttrib(); + PrintInfo("OK!"); + } + + void AttitudeIndicatorPlugin::drawBackground() + { + glBegin(GL_TRIANGLES); + glColor4f(0.0f, 0.0f, 0.0f, 1.0f); + + glVertex2d(-1.0, -1.0); + glVertex2d(-1.0, 1.0); + glVertex2d(1.0, 1.0); + + glVertex2d(-1.0, -1.0); + glVertex2d(1.0, 1.0); + glVertex2d(1.0, -1.0); + + glEnd(); + } + + void AttitudeIndicatorPlugin::drawPanel() + { + glLineWidth(2); + + glBegin(GL_LINE_STRIP); + glColor4f(1.0f, 1.0f, 1.0f, 1.0f); + + glVertex2d(-0.9, 0.0); + glVertex2d(-0.2, 0.0); + + int divisions = 20; + for (int i = 1; i < divisions; i++) + { + glVertex2d(-0.2 * std::cos(M_PI * i / divisions), + -0.2 * std::sin(M_PI * i / divisions)); + } + + glVertex2f(0.2, 0.0); + glVertex2f(0.9, 0.0); + glEnd(); + + glBegin(GL_LINES); + glVertex2f(0.0, -0.2f); + glVertex2f(0.0, -0.9f); + glEnd(); + } + + void AttitudeIndicatorPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(topic.c_str()); + } + + QRect current = placer_.rect(); + int x = current.x(); + int y = current.y(); + int width = current.width(); + int height = current.height(); + + if (node["x"]) + { + x = node["x"].as(); + } + + if (node["y"]) + { + y = node["y"].as(); + } + + if (node["width"]) + { + width = node["width"].as(); + } + + if (node["height"]) + { + height = node["height"].as(); + } + + QRect position(x, y, width, height); + placer_.setRect(position); + + TopicEdited(); + } + + void AttitudeIndicatorPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString(); + + QRect position = placer_.rect(); + + emitter << YAML::Key << "x" << YAML::Value << position.x(); + emitter << YAML::Key << "y" << YAML::Value << position.y(); + emitter << YAML::Key << "width" << YAML::Value << position.width(); + emitter << YAML::Key << "height" << YAML::Value << position.height(); + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/canvas_click_filter.cpp b/mapviz_plugins/src/canvas_click_filter.cpp new file mode 100644 index 000000000..13ca433df --- /dev/null +++ b/mapviz_plugins/src/canvas_click_filter.cpp @@ -0,0 +1,83 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include +#include +#include +#include "mapviz_plugins/canvas_click_filter.h" + +namespace mapviz_plugins +{ + CanvasClickFilter::CanvasClickFilter() + : QObject() + , is_mouse_down_(false) + , max_ms_(Q_INT64_C(500)) + , max_distance_(2.0) + { } + + void CanvasClickFilter::setMaxClickTime(qint64 max_ms) + { + max_ms_ = max_ms; + } + + void CanvasClickFilter::setMaxClickMovement(qreal max_distance) + { + max_distance_ = max_distance; + } + + bool CanvasClickFilter::eventFilter(QObject* object, QEvent* event) + { + if (event->type() == QEvent::MouseButtonPress) + { + is_mouse_down_ = true; + QMouseEvent* me = dynamic_cast(event); + mouse_down_pos_ = me->localPos(); + mouse_down_time_ = QDateTime::currentMSecsSinceEpoch(); + } else if (event->type() == QEvent::MouseButtonRelease) { + if (is_mouse_down_) + { + QMouseEvent* me = dynamic_cast(event); + + qreal distance = QLineF(mouse_down_pos_, me->localPos()).length(); + qint64 msecsDiff = QDateTime::currentMSecsSinceEpoch() - mouse_down_time_; + + // Only fire the event if the mouse has moved less than the maximum distance + // and was held for shorter than the maximum time.. This prevents click + // events from being fired if the user is dragging the mouse across the map + // or just holding the cursor in place. + if (msecsDiff < max_ms_ && distance <= max_distance_) + { + Q_EMIT pointClicked(me->localPos()); + } + } + is_mouse_down_ = false; + } + return false; + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/coordinate_picker_plugin.cpp b/mapviz_plugins/src/coordinate_picker_plugin.cpp new file mode 100644 index 000000000..fcee6ca8b --- /dev/null +++ b/mapviz_plugins/src/coordinate_picker_plugin.cpp @@ -0,0 +1,306 @@ +// ***************************************************************************** +// +// Copyright (c) 2018, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include +#include + +#include +#include +#include + +#if QT_VERSION >= 0x050000 +#include +#else +#include +#endif + +// ROS Libraries +#include + +// Mapviz Libraries +#include + +// +#include +#include +#include + +#include + +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::CoordinatePickerPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + +CoordinatePickerPlugin::CoordinatePickerPlugin() + : MapvizPlugin() + , config_widget_(new QWidget()) + , map_canvas_(nullptr) + , copy_on_click_(false) +{ + ui_.setupUi(config_widget_); + + QObject::connect(ui_.selectframe, SIGNAL(clicked()), + this, SLOT(SelectFrame())); + QObject::connect(ui_.frame, SIGNAL(editingFinished()), + this, SLOT(FrameEdited())); + QObject::connect(ui_.copyCheckBox, SIGNAL(stateChanged(int)), + this, SLOT(ToggleCopyOnClick(int))); + QObject::connect(ui_.clearListButton, SIGNAL(clicked()), + this, SLOT(ClearCoordList())); + + ui_.coordTextEdit->setPlaceholderText(tr("Click on the map; coordinates appear here")); +} + +CoordinatePickerPlugin::~CoordinatePickerPlugin() +{ + if (map_canvas_) + { + map_canvas_->removeEventFilter(this); + } +} + +QWidget* CoordinatePickerPlugin::GetConfigWidget(QWidget* parent) +{ + config_widget_->setParent(parent); + + return config_widget_; +} + +bool CoordinatePickerPlugin::Initialize(QGLWidget* canvas) +{ + map_canvas_ = dynamic_cast< mapviz::MapCanvas* >(canvas); + map_canvas_->installEventFilter(this); + + initialized_ = true; + PrintInfo("OK"); + + return true; +} + +bool CoordinatePickerPlugin::eventFilter(QObject* object, QEvent* event) +{ + if(!this->Visible()) + { + RCLCPP_DEBUG(node_->get_logger(), "Ignoring mouse event, since coordinate picker plugin is hidden"); + return false; + } + + switch (event->type()) + { + case QEvent::MouseButtonPress: + return handleMousePress(dynamic_cast< QMouseEvent* >(event)); + case QEvent::MouseButtonRelease: + return handleMouseRelease(dynamic_cast< QMouseEvent* >(event)); + case QEvent::MouseMove: + return handleMouseMove(dynamic_cast< QMouseEvent* >(event)); + default: + return false; + } +} + +bool CoordinatePickerPlugin::handleMousePress(QMouseEvent* event) +{ + QPointF point = event->localPos(); + RCLCPP_DEBUG(node_->get_logger(), "Map point: %f %f", point.x(), point.y()); + + swri_transform_util::Transform transform; + std::string frame = ui_.frame->text().toStdString(); + if (frame.empty()) + { + frame = target_frame_; + } + + // Frames get confusing. The `target_frame_` member is set by the "Fixed + // Frame" combobox in the GUI. When we transform the map coordinate to the + // fixed frame, we get it in the `target_frame_` frame. + // + // Then we translate from that frame into *our* target frame, `frame`. + if (tf_manager_->GetTransform(frame, target_frame_, transform)) + { + RCLCPP_DEBUG(node_->get_logger(), + "Transforming from fixed frame '%s' to (plugin) target frame '%s'", + target_frame_.c_str(), + frame.c_str()); + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + RCLCPP_DEBUG(node_->get_logger(), + "Point in fixed frame: %f %f", + transformed.x(), + transformed.y()); + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + position = transform * position; + point.setX(position.x()); + point.setY(position.y()); + + PrintInfo("OK"); + } else { + QString warning; + QTextStream(&warning) << "No available transform from '" + << QString::fromStdString(target_frame_) + << "' to '" + << QString::fromStdString(frame) + << "'"; + PrintWarning(warning.toStdString()); + return false; + } + + + RCLCPP_DEBUG(node_->get_logger(), + "Transformed point in frame '%s': %f %f", + frame.c_str(), + point.x(), + point.y()); + QString new_point; + QTextStream stream(&new_point); + if (swri_transform_util::FrameIdsEqual(frame, swri_transform_util::_wgs84_frame)) + { + stream.setRealNumberPrecision(9); + } + else + { + stream.setRealNumberPrecision(4); + } + stream << point.x() << ", " << point.y(); + + if (copy_on_click_) + { + QClipboard* clipboard = QGuiApplication::clipboard(); + clipboard->setText(new_point); + } + + stream << " (" << QString::fromStdString(frame) << ")\n"; + + ui_.coordTextEdit->setPlainText(ui_.coordTextEdit->toPlainText().prepend(new_point)); + + // Let other plugins process this event too + return false; +} + +bool CoordinatePickerPlugin::handleMouseRelease(QMouseEvent* event) +{ + // Let other plugins process this event too + return false; +} + +bool CoordinatePickerPlugin::handleMouseMove(QMouseEvent* event) +{ + // Let other plugins process this event too + return false; +} + +void CoordinatePickerPlugin::SelectFrame() +{ + std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_buf_); + if (!frame.empty()) + { + ui_.frame->setText(QString::fromStdString(frame)); + FrameEdited(); + } +} + +void CoordinatePickerPlugin::FrameEdited() +{ + RCLCPP_INFO(node_->get_logger(), + "Setting target frame to %s", + ui_.frame->text().toStdString().c_str()); +} + +void CoordinatePickerPlugin::ToggleCopyOnClick(int state) +{ + switch (state) + { + case Qt::Checked: + copy_on_click_ = true; + break; + case Qt::PartiallyChecked: + case Qt::Unchecked: + default: + copy_on_click_ = false; + break; + } +} + +void CoordinatePickerPlugin::ClearCoordList() +{ + ui_.coordTextEdit->setPlainText(QString()); +} + +void CoordinatePickerPlugin::Draw(double x, double y, double scale) +{ +} + +void CoordinatePickerPlugin::LoadConfig(const YAML::Node& node, const std::string& path) +{ + if (node["frame"]) + { + std::string frame; + frame = node["frame"].as(); + ui_.frame->setText(QString::fromStdString(frame)); + } + + if (node["copy"]) + { + bool copy; + copy = node["copy"].as(); + if (copy) + { + ui_.copyCheckBox->setCheckState(Qt::Checked); + } else { + ui_.copyCheckBox->setCheckState(Qt::Unchecked); + } + } +} + +void CoordinatePickerPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) +{ + std::string frame = ui_.frame->text().toStdString(); + emitter << YAML::Key << "frame" << YAML::Value << frame; + + bool copy_on_click = ui_.copyCheckBox->isChecked(); + emitter << YAML::Key << "copy" << YAML::Value << copy_on_click; +} + +void CoordinatePickerPlugin::PrintError(const std::string& message) +{ + PrintErrorHelper(ui_.status, message, 1.0); +} + +void CoordinatePickerPlugin::PrintInfo(const std::string& message) +{ + PrintInfoHelper(ui_.status, message, 1.0); +} + +void CoordinatePickerPlugin::PrintWarning(const std::string& message) +{ + PrintWarningHelper(ui_.status, message, 1.0); +} + +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/disparity_plugin.cpp b/mapviz_plugins/src/disparity_plugin.cpp new file mode 100644 index 000000000..6229829e2 --- /dev/null +++ b/mapviz_plugins/src/disparity_plugin.cpp @@ -0,0 +1,781 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include + +// ROS libraries +#include +#include +#include + +#ifdef USE_CVBRIDGE_H_FILES +#include +#else +#include +#endif + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::DisparityPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + DisparityPlugin::DisparityPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , anchor_(TOP_LEFT) + , units_(PIXELS) + , offset_x_(0) + , offset_y_(0) + , width_(320) + , height_(240) + , has_image_(false) + , last_width_(0) + , last_height_(0) + , has_message_(false) + { + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited())); + QObject::connect(ui_.anchor, SIGNAL(activated(QString)), this, SLOT(SetAnchor(QString))); + QObject::connect(ui_.units, SIGNAL(activated(QString)), this, SLOT(SetUnits(QString))); + QObject::connect(ui_.offsetx, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetX(int))); + QObject::connect(ui_.offsety, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetY(int))); + QObject::connect(ui_.width, SIGNAL(valueChanged(int)), this, SLOT(SetWidth(int))); + QObject::connect(ui_.height, SIGNAL(valueChanged(int)), this, SLOT(SetHeight(int))); + QObject::connect(this, SIGNAL(VisibleChanged(bool)), this, SLOT(SetSubscription(bool))); + } + + void DisparityPlugin::SetOffsetX(int offset) + { + offset_x_ = offset; + } + + void DisparityPlugin::SetOffsetY(int offset) + { + offset_y_ = offset; + } + + void DisparityPlugin::SetWidth(int width) + { + width_ = width; + } + + void DisparityPlugin::SetHeight(int height) + { + height_ = height; + } + + void DisparityPlugin::SetAnchor(QString anchor) + { + if (anchor == "top left") + { + anchor_ = TOP_LEFT; + } else if (anchor == "top center") { + anchor_ = TOP_CENTER; + } else if (anchor == "top right") { + anchor_ = TOP_RIGHT; + } else if (anchor == "center left") { + anchor_ = CENTER_LEFT; + } else if (anchor == "center") { + anchor_ = CENTER; + } else if (anchor == "center right") { + anchor_ = CENTER_RIGHT; + } else if (anchor == "bottom left") { + anchor_ = BOTTOM_LEFT; + } else if (anchor == "bottom center") { + anchor_ = BOTTOM_CENTER; + } else if (anchor == "bottom right") { + anchor_ = BOTTOM_RIGHT; + } + } + + void DisparityPlugin::SetUnits(QString units) + { + if (units == "pixels") + { + units_ = PIXELS; + } else if (units == "percent") { + units_ = PERCENT; + } + } + void DisparityPlugin::SetSubscription(bool visible) + { + if(topic_.empty()) + { + return; + } else if (!visible) { + disparity_sub_.reset(); + RCLCPP_INFO(node_->get_logger(), "Dropped subscription to %s", topic_.c_str()); + } else { + disparity_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&DisparityPlugin::disparityCallback, this, std::placeholders::_1) + ); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + void DisparityPlugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic( + node_, + "stereo_msgs/msg/DisparityImage" + ); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void DisparityPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (!this->Visible()) + { + PrintWarning("Topic is Hidden"); + initialized_ = false; + has_message_ = false; + if (!topic.empty()) + { + topic_ = topic; + } + disparity_sub_.reset(); + return; + } + if (topic != topic_) + { + PrintWarning("Topic is Hidden"); + initialized_ = false; + has_message_ = false; + topic_ = topic; + PrintWarning("No messages received."); + + disparity_sub_.reset(); + + if (!topic.empty()) + { + disparity_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&DisparityPlugin::disparityCallback, this, std::placeholders::_1) + ); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void DisparityPlugin::disparityCallback( + const stereo_msgs::msg::DisparityImage::SharedPtr disparity) + { + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + if (disparity->min_disparity == 0.0 && disparity->max_disparity == 0.0) + { + PrintError("Min and max disparity not set."); + has_image_ = false; + return; + } + + if (disparity->image.encoding != sensor_msgs::image_encodings::TYPE_32FC1) + { + PrintError("Invalid encoding."); + has_image_ = false; + return; + } + + disparity_ = *disparity; + + // Colormap and display the disparity image + float min_disparity = disparity->min_disparity; + float max_disparity = disparity->max_disparity; + float multiplier = 255.0f / (max_disparity - min_disparity); + + cv_bridge::CvImageConstPtr cv_disparity = + cv_bridge::toCvShare(disparity->image, disparity); + + disparity_color_.create(disparity->image.height, disparity->image.width); + + for (int row = 0; row < disparity_color_.rows; row++) + { + const float* d = cv_disparity->image.ptr(row); + for (int col = 0; col < disparity_color_.cols; col++) + { + int index = static_cast((d[col] - min_disparity) * multiplier + 0.5); + index = std::min(255, std::max(0, index)); + // Fill as BGR + disparity_color_(row, col)[2] = COLOR_MAP[3*index + 0]; + disparity_color_(row, col)[1] = COLOR_MAP[3*index + 1]; + disparity_color_(row, col)[0] = COLOR_MAP[3*index + 2]; + } + } + + last_width_ = 0; + last_height_ = 0; + + has_image_ = true; + } + + void DisparityPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void DisparityPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void DisparityPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* DisparityPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool DisparityPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + return true; + } + + void DisparityPlugin::ScaleImage(double width, double height) + { + if (!has_image_) + { + return; + } + + cv::resize(disparity_color_, scaled_image_, cvSize2D32f(width, height), 0, 0, CV_INTER_AREA); + } + + void DisparityPlugin::DrawIplImage(cv::Mat *image) + { + // TODO(malban): glTexture2D may be more efficient than glDrawPixels + + if (!has_image_) + return; + + if (image == NULL) + return; + + if (image->cols == 0 || image->rows == 0) + return; + + GLenum format; + switch (image->channels()) + { + case 1: + format = GL_LUMINANCE; + break; + case 2: + format = GL_LUMINANCE_ALPHA; + break; + case 3: + format = GL_BGR; + break; + default: + return; + } + + glPixelZoom(1.0, -1.0f); + glDrawPixels(image->cols, image->rows, format, GL_UNSIGNED_BYTE, image->ptr()); + + PrintInfo("OK"); + } + + void DisparityPlugin::Draw(double x, double y, double scale) + { + // Calculate the correct offsets and dimensions + double x_offset = offset_x_; + double y_offset = offset_y_; + double width = width_; + double height = height_; + if (units_ == PERCENT) + { + x_offset = offset_x_ * canvas_->width() / 100.0; + y_offset = offset_y_ * canvas_->height() / 100.0; + width = width_ * canvas_->width() / 100.0; + height = height_ * canvas_->height() / 100.0; + } + + // Scale the source image if necessary + if (width != last_width_ || height != last_height_) + { + ScaleImage(width, height); + } + + // Calculate the correct render position + double x_pos = 0; + double y_pos = 0; + if (anchor_ == TOP_LEFT) + { + x_pos = x_offset; + y_pos = y_offset; + } else if (anchor_ == TOP_CENTER) { + x_pos = (canvas_->width() - width) / 2.0 + x_offset; + y_pos = y_offset; + } else if (anchor_ == TOP_RIGHT) { + x_pos = canvas_->width() - width - x_offset; + y_pos = y_offset; + } else if (anchor_ == CENTER_LEFT) { + x_pos = x_offset; + y_pos = (canvas_->height() - height) / 2.0 + y_offset; + } else if (anchor_ == CENTER) { + x_pos = (canvas_->width() - width) / 2.0 + x_offset; + y_pos = (canvas_->height() - height) / 2.0 + y_offset; + } else if (anchor_ == CENTER_RIGHT) { + x_pos = canvas_->width() - width - x_offset; + y_pos = (canvas_->height() - height) / 2.0 + y_offset; + } else if (anchor_ == BOTTOM_LEFT) { + x_pos = x_offset; + y_pos = canvas_->height() - height - y_offset; + } else if (anchor_ == BOTTOM_CENTER) { + x_pos = (canvas_->width() - width) / 2.0 + x_offset; + y_pos = canvas_->height() - height - y_offset; + } else if (anchor_ == BOTTOM_RIGHT) { + x_pos = canvas_->width() - width - x_offset; + y_pos = canvas_->height() - height - y_offset; + } + + glMatrixMode(GL_PROJECTION); + glPushMatrix(); + glLoadIdentity(); + glOrtho(0, canvas_->width(), canvas_->height(), 0, -0.5f, 0.5f); + + glRasterPos2d(x_pos, y_pos); + + DrawIplImage(&scaled_image_); + + glPopMatrix(); + + last_width_ = width; + last_height_ = height; + } + + void DisparityPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(topic.c_str()); + TopicEdited(); + } + + if (node["anchor"]) + { + std::string anchor = node["anchor"].as(); + ui_.anchor->setCurrentIndex(ui_.anchor->findText(anchor.c_str())); + SetAnchor(anchor.c_str()); + } + + if (node["units"]) + { + std::string units = node["units"].as(); + ui_.units->setCurrentIndex(ui_.units->findText(units.c_str())); + SetUnits(units.c_str()); + } + + if (node["offset_x"]) + { + offset_x_ = node["offset_x"].as(); + ui_.offsetx->setValue(static_cast(offset_x_)); + } + + if (node["offset_y"]) + { + offset_y_ = node["offset_y"].as(); + ui_.offsety->setValue(static_cast(offset_y_)); + } + + if (node["width"]) + { + width_ = node["width"].as(); + ui_.width->setValue(static_cast(width_)); + } + + if (node["height"]) + { + height_ = node["height"].as(); + ui_.height->setValue(static_cast(height_)); + } + } + + void DisparityPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString(); + emitter << YAML::Key << "anchor" << YAML::Value << AnchorToString(anchor_); + emitter << YAML::Key << "units" << YAML::Value << UnitsToString(units_); + emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_; + emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_; + emitter << YAML::Key << "width" << YAML::Value << width_; + emitter << YAML::Key << "height" << YAML::Value << height_; + } + + std::string DisparityPlugin::AnchorToString(Anchor anchor) + { + std::string anchor_string = "top left"; + + if (anchor == TOP_LEFT) + { + anchor_string = "top left"; + } else if (anchor == TOP_CENTER) { + anchor_string = "top center"; + } else if (anchor == TOP_RIGHT) { + anchor_string = "top right"; + } else if (anchor == CENTER_LEFT) { + anchor_string = "center left"; + } else if (anchor == CENTER) { + anchor_string = "center"; + } else if (anchor == CENTER_RIGHT) { + anchor_string = "center right"; + } else if (anchor == BOTTOM_LEFT) { + anchor_string = "bottom left"; + } else if (anchor == BOTTOM_CENTER) { + anchor_string = "bottom center"; + } else if (anchor == BOTTOM_RIGHT) { + anchor_string = "bottom right"; + } + + return anchor_string; + } + + std::string DisparityPlugin::UnitsToString(Units units) + { + std::string units_string = "pixels"; + + if (units == PIXELS) + { + units_string = "pixels"; + } else if (units == PERCENT) { + units_string = "percent"; + } + + return units_string; + } + + const unsigned char DisparityPlugin::COLOR_MAP[768] = + { 150, 150, 150, + 107, 0, 12, + 106, 0, 18, + 105, 0, 24, + 103, 0, 30, + 102, 0, 36, + 101, 0, 42, + 99, 0, 48, + 98, 0, 54, + 97, 0, 60, + 96, 0, 66, + 94, 0, 72, + 93, 0, 78, + 92, 0, 84, + 91, 0, 90, + 89, 0, 96, + 88, 0, 102, + 87, 0, 108, + 85, 0, 114, + 84, 0, 120, + 83, 0, 126, + 82, 0, 131, + 80, 0, 137, + 79, 0, 143, + 78, 0, 149, + 77, 0, 155, + 75, 0, 161, + 74, 0, 167, + 73, 0, 173, + 71, 0, 179, + 70, 0, 185, + 69, 0, 191, + 68, 0, 197, + 66, 0, 203, + 65, 0, 209, + 64, 0, 215, + 62, 0, 221, + 61, 0, 227, + 60, 0, 233, + 59, 0, 239, + 57, 0, 245, + 56, 0, 251, + 55, 0, 255, + 54, 0, 255, + 52, 0, 255, + 51, 0, 255, + 50, 0, 255, + 48, 0, 255, + 47, 0, 255, + 46, 0, 255, + 45, 0, 255, + 43, 0, 255, + 42, 0, 255, + 41, 0, 255, + 40, 0, 255, + 38, 0, 255, + 37, 0, 255, + 36, 0, 255, + 34, 0, 255, + 33, 0, 255, + 32, 0, 255, + 31, 0, 255, + 29, 0, 255, + 28, 0, 255, + 27, 0, 255, + 26, 0, 255, + 24, 0, 255, + 23, 0, 255, + 22, 0, 255, + 20, 0, 255, + 19, 0, 255, + 18, 0, 255, + 17, 0, 255, + 15, 0, 255, + 14, 0, 255, + 13, 0, 255, + 11, 0, 255, + 10, 0, 255, + 9, 0, 255, + 8, 0, 255, + 6, 0, 255, + 5, 0, 255, + 4, 0, 255, + 3, 0, 255, + 1, 0, 255, + 0, 4, 255, + 0, 10, 255, + 0, 16, 255, + 0, 22, 255, + 0, 28, 255, + 0, 34, 255, + 0, 40, 255, + 0, 46, 255, + 0, 52, 255, + 0, 58, 255, + 0, 64, 255, + 0, 70, 255, + 0, 76, 255, + 0, 82, 255, + 0, 88, 255, + 0, 94, 255, + 0, 100, 255, + 0, 106, 255, + 0, 112, 255, + 0, 118, 255, + 0, 124, 255, + 0, 129, 255, + 0, 135, 255, + 0, 141, 255, + 0, 147, 255, + 0, 153, 255, + 0, 159, 255, + 0, 165, 255, + 0, 171, 255, + 0, 177, 255, + 0, 183, 255, + 0, 189, 255, + 0, 195, 255, + 0, 201, 255, + 0, 207, 255, + 0, 213, 255, + 0, 219, 255, + 0, 225, 255, + 0, 231, 255, + 0, 237, 255, + 0, 243, 255, + 0, 249, 255, + 0, 255, 255, + 0, 255, 249, + 0, 255, 243, + 0, 255, 237, + 0, 255, 231, + 0, 255, 225, + 0, 255, 219, + 0, 255, 213, + 0, 255, 207, + 0, 255, 201, + 0, 255, 195, + 0, 255, 189, + 0, 255, 183, + 0, 255, 177, + 0, 255, 171, + 0, 255, 165, + 0, 255, 159, + 0, 255, 153, + 0, 255, 147, + 0, 255, 141, + 0, 255, 135, + 0, 255, 129, + 0, 255, 124, + 0, 255, 118, + 0, 255, 112, + 0, 255, 106, + 0, 255, 100, + 0, 255, 94, + 0, 255, 88, + 0, 255, 82, + 0, 255, 76, + 0, 255, 70, + 0, 255, 64, + 0, 255, 58, + 0, 255, 52, + 0, 255, 46, + 0, 255, 40, + 0, 255, 34, + 0, 255, 28, + 0, 255, 22, + 0, 255, 16, + 0, 255, 10, + 0, 255, 4, + 2, 255, 0, + 8, 255, 0, + 14, 255, 0, + 20, 255, 0, + 26, 255, 0, + 32, 255, 0, + 38, 255, 0, + 44, 255, 0, + 50, 255, 0, + 56, 255, 0, + 62, 255, 0, + 68, 255, 0, + 74, 255, 0, + 80, 255, 0, + 86, 255, 0, + 92, 255, 0, + 98, 255, 0, + 104, 255, 0, + 110, 255, 0, + 116, 255, 0, + 122, 255, 0, + 128, 255, 0, + 133, 255, 0, + 139, 255, 0, + 145, 255, 0, + 151, 255, 0, + 157, 255, 0, + 163, 255, 0, + 169, 255, 0, + 175, 255, 0, + 181, 255, 0, + 187, 255, 0, + 193, 255, 0, + 199, 255, 0, + 205, 255, 0, + 211, 255, 0, + 217, 255, 0, + 223, 255, 0, + 229, 255, 0, + 235, 255, 0, + 241, 255, 0, + 247, 255, 0, + 253, 255, 0, + 255, 251, 0, + 255, 245, 0, + 255, 239, 0, + 255, 233, 0, + 255, 227, 0, + 255, 221, 0, + 255, 215, 0, + 255, 209, 0, + 255, 203, 0, + 255, 197, 0, + 255, 191, 0, + 255, 185, 0, + 255, 179, 0, + 255, 173, 0, + 255, 167, 0, + 255, 161, 0, + 255, 155, 0, + 255, 149, 0, + 255, 143, 0, + 255, 137, 0, + 255, 131, 0, + 255, 126, 0, + 255, 120, 0, + 255, 114, 0, + 255, 108, 0, + 255, 102, 0, + 255, 96, 0, + 255, 90, 0, + 255, 84, 0, + 255, 78, 0, + 255, 72, 0, + 255, 66, 0, + 255, 60, 0, + 255, 54, 0, + 255, 48, 0, + 255, 42, 0, + 255, 36, 0, + 255, 30, 0, + 255, 24, 0, + 255, 18, 0, + 255, 12, 0, + 255, 6, 0, + 255, 0, 0, + }; +} // namespace mapviz_plugins + diff --git a/mapviz_plugins/src/draw_polygon_plugin.cpp b/mapviz_plugins/src/draw_polygon_plugin.cpp new file mode 100644 index 000000000..0204bd7e2 --- /dev/null +++ b/mapviz_plugins/src/draw_polygon_plugin.cpp @@ -0,0 +1,424 @@ +// ***************************************************************************** +// +// Copyright (c) 2016, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include +#include +#include +#include + +#include +#include +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::DrawPolygonPlugin, mapviz::MapvizPlugin) + +namespace stu = swri_transform_util; + +namespace mapviz_plugins +{ + DrawPolygonPlugin::DrawPolygonPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , map_canvas_(nullptr) + , selected_point_(-1) + , is_mouse_down_(false) + , mouse_down_time_(0) + , max_ms_(Q_INT64_C(500)) + , max_distance_(2.0) + { + ui_.setupUi(config_widget_); + + ui_.color->setColor(Qt::green); + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selectframe, SIGNAL(clicked()), this, + SLOT(SelectFrame())); + QObject::connect(ui_.frame, SIGNAL(editingFinished()), this, + SLOT(FrameEdited())); + QObject::connect(ui_.publish, SIGNAL(clicked()), this, + SLOT(PublishPolygon())); + QObject::connect(ui_.clear, SIGNAL(clicked()), this, + SLOT(Clear())); + } + + DrawPolygonPlugin::~DrawPolygonPlugin() + { + if (map_canvas_) + { + map_canvas_->removeEventFilter(this); + } + } + + void DrawPolygonPlugin::SelectFrame() + { + std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_buf_); + if (!frame.empty()) + { + ui_.frame->setText(QString::fromStdString(frame)); + FrameEdited(); + } + } + + void DrawPolygonPlugin::FrameEdited() + { + source_frame_ = ui_.frame->text().toStdString(); + PrintWarning("Waiting for transform."); + + RCLCPP_INFO(node_->get_logger(), "Setting target frame to to %s", source_frame_.c_str()); + + initialized_ = true; + } + + void DrawPolygonPlugin::PublishPolygon() + { + if (polygon_topic_ != ui_.topic->text().toStdString()) + { + polygon_topic_ = ui_.topic->text().toStdString(); + rclcpp::QoS qos = rclcpp::QoS(1).durability(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL); + polygon_pub_ = node_->create_publisher( + polygon_topic_, qos); + } + + geometry_msgs::msg::PolygonStamped::UniquePtr polygon = + std::make_unique(); + polygon->header.stamp = node_->get_clock()->now(); + polygon->header.frame_id = ui_.frame->text().toStdString(); + + for (const auto& vertex : vertices_) + { + geometry_msgs::msg::Point32 point; + point.x = vertex.x(); + point.y = vertex.y(); + point.z = 0; + polygon->polygon.points.push_back(point); + } + + polygon_pub_->publish(*polygon); + } + + void DrawPolygonPlugin::Clear() + { + vertices_.clear(); + transformed_vertices_.clear(); + } + + void DrawPolygonPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message, 1.0); + } + + void DrawPolygonPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message, 1.0); + } + + void DrawPolygonPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message, 1.0); + } + + QWidget* DrawPolygonPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool DrawPolygonPlugin::Initialize(QGLWidget* canvas) + { + map_canvas_ = dynamic_cast(canvas); + map_canvas_->installEventFilter(this); + + initialized_ = true; + return true; + } + + bool DrawPolygonPlugin::eventFilter(QObject *object, QEvent* event) + { + switch (event->type()) + { + case QEvent::MouseButtonPress: + return handleMousePress(dynamic_cast(event)); + case QEvent::MouseButtonRelease: + return handleMouseRelease(dynamic_cast(event)); + case QEvent::MouseMove: + return handleMouseMove(dynamic_cast(event)); + default: + return false; + } + } + + bool DrawPolygonPlugin::handleMousePress(QMouseEvent* event) + { + if(!this->Visible()) + { + RCLCPP_DEBUG(node_->get_logger(), "Ignoring mouse press, since draw polygon plugin is hidden"); + return false; + } + + selected_point_ = -1; + int closest_point = 0; + double closest_distance = std::numeric_limits::max(); + + QPointF point = event->localPos(); + stu::Transform transform; + std::string frame = ui_.frame->text().toStdString(); + if (tf_manager_->GetTransform(target_frame_, frame, transform)) + { + for (size_t i = 0; i < vertices_.size(); i++) + { + tf2::Vector3 vertex = vertices_[i]; + vertex = transform * vertex; + + QPointF transformed = map_canvas_->FixedFrameToMapGlCoord(QPointF(vertex.x(), vertex.y())); + + double distance = QLineF(transformed, point).length(); + + if (distance < closest_distance) + { + closest_distance = distance; + closest_point = static_cast(i); + } + } + } + + if (event->button() == Qt::LeftButton) + { + if (closest_distance < 15) + { + selected_point_ = closest_point; + return true; + } else { + is_mouse_down_ = true; + mouse_down_pos_ = event->localPos(); + mouse_down_time_ = QDateTime::currentMSecsSinceEpoch(); + return false; + } + } else if (event->button() == Qt::RightButton) { + if (closest_distance < 15) + { + vertices_.erase(vertices_.begin() + closest_point); + transformed_vertices_.resize(vertices_.size()); + return true; + } + } + + return false; + } + + bool DrawPolygonPlugin::handleMouseRelease(QMouseEvent* event) + { + std::string frame = ui_.frame->text().toStdString(); + if (selected_point_ >= 0 && static_cast(selected_point_) < vertices_.size()) + { + QPointF point = event->localPos(); + stu::Transform transform; + if (tf_manager_->GetTransform(frame, target_frame_, transform)) + { + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + position = transform * position; + vertices_[selected_point_].setX(position.x()); + vertices_[selected_point_].setY(position.y()); + } + + selected_point_ = -1; + return true; + } else if (is_mouse_down_) { + qreal distance = QLineF(mouse_down_pos_, event->localPos()).length(); + qint64 msecsDiff = QDateTime::currentMSecsSinceEpoch() - mouse_down_time_; + + // Only fire the event if the mouse has moved less than the maximum distance + // and was held for shorter than the maximum time.. This prevents click + // events from being fired if the user is dragging the mouse across the map + // or just holding the cursor in place. + if (msecsDiff < max_ms_ && distance <= max_distance_) + { + QPointF point = event->localPos(); + + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + RCLCPP_INFO( + node_->get_logger(), + "mouse point at %f, %f -> %f, %f", + point.x(), + point.y(), + transformed.x(), + transformed.y()); + + stu::Transform transform; + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + + if (tf_manager_->GetTransform(frame, target_frame_, transform)) + { + position = transform * position; + vertices_.push_back(position); + transformed_vertices_.resize(vertices_.size()); + RCLCPP_INFO( + node_->get_logger(), + "Adding vertex at %lf, %lf %s", + position.x(), + position.y(), + frame.c_str()); + } + } + } + is_mouse_down_ = false; + + return false; + } + + bool DrawPolygonPlugin::handleMouseMove(QMouseEvent* event) + { + if (selected_point_ >= 0 && static_cast(selected_point_) < vertices_.size()) + { + QPointF point = event->localPos(); + stu::Transform transform; + std::string frame = ui_.frame->text().toStdString(); + if (tf_manager_->GetTransform(frame, target_frame_, transform)) + { + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + position = transform * position; + vertices_[selected_point_].setY(position.y()); + vertices_[selected_point_].setX(position.x()); + } + + return true; + } + return false; + } + + void DrawPolygonPlugin::Draw(double x, double y, double scale) + { + stu::Transform transform; + std::string frame = ui_.frame->text().toStdString(); + if (!tf_manager_->GetTransform(target_frame_, frame, transform)) + { + return; + } + + // Transform polygon + for (size_t i = 0; i < vertices_.size(); i++) + { + transformed_vertices_[i] = transform * vertices_[i]; + } + + glLineWidth(1); + const QColor color = ui_.color->color(); + glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0); + glBegin(GL_LINE_STRIP); + + for (const auto& vertex : transformed_vertices_) + { + glVertex2d(vertex.x(), vertex.y()); + } + + glEnd(); + + glBegin(GL_LINES); + + glColor4d(color.redF(), color.greenF(), color.blueF(), 0.25); + + if (transformed_vertices_.size() > 2) + { + glVertex2d(transformed_vertices_.front().x(), transformed_vertices_.front().y()); + glVertex2d(transformed_vertices_.back().x(), transformed_vertices_.back().y()); + } + + glEnd(); + + // Draw vertices + glPointSize(9); + glBegin(GL_POINTS); + + for (const auto& vertex : transformed_vertices_) + { + glVertex2d(vertex.x(), vertex.y()); + } + glEnd(); + + + + PrintInfo("OK"); + } + + void DrawPolygonPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["frame"]) + { + source_frame_ = node["frame"].as(); + ui_.frame->setText(source_frame_.c_str()); + } + + if (node["polygon_topic"]) + { + std::string polygon_topic = node["polygon_topic"].as(); + ui_.topic->setText(polygon_topic.c_str()); + } + if (node["color"]) + { + std::string color = node["color"].as(); + ui_.color->setColor(QColor(color.c_str())); + } + } + + void DrawPolygonPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + std::string frame = ui_.frame->text().toStdString(); + emitter << YAML::Key << "frame" << YAML::Value << frame; + + std::string polygon_topic = ui_.topic->text().toStdString(); + emitter << YAML::Key << "polygon_topic" << YAML::Value << polygon_topic; + + std::string color = ui_.color->color().name().toStdString(); + emitter << YAML::Key << "color" << YAML::Value << color; + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/float_plugin.cpp b/mapviz_plugins/src/float_plugin.cpp new file mode 100644 index 000000000..293520b05 --- /dev/null +++ b/mapviz_plugins/src/float_plugin.cpp @@ -0,0 +1,501 @@ +// ***************************************************************************** +// +// Copyright (c) 2019, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#include + +#include +#include + +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::FloatPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + const char* FloatPlugin::COLOR_KEY = "color"; + const char* FloatPlugin::FONT_KEY = "font"; + const char* FloatPlugin::TOPIC_KEY = "topic"; + const char* FloatPlugin::ANCHOR_KEY = "anchor"; + const char* FloatPlugin::UNITS_KEY = "units"; + const char* FloatPlugin::OFFSET_X_KEY = "offset_x"; + const char* FloatPlugin::OFFSET_Y_KEY = "offset_y"; + const char* FloatPlugin::POSTFIX_KEY = "postfix_text"; + + FloatPlugin::FloatPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , anchor_(TOP_LEFT) + , units_(PIXELS) + , offset_x_(0) + , offset_y_(0) + , has_message_(false) + , has_painted_(false) + , color_(Qt::black) + { + ui_.setupUi(config_widget_); + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited())); + QObject::connect(ui_.anchor, SIGNAL(activated(QString)), this, SLOT(SetAnchor(QString))); + QObject::connect(ui_.units, SIGNAL(activated(QString)), this, SLOT(SetUnits(QString))); + QObject::connect(ui_.offsetx, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetX(int))); + QObject::connect(ui_.offsety, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetY(int))); + QObject::connect(ui_.font_button, SIGNAL(clicked()), this, SLOT(SelectFont())); + QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor &)), this, SLOT(SelectColor())); + QObject::connect(ui_.postfix, SIGNAL(editingFinished()), this, SLOT(PostfixEdited())); + + font_.setFamily(tr("Helvetica")); + ui_.font_button->setFont(font_); + ui_.font_button->setText(font_.family()); + + ui_.color->setColor(color_); + } + + bool FloatPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + return true; + } + + void FloatPlugin::Draw(double, double, double) + { + // This plugin doesn't do any OpenGL drawing. + } + + void FloatPlugin::Paint(QPainter* painter, double, double, double) + { + if (has_message_) + { + painter->save(); + painter->resetTransform(); + painter->setFont(font_); + + if (!has_painted_) + { + // After the first time we get a new message, we do not know how wide it's + // going to be when rendered, so we can't accurately calculate the top left + // coordinate if it's offset from the right or bottom borders. + // The easiest workaround I've found for this is to draw it once using + // a completely transparent pen, which will cause the QStaticText class to + // know how wide it is; then we can recalculate the offsets and draw it + // again with a visible pen. + QPen invisPen(QBrush(Qt::transparent), 1); + painter->setPen(invisPen); + PaintText(painter); + has_painted_ = true; + } + QPen pen(QBrush(color_), 1); + painter->setPen(pen); + PaintText(painter); + + painter->restore(); + PrintInfo("OK"); + } + else + { + PrintWarning("No messages received."); + } + } + + void FloatPlugin::PaintText(QPainter* painter) + { + // Calculate the correct offsets and dimensions + int x_offset = offset_x_; + int y_offset = offset_y_; + if (units_ == PERCENT) + { + x_offset = static_cast((float)(offset_x_ * canvas_->width()) / 100.0); + y_offset = static_cast((float)(offset_y_ * canvas_->height()) / 100.0); + } + + int right = static_cast((float)canvas_->width() - message_.size().width()) - x_offset; + int bottom = static_cast((float)canvas_->height() - message_.size().height()) - y_offset; + int yCenter = static_cast((float)canvas_->height() / 2.0 - message_.size().height()/2.0); + int xCenter = static_cast((float)canvas_->width() / 2.0 - message_.size().width()/2.0); + + QPoint ulPoint; + + switch (anchor_) + { + case TOP_LEFT: + ulPoint.setX(x_offset); + ulPoint.setY(y_offset); + break; + case TOP_CENTER: + ulPoint.setX(xCenter); + ulPoint.setY(y_offset); + break; + case TOP_RIGHT: + ulPoint.setX(right); + ulPoint.setY(y_offset); + break; + case CENTER_LEFT: + ulPoint.setX(x_offset); + ulPoint.setY(yCenter); + break; + case CENTER: + ulPoint.setX(xCenter); + ulPoint.setY(yCenter); + break; + case CENTER_RIGHT: + ulPoint.setX(right); + ulPoint.setY(yCenter); + break; + case BOTTOM_LEFT: + ulPoint.setX(x_offset); + ulPoint.setY(bottom); + break; + case BOTTOM_CENTER: + ulPoint.setX(xCenter); + ulPoint.setY(bottom); + break; + case BOTTOM_RIGHT: + ulPoint.setX(right); + ulPoint.setY(bottom); + break; + } + painter->drawStaticText(ulPoint, message_); + } + + void FloatPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node[TOPIC_KEY]) + { + ui_.topic->setText(QString(node[TOPIC_KEY].as().c_str())); + TopicEdited(); + } + + if (node[FONT_KEY]) + { + font_.fromString(QString(node[FONT_KEY].as().c_str())); + ui_.font_button->setFont(font_); + ui_.font_button->setText(font_.family()); + } + + if (node[COLOR_KEY]) + { + color_ = QColor(node[COLOR_KEY].as().c_str()); + ui_.color->setColor(QColor(color_.name().toStdString().c_str())); + } + + if (node[ANCHOR_KEY]) + { + std::string anchor = node[ANCHOR_KEY].as(); + ui_.anchor->setCurrentIndex(ui_.anchor->findText(anchor.c_str())); + SetAnchor(anchor.c_str()); + } + + if (node[UNITS_KEY]) + { + std::string units = node[UNITS_KEY].as(); + ui_.units->setCurrentIndex(ui_.units->findText(units.c_str())); + SetUnits(units.c_str()); + } + + if (node[OFFSET_X_KEY]) + { + offset_x_ = node[OFFSET_X_KEY].as(); + ui_.offsetx->setValue(offset_x_); + } + + if (node[OFFSET_Y_KEY]) + { + offset_y_ = node[OFFSET_Y_KEY].as(); + ui_.offsety->setValue(offset_y_); + } + + if (node[POSTFIX_KEY]) + { + postfix_ = node[POSTFIX_KEY].as(); + ui_.postfix->setText(QString(postfix_.c_str())); + } + } + + void FloatPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key << FONT_KEY << YAML::Value << font_.toString().toStdString(); + emitter << YAML::Key << COLOR_KEY << YAML::Value << color_.name().toStdString(); + emitter << YAML::Key << TOPIC_KEY << YAML::Value << ui_.topic->text().toStdString(); + emitter << YAML::Key << ANCHOR_KEY << YAML::Value << AnchorToString(anchor_); + emitter << YAML::Key << UNITS_KEY << YAML::Value << UnitsToString(units_); + emitter << YAML::Key << OFFSET_X_KEY << YAML::Value << offset_x_; + emitter << YAML::Key << OFFSET_Y_KEY << YAML::Value << offset_y_; + emitter << YAML::Key << POSTFIX_KEY << YAML::Value << postfix_; + } + + QWidget* FloatPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + return config_widget_; + } + + void FloatPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void FloatPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void FloatPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + void FloatPlugin::SelectColor() + { + color_ = ui_.color->color(); + } + + void FloatPlugin::PostfixEdited() + { + postfix_ = ui_.postfix->text().toStdString(); + } + + void FloatPlugin::SelectFont() + { + bool ok; + QFont font = QFontDialog::getFont(&ok, font_, canvas_); + if (ok) + { + font_ = font; + message_.prepare(QTransform(), font_); + ui_.font_button->setFont(font_); + ui_.font_button->setText(font_.family()); + } + } + + void FloatPlugin::SelectTopic() + { + std::vector topics; + topics.emplace_back("std_msgs/msg/Float32"); + topics.emplace_back("std_msgs/msg/Float64"); + topics.emplace_back("marti_common_msgs/msg/Float32Stamped"); + topics.emplace_back("marti_common_msgs/msg/Float64Stamped"); + topics.emplace_back("marti_sensor_msgs/msg/Velocity"); + std::string topic = mapviz::SelectTopicDialog::selectTopic(node_, topics); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void FloatPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + has_message_ = false; + PrintWarning("No messages received."); + + float32_sub_.reset(); + float64_sub_.reset(); + float32_stamped_sub_.reset(); + float64_stamped_sub_.reset(); + velocity_sub_.reset(); + + topic_ = topic; + if (!topic.empty()) + { + float32_sub_ = node_->create_subscription(topic_, 1, + [this](const std_msgs::msg::Float32::ConstSharedPtr msg) { + floatCallback(msg->data); + }); + float64_sub_ = node_->create_subscription(topic_, 1, + [this](const std_msgs::msg::Float64::ConstSharedPtr msg) { + floatCallback(msg->data); + }); + float32_stamped_sub_ = node_->create_subscription(topic_, 1, + [this](const marti_common_msgs::msg::Float32Stamped::ConstSharedPtr msg) { + floatCallback(msg->value); + }); + float64_stamped_sub_ = node_->create_subscription(topic_, 1, + [this](const marti_common_msgs::msg::Float64Stamped::ConstSharedPtr msg) { + floatCallback(msg->value); + }); + velocity_sub_ = node_->create_subscription(topic_, 1, + [this](const marti_sensor_msgs::msg::Velocity::ConstSharedPtr msg) { + floatCallback(msg->velocity); + }); + } + } + } + + void FloatPlugin::SetAnchor(QString anchor) + { + if (anchor == "top left") + { + anchor_ = TOP_LEFT; + } + else if (anchor == "top center") + { + anchor_ = TOP_CENTER; + } + else if (anchor == "top right") + { + anchor_ = TOP_RIGHT; + } + else if (anchor == "center left") + { + anchor_ = CENTER_LEFT; + } + else if (anchor == "center") + { + anchor_ = CENTER; + } + else if (anchor == "center right") + { + anchor_ = CENTER_RIGHT; + } + else if (anchor == "bottom left") + { + anchor_ = BOTTOM_LEFT; + } + else if (anchor == "bottom center") + { + anchor_ = BOTTOM_CENTER; + } + else if (anchor == "bottom right") + { + anchor_ = BOTTOM_RIGHT; + } + } + + void FloatPlugin::SetUnits(QString units) + { + if (units == "pixels") + { + units_ = PIXELS; + } + else if (units == "percent") + { + units_ = PERCENT; + } + } + + void FloatPlugin::SetOffsetX(int offset) + { + offset_x_ = offset; + } + + void FloatPlugin::SetOffsetY(int offset) + { + offset_y_ = offset; + } + + void FloatPlugin::floatCallback(double value) + { + + std::string str = std::to_string(value); + str += postfix_; + message_.setText(QString(str.c_str())); + + message_.prepare(QTransform(), font_); + + has_message_ = true; + has_painted_ = false; + initialized_ = true; + } + + std::string FloatPlugin::AnchorToString(FloatPlugin::Anchor anchor) + { + std::string anchor_string = "top left"; + + if (anchor == TOP_LEFT) + { + anchor_string = "top left"; + } + else if (anchor == TOP_CENTER) + { + anchor_string = "top center"; + } + else if (anchor == TOP_RIGHT) + { + anchor_string = "top right"; + } + else if (anchor == CENTER_LEFT) + { + anchor_string = "center left"; + } + else if (anchor == CENTER) + { + anchor_string = "center"; + } + else if (anchor == CENTER_RIGHT) + { + anchor_string = "center right"; + } + else if (anchor == BOTTOM_LEFT) + { + anchor_string = "bottom left"; + } + else if (anchor == BOTTOM_CENTER) + { + anchor_string = "bottom center"; + } + else if (anchor == BOTTOM_RIGHT) + { + anchor_string = "bottom right"; + } + + return anchor_string; + } + + std::string FloatPlugin::UnitsToString(FloatPlugin::Units units) + { + std::string units_string = "pixels"; + + if (units == PIXELS) + { + units_string = "pixels"; + } + else if (units == PERCENT) + { + units_string = "percent"; + } + + return units_string; + } +} diff --git a/mapviz_plugins/src/gps_plugin.cpp b/mapviz_plugins/src/gps_plugin.cpp new file mode 100644 index 000000000..6679af67c --- /dev/null +++ b/mapviz_plugins/src/gps_plugin.cpp @@ -0,0 +1,292 @@ +// ***************************************************************************** +// +// Copyright (C) 2013 All Right Reserved, Southwest Research Institute® (SwRI®) +// +// Contract No. 10-58058A +// Contractor Southwest Research Institute® (SwRI®) +// Address 6220 Culebra Road, San Antonio, Texas 78228-0510 +// Contact Steve Dellenback (210) 522-3914 +// +// This code was developed as part of an internal research project fully funded +// by Southwest Research Institute®. +// +// THIS CODE AND INFORMATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY +// KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A +// PARTICULAR PURPOSE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include +#include + +#include + +// ROS libraries +#include + +#include +#include +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::GpsPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + GpsPlugin::GpsPlugin() + : PointDrawingPlugin() + , ui_() + , config_widget_(new QWidget()) + , has_message_(false) + { + ui_.setupUi(config_widget_); + + ui_.color->setColor(Qt::green); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, + SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, + SLOT(TopicEdited())); + QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this, + SLOT(PositionToleranceChanged(double))); + QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this, + SLOT(BufferSizeChanged(int))); + QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this, + SLOT(SetDrawStyle(QString))); + QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)), + this, SLOT(SetStaticArrowSizes(bool))); + QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)), + this, SLOT(SetArrowSize(int))); + QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this, + SLOT(SetColor(const QColor&))); + QObject::connect(ui_.show_laps, SIGNAL(toggled(bool)), this, + SLOT(LapToggled(bool))); + QObject::connect(ui_.buttonResetBuffer, SIGNAL(pressed()), this, + SLOT(ClearPoints())); + } + + void GpsPlugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic(node_, "gps_msgs/msg/GPSFix"); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void GpsPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + ClearPoints(); + has_message_ = false; + PrintWarning("No messages received."); + + gps_sub_.reset(); + + topic_ = topic; + if (!topic.empty()) + { + gps_sub_ = node_->create_subscription(topic_, rclcpp::QoS(1), + std::bind(&GpsPlugin::GPSFixCallback, this, std::placeholders::_1)); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void GpsPlugin::GPSFixCallback(const gps_msgs::msg::GPSFix::SharedPtr gps) + { + if (!tf_manager_->LocalXyUtil()->Initialized()) + { + return; + } + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + StampedPoint stamped_point; + stamped_point.stamp = gps->header.stamp; + stamped_point.source_frame = tf_manager_->LocalXyUtil()->Frame(); + double x; + double y; + tf_manager_->LocalXyUtil()->ToLocalXy(gps->latitude, gps->longitude, x, y); + + stamped_point.point = tf2::Vector3(x, y, gps->altitude); + + // The GPS "track" is in degrees, but createQuaternionFromYaw expects + // radians. + // Furthermore, the track rotates in the opposite direction and is also + // offset by 90 degrees, so all of that has to be compensated for. + auto temp_quat = tf2::Quaternion(); + temp_quat.setRPY(0, 0, (-gps->track * (M_PI / 180.0)) + M_PI_2); + stamped_point.orientation = temp_quat; + + pushPoint( std::move(stamped_point) ); + } + + void GpsPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void GpsPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void GpsPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* GpsPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool GpsPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + SetColor(ui_.color->color()); + + return true; + } + + void GpsPlugin::Draw(double x, double y, double scale) + { + if (DrawPoints(scale)) + { + PrintInfo("OK"); + } + } + + void GpsPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(topic.c_str()); + } + + if (node["color"]) + { + std::string color = node["color"].as(); + QColor qcolor(color.c_str()); + SetColor(qcolor); + ui_.color->setColor(qcolor); + } + + if (node["draw_style"]) + { + std::string draw_style = node["draw_style"].as(); + + if (draw_style == "lines") + { + ui_.drawstyle->setCurrentIndex(0); + SetDrawStyle( LINES ); + } else if (draw_style == "points") { + ui_.drawstyle->setCurrentIndex(1); + SetDrawStyle( POINTS ); + } else if (draw_style == "arrows") { + ui_.drawstyle->setCurrentIndex(2); + SetDrawStyle( ARROWS ); + } + } + + if (node["position_tolerance"]) + { + double position_tolerance = node["position_tolerance"].as(); + ui_.positiontolerance->setValue(position_tolerance); + PositionToleranceChanged(position_tolerance); + } + + if (node["buffer_size"]) + { + double buffer_size = node["buffer_size"].as(); + ui_.buffersize->setValue(buffer_size); + BufferSizeChanged(buffer_size); + } + + if (node["show_laps"]) + { + bool show_laps = node["show_laps"].as(); + ui_.show_laps->setChecked(show_laps); + LapToggled(show_laps); + } + + if (node["static_arrow_sizes"]) + { + bool static_arrow_sizes = node["static_arrow_sizes"].as(); + ui_.static_arrow_sizes->setChecked(static_arrow_sizes); + SetStaticArrowSizes(static_arrow_sizes); + } + + if (node["arrow_size"]) + { + int arrow_size = node["arrow_size"].as(); + ui_.arrow_size->setValue(arrow_size); + SetArrowSize(arrow_size); + } + + TopicEdited(); + } + + void GpsPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + std::string topic = ui_.topic->text().toStdString(); + emitter << YAML::Key << "topic" << YAML::Value << topic; + + emitter << YAML::Key << "color" << YAML::Value + << ui_.color->color().name().toStdString(); + + std::string draw_style = ui_.drawstyle->currentText().toStdString(); + emitter << YAML::Key << "draw_style" << YAML::Value << draw_style; + + emitter << YAML::Key << "position_tolerance" << + YAML::Value << positionTolerance(); + + emitter << YAML::Key << "buffer_size" << YAML::Value << bufferSize(); + + bool show_laps = ui_.show_laps->isChecked(); + emitter << YAML::Key << "show_laps" << YAML::Value << show_laps; + + emitter << YAML::Key + << "static_arrow_sizes" + << YAML::Value + << ui_.static_arrow_sizes->isChecked(); + + emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value(); + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/grid_plugin.cpp b/mapviz_plugins/src/grid_plugin.cpp new file mode 100644 index 000000000..5692e3f69 --- /dev/null +++ b/mapviz_plugins/src/grid_plugin.cpp @@ -0,0 +1,376 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +#include + +// QT libraries +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::GridPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + GridPlugin::GridPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , alpha_(1.0) + , top_left_(0, 0, 0) + , size_(1) + , rows_(1) + , columns_(1) + , transformed_(false) + { + ui_.setupUi(config_widget_); + + ui_.color->setColor(Qt::red); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.select_frame, SIGNAL(clicked()), this, SLOT(SelectFrame())); + QObject::connect(ui_.frame, SIGNAL(textEdited(const QString&)), this, SLOT(FrameEdited())); + QObject::connect(ui_.alpha, SIGNAL(valueChanged(double)), this, SLOT(SetAlpha(double))); + QObject::connect(ui_.x, SIGNAL(valueChanged(double)), this, SLOT(SetX(double))); + QObject::connect(ui_.y, SIGNAL(valueChanged(double)), this, SLOT(SetY(double))); + QObject::connect(ui_.size, SIGNAL(valueChanged(double)), this, SLOT(SetSize(double))); + QObject::connect(ui_.rows, SIGNAL(valueChanged(int)), this, SLOT(SetRows(int))); + QObject::connect(ui_.columns, SIGNAL(valueChanged(int)), this, SLOT(SetColumns(int))); + connect(ui_.color, SIGNAL(colorEdited(const QColor &)), this, SLOT(DrawIcon())); + } + + void GridPlugin::DrawIcon() + { + if (icon_) + { + QPixmap icon(16, 16); + icon.fill(Qt::transparent); + + QPainter painter(&icon); + painter.setRenderHint(QPainter::Antialiasing, true); + + QPen pen(QColor(ui_.color->color())); + + pen.setWidth(2); + pen.setCapStyle(Qt::SquareCap); + painter.setPen(pen); + + painter.drawLine(2, 2, 14, 2); + painter.drawLine(2, 2, 2, 14); + painter.drawLine(14, 2, 14, 14); + painter.drawLine(2, 14, 14, 14); + painter.drawLine(8, 2, 8, 14); + painter.drawLine(2, 8, 14, 8); + + icon_->SetPixmap(icon); + } + } + + void GridPlugin::SetAlpha(double alpha) + { + alpha_ = alpha; + } + + void GridPlugin::SetX(double x) + { + top_left_.setX(x); + + RecalculateGrid(); + } + + void GridPlugin::SetY(double y) + { + top_left_.setY(y); + + RecalculateGrid(); + } + + void GridPlugin::SetSize(double size) + { + size_ = size; + + RecalculateGrid(); + } + + void GridPlugin::SetRows(int rows) + { + rows_ = rows; + + RecalculateGrid(); + } + + void GridPlugin::SetColumns(int columns) + { + columns_ = columns; + + RecalculateGrid(); + } + + void GridPlugin::SelectFrame() + { + std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_buf_); + if (!frame.empty()) + { + ui_.frame->setText(QString::fromStdString(frame)); + FrameEdited(); + } + } + + void GridPlugin::FrameEdited() + { + source_frame_ = ui_.frame->text().toStdString(); + + initialized_ = true; + + RecalculateGrid(); + } + + void GridPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void GridPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void GridPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* GridPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool GridPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + DrawIcon(); + + return true; + } + + void GridPlugin::Draw(double x, double y, double scale) + { + if (transformed_) { + QColor color = ui_.color->color(); + + glLineWidth(3); + glColor4d(color.redF(), color.greenF(), color.blueF(), alpha_); + glBegin(GL_LINES); + + auto transformed_left_it = transformed_left_points_.begin(); + auto transformed_right_it = transformed_right_points_.begin(); + for (; transformed_left_it != transformed_left_points_.end(); ++transformed_left_it) { + glVertex2d(transformed_left_it->getX(), transformed_left_it->getY()); + glVertex2d(transformed_right_it->getX(), transformed_right_it->getY()); + + ++transformed_right_it; + } + + auto transformed_top_it = transformed_top_points_.begin(); + auto transformed_bottom_it = transformed_bottom_points_.begin(); + for (; transformed_top_it != transformed_top_points_.end(); ++transformed_top_it) { + glVertex2d(transformed_top_it->getX(), transformed_top_it->getY()); + glVertex2d(transformed_bottom_it->getX(), transformed_bottom_it->getY()); + + ++transformed_bottom_it; + } + + glEnd(); + + PrintInfo("OK"); + } + } + + void GridPlugin::RecalculateGrid() + { + transformed_ = false; + + left_points_.clear(); + right_points_.clear(); + top_points_.clear(); + bottom_points_.clear(); + + transformed_left_points_.clear(); + transformed_right_points_.clear(); + transformed_top_points_.clear(); + transformed_bottom_points_.clear(); + + // Set top and bottom + for (int c = 0; c <= columns_; c++) + { + tf2::Vector3 top_point(top_left_.getX() + c * size_, top_left_.getY(), 0); + top_points_.push_back(top_point); + transformed_top_points_.push_back(transform_ * top_point); + + tf2::Vector3 bottom_point(top_left_.getX() + c * size_, top_left_.getY() + size_ * rows_, 0); + bottom_points_.push_back(bottom_point); + transformed_bottom_points_.push_back(transform_ * bottom_point); + } + + // Set left and right + for (int r = 0; r <= rows_; r++) + { + tf2::Vector3 left_point(top_left_.getX(), top_left_.getY() + r * size_, 0); + left_points_.push_back(left_point); + transformed_left_points_.push_back(transform_ * left_point); + + tf2::Vector3 right_point( + top_left_.getX() + size_ * columns_, + top_left_.getY() + r * size_, + 0); + right_points_.push_back(right_point); + transformed_right_points_.push_back(transform_ * right_point); + } + } + + void GridPlugin::Transform() + { + transformed_ = false; + + if (GetTransform(rclcpp::Time(), transform_)) + { + Transform(left_points_, transformed_left_points_); + Transform(right_points_, transformed_right_points_); + Transform(top_points_, transformed_top_points_); + Transform(bottom_points_, transformed_bottom_points_); + + transformed_ = true; + } + } + + void GridPlugin::Transform(std::list& src, std::list& dst) + { + auto points_it = src.begin(); + auto transformed_it = dst.begin(); + for (; points_it != src.end() && transformed_it != dst.end(); ++points_it) + { + (*transformed_it) = transform_ * (*points_it); + + ++transformed_it; + } + } + + void GridPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["color"]) + { + std::string color = node["color"].as(); + ui_.color->setColor(QColor(color.c_str())); + } + + if (node["frame"]) + { + std::string frame = node["frame"].as(); + ui_.frame->setText(QString::fromStdString(frame)); + } + + if (node["x"]) + { + float x = node["x"].as(); + ui_.x->setValue(x); + } + + if (node["y"]) + { + float y = node["y"].as(); + ui_.y->setValue(y); + } + + if (node["alpha"]) + { + alpha_ = node["alpha"].as(); + ui_.alpha->setValue(alpha_); + } + + if (node["size"]) + { + size_ = node["size"].as(); + ui_.size->setValue(size_); + } + + if (node["rows"]) + { + rows_ = node["rows"].as(); + ui_.rows->setValue(rows_); + } + + if (node["columns"]) + { + columns_ = node["columns"].as(); + ui_.columns->setValue(columns_); + } + + FrameEdited(); + } + + void GridPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key << "color" << YAML::Value << ui_.color->color().name().toStdString(); + + emitter << YAML::Key << "alpha" << YAML::Value << alpha_; + + std::string frame = ui_.frame->text().toStdString(); + emitter << YAML::Key << "frame" << YAML::Value << frame; + + emitter << YAML::Key << "x" << YAML::Value << top_left_.getX(); + emitter << YAML::Key << "y" << YAML::Value << top_left_.getY(); + emitter << YAML::Key << "size" << YAML::Value << size_; + emitter << YAML::Key << "rows" << YAML::Value << rows_; + emitter << YAML::Key << "columns" << YAML::Value << columns_; + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/image_plugin.cpp b/mapviz_plugins/src/image_plugin.cpp new file mode 100644 index 000000000..7b401f50d --- /dev/null +++ b/mapviz_plugins/src/image_plugin.cpp @@ -0,0 +1,611 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include + +// ROS libraries +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::ImagePlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + ImagePlugin::ImagePlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , anchor_(TOP_LEFT) + , units_(PIXELS) + , offset_x_(0) + , offset_y_(0) + , width_(320) + , height_(240) + , transport_("default") + , force_resubscribe_(false) + , has_image_(false) + , last_width_(0) + , last_height_(0) + , original_aspect_ratio_(1.0) + , has_message_(false) + { + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited())); + QObject::connect(ui_.anchor, SIGNAL(activated(QString)), this, SLOT(SetAnchor(QString))); + QObject::connect(ui_.units, SIGNAL(activated(QString)), this, SLOT(SetUnits(QString))); + QObject::connect(ui_.offsetx, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetX(int))); + QObject::connect(ui_.offsety, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetY(int))); + QObject::connect(ui_.width, SIGNAL(valueChanged(double)), this, SLOT(SetWidth(double))); + QObject::connect(ui_.height, SIGNAL(valueChanged(double)), this, SLOT(SetHeight(double))); + QObject::connect(this, SIGNAL(VisibleChanged(bool)), this, SLOT(SetSubscription(bool))); + QObject::connect(ui_.keep_ratio, SIGNAL(toggled(bool)), this, SLOT(KeepRatioChanged(bool))); + QObject::connect(ui_.transport_combo_box, SIGNAL(activated(const QString&)), + this, SLOT(SetTransport(const QString&))); + + ui_.width->setKeyboardTracking(false); + ui_.height->setKeyboardTracking(false); + } + + void ImagePlugin::SetOffsetX(int offset) + { + offset_x_ = offset; + } + + void ImagePlugin::SetOffsetY(int offset) + { + offset_y_ = offset; + } + + void ImagePlugin::SetWidth(double width) + { + width_ = width; + } + + void ImagePlugin::SetHeight(double height) + { + height_ = height; + } + + void ImagePlugin::SetAnchor(QString anchor) + { + if (anchor == "top left") + { + anchor_ = TOP_LEFT; + } else if (anchor == "top center") { + anchor_ = TOP_CENTER; + } else if (anchor == "top right") { + anchor_ = TOP_RIGHT; + } else if (anchor == "center left") { + anchor_ = CENTER_LEFT; + } else if (anchor == "center") { + anchor_ = CENTER; + } else if (anchor == "center right") { + anchor_ = CENTER_RIGHT; + } else if (anchor == "bottom left") { + anchor_ = BOTTOM_LEFT; + } else if (anchor == "bottom center") { + anchor_ = BOTTOM_CENTER; + } else if (anchor == "bottom right") { + anchor_ = BOTTOM_RIGHT; + } + } + + void ImagePlugin::SetUnits(QString units) + { + // do this in both cases to avoid image clamping + ui_.width->setMaximum(10000); + ui_.height->setMaximum(10000); + + if (units == "pixels") + { + ui_.width->setDecimals(0); + ui_.height->setDecimals(0); + units_ = PIXELS; + width_ = width_ * static_cast(canvas_->width()) / 100.0; + height_ = height_ * static_cast(canvas_->height()) / 100.0; + ui_.width->setSuffix(" px"); + ui_.height->setSuffix(" px"); + } else if (units == "percent") { + ui_.width->setDecimals(1); + ui_.height->setDecimals(1); + units_ = PERCENT; + width_ = width_ * 100.0 / static_cast(canvas_->width()); + height_ = height_ * 100.0 / static_cast(canvas_->height()); + ui_.width->setSuffix(" %"); + ui_.height->setSuffix(" %"); + } + ui_.width->setValue( width_ ); + ui_.height->setValue( height_ ); + + if( units_ == PERCENT) + { + ui_.width->setMaximum(100); + ui_.height->setMaximum(100); + } + } + void ImagePlugin::SetSubscription(bool visible) + { + if(topic_.empty()) + { + return; + } else if (!visible) { + image_sub_.shutdown(); + RCLCPP_INFO(node_->get_logger(), "Dropped subscription to %s", topic_.c_str()); + } else { + Resubscribe(); + } + } + + void ImagePlugin::SetTransport(const QString& transport) + { + transport_ = transport.toStdString(); + RCLCPP_INFO(node_->get_logger(), "Changing image_transport to %s.", transport_.c_str()); + TopicEdited(); + } + + void ImagePlugin::KeepRatioChanged(bool checked) + { + ui_.height->setEnabled( !checked ); + if( checked ) + { + ui_.height->setValue( width_ * original_aspect_ratio_ ); + } + } + + void ImagePlugin::Resubscribe() + { + if (transport_ == "default") + { + force_resubscribe_ = true; + TopicEdited(); + } + } + + void ImagePlugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic( + node_, "sensor_msgs/msg/Image"); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void ImagePlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (!this->Visible()) + { + PrintWarning("Topic is Hidden"); + initialized_ = false; + has_message_ = false; + // Force it to resubscribe next time it's made visible + force_resubscribe_ = true; + if (!topic.empty()) + { + topic_ = topic; + } + image_sub_.shutdown(); + return; + } + // Re-subscribe if either the topic or the image transport + // have changed. + if (force_resubscribe_ || + topic != topic_ || + image_sub_.getTransport() != transport_) + { + force_resubscribe_ = false; + initialized_ = false; + has_message_ = false; + topic_ = topic; + PrintWarning("No messages received."); + + image_sub_.shutdown(); + + if (!topic_.empty()) + { + if (transport_ == "default") + { + RCLCPP_DEBUG(node_->get_logger(), "Using default transport."); + image_transport::ImageTransport it(node_); + image_sub_ = it.subscribe(topic_, 1, + std::bind(&ImagePlugin::imageCallback, this, std::placeholders::_1)); + } else { + RCLCPP_DEBUG(node_->get_logger(), "Setting transport to %s on %s.", + transport_.c_str(), node_->get_fully_qualified_name()); + + image_transport::ImageTransport it(node_); + image_sub_ = image_transport::create_subscription(node_.get(), + topic_, + std::bind(&ImagePlugin::imageCallback, this, std::placeholders::_1), + transport_, + rclcpp::QoS(1).get_rmw_qos_profile()); + } + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void ImagePlugin::imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr& image) + { + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + try + { + cv_image_ = cv_bridge::toCvCopy(image, sensor_msgs::image_encodings::BGR8); + } + catch (const cv_bridge::Exception& e) + { + PrintError(e.what()); + return; + } + + last_width_ = 0; + last_height_ = 0; + original_aspect_ratio_ = static_cast(image->height) / static_cast(image->width); + + if( ui_.keep_ratio->isChecked() ) + { + double height = width_ * original_aspect_ratio_; + if (units_ == PERCENT) + { + height *= static_cast(canvas_->width()) / static_cast(canvas_->height()); + } + ui_.height->setValue(height); + } + + has_image_ = true; + } + + void ImagePlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void ImagePlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void ImagePlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* ImagePlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool ImagePlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + return true; + } + + void ImagePlugin::ScaleImage(double width, double height) + { + if (!has_image_) + { + return; + } + + cv::resize(cv_image_->image, scaled_image_, cvSize2D32f(width, height), 0, 0, CV_INTER_AREA); + } + + void ImagePlugin::DrawIplImage(cv::Mat *image) + { + // TODO(malban) glTexture2D may be more efficient than glDrawPixels + + if (image == nullptr || image->cols == 0 || image->rows == 0) + { + return; + } + + GLenum format; + switch (image->channels()) + { + case 1: + format = GL_LUMINANCE; + break; + case 2: + format = GL_LUMINANCE_ALPHA; + break; + case 3: + format = GL_BGR; + break; + default: + return; + } + + glPixelZoom(1.0f, -1.0f); + glPixelStorei(GL_UNPACK_ALIGNMENT, 1); + glDrawPixels(image->cols, image->rows, format, GL_UNSIGNED_BYTE, image->ptr()); + glPixelStorei(GL_UNPACK_ALIGNMENT, 4); + + + PrintInfo("OK"); + } + + void ImagePlugin::Draw(double x, double y, double scale) + { + // Calculate the correct offsets and dimensions + double x_offset = offset_x_; + double y_offset = offset_y_; + double width = width_; + double height = height_; + + if (units_ == PERCENT) + { + x_offset = offset_x_ * canvas_->width() / 100.0; + y_offset = offset_y_ * canvas_->height() / 100.0; + width = width_ * canvas_->width() / 100.0; + height = height_ * canvas_->height() / 100.0; + } + + if( ui_.keep_ratio->isChecked() ) + { + height = original_aspect_ratio_ * width; + } + + // Scale the source image if necessary + if (width != last_width_ || height != last_height_) + { + ScaleImage(width, height); + } + + // Calculate the correct render position + double x_pos = 0; + double y_pos = 0; + if (anchor_ == TOP_LEFT) + { + x_pos = x_offset; + y_pos = y_offset; + } else if (anchor_ == TOP_CENTER) { + x_pos = (canvas_->width() - width) / 2.0 + x_offset; + y_pos = y_offset; + } else if (anchor_ == TOP_RIGHT) { + x_pos = canvas_->width() - width - x_offset; + y_pos = y_offset; + } else if (anchor_ == CENTER_LEFT) { + x_pos = x_offset; + y_pos = (canvas_->height() - height) / 2.0 + y_offset; + } else if (anchor_ == CENTER) { + x_pos = (canvas_->width() - width) / 2.0 + x_offset; + y_pos = (canvas_->height() - height) / 2.0 + y_offset; + } else if (anchor_ == CENTER_RIGHT) { + x_pos = canvas_->width() - width - x_offset; + y_pos = (canvas_->height() - height) / 2.0 + y_offset; + } else if (anchor_ == BOTTOM_LEFT) { + x_pos = x_offset; + y_pos = canvas_->height() - height - y_offset; + } else if (anchor_ == BOTTOM_CENTER) { + x_pos = (canvas_->width() - width) / 2.0 + x_offset; + y_pos = canvas_->height() - height - y_offset; + } else if (anchor_ == BOTTOM_RIGHT) { + x_pos = canvas_->width() - width - x_offset; + y_pos = canvas_->height() - height - y_offset; + } + + glMatrixMode(GL_PROJECTION); + glPushMatrix(); + glLoadIdentity(); + glOrtho(0, canvas_->width(), canvas_->height(), 0, -0.5f, 0.5f); + + glRasterPos2d(x_pos, y_pos); + + DrawIplImage(&scaled_image_); + + glPopMatrix(); + + last_width_ = width; + last_height_ = height; + } + + void ImagePlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + // Note that image_transport should be loaded before the + // topic to make sure the transport is set appropriately before we + // subscribe. + if (node["image_transport"]) + { + transport_ = node["image_transport"].as(); + int index = ui_.transport_combo_box->findText( QString::fromStdString(transport_) ); + if (index != -1) + { + ui_.transport_combo_box->setCurrentIndex(index); + } else { + RCLCPP_WARN(node_->get_logger(), "Saved image transport %s is unavailable.", + transport_.c_str()); + } + } + + if (node["topic"]) + { + std::string topic; + topic = node["topic"].as(); + ui_.topic->setText(topic.c_str()); + TopicEdited(); + } + + if (node["anchor"]) + { + std::string anchor; + anchor = node["anchor"].as(); + ui_.anchor->setCurrentIndex(ui_.anchor->findText(anchor.c_str())); + SetAnchor(anchor.c_str()); + } + + if (node["units"]) + { + std::string units; + units = node["units"].as(); + ui_.units->setCurrentIndex(ui_.units->findText(units.c_str())); + SetUnits(units.c_str()); + } + + if (node["offset_x"]) + { + offset_x_ = node["offset_x"].as(); + ui_.offsetx->setValue(offset_x_); + } + + if (node["offset_y"]) + { + offset_y_ = node["offset_y"].as(); + ui_.offsety->setValue(offset_y_); + } + + if (node["width"]) + { + width_ = node["width"].as(); + ui_.width->setValue(width_); + } + + if (node["height"]) + { + height_ = node["height"].as(); + ui_.height->setValue(height_); + } + + if (node["keep_ratio"]) + { + bool keep; + keep = node["keep_ratio"].as(); + ui_.keep_ratio->setChecked( keep ); + } + } + + void ImagePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString(); + emitter << YAML::Key << "anchor" << YAML::Value << AnchorToString(anchor_); + emitter << YAML::Key << "units" << YAML::Value << UnitsToString(units_); + emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_; + emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_; + emitter << YAML::Key << "width" << YAML::Value << width_; + emitter << YAML::Key << "height" << YAML::Value << height_; + emitter << YAML::Key << "keep_ratio" << YAML::Value << ui_.keep_ratio->isChecked(); + emitter << YAML::Key << "image_transport" << YAML::Value << transport_; + } + + std::string ImagePlugin::AnchorToString(Anchor anchor) + { + std::string anchor_string = "top left"; + + if (anchor == TOP_LEFT) + { + anchor_string = "top left"; + } else if (anchor == TOP_CENTER) { + anchor_string = "top center"; + } else if (anchor == TOP_RIGHT) { + anchor_string = "top right"; + } else if (anchor == CENTER_LEFT) { + anchor_string = "center left"; + } else if (anchor == CENTER) { + anchor_string = "center"; + } else if (anchor == CENTER_RIGHT) { + anchor_string = "center right"; + } else if (anchor == BOTTOM_LEFT) { + anchor_string = "bottom left"; + } else if (anchor == BOTTOM_CENTER) { + anchor_string = "bottom center"; + } else if (anchor == BOTTOM_RIGHT) { + anchor_string = "bottom right"; + } + + return anchor_string; + } + + std::string ImagePlugin::UnitsToString(Units units) + { + std::string units_string = "pixels"; + + if (units == PIXELS) + { + units_string = "pixels"; + } else if (units == PERCENT) { + units_string = "percent"; + } + + return units_string; + } + + void ImagePlugin::SetNode(rclcpp::Node& node) + { + node_ = node.shared_from_this(); + + // As soon as we have a node, we can find the available image transports + // and add them to our combo box. + image_transport::ImageTransport it(node_); + std::vector transports = it.getLoadableTransports(); + for (const std::string& transport : transports) + { + QString qtransport = QString::fromStdString(transport).replace("image_transport/", ""); + ui_.transport_combo_box->addItem(qtransport); + } + } +} // namespace mapviz_plugins + diff --git a/mapviz_plugins/src/laserscan_plugin.cpp b/mapviz_plugins/src/laserscan_plugin.cpp new file mode 100644 index 000000000..ee67e59a6 --- /dev/null +++ b/mapviz_plugins/src/laserscan_plugin.cpp @@ -0,0 +1,687 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// Boost libraries +#include + +// QT libraries +#include +#include + +// ROS libraries +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include + +// QT Autogenerated +#include "ui_topic_select.h" + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::LaserScanPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + LaserScanPlugin::LaserScanPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , topic_("") + , alpha_(1.0) + , min_value_(0.0) + , max_value_(100.0) + , point_size_(3) + , buffer_size_(0) + , has_message_(false) + , prev_ranges_size_(0) + , prev_angle_min_(0.0) + , prev_increment_(0.0) + { + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + // Initialize color selector colors + ui_.min_color->setColor(Qt::white); + ui_.max_color->setColor(Qt::black); + + // Set color transformer choices + ui_.color_transformer->addItem(QString("Flat Color"), QVariant(0)); + ui_.color_transformer->addItem(QString("Intensity"), QVariant(1)); + ui_.color_transformer->addItem(QString("Range"), QVariant(2)); + ui_.color_transformer->addItem(QString("X Axis"), QVariant(3)); + ui_.color_transformer->addItem(QString("Y Axis"), QVariant(4)); + ui_.color_transformer->addItem(QString("Z Axis"), QVariant(5)); + + QObject::connect(ui_.selecttopic, + SIGNAL(clicked()), + this, + SLOT(SelectTopic())); + QObject::connect(ui_.topic, + SIGNAL(editingFinished()), + this, + SLOT(TopicEdited())); + QObject::connect(ui_.alpha, + SIGNAL(valueChanged(double)), + this, + SLOT(AlphaEdited(double))); + QObject::connect(ui_.color_transformer, + SIGNAL(currentIndexChanged(int)), + this, + SLOT(ColorTransformerChanged(int))); + QObject::connect(ui_.max_color, + SIGNAL(colorEdited(const QColor &)), + this, + SLOT(UpdateColors())); + QObject::connect(ui_.min_color, + SIGNAL(colorEdited(const QColor &)), + this, + SLOT(UpdateColors())); + QObject::connect(ui_.minValue, + SIGNAL(valueChanged(double)), + this, + SLOT(MinValueChanged(double))); + QObject::connect(ui_.maxValue, + SIGNAL(valueChanged(double)), + this, + SLOT(MaxValueChanged(double))); + QObject::connect(ui_.bufferSize, + SIGNAL(valueChanged(int)), + this, + SLOT(BufferSizeChanged(int))); + QObject::connect(ui_.pointSize, + SIGNAL(valueChanged(int)), + this, + SLOT(PointSizeChanged(int))); + QObject::connect(ui_.use_rainbow, + SIGNAL(stateChanged(int)), + this, + SLOT(UseRainbowChanged(int))); + + QObject::connect(ui_.max_color, + SIGNAL(colorEdited(const QColor &)), + this, + SLOT(DrawIcon())); + QObject::connect(ui_.min_color, + SIGNAL(colorEdited(const QColor &)), + this, + SLOT(DrawIcon())); + QObject::connect(this, + SIGNAL(TargetFrameChanged(const std::string&)), + this, + SLOT(ResetTransformedScans())); + } + + void LaserScanPlugin::ClearHistory() + { + RCLCPP_DEBUG(node_->get_logger(), "LaserScan::ClearHistory()"); + scans_.clear(); + } + + void LaserScanPlugin::DrawIcon() + { + if (icon_) + { + QPixmap icon(16, 16); + icon.fill(Qt::transparent); + + QPainter painter(&icon); + painter.setRenderHint(QPainter::Antialiasing, true); + + QPen pen; + pen.setWidth(4); + pen.setCapStyle(Qt::RoundCap); + + pen.setColor(ui_.min_color->color()); + painter.setPen(pen); + painter.drawPoint(2, 13); + + pen.setColor(ui_.min_color->color()); + painter.setPen(pen); + painter.drawPoint(4, 6); + + pen.setColor(ui_.max_color->color()); + painter.setPen(pen); + painter.drawPoint(12, 9); + + pen.setColor(ui_.max_color->color()); + painter.setPen(pen); + painter.drawPoint(13, 2); + + icon_->SetPixmap(icon); + } + } + + void LaserScanPlugin::ResetTransformedScans() + { + for (Scan& scan : scans_) + { + scan.transformed = false; + } + } + + QColor LaserScanPlugin::CalculateColor(const StampedPoint& point, + bool has_intensity) + { + double val; + int color_transformer = ui_.color_transformer->currentIndex(); + if (color_transformer == COLOR_RANGE) + { + val = point.range; + } else if (color_transformer == COLOR_INTENSITY && has_intensity) { + val = point.intensity; + } else if (color_transformer == COLOR_X) { + val = point.point.x(); + } else if (color_transformer == COLOR_Y) { + val = point.point.y(); + } else if (color_transformer == COLOR_Z) { + val = point.transformed_point.z(); + } else { + // No intensity or (color_transformer == COLOR_FLAT) + return ui_.min_color->color(); + } + if (max_value_ > min_value_) + val = (val - min_value_) / (max_value_ - min_value_); + val = std::max(0.0, std::min(val, 1.0)); + if (ui_.use_rainbow->isChecked()) + { + // Hue Interpolation + int hue = static_cast(val * 255); + return QColor::fromHsl(hue, 255, 127, 255); + } else { + const QColor min_color = ui_.min_color->color(); + const QColor max_color = ui_.max_color->color(); + // RGB Interpolation + int red, green, blue; + red = static_cast(val * max_color.red() + ((1.0 - val) * min_color.red())); + green = static_cast(val * max_color.green() + ((1.0 - val) * min_color.green())); + blue = static_cast(val * max_color.blue() + ((1.0 - val) * min_color.blue())); + return QColor(red, green, blue, 255); + } + } + + void LaserScanPlugin::UpdateColors() + { + for (auto& scan : scans_) + { + for (auto& point : scan.points) + { + point.color = CalculateColor(point, scan.has_intensity); + } + } + } + + void LaserScanPlugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic( + node_, + "sensor_msgs/msg/LaserScan"); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void LaserScanPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + scans_.clear(); + has_message_ = false; + PrintWarning("No messages received."); + + laserscan_sub_.reset(); + + topic_ = topic; + if (!topic.empty()) + { + laserscan_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(100), + std::bind(&LaserScanPlugin::laserScanCallback, this, std::placeholders::_1) + ); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void LaserScanPlugin::MinValueChanged(double value) + { + min_value_ = value; + UpdateColors(); + } + + void LaserScanPlugin::MaxValueChanged(double value) + { + max_value_ = value; + UpdateColors(); + } + + void LaserScanPlugin::BufferSizeChanged(int value) + { + buffer_size_ = static_cast(value); + + if (buffer_size_ > 0) + { + while (scans_.size() > buffer_size_) + { + scans_.pop_front(); + } + } + } + + void LaserScanPlugin::PointSizeChanged(int value) + { + point_size_ = static_cast(value); + } + + void LaserScanPlugin::updatePreComputedTriginometic( + const sensor_msgs::msg::LaserScan::SharedPtr msg) + { + if( msg->ranges.size() != prev_ranges_size_ || + msg->angle_min != prev_angle_min_ || + msg->angle_increment != prev_increment_ ) + { + prev_ranges_size_ = msg->ranges.size(); + prev_angle_min_ = msg->angle_min; + prev_increment_ = msg->angle_increment; + + precomputed_cos_.resize( msg->ranges.size() ); + precomputed_sin_.resize( msg->ranges.size() ); + + for (size_t i = 0; i < msg->ranges.size(); i++) + { + double angle = msg->angle_min + msg->angle_increment * i; + precomputed_cos_[i] = cos(angle); + precomputed_sin_[i] = sin(angle); + } + } + } + + bool LaserScanPlugin::GetScanTransform( + const Scan& scan, + swri_transform_util::Transform& transform) + { + bool was_using_latest_transforms = this->use_latest_transforms_; + // Try first with use_latest_transforms_ = false + this->use_latest_transforms_ = false; + bool has_tranform = GetTransform(scan.source_frame_, scan.stamp, transform); + if (!has_tranform && was_using_latest_transforms) + { + // If failed use_latest_transforms_ = true + this->use_latest_transforms_ = true; + has_tranform = GetTransform(scan.source_frame_, scan.stamp, transform); + } + + this->use_latest_transforms_ = was_using_latest_transforms; + return has_tranform; + } + + void LaserScanPlugin::laserScanCallback(const sensor_msgs::msg::LaserScan::SharedPtr msg) + { + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + // Note that unlike some plugins, this one does not store nor rely on the + // source_frame_ member variable. This one can potentially store many + // messages with different source frames, so we need to store and transform + // them individually. + + Scan scan; + scan.stamp = msg->header.stamp; + scan.color = QColor::fromRgbF(1.0f, 0.0f, 0.0f, 1.0f); + scan.source_frame_ = msg->header.frame_id; + scan.has_intensity = !msg->intensities.empty(); + scan.points.reserve( msg->ranges.size() ); + + double x, y; + updatePreComputedTriginometic(msg); + + swri_transform_util::Transform transform; + scan.transformed = GetScanTransform(scan, transform); + + for (size_t i = 0; i < msg->ranges.size(); i++) + { + // Discard the point if it's out of range + if (msg->ranges[i] > msg->range_max || msg->ranges[i] < msg->range_min) + { + continue; + } + StampedPoint point; + x = precomputed_cos_[i] * msg->ranges[i]; + y = precomputed_sin_[i] * msg->ranges[i]; + point.point = tf2::Vector3(x, y, 0.0f); + point.range = msg->ranges[i]; + if (i < msg->intensities.size()) + point.intensity = msg->intensities[i]; + + if (scan.transformed) + { + point.transformed_point = transform * point.point; + } + point.color = CalculateColor(point, scan.has_intensity); + scan.points.push_back(point); + } + scans_.push_back(scan); + + // If there are more items in the scan buffer than buffer_size_, remove them + if (buffer_size_ > 0) + { + while (scans_.size() > buffer_size_) + { + scans_.pop_front(); + } + } + } + + void LaserScanPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void LaserScanPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void LaserScanPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* LaserScanPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool LaserScanPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + DrawIcon(); + + return true; + } + + void LaserScanPlugin::Draw(double x, double y, double scale) + { + glPointSize(point_size_); + glBegin(GL_POINTS); + + std::deque::const_iterator scan_it = scans_.begin(); + while (scan_it != scans_.end()) + { + if (scan_it->transformed) + { + for (const auto & point : scan_it->points) + { + glColor4d( + point.color.redF(), + point.color.greenF(), + point.color.blueF(), + alpha_); + glVertex2d( + point.transformed_point.getX(), + point.transformed_point.getY()); + } + } + ++scan_it; + } + + glEnd(); + + PrintInfo("OK"); + } + + void LaserScanPlugin::UseRainbowChanged(int check_state) + { + if (check_state == Qt::Checked) + { + ui_.max_color->setVisible(false); + ui_.min_color->setVisible(false); + ui_.maxColorLabel->setVisible(false); + ui_.minColorLabel->setVisible(false); + } else { + ui_.max_color->setVisible(true); + ui_.min_color->setVisible(true); + ui_.maxColorLabel->setVisible(true); + ui_.minColorLabel->setVisible(true); + } + UpdateColors(); + } + + void LaserScanPlugin::Transform() + { + for (auto & scan : scans_) + { + if (!scan.transformed) + { + swri_transform_util::Transform transform; + + if ( GetScanTransform( scan, transform) ) + { + scan.transformed = true; + + for (auto & point : scan.points) + { + point.transformed_point = transform * point.point; + } + } else { + PrintError("No transform between " + scan.source_frame_ + " and " + target_frame_); + } + } + } + // Z color is based on transformed color, so it is dependent on the + // transform + if (ui_.color_transformer->currentIndex() == COLOR_Z) + { + UpdateColors(); + } + } + + void LaserScanPlugin::LoadConfig(const YAML::Node& node, + const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(boost::trim_copy(topic).c_str()); + TopicEdited(); + } + + if (node["size"]) + { + point_size_ = node["size"].as(); + ui_.pointSize->setValue(static_cast(point_size_)); + } + + if (node["buffer_size"]) + { + buffer_size_ = node["buffer_size"].as(); + ui_.bufferSize->setValue(static_cast(buffer_size_)); + } + + if (node["color_transformer"]) + { + std::string color_transformer = node["color_transformer"].as(); + if (color_transformer == "Intensity") { + ui_.color_transformer->setCurrentIndex(COLOR_INTENSITY); + } else if (color_transformer == "Range") { + ui_.color_transformer->setCurrentIndex(COLOR_RANGE); + } else if (color_transformer == "X Axis") { + ui_.color_transformer->setCurrentIndex(COLOR_X); + } else if (color_transformer == "Y Axis") { + ui_.color_transformer->setCurrentIndex(COLOR_Y); + } else if (color_transformer == "Z Axis") { + ui_.color_transformer->setCurrentIndex(COLOR_Z); + } else { + ui_.color_transformer->setCurrentIndex(COLOR_FLAT); + } + } + + if (node["min_color"]) + { + std::string min_color_str = node["min_color"].as(); + ui_.min_color->setColor(QColor(min_color_str.c_str())); + } + + if (node["max_color"]) + { + std::string max_color_str = node["max_color"].as(); + ui_.max_color->setColor(QColor(max_color_str.c_str())); + } + + if (node["value_min"]) + { + min_value_ = node["value_min"].as(); + ui_.minValue->setValue(min_value_); + } + + if (node["max_value"]) + { + max_value_ = node["value_max"].as(); + ui_.maxValue->setValue(max_value_); + } + + if (node["alpha"]) + { + alpha_ = node["alpha"].as(); + ui_.alpha->setValue(alpha_); + } + + if (node["use_rainbow"]) + { + bool use_rainbow = node["use_rainbow"].as(); + ui_.use_rainbow->setChecked(use_rainbow); + } + + // UseRainbowChanged must be called *before* ColorTransformerChanged + UseRainbowChanged(ui_.use_rainbow->checkState()); + // ColorTransformerChanged will also update colors of all points + ColorTransformerChanged(ui_.color_transformer->currentIndex()); + } + + void LaserScanPlugin::ColorTransformerChanged(int index) + { + RCLCPP_DEBUG(node_->get_logger(), "Color transformer changed to %d", index); + switch (index) + { + case COLOR_FLAT: + ui_.min_color->setVisible(true); + ui_.max_color->setVisible(false); + ui_.maxColorLabel->setVisible(false); + ui_.minColorLabel->setVisible(false); + ui_.minValueLabel->setVisible(false); + ui_.maxValueLabel->setVisible(false); + ui_.minValue->setVisible(false); + ui_.maxValue->setVisible(false); + ui_.use_rainbow->setVisible(false); + break; + case COLOR_INTENSITY: // Intensity + case COLOR_RANGE: // Range + case COLOR_X: // X Axis + case COLOR_Y: // Y Axis + case COLOR_Z: // Z axis + default: + ui_.min_color->setVisible(!ui_.use_rainbow->isChecked()); + ui_.max_color->setVisible(!ui_.use_rainbow->isChecked()); + ui_.maxColorLabel->setVisible(!ui_.use_rainbow->isChecked()); + ui_.minColorLabel->setVisible(!ui_.use_rainbow->isChecked()); + ui_.minValueLabel->setVisible(true); + ui_.maxValueLabel->setVisible(true); + ui_.minValue->setVisible(true); + ui_.maxValue->setVisible(true); + ui_.use_rainbow->setVisible(true); + break; + } + UpdateColors(); + } + + /** + * Coerces alpha to [0.0, 1.0] and stores it in alpha_ + */ + void LaserScanPlugin::AlphaEdited(double val) + { + alpha_ = std::max(0.0f, std::min(static_cast(val), 1.0f)); + } + + void LaserScanPlugin::SaveConfig(YAML::Emitter& emitter, + const std::string& path) + { + emitter << YAML::Key << "topic" << + YAML::Value << boost::trim_copy(ui_.topic->text().toStdString()); + emitter << YAML::Key << "size" << + YAML::Value << ui_.pointSize->value(); + emitter << YAML::Key << "buffer_size" << + YAML::Value << ui_.bufferSize->value(); + emitter << YAML::Key << "alpha" << + YAML::Value << alpha_; + emitter << YAML::Key << "color_transformer" << + YAML::Value << ui_.color_transformer->currentText().toStdString(); + emitter << YAML::Key << "min_color" << + YAML::Value << ui_.min_color->color().name().toStdString(); + emitter << YAML::Key << "max_color" << + YAML::Value << ui_.max_color->color().name().toStdString(); + emitter << YAML::Key << "value_min" << + YAML::Value << ui_.minValue->text().toDouble(); + emitter << YAML::Key << "value_max" << + YAML::Value << ui_.maxValue->text().toDouble(); + emitter << YAML::Key << "use_rainbow" << + YAML::Value << ui_.use_rainbow->isChecked(); + } +} // namespace mapviz_plugins + diff --git a/mapviz_plugins/src/marker_plugin.cpp b/mapviz_plugins/src/marker_plugin.cpp new file mode 100644 index 000000000..03dce4c2e --- /dev/null +++ b/mapviz_plugins/src/marker_plugin.cpp @@ -0,0 +1,725 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +#include + +#include + +#include + +// Declare plugin +#include + +// C++ Standard Libraries +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::MarkerPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + MarkerPlugin::MarkerPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , connected_(false) + , has_message_(false) + { + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited())); + QObject::connect(ui_.clear, SIGNAL(clicked()), this, SLOT(ClearHistory())); + + startTimer(1000); + } + + void MarkerPlugin::ClearHistory() + { + RCLCPP_DEBUG(node_->get_logger(), "MarkerPlugin::ClearHistory()"); + markers_.clear(); + marker_visible_.clear(); + ui_.nsList->clear(); + } + + void MarkerPlugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic( + node_, + "visualization_msgs/msg/Marker", + "visualization_msgs/msg/MarkerArray"); + + if (topic.empty()) + { + return; + } + + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + + void MarkerPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + markers_.clear(); + marker_visible_.clear(); + ui_.nsList->clear(); + has_message_ = false; + PrintWarning("No messages received."); + + marker_sub_.reset(); + marker_array_sub_.reset(); + connected_ = false; + + topic_ = topic; + subscribe(); + } + } + + void MarkerPlugin::subscribe() + { + marker_sub_.reset(); + marker_array_sub_.reset(); + if (!topic_.empty()) + { + // ROS 2 does not allow for a simple way to subscribe to a general type of message (i.e. Marker and MarkerArray) + // That would require a way to de-serialize the data for mapviz to consume (based on message type) + // The code below checks for the topic type and subscribes in the appropriate manner + + auto known_topics = node_->get_topic_names_and_types(); + if (known_topics.count(topic_) > 0) + { + std::string topic_type = known_topics[topic_][0]; + if (topic_type == "visualization_msgs/msg/Marker") + { + marker_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(100), + std::bind(&MarkerPlugin::handleMarker, this, std::placeholders::_1)); + } + else if (topic_type == "visualization_msgs/msg/MarkerArray") + { + marker_array_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(100), + std::bind(&MarkerPlugin::handleMarkerArray, this, std::placeholders::_1)); + } + else + { + RCLCPP_ERROR(node_->get_logger(), + "Unable to subscribe to topic %s (unsupported type %s).", + topic_.c_str(), topic_type.c_str()); + return; + } + } + else + { + RCLCPP_ERROR(node_->get_logger(), + "Unable to subscribe to topic %s (does not exist).", topic_.c_str()); + return; + } + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + + void MarkerPlugin::handleMarker(visualization_msgs::msg::Marker::ConstSharedPtr marker) + { + processMarker(*marker); + } + + void MarkerPlugin::processMarker(const visualization_msgs::msg::Marker& marker) + { + connected_ = true; + if (marker.type == visualization_msgs::msg::Marker::ARROW && + marker.points.size() == 1) + { + // Arrow markers must have either 0 or >1 points; exactly one point is + // invalid. If we get one with 1 point, assume it's corrupt and ignore it. + return; + } + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + // Note that unlike some plugins, this one does not store nor rely on the + // source_frame_ member variable. This one can potentially store many + // messages with different source frames, so we need to store and transform + // them individually. + + if (marker.action == visualization_msgs::msg::Marker::ADD) + { + MarkerData& markerData = markers_[std::make_pair(marker.ns, marker.id)]; + markerData.points.clear(); // clear marker points + markerData.text.clear(); // clear marker text + markerData.stamp = marker.header.stamp; + markerData.display_type = marker.type; + markerData.color = {marker.color.r, marker.color.g, marker.color.b, marker.color.a}; + markerData.scale_x = static_cast(marker.scale.x); + markerData.scale_y = static_cast(marker.scale.y); + markerData.scale_z = static_cast(marker.scale.z); + markerData.transformed = true; + markerData.source_frame = marker.header.frame_id; + + if (marker_visible_.emplace(marker.ns, true).second) + { + QString name_string(marker.ns.c_str()); + auto* item = new QListWidgetItem(name_string, ui_.nsList); + item->setFlags(item->flags() | Qt::ItemIsUserCheckable); + item->setCheckState(Qt::Unchecked); + item->setCheckState(Qt::Checked); + } + + + // Since orientation was not implemented, many markers publish + // invalid all-zero orientations, so we need to check for this + // and provide a default identity transform. + tf2::Quaternion orientation(0.0, 0.0, 0.0, 1.0); + if (marker.pose.orientation.x || + marker.pose.orientation.y || + marker.pose.orientation.z || + marker.pose.orientation.w) + { + orientation = tf2::Quaternion(marker.pose.orientation.x, + marker.pose.orientation.y, + marker.pose.orientation.z, + marker.pose.orientation.w); + } + + markerData.local_transform = swri_transform_util::Transform( + tf2::Transform( + orientation, + tf2::Vector3(marker.pose.position.x, + marker.pose.position.y, + marker.pose.position.z))); + + markerData.points.clear(); + markerData.text = std::string(); + + swri_transform_util::Transform transform; + if (!GetTransform(markerData.source_frame, marker.header.stamp, transform)) + { + markerData.transformed = false; + PrintError("No transform between " + markerData.source_frame + " and " + target_frame_); + } + + // Handle lifetime parameter + rclcpp::Duration lifetime = marker.lifetime; + if (lifetime.nanoseconds() == 0) + { + markerData.expire_time = rclcpp::Time(rclcpp::Time::max().nanoseconds(), + node_->get_clock()->get_clock_type()); + } else { + // Temporarily add 5 seconds to fix some existing markers. + markerData.expire_time = node_->now() + lifetime + rclcpp::Duration(5, 0); + } + + if (markerData.display_type == visualization_msgs::msg::Marker::ARROW) + { + StampedPoint point; + point.color = markerData.color; + point.orientation = orientation; + + if (marker.points.empty()) + { + // If the "points" array is empty, we'll use the pose as the base of + // the arrow and scale its size based on the scale_x value. + point.point = markerData.local_transform * tf2::Vector3(0.0, 0.0, 0.0); + point.arrow_point = markerData.local_transform * tf2::Vector3(1.0, 0.0, 0.0); + } else { + // Otherwise the "points" array should have exactly two values, the + // start and end of the arrow. + point.point = markerData.local_transform * tf2::Vector3( + marker.points[0].x, + marker.points[0].y, + marker.points[0].z); + point.arrow_point = markerData.local_transform * tf2::Vector3( + marker.points[1].x, + marker.points[1].y, + marker.points[1].z); + } + + markerData.points.push_back(point); + + if (!marker.points.empty()) + { + // The point we just pushed back has both the start and end of the + // arrow, so the point we're pushing here is useless; we use it later + // only to indicate whether the original message had two points or not. + markerData.points.emplace_back(StampedPoint()); + } + + transformArrow(markerData, transform); + } else if (markerData.display_type == visualization_msgs::msg::Marker::CYLINDER || + markerData.display_type == visualization_msgs::msg::Marker::SPHERE || + markerData.display_type == visualization_msgs::msg::Marker::TEXT_VIEW_FACING) { + StampedPoint point; + point.point = tf2::Vector3(0.0, 0.0, 0.0); + point.transformed_point = transform * (markerData.local_transform * point.point); + point.color = markerData.color; + markerData.points.push_back(point); + markerData.text = marker.text; + } else if (markerData.display_type == visualization_msgs::msg::Marker::CUBE) { + StampedPoint point; + point.color = markerData.color; + + point.point = tf2::Vector3(marker.scale.x / 2, marker.scale.y / 2, 0.0); + point.transformed_point = transform * (markerData.local_transform * point.point); + markerData.points.push_back(point); + + point.point = tf2::Vector3(-marker.scale.x / 2, marker.scale.y / 2, 0.0); + point.transformed_point = transform * (markerData.local_transform * point.point); + markerData.points.push_back(point); + + point.point = tf2::Vector3(-marker.scale.x / 2, -marker.scale.y / 2, 0.0); + point.transformed_point = transform * (markerData.local_transform * point.point); + markerData.points.push_back(point); + + point.point = tf2::Vector3(marker.scale.x / 2, -marker.scale.y / 2, 0.0); + point.transformed_point = transform * (markerData.local_transform * point.point); + markerData.points.push_back(point); + } else if (markerData.display_type == visualization_msgs::msg::Marker::LINE_STRIP || + markerData.display_type == visualization_msgs::msg::Marker::LINE_LIST || + markerData.display_type == visualization_msgs::msg::Marker::CUBE_LIST || + markerData.display_type == visualization_msgs::msg::Marker::SPHERE_LIST || + markerData.display_type == visualization_msgs::msg::Marker::POINTS || + markerData.display_type == visualization_msgs::msg::Marker::TRIANGLE_LIST) { + markerData.points.reserve(marker.points.size()); + StampedPoint point; + for (unsigned int i = 0; i < marker.points.size(); i++) + { + point.point = tf2::Vector3(marker.points[i].x, marker.points[i].y, marker.points[i].z); + point.transformed_point = transform * (markerData.local_transform * point.point); + + if (i < marker.colors.size()) + { + point.color = { + marker.colors[i].r, + marker.colors[i].g, + marker.colors[i].b, + marker.colors[i].a}; + } else { + point.color = markerData.color; + } + + markerData.points.push_back(point); + } + } else { + RCLCPP_WARN_ONCE( + node_->get_logger(), + "Unsupported marker type: %d", + markerData.display_type); + } + } else if (marker.action == visualization_msgs::msg::Marker::DELETE) { + markers_.erase(std::make_pair(marker.ns, marker.id)); + } else if (marker.action == visualization_msgs::msg::Marker::DELETEALL) { + markers_.clear(); + } + } + + /** + * Given a MarkerData that represents an arrow and a transform, this function + * will generate the points involved in drawing the arrow and then transform + * all of them into the target frame. + * @param[inout] markerData A marker that represents an arrow. + * @param[in] transform The tf that should be applied to the arrow's points. + */ + void MarkerPlugin::transformArrow(MarkerData& markerData, + const swri_transform_util::Transform& transform) + { + // The first point in the markerData.points array always represents the + // base of the arrow. + StampedPoint& point = markerData.points.front(); + tf2::Vector3 arrowOffset; + if (markerData.points.size() == 1) + { + // If the markerData only has a single point, that means its "point" is + // the base of the arrow and the arrow's angle and length are determined + // by the orientation and scale_x. + point.transformed_point = transform * (markerData.local_transform * point.point); + tf2::Transform arrow_tf(tf2::Transform( + transform.GetOrientation()) * point.orientation, + tf2::Vector3(0.0, 0.0, 0.0)); + point.transformed_arrow_point = point.transformed_point + + arrow_tf * point.arrow_point * markerData.scale_x; + arrowOffset = tf2::Vector3(0.25, 0.0, 0.0); + } else { + // If the markerData has two points, that means that the start and end points + // of the arrow were explicitly specified in the original message, so the + // length and angle are determined by them. + point.transformed_point = transform * point.point; + point.transformed_arrow_point = transform * point.arrow_point; + // Also, in this mode, scale_y is the diameter of the arrow's head. + arrowOffset = tf2::Vector3(0.25 * markerData.scale_y, 0.0, 0.0); + } + + tf2::Vector3 pointDiff = point.transformed_arrow_point - point.transformed_point; + double angle = std::atan2(pointDiff.getY(), pointDiff.getX()); + + tf2::Quaternion left_q; + left_q.setRPY(0, 0, M_PI*0.75 + angle); + tf2::Transform left_tf(left_q); + + tf2::Quaternion right_q; + right_q.setRPY(0, 0, -M_PI*0.75 + angle); + tf2::Transform right_tf(right_q); + + point.transformed_arrow_left = point.transformed_arrow_point + left_tf * arrowOffset; + point.transformed_arrow_right = point.transformed_arrow_point + right_tf * arrowOffset; + } + + void MarkerPlugin::handleMarkerArray(visualization_msgs::msg::MarkerArray::ConstSharedPtr markers) + { + for (const auto & marker : markers->markers) + { + processMarker(marker); + } + } + + void MarkerPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void MarkerPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void MarkerPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* MarkerPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool MarkerPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + return true; + } + + void MarkerPlugin::Draw(double x, double y, double scale) + { + for (size_t i = 0; i < ui_.nsList->count(); i++) + { + if (ui_.nsList->item(i)->checkState() == Qt::Checked) + { + marker_visible_[ui_.nsList->item(i)->text().toStdString()] = true; + } else { + marker_visible_[ui_.nsList->item(i)->text().toStdString()] = false; + } + } + + rclcpp::Time now = node_->now(); + + auto markerIter = markers_.begin(); + while (markerIter != markers_.end()) + { + MarkerData& marker = markerIter->second; + + if (!(marker.expire_time > now)) { + PrintInfo("OK"); + markerIter = markers_.erase(markerIter); + continue; + } + + if (!marker.transformed) { + markerIter++; + continue; + } + + if (!marker_visible_[markerIter->first.first]) + { + markerIter++; + continue; + } + + glColor4f(marker.color.r, marker.color.g, marker.color.b, marker.color.a); + + if (marker.display_type == visualization_msgs::msg::Marker::ARROW) { + if (marker.points.size() == 1) { + // If the marker only has one point, use scale_y as the arrow width. + glLineWidth(marker.scale_y); + } else { + // If the marker has both start and end points explicitly specified, use + // scale_x as the shaft diameter. + glLineWidth(marker.scale_x); + } + glBegin(GL_LINES); + + for (const auto &point : marker.points) { + glColor4f(point.color.r, point.color.g, point.color.b, point.color.a); + + glVertex2d( + point.transformed_point.getX(), + point.transformed_point.getY()); + glVertex2d( + point.transformed_arrow_point.getX(), + point.transformed_arrow_point.getY()); + glVertex2d( + point.transformed_arrow_point.getX(), + point.transformed_arrow_point.getY()); + glVertex2d( + point.transformed_arrow_left.getX(), + point.transformed_arrow_left.getY()); + glVertex2d( + point.transformed_arrow_point.getX(), + point.transformed_arrow_point.getY()); + glVertex2d( + point.transformed_arrow_right.getX(), + point.transformed_arrow_right.getY()); + } + + glEnd(); + } else if (marker.display_type == visualization_msgs::msg::Marker::LINE_STRIP) { + glLineWidth(std::max(1.0f, marker.scale_x)); + glBegin(GL_LINE_STRIP); + + for (const auto &point : marker.points) { + glColor4f(point.color.r, point.color.g, point.color.b, point.color.a); + + glVertex2d( + point.transformed_point.getX(), + point.transformed_point.getY()); + } + + glEnd(); + } else if (marker.display_type == visualization_msgs::msg::Marker::LINE_LIST) { + glLineWidth(std::max(1.0f, marker.scale_x)); + glBegin(GL_LINES); + + for (const auto &point : marker.points) { + glColor4f(point.color.r, point.color.g, point.color.b, point.color.a); + + glVertex2d( + point.transformed_point.getX(), + point.transformed_point.getY()); + } + + glEnd(); + } else if (marker.display_type == visualization_msgs::msg::Marker::POINTS) { + glPointSize(std::max(1.0f, marker.scale_x)); + glBegin(GL_POINTS); + + for (const auto &point : marker.points) { + glColor4f(point.color.r, point.color.g, point.color.b, point.color.a); + + glVertex2d( + point.transformed_point.getX(), + point.transformed_point.getY()); + } + + glEnd(); + } else if (marker.display_type == visualization_msgs::msg::Marker::TRIANGLE_LIST) { + glBegin(GL_TRIANGLES); + + for (const auto &point : marker.points) { + glColor4f(point.color.r, point.color.g, point.color.b, point.color.a); + + glVertex2d( + point.transformed_point.getX(), + point.transformed_point.getY()); + } + + glEnd(); + } else if (marker.display_type == visualization_msgs::msg::Marker::CYLINDER || + marker.display_type == visualization_msgs::msg::Marker::SPHERE || + marker.display_type == visualization_msgs::msg::Marker::SPHERE_LIST) { + for (const auto &point : marker.points) { + glColor4f(point.color.r, point.color.g, point.color.b, point.color.a); + + glBegin(GL_TRIANGLE_FAN); + + + double marker_x = point.transformed_point.getX(); + double marker_y = point.transformed_point.getY(); + + glVertex2d(marker_x, marker_y); + + for (int32_t i = 0; i <= 360; i += 10) { + double radians = + static_cast(i) * static_cast(swri_math_util::_deg_2_rad); + // Spheres may be specified w/ only one scale value + if (marker.scale_y == 0.0) { + marker.scale_y = marker.scale_x; + } + glVertex2d( + marker_x + std::sin(radians) * marker.scale_x, + marker_y + std::cos(radians) * marker.scale_y); + } + + glEnd(); + } + } else if (marker.display_type == visualization_msgs::msg::Marker::CUBE || + marker.display_type == visualization_msgs::msg::Marker::CUBE_LIST) { + glBegin(GL_TRIANGLE_FAN); + for (const auto &point : marker.points) { + glColor4f(point.color.r, point.color.g, point.color.b, point.color.a); + + glVertex2d(point.transformed_point.getX(), point.transformed_point.getY()); + } + glEnd(); + } + + markerIter++; + PrintInfo("OK"); + } + } + + void MarkerPlugin::Paint(QPainter* painter, double x, double y, double scale) + { + // Most of the marker drawing is done using OpenGL commands, but text labels + // are rendered using a QPainter. This is intended primarily as an example + // of how the QPainter works. + rclcpp::Time now = node_->now(); + + // We don't want the text to be rotated or scaled, but we do want it to be + // translated appropriately. So, we save off the current world transform + // and reset it; when we actually draw the text, we'll manually translate + // it to the right place. + QTransform tf = painter->worldTransform(); + QFont font("Helvetica", 10); + painter->setFont(font); + painter->save(); + painter->resetTransform(); + + for (auto & markerIter : markers_) + { + MarkerData& marker = markerIter.second; + + if (marker.display_type != visualization_msgs::msg::Marker::TEXT_VIEW_FACING || + marker.expire_time <= now || + !marker.transformed) + { + continue; + } + + QPen pen(QBrush(QColor::fromRgbF(marker.color.r, marker.color.g, + marker.color.b, marker.color.a)), 1); + painter->setPen(pen); + + StampedPoint& rosPoint = marker.points.front(); + QPointF point = tf.map(QPointF(rosPoint.transformed_point.x(), + rosPoint.transformed_point.y())); + + auto text = QString::fromStdString(marker.text); + // Get bounding rectangle + QRectF rect(point, QSizeF(10, 10)); + rect = painter->boundingRect(rect, Qt::AlignLeft | Qt::AlignHCenter, text); + painter->drawText(rect, text); + + PrintInfo("OK"); + } + + painter->restore(); + } + + void MarkerPlugin::Transform() + { + for (auto & markerIter : markers_) + { + MarkerData& marker = markerIter.second; + + swri_transform_util::Transform transform; + if (GetTransform(marker.source_frame, marker.stamp, transform)) + { + marker.transformed = true; + + if (marker.display_type == visualization_msgs::msg::Marker::ARROW) + { + // Points for the ARROW marker type are stored a bit differently + // than other types, so they have their own special transform case. + transformArrow(marker, transform); + } else { + for (auto &point : marker.points) + { + point.transformed_point = transform * (marker.local_transform * point.point); + } + } + } else { + marker.transformed = false; + } + } + } + + void MarkerPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(boost::trim_copy(topic).c_str()); + + TopicEdited(); + } + } + + void MarkerPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key + << "topic" + << YAML::Value + << boost::trim_copy(ui_.topic->text().toStdString()); + } + + void MarkerPlugin::timerEvent(QTimerEvent *event) + { + bool new_connected = (marker_sub_ && marker_sub_->get_publisher_count() > 0) || + (marker_array_sub_ && marker_array_sub_->get_publisher_count() > 0); + if (connected_ && !new_connected) + { + subscribe(); + } + connected_ = new_connected; + } +} // namespace mapviz_plugins + diff --git a/mapviz_plugins/src/measuring_plugin.cpp b/mapviz_plugins/src/measuring_plugin.cpp new file mode 100644 index 000000000..5c2b5d023 --- /dev/null +++ b/mapviz_plugins/src/measuring_plugin.cpp @@ -0,0 +1,476 @@ +// ***************************************************************************** +// +// Copyright (c) 2018, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include +#include + +// QT libraries +#include +#include +#include +#include + +#include + +// ROS Libraries +#include + +// Mapviz Libraries +#include + +#include + +// C++ Libraries +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::MeasuringPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + +MeasuringPlugin::MeasuringPlugin() +: MapvizPlugin() +, ui_() +, config_widget_(new QWidget()) +, map_canvas_(nullptr) +, selected_point_(-1) +, is_mouse_down_(false) +, mouse_down_time_(0) +, max_ms_(Q_INT64_C(500)) +, max_distance_(2.0) +{ + ui_.setupUi(config_widget_); + ui_.main_color->setColor(Qt::black); + ui_.bkgnd_color->setColor(Qt::white); + + QObject::connect(ui_.clear, SIGNAL(clicked()), this, + SLOT(Clear())); + QObject::connect(ui_.show_measurements, SIGNAL(toggled(bool)), this, + SLOT(MeasurementsToggled(bool))); + QObject::connect(ui_.show_bkgnd_color, SIGNAL(toggled(bool)), this, + SLOT(BkgndColorToggled(bool))); + QObject::connect(ui_.font_size, SIGNAL(valueChanged(int)), this, + SLOT(FontSizeChanged(int))); + QObject::connect(ui_.alpha, SIGNAL(valueChanged(double)), this, + SLOT(AlphaChanged(double))); + connect(ui_.main_color, SIGNAL(colorEdited(const QColor &)), this, SLOT(DrawIcon())); + connect(ui_.bkgnd_color, SIGNAL(colorEdited(const QColor &)), this, SLOT(DrawIcon())); + + ui_.measurement->setText(tr("Click on the map. Distance between clicks will appear here")); + ui_.totaldistance->setText( + tr("Click on the map. Total distance between clicks will appear here")); +} + +MeasuringPlugin::~MeasuringPlugin() +{ + if (map_canvas_) + { + map_canvas_->removeEventFilter(this); + } +} + +void MeasuringPlugin::Clear() +{ + vertices_.clear(); + measurements_.clear(); + ui_.measurement->setText(tr("Click on the map. Distance between clicks will appear here")); + ui_.totaldistance->setText( + tr("Click on the map. Total distance between clicks will appear here")); +} + +QWidget* MeasuringPlugin::GetConfigWidget(QWidget* parent) +{ + config_widget_->setParent(parent); + + return config_widget_; +} + +bool MeasuringPlugin::Initialize(QGLWidget* canvas) +{ + map_canvas_ = dynamic_cast(canvas); + map_canvas_->installEventFilter(this); + + initialized_ = true; + PrintInfo("OK"); + + return true; +} + +bool MeasuringPlugin::eventFilter(QObject* object, QEvent* event) +{ + if(!this->Visible()) + { + RCLCPP_DEBUG(node_->get_logger(), "Ignoring mouse event, since measuring plugin is hidden"); + return false; + } + + switch (event->type()) + { + case QEvent::MouseButtonPress: + return handleMousePress(dynamic_cast(event)); + case QEvent::MouseButtonRelease: + return handleMouseRelease(dynamic_cast(event)); + case QEvent::MouseMove: + return handleMouseMove(dynamic_cast(event)); + default: + return false; + } +} + +bool MeasuringPlugin::handleMousePress(QMouseEvent* event) +{ + selected_point_ = -1; + int closest_point = 0; + double closest_distance = std::numeric_limits::max(); + QPointF point = event->localPos(); + RCLCPP_DEBUG(node_->get_logger(), "Map point: %f %f", point.x(), point.y()); + for (size_t i = 0; i < vertices_.size(); i++) + { + tf2::Vector3 vertex = vertices_[i]; + QPointF transformed = map_canvas_->FixedFrameToMapGlCoord(QPointF(vertex.x(), vertex.y())); + + double distance = QLineF(transformed, point).length(); + + if (distance < closest_distance) + { + closest_distance = distance; + closest_point = static_cast(i); + } + } + if (event->button() == Qt::LeftButton) + { + if (closest_distance < 15) + { + selected_point_ = closest_point; + return true; + } else { + is_mouse_down_ = true; + mouse_down_pos_ = event->localPos(); + mouse_down_time_ = QDateTime::currentMSecsSinceEpoch(); + return false; + } + } else if (event->button() == Qt::RightButton) { + if (closest_distance < 15) + { + vertices_.erase(vertices_.begin() + closest_point); + DistanceCalculation(); // function to calculate distance + return true; + } + } + + // Let other plugins process this event too + return false; +} + +bool MeasuringPlugin::handleMouseRelease(QMouseEvent* event) +{ + if (selected_point_ >= 0 && static_cast(selected_point_) < vertices_.size()) + { + QPointF point = event->localPos(); + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + vertices_[selected_point_].setX(position.x()); + vertices_[selected_point_].setY(position.y()); + + DistanceCalculation(); + + selected_point_ = -1; + + return true; + } else if (is_mouse_down_) { + qreal distance = QLineF(mouse_down_pos_, event->localPos()).length(); + qint64 msecsDiff = QDateTime::currentMSecsSinceEpoch() - mouse_down_time_; + + // Only fire the event if the mouse has moved less than the maximum distance + // and was held for shorter than the maximum time.. This prevents click + // events from being fired if the user is dragging the mouse across the map + // or just holding the cursor in place. + if (msecsDiff < max_ms_ && distance <= max_distance_) + { + QPointF point = event->localPos(); + + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + vertices_.push_back(position); + DistanceCalculation(); // call to calculate distance + } + } + is_mouse_down_ = false; + // Let other plugins process this event too + return false; +} + +void MeasuringPlugin::DistanceCalculation() +{ + double distance_instant = -1; // measurement between last two points + double distance_sum = 0; // sum of distance from all points + tf2::Vector3 last_position_(0, 0, 0); + std::string frame = target_frame_; + measurements_.clear(); + for (auto vertex : vertices_) + { + if (last_position_ != tf2::Vector3(0, 0, 0)) + { + distance_instant = last_position_.distance(vertex); + distance_sum = distance_sum + distance_instant; + measurements_.push_back(distance_instant); + } + last_position_ = vertex; + } + measurements_.push_back(distance_sum); + + QString new_point; + QTextStream stream(&new_point); + stream.setRealNumberPrecision(4); + + if (distance_instant > 0.0) + { + stream << distance_instant << " meters"; + } + + ui_.measurement->setText(new_point); + + QString new_point2; + QTextStream stream2(&new_point2); + stream2.setRealNumberPrecision(4); + + if (distance_sum > 0.0) + { + stream2 << distance_sum << " meters"; + } + + ui_.totaldistance->setText(new_point2); +} + +bool MeasuringPlugin::handleMouseMove(QMouseEvent* event) +{ + if (selected_point_ >= 0 && static_cast(selected_point_) < vertices_.size()) + { + QPointF point = event->localPos(); + std::string frame = target_frame_; + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + vertices_[selected_point_].setY(position.y()); + vertices_[selected_point_].setX(position.x()); + DistanceCalculation(); //function to calculate distance + return true; + } // Let other plugins process this event too + return false; +} + +void MeasuringPlugin::Draw(double x, double y, double scale) +{ + glLineWidth(1); + const QColor color = ui_.main_color->color(); + glColor4d(color.redF(), color.greenF(), color.blueF(), ui_.alpha->value()/2.0); + glBegin(GL_LINE_STRIP); + + for (const auto& vertex : vertices_) + { + glVertex2d(vertex.x(), vertex.y()); + } + + glEnd(); + + glBegin(GL_LINES); + + glColor4d(color.redF(), color.greenF(), color.blueF(), ui_.alpha->value()/2.0); + + glEnd(); + + // Draw vertices + glPointSize(9); + glBegin(GL_POINTS); + + for (const auto& vertex : vertices_) + { + glVertex2d(vertex.x(), vertex.y()); + } + glEnd(); + + PrintInfo("OK"); +} + +void MeasuringPlugin::Paint(QPainter* painter, double x, double y, double scale) +{ + bool show_measurements = ui_.show_measurements->isChecked(); + if (!show_measurements || vertices_.empty()) + { + return; + } + + QTransform tf = painter->worldTransform(); + QFont font("Helvetica", ui_.font_size->value()); + painter->setFont(font); + painter->save(); + painter->resetTransform(); + + // set the draw color for the text to be the same as the rest + QColor color = ui_.main_color->color(); + double alpha = ui_.alpha->value()*2.0 < 1.0 ? ui_.alpha->value()*2.0 : 1.0; + color.setAlphaF(alpha); + QPen pen(QBrush(color), 1); + painter->setPen(pen); + + const QRectF qrect = QRectF(0, 0, 0, 0); + MeasurementBox mb; + std::vector tags; + + // (midpoint positioned) measurements + for (int i = 0; i < vertices_.size()-1; i++) + { + tf2::Vector3 v1 = vertices_[i]; + tf2::Vector3 v2 = vertices_[i+1]; + + mb.string.setNum(measurements_[i], 'g', 5); + mb.string.prepend(" "); + mb.string.append(" m "); + // drawText used here to get correct mb.rect size + painter->drawText(qrect, 0, mb.string, &mb.rect); + mb.rect.moveTopLeft(tf.map(QPointF((v1.x()+v2.x())/2, (v1.y()+v2.y())/2))); + tags.push_back(mb); + } + // (endpoint positioned) total dist + mb.string.setNum(measurements_.back(), 'g', 5); + mb.string.prepend(" Total: "); + mb.string.append(" m "); + painter->drawText(qrect, 0, mb.string, &mb.rect); + mb.rect.moveTopLeft(tf.map(QPointF(vertices_.back().x(), vertices_.back().y()))); + tags.push_back(mb); + + // prevent text overlapping + for (int i = 0; i < tags.size(); i++) + { + for (int j = 0; j < tags.size(); j++) + { + if (i != j && tags[i].rect.intersects(tags[j].rect)) + { + QRectF overlap = tags[i].rect.intersected(tags[j].rect); + if (tags[i].rect.y() > tags[j].rect.y()) + { + tags[i].rect.moveTop(tags[i].rect.y() + overlap.height()); + } else { + tags[i].rect.moveTop(tags[i].rect.y() - overlap.height()); + } + } + } + } + + // paint tags + for (const auto& tag : tags) + { + if (ui_.show_bkgnd_color->isChecked()) + { + color = ui_.bkgnd_color->color(); + color.setAlphaF(ui_.alpha->value()); + painter->fillRect(tag.rect, color); + painter->drawRect(tag.rect); + } + painter->drawText(tag.rect, tag.string); + } + painter->restore(); +} + +void MeasuringPlugin::LoadConfig(const YAML::Node& node, const std::string& path) +{ + if (node["main_color"]) + { + std::string color = node["main_color"].as(); + ui_.main_color->setColor(QColor(color.c_str())); + } + + if (node["bkgnd_color"]) + { + std::string color = node["bkgnd_color"].as(); + ui_.bkgnd_color->setColor(QColor(color.c_str())); + } + + if (node["show_bkgnd_color"]) + { + bool show_bkgnd_color = node["show_bkgnd_color"].as(); + ui_.show_bkgnd_color->setChecked(show_bkgnd_color); + BkgndColorToggled(show_bkgnd_color); + } + + if (node["show_measurements"]) + { + bool show_measurements = node["show_measurements"].as(); + ui_.show_measurements->setChecked(show_measurements); + MeasurementsToggled(show_measurements); + } + + if (node["font_size"]) + { + int font_size = node["font_size"].as(); + ui_.font_size->setValue(font_size); + FontSizeChanged(font_size); + } + + if (node["alpha"]) + { + double alpha = node["alpha"].as(); + ui_.alpha->setValue(alpha); + AlphaChanged(alpha); + } +} + +void MeasuringPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) +{ + emitter << YAML::Key + << "main_color" + << YAML::Value + << ui_.main_color->color().name().toStdString(); + emitter << YAML::Key + << "bkgnd_color" + << YAML::Value + << ui_.bkgnd_color->color().name().toStdString(); + emitter << YAML::Key << "show_bkgnd_color" << YAML::Value << ui_.show_bkgnd_color->isChecked(); + emitter << YAML::Key << "show_measurements" << YAML::Value << ui_.show_measurements->isChecked(); + emitter << YAML::Key << "font_size" << YAML::Value << ui_.font_size->value(); + emitter << YAML::Key << "alpha" << YAML::Value << ui_.alpha->value(); +} + +void MeasuringPlugin::PrintError(const std::string& message) +{ + PrintErrorHelper(ui_.status, message, 1.0); +} + +void MeasuringPlugin::PrintInfo(const std::string& message) +{ + PrintInfoHelper(ui_.status, message, 1.0); +} + +void MeasuringPlugin::PrintWarning(const std::string& message) +{ + PrintWarningHelper(ui_.status, message, 1.0); +} + +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/move_base_plugin.cpp b/mapviz_plugins/src/move_base_plugin.cpp new file mode 100644 index 000000000..ca5de47cf --- /dev/null +++ b/mapviz_plugins/src/move_base_plugin.cpp @@ -0,0 +1,380 @@ +// ***************************************************************************** +// +// Copyright (c) 2017, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include +#include + +// QT libraries +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +// ROS libraries +#include +#include + +// Declare plugin +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::MoveBasePlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + +MoveBasePlugin::MoveBasePlugin() : + config_widget_(new QWidget()), + map_canvas_(NULL), + is_mouse_down_(false), + move_base_client_("move_base", true), + monitoring_action_state_(false) +{ + init_pose_pub_ = nh_.advertise("/initialpose", 1, false); + + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Background, Qt::white); + config_widget_->setPalette(p); + // Set status text red + + ui_.status->setText("OK"); + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::green); + ui_.status->setPalette(p3); + + QObject::connect(ui_.pushButtonInitialPose, SIGNAL(&QPushButton::toggled), + this, SLOT(&MoveBasePlugin::on_pushButtonInitialPose_toggled)); + + QObject::connect(ui_.pushButtonGoalPose, SIGNAL(&QPushButton::toggled), + this, SLOT(&MoveBasePlugin::on_pushButtonGoalPose_toggled)); + + QObject::connect(ui_.pushButtonAbort, SIGNAL(&QPushButton::clicked), + this, SLOT(&MoveBasePlugin::on_pushButtonAbort_clicked)); + + timer_ = nh_.createTimer(ros::Duration(1.0), &MoveBasePlugin::timerCallback, this); + +} + +MoveBasePlugin::~MoveBasePlugin() +{ + if (map_canvas_) + { + map_canvas_->removeEventFilter(this); + } +} + +void MoveBasePlugin::PrintError(const std::string& message) +{ + PrintErrorHelper( ui_.status, message); +} + +void MoveBasePlugin::PrintInfo(const std::string& message) +{ + PrintInfoHelper( ui_.status, message); +} + +void MoveBasePlugin::PrintWarning(const std::string& message) +{ + PrintWarningHelper( ui_.status, message); +} + +QWidget* MoveBasePlugin::GetConfigWidget(QWidget* parent) +{ + config_widget_->setParent(parent); + return config_widget_; +} + +bool MoveBasePlugin::Initialize(QGLWidget* canvas) +{ + map_canvas_ = static_cast(canvas); + map_canvas_->installEventFilter(this); + initialized_ = true; + return true; +} + +bool MoveBasePlugin::eventFilter(QObject *object, QEvent* event) +{ + switch (event->type()) + { + case QEvent::MouseButtonPress: + return handleMousePress(static_cast(event)); + case QEvent::MouseButtonRelease: + return handleMouseRelease(static_cast(event)); + case QEvent::MouseMove: + return handleMouseMove(static_cast(event)); + default: + return false; + } +} + +void MoveBasePlugin::timerCallback(const ros::TimerEvent &) +{ + bool connected = move_base_client_.isServerConnected(); + ui_.pushButtonAbort->setEnabled( connected ); + ui_.pushButtonGoalPose->setEnabled( connected ); + ui_.pushButtonInitialPose->setEnabled( connected ); + + if(!connected) + { + PrintErrorHelper( ui_.status, "[move_base] server not connected"); + } + else if( !monitoring_action_state_ ){ + PrintInfoHelper( ui_.status, "Ready to send command"); + } + else{ + actionlib::SimpleClientGoalState state = move_base_client_.getState(); + switch( state.state_ ) + { + case actionlib::SimpleClientGoalState::PENDING: + PrintWarningHelper( ui_.status, state.toString() ); + break; + + case actionlib::SimpleClientGoalState::PREEMPTED: + PrintWarningHelper( ui_.status, state.toString() ); + monitoring_action_state_ = false; + break; + + case actionlib::SimpleClientGoalState::ACTIVE: + PrintInfoHelper( ui_.status, state.toString() ); + break; + + case actionlib::SimpleClientGoalState::SUCCEEDED: + PrintInfoHelper( ui_.status, state.toString() ); + monitoring_action_state_ = false; + break; + + case actionlib::SimpleClientGoalState::REJECTED: + case actionlib::SimpleClientGoalState::ABORTED: + case actionlib::SimpleClientGoalState::LOST: + case actionlib::SimpleClientGoalState::RECALLED: + PrintErrorHelper( ui_.status, state.toString() ); + monitoring_action_state_ = false; + break; + } + } +} + + +bool MoveBasePlugin::handleMousePress(QMouseEvent* event) +{ + bool init_checked = ui_.pushButtonInitialPose->isChecked(); + bool goal_checked = ui_.pushButtonGoalPose->isChecked(); + if( !init_checked && !goal_checked) + { + return false; + } + + if (event->button() == Qt::LeftButton) + { + is_mouse_down_ = true; + arrow_angle_ = 0; +#if QT_VERSION >= 0x050000 + arrow_tail_position_= map_canvas_->MapGlCoordToFixedFrame( event->localPos() ); +#else + arrow_tail_position_= map_canvas_->MapGlCoordToFixedFrame( event->posF() ); +#endif + return true; + } + return false; +} + +bool MoveBasePlugin::handleMouseMove(QMouseEvent* event) +{ + if (is_mouse_down_) + { +#if QT_VERSION >= 0x050000 + QPointF head_pos = map_canvas_->MapGlCoordToFixedFrame( event->localPos() ); +#else + QPointF head_pos = map_canvas_->MapGlCoordToFixedFrame( event->posF() ); +#endif + arrow_angle_ = atan2( head_pos.y() - arrow_tail_position_.y(), + head_pos.x() - arrow_tail_position_.x() ); + } + return false; +} + +bool MoveBasePlugin::handleMouseRelease(QMouseEvent* event) +{ + if( !is_mouse_down_ ) + { + return false; + } + + is_mouse_down_ = false; + + bool init_checked = ui_.pushButtonInitialPose->isChecked(); + bool goal_checked = ui_.pushButtonGoalPose->isChecked(); + if( !init_checked && !goal_checked) + { + return false; + } + + tf::Quaternion quat = tf::createQuaternionFromYaw(arrow_angle_); + + if( goal_checked ){ + + move_base_msg_.action_goal.header.frame_id = target_frame_; + move_base_msg_.action_goal.header.stamp = ros::Time::now(); + move_base_msg_.action_goal.goal_id.stamp = move_base_msg_.action_goal.header.stamp; + move_base_msg_.action_goal.goal_id.id = "mapviz_goal"; + move_base_msg_.action_goal.goal.target_pose.header = move_base_msg_.action_goal.header; + + geometry_msgs::Pose& pose = move_base_msg_.action_goal.goal.target_pose.pose; + pose.position.x = arrow_tail_position_.x(); + pose.position.y = arrow_tail_position_.y(); + pose.position.z = 0.0; + tf::quaternionTFToMsg( quat, pose.orientation ); + + move_base_client_.sendGoal(move_base_msg_.action_goal.goal); + ui_.pushButtonGoalPose->setChecked(false); + monitoring_action_state_ = true; + } + if( init_checked ){ + geometry_msgs::PoseWithCovarianceStamped initpose; + initpose.header.frame_id = target_frame_; + initpose.header.stamp = ros::Time::now(); + initpose.pose.pose.position.x = arrow_tail_position_.x(); + initpose.pose.pose.position.y = arrow_tail_position_.y(); + initpose.pose.pose.position.z = 0.0; + tf::quaternionTFToMsg( quat, initpose.pose.pose.orientation ); + + init_pose_pub_.publish(initpose); + ui_.pushButtonInitialPose->setChecked(false); + } + return true; +} + + +void MoveBasePlugin::Draw(double x, double y, double scale) +{ + std::array arrow_points; + arrow_points[0] = QPointF(10, 0); + arrow_points[1] = QPointF(6, -2.5); + arrow_points[2] = QPointF(6.5, -1); + arrow_points[3] = QPointF(0, -1); + arrow_points[4] = QPointF(0, 1); + arrow_points[5] = QPointF(6.5, 1); + arrow_points[6] = QPointF(6, 2.5); + + if( is_mouse_down_ ) + { + QPointF transformed_points[7]; + for (size_t i=0; i<7; i++ ) + { + tf::Vector3 point(arrow_points[i].x(), arrow_points[i].y(), 0); + point *= scale*10; + point = tf::Transform( tf::createQuaternionFromYaw(arrow_angle_) ) * point; + transformed_points[i] = QPointF(point.x() + arrow_tail_position_.x(), + point.y() + arrow_tail_position_.y() ); + } + glColor3f(0.1, 0.9, 0.1); + glLineWidth(2); + glBegin(GL_TRIANGLE_FAN); + for (const QPointF& point: transformed_points ) + { + glVertex2d(point.x(), point.y()); + } + glEnd(); + + glColor3f(0.0, 0.6, 0.0); + glBegin(GL_LINE_LOOP); + for (const QPointF& point: transformed_points ) + { + glVertex2d(point.x(), point.y()); + } + glEnd(); + } +} + + +void MoveBasePlugin::LoadConfig(const YAML::Node& node, const std::string& path) +{ + +} + +void MoveBasePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) +{ + +} + +void MoveBasePlugin::on_pushButtonInitialPose_toggled(bool checked) +{ + const bool other_checked = ui_.pushButtonGoalPose->isChecked(); + + if(checked){ + if(other_checked){ + ui_.pushButtonGoalPose->setChecked(false); + } + else{ + QPixmap cursor_pixmap = QPixmap(":/images/green-arrow.png"); + QApplication::setOverrideCursor(QCursor(cursor_pixmap)); + } + } + if( !checked && !other_checked ) + { + QApplication::restoreOverrideCursor(); + } +} + +void MoveBasePlugin::on_pushButtonGoalPose_toggled(bool checked) +{ + const bool other_checked = ui_.pushButtonInitialPose->isChecked(); + if(checked){ + if( other_checked){ + ui_.pushButtonInitialPose->setChecked(false); + } + else{ + QPixmap cursor_pixmap = QPixmap(":/images/green-arrow.png"); + QApplication::setOverrideCursor(QCursor(cursor_pixmap)); + } + } + if( !checked && !other_checked ) + { + QApplication::restoreOverrideCursor(); + } + +} + +void MoveBasePlugin::on_pushButtonAbort_clicked() +{ + move_base_client_.cancelGoal(); +} + +} diff --git a/mapviz_plugins/src/navsat_plugin.cpp b/mapviz_plugins/src/navsat_plugin.cpp new file mode 100644 index 000000000..22653ea43 --- /dev/null +++ b/mapviz_plugins/src/navsat_plugin.cpp @@ -0,0 +1,246 @@ +// ***************************************************************************** +// +// Copyright (C) 2013 All Right Reserved, Southwest Research Institute® (SwRI®) +// +// Contract No. 10-58058A +// Contractor Southwest Research Institute® (SwRI®) +// Address 6220 Culebra Road, San Antonio, Texas 78228-0510 +// Contact Steve Dellenback (210) 522-3914 +// +// This code was developed as part of an internal research project fully funded +// by Southwest Research Institute®. +// +// THIS CODE AND INFORMATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY +// KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A +// PARTICULAR PURPOSE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include +#include + +#include + +// ROS libraries +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::NavSatPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + NavSatPlugin::NavSatPlugin() + : PointDrawingPlugin() + , ui_() + , config_widget_(new QWidget()) + , has_message_(false) + { + ui_.setupUi(config_widget_); + + ui_.color->setColor(Qt::green); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, + SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, + SLOT(TopicEdited())); + QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this, + SLOT(PositionToleranceChanged(double))); + QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this, + SLOT(BufferSizeChanged(int))); + QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this, + SLOT(SetDrawStyle(QString))); + QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this, + SLOT(SetColor(const QColor&))); + QObject::connect(ui_.buttonResetBuffer, SIGNAL(pressed()), this, + SLOT(ClearPoints())); + } + + void NavSatPlugin::SelectTopic() + { + std::string topic = + mapviz::SelectTopicDialog::selectTopic(node_, "sensor_msgs/msg/NavSatFix"); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void NavSatPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + ClearPoints(); + has_message_ = false; + PrintWarning("No messages received."); + + navsat_sub_.reset(); + topic_ = topic; + if (!topic.empty()) + { + navsat_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&NavSatPlugin::NavSatFixCallback, this, std::placeholders::_1)); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void NavSatPlugin::NavSatFixCallback( + const sensor_msgs::msg::NavSatFix::ConstSharedPtr navsat) + { + if (!tf_manager_->LocalXyUtil()->Initialized()) + { + return; + } + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + StampedPoint stamped_point; + stamped_point.stamp = navsat->header.stamp; + + double x; + double y; + tf_manager_->LocalXyUtil()->ToLocalXy(navsat->latitude, navsat->longitude, x, y); + + stamped_point.point = tf2::Vector3(x, y, navsat->altitude); + stamped_point.orientation.setRPY(0, 0, 0); + stamped_point.source_frame = tf_manager_->LocalXyUtil()->Frame(); + + pushPoint( std::move(stamped_point) ); + } + + void NavSatPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void NavSatPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void NavSatPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* NavSatPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool NavSatPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + SetColor(ui_.color->color()); + return true; + } + + void NavSatPlugin::Draw(double x, double y, double scale) + { + if (DrawPoints(scale)) + { + PrintInfo("OK"); + } + } + + void NavSatPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(topic.c_str()); + } + + if (node["color"]) + { + std::string color = node["color"].as(); + QColor qcolor(color.c_str()); + SetColor(qcolor); + ui_.color->setColor(qcolor); + } + + if (node["draw_style"]) + { + std::string draw_style = node["draw_style"].as(); + + if (draw_style == "lines") + { + ui_.drawstyle->setCurrentIndex(0); + SetDrawStyle( LINES ); + } else if (draw_style == "points") { + ui_.drawstyle->setCurrentIndex(1); + SetDrawStyle( POINTS ); + } + } + + if (node["position_tolerance"]) + { + auto position_tolerance = node["position_tolerance"].as(); + ui_.positiontolerance->setValue(position_tolerance); + PositionToleranceChanged(position_tolerance); + } + + if (node["buffer_size"]) + { + auto buffer_size = node["buffer_size"].as(); + ui_.buffersize->setValue(buffer_size); + BufferSizeChanged(buffer_size); + } + + TopicEdited(); + } + + void NavSatPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + std::string topic = ui_.topic->text().toStdString(); + emitter << YAML::Key << "topic" << YAML::Value << topic; + + std::string color = ui_.color->color().name().toStdString(); + emitter << YAML::Key << "color" << YAML::Value << color; + + std::string draw_style = ui_.drawstyle->currentText().toStdString(); + emitter << YAML::Key << "draw_style" << YAML::Value << draw_style; + + emitter << YAML::Key << "position_tolerance" << + YAML::Value << positionTolerance(); + + emitter << YAML::Key << "buffer_size" << YAML::Value << bufferSize(); + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/occupancy_grid_plugin.cpp b/mapviz_plugins/src/occupancy_grid_plugin.cpp new file mode 100644 index 000000000..72d1be4a5 --- /dev/null +++ b/mapviz_plugins/src/occupancy_grid_plugin.cpp @@ -0,0 +1,565 @@ +// ***************************************************************************** +// +// Copyright (c) 2018, Eurecat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Eurecat nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +#include + +// QT libraries +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::OccupancyGridPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + const int CHANNELS = 4; + + typedef std::array Palette; + + Palette makeMapPalette() + { + Palette palette; + uchar* palette_ptr = palette.data(); + // Standard gray map palette values + for( int i = 0; i <= 100; i++ ) + { + uchar v = 255 - (255 * i) / 100; + *palette_ptr++ = v; // red + *palette_ptr++ = v; // green + *palette_ptr++ = v; // blue + *palette_ptr++ = 255; // alpha + } + // illegal positive values in green + for( int i = 101; i <= 127; i++ ) + { + *palette_ptr++ = 0; // red + *palette_ptr++ = 255; // green + *palette_ptr++ = 0; // blue + *palette_ptr++ = 255; // alpha + } + // illegal negative (char) values in shades of red/yellow + for( int i = 128; i <= 254; i++ ) + { + *palette_ptr++ = 255; // red + *palette_ptr++ = (255*(i-128))/(254-128); // green + *palette_ptr++ = 0; // blue + *palette_ptr++ = 255; // alpha + } + // legal -1 value is tasteful blueish greenish grayish color + *palette_ptr++ = 0x70; // red + *palette_ptr++ = 0x89; // green + *palette_ptr++ = 0x86; // blue + *palette_ptr++ = 160; // alpha + + return palette; + } + + Palette makeCostmapPalette() + { + Palette palette; + uchar* palette_ptr = palette.data(); + + // zero values have alpha=0 + *palette_ptr++ = 0; // red + *palette_ptr++ = 0; // green + *palette_ptr++ = 0; // blue + *palette_ptr++ = 0; // alpha + + // Blue to red spectrum for most normal cost values + for( int i = 1; i <= 98; i++ ) + { + uchar v = (255 * i) / 100; + *palette_ptr++ = v; // red + *palette_ptr++ = 0; // green + *palette_ptr++ = 255 - v; // blue + *palette_ptr++ = 255; // alpha + } + // inscribed obstacle values (99) in cyan + *palette_ptr++ = 0; // red + *palette_ptr++ = 255; // green + *palette_ptr++ = 255; // blue + *palette_ptr++ = 255; // alpha + // lethal obstacle values (100) in purple + *palette_ptr++ = 255; // red + *palette_ptr++ = 0; // green + *palette_ptr++ = 255; // blue + *palette_ptr++ = 255; // alpha + // illegal positive values in green + for( int i = 101; i <= 127; i++ ) + { + *palette_ptr++ = 0; // red + *palette_ptr++ = 255; // green + *palette_ptr++ = 0; // blue + *palette_ptr++ = 255; // alpha + } + // illegal negative (char) values in shades of red/yellow + for( int i = 128; i <= 254; i++ ) + { + *palette_ptr++ = 255; // red + *palette_ptr++ = (255*(i-128))/(254-128); // green + *palette_ptr++ = 0; // blue + *palette_ptr++ = 255; // alpha + } + // legal -1 value is tasteful blueish greenish grayish color + *palette_ptr++ = 0x70; // red + *palette_ptr++ = 0x89; // green + *palette_ptr++ = 0x86; // blue + *palette_ptr++ = 160; // alpha + + return palette; + } + + OccupancyGridPlugin::OccupancyGridPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , transformed_(false) + , texture_id_(0) + , texture_x_(0.0) + , texture_y_(0.0) + , texture_size_(0) + , map_palette_( makeMapPalette() ) + , costmap_palette_( makeCostmapPalette() ) + { + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.select_grid, SIGNAL(clicked()), this, SLOT(SelectTopicGrid())); + + QObject::connect( + ui_.topic_grid, + SIGNAL(textEdited(const QString&)), + this, + SLOT(TopicGridEdited())); + + QObject::connect( + this, + SIGNAL(TargetFrameChanged(std::string)), + this, + SLOT(FrameChanged(std::string))); + + QObject::connect( + ui_.checkbox_update, + SIGNAL(toggled(bool)), + this, + SLOT(upgradeCheckBoxToggled(bool))); + + QObject::connect( + ui_.color_scheme, + SIGNAL(currentTextChanged(const QString &)), + this, + SLOT(colorSchemeUpdated(const QString &))); + } + + void OccupancyGridPlugin::DrawIcon() + { + if (icon_) + { + QPixmap icon(16, 16); + icon.fill(Qt::transparent); + + QPainter painter(&icon); + painter.setRenderHint(QPainter::Antialiasing, true); + + QPen pen(Qt::black); + + pen.setWidth(2); + pen.setCapStyle(Qt::SquareCap); + painter.setPen(pen); + + painter.drawLine(2, 2, 14, 2); + painter.drawLine(2, 2, 2, 14); + painter.drawLine(14, 2, 14, 14); + painter.drawLine(2, 14, 14, 14); + painter.drawLine(8, 2, 8, 14); + painter.drawLine(2, 8, 14, 8); + + icon_->SetPixmap(icon); + } + } + + void OccupancyGridPlugin::FrameChanged(std::string) + { + transformed_ = false; + } + + void OccupancyGridPlugin::SelectTopicGrid() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic(node_, "nav_msgs/msg/OccupancyGrid"); + if (!topic.empty()) + { + QString str = QString::fromStdString(topic); + ui_.topic_grid->setText( str); + TopicGridEdited(); + } + } + + + void OccupancyGridPlugin::TopicGridEdited() + { + const std::string topic = ui_.topic_grid->text().trimmed().toStdString(); + + initialized_ = false; + grid_.reset(); + raw_buffer_.clear(); + + grid_sub_.reset(); + update_sub_.reset(); + + if (!topic.empty()) + { + grid_sub_ = node_->create_subscription( + topic, + rclcpp::QoS(10), + std::bind(&OccupancyGridPlugin::Callback, this, std::placeholders::_1)); + if(ui_.checkbox_update->isChecked()) + { + update_sub_ = node_->create_subscription( + topic, + rclcpp::QoS(10), + std::bind(&OccupancyGridPlugin::CallbackUpdate, this, std::placeholders::_1)); + } + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic.c_str()); + } + } + + void OccupancyGridPlugin::upgradeCheckBoxToggled(bool) + { + const std::string topic = ui_.topic_grid->text().trimmed().toStdString(); + update_sub_.reset(); + + if (ui_.checkbox_update) + { + update_sub_ = node_->create_subscription( + topic, + rclcpp::QoS(10), + std::bind(&OccupancyGridPlugin::CallbackUpdate, this, std::placeholders::_1)); + } + } + + void OccupancyGridPlugin::colorSchemeUpdated(const QString &) + { + if( grid_ && !raw_buffer_.empty()) + { + const size_t width = grid_->info.width; + const size_t height = grid_->info.height; + const Palette& palette = + (ui_.color_scheme->currentText() == "map") ? map_palette_ : costmap_palette_; + + for (size_t row = 0; row < height; row++) + { + for (size_t col = 0; col < width; col++) + { + size_t index = (col + row * texture_size_); + uchar color = raw_buffer_[index]; + memcpy( &color_buffer_[index*CHANNELS], &palette[color*CHANNELS], CHANNELS); + } + } + updateTexture(); + } + } + + void OccupancyGridPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void OccupancyGridPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void OccupancyGridPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* OccupancyGridPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool OccupancyGridPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + DrawIcon(); + return true; + } + + void OccupancyGridPlugin::updateTexture() + { + if (texture_id_ != -1) + { + glDeleteTextures(1, &texture_id_); + } + + // Get a new texture id. + glGenTextures(1, &texture_id_); + + // Bind the texture with the correct size and null memory. + glBindTexture(GL_TEXTURE_2D, texture_id_); + glPixelStorei(GL_UNPACK_ALIGNMENT, 1); + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); + + glTexEnvf( GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_MODULATE ); + + glTexImage2D( + GL_TEXTURE_2D, + 0, + GL_RGBA, + texture_size_, + texture_size_, + 0, + GL_RGBA, + GL_UNSIGNED_BYTE, + color_buffer_.data()); + + glBindTexture(GL_TEXTURE_2D, 0); + glPixelStorei(GL_UNPACK_ALIGNMENT, 4); + } + + + void OccupancyGridPlugin::Callback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg) + { + grid_ = msg; + const int width = grid_->info.width; + const int height = grid_->info.height; + initialized_ = true; + source_frame_ = grid_->header.frame_id; + transformed_ = GetTransform( source_frame_, grid_->header.stamp, transform_); + if ( !transformed_ ) + { + PrintError("No transform between " + source_frame_ + " and " + target_frame_); + } + + int32_t max_dimension = std::max(height, width); + + texture_size_ = 2; + while (texture_size_ < max_dimension){ + texture_size_ = texture_size_ << 1; + } + + const Palette& palette = + (ui_.color_scheme->currentText() == "map") ? map_palette_ : costmap_palette_; + + raw_buffer_.resize(texture_size_*texture_size_, 0); + color_buffer_.resize(texture_size_*texture_size_*CHANNELS, 0); + + for (size_t row = 0; row < height; row++) + { + for (size_t col = 0; col < width; col++) + { + size_t index_src = (col + row*width); + size_t index_dst = (col + row*texture_size_); + uchar color = static_cast( grid_->data[ index_src ] ); + raw_buffer_[index_dst] = color; + memcpy( &color_buffer_[index_dst*CHANNELS], &palette[color*CHANNELS], CHANNELS); + } + } + + texture_x_ = static_cast(width) / static_cast(texture_size_); + texture_y_ = static_cast(height) / static_cast(texture_size_); + + updateTexture(); + PrintInfo("Map received"); + } + + void OccupancyGridPlugin::CallbackUpdate(const map_msgs::msg::OccupancyGridUpdate::SharedPtr msg) + { + PrintInfo("Update Received"); + + if( initialized_ ) + { + const Palette& palette = + (ui_.color_scheme->currentText() == "map") ? map_palette_ : costmap_palette_; + + for (size_t row = 0; row < msg->height; row++) + { + for (size_t col = 0; col < msg->width; col++) + { + size_t index_src = (col + row * msg->width); + size_t index_dst = ( (col + msg->x) + (row + msg->y)*texture_size_); + uchar color = static_cast( msg->data[ index_src ] ); + raw_buffer_[index_dst] = color; + memcpy( &color_buffer_[index_dst*CHANNELS], &palette[color*CHANNELS], CHANNELS); + } + } + updateTexture(); + } + } + + void OccupancyGridPlugin::Draw(double x, double y, double scale) + { + glPushMatrix(); + + if( grid_ && transformed_) + { + double resolution = grid_->info.resolution; + glTranslatef( transform_.GetOrigin().getX(), + transform_.GetOrigin().getY(), + 0.0); + + const double RAD_TO_DEG = 180.0 / M_PI; + + tf2Scalar yaw, pitch, roll; + tf2::Matrix3x3 mat( transform_.GetOrientation() ); + mat.getEulerYPR(yaw, pitch, roll); + + glRotatef(pitch * RAD_TO_DEG, 0, 1, 0); + glRotatef(roll * RAD_TO_DEG, 1, 0, 0); + glRotatef(yaw * RAD_TO_DEG, 0, 0, 1); + + glTranslatef( grid_->info.origin.position.x, + grid_->info.origin.position.y, + 0.0); + + glScalef( resolution, resolution, 1.0); + + float width = static_cast(grid_->info.width); + float height = static_cast(grid_->info.height); + + glEnable(GL_TEXTURE_2D); + glBindTexture(GL_TEXTURE_2D, texture_id_); + glBegin(GL_TRIANGLES); + + glColor4f(1.0f, 1.0f, 1.0f, ui_.alpha->value() ); + + glTexCoord2d(0, 0); + glVertex2d(0, 0); + glTexCoord2d(texture_x_, 0); + glVertex2d(width, 0); + glTexCoord2d(texture_x_, texture_y_); + glVertex2d(width, height); + + glTexCoord2d(0, 0); + glVertex2d(0, 0); + glTexCoord2d(texture_x_, texture_y_); + glVertex2d(width, height); + glTexCoord2d(0, texture_y_); + glVertex2d(0, height); + + glEnd(); + + glBindTexture(GL_TEXTURE_2D, 0); + glDisable(GL_TEXTURE_2D); + } + glPopMatrix(); + } + + void OccupancyGridPlugin::Transform() + { + if( !initialized_ ) return; + swri_transform_util::Transform transform; + if ( grid_ ) + { + if( GetTransform( source_frame_, rclcpp::Time(0), transform) ) + { + transformed_ = true; + transform_ = transform; + } + } + if ( !transformed_ ) + { + PrintError("No transform between " + source_frame_ + " and " + target_frame_); + } + } + + void OccupancyGridPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic_grid->setText(QString::fromStdString(topic)); + } + + if (node["update"]) + { + bool checked = node["update"].as(); + ui_.checkbox_update->setChecked( checked ); + } + + if (node["alpha"]) + { + double alpha = node["alpha"].as(); + ui_.alpha->setValue(alpha); + } + + if (node["scheme"]) + { + std::string scheme = node["scheme"].as(); + int index = ui_.color_scheme->findText(QString::fromStdString(scheme), Qt::MatchExactly); + if (index >= 0) + { + ui_.color_scheme->setCurrentIndex(index); + } + colorSchemeUpdated(QString::fromStdString(scheme)); + } + + TopicGridEdited(); + } + + void OccupancyGridPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key << "alpha" << YAML::Value << ui_.alpha->value(); + emitter << YAML::Key << "topic" << YAML::Value << ui_.topic_grid->text().toStdString(); + emitter << YAML::Key << "update" << YAML::Value << ui_.checkbox_update->isChecked(); + emitter << YAML::Key + << "scheme" + << YAML::Value + << ui_.color_scheme->currentText().toStdString(); + } +} // namespace mapviz_plugins + diff --git a/mapviz_plugins/src/odometry_plugin.cpp b/mapviz_plugins/src/odometry_plugin.cpp new file mode 100644 index 000000000..2aabf6849 --- /dev/null +++ b/mapviz_plugins/src/odometry_plugin.cpp @@ -0,0 +1,407 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include +#include +#include + +#include + +// ROS libraries +#include + +#include +#include +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::OdometryPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + OdometryPlugin::OdometryPlugin() + : PointDrawingPlugin() + , ui_() + , config_widget_(new QWidget()) + , has_message_(false) + { + ui_.setupUi(config_widget_); + ui_.color->setColor(Qt::green); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, + SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, + SLOT(TopicEdited())); + QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this, + SLOT(PositionToleranceChanged(double))); + QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this, + SLOT(BufferSizeChanged(int))); + QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this, + SLOT(SetDrawStyle(QString))); + QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)), + this, SLOT(SetStaticArrowSizes(bool))); + QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)), + this, SLOT(SetArrowSize(int))); + QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this, + SLOT(SetColor(const QColor&))); + QObject::connect(ui_.show_laps, SIGNAL(toggled(bool)), this, + SLOT(LapToggled(bool))); + QObject::connect(ui_.show_covariance, SIGNAL(toggled(bool)), this, + SLOT(CovariancedToggled(bool))); + QObject::connect(ui_.show_all_covariances, SIGNAL(toggled(bool)), this, + SLOT(ShowAllCovariancesToggled(bool))); + QObject::connect(ui_.buttonResetBuffer, SIGNAL(pressed()), this, + SLOT(ClearPoints())); + } + + void OdometryPlugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic(node_, "nav_msgs/msg/Odometry"); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void OdometryPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + ClearPoints(); + has_message_ = false; + PrintWarning("No messages received."); + + odometry_sub_.reset(); + + topic_ = topic; + if (!topic.empty()) + { + odometry_sub_ = node_->create_subscription(topic_, rclcpp::QoS(1), + std::bind(&OdometryPlugin::odometryCallback, this, std::placeholders::_1)); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void OdometryPlugin::odometryCallback( + const nav_msgs::msg::Odometry::SharedPtr odometry) + { + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + // Note that unlike some plugins, this one does not store nor rely on the + // source_frame_ member variable. This one can potentially store many + // messages with different source frames, so we need to store and transform + // them individually. + StampedPoint stamped_point; + stamped_point.stamp = odometry->header.stamp; + stamped_point.source_frame = odometry->header.frame_id; + + stamped_point.point = tf2::Vector3(odometry->pose.pose.position.x, + odometry->pose.pose.position.y, + odometry->pose.pose.position.z); + + stamped_point.orientation = tf2::Quaternion( + odometry->pose.pose.orientation.x, + odometry->pose.pose.orientation.y, + odometry->pose.pose.orientation.z, + odometry->pose.pose.orientation.w); + + if ( ui_.show_covariance->isChecked() ) + { + tf2::Matrix3x3 tf_cov = + swri_transform_util::GetUpperLeft(odometry->pose.covariance); + + if (tf_cov[0][0] < 100000 && tf_cov[1][1] < 100000) + { + cv::Mat cov_matrix_3d(3, 3, CV_32FC1); + for (int32_t r = 0; r < 3; r++) + { + for (int32_t c = 0; c < 3; c++) + { + cov_matrix_3d.at(r, c) = tf_cov[r][c]; + } + } + + cv::Mat cov_matrix_2d = swri_image_util::ProjectEllipsoid(cov_matrix_3d); + + if (!cov_matrix_2d.empty()) + { + stamped_point.cov_points = swri_image_util::GetEllipsePoints( + cov_matrix_2d, stamped_point.point, 3, 32); + + stamped_point.transformed_cov_points = stamped_point.cov_points; + } else { + RCLCPP_ERROR(node_->get_logger(), "Failed to project x, y, z covariance to xy-plane."); + } + } + } + + pushPoint(std::move(stamped_point)); + } + + void OdometryPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void OdometryPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void OdometryPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* OdometryPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool OdometryPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + SetColor(ui_.color->color()); + + return true; + } + + void OdometryPlugin::Draw(double x, double y, double scale) + { + if (ui_.show_covariance->isChecked()) + { + DrawCovariance(); + } + if (DrawPoints(scale)) + { + PrintInfo("OK"); + } + } + + void OdometryPlugin::Paint(QPainter* painter, double x, double y, double scale) + { + // dont render any timestamps if the show_timestamps is set to 0 + int interval = ui_.show_timestamps->value(); + if (interval == 0) + { + return; + } + + QTransform tf = painter->worldTransform(); + QFont font("Helvetica", 10); + painter->setFont(font); + painter->save(); + painter->resetTransform(); + + // set the draw color for the text to be the same as the rest + QPen pen(QBrush(ui_.color->color()), 1); + painter->setPen(pen); + + int counter = 0; // used to alternate between rendering text on some points + for (const StampedPoint& point : points()) + { + // this renders a timestamp every 'interval' points + if (point.transformed && counter % interval == 0) + { + QPointF qpoint = tf.map(QPointF(point.transformed_point.getX(), + point.transformed_point.getY())); + QString time; + time.setNum(point.stamp.seconds(), 'g', 12); + painter->drawText(qpoint, time); + } + counter++; + } + + painter->restore(); + } + + void OdometryPlugin::LoadConfig(const YAML::Node& node, + const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(topic.c_str()); + } + + if (node["color"]) + { + std::string color = node["color"].as(); + QColor qcolor(color.c_str()); + SetColor(qcolor); + ui_.color->setColor(qcolor); + } + + if (node["draw_style"]) + { + std::string draw_style; + draw_style = node["draw_style"].as(); + + if (draw_style == "lines") + { + ui_.drawstyle->setCurrentIndex(0); + SetDrawStyle( LINES ); + } else if (draw_style == "points") { + ui_.drawstyle->setCurrentIndex(1); + SetDrawStyle( POINTS ); + } else if (draw_style == "arrows") { + ui_.drawstyle->setCurrentIndex(2); + SetDrawStyle( ARROWS ); + } + } + + if (node["position_tolerance"]) + { + double position_tolerance = node["position_tolerance"].as(); + ui_.positiontolerance->setValue(position_tolerance); + PositionToleranceChanged(position_tolerance); + } + + if (node["buffer_size"]) + { + int buffer_size = node["buffer_size"].as(); + ui_.buffersize->setValue(buffer_size); + BufferSizeChanged(buffer_size); + } + + if (node["show_covariance"]) + { + bool show_covariance = node["show_covariance"].as(); + ui_.show_covariance->setChecked(show_covariance); + CovariancedToggled(show_covariance); + } + + if (node["show_all_covariances"]) + { + bool show_all_covariances = node["show_all_covariances"].as(); + ui_.show_all_covariances->setChecked(show_all_covariances); + ShowAllCovariancesToggled(show_all_covariances); + } + + if (node["show_laps"]) + { + bool show_laps = node["show_laps"].as(); + ui_.show_laps->setChecked(show_laps); + LapToggled(show_laps); + } + + if (node["static_arrow_sizes"]) + { + bool static_arrow_sizes = node["static_arrow_sizes"].as(); + ui_.static_arrow_sizes->setChecked(static_arrow_sizes); + SetStaticArrowSizes(static_arrow_sizes); + } + + if (node["arrow_size"]) + { + int arrow_size = node["arrow_size"].as(); + ui_.arrow_size->setValue(arrow_size); + SetArrowSize(arrow_size); + } + + if (node["show_timestamps"]) + { + ui_.show_timestamps->setValue(node["show_timestamps"].as()); + } + + TopicEdited(); + } + + void OdometryPlugin::SaveConfig(YAML::Emitter& emitter, + const std::string& path) + { + std::string topic = ui_.topic->text().toStdString(); + emitter << YAML::Key << "topic" << YAML::Value << topic; + + std::string color = ui_.color->color().name().toStdString(); + emitter << YAML::Key << "color" << YAML::Value << color; + + std::string draw_style = ui_.drawstyle->currentText().toStdString(); + emitter << YAML::Key << "draw_style" << YAML::Value << draw_style; + + emitter << YAML::Key << "position_tolerance" << + YAML::Value << positionTolerance(); + + emitter << YAML::Key << "buffer_size" << YAML::Value << bufferSize(); + + bool show_laps = ui_.show_laps->isChecked(); + emitter << YAML::Key << "show_laps" << YAML::Value << show_laps; + + bool show_covariance = ui_.show_covariance->isChecked(); + emitter << YAML::Key << "show_covariance" << YAML::Value << show_covariance; + + bool show_all_covariances = ui_.show_all_covariances->isChecked(); + emitter << YAML::Key << "show_all_covariances" << YAML::Value << show_all_covariances; + + emitter << YAML::Key + << "static_arrow_sizes" + << YAML::Value + << ui_.static_arrow_sizes->isChecked(); + + emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value(); + + emitter << YAML::Key << "show_timestamps" << YAML::Value << ui_.show_timestamps->value(); + } +} // namespace mapviz_plugins + + diff --git a/mapviz_plugins/src/path_plugin.cpp b/mapviz_plugins/src/path_plugin.cpp new file mode 100644 index 000000000..8c5e78bae --- /dev/null +++ b/mapviz_plugins/src/path_plugin.cpp @@ -0,0 +1,211 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include + +// ROS libraries +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::PathPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + PathPlugin::PathPlugin() + : PointDrawingPlugin() + , ui_() + , config_widget_(new QWidget()) + , has_message_(false) + { + ui_.setupUi(config_widget_); + ui_.path_color->setColor(Qt::green); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic())); + connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited())); + connect(ui_.path_color, SIGNAL(colorEdited(const QColor&)), this, + SLOT(SetColor(const QColor&))); + } + + void PathPlugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic(node_, "nav_msgs/msg/Path"); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void PathPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + ClearPoints(); + has_message_ = false; + PrintWarning("No messages received."); + + path_sub_.reset(); + + topic_ = topic; + if (!topic.empty()) + { + path_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&PathPlugin::pathCallback, this, std::placeholders::_1) + ); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void PathPlugin::pathCallback(const nav_msgs::msg::Path::SharedPtr path) + { + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + ClearPoints(); + + for (unsigned int i = 0; i < path->poses.size(); i++) + { + StampedPoint stamped_point; + stamped_point.stamp = path->header.stamp; + stamped_point.source_frame = path->header.frame_id; + stamped_point.point = tf2::Vector3(path->poses[i].pose.position.x, + path->poses[i].pose.position.y, 0); + + pushPoint( stamped_point ); + } + } + + void PathPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void PathPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void PathPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* PathPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool PathPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + DrawIcon(); + return true; + } + + void PathPlugin::Draw(double x, double y, double scale) + { + bool lines; + bool points; + QColor old_color = ui_.path_color->color(); + QColor color = old_color.darker(200); + SetDrawStyle( LINES ); + lines = DrawPoints(scale); + SetColor(color); + SetDrawStyle( POINTS ); + points = DrawPoints(scale); + SetColor(old_color); + if (lines && points) + { + PrintInfo("OK"); + } + } + + void PathPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(topic.c_str()); + TopicEdited(); + } + + if (node["color"]) + { + std::string color = node["color"].as(); + QColor qcolor(color.c_str()); + SetColor(qcolor); + ui_.path_color->setColor(qcolor); + } + } + + void PathPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + std::string topic = ui_.topic->text().toStdString(); + emitter << YAML::Key << "topic" << YAML::Value << topic; + + std::string color = ui_.path_color->color().name().toStdString(); + emitter << YAML::Key << "color" << YAML::Value << color; + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/placeable_window_proxy.cpp b/mapviz_plugins/src/placeable_window_proxy.cpp new file mode 100644 index 000000000..7ba0f216a --- /dev/null +++ b/mapviz_plugins/src/placeable_window_proxy.cpp @@ -0,0 +1,365 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +namespace mapviz_plugins +{ +PlaceableWindowProxy::PlaceableWindowProxy() + : QObject() + , target_(nullptr) + , visible_(true) + , has_cursor_(false) + , state_(INACTIVE) + , win_resize_timer_(-1) +{ +} + +PlaceableWindowProxy::~PlaceableWindowProxy() +{ + if (target_) + { + target_->removeEventFilter(this); + } +} + +void PlaceableWindowProxy::setContainer(QWidget *target) +{ + if (target_) + { + target_->removeEventFilter(this); + } + + target_ = target; + + if (target_) + { + target_->installEventFilter(this); + } +} + +QRect PlaceableWindowProxy::rect() const +{ + return rect_.toRect(); +} + +void PlaceableWindowProxy::setRect(const QRect &rect) +{ + rect_ = QRectF(rect); + state_ = INACTIVE; +} + +void PlaceableWindowProxy::setVisible(bool visible) +{ + if (visible == visible_) + { + return; + } + + visible_ = visible; + + if (!visible_ && state_ != INACTIVE) + { + if (has_cursor_) + { + QApplication::restoreOverrideCursor(); + has_cursor_ = false; + } + state_ = INACTIVE; + } +} + +bool PlaceableWindowProxy::eventFilter(QObject *, QEvent *event) +{ + // This should never happen, but doesn't hurt to be defensive. + if (!target_) + { + return false; + } + + if (!visible_) + { + return false; + } + + switch (event->type()) + { + case QEvent::MouseButtonPress: + return handleMousePress(dynamic_cast(event)); + case QEvent::MouseButtonRelease: + return handleMouseRelease(dynamic_cast(event)); + case QEvent::MouseMove: + return handleMouseMove(dynamic_cast(event)); + case QEvent::Resize: + return handleResize(dynamic_cast(event)); + default: + return false; + } +} + +bool PlaceableWindowProxy::handleMousePress(QMouseEvent *event) +{ + if (!visible_) + { + return false; + } + + if (!rect_.contains(event->pos())) + { + // We don't care about anything outside the rect. + return false; + } + + if (state_ != INACTIVE) + { + // We're already doing something, so we don't want to enter + // another state. But we also don't want someone else to start + // doing something, so we filter out the press. + return true; + } + + if (event->button() == Qt::LeftButton) + { + start_rect_ = rect_; + start_point_ = event->pos(); + state_ = getNextState(event->localPos()); + return true; + } + + // Event if we're not doing anything, we want to present a + // consistent interface that says "this region is belongs to me", so + // we filter out events. + return true; +} + +bool PlaceableWindowProxy::handleMouseRelease(QMouseEvent *event) +{ + if (!visible_) + { + return false; + } + + if (state_ == INACTIVE) + { + return false; + } + + if (event->button() == Qt::LeftButton) + { + state_ = INACTIVE; + return true; + } + + return false; +} + +bool PlaceableWindowProxy::handleMouseMove(QMouseEvent *event) +{ + if (!visible_) + { + return false; + } + + if (state_ == INACTIVE) + { + if (!rect_.contains(event->localPos())) + { + if (has_cursor_) + { + QApplication::restoreOverrideCursor(); + has_cursor_ = false; + } + return false; + } + + // The mouse cursor is over the rect, so we're going to change the + // cursor to indicate the state the user would enter by clicking. + + Qt::CursorShape shape; + switch(getNextState(event->localPos())) + { + case MOVE_TOP_LEFT: + case MOVE_BOTTOM_RIGHT: + shape = Qt::SizeFDiagCursor; + break; + case MOVE_TOP_RIGHT: + case MOVE_BOTTOM_LEFT: + shape = Qt::SizeBDiagCursor; + break; + default: + shape = Qt::SizeAllCursor; + } + + if (has_cursor_) + { + QApplication::changeOverrideCursor(QCursor(shape)); + } else { + QApplication::setOverrideCursor(QCursor(shape)); + has_cursor_ = true; + } + + return true; + } + + QPointF dp = event->localPos() - start_point_; + + // todo: enforce minimum size & constrain aspect ratio for resizes. + if (state_ == MOVE_ALL) + { + rect_ = start_rect_.translated(dp); + } else if (state_ == MOVE_TOP_LEFT) { + rect_ = resizeHelper(start_rect_, + start_rect_.bottomRight(), + start_rect_.topLeft(), + event->localPos()); + rect_.moveBottomRight(start_rect_.bottomRight()); + } else if (state_ == MOVE_BOTTOM_LEFT) { + rect_ = resizeHelper(start_rect_, + start_rect_.topRight(), + start_rect_.bottomLeft(), + event->localPos()); + rect_.moveTopRight(start_rect_.topRight()); + } else if (state_ == MOVE_BOTTOM_RIGHT) { + rect_ = resizeHelper(start_rect_, + start_rect_.topLeft(), + start_rect_.bottomRight(), + event->localPos()); + rect_.moveTopLeft(start_rect_.topLeft()); + } else if (state_ == MOVE_TOP_RIGHT) { + rect_ = resizeHelper(start_rect_, + start_rect_.bottomLeft(), + start_rect_.topRight(), + event->localPos()); + rect_.moveBottomLeft(start_rect_.bottomLeft()); + } else { + qWarning("Unhandled state in PlaceableWindowProxy: %d", state_); + } + + return true; +} + +QRectF PlaceableWindowProxy::resizeHelper(const QRectF &rect, + const QPointF &p1, + const QPointF &p2, + const QPointF &p3) const +{ + QPointF v1 = p2 - p1; + QPointF v2 = p3 - p1; + + double d = v1.x()*v2.y() - v1.y()*v2.x(); + if (d < 0) + { + double new_width = std::abs(p3.x() - p1.x()); + if (new_width < 10) + { + new_width = 10; + } + + double new_height = rect.height() / rect.width() * new_width; + return QRectF(0, 0, new_width, new_height); + } else { + double new_height = std::abs(p3.y() - p1.y()); + if (new_height < 10) + { + new_height = 10; + } + + double new_width = rect.width() / rect.height() * new_height; + return QRectF(0, 0, new_width, new_height); + } +} + + +bool PlaceableWindowProxy::handleResize(QResizeEvent *event) +{ + // We always want to pass the resize event along to other widgets. + return false; +} + +void PlaceableWindowProxy::timerEvent(QTimerEvent *event) +{ + if (event->timerId() == win_resize_timer_) + { + killTimer(win_resize_timer_); + win_resize_timer_ = -1; + if (target_) + { + winResize(target_->size()); + } + } +} + +void PlaceableWindowProxy::rectResize(int dx, int dy) +{ +} + +void PlaceableWindowProxy::winResize(const QSize &size) +{ +} + +PlaceableWindowProxy::State PlaceableWindowProxy::getNextState( + const QPointF &pt) const +{ + if (!rect_.contains(pt)) + { + return INACTIVE; + } + + const double threshold = 10.0; + bool near_left = std::fabs(pt.x() - rect_.left()) < threshold; + bool near_top = std::fabs(pt.y() - rect_.top()) < threshold; + bool near_right = std::fabs(rect_.right() - pt.x()) < threshold; + bool near_bottom = std::fabs(rect_.bottom() - pt.y()) < threshold; + + if (near_top && near_left) + { + return MOVE_TOP_LEFT; + } else if (near_top && near_right) { + return MOVE_TOP_RIGHT; + } else if (near_bottom && near_left) { + return MOVE_BOTTOM_LEFT; + } else if (near_bottom && near_right) { + return MOVE_BOTTOM_RIGHT; + } else { + return MOVE_ALL; + } +} +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/plan_route_plugin.cpp b/mapviz_plugins/src/plan_route_plugin.cpp new file mode 100644 index 000000000..d31325b9b --- /dev/null +++ b/mapviz_plugins/src/plan_route_plugin.cpp @@ -0,0 +1,497 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include +#include +#include +#include +#include +#include + +// ROS libraries +#include + +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::PlanRoutePlugin, mapviz::MapvizPlugin) + +using namespace std::chrono_literals; + +namespace mnm = marti_nav_msgs; +namespace sru = swri_route_util; +namespace stu = swri_transform_util; + +namespace mapviz_plugins +{ + PlanRoutePlugin::PlanRoutePlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , map_canvas_(nullptr) + , failed_service_(false) + , selected_point_(-1) + , is_mouse_down_(false) + , mouse_down_time_(0) + , max_ms_(Q_INT64_C(500)) + , max_distance_(2.0) + { + ui_.setupUi(config_widget_); + + ui_.color->setColor(Qt::green); + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + QObject::connect(ui_.service, SIGNAL(editingFinished()), this, + SLOT(PlanRoute())); + QObject::connect(ui_.publish, SIGNAL(clicked()), this, + SLOT(PublishRoute())); + QObject::connect(ui_.clear, SIGNAL(clicked()), this, + SLOT(Clear())); + QObject::connect(this, + SIGNAL(VisibleChanged(bool)), + this, + SLOT(VisibilityChanged(bool))); + } + + PlanRoutePlugin::~PlanRoutePlugin() + { + if (map_canvas_) + { + map_canvas_->removeEventFilter(this); + } + } + + void PlanRoutePlugin::VisibilityChanged(bool visible) + { + if (visible) + { + map_canvas_->installEventFilter(this); + } + else + { + map_canvas_->removeEventFilter(this); + } + } + + void PlanRoutePlugin::PublishRoute() + { + if (route_preview_) + { + if (route_topic_ != ui_.topic->text().toStdString()) + { + route_topic_ = ui_.topic->text().toStdString(); + route_pub_.reset(); + route_pub_ = node_->create_publisher( + route_topic_, + rclcpp::QoS(1)); + } + + route_pub_->publish(*route_preview_->toMsgPtr()); + } + } + + void PlanRoutePlugin::PlanRoute() + { + route_preview_ = sru::RoutePtr(); + bool start_from_vehicle = ui_.start_from_vehicle->isChecked(); + if (waypoints_.size() + start_from_vehicle < 2 || !Visible()) + { + return; + } + + std::string service = ui_.service->text().toStdString(); + if (service.empty()) + { + PrintError("Service name may not be empty."); + return; + } + auto client = node_->create_client(service); + client->wait_for_service(1ms); + + if (!client->service_is_ready()) + { + PrintError("Service is unavailable."); + return; + } + + auto plan_route = std::make_shared(); + + plan_route->header.frame_id = swri_transform_util::_wgs84_frame; + plan_route->header.stamp = node_->now(); + plan_route->plan_from_vehicle = static_cast(start_from_vehicle); + plan_route->waypoints = waypoints_; + + PrintInfo("Sending route..."); + auto result = client->async_send_request(plan_route, + std::bind(&PlanRoutePlugin::ClientCallback, this, std::placeholders::_1)); + } + + void PlanRoutePlugin::ClientCallback( + rclcpp::Client::SharedFuture future) + { + RCLCPP_ERROR(node_->get_logger(), "Request callback happened"); + const auto& result = future.get(); + if (future.valid()) + { + if (result->success) + { + PrintInfo("OK"); + route_preview_ = std::make_shared(result->route); + failed_service_ = false; + } else { + PrintError(result->message); + failed_service_ = true; + } + } else { + PrintError("Error calling PlanRoute service"); + failed_service_ = true; + } + } + + void PlanRoutePlugin::Retry() + { + PlanRoute(); + } + + void PlanRoutePlugin::Clear() + { + waypoints_.clear(); + route_preview_ = sru::RoutePtr(); + } + + void PlanRoutePlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message, 1.0); + } + + void PlanRoutePlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message, 1.0); + } + + void PlanRoutePlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message, 1.0); + } + + QWidget* PlanRoutePlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool PlanRoutePlugin::Initialize(QGLWidget* canvas) + { + map_canvas_ = dynamic_cast(canvas); + map_canvas_->installEventFilter(this); + + retry_timer_ = node_->create_wall_timer(1000ms, [this](){Retry();}); + + initialized_ = true; + return true; + } + + bool PlanRoutePlugin::eventFilter(QObject *object, QEvent* event) + { + switch (event->type()) + { + case QEvent::MouseButtonPress: + return handleMousePress(dynamic_cast(event)); + case QEvent::MouseButtonRelease: + return handleMouseRelease(dynamic_cast(event)); + case QEvent::MouseMove: + return handleMouseMove(dynamic_cast(event)); + default: + return false; + } + } + + bool PlanRoutePlugin::handleMousePress(QMouseEvent* event) + { + selected_point_ = -1; + int closest_point = 0; + double closest_distance = std::numeric_limits::max(); + + QPointF point = event->localPos(); + stu::Transform transform; + if (tf_manager_->GetTransform(target_frame_, stu::_wgs84_frame, transform)) + { + for (size_t i = 0; i < waypoints_.size(); i++) + { + tf2::Vector3 waypoint( + waypoints_[i].position.x, + waypoints_[i].position.y, + 0.0); + waypoint = transform * waypoint; + + QPointF transformed = + map_canvas_->FixedFrameToMapGlCoord(QPointF(waypoint.x(), waypoint.y())); + + double distance = QLineF(transformed, point).length(); + + if (distance < closest_distance) + { + closest_distance = distance; + closest_point = static_cast(i); + } + } + } + + if (event->button() == Qt::LeftButton) + { + if (closest_distance < 15) + { + selected_point_ = closest_point; + return true; + } else { + is_mouse_down_ = true; + mouse_down_pos_ = event->localPos(); + mouse_down_time_ = QDateTime::currentMSecsSinceEpoch(); + return false; + } + } else if (event->button() == Qt::RightButton) { + if (closest_distance < 15) + { + waypoints_.erase(waypoints_.begin() + closest_point); + PlanRoute(); + return true; + } + } + + return false; + } + + bool PlanRoutePlugin::handleMouseRelease(QMouseEvent* event) + { + QPointF point = event->localPos(); + if (selected_point_ >= 0 && static_cast(selected_point_) < waypoints_.size()) + { + stu::Transform transform; + if (tf_manager_->GetTransform(stu::_wgs84_frame, target_frame_, transform)) + { + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + position = transform * position; + waypoints_[selected_point_].position.x = position.x(); + waypoints_[selected_point_].position.y = position.y(); + PlanRoute(); + } + + selected_point_ = -1; + return true; + } else if (is_mouse_down_) { + qreal distance = QLineF(mouse_down_pos_, point).length(); + qint64 msecsDiff = QDateTime::currentMSecsSinceEpoch() - mouse_down_time_; + + // Only fire the event if the mouse has moved less than the maximum distance + // and was held for shorter than the maximum time.. This prevents click + // events from being fired if the user is dragging the mouse across the map + // or just holding the cursor in place. + if (msecsDiff < max_ms_ && distance <= max_distance_) + { + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + + stu::Transform transform; + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + if (tf_manager_->GetTransform(stu::_wgs84_frame, target_frame_, transform)) + { + position = transform * position; + + geometry_msgs::msg::Pose pose; + pose.position.x = position.x(); + pose.position.y = position.y(); + waypoints_.push_back(pose); + PlanRoute(); + } + } + } + is_mouse_down_ = false; + + return false; + } + + bool PlanRoutePlugin::handleMouseMove(QMouseEvent* event) + { + if (selected_point_ >= 0 && static_cast(selected_point_) < waypoints_.size()) + { + QPointF point = event->localPos(); + stu::Transform transform; + if (tf_manager_->GetTransform(stu::_wgs84_frame, target_frame_, transform)) + { + QPointF transformed = map_canvas_->MapGlCoordToFixedFrame(point); + tf2::Vector3 position(transformed.x(), transformed.y(), 0.0); + position = transform * position; + waypoints_[selected_point_].position.y = position.y(); + waypoints_[selected_point_].position.x = position.x(); + PlanRoute(); + } + + return true; + } + return false; + } + + void PlanRoutePlugin::Draw(double x, double y, double scale) + { + stu::Transform transform; + if (tf_manager_->GetTransform(target_frame_, stu::_wgs84_frame, transform)) + { + if (!failed_service_) + { + if (route_preview_) + { + sru::Route route = *route_preview_; + sru::transform(route, transform, target_frame_); + + glLineWidth(2); + const QColor color = ui_.color->color(); + glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0); + glBegin(GL_LINE_STRIP); + + for (auto & point : route.points) + { + glVertex2d(point.position().x(), point.position().y()); + } + + glEnd(); + } + } + + // Draw waypoints + + glPointSize(20); + glColor4f(0.0, 1.0, 1.0, 1.0); + glBegin(GL_POINTS); + + for (auto & waypoint : waypoints_) + { + tf2::Vector3 point(waypoint.position.x, waypoint.position.y, 0); + point = transform * point; + glVertex2d(point.x(), point.y()); + } + glEnd(); + } else { + PrintError("Failed to transform."); + } + } + + void PlanRoutePlugin::Paint(QPainter* painter, double x, double y, double scale) + { + painter->save(); + painter->resetTransform(); + + QPen pen(QBrush(QColor(Qt::darkCyan).darker()), 1); + painter->setPen(pen); + painter->setFont(QFont("DejaVu Sans Mono", 7)); + + stu::Transform transform; + if (tf_manager_->GetTransform(target_frame_, stu::_wgs84_frame, transform)) + { + for (size_t i = 0; i < waypoints_.size(); i++) + { + tf2::Vector3 point(waypoints_[i].position.x, waypoints_[i].position.y, 0); + point = transform * point; + QPointF gl_point = map_canvas_->FixedFrameToMapGlCoord(QPointF(point.x(), point.y())); + QPointF corner(gl_point.x() - 20, gl_point.y() - 20); + QRectF rect(corner, QSizeF(40, 40)); + painter->drawText( + rect, + Qt::AlignHCenter | Qt::AlignVCenter, + QString::fromStdString(std::to_string(i + 1))); + } + } + + painter->restore(); + } + + void PlanRoutePlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["route_topic"]) + { + std::string route_topic = node["route_topic"].as(); + ui_.topic->setText(route_topic.c_str()); + } + if (node["color"]) + { + std::string color = node["color"].as(); + ui_.color->setColor(QColor(color.c_str())); + } + if (node["service"]) + { + std::string service = node["service"].as(); + ui_.service->setText(service.c_str()); + } + if (node["start_from_vehicle"]) + { + bool start_from_vehicle = node["start_from_vehicle"].as(); + ui_.start_from_vehicle->setChecked(start_from_vehicle); + } + + PlanRoute(); + } + + void PlanRoutePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + std::string route_topic = ui_.topic->text().toStdString(); + emitter << YAML::Key << "route_topic" << YAML::Value << route_topic; + + std::string color = ui_.color->color().name().toStdString(); + emitter << YAML::Key << "color" << YAML::Value << color; + + std::string service = ui_.service->text().toStdString(); + emitter << YAML::Key << "service" << YAML::Value << service; + + bool start_from_vehicle = ui_.start_from_vehicle->isChecked(); + emitter << YAML::Key << "start_from_vehicle" << YAML::Value << start_from_vehicle; + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/point_click_publisher_plugin.cpp b/mapviz_plugins/src/point_click_publisher_plugin.cpp new file mode 100644 index 000000000..95e94cbee --- /dev/null +++ b/mapviz_plugins/src/point_click_publisher_plugin.cpp @@ -0,0 +1,254 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include +#include +#include + +// Declare plugin +#include + +// C++ Standard Libraries +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::PointClickPublisherPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + PointClickPublisherPlugin::PointClickPublisherPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , canvas_(nullptr) + { + ui_.setupUi(config_widget_); + + connect(&click_filter_, SIGNAL(pointClicked(const QPointF&)), + this, SLOT(pointClicked(const QPointF&))); + connect(ui_.topic, SIGNAL(textEdited(const QString&)), + this, SLOT(topicChanged(const QString&))); + + frame_timer_.start(1000); + connect(&frame_timer_, SIGNAL(timeout()), this, SLOT(updateFrames())); + } + + PointClickPublisherPlugin::~PointClickPublisherPlugin() + { + if (canvas_) + { + canvas_->removeEventFilter(&click_filter_); + } + } + + bool PointClickPublisherPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = dynamic_cast(canvas); + canvas_->installEventFilter(&click_filter_); + + PrintInfo("Ready."); + + return true; + } + + void PointClickPublisherPlugin::Draw(double x, double y, double scale) + { + } + + void PointClickPublisherPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + std::string tmp; + if (node["topic"]) + { + tmp = node["topic"].as(); + ui_.topic->setText(QString(tmp.c_str())); + topicChanged(ui_.topic->text()); + } + + if (node["output_frame"]) + { + tmp = node["output_frame"].as(); + ui_.outputframe->addItem(QString(tmp.c_str())); + } + } + + void PointClickPublisherPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key << "topic" << YAML::Value << ui_.topic->text().toStdString(); + emitter << YAML::Key + << "output_frame" + << YAML::Value + << ui_.outputframe->currentText().toStdString(); + } + + QWidget* PointClickPublisherPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + + void PointClickPublisherPlugin::pointClicked(const QPointF& point) + { + QPointF transformed = canvas_->MapGlCoordToFixedFrame(point); + + std::string output_frame = ui_.outputframe->currentText().toStdString(); + + if (target_frame_ != output_frame) + { + swri_transform_util::Transform tf; + tf2::Vector3 tfPoint(transformed.x(), transformed.y(), 0.0); + if (tf_manager_->GetTransform(output_frame, target_frame_, tf)) + { + tfPoint = tf * tfPoint; + } else { + std::stringstream error; + error << "Unable to find transform from " << target_frame_ << " to " << output_frame << "."; + PrintError(error.str()); + return; + } + transformed.setX(tfPoint.x()); + transformed.setY(tfPoint.y()); + } + + std::unique_ptr stamped = + std::make_unique(); + stamped->header.frame_id = output_frame; + stamped->header.stamp = node_->get_clock()->now(); + stamped->point.x = transformed.x(); + stamped->point.y = transformed.y(); + stamped->point.z = 0.0; + + std::stringstream ss; + ss << "Point in " << output_frame.c_str() << ": " << transformed.x() << "," << transformed.y(); + + // Only publish if this plugin is visible + if(this->Visible()) + { + point_publisher_->publish(*stamped); + } + else + { + ss << " (but not publishing since plugin is hidden)"; + } + + PrintInfo(ss.str()); + } + + void PointClickPublisherPlugin::SetNode(rclcpp::Node& node) + { + mapviz::MapvizPlugin::SetNode(node); + + // We override this method so that we can initialize our publisher after + // our node has been set, ensuring that it's in mapviz's namespace. + topicChanged(ui_.topic->text()); + } + + void PointClickPublisherPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void PointClickPublisherPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void PointClickPublisherPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + + void PointClickPublisherPlugin::topicChanged(const QString& topic) + { + std::stringstream ss; + ss << "Publishing points to topic: " << topic.toStdString().c_str(); + PrintInfo(ss.str()); + + if (!topic.isEmpty()) + { + point_publisher_ = node_->create_publisher( + topic.toStdString(), rclcpp::QoS(1000)); + } + } + + void PointClickPublisherPlugin::updateFrames() + { + std::vector frames; + tf_buf_->_getFrameStrings(frames); + + bool supports_wgs84 = tf_manager_->SupportsTransform( + swri_transform_util::_local_xy_frame, + swri_transform_util::_wgs84_frame); + + if (supports_wgs84) + { + frames.push_back(swri_transform_util::_wgs84_frame); + } + + if (ui_.outputframe->count() >= 0 && + static_cast(ui_.outputframe->count()) == frames.size()) + { + bool changed = false; + for (size_t i = 0; i < frames.size(); i++) + { + if (frames[i] != ui_.outputframe->itemText(static_cast(i)).toStdString()) + { + changed = true; + } + } + + if (!changed) + return; + } + + std::string current_output = ui_.outputframe->currentText().toStdString(); + + ui_.outputframe->clear(); + for (auto & frame : frames) + { + ui_.outputframe->addItem(frame.c_str()); + } + + if (!current_output.empty()) + { + int index = ui_.outputframe->findText(current_output.c_str()); + if (index < 0) + { + ui_.outputframe->addItem(current_output.c_str()); + } + + index = ui_.outputframe->findText(current_output.c_str()); + ui_.outputframe->setCurrentIndex(index); + } + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/point_drawing_plugin.cpp b/mapviz_plugins/src/point_drawing_plugin.cpp new file mode 100644 index 000000000..53169e01c --- /dev/null +++ b/mapviz_plugins/src/point_drawing_plugin.cpp @@ -0,0 +1,621 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +#include +#include +#include + +#include + +#include + +#include +#include +#include + +namespace mapviz_plugins +{ + PointDrawingPlugin::PointDrawingPlugin() + : MapvizPlugin() + , arrow_size_(25) + , draw_style_(LINES) + , position_tolerance_(0.0) + , buffer_size_(0) + , covariance_checked_(false) + , show_all_covariances_checked_(false) + , new_lap_(true) + , lap_checked_(false) + , buffer_holder_(false) + , scale_(1.0) + , static_arrow_sizes_(false) + , got_begin_(false) + { + QObject::connect(this, + SIGNAL(TargetFrameChanged(const std::string&)), + this, + SLOT(ResetTransformedPoints())); + } + + void PointDrawingPlugin::ClearHistory() + { + RCLCPP_INFO(node_->get_logger(), "PointDrawingPlugin::ClearHistory()"); + points_.clear(); + } + + void PointDrawingPlugin::DrawIcon() + { + if (icon_) + { + QPixmap icon(16, 16); + icon.fill(Qt::transparent); + + QPainter painter(&icon); + painter.setRenderHint(QPainter::Antialiasing, true); + + QPen pen(color_); + + if (draw_style_ == POINTS) + { + pen.setWidth(7); + pen.setCapStyle(Qt::RoundCap); + painter.setPen(pen); + painter.drawPoint(8, 8); + } else if (draw_style_ == LINES) { + pen.setWidth(3); + pen.setCapStyle(Qt::FlatCap); + painter.setPen(pen); + painter.drawLine(1, 14, 14, 1); + } else if (draw_style_ == ARROWS) { + pen.setWidth(2); + pen.setCapStyle(Qt::SquareCap); + painter.setPen(pen); + painter.drawLine(2, 13, 13, 2); + painter.drawLine(13, 2, 13, 8); + painter.drawLine(13, 2, 7, 2); + } + + icon_->SetPixmap(icon); + } + } + + void PointDrawingPlugin::SetArrowSize(int arrowSize) + { + arrow_size_ = arrowSize; + ResetTransformedPoints(); + } + + void PointDrawingPlugin::SetDrawStyle(QString style) + { + if (style == "lines") + { + draw_style_ = LINES; + } else if (style == "points") { + draw_style_ = POINTS; + } else if (style == "arrows") { + draw_style_ = ARROWS; + } + ResetTransformedPoints(); + DrawIcon(); + } + + void PointDrawingPlugin::SetDrawStyle(PointDrawingPlugin::DrawStyle style) + { + draw_style_ = style; + DrawIcon(); + } + + void PointDrawingPlugin::SetStaticArrowSizes(bool isChecked) + { + static_arrow_sizes_ = isChecked; + ResetTransformedPoints(); + } + + void PointDrawingPlugin::PositionToleranceChanged(double value) + { + position_tolerance_ = value; + } + + void PointDrawingPlugin::LapToggled(bool checked) + { + lap_checked_ = checked; + } + + void PointDrawingPlugin::CovariancedToggled(bool checked) + { + covariance_checked_ = checked; + } + + void PointDrawingPlugin::ShowAllCovariancesToggled(bool checked) + { + show_all_covariances_checked_ = checked; + } + + void PointDrawingPlugin::ResetTransformedPoints() + { + for (std::deque& lap : laps_) + { + for (StampedPoint& point : lap) + { + point.transformed = false; + } + } + for (StampedPoint& point : points_) + { + point.transformed = false; + } + Transform(); + } + + void PointDrawingPlugin::pushPoint(StampedPoint point) + { + cur_point_ = point; + + if (points_.empty() || + (point.point.distance(points_.back().point)) >= + (position_tolerance_)) + { + points_.push_back(std::move(point)); + } + + if (buffer_size_ > 0) + { + while (static_cast(points_.size()) >= buffer_size_) + { + points_.pop_front(); + } + } + } + + void PointDrawingPlugin::ClearPoints() + { + points_.clear(); + } + + double PointDrawingPlugin::bufferSize() const + { + if (!lap_checked_) + { + return buffer_size_; + } else { + return buffer_holder_; + } + } + + double PointDrawingPlugin::positionTolerance() const + { + return position_tolerance_; + } + + const std::deque &PointDrawingPlugin::points() const + { + return points_; + } + + void PointDrawingPlugin::BufferSizeChanged(int value) + { + buffer_size_ = value; + + if (buffer_size_ > 0) + { + while (static_cast(points_.size()) >= buffer_size_) + { + points_.pop_front(); + } + } + } + + bool PointDrawingPlugin::DrawPoints(double scale) + { + bool transformed = true; + + if (scale_ != scale && draw_style_ == ARROWS && static_arrow_sizes_) { + ResetTransformedPoints(); + } + scale_ = scale; + if (lap_checked_) { + CollectLaps(); + + if (draw_style_ == ARROWS) { + transformed &= DrawLapsArrows(); + } else { + transformed &= DrawLaps(); + } + } else if (buffer_size_ == INT_MAX) { + buffer_size_ = buffer_holder_; + laps_.clear(); + got_begin_ = false; + } + if (draw_style_ == ARROWS) { + transformed &= DrawArrows(); + } else { + transformed &= DrawLines(); + } + + return transformed; + } + + void PointDrawingPlugin::CollectLaps() + { + if (!got_begin_) + { + begin_ = cur_point_.point; + points_.clear(); + buffer_holder_ = buffer_size_; + buffer_size_ = INT_MAX; + got_begin_ = true; + } + tf2::Vector3 check = begin_ - cur_point_.point; + if (((std::fabs(check.x()) <= 3) && (std::fabs(check.y()) <= 3)) && + !new_lap_) + { + new_lap_ = true; + if (!points_.empty()) + { + laps_.push_back(points_); + laps_[0].pop_back(); + points_.clear(); + points_.push_back(cur_point_); + } + } + + if (((std::fabs(check.x()) > 25) && (std::fabs(check.y()) > 25)) && + new_lap_) + { + new_lap_ = false; + } + } + + bool PointDrawingPlugin::DrawLines() + { + bool success = cur_point_.transformed; + glColor4d(color_.redF(), color_.greenF(), color_.blueF(), 1.0); + if (draw_style_ == LINES && !points_.empty()) + { + glLineWidth(3); + glBegin(GL_LINE_STRIP); + } else { + glPointSize(6); + glBegin(GL_POINTS); + } + + for (const auto& pt : points_) + { + success &= pt.transformed; + if (pt.transformed) + { + glVertex2d(pt.transformed_point.getX(), pt.transformed_point.getY()); + } + } + + if (cur_point_.transformed) + { + glVertex2d(cur_point_.transformed_point.getX(), + cur_point_.transformed_point.getY()); + } + + glEnd(); + + return success; + } + + bool PointDrawingPlugin::DrawArrow(const StampedPoint& it) + { + if (it.transformed) + { + glVertex2d(it.transformed_point.getX(), + it.transformed_point.getY()); + + glVertex2d(it.transformed_arrow_point.getX(), + it.transformed_arrow_point.getY()); + + glVertex2d(it.transformed_arrow_point.getX(), + it.transformed_arrow_point.getY()); + glVertex2d(it.transformed_arrow_left.getX(), + it.transformed_arrow_left.getY()); + + glVertex2d(it.transformed_arrow_point.getX(), + it.transformed_arrow_point.getY()); + glVertex2d(it.transformed_arrow_right.getX(), + it.transformed_arrow_right.getY()); + return true; + } + return false; + } + + bool PointDrawingPlugin::DrawArrows() + { + bool success = true; + glLineWidth(4); + glBegin(GL_LINES); + glColor4d(color_.redF(), color_.greenF(), color_.blueF(), 0.5); + for (const auto &pt : points_) + { + success &= DrawArrow(pt); + } + + success &= DrawArrow(cur_point_); + + glEnd(); + + return success; + } + + void PointDrawingPlugin::SetColor(const QColor& color) + { + if (color != color_) + { + color_ = color; + DrawIcon(); + } + } + + bool PointDrawingPlugin::TransformPoint(StampedPoint& point) + { + if ( point.transformed ) + { + return true; + } + + swri_transform_util::Transform transform; + if( GetTransform(point.source_frame, point.stamp, transform)) + { + point.transformed_point = transform * point.point; + + if (draw_style_ == ARROWS) + { + tf2::Transform orientation(tf2::Transform(transform.GetOrientation()) * + point.orientation); + + double size = static_cast(arrow_size_); + if (static_arrow_sizes_) + { + size *= scale_; + } else { + size /= 10.0; + } + double arrow_width = size / 5.0; + double head_length = size * 0.75; + + // If quaternion malformed, just draw point instead + const tf2::Quaternion q(point.orientation); + if(std::fabs(q.x()*q.x() + q.y()*q.y() + q.z()*q.z() + q.w()*q.w() - 1) > 0.01) + { + orientation = tf2::Transform(tf2::Transform(transform.GetOrientation())); + arrow_width = 0.0; + head_length = 0.0; + size = 0; + } + + point.transformed_arrow_point = + point.transformed_point + orientation * tf2::Vector3(size, 0.0, 0.0); + point.transformed_arrow_left = + point.transformed_point + orientation * tf2::Vector3(head_length, -arrow_width, 0.0); + point.transformed_arrow_right = + point.transformed_point + orientation * tf2::Vector3(head_length, arrow_width, 0.0); + } + + if (covariance_checked_) + { + for (uint32_t i = 0; i < point.cov_points.size(); i++) + { + point.transformed_cov_points[i] = transform * point.cov_points[i]; + } + } + point.transformed = true; + return true; + } + point.transformed = false; + return false; + } + + void PointDrawingPlugin::Transform() + { + bool transformed = false; + + for (auto &pt : points_) + { + transformed = transformed | TransformPoint(pt); + } + + transformed = transformed | TransformPoint(cur_point_); + if (!laps_.empty()) + { + for (auto &lap : laps_) + { + for (auto &pt : lap) + { + transformed = transformed | TransformPoint(pt); + } + } + } + if (!points_.empty() && !transformed) + { + PrintError("No transform between " + cur_point_.source_frame + " and " + + target_frame_); + } + } + + bool PointDrawingPlugin::DrawLaps() + { + bool transformed = !points_.empty(); + glColor4d(color_.redF(), color_.greenF(), color_.blueF(), 0.5); + glLineWidth(3); + QColor base_color = color_; + + for (size_t i = 0; i < laps_.size(); i++) + { + UpdateColor(base_color, static_cast(i)); + if (draw_style_ == LINES) + { + glLineWidth(3); + glBegin(GL_LINE_STRIP); + } else { + glPointSize(6); + glBegin(GL_POINTS); + } + + for (const auto& pt : laps_[i]) + { + if (pt.transformed) + { + glVertex2d(pt.transformed_point.getX(), + pt.transformed_point.getY()); + } + } + glEnd(); + } + + if (draw_style_ == LINES) + { + glLineWidth(3); + glBegin(GL_LINE_STRIP); + } else { + glPointSize(6); + glBegin(GL_POINTS); + } + + glColor4d(base_color.redF(), base_color.greenF(), base_color.blueF(), 0.5); + + if (!points_.empty()) + { + for (const auto &pt : points_) + { + transformed &= pt.transformed; + if (pt.transformed) + { + glVertex2d(pt.transformed_point.getX(), + pt.transformed_point.getY()); + } + } + } + + glEnd(); + return transformed; + } + + void PointDrawingPlugin::UpdateColor(QColor base_color, int i) + { + int hue = static_cast(color_.hue() + (i + 1.0) * 10.0 * M_PI); + if (hue > 360) + { + hue %= 360; + } + int sat = color_.saturation(); + int v = color_.value(); + base_color.setHsv(hue, sat, v); + glColor4d(base_color.redF(), base_color.greenF(), base_color.blueF(), + 0.5); + } + + void PointDrawingPlugin::DrawCovariance() + { + glLineWidth(4); + + glColor4d(color_.redF(), color_.greenF(), color_.blueF(), 1.0); + + if (show_all_covariances_checked_) + { + for (const auto &pt : points_) + { + if (!pt.transformed || pt.transformed_cov_points.empty()) + { + continue; + } + glBegin(GL_LINE_STRIP); + + for (const auto & transformed_cov_point : pt.transformed_cov_points) + { + glVertex2d(transformed_cov_point.getX(), + transformed_cov_point.getY()); + } + + glVertex2d(pt.transformed_cov_points.front().getX(), + pt.transformed_cov_points.front().getY()); + + glEnd(); + } + } else if (cur_point_.transformed && !cur_point_.transformed_cov_points.empty()) { + glBegin(GL_LINE_STRIP); + + for (auto & transformed_cov_point : cur_point_.transformed_cov_points) + { + glVertex2d(transformed_cov_point.getX(), + transformed_cov_point.getY()); + } + + glVertex2d(cur_point_.transformed_cov_points.front().getX(), + cur_point_.transformed_cov_points.front().getY()); + + glEnd(); + } + } + + bool PointDrawingPlugin::DrawLapsArrows() + { + bool success = !laps_.empty() && !points_.empty(); + glColor4d(color_.redF(), color_.greenF(), color_.blueF(), 0.5); + glLineWidth(2); + QColor base_color = color_; + if (!laps_.empty()) + { + for (size_t i = 0; i < laps_.size(); i++) + { + UpdateColor(base_color, static_cast(i)); + for (const auto &pt : laps_[i]) + { + glBegin(GL_LINE_STRIP); + success &= DrawArrow(pt); + glEnd(); + } + } + glEnd(); + + int hue = static_cast(color_.hue() + laps_.size() * 10.0 * M_PI); + int sat = color_.saturation(); + int v = color_.value(); + base_color.setHsv(hue, sat, v); + glColor4d(base_color.redF(), base_color.greenF(), base_color.blueF(), + 0.5); + } + + if (!points_.empty()) + { + for (const auto& pt : points_) + { + glBegin(GL_LINE_STRIP); + success &= DrawArrow(pt); + glEnd(); + } + } + + return success; + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/pointcloud2_plugin.cpp b/mapviz_plugins/src/pointcloud2_plugin.cpp new file mode 100644 index 000000000..5dd29a7a3 --- /dev/null +++ b/mapviz_plugins/src/pointcloud2_plugin.cpp @@ -0,0 +1,888 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include +#include + +// Boost libraries +#include + +// QT libraries +#include +#include + +// ROS libraries +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include +#include + +// QT Autogenerated +#include "ui_topic_select.h" + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::PointCloud2Plugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + PointCloud2Plugin::PointCloud2Plugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , topic_("") + , alpha_(1.0) + , max_value_(100.0) + , min_value_(0.0) + , point_size_(3) + , buffer_size_(1) + , new_topic_(true) + , has_message_(false) + , num_of_feats_(0) + , need_new_list_(true) + , need_minmax_(false) + { + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + // Initialize color selector colors + ui_.min_color->setColor(Qt::white); + ui_.max_color->setColor(Qt::black); + // Set color transformer choices + ui_.color_transformer->addItem(QString("Flat Color"), QVariant(0)); + + QObject::connect(ui_.selecttopic, + SIGNAL(clicked()), + this, + SLOT(SelectTopic())); + QObject::connect(ui_.buttonResetBuffer, + SIGNAL(clicked()), + this, + SLOT(ClearPointClouds())); + QObject::connect(ui_.topic, + SIGNAL(editingFinished()), + this, + SLOT(TopicEdited())); + QObject::connect(ui_.alpha, + SIGNAL(valueChanged(double)), + this, + SLOT(AlphaEdited(double))); + QObject::connect(ui_.color_transformer, + SIGNAL(currentIndexChanged(int)), + this, + SLOT(ColorTransformerChanged(int))); + QObject::connect(ui_.max_color, + SIGNAL(colorEdited(const QColor &)), + this, + SLOT(UpdateColors())); + QObject::connect(ui_.min_color, + SIGNAL(colorEdited(const QColor &)), + this, + SLOT(UpdateColors())); + QObject::connect(ui_.minValue, + SIGNAL(valueChanged(double)), + this, + SLOT(MinValueChanged(double))); + QObject::connect(ui_.maxValue, + SIGNAL(valueChanged(double)), + this, + SLOT(MaxValueChanged(double))); + QObject::connect(ui_.bufferSize, + SIGNAL(valueChanged(int)), + this, + SLOT(BufferSizeChanged(int))); + QObject::connect(ui_.pointSize, + SIGNAL(valueChanged(int)), + this, + SLOT(PointSizeChanged(int))); + QObject::connect(ui_.use_rainbow, + SIGNAL(stateChanged(int)), + this, + SLOT(UseRainbowChanged(int))); + QObject::connect(ui_.unpack_rgb, + SIGNAL(stateChanged(int)), + this, + SLOT(UseRainbowChanged(int))); + QObject::connect(ui_.use_automaxmin, + SIGNAL(stateChanged(int)), + this, + SLOT(UseAutomaxminChanged(int))); + QObject::connect(ui_.max_color, + SIGNAL(colorEdited(const QColor &)), + this, + SLOT(DrawIcon())); + QObject::connect(ui_.min_color, + SIGNAL(colorEdited( const QColor &)), + this, + SLOT(DrawIcon())); + QObject::connect(this, + SIGNAL(TargetFrameChanged(const std::string&)), + this, + SLOT(ResetTransformedPointClouds())); + QObject::connect(this, + SIGNAL(VisibleChanged(bool)), + this, + SLOT(SetSubscription(bool))); + } + + void PointCloud2Plugin::ClearHistory() + { + RCLCPP_DEBUG(node_->get_logger(), "PointCloud2Plugin::ClearHistory()"); + scans_.clear(); + } + + void PointCloud2Plugin::DrawIcon() + { + if (icon_) + { + QPixmap icon(16, 16); + icon.fill(Qt::transparent); + + QPainter painter(&icon); + painter.setRenderHint(QPainter::Antialiasing, true); + + QPen pen; + pen.setWidth(4); + pen.setCapStyle(Qt::RoundCap); + + pen.setColor(ui_.min_color->color()); + painter.setPen(pen); + painter.drawPoint(2, 13); + + pen.setColor(ui_.min_color->color()); + painter.setPen(pen); + painter.drawPoint(4, 6); + + pen.setColor(ui_.max_color->color()); + painter.setPen(pen); + painter.drawPoint(12, 9); + + pen.setColor(ui_.max_color->color()); + painter.setPen(pen); + painter.drawPoint(13, 2); + + icon_->SetPixmap(icon); + } + } + + void PointCloud2Plugin::ResetTransformedPointClouds() + { + QMutexLocker locker(&scan_mutex_); + for (Scan& scan : scans_) + { + scan.transformed = false; + scan.gl_color.clear(); + scan.gl_point.clear(); + } + } + + void PointCloud2Plugin::ClearPointClouds() + { + QMutexLocker locker(&scan_mutex_); + scans_.clear(); + } + + void PointCloud2Plugin::SetSubscription(bool subscribe) + { + pc2_sub_.reset(); + + if (subscribe && !topic_.empty()) + { + pc2_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(10), + std::bind(&PointCloud2Plugin::PointCloud2Callback, this, std::placeholders::_1) + ); + new_topic_ = true; + need_new_list_ = true; + max_.clear(); + min_.clear(); + } + } + + QColor PointCloud2Plugin::CalculateColor(const StampedPoint& point) + { + float val; + unsigned int color_transformer = + static_cast(ui_.color_transformer->currentIndex()); + unsigned int transformer_index = color_transformer -1; + if (num_of_feats_ > 0 && color_transformer > 0) + { + val = point.features[transformer_index]; + if (need_minmax_) + { + if (val > max_[transformer_index]) + { + max_[transformer_index] = val; + } + + if (val < min_[transformer_index]) + { + min_[transformer_index] = val; + } + } + } else { + // No intensity or (color_transformer == COLOR_FLAT) + return ui_.min_color->color(); + } + + if (ui_.unpack_rgb->isChecked()) + { + uint8_t* pixelColor = reinterpret_cast(&val); + return QColor(pixelColor[2], pixelColor[1], pixelColor[0], 255); + } + + if (max_value_ > min_value_) + { + val = (val - min_value_) / (max_value_ - min_value_); + } + val = std::max(0.0f, std::min(val, 1.0f)); + + if (ui_.use_automaxmin->isChecked()) + { + max_value_ = max_[transformer_index]; + min_value_ = min_[transformer_index]; + } + + if (ui_.use_rainbow->isChecked()) + { // Hue Interpolation + int hue = static_cast(val * 255.0); + return QColor::fromHsl(hue, 255, 127, 255); + } else { + const QColor min_color = ui_.min_color->color(); + const QColor max_color = ui_.max_color->color(); + // RGB Interpolation + int red, green, blue; + red = static_cast(val * max_color.red() + ((1.0 - val) * min_color.red())); + green = static_cast(val * max_color.green() + ((1.0 - val) * min_color.green())); + blue = static_cast(val * max_color.blue() + ((1.0 - val) * min_color.blue())); + return QColor(red, green, blue, 255); + } + } + + inline int32_t findChannelIndex( + const sensor_msgs::msg::PointCloud2::SharedPtr cloud, + const std::string& channel) + { + for (int32_t i = 0; static_cast(i) < cloud->fields.size(); ++i) + { + if (cloud->fields[i].name == channel) + { + return i; + } + } + + return -1; + } + + void PointCloud2Plugin::UpdateColors() + { + { + QMutexLocker locker(&scan_mutex_); + for (Scan& scan : scans_) + { + scan.gl_color.clear(); + scan.gl_color.reserve(scan.points.size()*4); + for (const StampedPoint& point : scan.points) + { + const QColor color = CalculateColor(point); + scan.gl_color.push_back( color.red()); + scan.gl_color.push_back( color.green()); + scan.gl_color.push_back( color.blue()); + scan.gl_color.push_back( static_cast(alpha_ * 255.0 ) ); + } + } + } + canvas_->update(); + } + + void PointCloud2Plugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic( + node_, + "sensor_msgs/msg/PointCloud2"); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + + void PointCloud2Plugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + { + QMutexLocker locker(&scan_mutex_); + scans_.clear(); + } + has_message_ = false; + PrintWarning("No messages received."); + + topic_ = topic; + SetSubscription(this->Visible()); + } + } + + void PointCloud2Plugin::MinValueChanged(double value) + { + min_value_ = value; + UpdateColors(); + } + + void PointCloud2Plugin::MaxValueChanged(double value) + { + max_value_ = value; + UpdateColors(); + } + + void PointCloud2Plugin::BufferSizeChanged(int value) + { + buffer_size_ = (size_t)value; + + if (buffer_size_ > 0) + { + QMutexLocker locker(&scan_mutex_); + while (scans_.size() > buffer_size_) + { + scans_.pop_front(); + } + } + + canvas_->update(); + } + + void PointCloud2Plugin::PointSizeChanged(int value) + { + point_size_ = (size_t)value; + + canvas_->update(); + } + + void PointCloud2Plugin::PointCloud2Callback(const sensor_msgs::msg::PointCloud2::SharedPtr msg) + { + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + // Note that unlike some plugins, this one does not store nor rely on the + // source_frame_ member variable. This one can potentially store many + // messages with different source frames, so we need to store and transform + // them individually. + + Scan scan; + { + // recycle already allocated memory, reusing an old scan + QMutexLocker locker(&scan_mutex_); + if (buffer_size_ > 0 ) + { + if( scans_.size() >= buffer_size_) + { + scan = std::move( scans_.front() ); + } else { + glGenBuffers(1, &scan.color_vbo); + glGenBuffers(1, &scan.point_vbo); + } + while (scans_.size() >= buffer_size_) + { + scans_.pop_front(); + } + } + } + + scan.stamp = msg->header.stamp; + scan.color = QColor::fromRgbF(1.0f, 0.0f, 0.0f, 1.0f); + scan.source_frame = msg->header.frame_id; + scan.transformed = true; + + swri_transform_util::Transform transform; + if (!GetTransform(scan.source_frame, msg->header.stamp, transform)) + { + scan.transformed = false; + PrintError("No transform between " + scan.source_frame + " and " + target_frame_); + return; + } + + int32_t xi = findChannelIndex(msg, "x"); + int32_t yi = findChannelIndex(msg, "y"); + int32_t zi = findChannelIndex(msg, "z"); + + if (xi == -1 || yi == -1 || zi == -1) + { + return; + } + + if (new_topic_) + { + for (auto & field : msg->fields) + { + FieldInfo input; + std::string name = field.name; + + uint32_t offset_value = field.offset; + uint8_t datatype_value = field.datatype; + input.offset = offset_value; + input.datatype = datatype_value; + scan.new_features.insert(std::pair(name, input)); + } + + new_topic_ = false; + num_of_feats_ = scan.new_features.size(); + + max_.resize(num_of_feats_); + min_.resize(num_of_feats_); + + int label = 1; + if (need_new_list_) + { + int new_feature_index = ui_.color_transformer->currentIndex(); + std::map::const_iterator it; + for (it = scan.new_features.begin(); it != scan.new_features.end(); ++it) + { + ui_.color_transformer->removeItem(static_cast(num_of_feats_)); + num_of_feats_--; + } + + for (it = scan.new_features.begin(); it != scan.new_features.end(); ++it) + { + std::string const field = it->first; + if (field == saved_color_transformer_) + { + // The very first time we see a new set of features, that means the + // plugin was just created; if we have a saved value, set the current + // index to that and clear the saved value. + new_feature_index = label; + saved_color_transformer_ = ""; + } + + ui_.color_transformer->addItem(QString::fromStdString(field), QVariant(label)); + num_of_feats_++; + label++; + } + ui_.color_transformer->setCurrentIndex(new_feature_index); + need_new_list_ = false; + } + } + + if (!msg->data.empty()) + { + const uint8_t* ptr = &msg->data.front(); + const uint32_t point_step = msg->point_step; + const uint32_t xoff = msg->fields[xi].offset; + const uint32_t yoff = msg->fields[yi].offset; + const uint32_t zoff = msg->fields[zi].offset; + const size_t num_points = msg->data.size() / point_step; + const size_t num_features = scan.new_features.size(); + scan.points.resize(num_points); + + std::vector field_infos; + field_infos.reserve(num_features); + for (auto & new_feature : scan.new_features) + { + field_infos.push_back(new_feature.second); + } + + scan.gl_point.clear(); + scan.gl_point.reserve(num_points*2); + scan.gl_color.clear(); + scan.gl_color.reserve(num_points*4); + + for (size_t i = 0; i < num_points; i++, ptr += point_step) + { + float x = *reinterpret_cast(ptr + xoff); + float y = *reinterpret_cast(ptr + yoff); + float z = *reinterpret_cast(ptr + zoff); + + StampedPoint& point = scan.points[i]; + point.point = tf2::Vector3(x, y, z); + + point.features.resize(num_features); + + for (int count=0; count < field_infos.size(); count++) + { + point.features[count] = PointFeature(ptr, field_infos[count]); + } + if (scan.transformed) + { + const tf2::Vector3 transformed_point = transform * point.point; + scan.gl_point.push_back( transformed_point.getX() ); + scan.gl_point.push_back( transformed_point.getY() ); + } + const QColor color = CalculateColor(point); + scan.gl_color.push_back( color.red()); + scan.gl_color.push_back( color.green()); + scan.gl_color.push_back( color.blue()); + scan.gl_color.push_back( static_cast(alpha_ * 255.0 ) ); + } + } + + { + QMutexLocker locker(&scan_mutex_); + scans_.push_back( std::move(scan) ); + } + new_topic_ = true; + canvas_->update(); + } + + float PointCloud2Plugin::PointFeature(const uint8_t* data, const FieldInfo& feature_info) + { + switch (feature_info.datatype) + { + case 1: + return *reinterpret_cast(data + feature_info.offset); + case 2: + return *(data + feature_info.offset); + case 3: + return *reinterpret_cast(data + feature_info.offset); + case 4: + return *reinterpret_cast(data + feature_info.offset); + case 5: + return *reinterpret_cast(data + feature_info.offset); + case 6: + return *reinterpret_cast(data + feature_info.offset); + case 7: + return *reinterpret_cast(data + feature_info.offset); + case 8: + return static_cast(*reinterpret_cast(data + feature_info.offset)); + default: + RCLCPP_WARN(node_->get_logger(), "Unknown data type in point: %d", feature_info.datatype); + return 0.0; + } + } + + void PointCloud2Plugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void PointCloud2Plugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void PointCloud2Plugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* PointCloud2Plugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool PointCloud2Plugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + DrawIcon(); + + return true; + } + + void PointCloud2Plugin::Draw(double x, double y, double scale) + { + glPointSize(point_size_); + + glEnableClientState(GL_VERTEX_ARRAY); + glEnableClientState(GL_COLOR_ARRAY); + + { + QMutexLocker locker(&scan_mutex_); + + for (Scan& scan : scans_) + { + if (scan.transformed && !scan.gl_color.empty()) + { + glBindBuffer(GL_ARRAY_BUFFER, scan.point_vbo); // coordinates + glBufferData( + GL_ARRAY_BUFFER, + scan.gl_point.size() * sizeof(float), + scan.gl_point.data(), + GL_STATIC_DRAW); + glVertexPointer( 2, GL_FLOAT, 0, nullptr); + + glBindBuffer(GL_ARRAY_BUFFER, scan.color_vbo); // color + glBufferData( + GL_ARRAY_BUFFER, + scan.gl_color.size() * sizeof(uint8_t), + scan.gl_color.data(), + GL_STATIC_DRAW); + glColorPointer( 4, GL_UNSIGNED_BYTE, 0, nullptr); + + glDrawArrays(GL_POINTS, 0, scan.gl_point.size() / 2 ); + } + } + } + glDisableClientState(GL_VERTEX_ARRAY); + glDisableClientState(GL_COLOR_ARRAY); + glBindBuffer(GL_ARRAY_BUFFER, 0); + + PrintInfo("OK"); + } + + void PointCloud2Plugin::UseRainbowChanged(int check_state) + { + UpdateMinMaxWidgets(); + UpdateColors(); + } + + void PointCloud2Plugin::UseAutomaxminChanged(int check_state) + { + need_minmax_ = check_state == Qt::Checked; + if( !need_minmax_ ) + { + min_value_ = ui_.minValue->value(); + max_value_ = ui_.maxValue->value(); + } + + UpdateMinMaxWidgets(); + UpdateColors(); + } + + void PointCloud2Plugin::Transform() + { + { + QMutexLocker locker(&scan_mutex_); + + bool was_using_latest_transforms = use_latest_transforms_; + use_latest_transforms_ = false; + for (Scan& scan : scans_) + { + if (!scan.transformed) + { + swri_transform_util::Transform transform; + if (GetTransform(scan.source_frame, scan.stamp, transform)) + { + scan.gl_point.clear(); + scan.gl_point.reserve(scan.points.size()*2); + + scan.transformed = true; + for (StampedPoint& point : scan.points) + { + const tf2::Vector3 transformed_point = transform * point.point; + scan.gl_point.push_back( transformed_point.getX() ); + scan.gl_point.push_back( transformed_point.getY() ); + } + } else { + RCLCPP_WARN(node_->get_logger(), "Unable to get transform."); + scan.transformed = false; + } + } + } + use_latest_transforms_ = was_using_latest_transforms; + } + // Z color is based on transformed color, so it is dependent on the + // transform + if (ui_.color_transformer->currentIndex() == COLOR_Z) + { + UpdateColors(); + } + } + + void PointCloud2Plugin::LoadConfig(const YAML::Node& node, + const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(boost::trim_copy(topic).c_str()); + TopicEdited(); + } + + if (node["size"]) + { + point_size_ = node["size"].as(); + ui_.pointSize->setValue(static_cast(point_size_)); + } + + if (node["buffer_size"]) + { + buffer_size_ = node["buffer_size"].as(); + ui_.bufferSize->setValue(static_cast(buffer_size_)); + } + + if (node["color_transformer"]) + { + saved_color_transformer_ = node["color_transformer"].as(); + } + + if (node["min_color"]) + { + std::string min_color_str = node["min_color"].as(); + ui_.min_color->setColor(QColor(min_color_str.c_str())); + } + + if (node["max_color"]) + { + std::string max_color_str = node["max_color"].as(); + ui_.max_color->setColor(QColor(max_color_str.c_str())); + } + + if (node["value_min"]) + { + min_value_ = node["value_min"].as(); + ui_.minValue->setValue(min_value_); + } + + if (node["value_max"]) + { + max_value_ = node["value_max"].as(); + ui_.maxValue->setValue(max_value_); + } + + if (node["alpha"]) + { + alpha_ = node["alpha"].as(); + ui_.alpha->setValue(alpha_); + } + + if (node["use_rainbow"]) + { + bool use_rainbow = node["use_rainbow"].as(); + ui_.use_rainbow->setChecked(use_rainbow); + } + + if (node["unpack_rgb"]) + { + bool unpack_rgb = node["unpack_rgb"].as(); + ui_.unpack_rgb->setChecked(unpack_rgb); + } + + // UseRainbowChanged must be called *before* ColorTransformerChanged + UseRainbowChanged(ui_.use_rainbow->checkState()); + + if (node["use_automaxmin"]) + { + bool use_automaxmin = node["use_automaxmin"].as(); + ui_.use_automaxmin->setChecked(use_automaxmin); + } + // UseRainbowChanged must be called *before* ColorTransformerChanged + UseAutomaxminChanged(ui_.use_automaxmin->checkState()); + // ColorTransformerChanged will also update colors of all points + ColorTransformerChanged(ui_.color_transformer->currentIndex()); + } + + void PointCloud2Plugin::ColorTransformerChanged(int index) + { + RCLCPP_DEBUG(node_->get_logger(), "Color transformer changed to %d", index); + UpdateMinMaxWidgets(); + UpdateColors(); + } + + void PointCloud2Plugin::UpdateMinMaxWidgets() + { + bool color_is_flat = ui_.color_transformer->currentIndex() == COLOR_FLAT; + + if (color_is_flat) + { + ui_.maxColorLabel->hide(); + ui_.max_color->hide(); + ui_.minColorLabel->hide(); + ui_.min_max_color_widget->show(); + ui_.min_max_value_widget->hide(); + ui_.use_automaxmin->hide(); + ui_.use_rainbow->hide(); + } else { + ui_.maxColorLabel->show(); + ui_.max_color->show(); + ui_.minColorLabel->show(); + ui_.min_max_color_widget->setVisible(!ui_.use_rainbow->isChecked()); + ui_.min_max_value_widget->setVisible(!ui_.use_automaxmin->isChecked()); + ui_.use_automaxmin->show(); + ui_.use_rainbow->show(); + } + + config_widget_->updateGeometry(); + config_widget_->adjustSize(); + + Q_EMIT SizeChanged(); + } + + /** + * Coerces alpha to [0.0, 1.0] and stores it in alpha_ + */ + void PointCloud2Plugin::AlphaEdited(double value) + { + alpha_ = std::max(0.0f, std::min(static_cast(value), 1.0f)); + } + + void PointCloud2Plugin::SaveConfig(YAML::Emitter& emitter, + const std::string& path) + { + emitter << YAML::Key << "topic" << + YAML::Value << boost::trim_copy(ui_.topic->text().toStdString()); + emitter << YAML::Key << "size" << + YAML::Value << ui_.pointSize->value(); + emitter << YAML::Key << "buffer_size" << + YAML::Value << ui_.bufferSize->value(); + emitter << YAML::Key << "alpha" << + YAML::Value << alpha_; + emitter << YAML::Key << "color_transformer" << + YAML::Value << ui_.color_transformer->currentText().toStdString(); + emitter << YAML::Key << "min_color" << + YAML::Value << ui_.min_color->color().name().toStdString(); + emitter << YAML::Key << "max_color" << + YAML::Value << ui_.max_color->color().name().toStdString(); + emitter << YAML::Key << "value_min" << + YAML::Value << ui_.minValue->value(); + emitter << YAML::Key << "value_max" << + YAML::Value << ui_.maxValue->value(); + emitter << YAML::Key << "use_rainbow" << + YAML::Value << ui_.use_rainbow->isChecked(); + emitter << YAML::Key << "use_automaxmin" << + YAML::Value << ui_.use_automaxmin->isChecked(); + emitter << YAML::Key << "unpack_rgb" << + YAML::Value << ui_.unpack_rgb->isChecked(); + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/pose_plugin.cpp b/mapviz_plugins/src/pose_plugin.cpp new file mode 100644 index 000000000..a784803c9 --- /dev/null +++ b/mapviz_plugins/src/pose_plugin.cpp @@ -0,0 +1,299 @@ +/** + * Copyright 2019 Hatchbed L.L.C. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. Neither the name of the copyright holder nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + **/ + +#include + +// QT libraries +#include +#include +#include + +#include + +// ROS libraries +#include + +#include +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::PosePlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + PosePlugin::PosePlugin() + : PointDrawingPlugin() + , ui_() + , config_widget_(new QWidget()) + , has_message_(false) + { + ui_.setupUi(config_widget_); + + ui_.color->setColor(Qt::green); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, + SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, + SLOT(TopicEdited())); + QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this, + SLOT(PositionToleranceChanged(double))); + QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this, + SLOT(BufferSizeChanged(int))); + QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this, + SLOT(SetDrawStyle(QString))); + QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)), + this, SLOT(SetStaticArrowSizes(bool))); + QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)), + this, SLOT(SetArrowSize(int))); + QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this, + SLOT(SetColor(const QColor&))); + QObject::connect(ui_.show_laps, SIGNAL(toggled(bool)), this, + SLOT(LapToggled(bool))); + QObject::connect(ui_.buttonResetBuffer, SIGNAL(pressed()), this, + SLOT(ClearPoints())); + } + + void PosePlugin::SelectTopic() + { + std::string topic = + mapviz::SelectTopicDialog::selectTopic(node_, "geometry_msgs/msg/PoseStamped"); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void PosePlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + ClearPoints(); + has_message_ = false; + PrintWarning("No messages received."); + + // pose_sub_.shutdown(); + pose_sub_.reset(); + + topic_ = topic; + if (!topic.empty()) + { + pose_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&PosePlugin::PoseCallback, this, std::placeholders::_1)); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void PosePlugin::PoseCallback(const geometry_msgs::msg::PoseStamped::SharedPtr pose) + { + if (!has_message_) + { + initialized_ = true; + has_message_ = true; + } + + StampedPoint stamped_point; + stamped_point.stamp = pose->header.stamp; + stamped_point.source_frame = pose->header.frame_id; + + stamped_point.point = tf2::Vector3(pose->pose.position.x, + pose->pose.position.y, + pose->pose.position.z); + + stamped_point.orientation = tf2::Quaternion( + pose->pose.orientation.x, + pose->pose.orientation.y, + pose->pose.orientation.z, + pose->pose.orientation.w); + + pushPoint( std::move(stamped_point) ); + } + + void PosePlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void PosePlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void PosePlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* PosePlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool PosePlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + SetColor(ui_.color->color()); + + return true; + } + + void PosePlugin::Draw(double x, double y, double scale) + { + if (DrawPoints(scale)) + { + PrintInfo("OK"); + } + } + + void PosePlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["topic"]) + { + std::string topic = node["topic"].as(); + ui_.topic->setText(topic.c_str()); + } + + if (node["color"]) + { + std::string color = node["color"].as(); + QColor qcolor(color.c_str()); + SetColor(qcolor); + ui_.color->setColor(qcolor); + } + + if (node["draw_style"]) + { + std::string draw_style = node["draw_style"].as(); + + if (draw_style == "lines") + { + ui_.drawstyle->setCurrentIndex(0); + SetDrawStyle( LINES ); + } else if (draw_style == "points") { + ui_.drawstyle->setCurrentIndex(1); + SetDrawStyle( POINTS ); + } else if (draw_style == "arrows") { + ui_.drawstyle->setCurrentIndex(2); + SetDrawStyle( ARROWS ); + } + } + + if (node["position_tolerance"]) + { + double position_tolerance = node["position_tolerance"].as(); + ui_.positiontolerance->setValue(position_tolerance); + PositionToleranceChanged(position_tolerance); + } + + if (node["buffer_size"]) + { + int buffer_size = node["buffer_size"].as(); + ui_.buffersize->setValue(buffer_size); + BufferSizeChanged(buffer_size); + } + + if (node["show_laps"]) + { + bool show_laps = node["show_laps"].as(); + ui_.show_laps->setChecked(show_laps); + LapToggled(show_laps); + } + + if (node["static_arrow_sizes"]) + { + bool static_arrow_sizes = node["static_arrow_sizes"].as(); + ui_.static_arrow_sizes->setChecked(static_arrow_sizes); + SetStaticArrowSizes(static_arrow_sizes); + } + + if (node["arrow_size"]) + { + int arrow_size = node["arrow_size"].as(); + ui_.arrow_size->setValue(arrow_size); + SetArrowSize(arrow_size); + } + + TopicEdited(); + } + + void PosePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + std::string topic = ui_.topic->text().toStdString(); + emitter << YAML::Key << "topic" << YAML::Value << topic; + + emitter << YAML::Key << "color" << YAML::Value + << ui_.color->color().name().toStdString(); + + std::string draw_style = ui_.drawstyle->currentText().toStdString(); + emitter << YAML::Key << "draw_style" << YAML::Value << draw_style; + + emitter << YAML::Key << "position_tolerance" << + YAML::Value << positionTolerance(); + + emitter << YAML::Key << "buffer_size" << YAML::Value << bufferSize(); + + bool show_laps = ui_.show_laps->isChecked(); + emitter << YAML::Key << "show_laps" << YAML::Value << show_laps; + + emitter << YAML::Key + << "static_arrow_sizes" + << YAML::Value + << ui_.static_arrow_sizes->isChecked(); + + emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value(); + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/robot_image_plugin.cpp b/mapviz_plugins/src/robot_image_plugin.cpp new file mode 100644 index 000000000..947df56cb --- /dev/null +++ b/mapviz_plugins/src/robot_image_plugin.cpp @@ -0,0 +1,452 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2010, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include +#include +#include +#include + +// ROS libraries +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::RobotImagePlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + RobotImagePlugin::RobotImagePlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , width_(2.0) + , height_(1.0) + , offset_x_(0.0) + , offset_y_(0.0) + , image_ratio_(1.0) + , dimension_(0) + , texture_id_(0) + , texture_loaded_(false) + , transformed_(false) + { + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + UpdateShape(); + + QObject::connect(ui_.browse, SIGNAL(clicked()), this, SLOT(SelectFile())); + QObject::connect(ui_.selectframe, SIGNAL(clicked()), this, SLOT(SelectFrame())); + QObject::connect(ui_.frame, SIGNAL(editingFinished()), this, SLOT(FrameEdited())); + QObject::connect(ui_.image, SIGNAL(editingFinished()), this, SLOT(ImageEdited())); + QObject::connect(ui_.width, SIGNAL(valueChanged(double)), this, SLOT(WidthChanged(double))); + QObject::connect(ui_.height, SIGNAL(valueChanged(double)), this, SLOT(HeightChanged(double))); + QObject::connect(ui_.offset_x, + SIGNAL(valueChanged(double)), + this, + SLOT(OffsetXChanged(double))); + QObject::connect(ui_.offset_y, + SIGNAL(valueChanged(double)), + this, + SLOT(OffsetYChanged(double))); + ui_.offset_x->setMinimum(-99.99); // default is 0.0 but negative offset must be supported + ui_.offset_y->setMinimum(-99.99); + QObject::connect(ui_.ratio_equal, SIGNAL(toggled(bool)), this, SLOT(RatioEqualToggled(bool))); + QObject::connect(ui_.ratio_custom, SIGNAL(toggled(bool)), this, SLOT(RatioCustomToggled(bool))); + QObject::connect(ui_.ratio_original, + SIGNAL(toggled(bool)), + this, + SLOT(RatioOriginalToggled(bool))); + } + + void RobotImagePlugin::SelectFile() + { + QFileDialog dialog(config_widget_, "Select PNG Image"); + dialog.setFileMode(QFileDialog::ExistingFile); + dialog.setNameFilter(tr("PNG Image Files (*.png)")); + + dialog.exec(); + + if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1) + { + ui_.image->setText(dialog.selectedFiles().first()); + filename_ = dialog.selectedFiles().first().toStdString(); + LoadImage(); + } + } + + void RobotImagePlugin::SelectFrame() + { + std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_buf_); + if (!frame.empty()) + { + ui_.frame->setText(QString::fromStdString(frame)); + FrameEdited(); + } + } + + void RobotImagePlugin::ImageEdited() + { + filename_ = ui_.image->text().toStdString(); + LoadImage(); + } + + void RobotImagePlugin::FrameEdited() + { + source_frame_ = ui_.frame->text().toStdString(); + PrintWarning("Waiting for transform."); + + RCLCPP_INFO(node_->get_logger(), "Setting target frame to to %s", source_frame_.c_str()); + + initialized_ = true; + + UpdateShape(); + } + + void RobotImagePlugin::WidthChanged(double value) + { + width_ = value; + if( ui_.ratio_equal->isChecked()){ + ui_.height->setValue( width_ ); + } else if( ui_.ratio_original->isChecked()) { + ui_.height->setValue( width_ * image_ratio_ ); + } + UpdateShape(); + } + + void RobotImagePlugin::HeightChanged(double value) + { + height_ = value; + UpdateShape(); + } + + void RobotImagePlugin::OffsetXChanged(double value) + { + offset_x_ = value; + UpdateShape(); + } + + void RobotImagePlugin::OffsetYChanged(double value) + { + offset_y_ = value; + UpdateShape(); + } + + void RobotImagePlugin::RatioEqualToggled(bool toggled) + { + if( toggled ) + { + ui_.height->setValue(width_); + ui_.height->setEnabled(false); + UpdateShape(); + } + } + + void RobotImagePlugin::RatioCustomToggled(bool toggled) + { + if( toggled ) + { + ui_.height->setEnabled(true); + UpdateShape(); + } + } + + void RobotImagePlugin::RatioOriginalToggled(bool toggled) + { + if( toggled ) + { + ui_.height->setValue(width_*image_ratio_); + ui_.height->setEnabled(false); + UpdateShape(); + } + } + + void RobotImagePlugin::UpdateShape() + { + double hw = 0.5*width_; // half width + double hh = 0.5*height_; // half height + top_left_ = tf2::Vector3(offset_x_ - hw, offset_y_ + hh, 0); + top_right_ = tf2::Vector3(offset_x_ + hw, offset_y_ + hh, 0); + bottom_left_ = tf2::Vector3(offset_x_ - hw, offset_y_ - hh, 0); + bottom_right_ = tf2::Vector3(offset_x_ + hw, offset_y_ - hh, 0); + } + + void RobotImagePlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void RobotImagePlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void RobotImagePlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* RobotImagePlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool RobotImagePlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + return true; + } + + void RobotImagePlugin::Draw(double x, double y, double scale) + { + if (texture_loaded_ && transformed_) + { + glColor3f(1.0f, 1.0f, 1.0f); + glEnable(GL_TEXTURE_2D); + glBindTexture(GL_TEXTURE_2D, static_cast(texture_id_)); + + glBegin(GL_QUADS); + + glTexCoord2f(0, 1); glVertex2d(top_left_transformed_.x(), top_left_transformed_.y()); + glTexCoord2f(1, 1); glVertex2d(top_right_transformed_.x(), top_right_transformed_.y()); + glTexCoord2f(1, 0); glVertex2d(bottom_right_transformed_.x(), bottom_right_transformed_.y()); + glTexCoord2f(0, 0); glVertex2d(bottom_left_transformed_.x(), bottom_left_transformed_.y()); + + glEnd(); + + glDisable(GL_TEXTURE_2D); + + PrintInfo("OK"); + } + } + + void RobotImagePlugin::Transform() + { + transformed_ = false; + + swri_transform_util::Transform transform; + if (GetTransform(node_->get_clock()->now(), transform)) + { + top_left_transformed_ = transform * top_left_; + top_right_transformed_ = transform * top_right_; + bottom_left_transformed_ = transform * bottom_left_; + bottom_right_transformed_ = transform * bottom_right_; + transformed_ = true; + } else { + PrintError("No transform between " + source_frame_ + " and " + target_frame_); + } + } + + void RobotImagePlugin::LoadImage() + { + RCLCPP_INFO(node_->get_logger(), "Loading image"); + try + { + QImage nullImage; + image_ = nullImage; + + if (texture_loaded_) + { + GLuint ids[1]; + ids[0] = static_cast(texture_id_); + glDeleteTextures(1, &ids[0]); + texture_loaded_ = false; + } + + const std::string prefix = "$(find "; + std::string real_filename; + size_t spos = filename_.find(prefix); + bool has_close = spos != -1 ? filename_.find(')', spos) != -1: false; + if (spos != -1 && spos + prefix.length() < filename_.size() && has_close) + { + std::string package = filename_.substr(spos + prefix.length()); + package = package.substr(0, package.find(')')); + + std::string package_path = ament_index_cpp::get_package_share_directory(package); + real_filename = QDir(QString::fromStdString(package_path)) + .filePath(QString::fromStdString(filename_.substr(filename_.find(')')+1))) + .toStdString(); + } else { + real_filename = filename_; + } + + + if (image_.load(real_filename.c_str())) + { + int width = image_.width(); + int height = image_.height(); + image_ratio_ = static_cast(height) / static_cast(width); + + float max_dim = std::max(width, height); + dimension_ = static_cast(std::pow(2, std::ceil(std::log(max_dim) / std::log(2.0f)))); + + if (width != dimension_ || height != dimension_) + { + image_ = image_.scaled(dimension_, + dimension_, + Qt::IgnoreAspectRatio, + Qt::FastTransformation); + } + + image_ = QGLWidget::convertToGLFormat(image_); + + GLuint ids[1]; + glGenTextures(1, &ids[0]); + texture_id_ = ids[0]; + + glBindTexture(GL_TEXTURE_2D, static_cast(texture_id_)); + glTexImage2D(GL_TEXTURE_2D, + 0, + GL_RGBA, + dimension_, + dimension_, + 0, + GL_RGBA, + GL_UNSIGNED_BYTE, + image_.bits()); + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); + + texture_loaded_ = true; + if ( ui_.ratio_original->isChecked() ) + { + RatioOriginalToggled(true); + } + } else { + PrintError("Failed to load image."); + } + } + catch (const std::exception& e) + { + PrintError("Failed to load image. Exception occured."); + } + } + + void RobotImagePlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["frame"]) + { + source_frame_ = node["frame"].as(); + ui_.frame->setText(source_frame_.c_str()); + } + if (node["offset_x"]) + { + offset_x_ = node["offset_x"].as(); + ui_.offset_x->setValue(offset_x_); + } + + if (node["offset_y"]) + { + offset_y_ = node["offset_y"].as(); + ui_.offset_y->setValue(offset_y_); + } + + if (node["image"]) + { + filename_ = node["image"].as(); + ui_.image->setText(filename_.c_str()); + } + + if (node["width"]) + { + width_ = node["width"].as(); + ui_.width->setValue(width_); + } + + if (node["height"]) + { + height_ = node["height"].as(); + ui_.height->setValue(height_); + } + + if (node["ratio"]) + { + std::string value = node["ratio"].as(); + if(value == "equal") + { + ui_.ratio_equal->setChecked(true); + } else if(value == "custom") { + ui_.ratio_custom->setChecked(true); + } else if(value == "original") { + ui_.ratio_original->setChecked(true); + } + } + + UpdateShape(); + LoadImage(); + FrameEdited(); + } + + void RobotImagePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key << "frame" << YAML::Value << ui_.frame->text().toStdString(); + emitter << YAML::Key << "image" << YAML::Value << ui_.image->text().toStdString(); + emitter << YAML::Key << "width" << YAML::Value << width_; + emitter << YAML::Key << "height" << YAML::Value << height_; + emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_; + emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_; + if( ui_.ratio_custom->isChecked()) + { + emitter << YAML::Key << "ratio" << YAML::Value << "custom"; + } else if( ui_.ratio_equal->isChecked()) { + emitter << YAML::Key << "ratio" << YAML::Value << "equal"; + } else if( ui_.ratio_original->isChecked()) { + emitter << YAML::Key << "ratio" << YAML::Value << "original"; + } + } +} // namespace mapviz_plugins + diff --git a/mapviz_plugins/src/route_plugin.cpp b/mapviz_plugins/src/route_plugin.cpp new file mode 100644 index 000000000..4ccf85cc1 --- /dev/null +++ b/mapviz_plugins/src/route_plugin.cpp @@ -0,0 +1,423 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include +#include +#include + +#include + +// ROS libraries +#include + +#include +#include +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::RoutePlugin, mapviz::MapvizPlugin) + +namespace sru = swri_route_util; +namespace stu = swri_transform_util; + +namespace mapviz_plugins +{ + RoutePlugin::RoutePlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()), draw_style_(LINES) + { + ui_.setupUi(config_widget_); + + ui_.color->setColor(Qt::green); + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, + SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, + SLOT(TopicEdited())); + QObject::connect(ui_.selectpositiontopic, SIGNAL(clicked()), this, + SLOT(SelectPositionTopic())); + QObject::connect(ui_.positiontopic, SIGNAL(editingFinished()), this, + SLOT(PositionTopicEdited())); + QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this, + SLOT(SetDrawStyle(QString))); + QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this, + SLOT(DrawIcon())); + } + + void RoutePlugin::DrawIcon() + { + if (icon_) + { + QPixmap icon(16, 16); + icon.fill(Qt::transparent); + + QPainter painter(&icon); + painter.setRenderHint(QPainter::Antialiasing, true); + + QPen pen(ui_.color->color()); + + if (draw_style_ == POINTS) + { + pen.setWidth(7); + pen.setCapStyle(Qt::RoundCap); + painter.setPen(pen); + painter.drawPoint(8, 8); + } else if (draw_style_ == LINES) { + pen.setWidth(3); + pen.setCapStyle(Qt::FlatCap); + painter.setPen(pen); + painter.drawLine(1, 14, 14, 1); + } + + icon_->SetPixmap(icon); + } + } + + void RoutePlugin::SetDrawStyle(QString style) + { + if (style == "lines") + { + draw_style_ = LINES; + } else if (style == "points") { + draw_style_ = POINTS; + } + DrawIcon(); + } + + void RoutePlugin::SelectTopic() + { + std::string topic = + mapviz::SelectTopicDialog::selectTopic(node_, "marti_nav_msgs/msg/Route"); + + if (topic.empty()) + { + return; + } + + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + + void RoutePlugin::SelectPositionTopic() + { + std::string topic = + mapviz::SelectTopicDialog::selectTopic(node_, "marti_nav_msgs/msg/RoutePosition"); + + if (topic.empty()) + { + return; + } + + ui_.positiontopic->setText(QString::fromStdString(topic)); + PositionTopicEdited(); + } + + void RoutePlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + src_route_ = sru::Route(); + + route_sub_.reset(); + + topic_ = topic; + if (!topic.empty()) + { + route_sub_ = + node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&RoutePlugin::RouteCallback, this, std::placeholders::_1) + ); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void RoutePlugin::PositionTopicEdited() + { + std::string topic = ui_.positiontopic->text().trimmed().toStdString(); + if (topic != position_topic_) + { + src_route_position_.reset(); + position_sub_.reset(); + + if (!topic.empty()) + { + position_topic_ = topic; + position_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1), + std::bind(&RoutePlugin::PositionCallback, this, std::placeholders::_1) + ); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", position_topic_.c_str()); + } + } + } + + void RoutePlugin::PositionCallback( + const marti_nav_msgs::msg::RoutePosition::SharedPtr msg) + { + src_route_position_ = msg; + } + + void RoutePlugin::RouteCallback(const marti_nav_msgs::msg::Route::SharedPtr msg) + { + src_route_ = sru::Route(*msg); + } + + void RoutePlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message, 1.0); + } + + void RoutePlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message, 1.0); + } + + void RoutePlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message, 1.0); + } + + QWidget* RoutePlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool RoutePlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + DrawIcon(); + + initialized_ = true; + return true; + } + + void RoutePlugin::Draw(double x, double y, double scale) + { + if (!src_route_.valid()) + { + PrintError("No valid route received."); + return; + } + + sru::Route route = src_route_; + if (route.header.frame_id.empty()) + { + route.header.frame_id = "wgs84"; + } + + stu::Transform transform; + if (!GetTransform(route.header.frame_id, rclcpp::Time(), transform)) + { + PrintError("Failed to transform route"); + return; + } + + sru::transform(route, transform, target_frame_); + sru::projectToXY(route); + sru::fillOrientations(route); + + DrawRoute(route); + + bool ok = true; + if (route.valid() && src_route_position_) + { + sru::RoutePoint point; + if (sru::interpolateRoutePosition(point, route, *src_route_position_, true)) + { + DrawRoutePoint(point); + } else { + PrintError("Failed to find route position in route."); + ok = false; + } + } + + if (ok) + { + PrintInfo("OK"); + } + } + + void RoutePlugin::DrawStopWaypoint(double x, double y) + { + const double a = 2; + const double S = a * 2.414213562373095; + + glBegin(GL_POLYGON); + + glColor3f(1.0, 0.0, 0.0); + + glVertex2d(x + S / 2.0, y - a / 2.0); + glVertex2d(x + S / 2.0, y + a / 2.0); + glVertex2d(x + a / 2.0, y + S / 2.0); + glVertex2d(x - a / 2.0, y + S / 2.0); + glVertex2d(x - S / 2.0, y + a / 2.0); + glVertex2d(x - S / 2.0, y - a / 2.0); + glVertex2d(x - a / 2.0, y - S / 2.0); + glVertex2d(x + a / 2.0, y - S / 2.0); + + glEnd(); + } + + void RoutePlugin::DrawRoute(const sru::Route& route) + { + const QColor color = ui_.color->color(); + glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0); + + if (draw_style_ == LINES) + { + glLineWidth(3); + glBegin(GL_LINE_STRIP); + } else { + glPointSize(2); + glBegin(GL_POINTS); + } + + for (const auto & point : route.points) + { + glVertex2d(point.position().x(), + point.position().y()); + } + glEnd(); + } + + void RoutePlugin::DrawRoutePoint(const sru::RoutePoint& point) + { + const double arrow_size = ui_.iconsize->value(); + + tf2::Vector3 v1(arrow_size, 0.0, 0.0); + tf2::Vector3 v2(0.0, arrow_size / 2.0, 0.0); + tf2::Vector3 v3(0.0, -arrow_size / 2.0, 0.0); + + tf2::Transform point_g(point.orientation(), point.position()); + + v1 = point_g * v1; + v2 = point_g * v2; + v3 = point_g * v3; + + const QColor color = ui_.positioncolor->color(); + glLineWidth(3); + glBegin(GL_POLYGON); + glColor4d(color.redF(), color.greenF(), color.blueF(), 1.0); + glVertex2d(v1.x(), v1.y()); + glVertex2d(v2.x(), v2.y()); + glVertex2d(v3.x(), v3.y()); + glEnd(); + } + + void RoutePlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["topic"]) + { + std::string route_topic = node["topic"].as(); + ui_.topic->setText(route_topic.c_str()); + } + if (node["color"]) + { + std::string color = node["color"].as(); + ui_.color->setColor(QColor(color.c_str())); + } + if (node["postopic"]) + { + std::string pos_topic = node["postopic"].as(); + ui_.positiontopic->setText(pos_topic.c_str()); + } + if (node["poscolor"]) + { + std::string poscolor = node["poscolor"].as(); + ui_.positioncolor->setColor(QColor(poscolor.c_str())); + } + + if (node["draw_style"]) + { + std::string draw_style = node["draw_style"].as(); + + if (draw_style == "lines") + { + draw_style_ = LINES; + ui_.drawstyle->setCurrentIndex(0); + } else if (draw_style == "points") { + draw_style_ = POINTS; + ui_.drawstyle->setCurrentIndex(1); + } + } + + TopicEdited(); + PositionTopicEdited(); + } + + void RoutePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + std::string route_topic = ui_.topic->text().toStdString(); + emitter << YAML::Key << "topic" << YAML::Value << route_topic; + + std::string color = ui_.color->color().name().toStdString(); + emitter << YAML::Key << "color" << YAML::Value << color; + + std::string pos_topic = ui_.positiontopic->text().toStdString(); + emitter << YAML::Key << "postopic" << YAML::Value << pos_topic; + + std::string pos_color = ui_.positioncolor->color().name().toStdString(); + emitter << YAML::Key << "poscolor" << YAML::Value << pos_color; + + std::string draw_style = ui_.drawstyle->currentText().toStdString(); + emitter << YAML::Key << "draw_style" << YAML::Value << draw_style; + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/string_plugin.cpp b/mapviz_plugins/src/string_plugin.cpp new file mode 100644 index 000000000..05a55f1b5 --- /dev/null +++ b/mapviz_plugins/src/string_plugin.cpp @@ -0,0 +1,435 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#include + +#include + +#include + +#include + +#include +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::StringPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + const char* StringPlugin::COLOR_KEY = "color"; + const char* StringPlugin::FONT_KEY = "font"; + const char* StringPlugin::TOPIC_KEY = "topic"; + const char* StringPlugin::ANCHOR_KEY = "anchor"; + const char* StringPlugin::UNITS_KEY = "units"; + const char* StringPlugin::OFFSET_X_KEY = "offset_x"; + const char* StringPlugin::OFFSET_Y_KEY = "offset_y"; + + StringPlugin::StringPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , anchor_(TOP_LEFT) + , units_(PIXELS) + , offset_x_(0) + , offset_y_(0) + , has_message_(false) + , has_painted_(false) + , color_(Qt::black) + { + ui_.setupUi(config_widget_); + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited())); + QObject::connect(ui_.anchor, SIGNAL(activated(QString)), this, SLOT(SetAnchor(QString))); + QObject::connect(ui_.units, SIGNAL(activated(QString)), this, SLOT(SetUnits(QString))); + QObject::connect(ui_.offsetx, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetX(int))); + QObject::connect(ui_.offsety, SIGNAL(valueChanged(int)), this, SLOT(SetOffsetY(int))); + QObject::connect(ui_.font_button, SIGNAL(clicked()), this, SLOT(SelectFont())); + QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor &)), this, SLOT(SelectColor())); + + font_.setFamily(tr("Helvetica")); + ui_.font_button->setFont(font_); + ui_.font_button->setText(font_.family()); + + ui_.color->setColor(color_); + } + + bool StringPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + return true; + } + + void StringPlugin::Draw(double, double, double) + { + // This plugin doesn't do any OpenGL drawing. + } + + void StringPlugin::Paint(QPainter* painter, double, double, double) + { + if (has_message_) + { + painter->save(); + painter->resetTransform(); + painter->setFont(font_); + + if (!has_painted_) + { + // After the first time we get a new message, we do not know how wide it's + // going to be when rendered, so we can't accurately calculate the top left + // coordinate if it's offset from the right or bottom borders. + // The easiest workaround I've found for this is to draw it once using + // a completely transparent pen, which will cause the QStaticText class to + // know how wide it is; then we can recalculate the offsets and draw it + // again with a visible pen. + QPen invisPen(QBrush(Qt::transparent), 1); + painter->setPen(invisPen); + PaintText(painter); + has_painted_ = true; + } + QPen pen(QBrush(color_), 1); + painter->setPen(pen); + PaintText(painter); + + painter->restore(); + PrintInfo("OK"); + } else { + PrintWarning("No messages received."); + } + } + + void StringPlugin::PaintText(QPainter* painter) + { + // Calculate the correct offsets and dimensions + int x_offset = offset_x_; + int y_offset = offset_y_; + if (units_ == PERCENT) + { + x_offset = static_cast(static_cast(offset_x_ * canvas_->width()) / 100.0); + y_offset = static_cast(static_cast(offset_y_ * canvas_->height()) / 100.0); + } + + int right = static_cast( + static_cast(canvas_->width()) - message_.size().width()) - x_offset; + int bottom = static_cast( + static_cast(canvas_->height()) - message_.size().height()) - y_offset; + int yCenter = static_cast( + static_cast(canvas_->height()) / 2.0 - message_.size().height()/2.0); + int xCenter = static_cast( + static_cast(canvas_->width()) / 2.0 - message_.size().width()/2.0); + + QPoint ulPoint; + + switch (anchor_) + { + case TOP_LEFT: + ulPoint.setX(x_offset); + ulPoint.setY(y_offset); + break; + case TOP_CENTER: + ulPoint.setX(xCenter); + ulPoint.setY(y_offset); + break; + case TOP_RIGHT: + ulPoint.setX(right); + ulPoint.setY(y_offset); + break; + case CENTER_LEFT: + ulPoint.setX(x_offset); + ulPoint.setY(yCenter); + break; + case CENTER: + ulPoint.setX(xCenter); + ulPoint.setY(yCenter); + break; + case CENTER_RIGHT: + ulPoint.setX(right); + ulPoint.setY(yCenter); + break; + case BOTTOM_LEFT: + ulPoint.setX(x_offset); + ulPoint.setY(bottom); + break; + case BOTTOM_CENTER: + ulPoint.setX(xCenter); + ulPoint.setY(bottom); + break; + case BOTTOM_RIGHT: + ulPoint.setX(right); + ulPoint.setY(bottom); + break; + } + painter->drawStaticText(ulPoint, message_); + } + + void StringPlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node[TOPIC_KEY]) + { + ui_.topic->setText(QString(node[TOPIC_KEY].as().c_str())); + TopicEdited(); + } + + if (node[FONT_KEY]) + { + font_.fromString(QString(node[FONT_KEY].as().c_str())); + ui_.font_button->setFont(font_); + ui_.font_button->setText(font_.family()); + } + + if (node[COLOR_KEY]) + { + color_ = QColor(node[COLOR_KEY].as().c_str()); + ui_.color->setColor(QColor(color_.name().toStdString().c_str())); + } + + if (node[ANCHOR_KEY]) + { + std::string anchor = node[ANCHOR_KEY].as(); + ui_.anchor->setCurrentIndex(ui_.anchor->findText(anchor.c_str())); + SetAnchor(anchor.c_str()); + } + + if (node[UNITS_KEY]) + { + std::string units = node[UNITS_KEY].as(); + ui_.units->setCurrentIndex(ui_.units->findText(units.c_str())); + SetUnits(units.c_str()); + } + + if (node[OFFSET_X_KEY]) + { + offset_x_ = node[OFFSET_X_KEY].as(); + ui_.offsetx->setValue(offset_x_); + } + + if (node[OFFSET_Y_KEY]) + { + offset_y_ = node[OFFSET_Y_KEY].as(); + ui_.offsety->setValue(offset_y_); + } + } + + void StringPlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + emitter << YAML::Key << FONT_KEY << YAML::Value << font_.toString().toStdString(); + emitter << YAML::Key << COLOR_KEY << YAML::Value << color_.name().toStdString(); + emitter << YAML::Key << TOPIC_KEY << YAML::Value << ui_.topic->text().toStdString(); + emitter << YAML::Key << ANCHOR_KEY << YAML::Value << AnchorToString(anchor_); + emitter << YAML::Key << UNITS_KEY << YAML::Value << UnitsToString(units_); + emitter << YAML::Key << OFFSET_X_KEY << YAML::Value << offset_x_; + emitter << YAML::Key << OFFSET_Y_KEY << YAML::Value << offset_y_; + } + + QWidget* StringPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + return config_widget_; + } + + void StringPlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void StringPlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void StringPlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + void StringPlugin::SelectColor() + { + color_ = ui_.color->color(); + } + + void StringPlugin::SelectFont() + { + bool ok; + QFont font = QFontDialog::getFont(&ok, font_, canvas_); + if (ok) + { + font_ = font; + message_.prepare(QTransform(), font_); + ui_.font_button->setFont(font_); + ui_.font_button->setText(font_.family()); + } + } + + void StringPlugin::SelectTopic() + { + std::string topic = mapviz::SelectTopicDialog::selectTopic( + node_, "std_msgs/msg/String" + ); + + if (!topic.empty()) + { + ui_.topic->setText(QString::fromStdString(topic)); + TopicEdited(); + } + } + + void StringPlugin::TopicEdited() + { + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) + { + initialized_ = false; + has_message_ = false; + PrintWarning("No messages received."); + + string_sub_.reset(); + + topic_ = topic; + if (!topic.empty()) + { + string_sub_ = node_->create_subscription(topic_, + rclcpp::QoS(1), + [this](const std_msgs::msg::String::ConstSharedPtr str) { + SetText(QString(str->data.c_str())); + }); + string_stamped_sub_ = node_->create_subscription(topic_, + rclcpp::QoS(1), + [this](const marti_common_msgs::msg::StringStamped::ConstSharedPtr str) { + SetText(QString(str->value.c_str())); + }); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } + } + + void StringPlugin::SetText(const QString& text) + { + message_.setText(text); + message_.prepare(QTransform(), font_); + + has_message_ = true; + has_painted_ = false; + initialized_ = true; + } + + void StringPlugin::SetAnchor(QString anchor) + { + if (anchor == "top left") + { + anchor_ = TOP_LEFT; + } else if (anchor == "top center") { + anchor_ = TOP_CENTER; + } else if (anchor == "top right") { + anchor_ = TOP_RIGHT; + } else if (anchor == "center left") { + anchor_ = CENTER_LEFT; + } else if (anchor == "center") { + anchor_ = CENTER; + } else if (anchor == "center right") { + anchor_ = CENTER_RIGHT; + } else if (anchor == "bottom left") { + anchor_ = BOTTOM_LEFT; + } else if (anchor == "bottom center") { + anchor_ = BOTTOM_CENTER; + } else if (anchor == "bottom right") { + anchor_ = BOTTOM_RIGHT; + } + } + + void StringPlugin::SetUnits(QString units) + { + if (units == "pixels") + { + units_ = PIXELS; + } else if (units == "percent") { + units_ = PERCENT; + } + } + + void StringPlugin::SetOffsetX(int offset) + { + offset_x_ = offset; + } + + void StringPlugin::SetOffsetY(int offset) + { + offset_y_ = offset; + } + + std::string StringPlugin::AnchorToString(StringPlugin::Anchor anchor) + { + std::string anchor_string = "top left"; + + if (anchor == TOP_LEFT) + { + anchor_string = "top left"; + } else if (anchor == TOP_CENTER) { + anchor_string = "top center"; + } else if (anchor == TOP_RIGHT) { + anchor_string = "top right"; + } else if (anchor == CENTER_LEFT) { + anchor_string = "center left"; + } else if (anchor == CENTER) { + anchor_string = "center"; + } else if (anchor == CENTER_RIGHT) { + anchor_string = "center right"; + } else if (anchor == BOTTOM_LEFT) { + anchor_string = "bottom left"; + } else if (anchor == BOTTOM_CENTER) { + anchor_string = "bottom center"; + } else if (anchor == BOTTOM_RIGHT) { + anchor_string = "bottom right"; + } + + return anchor_string; + } + + std::string StringPlugin::UnitsToString(StringPlugin::Units units) + { + std::string units_string = "pixels"; + + if (units == PIXELS) + { + units_string = "pixels"; + } else if (units == PERCENT) { + units_string = "percent"; + } + + return units_string; + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/textured_marker_plugin.cpp b/mapviz_plugins/src/textured_marker_plugin.cpp new file mode 100755 index 000000000..3771e062b --- /dev/null +++ b/mapviz_plugins/src/textured_marker_plugin.cpp @@ -0,0 +1,522 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// Boost libraries +#include + +// QT libraries +#include +#include + +// ROS libraries +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include +#include +#include +#include + +using namespace std::chrono_literals; + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::TexturedMarkerPlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ +TexturedMarkerPlugin::TexturedMarkerPlugin() +: MapvizPlugin() +, ui_() +, alphaVal_(1.0f) +, config_widget_(new QWidget()) +, has_message_(false) +{ + ui_.setupUi(config_widget_); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selecttopic, SIGNAL(clicked()), this, SLOT(SelectTopic())); + QObject::connect(ui_.topic, SIGNAL(editingFinished()), this, SLOT(TopicEdited())); + QObject::connect(ui_.clear, SIGNAL(clicked()), this, SLOT(ClearHistory())); + QObject::connect(ui_.alphaSlide, SIGNAL(valueChanged(int)), this, SLOT(SetAlphaLevel(int))); + + // By using a signal/slot connection, we ensure that we only generate GL textures on the + // main thread in case a non-main thread handles the ROS callbacks. + qRegisterMetaType("TexturedMarker"); + + QObject::connect(this, + SIGNAL(MarkerReceived(marti_visualization_msgs::msg::TexturedMarker)), + this, + SLOT(ProcessMarker(marti_visualization_msgs::msg::TexturedMarker))); +} + +void TexturedMarkerPlugin::ClearHistory() +{ + RCLCPP_DEBUG(node_->get_logger(), "TexturedMarkerPlugin::ClearHistory()"); + markers_.clear(); +} + +// TODO(P. J. Reed) could instead use the value() function on alphaSlide when needed, +// assuming value is always good +// Modify min and max values by adjusting textured_marker_config.ui +void TexturedMarkerPlugin::SetAlphaLevel(int alpha) +{ + int max = ui_.alphaSlide->maximum(); + int min = ui_.alphaSlide->minimum(); + + if (max < 1 || + min < 0 || + alpha > max || + alpha < min) // ignore negative min and max + { + alphaVal_ = 1.0f; + PrintWarning("Invalid alpha input."); + } else { + // Ex. convert int in range 0-100 to float in range 0-1 + alphaVal_ = (static_cast(alpha) / max); + RCLCPP_INFO(node_->get_logger(), "Adjusting alpha value to: %f", alphaVal_); + } +} + +void TexturedMarkerPlugin::SelectTopic() +{ + std::string topic = mapviz::SelectTopicDialog::selectTopic( + node_, + "marti_visualization_msgs/msg/TexturedMarker", + "marti_visualization_msgs/msg/TexturedMarkerArray" + ); + + if (!topic.empty()) { + ui_.topic->setText(QString::fromStdString(topic)); + + TopicEdited(); + } +} + +void TexturedMarkerPlugin::TopicEdited() +{ + std::string topic = ui_.topic->text().trimmed().toStdString(); + if (topic != topic_) { + initialized_ = false; + markers_.clear(); + has_message_ = false; + PrintWarning("No messages received."); + + marker_sub_.reset(); + marker_arr_sub_.reset(); + + topic_ = topic; + if (!topic.empty()) { + marker_arr_sub_ = + node_->create_subscription( + topic_, + rclcpp::QoS(1000), + std::bind(&TexturedMarkerPlugin::MarkerArrayCallback, this, std::placeholders::_1) + ); + marker_sub_ = node_->create_subscription( + topic_, + rclcpp::QoS(1000), + std::bind(&TexturedMarkerPlugin::MarkerCallback, this, std::placeholders::_1) + ); + + RCLCPP_INFO(node_->get_logger(), "Subscribing to %s", topic_.c_str()); + } + } +} + +void TexturedMarkerPlugin::ProcessMarker(const marti_visualization_msgs::msg::TexturedMarker marker) +{ + if (!has_message_) { + initialized_ = true; + has_message_ = true; + } + + // Note that unlike some plugins, this one does not store nor rely on the + // source_frame_ member variable. This one can potentially store many + // messages with different source frames, so we need to store and transform + // them individually. + + if (marker.action == marti_visualization_msgs::msg::TexturedMarker::ADD) { + MarkerData & markerData = markers_[marker.ns][marker.id]; + markerData.stamp = marker.header.stamp; + + markerData.transformed = true; + markerData.alpha_ = marker.alpha; + markerData.source_frame_ = marker.header.frame_id; + + swri_transform_util::Transform transform; + if (!GetTransform(markerData.source_frame_, marker.header.stamp, transform)) { + markerData.transformed = false; + PrintError("No transform between " + markerData.source_frame_ + " and " + target_frame_); + } + + // Handle lifetime parameter + rclcpp::Duration lifetime = marker.lifetime; + if (lifetime.seconds() == 0 && lifetime.nanoseconds() == 0) { + markerData.expire_time = rclcpp::Time::max(); + } else { + // Temporarily add 5 seconds to fix some existing markers. + markerData.expire_time = rclcpp::Time() + lifetime + rclcpp::Duration(5s); + } + + tf2::Transform offset( + tf2::Quaternion( + marker.pose.orientation.x, + marker.pose.orientation.y, + marker.pose.orientation.z, + marker.pose.orientation.w), + tf2::Vector3( + marker.pose.position.x, + marker.pose.position.y, + marker.pose.position.z)); + + double right = marker.image.width * marker.resolution / 2.0; + double left = -right; + double top = marker.image.height * marker.resolution / 2.0; + double bottom = -top; + + tf2::Vector3 top_left(left, top, 0); + tf2::Vector3 top_right(right, top, 0); + tf2::Vector3 bottom_left(left, bottom, 0); + tf2::Vector3 bottom_right(right, bottom, 0); + + top_left = offset * top_left; + top_right = offset * top_right; + bottom_left = offset * bottom_left; + bottom_right = offset * bottom_right; + + markerData.quad_.clear(); + markerData.quad_.push_back(top_left); + markerData.quad_.push_back(top_right); + markerData.quad_.push_back(bottom_right); + + markerData.quad_.push_back(top_left); + markerData.quad_.push_back(bottom_right); + markerData.quad_.push_back(bottom_left); + + markerData.transformed_quad_.clear(); + for (size_t i = 0; i < markerData.quad_.size(); i++) { + markerData.transformed_quad_.push_back(transform * markerData.quad_[i]); + } + + int32_t max_dimension = std::max(marker.image.height, marker.image.width); + int32_t new_size = 1; + while (new_size < max_dimension) { + new_size = new_size << 1; + } + + if (new_size != markerData.texture_size_ || markerData.encoding_ != marker.image.encoding) { + markerData.texture_size_ = new_size; + + markerData.encoding_ = marker.image.encoding; + + GLuint ids[1]; + + // Free the current texture. + if (markerData.texture_id_ != -1) { + ids[0] = static_cast(markerData.texture_id_); + glDeleteTextures(1, &ids[0]); + } + + // Get a new texture id. + glGenTextures(1, &ids[0]); + markerData.texture_id_ = ids[0]; + + // Bind the texture with the correct size and null memory. + glBindTexture(GL_TEXTURE_2D, static_cast(markerData.texture_id_)); + + glPixelStorei(GL_UNPACK_ALIGNMENT, 1); + + size_t bpp = 0; + if (markerData.encoding_ == sensor_msgs::image_encodings::BGRA8) { + bpp = 4; + markerData.texture_.resize(static_cast(markerData.texture_size_ * + markerData.texture_size_ * 4)); + } else if (markerData.encoding_ == sensor_msgs::image_encodings::BGR8) { + bpp = 3; + markerData.texture_.resize(static_cast(markerData.texture_size_ * + markerData.texture_size_ * 3)); + } else if (markerData.encoding_ == sensor_msgs::image_encodings::MONO8) { + bpp = 1; + markerData.texture_.resize(static_cast(markerData.texture_size_ * + markerData.texture_size_)); + } else { + RCLCPP_WARN(node_->get_logger(), "Unsupported encoding: %s", markerData.encoding_.c_str()); + } + + size_t expected = marker.image.height * marker.image.width * bpp; + if (!markerData.texture_.empty() && marker.image.data.size() < expected) { + RCLCPP_ERROR( + node_->get_logger(), + "TexturedMarker image had expected data size %li but only got %li. Dropping message.", + expected, + marker.image.data.size()); + return; + } + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST); + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); + + glTexEnvf(GL_TEXTURE_ENV, GL_TEXTURE_ENV_MODE, GL_MODULATE); + + glBindTexture(GL_TEXTURE_2D, 0); + + glPixelStorei(GL_UNPACK_ALIGNMENT, 4); + } + + glBindTexture(GL_TEXTURE_2D, static_cast(markerData.texture_id_)); + + if (markerData.encoding_ == sensor_msgs::image_encodings::BGRA8) { + for (size_t row = 0; row < marker.image.height; row++) { + for (size_t col = 0; col < marker.image.width; col++) { + size_t src_index = (row * marker.image.width + col) * 4; + size_t dst_index = (row * markerData.texture_size_ + col) * 4; + + markerData.texture_[dst_index + 0] = marker.image.data[src_index + 0]; + markerData.texture_[dst_index + 1] = marker.image.data[src_index + 1]; + markerData.texture_[dst_index + 2] = marker.image.data[src_index + 2]; + markerData.texture_[dst_index + 3] = marker.image.data[src_index + 3]; + } + } + + glTexImage2D( + GL_TEXTURE_2D, + 0, + GL_RGBA, + markerData.texture_size_, + markerData.texture_size_, + 0, + GL_BGRA, + GL_UNSIGNED_BYTE, + markerData.texture_.data()); + } else if (markerData.encoding_ == sensor_msgs::image_encodings::BGR8) { + for (size_t row = 0; row < marker.image.height; row++) { + for (size_t col = 0; col < marker.image.width; col++) { + size_t src_index = (row * marker.image.width + col) * 3; + size_t dst_index = (row * markerData.texture_size_ + col) * 3; + + markerData.texture_[dst_index + 0] = marker.image.data[src_index + 0]; + markerData.texture_[dst_index + 1] = marker.image.data[src_index + 1]; + markerData.texture_[dst_index + 2] = marker.image.data[src_index + 2]; + } + } + + glTexImage2D( + GL_TEXTURE_2D, + 0, + GL_RGB, + markerData.texture_size_, + markerData.texture_size_, + 0, + GL_BGR, + GL_UNSIGNED_BYTE, + markerData.texture_.data()); + } else if (markerData.encoding_ == sensor_msgs::image_encodings::MONO8) { + for (size_t row = 0; row < marker.image.height; row++) { + for (size_t col = 0; col < marker.image.width; col++) { + size_t src_index = row * marker.image.width + col; + size_t dst_index = row * markerData.texture_size_ + col; + + markerData.texture_[dst_index] = marker.image.data[src_index]; + } + } + + glTexImage2D( + GL_TEXTURE_2D, + 0, + GL_LUMINANCE, + markerData.texture_size_, + markerData.texture_size_, + 0, + GL_LUMINANCE, + GL_UNSIGNED_BYTE, + markerData.texture_.data()); + } + + glBindTexture(GL_TEXTURE_2D, 0); + + markerData.texture_x_ = static_cast(marker.image.width) / + static_cast(markerData.texture_size_); + markerData.texture_y_ = static_cast(marker.image.height) / + static_cast(markerData.texture_size_); + } else { + markers_[marker.ns].erase(marker.id); + } +} + +void TexturedMarkerPlugin::MarkerCallback( + marti_visualization_msgs::msg::TexturedMarker::ConstSharedPtr marker) +{ + Q_EMIT MarkerReceived(*marker); +} + +void TexturedMarkerPlugin::MarkerArrayCallback( + marti_visualization_msgs::msg::TexturedMarkerArray::ConstSharedPtr markers) +{ + for (const auto & marker : markers->markers) { + Q_EMIT MarkerReceived(marker); + } +} + +void TexturedMarkerPlugin::PrintError(const std::string & message) +{ + PrintErrorHelper(ui_.status, message); +} + +void TexturedMarkerPlugin::PrintInfo(const std::string & message) +{ + PrintInfoHelper(ui_.status, message); +} + +void TexturedMarkerPlugin::PrintWarning(const std::string & message) +{ + PrintWarningHelper(ui_.status, message); +} + +QWidget * TexturedMarkerPlugin::GetConfigWidget(QWidget * parent) +{ + config_widget_->setParent(parent); + + return config_widget_; +} + +bool TexturedMarkerPlugin::Initialize(QGLWidget * canvas) +{ + canvas_ = canvas; + + return true; +} + +void TexturedMarkerPlugin::Draw(double x, double y, double scale) +{ + rclcpp::Time now = rclcpp::Time(); + + float alphaVal = alphaVal_; // Set all markers to same alpha value + + std::map>::iterator nsIter; + for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter) { + std::map::iterator markerIter; + for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter) { + MarkerData & marker = markerIter->second; + marker.alpha_ = alphaVal; // Update current marker's alpha value + + if (marker.expire_time > now) { + if (marker.transformed) { + glEnable(GL_TEXTURE_2D); + + glBindTexture(GL_TEXTURE_2D, static_cast(marker.texture_id_)); + + glBegin(GL_TRIANGLES); + + glColor4f(1.0f, 1.0f, 1.0f, marker.alpha_); + + double marker_x = marker.texture_x_; + double marker_y = marker.texture_y_; + + glTexCoord2d(0, 0); glVertex2d( + marker.transformed_quad_[0].x(), marker.transformed_quad_[0].y()); + glTexCoord2d(marker_x, 0); glVertex2d( + marker.transformed_quad_[1].x(), marker.transformed_quad_[1].y()); + glTexCoord2d(marker_x, marker_y); glVertex2d( + marker.transformed_quad_[2].x(), marker.transformed_quad_[2].y()); + + glTexCoord2d(0, 0); glVertex2d( + marker.transformed_quad_[3].x(), marker.transformed_quad_[3].y()); + glTexCoord2d(marker_x, marker_y); glVertex2d( + marker.transformed_quad_[4].x(), marker.transformed_quad_[4].y()); + glTexCoord2d(0, marker_y); glVertex2d( + marker.transformed_quad_[5].x(), marker.transformed_quad_[5].y()); + + glEnd(); + + glBindTexture(GL_TEXTURE_2D, 0); + + glDisable(GL_TEXTURE_2D); + + PrintInfo("OK"); + } + } + } + } +} + +void TexturedMarkerPlugin::Transform() +{ + std::map>::iterator nsIter; + for (nsIter = markers_.begin(); nsIter != markers_.end(); ++nsIter) { + std::map::iterator markerIter; + for (markerIter = nsIter->second.begin(); markerIter != nsIter->second.end(); ++markerIter) { + swri_transform_util::Transform transform; + if (GetTransform(markerIter->second.source_frame_, markerIter->second.stamp, transform)) { + markerIter->second.transformed_quad_.clear(); + for (size_t i = 0; i < markerIter->second.quad_.size(); i++) { + markerIter->second.transformed_quad_.push_back(transform * markerIter->second.quad_[i]); + } + } + } + } +} + +void TexturedMarkerPlugin::LoadConfig(const YAML::Node & node, const std::string & path) +{ + if (node["topic"]) { + std::string topic = node["topic"].as(); + ui_.topic->setText(boost::trim_copy(topic).c_str()); + } + + TopicEdited(); +} + +void TexturedMarkerPlugin::SaveConfig(YAML::Emitter & emitter, const std::string & path) +{ + emitter << YAML::Key << "topic" << YAML::Value << + boost::trim_copy(ui_.topic->text().toStdString()); +} +} // namespace mapviz_plugins diff --git a/mapviz_plugins/src/tf_frame_plugin.cpp b/mapviz_plugins/src/tf_frame_plugin.cpp new file mode 100644 index 000000000..5bc23847f --- /dev/null +++ b/mapviz_plugins/src/tf_frame_plugin.cpp @@ -0,0 +1,255 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// QT libraries +#include +#include + +#include + +// Declare plugin +#include + +// C++ standard libraries +#include +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::TfFramePlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + TfFramePlugin::TfFramePlugin() + : PointDrawingPlugin() + , ui_() + , config_widget_(new QWidget()) + { + ui_.setupUi(config_widget_); + + ui_.color->setColor(Qt::green); + + // Set background white + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + // Set status text red + QPalette p3(ui_.status->palette()); + p3.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p3); + + QObject::connect(ui_.selectframe, SIGNAL(clicked()), this, + SLOT(SelectFrame())); + QObject::connect(ui_.frame, SIGNAL(editingFinished()), this, + SLOT(FrameEdited())); + QObject::connect(ui_.positiontolerance, SIGNAL(valueChanged(double)), this, + SLOT(PositionToleranceChanged(double))); + QObject::connect(ui_.buffersize, SIGNAL(valueChanged(int)), this, + SLOT(BufferSizeChanged(int))); + QObject::connect(ui_.drawstyle, SIGNAL(activated(QString)), this, + SLOT(SetDrawStyle(QString))); + QObject::connect(ui_.static_arrow_sizes, SIGNAL(clicked(bool)), + this, SLOT(SetStaticArrowSizes(bool))); + QObject::connect(ui_.arrow_size, SIGNAL(valueChanged(int)), + this, SLOT(SetArrowSize(int))); + QObject::connect(ui_.color, SIGNAL(colorEdited(const QColor&)), this, + SLOT(SetColor(const QColor&))); + QObject::connect(ui_.buttonResetBuffer, SIGNAL(pressed()), this, + SLOT(ClearPoints())); + } + + void TfFramePlugin::SelectFrame() + { + std::string frame = mapviz::SelectFrameDialog::selectFrame(tf_buf_); + if (!frame.empty()) + { + ui_.frame->setText(QString::fromStdString(frame)); + FrameEdited(); + } + } + + void TfFramePlugin::FrameEdited() + { + source_frame_ = ui_.frame->text().toStdString(); + PrintWarning("Waiting for transform."); + + RCLCPP_INFO(node_->get_logger(), "Setting target frame to to %s", source_frame_.c_str()); + + initialized_ = true; + } + + void TfFramePlugin::TimerCallback() + { + swri_transform_util::Transform transform; + if (GetTransform(node_->get_clock()->now(), transform)) + { + StampedPoint stamped_point; + stamped_point.point = transform.GetOrigin(); + stamped_point.orientation = transform.GetOrientation(); + stamped_point.source_frame = target_frame_; + stamped_point.stamp = tf2_ros::toMsg(transform.GetStamp()); + stamped_point.transformed = false; + + pushPoint( stamped_point ); + } + } + + void TfFramePlugin::PrintError(const std::string& message) + { + PrintErrorHelper(ui_.status, message); + } + + void TfFramePlugin::PrintInfo(const std::string& message) + { + PrintInfoHelper(ui_.status, message); + } + + void TfFramePlugin::PrintWarning(const std::string& message) + { + PrintWarningHelper(ui_.status, message); + } + + QWidget* TfFramePlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool TfFramePlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + timer_ = node_->create_wall_timer(std::chrono::milliseconds(100), + std::bind(&TfFramePlugin::TimerCallback, this)); + + SetColor(ui_.color->color()); + + return true; + } + + void TfFramePlugin::Draw(double x, double y, double scale) + { + if (DrawPoints(scale)) + { + PrintInfo("OK"); + } + } + void TfFramePlugin::LoadConfig(const YAML::Node& node, + const std::string& path) + { + if (node["frame"]) + { + source_frame_ = node["frame"].as(); + ui_.frame->setText(source_frame_.c_str()); + } + + if (node["color"]) + { + std::string color = node["color"].as(); + QColor qcolor(color.c_str()); + SetColor(qcolor); + ui_.color->setColor(qcolor); + } + + if (node["draw_style"]) + { + std::string draw_style = node["draw_style"].as(); + + if (draw_style == "lines") + { + ui_.drawstyle->setCurrentIndex(0); + SetDrawStyle( LINES ); + } else if (draw_style == "points") { + ui_.drawstyle->setCurrentIndex(1); + SetDrawStyle( POINTS ); + } else if (draw_style == "arrows") { + ui_.drawstyle->setCurrentIndex(2); + SetDrawStyle( ARROWS ); + } + } + + if (node["position_tolerance"]) + { + auto position_tolerance = node["position_tolerance"].as(); + ui_.positiontolerance->setValue(position_tolerance); + PositionToleranceChanged(position_tolerance); + } + + if (node["buffer_size"]) + { + auto buffer_size = node["buffer_size"].as(); + ui_.buffersize->setValue(buffer_size); + BufferSizeChanged(buffer_size); + } + + if (node["static_arrow_sizes"]) + { + bool static_arrow_sizes = node["static_arrow_sizes"].as(); + ui_.static_arrow_sizes->setChecked(static_arrow_sizes); + SetStaticArrowSizes(static_arrow_sizes); + } + + if (node["arrow_size"]) + { + int arrow_size = node["arrow_size"].as(); + ui_.arrow_size->setValue(arrow_size); + SetArrowSize(arrow_size); + } + + FrameEdited(); + } + + void TfFramePlugin::SaveConfig(YAML::Emitter& emitter, + const std::string& path) + { + emitter << YAML::Key << "frame" << YAML::Value + << ui_.frame->text().toStdString(); + emitter << YAML::Key << "color" << YAML::Value + << ui_.color->color().name().toStdString(); + + std::string draw_style = ui_.drawstyle->currentText().toStdString(); + emitter << YAML::Key << "draw_style" << YAML::Value << draw_style; + + emitter << YAML::Key << "position_tolerance" << + YAML::Value << positionTolerance(); + + emitter << YAML::Key << "buffer_size" << YAML::Value << bufferSize(); + + emitter << YAML::Key + << "static_arrow_sizes" + << YAML::Value + << ui_.static_arrow_sizes->isChecked(); + + emitter << YAML::Key << "arrow_size" << YAML::Value << ui_.arrow_size->value(); + } +} // namespace mapviz_plugins diff --git a/mapviz_plugins/ui/attitude_indicator_config.ui b/mapviz_plugins/ui/attitude_indicator_config.ui new file mode 100644 index 000000000..9d9753818 --- /dev/null +++ b/mapviz_plugins/ui/attitude_indicator_config.ui @@ -0,0 +1,107 @@ + + + attitude_indicator_config + + + + 0 + 0 + 401 + 68 + + + + false + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + Sans Serif + 10 + + + + Topic: + + + + + + + + + + false + + + Select + + + + + + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + + diff --git a/mapviz_plugins/ui/coordinate_picker_config.ui b/mapviz_plugins/ui/coordinate_picker_config.ui new file mode 100644 index 000000000..608896f37 --- /dev/null +++ b/mapviz_plugins/ui/coordinate_picker_config.ui @@ -0,0 +1,119 @@ + + + coordinate_picker_config + + + + 0 + 0 + 404 + 304 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + + + Status: + + + + + + + + + + + + + No topic + + + true + + + + + + + QPlainTextEdit::NoWrap + + + true + + + 4.000000000000000 + + + Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse + + + + + + + Frame: + + + + + + + + + + Select + + + + + + + Copy to Clipboard on Click + + + + + + + Clear List + + + + + + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + + diff --git a/mapviz_plugins/ui/disparity_config.ui b/mapviz_plugins/ui/disparity_config.ui new file mode 100644 index 000000000..50ec85fd5 --- /dev/null +++ b/mapviz_plugins/ui/disparity_config.ui @@ -0,0 +1,313 @@ + + + disparity_config + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + + 4 + + + 2 + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + + top left + + + + + top center + + + + + top right + + + + + center left + + + + + center + + + + + center right + + + + + bottom left + + + + + bottom center + + + + + bottom right + + + + + + + + + Sans Serif + 8 + + + + Anchor: + + + + + + + + Sans Serif + 8 + + + + Offset X: + + + + + + + 2000 + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + Sans Serif + 8 + + + + Offset Y: + + + + + + + 2000 + + + + + + + + Sans Serif + 8 + + + + Width: + + + + + + + 2000 + + + 320 + + + + + + + + Sans Serif + 8 + + + + Height: + + + + + + + 2000 + + + 240 + + + + + + + + Sans Serif + 8 + + + + Units: + + + + + + + + 16777213 + 25 + + + + + Sans Serif + 9 + + + + + pixels + + + + + percent + + + + + + + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + + diff --git a/mapviz_plugins/ui/draw_polygon_config.ui b/mapviz_plugins/ui/draw_polygon_config.ui new file mode 100644 index 000000000..c171604c7 --- /dev/null +++ b/mapviz_plugins/ui/draw_polygon_config.ui @@ -0,0 +1,152 @@ + + + draw_polygon_config + + + + 0 + 0 + 404 + 304 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + + + Topic: + + + + + + + Publish Polygon + + + + + + + + + + Status: + + + + + + + Clear + + + + + + + + + + Color: + + + + + + + + + + + + + No topic + + + true + + + + + + + Frame: + + + + + + + + + + Select + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/float_config.ui b/mapviz_plugins/ui/float_config.ui new file mode 100644 index 000000000..b3a1c8424 --- /dev/null +++ b/mapviz_plugins/ui/float_config.ui @@ -0,0 +1,358 @@ + + + float_config + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans Serif + 8 + + + + Font: + + + + + + + + 16777215 + 16777215 + + + + + Sans Serif + 8 + + + + Helvetica + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + + top left + + + + + top center + + + + + top right + + + + + center left + + + + + center + + + + + center right + + + + + bottom left + + + + + bottom center + + + + + bottom right + + + + + + + + 2000 + + + + + + + + Sans Serif + 8 + + + + Anchor: + + + + + + + + Sans Serif + 8 + + + + Offset X: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + 2000 + + + + + + + + Sans Serif + 8 + + + + Offset Y: + + + + + + + + Sans Serif + 8 + + + + Units: + + + + + + + + 16777213 + 25 + + + + + Sans Serif + 9 + + + + + pixels + + + + + percent + + + + + + + + + + + Postfix: + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + SelectFont() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/gps_config.ui b/mapviz_plugins/ui/gps_config.ui new file mode 100644 index 000000000..876e6b207 --- /dev/null +++ b/mapviz_plugins/ui/gps_config.ui @@ -0,0 +1,330 @@ + + + gps_config + + + + 0 + 0 + 400 + 222 + + + + Form + + + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + Sans Serif + 8 + + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + Sans Serif + 8 + + + + Draw Style: + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + + lines + + + + + points + + + + + arrows + + + + + + + + + Sans Serif + 8 + + + + Static Arrow Sizes: + + + + + + + + + + + + + + + + 1 + + + 500 + + + 25 + + + Qt::Horizontal + + + + + + + + + + Sans Serif + 8 + + + + Position Tolerance: + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 1.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Buffer Size: + + + + + + + + + QAbstractSpinBox::PlusMinus + + + 99999999 + + + + + + + + 55 + 16777215 + + + + Clear + + + + + + + + + Show Laps + + + + + + + + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/grid_config.ui b/mapviz_plugins/ui/grid_config.ui new file mode 100644 index 000000000..f7a7239f5 --- /dev/null +++ b/mapviz_plugins/ui/grid_config.ui @@ -0,0 +1,328 @@ + + + grid_config + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + + 4 + + + 2 + + + + + + Sans Serif + 8 + + + + Frame: + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + Sans Serif + 8 + + + + X: + + + + + + + + Sans Serif + 8 + + + + Y: + + + + + + + + Sans Serif + 8 + + + + Size: + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + + + + No frame + + + true + + + + + + + + Sans Serif + 8 + + + + Rows: + + + + + + + + Sans Serif + 8 + + + + Columns: + + + + + + + + Sans Serif + 8 + + + + Alpha: + + + + + + + + 8 + + + + Select + + + + + + + + 8 + + + + + + + + true + + + 1.000000000000000 + + + 0.010000000000000 + + + 1.000000000000000 + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::UpDownArrows + + + + + + -999999999.000000000000000 + + + 999999999.000000000000000 + + + 0.000000000000000 + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::UpDownArrows + + + + + + -999999999.000000000000000 + + + 999999999.000000000000000 + + + 0.000000000000000 + + + + + + + QAbstractSpinBox::UpDownArrows + + + 999999999.000000000000000 + + + 1.000000000000000 + + + + + + + QAbstractSpinBox::PlusMinus + + + 1 + + + 10000 + + + + + + + QAbstractSpinBox::PlusMinus + + + 1 + + + 10000 + + + 1 + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/image_config.ui b/mapviz_plugins/ui/image_config.ui new file mode 100644 index 000000000..31c5ff450 --- /dev/null +++ b/mapviz_plugins/ui/image_config.ui @@ -0,0 +1,367 @@ + + + image_config + + + + 0 + 0 + 396 + 371 + + + + Form + + + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + 16777215 + 25 + + + + + default + + + + + + + + + Sans Serif + 8 + + + + Anchor: + + + + + + + Keep original aspect ratio + + + + + + + + Sans Serif + 8 + + + + Units: + + + + + + + + Sans Serif + 8 + + + + Height: + + + + + + + + 16777213 + 25 + + + + + Sans Serif + 9 + + + + + pixels + + + + + percent + + + + + + + + + Sans Serif + 8 + + + + Transport: + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + Width: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + Sans Serif + 8 + + + + Offset Y: + + + + + + + + Sans Serif + 8 + + + + Offset X: + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + 2000 + + + + + + + 2000 + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + + top left + + + + + top center + + + + + top right + + + + + center left + + + + + center + + + + + center right + + + + + bottom left + + + + + bottom center + + + + + bottom right + + + + + + + + + Sans Serif + 8 + + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + 0 + + + 1.000000000000000 + + + 10000.000000000000000 + + + 320.000000000000000 + + + + + + + 0 + + + 1.000000000000000 + + + 10000.000000000000000 + + + 240.000000000000000 + + + + + + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + + diff --git a/mapviz_plugins/ui/laserscan_config.ui b/mapviz_plugins/ui/laserscan_config.ui new file mode 100644 index 000000000..3997613c3 --- /dev/null +++ b/mapviz_plugins/ui/laserscan_config.ui @@ -0,0 +1,376 @@ + + + laserscan_config + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + Sans Serif + 8 + + + + Min Value: + + + + + + + -999999999.000000000000000 + + + 999999999.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Max Value: + + + + + + + -999999999.000000000000000 + + + 999999999.000000000000000 + + + 100.000000000000000 + + + + + + + 99999999 + + + 1 + + + + + + + 1.000000000000000 + + + 0.100000000000000 + + + 1.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Alpha: + + + + + + + + + + + Sans Serif + 8 + + + + Point Size: + + + + + + + pixel + + + 1 + + + 3 + + + + + + + + Sans Serif + 8 + + + + Buffer Size: + + + + + + + + Sans Serif + 8 + + + + Color Transformer: + + + + + + + + + + Sans Serif + 8 + + + + Use Rainbow + + + + + + + + + + Sans Serif + 8 + false + + + + Min: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 24 + 24 + + + + + + + + + + + + Sans Serif + 8 + + + + Max: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 24 + 24 + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/marker_config.ui b/mapviz_plugins/ui/marker_config.ui new file mode 100644 index 000000000..745e0c95c --- /dev/null +++ b/mapviz_plugins/ui/marker_config.ui @@ -0,0 +1,133 @@ + + + marker_config + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + Clear All Markers + + + + + + + + + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + + diff --git a/mapviz_plugins/ui/measuring_config.ui b/mapviz_plugins/ui/measuring_config.ui new file mode 100644 index 000000000..0639690e3 --- /dev/null +++ b/mapviz_plugins/ui/measuring_config.ui @@ -0,0 +1,269 @@ + + + measuring_config + + + + 0 + 0 + 300 + 240 + + + + + 8 + + + + Form + + + + + + + + + + 100 + 16777215 + + + + Distance: + + + + + + + + + + true + + + + + + + + 100 + 16777215 + + + + Total Distance: + + + + + + + + + + true + + + + + + + + 24 + 24 + + + + + + + false + + + + + + + Status: + + + + + + + + + + No topic + + + true + + + + + + + + + + true + + + + + + + Show Measurements: + + + + + + + + 140 + 16777215 + + + + Clear + + + + 16 + 16 + + + + + + + + + 24 + 24 + + + + + + + false + + + + + + + Main Color: + + + + + + + Background Color: + + + + + + + Show Background Color: + + + + + + + + + + true + + + + + + + + 48 + 16777215 + + + + QAbstractSpinBox::PlusMinus + + + 5 + + + 40 + + + 10 + + + + + + + Font Size: + + + + + + + + 48 + 16777215 + + + + QAbstractSpinBox::PlusMinus + + + 0.0 + + + 1.0 + + + 0.5 + + + 0.1 + + + + + + + Alpha: + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/move_base_config.ui b/mapviz_plugins/ui/move_base_config.ui new file mode 100644 index 000000000..4700a653d --- /dev/null +++ b/mapviz_plugins/ui/move_base_config.ui @@ -0,0 +1,202 @@ + + + move_base_config + + + + 0 + 0 + 394 + 218 + + + + Form + + + + + + + + + 11 + + + + + + 65 + 0 + + + + + 65 + 16777215 + + + + + 8 + + + + <html><head/><body><p>Abort [2D Nav Goal] execution</p></body></html> + + + Abort + + + + :/images/remove-icon-th.png:/images/remove-icon-th.png + + + + + + + + 100 + 0 + + + + + 110 + 16777215 + + + + + 8 + + + + <html><head/><body><p>Publish robot pose on topic [/initialpose]</p></body></html> + + + Estimated Pose + + + + :/images/green-arrow.png:/images/green-arrow.png + + + true + + + + + + + + 100 + 0 + + + + + 100 + 16777215 + + + + + 8 + + + + <html><head/><body><p>Send a goal to [move_base] action server</p></body></html> + + + 2D Nav Goal + + + + :/images/green-arrow.png:/images/green-arrow.png + + + true + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Qt::Horizontal + + + + + + + + + + + + Status: + + + + + + + + + + + + + No topic + + + true + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + + diff --git a/mapviz_plugins/ui/navsat_config.ui b/mapviz_plugins/ui/navsat_config.ui new file mode 100644 index 000000000..f811fa51e --- /dev/null +++ b/mapviz_plugins/ui/navsat_config.ui @@ -0,0 +1,282 @@ + + + navsat_config + + + + 0 + 0 + 400 + 159 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + Sans Serif + 8 + + + + Buffer Size: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + Sans Serif + 8 + + + + Position Tolerance: + + + + + + + QAbstractSpinBox::PlusMinus + + + 99999999 + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + 55 + 16777215 + + + + Clear + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 1.000000000000000 + + + + + + + + Sans Serif + 8 + + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + + lines + + + + + points + + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + Draw Style: + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/occupancy_grid_config.ui b/mapviz_plugins/ui/occupancy_grid_config.ui new file mode 100644 index 000000000..ad5601214 --- /dev/null +++ b/mapviz_plugins/ui/occupancy_grid_config.ui @@ -0,0 +1,181 @@ + + + occupancy_grid_config + + + + 0 + 0 + 347 + 123 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + 50 + 16777215 + + + + 1 + + + 1.000000000000000 + + + 0.100000000000000 + + + 1.000000000000000 + + + + + + + Subscribe to grid_updates + + + true + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + 8 + + + + Alpha: + + + + + + + + 8 + + + + + + + + + Sans Serif + 8 + + + + + + + No frame + + + true + + + + + + + + 100 + 16777215 + + + + + 8 + + + + Select Topic: + + + + + + + + 8 + + + + Color Scheme: + + + + + + + + 100 + 16777215 + + + + + map + + + + + costmap + + + + + + + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + + diff --git a/mapviz_plugins/ui/odometry_config.ui b/mapviz_plugins/ui/odometry_config.ui new file mode 100644 index 000000000..8dd0484b1 --- /dev/null +++ b/mapviz_plugins/ui/odometry_config.ui @@ -0,0 +1,409 @@ + + + odometry_config + + + + 0 + 0 + 286 + 312 + + + + Form + + + + + + + + + + Sans Serif + 8 + + + + Timestamp Interval: + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + + + + + + + + + + + + + + + Sans Serif + 8 + + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 1.000000000000000 + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + Buffer Size: + + + + + + + QAbstractSpinBox::PlusMinus + + + 99999999 + + + + + + + + 55 + 16777215 + + + + Clear + + + + + + + + Sans Serif + 8 + + + + Show Covariance: + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + + lines + + + + + points + + + + + arrows + + + + + + + + + Sans Serif + 8 + + + + Draw Style: + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + 8 + + + + Show Laps + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + Sans Serif + 8 + + + + Static Arrow Sizes: + + + + + + + + Sans Serif + 8 + + + + Position Tolerance: + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 0.000000000000000 + + + + + + + 6 + + + + + + + + + + + + 1 + + + 500 + + + 25 + + + Qt::Horizontal + + + QSlider::NoTicks + + + + + + + + + + Sans Serif + 8 + + + + All Covariances: + + + + + + + + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/path_config.ui b/mapviz_plugins/ui/path_config.ui new file mode 100644 index 000000000..5a43a980e --- /dev/null +++ b/mapviz_plugins/ui/path_config.ui @@ -0,0 +1,159 @@ + + + path_config + + + + 0 + 0 + 400 + 79 + + + + Form + + + + + + + 4 + + + 2 + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + 8 + + + + Color: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + 24 + 24 + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/plan_route_config.ui b/mapviz_plugins/ui/plan_route_config.ui new file mode 100644 index 000000000..5d970b3a2 --- /dev/null +++ b/mapviz_plugins/ui/plan_route_config.ui @@ -0,0 +1,178 @@ + + + plan_route_config + + + + 0 + 0 + 404 + 304 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + + + + -1 + + + + + + + No topic + + + true + + + + + + + + -1 + + + + Preview Color: + + + + + + + + -1 + + + + Plan Route Service: + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + -1 + + + + + + + + Publish Route + + + + + + + + -1 + + + + Status: + + + + + + + + -1 + + + + Route Topic: + + + + + + + + + + + + + + Start From Vehicle: + + + + + + + Clear + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/point_click_publisher_config.ui b/mapviz_plugins/ui/point_click_publisher_config.ui new file mode 100644 index 000000000..341925eed --- /dev/null +++ b/mapviz_plugins/ui/point_click_publisher_config.ui @@ -0,0 +1,132 @@ + + + point_click_publisher_config + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + + 4 + + + 2 + + + + + + Sans Serif + 8 + + + + clicked_point + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + Sans Serif + 8 + + + + Frame: + + + + + + + + 0 + 0 + + + + + 16777215 + 25 + + + + + Sans Serif + 8 + + + + The reference frame that points will be published in. + + + + true + + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + + diff --git a/mapviz_plugins/ui/pointcloud2_config.ui b/mapviz_plugins/ui/pointcloud2_config.ui new file mode 100644 index 000000000..745bae579 --- /dev/null +++ b/mapviz_plugins/ui/pointcloud2_config.ui @@ -0,0 +1,476 @@ + + + PointCloud2_config + + + + 0 + 0 + 307 + 341 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + 1 + + + 100 + + + 1 + + + + + + + + + + 1.000000000000000 + + + 0.100000000000000 + + + 1.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Alpha: + + + + + + + Qt::Vertical + + + + 20 + 0 + + + + + + + + + Sans Serif + 8 + + + + Point Size: + + + + + + + pixel + + + 1 + + + 3 + + + + + + + + Sans Serif + 8 + + + + Buffer Size: + + + + + + + + Sans Serif + 8 + + + + Color Transformer: + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + + + Sans Serif + 8 + + + + Use Rainbow + + + + + + + + 8 + + + + Use Auto Max/Min + + + + + + + + 8 + + + + Unpack RGB + + + + + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + + Sans Serif + 8 + false + + + + Min: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 24 + 24 + + + + + + + + + + + + Sans Serif + 8 + + + + Max: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 24 + 24 + + + + + + + + + + + Qt::Horizontal + + + + 4 + 20 + + + + + + + + + + + + + + 0 + 0 + + + + + 0 + + + 0 + + + 0 + + + 0 + + + 4 + + + + + + 99 + 0 + + + + + Sans Serif + 8 + + + + Min Value: + + + + + + + + Sans Serif + 8 + + + + Max Value: + + + + + + + -999999999.000000000000000 + + + 999999999.000000000000000 + + + + + + + -999999999.000000000000000 + + + 999999999.000000000000000 + + + 100.000000000000000 + + + + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + 55 + 16777215 + + + + Clear + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/pose_config.ui b/mapviz_plugins/ui/pose_config.ui new file mode 100644 index 000000000..9659b12b5 --- /dev/null +++ b/mapviz_plugins/ui/pose_config.ui @@ -0,0 +1,330 @@ + + + pose_config + + + + 0 + 0 + 400 + 222 + + + + Form + + + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + Sans Serif + 8 + + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + Sans Serif + 8 + + + + Draw Style: + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + + lines + + + + + points + + + + + arrows + + + + + + + + + Sans Serif + 8 + + + + Static Arrow Sizes: + + + + + + + + + + + + + + + + 1 + + + 500 + + + 25 + + + Qt::Horizontal + + + + + + + + + + Sans Serif + 8 + + + + Position Tolerance: + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 1.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Buffer Size: + + + + + + + + + QAbstractSpinBox::PlusMinus + + + 99999999 + + + + + + + + 55 + 16777215 + + + + Clear + + + + + + + + + Show Laps + + + + + + + + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/robot_image_config.ui b/mapviz_plugins/ui/robot_image_config.ui new file mode 100644 index 000000000..548be82ef --- /dev/null +++ b/mapviz_plugins/ui/robot_image_config.ui @@ -0,0 +1,315 @@ + + + robot_image_config + + + + 0 + 0 + 383 + 300 + + + + Form + + + + + + + + + + Sans Serif + 8 + + + + Image File: + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Browse + + + + + + + + Sans Serif + 8 + + + + Frame: + + + + + + + + Sans Serif + 8 + + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + Width: + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 2.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Height: + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 1.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Offset x: + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 0.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Offset y: + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 0.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + Image ratio: + + + + + + + + Sans Serif + 8 + + + + + + + + + + + Custom + + + + + + + 1:1 + + + + + + + Original + + + + + + + + + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + + diff --git a/mapviz_plugins/ui/route_config.ui b/mapviz_plugins/ui/route_config.ui new file mode 100644 index 000000000..5eb43aec9 --- /dev/null +++ b/mapviz_plugins/ui/route_config.ui @@ -0,0 +1,296 @@ + + + route_config + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + 24 + 24 + + + + + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + 2 + + + 0 + + + + lines + + + + + points + + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + CrossCursor + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + Draw Style: + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + + + + Sans Serif + 8 + + + + + + + + + 8 + + + + Position Topic: + + + + + + + true + + + + 55 + 16777215 + + + + + 8 + + + + Select + + + + + + + + 8 + + + + Waypoint Color: + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + 1 + + + 30 + + + Qt::Horizontal + + + + + + + + 8 + + + + Icon Size: + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/string_config.ui b/mapviz_plugins/ui/string_config.ui new file mode 100644 index 000000000..3fa16e11c --- /dev/null +++ b/mapviz_plugins/ui/string_config.ui @@ -0,0 +1,339 @@ + + + string_config + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + + 4 + + + 2 + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + + Sans Serif + 8 + + + + Font: + + + + + + + + 16777215 + 16777215 + + + + + Sans Serif + 8 + + + + Helvetica + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + + top left + + + + + top center + + + + + top right + + + + + center left + + + + + center + + + + + center right + + + + + bottom left + + + + + bottom center + + + + + bottom right + + + + + + + + + Sans Serif + 8 + + + + Anchor: + + + + + + + + Sans Serif + 8 + + + + Offset X: + + + + + + + 2000 + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + Sans Serif + 8 + + + + Offset Y: + + + + + + + 2000 + + + + + + + + Sans Serif + 8 + + + + Units: + + + + + + + + 16777213 + 25 + + + + + Sans Serif + 9 + + + + + pixels + + + + + percent + + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + SelectFont() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/textured_marker_config.ui b/mapviz_plugins/ui/textured_marker_config.ui new file mode 100644 index 000000000..4699395ef --- /dev/null +++ b/mapviz_plugins/ui/textured_marker_config.ui @@ -0,0 +1,162 @@ + + + textured_marker_config + + + + 0 + 0 + 400 + 330 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + Sans Serif + 8 + + + + Topic: + + + + + + + Clear All Markers + + + + + + + + Sans Serif + 8 + + + + Alpha: + + + + + + + 5 + + + 25 + + + 25 + + + Qt::Horizontal + + + QSlider::NoTicks + + + + + + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + + diff --git a/mapviz_plugins/ui/tf_frame_config.ui b/mapviz_plugins/ui/tf_frame_config.ui new file mode 100644 index 000000000..5e44049c9 --- /dev/null +++ b/mapviz_plugins/ui/tf_frame_config.ui @@ -0,0 +1,312 @@ + + + tf_frame_config + + + + 0 + 0 + 383 + 197 + + + + Form + + + + + + + + + + Sans Serif + 8 + + + + Color: + + + + + + + + 0 + 0 + + + + QAbstractSpinBox::PlusMinus + + + + + + 1.000000000000000 + + + + + + + + Sans Serif + 8 + + + + Frame: + + + + + + + + 16777215 + 25 + + + + + Sans Serif + 9 + + + + + lines + + + + + points + + + + + arrows + + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Select + + + + + + + + 24 + 24 + + + + false + + + + + + + + + + + + + + 55 + 16777215 + + + + Clear + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + Buffer Size: + + + + + + + QAbstractSpinBox::PlusMinus + + + 99999999 + + + + + + + + Sans Serif + 8 + + + + Position Tolerance: + + + + + + + + Sans Serif + 8 + + + + + + + No topic + + + true + + + + + + + + + + + + + + + + 1 + + + 500 + + + 25 + + + Qt::Horizontal + + + + + + + + + + Sans Serif + 8 + + + + Draw Style: + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans Serif + 8 + + + + Static Arrow Sizes: + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + mapviz::ColorButton + QPushButton +
      mapviz/color_button.h
      +
      +
      + + + + SelectColor() + SelectTopic() + TopicEdited() + PositionToleranceChanged(double) + AngleToleranceChanged(double) + +
      diff --git a/mapviz_plugins/ui/topic_select.ui b/mapviz_plugins/ui/topic_select.ui new file mode 100644 index 000000000..4642c4c81 --- /dev/null +++ b/mapviz_plugins/ui/topic_select.ui @@ -0,0 +1,74 @@ + + + topicselect + + + + 0 + 0 + 400 + 300 + + + + Select Topic + + + true + + + + + + true + + + + + + + Qt::Vertical + + + QDialogButtonBox::Cancel|QDialogButtonBox::Ok + + + + + + + + + buttonBox + accepted() + topicselect + accept() + + + 306 + 243 + + + 157 + 274 + + + + + buttonBox + rejected() + topicselect + reject() + + + 316 + 260 + + + 286 + 274 + + + + + diff --git a/multires_image/CHANGELOG.rst b/multires_image/CHANGELOG.rst new file mode 100644 index 000000000..460df5203 --- /dev/null +++ b/multires_image/CHANGELOG.rst @@ -0,0 +1,129 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package multires_image +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.3.0 (2023-08-24) +------------------ + +2.2.2 (2023-06-07) +------------------ +* Iron Compatibility (`#779 `_) +* Contributors: David Anthony + +2.2.1 (2023-05-30) +------------------ +* Updating maintainers list (`#778 `_) +* Merge pull request `#754 `_ from cottsay/python3-shebang +* Use python3 in mapviz_tile_loader shebang +* Contributors: David Anthony, Scott K Logan + +2.1.0 (2020-10-22) +------------------ +* ROS Foxy support (`#695 `_) +* Contributors: P. J. Reed + +2.0.0 (2020-05-13) +------------------ +* Port mapviz to ROS 2 (`#672 `_) +* Remove OpenGL warning (`#667 `_) +* Contributors: Daniel D'Souza, P. J. Reed, Jacob Hassold, Kevin Nickels, Roger Strain + +1.2.0 (2019-09-04) +------------------ +* Use local_xy_origin for loading tiles of GPSFix not available (`#634 `_) +* Contributors: agyoungs + +1.1.1 (2019-05-17) +------------------ + +1.1.0 (2019-02-20) +------------------ + +1.0.1 (2019-01-25) +------------------ + +1.0.0 (2019-01-23) +------------------ +* Sharing tf_manager\_ between main app and plugins (`#555 `_) +* Contributors: Davide Faconti + +0.3.0 (2018-11-16) +------------------ +* Merge all -devel branches into a single master branch +* Contributors: P. J. Reed + +0.2.6 (2018-07-31) +------------------ + +0.2.5 (2018-04-12) +------------------ +* Add ability to set offset for multires image (`#565 `_) +* Fix multires image scale when projection is WGS84. +* update to use non deprecated pluginlib macro +* Mapviz tile loader (Kinetic) (`#509 `_) +* Change package.xml dep order +* Support transparent tiles in multires_image +* Contributors: Marc Alban, Mikael Arguedas, P. J. Reed, jgassaway + +0.2.4 (2017-08-11) +------------------ + +0.2.3 (2016-12-10) +------------------ + +0.2.2 (2016-12-07) +------------------ +* Migrated OpenCV to 3.1 (default in Kinetic) +* Contributors: Brian Holt + +0.2.1 (2016-10-23) +------------------ + +0.2.0 (2016-06-23) +------------------ +* Update Qt to version 5 +* Contributors: Ed Venator + +0.1.3 (2016-05-20) +------------------ +* Implement service for adding and modifying mapviz displays. +* Fix for `#339 `_; explicitly depending on OpenCV 2 +* Contributors: Marc Alban, P. J. Reed + +0.1.2 (2016-01-06) +------------------ +* Enables the possibility to load a one-layer tile set +* Contributors: Vincent Rousseau + +0.1.1 (2015-11-17) +------------------ +* Use extension from geo file +* Contributors: Vincent Rousseau + +0.1.0 (2015-09-29) +------------------ + +0.0.3 (2015-09-28) +------------------ + +0.0.2 (2015-09-27) +------------------ +* Adds missing qt4_opengl dependency + +0.0.1 (2015-09-27) +------------------ +* Renames all marti_common packages that were renamed. + (See http://github.com/swri-robotics/marti_common/issues/231) +* Fixes catkin_lint problems that could prevent installation. +* Cleans up dependencies +* Adds find_package(OpenCV REQUIRED) to cmake config +* fixes lint issues +* updates cmake version to squash the CMP0003 warning +* removes dependencies on build_tools +* uses format 2 package definition +* fix missing organization in license text +* exports the multires_image library +* catkinizes mapviz +* changes license to BSD +* adds license and readme files +* Contributors: Ed Venator, Edward Venator, Jerry Towler, Marc Alban, P. J. Reed diff --git a/multires_image/CMakeLists.txt b/multires_image/CMakeLists.txt new file mode 100644 index 000000000..a1ac52338 --- /dev/null +++ b/multires_image/CMakeLists.txt @@ -0,0 +1,169 @@ +### SET CMAKE POLICIES ### +cmake_minimum_required(VERSION 3.10...3.17) + +if(${CMAKE_VERSION} VERSION_LESS 3.12) + cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) +endif() + +if (NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(${CMAKE_VERSION} VERSION_EQUAL "3.11.0" OR ${CMAKE_VERSION} VERSION_GREATER "3.11.0") + cmake_policy(SET CMP0072 NEW) +endif() + +if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() +### END CMAKE POLICIES ### + +project(multires_image + LANGUAGES CXX) + +find_package(ament_cmake REQUIRED) +find_package(cv_bridge REQUIRED) +find_package(gps_msgs REQUIRED) +find_package(mapviz REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(tf2 REQUIRED) +find_package(swri_transform_util REQUIRED) +find_package(swri_math_util REQUIRED) + +### Boost ### +find_package(Boost REQUIRED filesystem thread) + +### OpenGL ### +find_package(OpenGL REQUIRED) + +### OpenCV ### +# multires_image doesn't directly use OpenCV, but it uses swri_transform_util, and +# we need to include OpenCV to make one of its headers compile. +find_package(OpenCV COMPONENTS core imgproc REQUIRED) + +find_package(Qt5Core REQUIRED) +find_package(Qt5Gui REQUIRED) +find_package(Qt5OpenGL REQUIRED) +find_package(Qt5Widgets REQUIRED) +add_definitions(-DWFlags=WindowFlags) + +set(CMAKE_INCLUDE_CURRENT_DIR ON) + +# Build libtile_cache +set(TILE_SRC_FILES + src/tile.cpp + src/tile_cache.cpp + src/tile_set.cpp + src/tile_set_layer.cpp) + +qt5_wrap_cpp(TILE_SRC_FILES include/${PROJECT_NAME}/tile_cache.h) + +add_library(${PROJECT_NAME} + ${TILE_SRC_FILES} +) +target_include_directories(${PROJECT_NAME} + PUBLIC + include) +target_link_libraries(${PROJECT_NAME} + ${Boost_LIBRARIES} + OpenGL::GL + Qt5::Core + Qt5::Gui + Qt5::OpenGL + Qt5::Widgets +) +ament_target_dependencies(${PROJECT_NAME} + ament_cmake + cv_bridge + gps_msgs + mapviz + pluginlib + rclcpp + tf2 + swri_transform_util + swri_math_util +) + +# Build libmultires_widget +set(UI_FILES + src/QGLMap.ui + src/multires_config.ui +) +set(WIDGET_SRC_FILES src/tile_view.cpp src/QGLMap.cpp) + +qt5_wrap_ui(WIDGET_SRC_FILES ${UI_FILES}) +qt5_wrap_cpp(WIDGET_SRC_FILES include/${PROJECT_NAME}/QGLMap.h) + +add_library(multires_widget + ${WIDGET_SRC_FILES} +) +target_link_libraries(multires_widget + ${PROJECT_NAME} + OpenGL::GL + Qt5::Core + Qt5::Gui + Qt5::OpenGL + Qt5::Widgets +) + +# Build nodes +set(VIEW_NODE_SRC_FILES src/nodes/multires_view_node.cpp) +qt5_wrap_cpp(VIEW_NODE_SRC_FILES include/${PROJECT_NAME}/multires_view_node.h) +add_executable(multires_view_node ${VIEW_NODE_SRC_FILES}) +target_link_libraries(multires_view_node + multires_widget + Boost::filesystem + Boost::thread +) +ament_target_dependencies(multires_view_node + ament_cmake + rclcpp + swri_transform_util +) + +# Build mapviz plugin +set(MAPVIZ_SRC_FILES + src/${PROJECT_NAME}_plugin.cpp + src/multires_view.cpp) +qt5_wrap_ui(MAPVIZ_SRC_FILES src/multires_config.ui) +qt5_wrap_cpp(MAPVIZ_SRC_FILES include/${PROJECT_NAME}/${PROJECT_NAME}_plugin.h) + +add_library(${PROJECT_NAME}_plugin SHARED + ${MAPVIZ_SRC_FILES} +) +target_compile_definitions(${PROJECT_NAME}_plugin PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") +target_link_libraries(${PROJECT_NAME}_plugin + ${PROJECT_NAME} +) + +### Install ${PROJECT_NAME} plugin ### +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION include/${PROJECT_NAME} + FILES_MATCHING PATTERN "*.h" +) + +install(TARGETS ${PROJECT_NAME} + multires_view_node + multires_widget + ${PROJECT_NAME}_plugin + RUNTIME DESTINATION lib/${PROJECT_NAME} + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib +) + +install(PROGRAMS nodes/mapviz_tile_loader + DESTINATION lib/${PROJECT_NAME} +) + +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME} + FILES_MATCHING PATTERN ".py" PATTERN ".launch" +) + +pluginlib_export_plugin_description_file(mapviz mapviz_plugins.xml) + +ament_export_dependencies(${RUNTIME_DEPS} Qt) +ament_export_include_directories(include) +ament_export_libraries(${PROJECT_NAME}) +ament_package() diff --git a/multires_image/include/multires_image/QGLMap.h b/multires_image/include/multires_image/QGLMap.h new file mode 100644 index 000000000..f56070aa1 --- /dev/null +++ b/multires_image/include/multires_image/QGLMap.h @@ -0,0 +1,110 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MULTIRES_IMAGE_QGLMAP_H_ +#define MULTIRES_IMAGE_QGLMAP_H_ + +// QT libraries +#include +#include +#include + +// QT auto-generated headers +#include "ui_QGLMap.h" + +#include + +#include +#include + +namespace multires_image +{ + class QGLMap : public QGLWidget + { + Q_OBJECT + + public: + explicit QGLMap(QWidget *parent = 0); + ~QGLMap() override = default; + + void Exit(); + void UpdateView(); + void SetTiles(TileSet* tiles); + + tf2::Vector3 SceneCenter() { return m_scene_center; } + tf2::Vector3 ViewCenter() { return m_view_center; } + + signals: + void SignalZoomChange(double z); + void SignalViewChange(double x1, double y1, double x2, double y2); + void SignalMemorySize(int64_t bytes); + + public slots: + void LoadTexture(Tile* tile); + void DeleteTexture(Tile* tile); + void ChangeCenter(double x, double y); + void SetTextureMemory(int64_t bytes); + + protected: + void initializeGL() override; + void resizeGL(int w, int h) override; + void paintGL() override; + void mousePressEvent(QMouseEvent* e) override; + void mouseDoubleClickEvent(QMouseEvent* e) override; + void mouseReleaseEvent(QMouseEvent* e) override; + void mouseMoveEvent(QMouseEvent* e) override; + void wheelEvent(QWheelEvent* e) override; + + private: + Ui::QGLMapClass ui; + + bool m_initialized; + + double m_scale; + + bool m_mouseDown; + int m_mouseDownX; + int m_mouseDownY; + + TileView* m_tileView; + + tf2::Vector3 m_view_top_left; + tf2::Vector3 m_view_bottom_right; + tf2::Vector3 m_view_center; + + tf2::Vector3 m_scene_top_left; + tf2::Vector3 m_scene_bottom_right; + tf2::Vector3 m_scene_center; + + void Recenter(); + void MousePan(int x, int y); + }; +} + +#endif // MULTIRES_IMAGE_QGLMAP_H_ diff --git a/multires_image/include/multires_image/multires_image_plugin.h b/multires_image/include/multires_image/multires_image_plugin.h new file mode 100644 index 000000000..570c93b14 --- /dev/null +++ b/multires_image/include/multires_image/multires_image_plugin.h @@ -0,0 +1,113 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS_MULTIRES_IMAGE_PLUGIN_H_ +#define MAPVIZ_PLUGINS_MULTIRES_IMAGE_PLUGIN_H_ + +// C++ standard libraries +#include + +// Boost libraries +#include + +#include + +// QT libraries +#include +#include +#include + +#include +#include + +#include + +// QT autogenerated files +#include "ui_multires_config.h" + +namespace mapviz_plugins +{ + class MultiresImagePlugin : public mapviz::MapvizPlugin + { + Q_OBJECT + + public: + MultiresImagePlugin(); + ~MultiresImagePlugin() override; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void Transform() override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + protected: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + protected Q_SLOTS: + void SelectFile(); + void AcceptConfiguration(); + void SetXOffset(double long_offset); + void SetYOffset(double latitude_offset); + + private: + bool loaded_; + double center_x_; + double center_y_; + double offset_x_; + double offset_y_; + + multires_image::TileSet* tile_set_; + MultiresView* tile_view_; + + Ui::multires_config ui_; + QWidget* config_widget_; + + swri_transform_util::Transform transform_; + swri_transform_util::Transform inverse_transform_; + + bool transformed_; + + void GetCenterPoint(double x, double y); + + boost::filesystem::path MakePathRelative( + boost::filesystem::path path, + boost::filesystem::path base); + }; +} + +#endif // MAPVIZ_PLUGINS_MULTIRES_IMAGE_PLUGIN_H_ diff --git a/multires_image/include/multires_image/multires_view.h b/multires_image/include/multires_image/multires_view.h new file mode 100644 index 000000000..a94d743fb --- /dev/null +++ b/multires_image/include/multires_image/multires_view.h @@ -0,0 +1,68 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MAPVIZ_PLUGINS_MULTIRES_VIEW_H_ +#define MAPVIZ_PLUGINS_MULTIRES_VIEW_H_ + +// QT libraries +#include + +#include +#include + +namespace mapviz_plugins +{ +class MultiresView +{ + public: + MultiresView(multires_image::TileSet* tiles, QGLWidget* widget); + ~MultiresView() = default; + + const multires_image::TileCache* Cache() { return &m_cache; } + + void SetView(double x, double y, double radius, double scale); + + void Draw(); + + void Exit() { m_cache.Exit(); } + + private: + multires_image::TileSet* m_tiles; + multires_image::TileCache m_cache; + int m_currentLayer; + int m_startRow; + int m_startColumn; + int m_endRow; + int m_endColumn; + + double min_scale_; + }; +} + +#endif // MAPVIZ_PLUGINS_MULTIRES_VIEW_H_ diff --git a/multires_image/include/multires_image/multires_view_node.h b/multires_image/include/multires_image/multires_view_node.h new file mode 100644 index 000000000..b821ce6ab --- /dev/null +++ b/multires_image/include/multires_image/multires_view_node.h @@ -0,0 +1,84 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MULTIRES_IMAGE_MULTIRES_VIEW_NODE_H_ +#define MULTIRES_IMAGE_MULTIRES_VIEW_NODE_H_ + +// C++ standard libraries +#include + +// Boost libraries +#include + +// QT libraries +#include +#include +#include +#include + +// ROS libraries +#include + +#include +#include + +namespace multires_image +{ + class MultiresViewNode : public QMainWindow + { + Q_OBJECT + + public: + MultiresViewNode(int argc, char **argv, QWidget *parent = 0, Qt::WindowFlags flags = Qt::WindowFlags()); + ~MultiresViewNode() override = default; + + virtual void showEvent(QShowEvent* event) override; + + void Initialize(); + + void Spin(); + + private: + void SpinLoop(); + + int argc_; + char** argv_; + + rclcpp::Node::SharedPtr node_; + boost::thread* thread_; + + bool initialized_; + + std::string image_path_; + + TileSet* tile_set_; + }; +} + +#endif // MULTIRES_IMAGE_MULTIRES_VIEW_NODE_H_ diff --git a/multires_image/include/multires_image/tile.h b/multires_image/include/multires_image/tile.h new file mode 100644 index 000000000..6284e2241 --- /dev/null +++ b/multires_image/include/multires_image/tile.h @@ -0,0 +1,109 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MULTIRES_IMAGE_TILE_H_ +#define MULTIRES_IMAGE_TILE_H_ + +// C++ standard libraries +#include + +// QT libraries +#include +#include + +#include + +#include + +#ifndef GL_CLAMP_TO_EDGE +#define GL_CLAMP_TO_EDGE 0x812F +#endif + +namespace multires_image +{ + class Tile + { + public: + Tile( + const std::string& path, int column, int row, int level, + const tf2::Vector3& topLeft, + const tf2::Vector3& topRight, + const tf2::Vector3& bottomLeft, + const tf2::Vector3& bottomRight); + ~Tile() = default; + + bool Exists(); + bool Failed() const { return m_failed; } + bool TextureLoaded() const { return m_textureLoaded; } + const QImage& Image() const { return m_image; } + int64_t TileID() const { return m_tileId; } + int Layer() const { return m_level; } + int MemorySize() const { return m_memorySize; } + int Row() const { return m_row; } + int Column() const { return m_column; } + + bool LoadImageToMemory(bool gl = true); + void UnloadImage(); + + bool LoadTexture(); + void UnloadTexture(); + + void Draw(); + + void Transform(const swri_transform_util::Transform& transform); + void Transform(const swri_transform_util::Transform& transform, const swri_transform_util::Transform& offset_tf); + + private: + const std::string m_path; + const int m_column; + const int m_row; + const int m_level; + + tf2::Vector3 m_top_left; + tf2::Vector3 m_top_right; + tf2::Vector3 m_bottom_right; + tf2::Vector3 m_bottom_left; + + tf2::Vector3 m_transformed_top_left; + tf2::Vector3 m_transformed_top_right; + tf2::Vector3 m_transformed_bottom_right; + tf2::Vector3 m_transformed_bottom_left; + + bool m_failed; + bool m_textureLoaded; + int m_dimension; + int m_textureId; + int64_t m_tileId; + int m_memorySize; + QImage m_image; + QMutex m_mutex; + }; +} + +#endif // MULTIRES_IMAGE_TILE_H_ diff --git a/multires_image/include/multires_image/tile_cache.h b/multires_image/include/multires_image/tile_cache.h new file mode 100644 index 000000000..5392f6948 --- /dev/null +++ b/multires_image/include/multires_image/tile_cache.h @@ -0,0 +1,128 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MULTIRES_IMAGE_TILE_CACHE_H_ +#define MULTIRES_IMAGE_TILE_CACHE_H_ + +// C++ standard libraries +#include +#include +#include +#include + +// QT libraries +#include +#include +#include +#include + +#include + +#include +#include + +namespace multires_image +{ + class TileCache : public QObject + { + Q_OBJECT + + public: + TileCache(TileSet* tileSet, QGLWidget* widget); + ~TileCache() override; + + void Load(Tile* tile); + void Precache(const tf2::Vector3& position); + void Precache(double x, double y); + + void SetCurrentLayer(int layer) { m_currentLayer = layer; } + + void Exit(); + + public Q_SLOTS: + void LoadTextureSlot(Tile*); + void DeleteTextureSlot(Tile*); + + Q_SIGNALS: + void SignalLoadTexture(Tile*); + void SignalDeleteTexture(Tile*); + void SignalMemorySize(int64_t); + + private: + TileSet* m_tileSet; + QGLWidget* m_widget; + int32_t m_currentLayer; + tf2::Vector3 m_currentPosition; + bool m_exit; + int64_t m_memorySize; + + std::vector > m_precacheRequests; + std::stack m_renderRequests; + std::map m_textureLoaded; + std::map m_renderRequestSet; + std::map m_precacheRequestSet; + + void PrecacheLayer(int layer, const tf2::Vector3& position, int size); + void LoadTexture(Tile* tile); + void UnloadTexture(Tile* tile); + + class CacheThread : public QThread + { + public: + explicit CacheThread(TileCache* parent) : p(parent) {} + virtual void run(); + + private: + TileCache* p; + }; + friend class CacheThread; + + class FreeThread : public QThread + { + public: + explicit FreeThread(TileCache* parent) : p(parent) {} + virtual void run(); + + private: + TileCache* p; + }; + friend class FreeThread; + + CacheThread m_cacheThread; + FreeThread m_freeThread; + + QMutex m_renderRequestsLock; + QMutex m_renderRequestSetLock; + QMutex m_precacheRequestsLock; + QMutex m_precacheRequestSetLock; + QMutex m_textureLoadedLock; + }; +} + +#endif // MULTIRES_IMAGE_TILE_CACHE_H_ diff --git a/multires_image/include/multires_image/tile_set.h b/multires_image/include/multires_image/tile_set.h new file mode 100644 index 000000000..a8d9dfd38 --- /dev/null +++ b/multires_image/include/multires_image/tile_set.h @@ -0,0 +1,78 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MULTIRES_IMAGE_TILE_SET_H_ +#define MULTIRES_IMAGE_TILE_SET_H_ + +// C++ standard libraries +#include +#include + +#include + +#include + +namespace multires_image +{ + class TileSet + { + public: + explicit TileSet(const std::string& geofile); + TileSet(const std::string& geofile, const std::string extension); + explicit TileSet(const swri_transform_util::GeoReference& georeference); + TileSet(const swri_transform_util::GeoReference& georeference, + const std::string extension); + + ~TileSet(); + + bool Load(); + + int LayerCount() { return m_layerCount; } + int TileSize() { return m_tileSize; } + + swri_transform_util::GeoReference& GeoReference() { return m_geo; } + + TileSetLayer* GetLayer(int layer) { return m_layers[layer]; } + + private: + swri_transform_util::GeoReference m_geo; + int m_tileSize{}; + int m_width{}; + int m_height{}; + + std::string m_cacheDir; + std::string m_extension; + + int m_layerCount{}; + + std::vector m_layers; + }; +} + +#endif // MULTIRES_IMAGE_TILE_SET_H_ diff --git a/multires_image/include/multires_image/tile_set_layer.h b/multires_image/include/multires_image/tile_set_layer.h new file mode 100644 index 000000000..65d9e9f94 --- /dev/null +++ b/multires_image/include/multires_image/tile_set_layer.h @@ -0,0 +1,87 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MULTIRES_IMAGE_TILE_SET_LAYER_H_ +#define MULTIRES_IMAGE_TILE_SET_LAYER_H_ + +// C++ standard libraries +#include +#include + +#include + +#include + +#include + +namespace multires_image +{ + class TileSetLayer + { + public: + TileSetLayer( + const swri_transform_util::GeoReference& geo, + const std::string& path, + int tileSize, int layer); + + ~TileSetLayer() = default; + + bool Load(); + bool Load(const std::string extension); + + Tile* GetTile(int column, int row) { return m_tiles[column][row]; } + + void GetTileIndex(const tf2::Vector3& position, int& row, int& column) const; + void GetTileIndex(double x, double y, int& row, int& column) const; + void GetTileRange( + const tf2::Vector3& top_left, + const tf2::Vector3& bottom_right, + int& startRow, int& startColumn, + int& endRow, int& endColumn) const; + + int RowCount() { return m_rows; } + int ColumnCount() { return m_columns; } + + private: + const swri_transform_util::GeoReference& m_geo; + const std::string m_path; + const int m_tileSize; + const int m_layer; + const double m_scale; + + bool m_expectTiles; + + int m_columns; + int m_rows; + + std::vector > m_tiles; + }; +} + +#endif // MULTIRES_IMAGE_TILE_SET_LAYER_H_ diff --git a/multires_image/include/multires_image/tile_view.h b/multires_image/include/multires_image/tile_view.h new file mode 100644 index 000000000..638ad842a --- /dev/null +++ b/multires_image/include/multires_image/tile_view.h @@ -0,0 +1,67 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef MULTIRES_IMAGE_TILE_VIEW_H_ +#define MULTIRES_IMAGE_TILE_VIEW_H_ + +// QT libraries +#include + +#include +#include + +namespace multires_image +{ + class TileView + { + public: + TileView(TileSet* tiles, QGLWidget* widget); + ~TileView() = default; + + const TileCache* Cache() { return &m_cache; } + + void SetView(double x, double y, double radius, double scale); + + void Draw(); + + void Exit() { m_cache.Exit(); } + + private: + TileSet* m_tiles; + TileCache m_cache; + int m_currentLayer; + int m_startRow; + int m_startColumn; + int m_endRow; + int m_endColumn; + double min_scale_; + }; +} + +#endif // MULTIRES_IMAGE_TILE_VIEW_H_ diff --git a/multires_image/launch/mapviz_tile_loader.launch b/multires_image/launch/mapviz_tile_loader.launch new file mode 100644 index 000000000..2bffbed21 --- /dev/null +++ b/multires_image/launch/mapviz_tile_loader.launch @@ -0,0 +1,31 @@ + + + + + + + [{ name: swri, + latitude: 29.45196669, + longitude: -98.61370577, + altitude: 233.719, + heading: 0.0}, + + { name: back_40, + latitude: 29.447507, + longitude: -98.629367, + altitude: 200.0, + heading: 0.0}] + + + + + + + + + + + + + + diff --git a/multires_image/launch/multires.launch b/multires_image/launch/multires.launch new file mode 100644 index 000000000..d5178d01f --- /dev/null +++ b/multires_image/launch/multires.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/multires_image/mainpage.dox b/multires_image/mainpage.dox new file mode 100644 index 000000000..c595901e9 --- /dev/null +++ b/multires_image/mainpage.dox @@ -0,0 +1,33 @@ +/** +\mainpage +\section multires_image + +\b multires_image is a set of API's and nodes for ... + +This package... (see sumet_perception/material_classification/mainpage.dox for example description) + + +\subsection codeapi Code API + +The C++ API consists of the following main classes: + +- \b multires_image::GeoRegister - \copybrief multires_image::GeoRegister +- \b multires_image::ImageManip - \copybrief multires_image::ImageManip +- \b multires_image::MathUtil - \copybrief multires_image::MathUtil +- \b multires_image::Point - \copybrief multires_image::Point +- \b multires_image::QGLMap - \copybrief multires_image::QGLMap +- \b multires_image::StringUtil - \copybrief multires_image::StringUtil +- \b multires_image::TileCache - \copybrief multires_image::TileCache +- \b multires_image::TileSetLayer - \copybrief multires_image::TileSetLayer +- \b multires_image::TileSet - \copybrief multires_image::TileSet +- \b multires_image::TileView - \copybrief multires_image::TileView +- \b multires_image::Tile - \copybrief multires_image::Tile + + +\subsection nodes Nodes + +\subsubsection multires_view_node +\copydetails src/nodes/multires_view_node.cpp + + +**/ diff --git a/multires_image/mapviz_plugins.xml b/multires_image/mapviz_plugins.xml new file mode 100644 index 000000000..81aabc578 --- /dev/null +++ b/multires_image/mapviz_plugins.xml @@ -0,0 +1,6 @@ + + + Multires image mapviz plugin. + + + diff --git a/multires_image/nodes/mapviz_tile_loader b/multires_image/nodes/mapviz_tile_loader new file mode 100755 index 000000000..66f3a7d2e --- /dev/null +++ b/multires_image/nodes/mapviz_tile_loader @@ -0,0 +1,204 @@ +#!/usr/bin/env python3 +# -*- coding: utf-8 -*- + +# +# Copyright (C) 2016 All Right Reserved, Southwest Research Institute® (SwRI®) +# + +import fnmatch +import math +import os +import pyproj +import rospy +import yaml +from collections import namedtuple +from geometry_msgs.msg import PoseStamped +from gps_common.msg import GPSFix +from mapviz.srv import AddMapvizDisplay, AddMapvizDisplayRequest +from marti_common_msgs.msg import KeyValue + +GeoReference = namedtuple("GeoReference", "path min_lat min_lon max_lat max_lon area") +_gps_fix = None + +def distance(lat1, lon1, lat2, lon2): + x1 = math.radians(lat1) + y1 = math.radians(lon1) + x2 = math.radians(lat2) + y2 = math.radians(lon2) + return math.acos(math.sin(x1) * math.sin(x2) + math.cos(x1) * math.cos(x2) * math.cos(y1 - y2)) + +def gps_callback(data): + global _gps_fix + _gps_fix = data + +def load_tiles(): + rospy.init_node('mapviz_tile_loader', anonymous=True) + + base_directory = rospy.get_param('~base_directory', os.path.expanduser('~') + "/.ros") + max_search_depth = rospy.get_param('~max_search_depth', 1) + rate = max(0.1, rospy.get_param('~rate', 1.0)) + display_name = rospy.get_param('~display_name', 'satellite') + draw_order = rospy.get_param('~draw_order', 1) + use_local_xy = rospy.get_param('~use_local_xy', False) + + gps_sub = rospy.Subscriber("gps", GPSFix, gps_callback) + + geofiles = [] + initial_depth = base_directory.count(os.sep) + for path, dirs, filenames in os.walk(base_directory): + for filename in fnmatch.filter(filenames, '*.geo'): + geofiles.append(os.path.join(path, filename)) + current_depth = path.count(os.sep) - initial_depth + if current_depth >= max_search_depth: + dirs[:] = [] + + georeferences = [] + for geofile in geofiles: + rospy.loginfo("Parsing %s...", geofile) + f = open(geofile) + min_lat = 90.0 + max_lat = -90.0 + min_lon = 180.0 + max_lon = -180.0 + geodata = yaml.safe_load(f) + if str(geodata['projection']).lower() == 'utm': + rospy.loginfo(" projection: utm") + zone = 1 + band = 'N' + if ('utm_zone' in geodata): + zone = int(geodata['utm_zone']) + if zone >= 1 or zone <= 60: + rospy.loginfo(" utm zone: %d", zone) + else: + rospy.logwarn(" invalid utm zone!") + f.close() + continue + else: + rospy.logwarn(" no utm zone!") + f.close() + continue + if ('utm_band' in geodata): + band = str(geodata['utm_band']) + if band >= 'C' or band <= 'X': + rospy.loginfo(" utm band: %s", band) + else: + rospy.logwarn(" invalid utm band!") + f.close() + continue + else: + rospy.logwarn(" no utm band!") + f.close() + continue + + utm_proj = pyproj.Proj(proj='utm', zone=zone, ellps='WGS84', south=(band < 'N')) + + if 'tiepoints' in geodata: + if len(geodata['tiepoints']) > 1: + for point in geodata['tiepoints']: + easting = point['point'][2] + northing = point['point'][3] + lon, lat = utm_proj(easting, northing, inverse=True) + min_lon = min(lon, min_lon) + max_lon = max(lon, max_lon) + min_lat = min(lat, min_lat) + max_lat = max(lat, max_lat) + else: + rospy.logwarn(" not enough tiepoints!") + f.close() + continue + else: + rospy.logwarn(" no tiepoints!") + f.close() + continue + + area = (max_lat - min_lat) * (max_lon - min_lon) + + georeferences.append(GeoReference(geofile, min_lat, min_lon, max_lat, max_lon, area)) + rospy.loginfo(" lat/lon bounds: (%lf, %lf) - (%lf, %lf)", min_lat, min_lon, max_lat, max_lon) + + f.close() + + rospy.loginfo("waiting for service: %s ...", rospy.resolve_name('add_mapviz_display')) + rospy.wait_for_service('add_mapviz_display') + + last_path = None + while not rospy.is_shutdown(): + if use_local_xy: + if last_path is None and georeferences: + # Select the geofile that contains the current local_xy origin point. If multiple + # geo-files contain the point, select the largest. If no geo-files + # contain the point, select the closest one. + + # get local xy origin + local_xy = rospy.wait_for_message("/local_xy_origin", PoseStamped) + max_area = 0 + path = None + for georef in georeferences: + if local_xy.pose.position.y > georef.min_lat and local_xy.pose.position.y < georef.max_lat and local_xy.pose.position.x > georef.min_lon and local_xy.pose.position.x < georef.max_lon and georef.area > max_area: + path = georef.path + max_area = georef.area + + if path is None: + min_dist = float("inf") + for georef in georeferences: + lat = (georef.min_lat + georef.max_lat) / 2.0 + lon = (georef.min_lon + georef.max_lon) / 2.0 + dist = distance(lat, lon, local_xy.pose.position.y, local_xy.pose.position.x) + if (dist < min_dist): + min_dist = dist + path = georef.path + + # If the geo-file has changed, call the service for adding/updating + # the mapviz display + if path is not None and path != last_path: + rospy.loginfo("updating tileset: %s", path); + add_mapviz_display = rospy.ServiceProxy('add_mapviz_display', AddMapvizDisplay) + request = AddMapvizDisplayRequest(type='mapviz_plugins/multires_image', draw_order=draw_order, name=display_name, visible=True) + request.properties.append(KeyValue(key='path', value=path)) + response = add_mapviz_display(request) + if response.success: + last_path = path + else: + rospy.logwarn("failed to update tileset: %s", response.message) + else: + if _gps_fix is not None: + # Select the geofile that contains the current GPS point. If multiple + # geo-files contain the point, select the largest. If no geo-files + # contain the point, select the closest one. + max_area = 0 + path = None + for georef in georeferences: + if _gps_fix.latitude > georef.min_lat and _gps_fix.latitude < georef.max_lat and _gps_fix.longitude > georef.min_lon and _gps_fix.longitude < georef.max_lon and georef.area > max_area: + path = georef.path + max_area = georef.area + + if path is None: + min_dist = float("inf") + for georef in georeferences: + lat = (georef.min_lat + georef.max_lat) / 2.0 + lon = (georef.min_lon + georef.max_lon) / 2.0 + dist = distance(lat, lon, _gps_fix.latitude, _gps_fix.longitude) + if (dist < min_dist): + min_dist = dist + path = georef.path + + # If the geo-file has changed, call the service for adding/updating + # the mapviz display + if path is not None and path != last_path: + rospy.loginfo("updating tileset: %s", path); + add_mapviz_display = rospy.ServiceProxy('add_mapviz_display', AddMapvizDisplay) + request = AddMapvizDisplayRequest(type='mapviz_plugins/multires_image', draw_order=draw_order, name=display_name, visible=True) + request.properties.append(KeyValue(key='path', value=path)) + response = add_mapviz_display(request) + if response.success: + last_path = path + else: + rospy.logwarn("failed to update tileset: %s", response.message) + else: + rospy.loginfo("waiting for gps message: %s", rospy.resolve_name('gps')) + rospy.sleep(1.0 / rate) + +if __name__ == '__main__': + try: + load_tiles() + except rospy.ROSInterruptException: pass diff --git a/multires_image/package.xml b/multires_image/package.xml new file mode 100644 index 000000000..f9ef40e51 --- /dev/null +++ b/multires_image/package.xml @@ -0,0 +1,41 @@ + + multires_image + 2.3.0 + + + multires_image + + + Marc Alban + P. J. Reed + Southwest Research Institute + BSD + https://github.com/swri-robotics/mapviz + + ament_cmake + qt5-qmake + + libqt5-core + libqt5-opengl-dev + + cv_bridge + geometry_msgs + gps_msgs + mapviz + pluginlib + rclcpp + swri_math_util + swri_transform_util + tf2 + + libqt5-opengl + rclpy + + + ament_cmake + + + + + + diff --git a/multires_image/src/QGLMap.cpp b/multires_image/src/QGLMap.cpp new file mode 100644 index 000000000..834a9a6e8 --- /dev/null +++ b/multires_image/src/QGLMap.cpp @@ -0,0 +1,301 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include + +namespace multires_image +{ +QGLMap::QGLMap(QWidget *parent) + : QGLWidget(parent) + , ui() + , m_initialized(false) + , m_scale(1.0) + , m_mouseDown(false) + , m_mouseDownX(0) + , m_mouseDownY(0) + , m_tileView(nullptr) + , m_view_top_left(0, 0, 0) + , m_view_bottom_right(0, 0, 0) + , m_view_center(0, 0, 0) + , m_scene_top_left(0, 0, 0) + , m_scene_bottom_right(0, 0, 0) + , m_scene_center(0, 0, 0) +{ + ui.setupUi(this); +} + +void QGLMap::Exit() +{ + if (m_tileView != nullptr) + { + m_tileView->Exit(); + } +} + +void QGLMap::UpdateView() +{ + if (m_initialized) + { + Recenter(); + + if (m_tileView != nullptr) + { + m_tileView->SetView(m_view_center.x(), m_view_center.y(), 1, m_scale); + } + + glViewport(0, 0, width(), height()); + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + glOrtho(m_view_top_left.x(), m_view_bottom_right.x(), + m_view_bottom_right.y(), m_view_top_left.y(), -0.5f, 0.5f); + + update(); + + // Signal a view change as occured. The minimap listens for this + // so that it can update its view box. + emit SignalViewChange(m_view_top_left.x(), m_view_top_left.y(), + m_view_bottom_right.x(), m_view_bottom_right.y()); + } +} + +void QGLMap::SetTiles(TileSet* tiles) +{ + double top, left, bottom, right; + tiles->GeoReference().GetCoordinate(0, 0, left, top); + tiles->GeoReference().GetCoordinate( + tiles->GeoReference().Width(), + tiles->GeoReference().Height(), + right, + bottom); + + m_scene_top_left = tf2::Vector3(left, top, 0); + m_scene_bottom_right = tf2::Vector3(right, bottom, 0); + m_scene_center = (m_scene_top_left + m_scene_bottom_right) / 2.0; + + m_view_center = m_scene_center; + + m_tileView = new TileView(tiles, this); + + connect(m_tileView->Cache(), SIGNAL(SignalMemorySize(int64_t)), + SLOT(SetTextureMemory(int64_t))); + + // Create connections for the texture loading functions which must + // be executed on this object's thread. + + m_tileView->SetView(m_view_center.x(), m_view_center.y(), 1, m_scale); +} + +void QGLMap::wheelEvent(QWheelEvent* e) +{ + float numDegrees = static_cast(e->angleDelta().y()) / -8.0f; + + m_scale *= pow(1.1, numDegrees / 10.0); + + UpdateView(); +} + +void QGLMap::LoadTexture(Tile* tile) +{ + tile->LoadTexture(); +} + +void QGLMap::DeleteTexture(Tile* tile) +{ + tile->UnloadTexture(); +} + +void QGLMap::SetTextureMemory(int64_t bytes) +{ + // Signal that the texture memory size has changed. The status bar listens + // to this so that the user can see how much memory the map is using. + emit SignalMemorySize(bytes); +} + +void QGLMap::ChangeCenter(double x, double y) +{ + if (x != 0) + m_view_center.setX(x); + + if (y != 0) + m_view_center.setY(y); + + UpdateView(); +} + +void QGLMap::initializeGL() +{ + glClearColor(0.58f, 0.56f, 0.5f, 1); + glEnable(GL_POINT_SMOOTH); + glEnable(GL_LINE_SMOOTH); + glEnable(GL_POLYGON_SMOOTH); + glHint(GL_LINE_SMOOTH_HINT, GL_NICEST); + glHint(GL_POINT_SMOOTH_HINT, GL_NICEST); + glHint(GL_POLYGON_SMOOTH_HINT, GL_NICEST); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + glDepthFunc(GL_NEVER); + glDisable(GL_DEPTH_TEST); + m_initialized = true; +} + +void QGLMap::resizeGL(int w, int h) +{ + UpdateView(); +} + +void QGLMap::paintGL() +{ + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + if (m_tileView != nullptr) + { + m_tileView->Draw(); + } +} + +void QGLMap::mousePressEvent(QMouseEvent* e) +{ + m_mouseDownX = e->x(); + m_mouseDownY = e->y(); + m_mouseDown = true; + + update(); +} + +void QGLMap::mouseDoubleClickEvent(QMouseEvent* e) +{ + update(); +} + +void QGLMap::mouseReleaseEvent(QMouseEvent* e) +{ + m_mouseDown = false; + + update(); +} + +void QGLMap::mouseMoveEvent(QMouseEvent* e) +{ + if (m_mouseDown) + MousePan(e->x(), e->y()); +} + +void QGLMap::MousePan(int x, int y) +{ + bool changed = false; + if (m_mouseDown) + { + double diffX = ((m_mouseDownX - x) * m_scale); + double diffY = ((m_mouseDownY - y) * m_scale); + + if (diffX != 0) + { + m_view_center.setX(m_view_center.x() + diffX); + m_mouseDownX = x; + changed = true; + } + if (diffY != 0) + { + m_view_center.setY(m_view_center.y() + diffY); + m_mouseDownY = y; + changed = true; + } + } + + if (changed) + { + UpdateView(); + } +} + +void QGLMap::Recenter() +{ + double scene_width = std::fabs(m_scene_top_left.x() - m_scene_bottom_right.x()); + double scene_height = std::fabs(m_scene_top_left.y() - m_scene_bottom_right.y()); + double view_width = width() * m_scale; + double view_height = height() * m_scale; + + m_view_top_left.setX(m_view_center.x() - (view_width * 0.5)); + m_view_top_left.setY(m_view_center.y() - (view_width * 0.5)); + + m_view_bottom_right.setX(m_view_center.x() + (view_width * 0.5)); + m_view_bottom_right.setY(m_view_center.y() + (view_width * 0.5)); + + if (view_width > scene_width) + { + m_view_center.setX(m_scene_center.x()); + m_view_top_left.setX(m_view_center.x() - (view_width * 0.5)); + m_view_bottom_right.setX(m_view_center.x() + (view_width * 0.5)); + } + else + { + if (m_view_top_left.x() < m_scene_top_left.x()) + { + m_view_top_left.setX(m_scene_top_left.x()); + m_view_bottom_right.setX(m_view_top_left.x() + view_width); + m_view_center.setX(m_view_top_left.x() + (view_width * 0.5)); + } + + if (m_view_bottom_right.x() > m_scene_bottom_right.x()) + { + m_view_bottom_right.setX(m_scene_bottom_right.x()); + m_view_top_left.setX(m_view_bottom_right.x() - view_width); + m_view_center.setX(m_view_top_left.x() + (view_width * 0.5)); + } + } + + if (view_height < scene_height) + { + m_view_center.setY(m_scene_center.y()); + m_view_top_left.setY(m_scene_center.y() - (view_height * 0.5)); + m_view_bottom_right.setY(m_scene_center.y() + (view_height * 0.5)); + } + else + { + if (m_view_top_left.y() > m_scene_top_left.y()) + { + m_view_top_left.setY(m_scene_top_left.y()); + m_view_bottom_right.setY(m_view_top_left.y() + (view_height)); + m_view_center.setY(m_view_top_left.y() + (view_height * 0.5)); + } + + if (m_view_bottom_right.y() < m_scene_bottom_right.y()) + { + m_view_bottom_right.setY(m_scene_bottom_right.y()); + m_view_top_left.setY(m_view_bottom_right.y() - (view_height)); + m_view_center.setY(m_view_top_left.y() + (view_height * 0.5)); + } + } +} + +} + diff --git a/multires_image/src/QGLMap.ui b/multires_image/src/QGLMap.ui new file mode 100644 index 000000000..cab3bba1c --- /dev/null +++ b/multires_image/src/QGLMap.ui @@ -0,0 +1,32 @@ + + + QGLMapClass + + + + 0 + 0 + 400 + 300 + + + + QGLMap + + + + + + QGLWidget + QWidget +
      qglwidget.h
      + 1 +
      +
      + + + + LoadTexture(Tile*tile) + DeleteTexture(Tile*tile) + +
      diff --git a/multires_image/src/multires_config.ui b/multires_image/src/multires_config.ui new file mode 100644 index 000000000..7d2343097 --- /dev/null +++ b/multires_image/src/multires_config.ui @@ -0,0 +1,165 @@ + + + multires_config + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + + 2 + + + 2 + + + 2 + + + 2 + + + 4 + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + + Sans Serif + 8 + + + + + + + Unconfigured + + + true + + + + + + + + 55 + 16777215 + + + + + Sans Serif + 8 + + + + + + + Browse + + + + + + + + Sans Serif + 8 + + + + Geo File: + + + + + + + + Sans Serif + 8 + + + + + + + + + Sans + 8 + + + + X (East) offset + + + + + + + + Sans + 8 + + + + Y (North) offset + + + + + + + -100.000000000000000 + + + 0.100000000000000 + + + 0.000000000000000 + + + + + + + -100.000000000000000 + + + 0.100000000000000 + + + + + + + + diff --git a/multires_image/src/multires_image_plugin.cpp b/multires_image/src/multires_image_plugin.cpp new file mode 100644 index 000000000..f215702c4 --- /dev/null +++ b/multires_image/src/multires_image_plugin.cpp @@ -0,0 +1,363 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include + +// QT libraries +#include +#include +#include + +// ROS libraries +#include +#include + +// Declare plugin +#include +PLUGINLIB_EXPORT_CLASS(mapviz_plugins::MultiresImagePlugin, mapviz::MapvizPlugin) + +namespace mapviz_plugins +{ + MultiresImagePlugin::MultiresImagePlugin() + : MapvizPlugin() + , ui_() + , loaded_(false) + , center_x_(0.0) + , center_y_(0.0) + , offset_x_(0.0) + , offset_y_(0.0) + , tile_set_(nullptr) + , tile_view_(nullptr) + , config_widget_(new QWidget()) + , transformed_(false) + { + ui_.setupUi(config_widget_); + + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + QPalette p2(ui_.status->palette()); + p2.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p2); + + QObject::connect(ui_.browse, SIGNAL(clicked()), this, SLOT(SelectFile())); + QObject::connect(ui_.path, SIGNAL(editingFinished()), this, SLOT(AcceptConfiguration())); + QObject::connect(ui_.x_offset_spin_box, SIGNAL(valueChanged(double)), this, SLOT(SetXOffset(double))); + QObject::connect(ui_.y_offset_spin_box, SIGNAL(valueChanged(double)), this, SLOT(SetYOffset(double))); + + source_frame_ = "/"; + } + + MultiresImagePlugin::~MultiresImagePlugin() + { + delete tile_view_; + delete tile_set_; + } + + void MultiresImagePlugin::PrintError(const std::string& message) + { + if (message == ui_.status->text().toStdString()) { + return; + } + + RCLCPP_ERROR(node_->get_logger(), "Error: %s", message.c_str()); + QPalette p(ui_.status->palette()); + p.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p); + ui_.status->setText(message.c_str()); + } + + void MultiresImagePlugin::PrintInfo(const std::string& message) + { + if (message == ui_.status->text().toStdString()) { + return; + } + + RCLCPP_INFO(node_->get_logger(), "%s", message.c_str()); + QPalette p(ui_.status->palette()); + p.setColor(QPalette::Text, Qt::green); + ui_.status->setPalette(p); + ui_.status->setText(message.c_str()); + } + + void MultiresImagePlugin::PrintWarning(const std::string& message) + { + if (message == ui_.status->text().toStdString()) { + return; + } + + RCLCPP_WARN(node_->get_logger(), "%s", message.c_str()); + QPalette p(ui_.status->palette()); + p.setColor(QPalette::Text, Qt::darkYellow); + ui_.status->setPalette(p); + ui_.status->setText(message.c_str()); + } + + void MultiresImagePlugin::AcceptConfiguration() + { + RCLCPP_INFO(node_->get_logger(), "Accept multires image configuration."); + if (tile_set_ != NULL && tile_set_->GeoReference().GeoPath() == ui_.path->text().toStdString()) + { + // Nothing to do. + } + else + { + loaded_ = false; + delete tile_set_; + delete tile_view_; + tile_set_ = new multires_image::TileSet(ui_.path->text().toStdString()); + + if (tile_set_->Load()) + { + loaded_ = true; + + source_frame_ = tile_set_->GeoReference().Projection(); + if (source_frame_.empty() || source_frame_[0] != '/') + { + source_frame_ = std::string("/") + source_frame_; + } + + QPalette p(ui_.status->palette()); + p.setColor(QPalette::Text, Qt::green); + ui_.status->setPalette(p); + ui_.status->setText("OK"); + + initialized_ = true; + + MultiresView* view = new MultiresView(tile_set_, canvas_); + tile_view_ = view; + } + else + { + PrintError("Failed to load image."); + delete tile_set_; + tile_set_ = 0; + tile_view_ = 0; + } + } + } + + void MultiresImagePlugin::SelectFile() + { + QFileDialog dialog(config_widget_, "Select Multires Image"); + dialog.setFileMode(QFileDialog::ExistingFile); + dialog.setNameFilter(tr("Geo Files (*.geo)")); + + dialog.exec(); + + if (dialog.result() == QDialog::Accepted && dialog.selectedFiles().count() == 1) + { + ui_.path->setText(dialog.selectedFiles().first()); + AcceptConfiguration(); + } + } + + + void MultiresImagePlugin::SetXOffset(double offset_x) + { + offset_x_ = offset_x; + } + + void MultiresImagePlugin::SetYOffset(double offset_y) + { + offset_y_ = offset_y; + } + + QWidget* MultiresImagePlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool MultiresImagePlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + return true; + } + + void MultiresImagePlugin::GetCenterPoint(double x, double y) + { + tf2::Vector3 point(x, y, 0); + tf2::Vector3 center = inverse_transform_ * point; + center_x_ = center.getX(); + center_y_ = center.getY(); + } + + void MultiresImagePlugin::Draw(double x, double y, double scale) + { + if (transformed_ && tile_set_ != NULL && tile_view_ != NULL) + { + GetCenterPoint(x, y); + tile_view_->SetView(center_x_, center_y_, 1, scale); + + tile_view_->Draw(); + + PrintInfo("OK"); + } + } + + void MultiresImagePlugin::Transform() + { + transformed_ = false; + + if (!loaded_) + return; + + if (!tf_manager_->GetTransform(target_frame_, source_frame_, transform_)) + { + PrintError("Failed transform from " + source_frame_ + " to " + target_frame_); + return; + } + + if (!tf_manager_->GetTransform(source_frame_, target_frame_, inverse_transform_)) + { + PrintError("Failed inverse transform from " + target_frame_ + " to " + source_frame_); + return; + } + + // Add in user-specified offset to map + swri_transform_util::Transform offset( + tf2::Transform( + tf2::Quaternion(0, 0, 0, 1), + tf2::Vector3(offset_x_, offset_y_, 0.0))); + + // Set relative positions of tile points based on tf transform + for (int i = 0; i < tile_set_->LayerCount(); i++) + { + multires_image::TileSetLayer* layer = tile_set_->GetLayer(i); + for (int r = 0; r < layer->RowCount(); r++) + { + for (int c = 0; c < layer->ColumnCount(); c++) + { + multires_image::Tile* tile = layer->GetTile(c, r); + + tile->Transform(transform_, offset); + } + } + } + + transformed_ = true; + } + + boost::filesystem::path MultiresImagePlugin::MakePathRelative(boost::filesystem::path path, boost::filesystem::path base) + { + // Borrowed from: https://svn.boost.org/trac/boost/ticket/1976#comment:2 + if (path.has_root_path()) + { + if (path.root_path() != base.root_path()) + { + return path; + } + else + { + return MakePathRelative(path.relative_path(), base.relative_path()); + } + } + else + { + if (base.has_root_path()) + { + RCLCPP_WARN(node_->get_logger(), "Cannot uncomplete a path relative path from a rooted base."); + return path; + } + else + { + typedef boost::filesystem::path::const_iterator path_iterator; + path_iterator path_it = path.begin(); + path_iterator base_it = base.begin(); + while (path_it != path.end() && base_it != base.end()) + { + if (*path_it != *base_it) + break; + ++path_it; + ++base_it; + } + boost::filesystem::path result; + for (; base_it != base.end(); ++base_it) + { + result /= ".."; + } + for (; path_it != path.end(); ++path_it) + { + result /= *path_it; + } + return result; + } + } + } + + void MultiresImagePlugin::LoadConfig(const YAML::Node& node, const std::string& path) + { + if (node["path"]) + { + std::string path_string = node["path"].as(); + + boost::filesystem::path image_path(path_string); + if (!image_path.is_complete()) + { + boost::filesystem::path base_path(path); + path_string = + (path / image_path.relative_path()).normalize().string(); + } + + ui_.path->setText(path_string.c_str()); + + AcceptConfiguration(); + } + + if (node["offset_x"]) + { + offset_x_ = node["offset_x"].as(); + ui_.x_offset_spin_box->setValue(offset_x_); + } + if (node["offset_y"]) + { + offset_y_ = node["offset_y"].as(); + ui_.y_offset_spin_box->setValue(offset_y_); + } + } + + void MultiresImagePlugin::SaveConfig(YAML::Emitter& emitter, const std::string& path) + { + boost::filesystem::path abs_path(ui_.path->text().toStdString()); + boost::filesystem::path base_path(path); + boost::filesystem::path rel_path = MakePathRelative(abs_path, base_path); + + emitter << YAML::Key << "path" << YAML::Value << rel_path.string(); + emitter << YAML::Key << "offset_x" << YAML::Value << offset_x_; + emitter << YAML::Key << "offset_y" << YAML::Value << offset_y_; + } +} + diff --git a/multires_image/src/multires_view.cpp b/multires_image/src/multires_view.cpp new file mode 100644 index 000000000..43f1189a0 --- /dev/null +++ b/multires_image/src/multires_view.cpp @@ -0,0 +1,199 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include +#include + +#include + +namespace mapviz_plugins +{ + MultiresView::MultiresView(multires_image::TileSet* tiles, QGLWidget* widget) : + m_tiles(tiles), + m_cache(tiles, widget), + m_currentLayer(tiles->LayerCount() - 1), + m_startRow(0), + m_startColumn(0), + m_endRow(0), + m_endColumn(0) + { + double top, left, bottom, right; + + tiles->GeoReference().GetCoordinate(0, 0, left, top); + + tiles->GeoReference().GetCoordinate( + tiles->GeoReference().Width(), + tiles->GeoReference().Height(), + right, + bottom); + + double width_m, height_m; + if (tiles->GeoReference().Projection() == "wgs84") + { + width_m = swri_transform_util::GreatCircleDistance(top, left, top, right); + height_m = swri_transform_util::GreatCircleDistance(top, left, bottom, left); + } + else + { + width_m = std::fabs(right - left); + height_m = std::fabs(top - bottom); + } + + double scale_x = width_m / tiles->GeoReference().Width(); + double scale_y = height_m / tiles->GeoReference().Height(); + + min_scale_ = scale_x; + if (scale_y > scale_x) { + min_scale_ = scale_y; + } + } + + void MultiresView::SetView(double x, double y, double radius, double scale) + { + int layer = 0; + while (min_scale_ * std::pow(2.0, layer + 1) < scale) layer++; + + if (layer >= m_tiles->LayerCount()) { + layer = m_tiles->LayerCount() - 1; + } + + if (layer != m_currentLayer) + { + m_currentLayer = layer; + m_cache.SetCurrentLayer(layer); + } + + int row, column; + m_tiles->GetLayer(m_currentLayer)->GetTileIndex(x, y, row, column); + + int size = 3; + + m_startRow = row - size; + if (m_startRow < 0) { + m_startRow = 0; + } + if (m_startRow >= m_tiles->GetLayer(m_currentLayer)->RowCount()) { + m_startRow = m_tiles->GetLayer(m_currentLayer)->RowCount() - 1; + } + + m_endRow = row + size; + if (m_endRow < 0) { + m_endRow = 0; + } + if (m_endRow >= m_tiles->GetLayer(m_currentLayer)->RowCount()) { + m_endRow = m_tiles->GetLayer(m_currentLayer)->RowCount() - 1; + } + + m_startColumn = column - size; + if (m_startColumn < 0) { + m_startColumn = 0; + } + if (m_startColumn >= m_tiles->GetLayer(m_currentLayer)->ColumnCount()) { + m_startColumn = m_tiles->GetLayer(m_currentLayer)->ColumnCount() - 1; + } + + m_endColumn = column + size; + if (m_endColumn < 0) { + m_endColumn = 0; + } + if (m_endColumn >= m_tiles->GetLayer(m_currentLayer)->ColumnCount()) { + m_endColumn = m_tiles->GetLayer(m_currentLayer)->ColumnCount() - 1; + } + + m_cache.Precache(x, y); + } + + void MultiresView::Draw() + { + glEnable(GL_TEXTURE_2D); + + glColor4f(1.0f, 1.0f, 1.0f, 1.0f); + + // Always draw bottom layers + + multires_image::TileSetLayer* baseLayer = m_tiles->GetLayer(m_tiles->LayerCount() - 1); + multires_image::Tile* tile = baseLayer->GetTile(0, 0); + if (tile->TextureLoaded()) + { + tile->Draw(); + } + else + { + m_cache.Load(tile); + } + + if(m_tiles->LayerCount() >= 2) + { + baseLayer = m_tiles->GetLayer(m_tiles->LayerCount() - 2); + for (int c = 0; c < baseLayer->ColumnCount(); c++) + { + for (int r = 0; r < baseLayer->RowCount(); r++) + { + tile = baseLayer->GetTile(c, r); + if (tile->TextureLoaded()) + { + tile->Draw(); + } + else + { + m_cache.Load(tile); + } + } + } + } + + if (m_tiles->LayerCount() >= 2 && m_currentLayer < m_tiles->LayerCount() - 2) + { + multires_image::TileSetLayer* layer = m_tiles->GetLayer(m_currentLayer); + if (m_endColumn < layer->ColumnCount() && m_endRow < layer->RowCount()) + { + for (int c = m_startColumn; c <= m_endColumn; c++) + { + for (int r = m_startRow; r <= m_endRow; r++) + { + tile = layer->GetTile(c, r); + if (tile->TextureLoaded()) + { + tile->Draw(); + } + else + { + m_cache.Load(tile); + } + } + } + } + } + + glDisable(GL_TEXTURE_2D); + } +} diff --git a/multires_image/src/nodes/multires_view_node.cpp b/multires_image/src/nodes/multires_view_node.cpp new file mode 100644 index 000000000..82109f92a --- /dev/null +++ b/multires_image/src/nodes/multires_view_node.cpp @@ -0,0 +1,128 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +/** + * \file + * + * multires_image::MultiresViewNode. Description. + * - \b Parameters + * - \e "node_name"/image_path [string] - Description. [""] + */ + +#include + +// QT libraries +#include +#include +#include +#include +#include + +#include + +namespace multires_image +{ + MultiresViewNode::MultiresViewNode(int argc, char **argv, QWidget *parent, Qt::WindowFlags flags) + : QMainWindow(parent, flags) + , argc_(argc) + , argv_(argv) + , node_(nullptr) + , thread_(nullptr) + , initialized_(false) + , tile_set_(nullptr) + { + setCentralWidget(new QGLMap()); + this->setMinimumSize(640, 480); + } + + void MultiresViewNode::Spin() + { + if (!thread_) + { + thread_ = new boost::thread(&MultiresViewNode::SpinLoop, this); + } + } + + void MultiresViewNode::SpinLoop() + { + while (rclcpp::ok()) + { + rclcpp::spin_some(node_); + + usleep(10); + } + } + + void MultiresViewNode::showEvent(QShowEvent* event) + { + Initialize(); + } + + void MultiresViewNode::Initialize() + { + if (!initialized_) + { + rclcpp::init(argc_, argv_); + + node_ = std::make_shared("multires_view_node"); + + node_->declare_parameter("image_path", ""); + + node_->get_parameter("image_path", image_path_); + + tile_set_ = new TileSet(image_path_); + + if (tile_set_->Load()) + { + QGLMap* glMap = reinterpret_cast(centralWidget()); + glMap->SetTiles(tile_set_); + glMap->UpdateView(); + } + else + { + QMessageBox::warning(this, "Error", "Failed to load tiles."); + } + + Spin(); + + initialized_ = true; + } + } +} + +int main(int argc, char **argv) +{ + // Initialize QT + QApplication app(argc, argv); + + multires_image::MultiresViewNode node(argc, argv); + node.show(); + + return QApplication::exec(); +} diff --git a/multires_image/src/tile.cpp b/multires_image/src/tile.cpp new file mode 100644 index 000000000..233a20ffd --- /dev/null +++ b/multires_image/src/tile.cpp @@ -0,0 +1,223 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include +#include +#include +#include + +// QT libraries +#include +#include + +#include + +namespace multires_image +{ + Tile::Tile( + const std::string& path, int column, int row, int level, + const tf2::Vector3& topLeft, const tf2::Vector3& topRight, + const tf2::Vector3& bottomLeft, const tf2::Vector3& bottomRight) : + m_path(path), + m_column(column), + m_row(row), + m_level(level), + m_top_left(topLeft), + m_top_right(topRight), + m_bottom_right(bottomRight), + m_bottom_left(bottomLeft), + m_transformed_top_left(topLeft), + m_transformed_top_right(topRight), + m_transformed_bottom_right(bottomRight), + m_transformed_bottom_left(bottomLeft), + m_failed(false), + m_textureLoaded(false), + m_dimension(0), + m_textureId(0), + m_tileId(1000000 * level + 1000 * column + row), + m_memorySize(0) + { + } + + bool Tile::Exists() + { + return QFile::exists(m_path.c_str()); + } + + bool Tile::LoadImageToMemory(bool gl) + { + if (!m_failed) + { + m_mutex.lock(); + + try + { + QImage nullImage; + m_image = nullImage; + + if (m_image.load(m_path.c_str())) + { + if (gl) + { + int width = m_image.width(); + int height = m_image.height(); + + float max_dim = std::max(width, height); + m_dimension = swri_math_util::Round( + std::pow(2.0f, std::ceil(std::log(max_dim)/std::log(2.0f)))); + + if (width != m_dimension || height != m_dimension) + { + m_image = m_image.scaled(m_dimension, m_dimension, Qt::IgnoreAspectRatio, Qt::FastTransformation); + } + + m_memorySize = m_dimension * m_dimension * 4; + + m_image = QGLWidget::convertToGLFormat(m_image); + } + } + else + { + m_failed = true; + } + } + catch(std::exception& e) + { + std::cout << "An exception occurred loading image: " << e.what() << std::endl; + m_failed = true; + } + + m_mutex.unlock(); + } + + return !m_failed; + } + + void Tile::UnloadImage() + { + m_mutex.lock(); + + QImage nullImage; + m_image = nullImage; + + m_mutex.unlock(); + } + + bool Tile::LoadTexture() + { + if (!m_textureLoaded && !m_failed) + { + m_mutex.lock(); + + try + { + GLuint ids[1]; + glGenTextures(1, &ids[0]); + m_textureId = ids[0]; + + glBindTexture(GL_TEXTURE_2D, m_textureId); + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, m_dimension, m_dimension, 0, GL_RGBA, GL_UNSIGNED_BYTE, m_image.bits()); + + // TODO(malban): check for GL error + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); + + m_textureLoaded = true; + } + catch (const std::exception& e) + { + std::cout << "An exception occured loading texture: " << e.what() << std::endl; + m_failed = true; + } + + m_mutex.unlock(); + } + + return m_textureLoaded; + } + + void Tile::UnloadTexture() + { + m_mutex.lock(); + + if (m_textureLoaded) + { + m_textureLoaded = false; + GLuint ids[1]; + ids[0] = m_textureId; + glDeleteTextures(1, &ids[0]); + } + + m_mutex.unlock(); + } + + void Tile::Draw() + { + if (!m_failed) + { + if (m_textureLoaded) + { + glBindTexture(GL_TEXTURE_2D, m_textureId); + + glBegin(GL_QUADS); + + glTexCoord2f(0, 1); glVertex2f(m_transformed_top_left.x(), m_transformed_top_left.y()); + glTexCoord2f(1, 1); glVertex2f(m_transformed_top_right.x(), m_transformed_top_right.y()); + glTexCoord2f(1, 0); glVertex2f(m_transformed_bottom_right.x(), m_transformed_bottom_right.y()); + glTexCoord2f(0, 0); glVertex2f(m_transformed_bottom_left.x(), m_transformed_bottom_left.y()); + + glEnd(); + } + } + } + + void Tile::Transform(const swri_transform_util::Transform& transform) + { + m_transformed_top_left = transform * m_top_left; + m_transformed_top_right = transform * m_top_right; + m_transformed_bottom_left = transform * m_bottom_left; + m_transformed_bottom_right = transform * m_bottom_right; + } + + void Tile::Transform(const swri_transform_util::Transform& transform, const swri_transform_util::Transform& offset_tf) + { + m_transformed_top_left = offset_tf * (transform * m_top_left); + m_transformed_top_right = offset_tf * (transform * m_top_right); + m_transformed_bottom_left = offset_tf * (transform * m_bottom_left); + m_transformed_bottom_right = offset_tf * (transform * m_bottom_right); + } +} + diff --git a/multires_image/src/tile_cache.cpp b/multires_image/src/tile_cache.cpp new file mode 100644 index 000000000..d31d553d1 --- /dev/null +++ b/multires_image/src/tile_cache.cpp @@ -0,0 +1,396 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include +#include +#include +#include + +// QT libraries +#include +#include + +#include + +namespace multires_image +{ + TileCache::TileCache(TileSet* tileSet, QGLWidget* widget) + : QObject() + , m_tileSet(tileSet) + , m_widget(widget) + , m_currentLayer(0) + , m_currentPosition(0, 0, 0) + , m_exit(false) + , m_memorySize(0) + , m_cacheThread(this) + , m_freeThread(this) + , m_renderRequestsLock(QMutex::Recursive) + , m_renderRequestSetLock(QMutex::Recursive) + , m_precacheRequestsLock(QMutex::Recursive) + , m_precacheRequestSetLock(QMutex::Recursive) + , m_textureLoadedLock(QMutex::Recursive) + { + connect(this, SIGNAL(SignalLoadTexture(Tile*)), + SLOT(LoadTextureSlot(Tile*)), Qt::BlockingQueuedConnection); + + connect(this, SIGNAL(SignalDeleteTexture(Tile*)), + SLOT(DeleteTextureSlot(Tile*)), Qt::BlockingQueuedConnection); + + m_cacheThread.setPriority(QThread::NormalPriority); + m_cacheThread.start(); + + m_freeThread.setPriority(QThread::LowPriority); + m_freeThread.start(); + + for (int i = 0; i < m_tileSet->LayerCount(); i++) + { + m_precacheRequests.emplace_back(std::queue()); + } + } + + TileCache::~TileCache() + { + m_exit = true; + m_cacheThread.wait(); + m_freeThread.wait(); + } + + void TileCache::LoadTextureSlot(Tile* tile) + { + tile->LoadTexture(); + } + + void TileCache::DeleteTextureSlot(Tile* tile) + { + tile->UnloadTexture(); + } + + void TileCache::Load(Tile* tile) + { + m_renderRequestsLock.lock(); + m_renderRequestSetLock.lock(); + + try + { + if (m_renderRequestSet.count(tile->TileID()) == 0) + { + m_renderRequests.push(tile); + m_renderRequestSet[tile->TileID()] = tile; + } + } + catch(const std::exception& e) + { + std::cout << "An exception occurred queuing a tile to be cached: " << e.what() << std::endl; + } + + m_renderRequestSetLock.unlock(); + m_renderRequestsLock.unlock(); + } + + void TileCache::Precache(double x, double y) + { + tf2::Vector3 point(x, y, 0); + Precache(point); + } + + void TileCache::Precache(const tf2::Vector3& position) + { + m_currentPosition = position; + + int sizes[] = {3, 2, 2, 1, 1, 1}; + + PrecacheLayer(m_currentLayer, m_currentPosition, sizes[0]); + + for (int i = 1; i <= 5; i++) + { + int layer = m_currentLayer + i; + if (layer < m_tileSet->LayerCount()) + { + PrecacheLayer(layer, m_currentPosition, sizes[i]); + } + + layer = m_currentLayer - i; + if (layer >= 0) + { + PrecacheLayer(layer, m_currentPosition, sizes[i]); + } + } + } + + void TileCache::PrecacheLayer(int layerNum, const tf2::Vector3& position, int size) + { + TileSetLayer* layer = m_tileSet->GetLayer(layerNum); + + int row, column; + layer->GetTileIndex(position, row, column); + + int startRow = std::max(0, row - size); + int endRow = std::min(layer->RowCount() - 1, row + size); + int startColumn = std::max(0, column - size); + int endColumn = std::min(layer->ColumnCount() - 1, column + size); + + for (int c = startColumn; c <= endColumn; c++) + { + for (int r = startRow; r <= endRow; r++) + { + Tile* tile = layer->GetTile(c, r); + + m_precacheRequestsLock.lock(); + m_precacheRequestSetLock.lock(); + + try + { + if (m_precacheRequestSet.count(tile->TileID()) == 0) + { + m_precacheRequests[layerNum].push(tile); + m_precacheRequestSet[tile->TileID()] = tile; + } + } + catch (const std::exception& e) + { + std::cout << "An exception occurred queuing tiles for precaching: " << e.what() << std::endl; + } + + m_precacheRequestSetLock.unlock(); + m_precacheRequestsLock.unlock(); + } + } + } + + void TileCache::Exit() + { + m_exit = true; + } + + void TileCache::LoadTexture(Tile* tile) + { + Q_EMIT SignalLoadTexture(tile); + + m_memorySize += tile->MemorySize(); + Q_EMIT SignalMemorySize(m_memorySize); + + m_textureLoadedLock.lock(); + + try + { + m_textureLoaded[tile->TileID()] = tile; + } + catch (const std::exception& e) + { + std::cout << "An exception occurred loading texture: " << e.what() << std::endl; + } + + m_textureLoadedLock.unlock(); + + if (tile->Layer() == m_currentLayer) + { + QApplication::postEvent(m_widget, new QEvent(QEvent::UpdateRequest)); + } + } + + void TileCache::UnloadTexture(Tile* tile) + { + Q_EMIT SignalDeleteTexture(tile); + + m_memorySize -= tile->MemorySize(); + Q_EMIT SignalMemorySize(m_memorySize); + + m_textureLoadedLock.lock(); + + try + { + m_textureLoaded.erase(tile->TileID()); + } + catch (const std::exception& e) + { + std::cout << "An exception occurred unloading texture: " << e.what() << std::endl; + } + + m_textureLoadedLock.unlock(); + } + + void TileCache::CacheThread::run() + { + while (!p->m_exit) + { + Tile* tile = nullptr; + p->m_renderRequestsLock.lock(); + + if (!p->m_renderRequests.empty()) + { + tile = p->m_renderRequests.top(); + p->m_renderRequests.pop(); + } + + p->m_renderRequestsLock.unlock(); + + if (tile != nullptr) + { + if (!tile->Failed()) + { + if (tile->Layer() == p->m_currentLayer) + { + int row, column; + p->m_tileSet->GetLayer(tile->Layer())->GetTileIndex(p->m_currentPosition, row, column); + + if (abs(tile->Row() - row) <= 3 || abs(tile->Column() - column) < 3) + { + if (!tile->TextureLoaded()) + { + if (tile->LoadImageToMemory()) + { + p->LoadTexture(tile); + tile->UnloadImage(); + } + else + { + printf("failed to load image\n"); + } + } + } + } + else + { + p->m_precacheRequests[tile->Layer()].push(tile); + } + + p->m_renderRequestSetLock.lock(); + p->m_renderRequestSet.erase(tile->TileID()); + p->m_renderRequestSetLock.unlock(); + } + else + { + } + } + else + { + p->m_precacheRequestsLock.lock(); + + try + { + for (uint32_t i = 0; (i < p->m_precacheRequests.size()) && (tile == nullptr); i++) + { + int32_t index = p->m_currentLayer + i; + if ((index < (int64_t)p->m_precacheRequests.size()) && + (!p->m_precacheRequests[index].empty())) + { + tile = p->m_precacheRequests[index].front(); + p->m_precacheRequests[index].pop(); + } + else if (i != 0) + { + index = p->m_currentLayer - i; + if (index >= 0 && !p->m_precacheRequests[index].empty()) + { + tile = p->m_precacheRequests[index].front(); + p->m_precacheRequests[index].pop(); + } + } + } + } + catch (const std::exception& e) + { + std::cout << "An exception occurred precaching texture: " << e.what() << std::endl; + } + + p->m_precacheRequestsLock.unlock(); + + if (tile != nullptr && !tile->Failed() && !tile->TextureLoaded()) + { + int row, column; + p->m_tileSet->GetLayer(tile->Layer())->GetTileIndex(p->m_currentPosition, row, column); + if (abs(tile->Row() - row) <= 3 || abs(tile->Column() - column) <= 3) + { + if (tile->LoadImageToMemory()) + { + p->LoadTexture(tile); + + tile->UnloadImage(); + } + else + { + printf("failed to precache load image\n"); + } + } + + p->m_precacheRequestSetLock.lock(); + p->m_precacheRequestSet.erase(tile->TileID()); + p->m_precacheRequestSetLock.unlock(); + } + } + + if (tile == nullptr) + { + usleep(10); + } + } + } + + void TileCache::FreeThread::run() + { + while (!p->m_exit) + { + std::map* tiles; + p->m_textureLoadedLock.lock(); + + tiles = new std::map(p->m_textureLoaded); + + p->m_textureLoadedLock.unlock(); + + std::map::iterator iter; + + for (iter = tiles->begin(); iter != tiles->end(); ++iter) + { + Tile* tile = iter->second; + int row, column; + p->m_tileSet->GetLayer(tile->Layer())->GetTileIndex(p->m_currentPosition, row, column); + + if (abs(tile->Row() - row) > 6 || abs(tile->Column() - column) > 6) + { + p->m_renderRequestSetLock.lock(); + p->m_renderRequestSet.erase(tile->TileID()); + p->m_renderRequestSetLock.unlock(); + + p->m_precacheRequestSetLock.lock(); + p->m_precacheRequestSet.erase(tile->TileID()); + p->m_precacheRequestSetLock.unlock(); + + p->UnloadTexture(tile); + } + } + + delete tiles; + + sleep(2); + } + } +} diff --git a/multires_image/src/tile_set.cpp b/multires_image/src/tile_set.cpp new file mode 100644 index 000000000..77627492a --- /dev/null +++ b/multires_image/src/tile_set.cpp @@ -0,0 +1,124 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include +#include +#include + +// QT libraries +#include +#include +#include +#include + +namespace multires_image +{ + TileSet::TileSet(const std::string& geofile) : + m_geo(geofile), + m_extension("jpg") + { + } + + TileSet::TileSet(const std::string& geofile, const std::string extension) : + m_geo(geofile), + m_extension(extension) + { + } + + TileSet::TileSet(const swri_transform_util::GeoReference& georeference) : + m_geo(georeference), + m_extension("jpg") + { + } + + TileSet::TileSet(const swri_transform_util::GeoReference& georeference, + const std::string extension) : + m_geo(georeference), + m_extension(extension) + { + } + + TileSet::~TileSet() + { + // Free each of the layers. + for (auto & m_layer : m_layers) + { + delete m_layer; + } + } + + bool TileSet::Load() + { + if (!m_geo.Load()) + { + return false; + } + + m_cacheDir = m_geo.Path(); + m_width = m_geo.Width(); + m_height = m_geo.Height(); + m_tileSize = m_geo.TileSize(); + m_extension = m_geo.Extension(); + + float max_dim = std::max(m_width, m_height); + m_layerCount = std::ceil(std::log(max_dim / m_tileSize) / std::log(2.0f)) + 1; + m_layers.reserve(m_layerCount); + + // Check if the cache directory for this image exists. + QDir directory(m_cacheDir.c_str()); + if (!directory.exists()) + { + return false; + } + + // Load each layer. + for (int i = 0; i < m_layerCount; i++) + { + QString layerNum = QString::number(i); + + // Check if this layer exists in the cache. + QDir layerDir(directory.absolutePath() + "/layer" + layerNum); + if (!layerDir.exists(layerDir.absolutePath())) + { + return false; + } + + // Load the base layer. + m_layers.push_back(new TileSetLayer(m_geo, layerDir.absolutePath().toStdString(), m_tileSize, i)); + + if (!m_layers[i]->Load(m_extension)) + return false; + } + + return true; + } +} diff --git a/multires_image/src/tile_set_layer.cpp b/multires_image/src/tile_set_layer.cpp new file mode 100644 index 000000000..cbbcf39a7 --- /dev/null +++ b/multires_image/src/tile_set_layer.cpp @@ -0,0 +1,197 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include +#include + +// QT libraries +#include + +namespace multires_image +{ + TileSetLayer::TileSetLayer(const swri_transform_util::GeoReference& geo, + const std::string& path, + int tileSize, int layer) : + m_geo(geo), + m_path(path), + m_tileSize(tileSize), + m_layer(layer), + m_scale(std::pow(2.0, m_layer)), + m_expectTiles(true) + { + // Calculate the width and height in pixels of this layer + float width = std::ceil(m_geo.Width() / std::pow(2.0f, layer)); + float height = std::ceil(m_geo.Height() / std::pow(2.0f, layer)); + + // Calculate the number for tile rows and columns for this layer + m_columns = std::ceil(width / static_cast(tileSize)); + m_rows = std::ceil(height / static_cast(tileSize)); + + m_tiles.reserve(m_columns); + for (int c = 0; c < m_columns; c++) + { + m_tiles.emplace_back(std::vector()); + m_tiles[c].reserve(m_rows); + } + } + + bool TileSetLayer::Load() + { + return Load("jpg"); + } + + bool TileSetLayer::Load(const std::string extension) + { + bool needsTiles = false; + + for (int32_t c = 0; c < m_columns; c++) + { + for (int32_t r = 0; r < m_rows; r++) + { + std::string rowString = QString::number(r).toStdString(); + while (rowString.length() < 5) { + rowString = '0' + rowString; + } + + std::string columnString = QString::number(c).toStdString(); + while (columnString.length() < 5) { + columnString = '0' + columnString; + } + + // Get 4 corners of this tile + int left = c * m_tileSize * m_scale; + int top = r * m_tileSize * m_scale; + int bottom = (r + 1) * m_tileSize * m_scale; + int right = (c + 1) * m_tileSize * m_scale; + + if (right > (int64_t)m_geo.Width()) + { + right = m_geo.Width(); + } + if (bottom > (int64_t)m_geo.Height()) + { + bottom = m_geo.Height(); + } + + double x, y; + m_geo.GetCoordinate(left, top, x, y); + tf2::Vector3 top_left(x, y, 0); + + m_geo.GetCoordinate(right, top, x, y); + tf2::Vector3 top_right(x, y, 0); + + m_geo.GetCoordinate(left, bottom, x, y); + tf2::Vector3 bottom_left(x, y, 0); + + m_geo.GetCoordinate(right, bottom, x, y); + tf2::Vector3 bottom_right(x, y, 0); + + std::stringstream ss; + ss << m_path << "/tile" << rowString << "x" << columnString << "." << extension; + m_tiles[c].push_back(new Tile( + ss.str(), c, r, m_layer, top_left, top_right, bottom_left, bottom_right)); + + needsTiles |= !m_tiles[c][r]->Exists(); + } + } + + if (needsTiles) + { + if (m_expectTiles) + { + printf("Error: Missing expected tiles\n"); + return false; + } + } + + return true; + } + + void TileSetLayer::GetTileIndex(double x, double y, int& row, int& column) const + { + tf2::Vector3 position(x, y, 0); + GetTileIndex(position, row, column); + } + + void TileSetLayer::GetTileIndex(const tf2::Vector3& position, int& row, int& column) const + { + int x, y; + m_geo.GetPixel(position.x(), position.y(), x, y); + + column = static_cast(x / (m_scale * m_tileSize)); + row = static_cast(y / (m_scale * m_tileSize)); + } + + void TileSetLayer::GetTileRange( + const tf2::Vector3& top_left, + const tf2::Vector3& bottom_right, + int& startRow, int& startColumn, + int& endRow, int& endColumn) const + { + GetTileIndex(top_left.x(), top_left.y(), startRow, startColumn); + if (startColumn < 0) + { + startColumn = 0; + } + if ((uint32_t)startColumn >= m_tiles.size()) + { + startColumn = m_tiles.size() - 1; + } + if (startRow < 0) + { + startRow = 0; + } + if ((uint32_t)startRow >= m_tiles[0].size()) + { + startRow = m_tiles[0].size() - 1; + } + + GetTileIndex(bottom_right.x(), bottom_right.y(), endRow, endColumn); + if (endColumn < 0) + { + endColumn = 0; + } + if ((uint32_t)endColumn >= m_tiles.size()) + { + endColumn = m_tiles.size() - 1; + } + if (endRow < 0) + { + endRow = 0; + } + if ((uint32_t)endRow >= m_tiles[0].size()) + { + endRow = m_tiles[0].size() - 1; + } + } +} + diff --git a/multires_image/src/tile_view.cpp b/multires_image/src/tile_view.cpp new file mode 100644 index 000000000..7826ce5a8 --- /dev/null +++ b/multires_image/src/tile_view.cpp @@ -0,0 +1,175 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +// C++ standard libraries +#include +#include + +namespace multires_image +{ + TileView::TileView(TileSet* tiles, QGLWidget* widget) : + m_tiles(tiles), + m_cache(tiles, widget), + m_currentLayer(tiles->LayerCount() - 1), + m_startRow(0), + m_startColumn(0), + m_endRow(0), + m_endColumn(0) + { + double top, left, bottom, right; + tiles->GeoReference().GetCoordinate(0, 0, left, top); + tiles->GeoReference().GetCoordinate(tiles->GeoReference().Width(),tiles->GeoReference().Height(), right, bottom); + + double scale_x = std::abs(right - left) / tiles->GeoReference().Width(); + double scale_y = std::abs(top - bottom) / tiles->GeoReference().Height(); + + min_scale_ = scale_x; + if (scale_y > scale_x) + min_scale_ = scale_y; + } + + void TileView::SetView(double x, double y, double radius, double scale) + { + int layer = 0; + while (min_scale_ * std::pow(2.0, layer + 1) < scale) layer++; + + if (layer >= m_tiles->LayerCount()) + layer = m_tiles->LayerCount() - 1; + + if (layer != m_currentLayer) + { + m_currentLayer = layer; + m_cache.SetCurrentLayer(layer); + } + + int row, column; + m_tiles->GetLayer(m_currentLayer)->GetTileIndex(x, y, row, column); + + m_startRow = row - 2; + if (m_startRow < 0) { + m_startRow = 0; + } + if (m_startRow >= m_tiles->GetLayer(m_currentLayer)->RowCount()) { + m_startRow = m_tiles->GetLayer(m_currentLayer)->RowCount() - 1; + } + + m_endRow = row + 2; + if (m_endRow < 0) { + m_endRow = 0; + } + if (m_endRow >= m_tiles->GetLayer(m_currentLayer)->RowCount()) { + m_endRow = m_tiles->GetLayer(m_currentLayer)->RowCount() - 1; + } + + m_startColumn = column - 2; + if (m_startColumn < 0) { + m_startColumn = 0; + } + if (m_startColumn >= m_tiles->GetLayer(m_currentLayer)->ColumnCount()) { + m_startColumn = m_tiles->GetLayer(m_currentLayer)->ColumnCount() - 1; + } + + m_endColumn = column + 2; + if (m_endColumn < 0) { + m_endColumn = 0; + } + if (m_endColumn >= m_tiles->GetLayer(m_currentLayer)->ColumnCount()) { + m_endColumn = m_tiles->GetLayer(m_currentLayer)->ColumnCount() - 1; + } + + m_cache.Precache(x, y); + } + + void TileView::Draw() + { + glEnable(GL_TEXTURE_2D); + + glColor4f(1.0f, 1.0f, 1.0f, 1.0f); + + // Always draw bottom layers + if (m_currentLayer != m_tiles->LayerCount() - 1) + { + TileSetLayer* baseLayer = m_tiles->GetLayer(m_tiles->LayerCount() - 1); + Tile* tile = baseLayer->GetTile(0, 0); + if (tile->TextureLoaded()) + { + tile->Draw(); + } + else + { + m_cache.Load(tile); + } + } + + if (m_tiles->LayerCount() >= 2 && m_currentLayer != m_tiles->LayerCount() - 2) + { + TileSetLayer* baseLayer = m_tiles->GetLayer(m_tiles->LayerCount() - 2); + for (int c = 0; c < baseLayer->ColumnCount(); c++) + { + for (int r = 0; r < baseLayer->RowCount(); r++) + { + Tile* tile = baseLayer->GetTile(c, r); + if (tile->TextureLoaded()) + { + tile->Draw(); + } + else + { + m_cache.Load(tile); + } + } + } + } + + TileSetLayer* layer = m_tiles->GetLayer(m_currentLayer); + if (m_endColumn < layer->ColumnCount() && m_endRow < layer->RowCount()) + { + for (int c = m_startColumn; c <= m_endColumn; c++) + { + for (int r = m_startRow; r <= m_endRow; r++) + { + Tile* tile = layer->GetTile(c, r); + if (tile->TextureLoaded()) + { + tile->Draw(); + } + else + { + m_cache.Load(tile); + } + } + } + } + + glDisable(GL_TEXTURE_2D); + } +} + diff --git a/multires_image/test.geo b/multires_image/test.geo new file mode 100644 index 000000000..505e21f47 --- /dev/null +++ b/multires_image/test.geo @@ -0,0 +1,13 @@ +// Image properties +image_path: tiles +image_width: 25600 +image_height: 17920 +tile_size: 512 + +// Coordinate System +datum: wgs84 +projection: geographic + +// Georeference +tiepoint: [6785, 336, 29.45196669, -98.61370577] +pixel_scale: [0.00000157, 0.000001375] diff --git a/tile_map/CHANGELOG.rst b/tile_map/CHANGELOG.rst new file mode 100644 index 000000000..d5ac1e4f5 --- /dev/null +++ b/tile_map/CHANGELOG.rst @@ -0,0 +1,154 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package tile_map +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +2.3.0 (2023-08-24) +------------------ + +2.2.2 (2023-06-07) +------------------ +* Iron Compatibility (`#779 `_) +* Contributors: David Anthony + +2.2.1 (2023-05-30) +------------------ +* Updating maintainers list (`#778 `_) +* Contributors: David Anthony + +2.1.0 (2020-10-22) +------------------ + +2.0.0 (2020-05-13) +------------------ +* Port mapviz to ROS 2 (`#672 `_) +* Remove OpenGL warning (`#667 `_) +* Contributors: Daniel D'Souza, P. J. Reed, Jacob Hassold, Kevin Nickels, Roger Strain, Matthew Bries + +1.2.0 (2019-09-04) +------------------ + +1.1.1 (2019-05-17) +------------------ + +1.1.0 (2019-02-20) +------------------ +* Fix non-Bing sources (`#615 `_) +* Contributors: P. J. Reed + +1.0.1 (2019-01-25) +------------------ + +1.0.0 (2019-01-23) +------------------ +* Sharing tf_manager\_ between main app and plugins (`#555 `_) +* Fix issue with loading Bing map tiles (`#599 `_) +* Contributors: Davide Faconti, P. J. Reed + +0.3.0 (2018-11-16) +------------------ +* Merge all -devel branches into a single master branch +* Contributors: P. J. Reed + +0.2.6 (2018-07-31) +------------------ + +0.2.5 (2018-04-12) +------------------ +* Bug fix in TileMap. GenTexture was invoked over and over again (`#559 `_) +* Improve tile loading prioritization. +* Glew warning fixed (`#539 `_) +* update to use non deprecated pluginlib macro +* Contributors: Davide Faconti, Marc Alban, Mikael Arguedas, P. J. Reed + +0.2.4 (2017-08-11) +------------------ +* add include for boost::algorithm::trim_copy to fix tile_map_plugin.cpp:408:31: error: ‘trim_copy’ is not a member of ‘boost’ (`#497 `_) +* Contributors: Austin Deric + +0.2.3 (2016-12-10) +------------------ + +0.2.2 (2016-12-07) +------------------ + +0.2.1 (2016-10-23) +------------------ +* Rewrite tile_map loading to be more reliable + This changes how the tile_map plugin handles making network requires for tiles. + It will now: + - Use thread conditions to prompt loading rather than spinning + - Prioritize loading tiles in the visible area + - Retry a failed network request up to 5 times + - Not discard tile requests if there are more than 100 in the queue + This changes should significantly reduce (if not completely eliminate) the + number of tiles that fail to load and hopefully make tiles within the visible + area appear faster when there are many in the queue. + Fixes `#342 `_ and `#421 `_. +* Adding support for Bing Maps (`#409 `_) + This makes a number of changes in the `tile_map` plugin in order to support + different types of tile servers, including Bing Maps. Notable changes include: + - TileSource is now an abstract class + - WMTS server-specific behavior has been moved into a new WmtsSource class + - BingSource provides support for obtaining tiles from Bing Maps + - The UI for specifying server URLs has changed + - Prefix and coordinate order are no longer separate fields + - In URLs for WMTS sources, the variables {level}, {x}, and {y} will be substituted with appropriate values when tiles are requested + - Rather than generating hashes for image tiles based on their URLs, hashes are now generated by the TileSource implementations in order to support sources that can pull tiles from multiple servers + - Idle performance has been improved by removing redundant recalculations of the map view + - Added a dependency on libjsoncpp + Resolves `#227 `_ + Conflicts: + tile_map/CMakeLists.txt + tile_map/package.xml +* Giving `tile_map` an interface overhaul + MapQuest has turned off their public API for map tiles, so this plugin needed some work. I have: + - Removed the MapQuest sources + - Made the interface for adding new sources more powerful + - Overhauled how sources are saved and loaded under the hood + - Added a button to reset the current tile cache + Resolves `#402 `_ + Conflicts: + tile_map/CMakeLists.txt +* Contributors: P. J. Reed + +0.2.0 (2016-06-23) +------------------ +* Update tile_map to Qt5. +* Contributors: Ed Venator + +0.1.3 (2016-05-20) +------------------ +* Fix typo in tile map view size comparison. +* Contributors: Marc Alban + +0.1.2 (2016-01-06) +------------------ + +0.1.1 (2015-11-17) +------------------ +* Mark single argument constructors explicit. +* Contributors: Marc Alban + +0.1.0 (2015-09-29) +------------------ + +0.0.3 (2015-09-28) +------------------ + +0.0.2 (2015-09-27) +------------------ + +0.0.1 (2015-09-27) +------------------ +* Adds missing qt-opengl dependency to tile_map. +* Renames all marti_common packages that were renamed. + (See http://github.com/swri-robotics/marti_common/issues/231) +* Fixes catkin_lint problems that could prevent installation. +* updates cmake version to squash the CMP0003 warning +* removes dependencies on build_tools +* uses format 2 package definition +* implements subdivision of map tiles at the highest zoom levels to correctly warp map to the canvas coordinate system +* only transform tile map when the transform changes +* fixes related to merging catkin branch into tile_map and building on Ubuntu 12.04 +* initial working implementation of tile map plugin +* Contributors: Ed Venator, Edward Venator, Marc Alban, P. J. Reed diff --git a/tile_map/CMakeLists.txt b/tile_map/CMakeLists.txt new file mode 100644 index 000000000..1850bb005 --- /dev/null +++ b/tile_map/CMakeLists.txt @@ -0,0 +1,141 @@ +### SET CMAKE POLICIES ### +cmake_minimum_required(VERSION 3.10...3.17) + +if(${CMAKE_VERSION} VERSION_LESS 3.12) + cmake_policy(VERSION ${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION}) +endif() + +if (NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(${CMAKE_VERSION} VERSION_EQUAL "3.11.0" OR ${CMAKE_VERSION} VERSION_GREATER "3.11.0") + cmake_policy(SET CMP0072 NEW) +endif() + +if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() +### END CMAKE POLICIES ### + +project(tile_map + LANGUAGES CXX) + +# ROS packages +find_package(ament_cmake REQUIRED) +find_package(mapviz REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(swri_math_util REQUIRED) +find_package(swri_transform_util REQUIRED) +find_package(tf2 REQUIRED) + +# Qt 5 +find_package(Qt5Core REQUIRED) +find_package(Qt5Gui REQUIRED) +find_package(Qt5Network REQUIRED) +find_package(Qt5OpenGL REQUIRED) +find_package(Qt5Widgets REQUIRED) +# Still useful? +# add_definitions(-DWFlags=WindowFlags) + +### OpenGL ### +find_package(OpenGL REQUIRED) + +### GLEW ### +find_package(GLEW REQUIRED) + +### PkgConfig ### +find_package(PkgConfig REQUIRED) + +### yaml-cpp ### +pkg_check_modules(YamlCpp yaml-cpp) + +### Use PkgConfig to find jsoncpp ### +pkg_check_modules(JSONCPP REQUIRED jsoncpp) + +# Fix conflict between Boost signals used by tf and QT signals used by mapviz +add_definitions(-DQT_NO_KEYWORDS) + +# Need to include the current dir to include the results of building Qt UI files +set(CMAKE_INCLUDE_CURRENT_DIR ON) + +set(TILE_SRC_FILES + src/image_cache.cpp + src/texture_cache.cpp + src/bing_source.cpp + src/tile_source.cpp + src/wmts_source.cpp + src/${PROJECT_NAME}_view.cpp +) +set(QT_HEADERS + include/${PROJECT_NAME}/image_cache.h + include/${PROJECT_NAME}/tile_source.h + include/${PROJECT_NAME}/wmts_source.h + include/${PROJECT_NAME}/bing_source.h +) +qt5_wrap_cpp(TILE_SRC_FILES ${QT_HEADERS}) +add_library(${PROJECT_NAME} ${TILE_SRC_FILES}) +target_include_directories(${PROJECT_NAME} + PUBLIC + include) +target_include_directories(${PROJECT_NAME} SYSTEM + PUBLIC + GLEW::GLEW + ${JSONCPP_INCLUDE_DIRS} + ${YamlCpp_INCLUDE_DIRS}) +ament_target_dependencies(${PROJECT_NAME} + ament_cmake + mapviz + pluginlib + rclcpp + swri_math_util + swri_transform_util + tf2 +) +target_link_libraries(${PROJECT_NAME} + ${GLU_LIBRARY} + ${JSONCPP_LIBRARIES} + ${YamlCpp_LIBRARIES} + Qt5::Network + Qt5::Core + Qt5::Gui + Qt5::OpenGL + Qt5::Widgets +) + +set(PLUGIN_SRC_FILES + src/${PROJECT_NAME}_plugin.cpp) +set(PLUGIN_UI_FILES + src/${PROJECT_NAME}_config.ui) + +qt5_wrap_ui(PLUGIN_SRC_FILES ${PLUGIN_UI_FILES}) +qt5_wrap_cpp(PLUGIN_SRC_FILES include/${PROJECT_NAME}/${PROJECT_NAME}_plugin.h) + +add_library(${PROJECT_NAME}_plugin SHARED ${PLUGIN_SRC_FILES}) +target_compile_definitions(${PROJECT_NAME}_plugin PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") +target_link_libraries(${PROJECT_NAME}_plugin ${PROJECT_NAME}) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION include/${PROJECT_NAME} + FILES_MATCHING PATTERN "*.h" +) + +install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_plugin + RUNTIME DESTINATION lib/${PROJECT_NAME} + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib +) + +pluginlib_export_plugin_description_file(mapviz mapviz_plugins.xml) + +ament_export_dependencies(${RUNTIME_DEPS} + Qt5::Network + Qt5::Core + Qt5::Gui + Qt5::OpenGL + Qt5::Widgets +) +ament_export_include_directories(include) +ament_export_libraries(${PROJECT_NAME}) +ament_package() diff --git a/tile_map/include/tile_map/bing_source.h b/tile_map/include/tile_map/bing_source.h new file mode 100644 index 000000000..8413de547 --- /dev/null +++ b/tile_map/include/tile_map/bing_source.h @@ -0,0 +1,141 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#ifndef TILE_MAP_BING_SOURCE_H +#define TILE_MAP_BING_SOURCE_H + +#include "tile_source.h" + +#include +#include + +#include + +#include +#include +#include + +namespace tile_map +{ + class BingSource : public TileSource + { + Q_OBJECT + public: + /** + * Initializes a Bing map source with a given name. + * + * Note that currently, only a single, hard-coded Bing map source is supported. + * There's only one Bing Maps, after all. + * In the future, though, it would probably make sense to extend its + * functionality to allow pulling different tile sets from Bing. + * @param name The name the source will appear as in the combo box. + */ + explicit BingSource(const QString& name); + + /** + * Generates a unique hash that identifies the tile as the given coordinates. + * + * Note that Bing Maps tiles could potentially be pulled from one of many + * different servers, depending on the subdomain list given to us after we + * authenticate with our API Key. That means the exact URL to any given tile + * should not be used as part of the hash, because there are many valid URLs + * for a tile. + * @param level The zoom level + * @param x The X coordinate + * @param y The Y coordinate + * @return A hash that uniquely identifies this tile + */ + size_t GenerateTileHash(int32_t level, int64_t x, int64_t y) override; + + /** + * Generates a URL that will retrieve a tile for the given coordinates. + * + * Since Bing can give us a list of subdomains to pull tiles from, the + * exact subdomain for a tile is chosen at random every time this function + * is called. That means you are not guaranteed to get the same URL for a + * tile every time you call this function. + * @param level The zoom level + * @param x The X coordinate + * @param y The Y coordinate + * @return A URL that points to this tile + */ + QString GenerateTileUrl(int32_t level, int64_t x, int64_t y) override; + + QString GetType() const override; + + QString GetApiKey() const; + + /** + * Bing requires an API key in order to access its tiles. The key provided + * will determine the URL we use to retrieve map tiles, so setting the API + * key will also cause this object to make a network request to the Bing Map + * server to get the appropriate URL. + * + * More information about getting an API key: + * https://msdn.microsoft.com/en-us/library/ff428642.aspx + * @param api_key A valid Bing Maps key + */ + void SetApiKey(const QString& api_key); + + static const QString BING_TYPE; + + protected Q_SLOTS: + void ReplyFinished(QNetworkReply* reply); + + protected: + /** + * Bing Maps identifies tiles using a quadkey that is generated from the zoom + * level and x and y coordinates. Details on how the quadkey is generated can + * be found here: + * https://msdn.microsoft.com/en-us/library/bb259689.aspx + * + * @param level The zoom level + * @param x The X coordinate + * @param y The Y coordinate + * @return The quadkey that represents the tile at the requested location + */ + QString GenerateQuadKey(int32_t level, int64_t x, int64_t y) const; + + QString api_key_; + boost::hash hash_; + QNetworkAccessManager network_manager_; + boost::random::mt19937 rng_; + std::vector subdomains_; + QString tile_url_; + + static const std::string BING_IMAGE_URL_KEY; + static const std::string BING_IMAGE_URL_SUBDOMAIN_KEY; + static const std::string BING_RESOURCE_SET_KEY; + static const std::string BING_RESOURCE_KEY; + static const std::string BING_STATUS_CODE_KEY; + }; +} + +#endif //TILE_MAP_BING_SOURCE_H diff --git a/tile_map/include/tile_map/image_cache.h b/tile_map/include/tile_map/image_cache.h new file mode 100644 index 000000000..cdfb8483f --- /dev/null +++ b/tile_map/include/tile_map/image_cache.h @@ -0,0 +1,171 @@ +// ***************************************************************************** +// +// Copyright (c) 2014-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef TILE_MAP_IMAGE_CACHE_H_ +#define TILE_MAP_IMAGE_CACHE_H_ + +#include +#include + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace tile_map +{ + class CacheThread; + + class Image + { + public: + Image(const QString& uri, size_t uri_hash, uint64_t priority = 0); + ~Image() = default; + + QString Uri() const { return uri_; } + size_t UriHash() const { return uri_hash_; } + + std::shared_ptr GetImage() { return image_; } + + void InitializeImage(); + void ClearImage(); + + void AddFailure(); + bool Failed() const { return failed_; } + + void IncreasePriority() + { + if (priority_ < std::numeric_limits::max()) + { + priority_++; + } + } + void SetPriority(uint64_t priority) { priority_ = priority; } + uint64_t Priority() const { return priority_; } + + bool Loading() const { return loading_; } + void SetLoading(bool loading) { loading_ = loading; } + + private: + QString uri_; + + size_t uri_hash_; + + bool loading_; + int32_t failures_; + bool failed_; + uint64_t priority_; + + mutable std::shared_ptr image_; + + static const int MAXIMUM_FAILURES; + }; + typedef std::shared_ptr ImagePtr; + + class ImageCache : public QObject + { + Q_OBJECT + + public: + explicit ImageCache(const QString& cache_dir, + size_t size = 4096, + rclcpp::Logger logger = rclcpp::get_logger("tile_map::ImageCache")); + ~ImageCache() override; + + ImagePtr GetImage(size_t uri_hash, const QString& uri, int32_t priority = 0); + + void SetLogger(rclcpp::Logger logger); + + public Q_SLOTS: + void ProcessRequest(QString uri); + void ProcessReply(QNetworkReply* reply); + void Clear(); + + private: + QNetworkAccessManager network_manager_; + + QString cache_dir_; + + QCache cache_; + QMap unprocessed_; + QSet failed_; + QMap uri_to_hash_map_; + + QMutex cache_mutex_; + QMutex unprocessed_mutex_; + bool exit_; + + uint64_t tick_; + + CacheThread* cache_thread_; + + QSemaphore network_request_semaphore_; + + rclcpp::Logger logger_; + + friend class CacheThread; + + static const int MAXIMUM_NETWORK_REQUESTS; + }; + + class CacheThread : public QThread + { + Q_OBJECT + public: + explicit CacheThread(ImageCache* parent); + + void run() override; + + void notify(); + + Q_SIGNALS: + void RequestImage(QString); + + private: + ImageCache* image_cache_; + QMutex waiting_mutex_; + + static const int MAXIMUM_SEQUENTIAL_REQUESTS; + }; + + + typedef std::shared_ptr ImageCachePtr; +} + +#endif // TILE_MAP_IMAGE_CACHE_H_ diff --git a/tile_map/include/tile_map/texture_cache.h b/tile_map/include/tile_map/texture_cache.h new file mode 100644 index 000000000..39f62531d --- /dev/null +++ b/tile_map/include/tile_map/texture_cache.h @@ -0,0 +1,78 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef TILE_MAP_TEXTURE_CACHE_H_ +#define TILE_MAP_TEXTURE_CACHE_H_ + +#include + +#include + +#include + +namespace tile_map +{ + class Texture + { + public: + Texture(int32_t texture_id, size_t hash); + ~Texture(); + + const int32_t id; + const size_t url_hash; + + bool failed; + }; + typedef std::shared_ptr TexturePtr; + + class TextureCache + { + public: + explicit TextureCache(ImageCachePtr image_cache, + size_t size = 512, + rclcpp::Logger logger = rclcpp::get_logger("tile_map::TextureCache")); + + TexturePtr GetTexture(size_t url_hash, const QString& url, bool& failed, int priority); + void AddTexture(const TexturePtr& texture); + + void SetLogger(rclcpp::Logger logger); + + void Clear(); + + private: + QCache cache_; + + ImageCachePtr image_cache_; + + rclcpp::Logger logger_; + }; + typedef std::shared_ptr TextureCachePtr; +} + +#endif // TILE_MAP_TEXTURE_CACHE_H_ diff --git a/tile_map/include/tile_map/tile_map_plugin.h b/tile_map/include/tile_map/tile_map_plugin.h new file mode 100644 index 000000000..d0b9cb2da --- /dev/null +++ b/tile_map/include/tile_map/tile_map_plugin.h @@ -0,0 +1,126 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef TILE_MAP_TILE_MAP_PLUGIN_H_ +#define TILE_MAP_TILE_MAP_PLUGIN_H_ + +// C++ standard libraries +#include +#include + +// Boost libraries +#include +#include + +#include + +// QT libraries +#include +#include +#include + +#include +#include + +// QT autogenerated files +#include "ui_tile_map_config.h" + +namespace tile_map +{ + class TileSource; + + class TileMapPlugin : public mapviz::MapvizPlugin + { + Q_OBJECT + + public: + TileMapPlugin(); + ~TileMapPlugin() override = default; + + bool Initialize(QGLWidget* canvas) override; + void Shutdown() override {} + + void Draw(double x, double y, double scale) override; + + void Transform() override; + + void LoadConfig(const YAML::Node& node, const std::string& path) override; + void SaveConfig(YAML::Emitter& emitter, const std::string& path) override; + + QWidget* GetConfigWidget(QWidget* parent) override; + + void SetNode(rclcpp::Node& node) override; + + protected Q_SLOTS: + void PrintError(const std::string& message) override; + void PrintInfo(const std::string& message) override; + void PrintWarning(const std::string& message) override; + + void DeleteTileSource(); + void SelectSource(const QString& source_name); + void SaveCustomSource(); + void ResetTileCache(); + + private: + void selectTileSource(const std::shared_ptr& tile_source); + void startCustomEditing(); + void stopCustomEditing(); + + Ui::tile_map_config ui_; + QWidget* config_widget_; + + swri_transform_util::Transform transform_; + swri_transform_util::Transform inverse_transform_; + + bool transformed_; + + TileMapView tile_map_; + std::map > tile_sources_; + + double last_center_x_; + double last_center_y_; + double last_scale_; + int32_t last_height_; + int32_t last_width_; + + static std::string BASE_URL_KEY; + static std::string BING_API_KEY; + static std::string CUSTOM_SOURCES_KEY; + static std::string MAX_ZOOM_KEY; + static std::string NAME_KEY; + static std::string SOURCE_KEY; + static std::string TYPE_KEY; + static QString BING_NAME; + static QString STAMEN_TERRAIN_NAME; + static QString STAMEN_TONER_NAME; + static QString STAMEN_WATERCOLOR_NAME; + }; +} + +#endif // TILE_MAP_TILE_MAP_PLUGIN_H_ diff --git a/tile_map/include/tile_map/tile_map_view.h b/tile_map/include/tile_map/tile_map_view.h new file mode 100644 index 000000000..eb9232243 --- /dev/null +++ b/tile_map/include/tile_map/tile_map_view.h @@ -0,0 +1,115 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#ifndef TILE_MAP_TILE_MAP_VIEW_H_ +#define TILE_MAP_TILE_MAP_VIEW_H_ + +#include + +#include +#include + +#include + +#include + +namespace tile_map +{ + class TileSource; + + struct Tile + { + public: + QString url; + size_t url_hash; + int32_t level; + int32_t subdiv_count; + double subwidth; + + TexturePtr texture; + + std::vector points; + std::vector points_t; + }; + + class TileMapView + { + public: + explicit TileMapView(rclcpp::Logger logger = rclcpp::get_logger("tile_map::TileMapView")); + + bool IsReady(); + + void ResetCache(); + + void SetLogger(rclcpp::Logger logger); + + void SetTileSource(const std::shared_ptr& tile_source); + + void SetTransform(const swri_transform_util::Transform& transform); + + void SetView( + double latitude, + double longitude, + double scale, + int32_t width, + int32_t height); + + void Draw(); + + private: + void DrawTiles(std::vector &tiles ,int priority); + + std::shared_ptr tile_source_; + + swri_transform_util::Transform transform_; + + int32_t level_; + + int64_t center_x_; + int64_t center_y_; + + int64_t size_; + + int32_t width_; + int32_t height_; + + std::vector tiles_; + std::vector precache_; + + TextureCachePtr tile_cache_; + + rclcpp::Logger logger_; + + void ToLatLon(int32_t level, double x, double y, double& latitude, double& longitude); + + void InitializeTile(int32_t level, int64_t x, int64_t y, Tile& tile, int priority); + }; +} + +#endif // TILE_MAP_TILE_MAP_VIEW_H_ diff --git a/tile_map/include/tile_map/tile_source.h b/tile_map/include/tile_map/tile_source.h new file mode 100644 index 000000000..d1c5d504e --- /dev/null +++ b/tile_map/include/tile_map/tile_source.h @@ -0,0 +1,122 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#ifndef TILE_MAP_TILE_SOURCE_H +#define TILE_MAP_TILE_SOURCE_H + +#include +#include + +namespace tile_map +{ + /** + * Represents a network source for map tiles; contains information about how to + * connect to the source and how to retrieve tiles from it. + * + * Implementations of this should be specific to a type of map server such as + * WMS, WMTS, or TMS, and implement the appropriate methods for retrieiving tiles + * from those servers. + */ + class TileSource : public QObject + { + Q_OBJECT + public: + ~TileSource() override = default; + + virtual const QString& GetBaseUrl() const; + + virtual void SetBaseUrl(const QString& base_url); + + virtual bool IsCustom() const; + + virtual bool IsReady() const { return is_ready_; }; + + virtual void SetCustom(bool is_custom); + + virtual int32_t GetMaxZoom() const; + + virtual void SetMaxZoom(int32_t max_zoom); + + virtual int32_t GetMinZoom() const; + + virtual void SetMinZoom(int32_t min_zoom); + + virtual const QString& GetName() const; + + virtual void SetName(const QString& name); + + /** + * Generates a hash that uniquely identifies the tile from this source at the + * specified level and coordinates. + * @param level The zoom level + * @param x The X coordinate + * @param y The Y coordinate + * @return A hash identifying the tile + */ + virtual size_t GenerateTileHash(int32_t level, int64_t x, int64_t y) = 0; + + /** + * Generates an HTTP or HTTPS URL that refers to a map tile from this source + * at the given level and x and y coordinates. + * @param level The zoom level + * @param x The x coordinate + * @param y The y coordinate + * @return A URL referring to the map tile + */ + virtual QString GenerateTileUrl(int32_t level, int64_t x, int64_t y) = 0; + + /** + * Returns a string identifying the type of map source ("wmts", "bing", etc.) + * @return + */ + virtual QString GetType() const = 0; + + Q_SIGNALS: + void ErrorMessage(const std::string& error_msg) const; + void InfoMessage(const std::string& info_msg) const; + + protected: + TileSource() : + is_custom_(false), + is_ready_(true), + max_zoom_(20), + min_zoom_(0) + {}; + + QString base_url_; + bool is_custom_; + bool is_ready_; + int32_t max_zoom_; + int32_t min_zoom_; + QString name_; + }; +} + +#endif //TILE_MAP_TILE_SOURCE_H diff --git a/tile_map/include/tile_map/wmts_source.h b/tile_map/include/tile_map/wmts_source.h new file mode 100644 index 000000000..b9d645823 --- /dev/null +++ b/tile_map/include/tile_map/wmts_source.h @@ -0,0 +1,86 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#ifndef TILE_MAP_WMTS_SOURCE_H +#define TILE_MAP_WMTS_SOURCE_H + +#include "tile_source.h" + +#include + +namespace tile_map +{ + class WmtsSource : public TileSource + { + Q_OBJECT + public: + /** + * Creates a new tile source from a set of known parameters. + * + * @param[in] name A user-friendly display name + * @param[in] base_url The base HTTP URL of the data source; e. g.: + * "http://tile.stamen.com/terrain/" + * @param[in] is_custom If this is a custom (i. e. not one of the default) + * tile source; custom sources are saved and loaded from our settings + * @param[in] max_zoom The maximum zoom level + */ + explicit WmtsSource(const QString& name, + const QString& base_url, + bool is_custom, + int32_t max_zoom); + + virtual size_t GenerateTileHash(int32_t level, int64_t x, int64_t y); + + /** + * Given a zoom level and x and y coordinates appropriate for the tile source's + * projection, this will generate a URL that points to an image tile for that + * location. + * + * This expects the URL to have three strings in it, "{level}", "{x}", and "{y}", + * which will be replaced with the passed values. See tile_map_plugin.cpp for + * example URLs. + * + * @param[in] level The zoom level + * @param[in] x The X coordinate of the tile + * @param[in] y The Y coordinate of the tile + * @return A URL that references that tile + */ + virtual QString GenerateTileUrl(int32_t level, int64_t x, int64_t y); + + virtual QString GetType() const; + + static const QString WMTS_TYPE; + + private: + boost::hash hash_; + }; +} + +#endif //TILE_MAP_WMTS_SOURCE_H diff --git a/tile_map/mapviz_plugins.xml b/tile_map/mapviz_plugins.xml new file mode 100644 index 000000000..27829fd45 --- /dev/null +++ b/tile_map/mapviz_plugins.xml @@ -0,0 +1,6 @@ + + + Plugin for viewing slippy maps from a map server. + + + diff --git a/tile_map/package.xml b/tile_map/package.xml new file mode 100644 index 000000000..9abce9a36 --- /dev/null +++ b/tile_map/package.xml @@ -0,0 +1,42 @@ + + tile_map + 2.3.0 + + + Tile map provides a slippy map style interface for visualizing + OpenStreetMap and GoogleMap tiles. A mapviz visualization plug-in is also + implemented + + + Marc Alban + P. J. Reed + Southwest Research Institute + BSD + https://github.com/swri-robotics/mapviz + + ament_cmake + qt5-qmake + + libjsoncpp-dev + libqt5-core + libqt5-opengl-dev + + libglew-dev + mapviz + pluginlib + rclcpp + swri_math_util + swri_transform_util + tf2 + yaml-cpp + + libjsoncpp + libqt5-opengl + + + ament_cmake + + + + + diff --git a/tile_map/src/bing_source.cpp b/tile_map/src/bing_source.cpp new file mode 100644 index 000000000..cb3c3a1d6 --- /dev/null +++ b/tile_map/src/bing_source.cpp @@ -0,0 +1,187 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#include +#include +#include + +#include +#include + +#include + +namespace tile_map +{ + const QString BingSource::BING_TYPE = "bing"; + const std::string BingSource::BING_IMAGE_URL_KEY = "imageUrl"; + const std::string BingSource::BING_IMAGE_URL_SUBDOMAIN_KEY = "imageUrlSubdomains"; + const std::string BingSource::BING_RESOURCE_SET_KEY = "resourceSets"; + const std::string BingSource::BING_RESOURCE_KEY = "resources"; + const std::string BingSource::BING_STATUS_CODE_KEY = "statusCode"; + + BingSource::BingSource(const QString& name) : + TileSource(), + network_manager_(this) + { + name_ = name; + is_custom_ = false; + max_zoom_ = 19; + base_url_ = "https://dev.virtualearth.net/REST/v1/Imagery/Metadata/Aerial?uriScheme=https&include=ImageryProviders&key={api_key}"; + tile_url_ = ""; + min_zoom_ = 2; + + QObject::connect(&network_manager_, SIGNAL(finished(QNetworkReply*)), + this, SLOT(ReplyFinished(QNetworkReply*))); + } + + size_t BingSource::GenerateTileHash(int32_t level, int64_t x, int64_t y) + { + size_t hash = hash_((base_url_ + api_key_ + GenerateQuadKey(level, x, y)).toStdString()); + return hash; + } + + QString BingSource::GenerateTileUrl(int32_t level, int64_t x, int64_t y) + { + QString url = tile_url_; + if (!subdomains_.empty()) + { + boost::random::uniform_int_distribution<> random(0, (int) subdomains_.size() - 1); + url.replace(QString::fromStdString("{subdomain}"), subdomains_[random(rng_)]); + } + url.replace(QString::fromStdString("{quadkey}"), GenerateQuadKey(level, x, y)); + return url; + } + + QString BingSource::GetType() const + { + return BING_TYPE; + } + + QString BingSource::GetApiKey() const + { + return api_key_; + } + + void BingSource::SetApiKey(const QString& api_key) + { + api_key_ = api_key.trimmed(); + if (!api_key_.isEmpty()) + { + QString url(base_url_); + url.replace(QString::fromStdString("{api_key}"), api_key_); + // Changing the API key will result in the tile URL changing; go ahead + // and blank it out so we don't make requests using the old one. + tile_url_= ""; + subdomains_.clear(); + network_manager_.get(QNetworkRequest(QUrl(url))); + } + } + + QString BingSource::GenerateQuadKey(int32_t level, int64_t x, int64_t y) const + { + QString quadkey; + for (int32_t i = level; i > 0; i--) + { + int32_t bitmask = 1 << (i-1); + int32_t digit = 0; + if ((x & bitmask) != 0) + { + digit |= 1; + } + if ((y & bitmask) != 0) + { + digit |= 2; + } + quadkey.append(QString::number(digit)); + } + + return quadkey; + } + + void BingSource::ReplyFinished(QNetworkReply* reply) + { + QString reply_string(reply->readAll()); + Json::Reader reader; + Json::Value root; + reader.parse(reply_string.toStdString(), root); + + int status = root[BING_STATUS_CODE_KEY].asInt(); + if (status != 200) + { + Q_EMIT ErrorMessage("Bing authorization error: " + std::to_string(status)); + } + else + { + if (!root[BING_RESOURCE_SET_KEY].isArray() || + root[BING_RESOURCE_SET_KEY].empty()) + { + Q_EMIT ErrorMessage("No Bing resource sets found."); + return; + } + Json::Value firstResourceSet = root[BING_RESOURCE_SET_KEY][0]; + + if (!firstResourceSet[BING_RESOURCE_KEY].isArray() || + firstResourceSet[BING_RESOURCE_KEY].empty()) + { + Q_EMIT ErrorMessage("No Bing resources found."); + return; + } + + Json::Value first_resource = firstResourceSet[BING_RESOURCE_KEY][0]; + + std::string image_url = first_resource[BING_IMAGE_URL_KEY].asString(); + + if (image_url.empty()) + { + Q_EMIT ErrorMessage("No Bing image URL found."); + return; + } + + tile_url_ = QString::fromStdString(image_url); + SetMaxZoom(19); + + + if (!first_resource[BING_IMAGE_URL_SUBDOMAIN_KEY].isArray() || + first_resource[BING_IMAGE_URL_SUBDOMAIN_KEY].empty()) + { + Q_EMIT ErrorMessage("No image URL subdomains; maybe that's ok sometimes?"); + } + + for (const auto& subdomain : first_resource[BING_IMAGE_URL_SUBDOMAIN_KEY]) + { + subdomains_.push_back(QString::fromStdString(subdomain.asString())); + } + + Q_EMIT InfoMessage("API Key Set."); + + is_ready_ = true; + } + } +} diff --git a/tile_map/src/image_cache.cpp b/tile_map/src/image_cache.cpp new file mode 100644 index 000000000..510446e76 --- /dev/null +++ b/tile_map/src/image_cache.cpp @@ -0,0 +1,337 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace tile_map +{ + bool ComparePriority(const ImagePtr left, const ImagePtr right) + { + return left->Priority() > right->Priority(); + } + + const int Image::MAXIMUM_FAILURES = 5; + + Image::Image(const QString& uri, size_t uri_hash, uint64_t priority) : + uri_(uri), + uri_hash_(uri_hash), + loading_(false), + failures_(0), + failed_(false), + priority_(priority) + { + } + + void Image::InitializeImage() + { + image_ = std::make_shared(); + } + + void Image::ClearImage() + { + image_.reset(); + } + + void Image::AddFailure() + { + failures_++; + failed_ = failures_ > MAXIMUM_FAILURES; + } + + const int ImageCache::MAXIMUM_NETWORK_REQUESTS = 6; + + ImageCache::ImageCache(const QString& cache_dir, + size_t size, + rclcpp::Logger logger) : + network_manager_(this), + cache_dir_(cache_dir), + cache_(size), + exit_(false), + tick_(0), + cache_thread_(new CacheThread(this)), + network_request_semaphore_(MAXIMUM_NETWORK_REQUESTS), + logger_(logger) + { + QNetworkDiskCache* disk_cache = new QNetworkDiskCache(this); + disk_cache->setCacheDirectory(cache_dir_); + network_manager_.setCache(disk_cache); + + connect(&network_manager_, SIGNAL(finished(QNetworkReply*)), this, SLOT(ProcessReply(QNetworkReply*))); + connect(cache_thread_, SIGNAL(RequestImage(QString)), this, SLOT(ProcessRequest(QString))); + + cache_thread_->start(); + cache_thread_->setPriority(QThread::NormalPriority); + } + + ImageCache::~ImageCache() + { + // After setting our exit flag to true, release any conditions the cache thread + // might be waiting on so that it will exit. + exit_ = true; + cache_thread_->notify(); + network_request_semaphore_.release(MAXIMUM_NETWORK_REQUESTS); + cache_thread_->wait(); + delete cache_thread_; + } + + void ImageCache::Clear() + { + cache_.clear(); + network_manager_.cache()->clear(); + } + + ImagePtr ImageCache::GetImage(size_t uri_hash, const QString& uri, int32_t priority) + { + ImagePtr image; + + // Retrieve the image reference from the cache, updating the freshness. + cache_mutex_.lock(); + + if (failed_.contains(uri_hash)) + { + cache_mutex_.unlock(); + return image; + } + + ImagePtr* image_ptr = cache_.take(uri_hash); + if (!image_ptr) + { + // If the image is not in the cache, create a new reference. + image_ptr = new ImagePtr(std::make_shared(uri, uri_hash)); + image = *image_ptr; + if (!cache_.insert(uri_hash, image_ptr)) + { + RCLCPP_ERROR(logger_, "FAILED TO CREATE HANDLE: %s", uri.toStdString().c_str()); + image_ptr = nullptr; + } + } + else + { + image = *image_ptr; + + // Add raw pointer back to cache. + cache_.insert(uri_hash, image_ptr); + } + + cache_mutex_.unlock(); + + unprocessed_mutex_.lock(); + if (image && !image->GetImage()) + { + if (!image->Failed()) + { + if (!unprocessed_.contains(uri_hash)) + { + // Set an image's starting priority so that it's higher than the + // starting priority of every other image we've requested so + // far; that ensures that, all other things being equal, the + // most recently requested images will be loaded first. + image->SetPriority(priority + tick_++); + unprocessed_[uri_hash] = image; + uri_to_hash_map_[uri] = uri_hash; + cache_thread_->notify(); + } + else + { + // Every time an image is requested but hasn't been loaded yet, + // increase its priority. Tiles within the visible area will + // be requested more frequently, so this will make them load faster + // than tiles the user can't see. + image->SetPriority(priority + tick_++); + } + } + else + { + failed_.insert(uri_hash); + } + } + + unprocessed_mutex_.unlock(); + + return image; + } + + void ImageCache::SetLogger(rclcpp::Logger logger) + { + logger_ = logger; + } + + void ImageCache::ProcessRequest(QString uri) + { + QNetworkRequest request; + request.setUrl(QUrl(uri)); + request.setRawHeader("User-Agent", "mapviz-1.0"); + request.setAttribute( + QNetworkRequest::CacheLoadControlAttribute, + QNetworkRequest::PreferCache); + request.setAttribute( + QNetworkRequest::HttpPipeliningAllowedAttribute, + true); + + network_manager_.get(request); + } + + void ImageCache::ProcessReply(QNetworkReply* reply) + { + QString url = reply->url().toString(); + + ImagePtr image; + unprocessed_mutex_.lock(); + + size_t hash = uri_to_hash_map_[url]; + image = unprocessed_[hash]; + if (image) + { + if (reply->error() == QNetworkReply::NoError) + { + QByteArray data = reply->readAll(); + image->InitializeImage(); + if (!image->GetImage()->loadFromData(data)) + { + image->ClearImage(); + image->AddFailure(); + } + } + else + { + auto steady_clock = rclcpp::Clock(); + RCLCPP_ERROR_THROTTLE(logger_, steady_clock, 1.0, "NETWORK ERROR: %s", reply->errorString().toStdString().c_str()); + image->AddFailure(); + } + } + + unprocessed_.remove(hash); + uri_to_hash_map_.remove(url); + if (image) + { + image->SetLoading(false); + } + network_request_semaphore_.release(); + + unprocessed_mutex_.unlock(); + + reply->deleteLater(); + } + + const int CacheThread::MAXIMUM_SEQUENTIAL_REQUESTS = 12; + + CacheThread::CacheThread(ImageCache* parent) : + image_cache_(parent), + waiting_mutex_() + { + waiting_mutex_.lock(); + } + + void CacheThread::notify() + { + waiting_mutex_.unlock(); + } + + void CacheThread::run() + { + while (!image_cache_->exit_) + { + // Wait until we're told there are images we need to request. + waiting_mutex_.lock(); + + // Next, get all of them and sort them by priority. + image_cache_->unprocessed_mutex_.lock(); + QList images = image_cache_->unprocessed_.values(); + image_cache_->unprocessed_mutex_.unlock(); + + std::sort(images.begin(), images.end(), ComparePriority); + + // Go through all of them and request them. Qt's network manager will + // only handle six simultaneous requests at once, so we use a semaphore + // to limit ourselves to that many. + // Each individual image will release the semaphore when it is done loading. + // Also, only load up to a certain number at a time in this loop. If there + // are more left afterward, we'll start over. This ensures that we + // concentrate on processing the highest-priority images. + int count = 0; + while (!image_cache_->exit_ && !images.empty() && count < MAXIMUM_SEQUENTIAL_REQUESTS) + { + image_cache_->network_request_semaphore_.acquire(); + + ImagePtr image = images.front(); + image_cache_->unprocessed_mutex_.lock(); + if (!image->Loading() && !image->Failed()) + { + count++; + image->SetLoading(true); + images.pop_front(); + + QString uri = image->Uri(); + size_t hash = image_cache_->uri_to_hash_map_[uri]; + if (uri.startsWith(QString("file:///"))) + { + image->InitializeImage(); + QString filepath = uri.replace(QString("file:///"), QString("/")); + if (!image->GetImage()->load(filepath)) + { + image->ClearImage(); + image->AddFailure(); + } + + image_cache_->unprocessed_.remove(hash); + image_cache_->uri_to_hash_map_.remove(uri); + image->SetLoading(false); + image_cache_->network_request_semaphore_.release(); + } + else + { + Q_EMIT RequestImage(image->Uri()); + } + } + else + { + images.pop_front(); + } + image_cache_->unprocessed_mutex_.unlock(); + + } + if (!images.empty()) + { + waiting_mutex_.unlock(); + } + } + } +} diff --git a/tile_map/src/texture_cache.cpp b/tile_map/src/texture_cache.cpp new file mode 100644 index 000000000..8bb4fedeb --- /dev/null +++ b/tile_map/src/texture_cache.cpp @@ -0,0 +1,178 @@ +// ***************************************************************************** +// +// Copyright (c) 2014, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +#include + +#include + +#include +#include +#include + +#include + +#include +#include + +#include + +namespace tile_map +{ + Texture::Texture(int32_t texture_id, size_t hash) : + id(texture_id), + url_hash(hash) + { + } + + Texture::~Texture() + { + //ROS_ERROR("==== DELETING TEXTURE: %d ====", id); + // The texture will automatically be freed from the GPU memory when it goes + // out of scope. This is effectively when it is no longer in the texture + // cache or being referenced for a render. + GLuint ids[1]; + ids[0] = id; + glDeleteTextures(1, &ids[0]); + } + + TextureCache::TextureCache(ImageCachePtr image_cache, + size_t size, + rclcpp::Logger logger) : + cache_(size), + image_cache_(image_cache), + logger_(logger) + { + + } + + TexturePtr TextureCache::GetTexture(size_t url_hash, const QString& url, bool& failed, int priority) + { + TexturePtr texture; + + failed = false; + + TexturePtr* texture_ptr = cache_.take(url_hash); + if (texture_ptr) + { + texture = *texture_ptr; + delete texture_ptr; + } + + if (!texture) + { + ImagePtr image = image_cache_->GetImage(url_hash, url, priority); + + if (image) + { + failed = image->Failed(); + std::shared_ptr image_ptr = image->GetImage(); + if (image_ptr) + { + // All of the OpenGL calls need to occur on the main thread and so + // can't be done in the background. The QImage calls could + // potentially be done in a background thread by the image cache. + QImage qimage = *image_ptr; + + GLuint ids[1]; + uint32_t check = 9999999; + ids[0] = check; + + glGenTextures(1, &ids[0]); + + if (check == ids[0]) + { + RCLCPP_ERROR(logger_, "FAILED TO CREATE TEXTURE"); + + GLenum err = glGetError(); + const GLubyte *errString = gluErrorString(err); + RCLCPP_ERROR(logger_, "GL ERROR(%u): %s", err, errString); + return texture; + } + + texture_ptr = new TexturePtr(std::make_shared(ids[0], url_hash)); + texture = *texture_ptr; + + float max_dim = std::max(qimage.width(), qimage.height()); + int32_t dimension = swri_math_util::Round( + std::pow(2, std::ceil(std::log(max_dim) / std::log(2.0f)))); + + if (qimage.width() != dimension || qimage.height() != dimension) + { + qimage = qimage.scaled(dimension, dimension, Qt::IgnoreAspectRatio, Qt::FastTransformation); + } + + glBindTexture(GL_TEXTURE_2D, texture->id); + glTexImage2D( + GL_TEXTURE_2D, + 0, + GL_RGBA, + dimension, + dimension, + 0, + GL_RGBA, + GL_UNSIGNED_BYTE, + QGLWidget::convertToGLFormat(qimage).bits()); + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); + + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); + + cache_.insert(url_hash, texture_ptr); + } + } + } + + return texture; + } + + void TextureCache::AddTexture(const TexturePtr& texture) + { + if (texture) + { + TexturePtr* texture_ptr = new TexturePtr(texture); + cache_.insert(texture->url_hash, texture_ptr); + } + } + + void TextureCache::SetLogger(rclcpp::Logger logger) + { + logger_ = logger; + image_cache_->SetLogger(logger_); + } + + void TextureCache::Clear() + { + image_cache_->Clear(); + cache_.clear(); + } +} diff --git a/tile_map/src/tile_map_config.ui b/tile_map/src/tile_map_config.ui new file mode 100644 index 000000000..068e61d13 --- /dev/null +++ b/tile_map/src/tile_map_config.ui @@ -0,0 +1,198 @@ + + + tile_map_config + + + + 0 + 0 + 305 + 141 + + + + Form + + + + + + + 4 + + + 2 + + + + + + Sans Serif + 8 + + + + Base URL: + + + + + + + + Sans Serif + 8 + + + + Source: + + + + + + + + Sans Serif + 8 + + + + + + + Unconfigured + + + true + + + + + + + + Sans Serif + 8 + + + + Max Zoom: + + + + + + + Reset Cache + + + + + + + + 16777215 + 27 + + + + false + + + + Stamen (terrain) + + + + + Stamen (watercolor) + + + + + Stamen (toner) + + + + + Bing Maps (terrain) + + + + + Custom WMTS Source... + + + + + + + + false + + + http://tile.stamen.com/terrain/ + + + + + + + false + + + Delete + + + + + + + false + + + Save... + + + + + + + + Sans Serif + 8 + + + + Status: + + + + + + + false + + + + 0 + 0 + + + + + 50 + 16777215 + + + + 15 + + + + + + + + diff --git a/tile_map/src/tile_map_plugin.cpp b/tile_map/src/tile_map_plugin.cpp new file mode 100644 index 000000000..85991b143 --- /dev/null +++ b/tile_map/src/tile_map_plugin.cpp @@ -0,0 +1,469 @@ +// ***************************************************************************** +// +// Copyright (c) 2015-2020, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include +#include +#include +#include + +#include + +#include +#include +#include + +// QT libraries +#include +#include +#include +#include + +// ROS libraries +#include +#include + +#include + +// Declare plugin +#include +PLUGINLIB_EXPORT_CLASS(tile_map::TileMapPlugin, mapviz::MapvizPlugin) + +namespace tile_map +{ + std::string TileMapPlugin::BASE_URL_KEY = "base_url"; + std::string TileMapPlugin::BING_API_KEY = "bing_api_key"; + std::string TileMapPlugin::CUSTOM_SOURCES_KEY = "custom_sources"; + std::string TileMapPlugin::MAX_ZOOM_KEY = "max_zoom"; + std::string TileMapPlugin::NAME_KEY = "name"; + std::string TileMapPlugin::SOURCE_KEY = "source"; + std::string TileMapPlugin::TYPE_KEY = "type"; + QString TileMapPlugin::BING_NAME = "Bing Maps (terrain)"; + QString TileMapPlugin::STAMEN_TERRAIN_NAME = "Stamen (terrain)"; + QString TileMapPlugin::STAMEN_TONER_NAME = "Stamen (toner)"; + QString TileMapPlugin::STAMEN_WATERCOLOR_NAME = "Stamen (watercolor)"; + + TileMapPlugin::TileMapPlugin() + : MapvizPlugin() + , ui_() + , config_widget_(new QWidget()) + , transformed_(false) + , last_center_x_(0.0) + , last_center_y_(0.0) + , last_scale_(0.0) + , last_height_(0) + , last_width_(0) + { + ui_.setupUi(config_widget_); + + tile_sources_[STAMEN_TERRAIN_NAME] = + std::make_shared(STAMEN_TERRAIN_NAME, + "http://tile.stamen.com/terrain/{level}/{x}/{y}.png", + false, + 15); + tile_sources_[STAMEN_TONER_NAME] = + std::make_shared(STAMEN_TONER_NAME, + "http://tile.stamen.com/toner/{level}/{x}/{y}.png", + false, + 19); + tile_sources_[STAMEN_WATERCOLOR_NAME] = + std::make_shared(STAMEN_WATERCOLOR_NAME, + "http://tile.stamen.com/watercolor/{level}/{x}/{y}.jpg", + false, + 19); + std::shared_ptr bing = std::make_shared(BING_NAME); + tile_sources_[BING_NAME] = bing; + + QPalette p(config_widget_->palette()); + p.setColor(QPalette::Window, Qt::white); + config_widget_->setPalette(p); + + QPalette p2(ui_.status->palette()); + p2.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p2); + + source_frame_ = swri_transform_util::_wgs84_frame; + + QObject::connect(bing.get(), SIGNAL(ErrorMessage(const std::string&)), + this, SLOT(PrintError(const std::string&))); + QObject::connect(bing.get(), SIGNAL(InfoMessage(const std::string&)), + this, SLOT(PrintInfo(const std::string&))); + QObject::connect(ui_.delete_button, SIGNAL(clicked()), this, SLOT(DeleteTileSource())); + QObject::connect(ui_.source_combo, SIGNAL(activated(const QString&)), this, SLOT(SelectSource(const QString&))); + QObject::connect(ui_.save_button, SIGNAL(clicked()), this, SLOT(SaveCustomSource())); + QObject::connect(ui_.reset_cache_button, SIGNAL(clicked()), this, SLOT(ResetTileCache())); + } + + void TileMapPlugin::DeleteTileSource() + { + int source_index = ui_.source_combo->currentIndex(); + QString current_name = ui_.source_combo->currentText(); + + QMessageBox mbox; + mbox.setText("Are you sure you want to delete the source \"" + current_name + "\"?"); + mbox.setIcon(QMessageBox::Warning); + mbox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); + mbox.setDefaultButton(QMessageBox::Cancel); + int ret = mbox.exec(); + + if (ret == QMessageBox::Ok) + { + ui_.source_combo->removeItem(source_index); + tile_sources_.erase(current_name); + ui_.source_combo->setCurrentIndex(0); + SelectSource(ui_.source_combo->currentText()); + } + } + + void TileMapPlugin::SelectSource(const QString& source) + { + if (source == STAMEN_TERRAIN_NAME || + source == STAMEN_WATERCOLOR_NAME || + source == STAMEN_TONER_NAME || + source == BING_NAME) + { + stopCustomEditing(); + } + else + { + startCustomEditing(); + } + + std::map >::iterator iter = tile_sources_.find(source); + + // If the previously selected source was Bing, these will have been changed, so + // they should be changed back. There's not an easy way to know here what the + // previously selected item was, so just always change them. + ui_.url_label->setText("Base URL:"); + ui_.save_button->setText("Save..."); + if (iter != tile_sources_.end()) + { + selectTileSource(iter->second); + initialized_ = true; + // For the Bing map type, change a couple of the fields to have more appropriate + // labels. There should probably be a cleaner way to do this if we end up adding + // more tile source types.... + if (iter->second->GetType() == BingSource::BING_TYPE) + { + ui_.url_label->setText("API Key:"); + ui_.save_button->setText("Save"); + ui_.base_url_text->setEnabled(true); + ui_.save_button->setEnabled(true); + } + } + else + { + ui_.delete_button->setEnabled(false); + } + } + + void TileMapPlugin::SaveCustomSource() + { + // If the user is editing a custom source, we want to fill in the default + // name for it with its current name. + // Otherwise, they're creating a new custom source, in which case we + // should leave the default blank. + QString current_source = ui_.source_combo->currentText(); + QString default_name = ""; + + auto iter = tile_sources_.find(current_source); + if (iter != tile_sources_.end()) + { + if (iter->second->IsCustom()) + { + default_name = current_source; + } + else if (iter->second->GetType() == BingSource::BING_TYPE) + { + // If the user has picked Bing as they're source, we're not actually + // saving a custom map source, just updating the API key + BingSource* bing_source = dynamic_cast(iter->second.get()); + bing_source->SetApiKey(ui_.base_url_text->text()); + return; + } + } + + bool ok; + QString name = QInputDialog::getText(config_widget_, + tr("Save New Tile Source"), + tr("Tile Source Name:"), + QLineEdit::Normal, + default_name, + &ok); + name = name.trimmed(); + if (ok && !name.isEmpty()) + { + std::shared_ptr source = std::make_shared(name, + ui_.base_url_text->text(), + true, + ui_.max_zoom_spin_box->value()); + int existing_index = ui_.source_combo->findText(name); + if (existing_index != -1) + { + ui_.source_combo->removeItem(existing_index); + } + tile_sources_[name] = source; + ui_.source_combo->addItem(name); + int new_index = ui_.source_combo->findText(name); + ui_.source_combo->setCurrentIndex(new_index); + SelectSource(name); + } + } + + void TileMapPlugin::ResetTileCache() + { + tile_map_.ResetCache(); + } + + void TileMapPlugin::PrintError(const std::string& message) + { + if (message == ui_.status->text().toStdString()) + return; + + RCLCPP_ERROR(node_->get_logger(), "Error: %s", message.c_str()); + QPalette p(ui_.status->palette()); + p.setColor(QPalette::Text, Qt::red); + ui_.status->setPalette(p); + ui_.status->setText(message.c_str()); + } + + void TileMapPlugin::PrintInfo(const std::string& message) + { + if (message == ui_.status->text().toStdString()) + return; + + RCLCPP_INFO(node_->get_logger(), "%s", message.c_str()); + QPalette p(ui_.status->palette()); + p.setColor(QPalette::Text, Qt::green); + ui_.status->setPalette(p); + ui_.status->setText(message.c_str()); + } + + void TileMapPlugin::PrintWarning(const std::string& message) + { + if (message == ui_.status->text().toStdString()) + return; + + RCLCPP_WARN(node_->get_logger(), "%s", message.c_str()); + QPalette p(ui_.status->palette()); + p.setColor(QPalette::Text, Qt::darkYellow); + ui_.status->setPalette(p); + ui_.status->setText(message.c_str()); + } + + QWidget* TileMapPlugin::GetConfigWidget(QWidget* parent) + { + config_widget_->setParent(parent); + + return config_widget_; + } + + bool TileMapPlugin::Initialize(QGLWidget* canvas) + { + canvas_ = canvas; + + SelectSource(STAMEN_TERRAIN_NAME); + + return true; + } + + void TileMapPlugin::Draw(double x, double y, double scale) + { + if (!tile_map_.IsReady()) + { + return; + } + + swri_transform_util::Transform to_wgs84; + if (tf_manager_->GetTransform(source_frame_, target_frame_, to_wgs84)) + { + tf2::Vector3 center(x, y, 0); + center = to_wgs84 * center; + + if (center.y() != last_center_y_ || + center.x() != last_center_x_ || + scale != last_scale_ || + canvas_->width() != last_width_ || + canvas_->height() != last_height_) + { + // Draw() is called very frequently, and SetView is a fairly expensive operation, so we + // can save some CPU time by only calling it when the relevant parameters have changed. + last_center_y_ = center.y(); + last_center_x_ = center.x(); + last_scale_ = scale; + last_width_ = canvas_->width(); + last_height_ = canvas_->height(); + tile_map_.SetView(center.y(), center.x(), scale, canvas_->width(), canvas_->height()); + RCLCPP_DEBUG(node_->get_logger(), "TileMapPlugin::Draw: Successfully set view"); + } + tile_map_.Draw(); + } + } + + void TileMapPlugin::Transform() + { + swri_transform_util::Transform to_target; + if (tf_manager_->GetTransform(target_frame_, source_frame_, to_target)) + { + tile_map_.SetTransform(to_target); + PrintInfo("OK"); + } + else + { + PrintError("No transform between " + source_frame_ + " and " + target_frame_); + } + } + + void TileMapPlugin::LoadConfig(const YAML::Node& node, const std::string&) + { + if (node[CUSTOM_SOURCES_KEY]) + { + const YAML::Node& sources = node[CUSTOM_SOURCES_KEY]; + YAML::Node::const_iterator source_iter; + for (auto source_yaml : sources) + { + std::string type; + if (source_yaml[TYPE_KEY]) + { + // If the type isn't set, we'll assume it's WMTS + type = source_yaml[TYPE_KEY].as(); + } + std::shared_ptr source; + if (type == "wmts" || type.empty()) + { + std::string name; + std::string base_url; + int max_zoom; + name = source_yaml[NAME_KEY].as(); + base_url = source_yaml[BASE_URL_KEY].as(); + max_zoom = source_yaml[MAX_ZOOM_KEY].as(); + source = std::make_shared( + QString::fromStdString(name), + QString::fromStdString(base_url), + true, + max_zoom); + } + else if (type == "bing") + { + std::string name; + name = source_yaml[NAME_KEY].as(); + source = std::make_shared(QString::fromStdString(name)); + } + tile_sources_[source->GetName()] = source; + ui_.source_combo->addItem(source->GetName()); + } + } + + if (node[BING_API_KEY]) + { + std::string key = node[BING_API_KEY].as(); + BingSource* source = dynamic_cast(tile_sources_[BING_NAME].get()); + source->SetApiKey(QString::fromStdString(key)); + } + + if (node[SOURCE_KEY]) + { + std::string source = node[SOURCE_KEY].as(); + + int index = ui_.source_combo->findText(QString::fromStdString(source), Qt::MatchExactly); + + if (index >= 0) + { + ui_.source_combo->setCurrentIndex(index); + } + + SelectSource(QString::fromStdString(source)); + } + } + + void TileMapPlugin::SaveConfig(YAML::Emitter& emitter, const std::string&) + { + emitter << YAML::Key << CUSTOM_SOURCES_KEY << YAML::Value << YAML::BeginSeq; + + std::map >::iterator iter; + for (iter = tile_sources_.begin(); iter != tile_sources_.end(); iter++) + { + if (iter->second->IsCustom()) + { + emitter << YAML::BeginMap; + emitter << YAML::Key << BASE_URL_KEY << YAML::Value << iter->second->GetBaseUrl().toStdString(); + emitter << YAML::Key << MAX_ZOOM_KEY << YAML::Value << iter->second->GetMaxZoom(); + emitter << YAML::Key << NAME_KEY << YAML::Value << iter->second->GetName().toStdString(); + emitter << YAML::Key << TYPE_KEY << YAML::Value << iter->second->GetType().toStdString(); + emitter << YAML::EndMap; + } + } + emitter << YAML::EndSeq; + + BingSource* bing_source = dynamic_cast(tile_sources_[BING_NAME].get()); + emitter << YAML::Key << BING_API_KEY << + YAML::Value << boost::trim_copy(bing_source->GetApiKey().toStdString()); + + emitter << YAML::Key << SOURCE_KEY << + YAML::Value << boost::trim_copy(ui_.source_combo->currentText().toStdString()); + } + + void TileMapPlugin::selectTileSource(const std::shared_ptr& tile_source) + { + last_height_ = 0; // This will force us to recalculate our view + tile_map_.SetTileSource(tile_source); + if (tile_source->GetType() == BingSource::BING_TYPE) + { + BingSource* bing_source = dynamic_cast(tile_source.get()); + ui_.base_url_text->setText(bing_source->GetApiKey()); + } + else + { + ui_.base_url_text->setText(tile_source->GetBaseUrl()); + } + ui_.max_zoom_spin_box->setValue(tile_source->GetMaxZoom()); + } + + void TileMapPlugin::startCustomEditing() + { + ui_.base_url_text->setEnabled(true); + ui_.delete_button->setEnabled(true); + ui_.max_zoom_spin_box->setEnabled(true); + ui_.save_button->setEnabled(true); + } + + void TileMapPlugin::stopCustomEditing() + { + ui_.base_url_text->setEnabled(false); + ui_.delete_button->setEnabled(false); + ui_.max_zoom_spin_box->setEnabled(false); + ui_.save_button->setEnabled(false); + } + + void TileMapPlugin::SetNode(rclcpp::Node& node) + { + MapvizPlugin::SetNode(node); + tile_map_.SetLogger(node.get_logger()); + } +} + diff --git a/tile_map/src/tile_map_view.cpp b/tile_map/src/tile_map_view.cpp new file mode 100644 index 000000000..92d39191a --- /dev/null +++ b/tile_map/src/tile_map_view.cpp @@ -0,0 +1,325 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY +// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ***************************************************************************** + +#include + +#include + +#include + +#include +#include +#include + +#include + +#include +#include +#include + +#include + +namespace tile_map +{ + TileMapView::TileMapView(rclcpp::Logger logger) : + level_(-1), + width_(100), + height_(100), + logger_(logger) + { + ImageCachePtr image_cache = std::make_shared("/tmp/tile_map", 4096, logger); + tile_cache_ = std::make_shared(image_cache, 512, logger); + } + + bool TileMapView::IsReady() + { + return tile_source_ && tile_source_->IsReady(); + } + + void TileMapView::ResetCache() + { + tile_cache_->Clear(); + } + + void TileMapView::SetLogger(rclcpp::Logger logger) + { + logger_ = logger; + tile_cache_->SetLogger(logger_); + } + + void TileMapView::SetTileSource(const std::shared_ptr& tile_source) + { + tile_source_ = tile_source; + level_ = -1; + } + + void TileMapView::SetTransform(const swri_transform_util::Transform& transform) + { + if (transform.GetOrigin() == transform_.GetOrigin() && + transform.GetOrientation() == transform_.GetOrientation()) + { + return; + } + + transform_ = transform; + + for (auto & tile : tiles_) + { + for (size_t j = 0; j < tile.points_t.size(); j++) + { + tile.points_t[j] = transform_ * tile.points[j]; + } + } + + for (auto & i : precache_) + { + for (size_t j = 0; j < i.points_t.size(); j++) + { + i.points_t[j] = transform_ * i.points[j]; + } + } + } + + void TileMapView::SetView( + double latitude, + double longitude, + double scale, + int32_t width, + int32_t height) + { + latitude = std::max(-90.0, std::min(90.0, latitude)); + longitude = std::max(-180.0, std::min(180.0, longitude)); + + double lat = swri_math_util::ToRadians(latitude); + + // Calculate the current zoom level: + // + // According to http://wiki.openstreetmap.org/wiki/Zoom_levels: + // meters_per_pixel = earth_circumference * cos(lat) / 2^(level + 8) + // + // Therefore, + // level = log2(earth_circumference * cos(lat) / meters_per_pixel) - 8 + // + double lat_circumference = + swri_transform_util::_earth_equator_circumference * std::cos(lat) / scale; + int32_t level = std::min(tile_source_->GetMaxZoom(), + std::max(tile_source_->GetMinZoom(), static_cast(std::ceil(std::log(lat_circumference) / std::log(2) - 8)))); + int64_t max_size = std::pow(2, level); + + int64_t center_x = std::min(max_size - 1, static_cast( + std::floor(((longitude + 180.0) / 360.0) * std::pow(2.0, level)))); + int64_t center_y = std::min(max_size - 1, static_cast( + std::floor((1.0 - std::log(std::tan(lat) + 1.0 / std::cos(lat)) / swri_math_util::_pi) / 2.0 * std::pow(2.0, level)))); + + width_ = width; + height_ = height; + + double max_dimension = std::max(width, height); + + double meters_per_pixel = swri_transform_util::_earth_equator_circumference * std::cos(lat) / std::pow(2, level + 8); + double tile_size = 256.0 * (meters_per_pixel / scale); + + int64_t size = std::max(static_cast(1L), std::min(max_size, static_cast( + std::ceil(0.5 * max_dimension / tile_size) * 2 + 1))); + + if (size > 50) + { + RCLCPP_ERROR(logger_, "Invalid map size: %ld", size); + return; + } + + if (size_ != size || level_ != level || center_x_ != center_x || center_y_ != center_y) + { + size_ = size; + level_ = level; + center_x_ = center_x; + center_y_ = center_y; + + int64_t top = std::max(static_cast(0L), center_y_ - size_ / 2); + int64_t left = std::max(static_cast(0L), center_x_ - size_ / 2); + + int64_t right = std::min(max_size, left + size_); + int64_t bottom = std::min(max_size, top + size_); + + for (auto & tile : tiles_) + { + tile_cache_->AddTexture(tile.texture); + } + tiles_.clear(); + + for (int64_t i = top; i < bottom; i++) + { + for (int64_t j = left; j < right; j++) + { + Tile tile; + InitializeTile(level_, j, i, tile, 10000); + tiles_.push_back(tile); + } + } + + for (auto & i : precache_) + { + tile_cache_->AddTexture(i.texture); + } + precache_.clear(); + + if (level_ > 0) + { + int64_t precache_x = std::floor(((longitude + 180.0) / 360.0) * std::pow(2.0, level - 1)); + int64_t precache_y = std::floor((1.0 - std::log(std::tan(lat) + 1.0 / std::cos(lat)) / swri_math_util::_pi) / 2.0 * std::pow(2.0, level - 1)); + + int64_t precache_max_size = std::pow(2, level - 1); + + int64_t precache_top = std::max(static_cast(0L), precache_y - (size_ - 1) / 2); + int64_t precache_left = std::max(static_cast(0L), precache_x - (size_ - 1) / 2); + + int64_t precache_right = std::min(precache_max_size, precache_left + size_); + int64_t precache_bottom = std::min(precache_max_size, precache_top + size_); + + for (int64_t i = precache_top; i < precache_bottom; i++) + { + for (int64_t j = precache_left; j < precache_right; j++) + { + Tile tile; + InitializeTile(level_ - 1, j, i, tile, 0); + precache_.push_back(tile); + } + } + } + } + } + + void TileMapView::DrawTiles(std::vector& tiles, int priority) + { + for (auto & tile : tiles) + { + TexturePtr& texture = tile.texture; + + if (!texture) + { + bool failed; + texture = tile_cache_->GetTexture(tile.url_hash, tile.url, failed, priority); + } + + if (texture) + { + glBindTexture(GL_TEXTURE_2D, texture->id); + + glBegin(GL_TRIANGLES); + + glColor4f(1.0f, 1.0f, 1.0f, 1.0f); + + for (int32_t row = 0; row < tile.subdiv_count; row++) + { + for (int32_t col = 0; col < tile.subdiv_count; col++) + { + double u_0 = col * tile.subwidth; + double v_0 = 1.0 - row * tile.subwidth; + double u_1 = (col + 1.0) * tile.subwidth; + double v_1 = 1.0 - (row + 1.0) * tile.subwidth; + + const tf2::Vector3& tl = tile.points_t[row * (tile.subdiv_count + 1) + col]; + const tf2::Vector3& tr = tile.points_t[row * (tile.subdiv_count + 1) + col + 1]; + const tf2::Vector3& br = tile.points_t[(row + 1) * (tile.subdiv_count + 1) + col + 1]; + const tf2::Vector3& bl = tile.points_t[(row + 1) * (tile.subdiv_count + 1) + col]; + + // Triangle 1 + glTexCoord2f(u_0, v_0); glVertex2d(tl.x(), tl.y()); + glTexCoord2f(u_1, v_0); glVertex2d(tr.x(), tr.y()); + glTexCoord2f(u_1, v_1); glVertex2d(br.x(), br.y()); + + // Triangle 2 + glTexCoord2f(u_0, v_0); glVertex2d(tl.x(), tl.y()); + glTexCoord2f(u_1, v_1); glVertex2d(br.x(), br.y()); + glTexCoord2f(u_0, v_1); glVertex2d(bl.x(), bl.y()); + } + } + + glEnd(); + + glBindTexture(GL_TEXTURE_2D, 0); + } + } + } + + void TileMapView::Draw() + { + if (!tile_source_) + { + return; + } + + glEnable(GL_TEXTURE_2D); + + DrawTiles( precache_, 0 ); + DrawTiles( tiles_, 10000 ); + + glDisable(GL_TEXTURE_2D); + } + + void TileMapView::ToLatLon(int32_t level, double x, double y, double& latitude, double& longitude) + { + double n = std::pow(2, level); + longitude = x / n * 360.0 - 180.0; + + double r = swri_math_util::_pi - swri_math_util::_2pi * y / n; + latitude = swri_math_util::_rad_2_deg * std::atan(0.5 * (std::exp(r) - std::exp(-r))); + } + + void TileMapView::InitializeTile(int32_t level, int64_t x, int64_t y, Tile& tile, int priority) + { + tile.url = tile_source_->GenerateTileUrl(level, x, y); + + tile.url_hash = tile_source_->GenerateTileHash(level, x, y); + + tile.level = level; + + bool failed; + tile.texture = tile_cache_->GetTexture(tile.url_hash, tile.url, failed, priority); + + int32_t subdivs = std::max(0, 4 - level); + tile.subwidth = 1.0 / (subdivs + 1.0); + tile.subdiv_count = std::pow(2, subdivs); + for (int32_t row = 0; row <= tile.subdiv_count; row++) + { + for (int32_t col = 0; col <= tile.subdiv_count; col++) + { + double t_lat, t_lon; + ToLatLon(level, x + col * tile.subwidth, y + row * tile.subwidth, t_lat, t_lon); + tile.points.emplace_back(tf2::Vector3(t_lon, t_lat, 0)); + } + } + + tile.points_t = tile.points; + for (auto & i : tile.points_t) + { + i = transform_ * i; + } + } +} diff --git a/tile_map/src/tile_source.cpp b/tile_map/src/tile_source.cpp new file mode 100644 index 000000000..383186aa0 --- /dev/null +++ b/tile_map/src/tile_source.cpp @@ -0,0 +1,84 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#include + +namespace tile_map +{ + const QString& TileSource::GetBaseUrl() const + { + return base_url_; + } + + void TileSource::SetBaseUrl(const QString& base_url) + { + base_url_ = base_url; + } + + bool TileSource::IsCustom() const + { + return is_custom_; + } + + void TileSource::SetCustom(bool is_custom) + { + is_custom_ = is_custom; + } + + int32_t TileSource::GetMaxZoom() const + { + return max_zoom_; + } + + void TileSource::SetMaxZoom(int32_t max_zoom) + { + max_zoom_ = max_zoom; + } + + int32_t TileSource::GetMinZoom() const + { + return min_zoom_; + } + + void TileSource::SetMinZoom(int32_t min_zoom) + { + min_zoom_ = min_zoom; + } + + const QString& TileSource::GetName() const + { + return name_; + } + + void TileSource::SetName(const QString& name) + { + name_ = name; + } +} diff --git a/tile_map/src/wmts_source.cpp b/tile_map/src/wmts_source.cpp new file mode 100644 index 000000000..b056825aa --- /dev/null +++ b/tile_map/src/wmts_source.cpp @@ -0,0 +1,71 @@ +// ***************************************************************************** +// +// Copyright (c) 2015, Southwest Research Institute® (SwRI®) +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// * Neither the name of Southwest Research Institute® (SwRI®) nor the +// names of its contributors may be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL Southwest Research Institute® BE LIABLE +// FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +// DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +// SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY +// OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH +// DAMAGE. +// +// ***************************************************************************** + +#include + +#include + +namespace tile_map +{ + const QString WmtsSource::WMTS_TYPE = "wmts"; + + WmtsSource::WmtsSource(const QString& name, + const QString& base_url, + bool is_custom, + int32_t max_zoom) : + TileSource() + { + name_ = name; + base_url_ = base_url; + is_custom_ = is_custom; + max_zoom_ = max_zoom; + min_zoom_ = 1; + } + + QString WmtsSource::GetType() const + { + return WMTS_TYPE; + } + + size_t WmtsSource::GenerateTileHash(int32_t level, int64_t x, int64_t y) + { + return hash_(GenerateTileUrl(level, x, y).toStdString()); + } + + QString WmtsSource::GenerateTileUrl(int32_t level, int64_t x, int64_t y) + { + QString url(base_url_); + url.replace(QString::fromStdString("{level}"), QString::number(level)); + url.replace(QString::fromStdString("{x}"), QString::number(x)); + url.replace(QString::fromStdString("{y}"), QString::number(y)); + + return url; + } +}

      2?st_tF)s;G0%!PyxP~IRAzNs zGi{cOnwbzcM0YWAea(29eS_ie1ZS8nT>9GQhtqSq@B!ItwiU6C_`Ke&e3+4e zJFHYbp3Id?mZj|k)e`G2jHKi?!mCsnR$fn2jyw$3g6y#)C!s6vm5}_(YI!kNZ-Wl~ zN3w3D+|x74Q`DS;pH26Ro%c)hS07BE0oQhgn-n=GH(w_oLMh?;DC@depcDyply!{= zYRp4nhFJO01BWh!w)33w)yyM(CaI^lfF6mFujVbza^gmf(u&8|H*ivnUf&}%uXbjX zt0NfBb+V8)w5kC#+Oug(B#3|votjRA&jSf2MFr?*`(5wmLTVmg)HMAGNVXopLs{oA z7vhNl|EJF*rW^q)=t(A3qE3MIY?7&dX4S+l(0NbTj3luCm6d+_Ggr0qyra7}qIzj^ zbMW-_mA>2CslUBqszTCcJ~!XJ1Fn`5qLuycuMZ$RMwCddw1gbEi3nOLEaeF>b`2es z<$8yf1V^LNbi7R7al|wRs_IpHXGoJsV2(B2?D~DeVP3WHZHaQH&#)>(_W@3+&F^j| zynea-F?=L0EMw`qL=TUDW@lk6pc1df z66FO+gGjlaKff#dgM~Y_)NtZZ=zv7*0)0rZa zl(ZbY0O?yM#G3f9b|gk3&pg(qhNXp~5yPFZ2kI2F*REX;(@@7&K|5(4O1q)Z8*9^H@k-sarqa10-M9>x(`Xe`@5~# zpJZ3O%>-}$*%j6JSa5&|%rvI>CI+Q=SjAG(h$_Grskq(*M+4dYfGR?0>r$&kS}x?h z39GJ{%?QqEjKvD+&7HCddendmjMhSM1mTUN+l|s8&R5x+6tV8L%T3N^<5L0vb~oRg z(!RR}LT24Wg%sXK>`?Yk(}^Iea6C%9)Tcuh<&M3*41pIbeF~(*vER3ClfTr&w}gWj z8K-?x_R1}3nC`d-{+=xa?2KKFl)&TB08~j~2mjSEpmL{1lK zYU+fbLV>dKv=qUg$vyZyCj?Lc5Qx~U;D5+rIDjbp2Za=uMy6zDC?;#Dxi@%`mzWw8 zQIV{`{`*?314;Glw}+#Hx%cny3&LJHtj{^mb0J=bW2S~zGy4awxl~xnI5N|dEF&Kj z0@0x7TnNco0-_U-s|l;5Qi3MNp^?PLl%UZu!_uI1Fb+vgQq&R+ckbzX+j<(B+0A!> zgb*sNt=Z-jU0m!4+mU7m#WCUu)!O>N?-+V*U{hHVYR317S4&s$@O zx>?{$6%c805$b>_bpck(*R`%D7=0-esj{K4T9WTRJ7quyfp0*mo4FoxEeE;HiKzwQxSQd(#B z){l4N<|IS#Qp+~NPv!0!I>{8m>#a$~^vgF%KpGO6!-OuZ={TOyvFQ>9P8bh+yYzIM zQ|2fxpW<8DY01B9%ky-x>Pr9?GKTzegJECzH*Yfr<^=N+=} z{w5@nXpu^kfy2VYQkS6A;ITqvY$2p9A;=7naQ`&t?~NNiEvAYfZaf_T1zJ-m+h0Rnm7R%)d zpzc`QLdK`LVE;;i{b|4;fM&rP>*28q!yAKwR7W^#ExY$t$fS~4t>I&_@}3|LLBv?q zIpiSFy^BlIO!rm~S736SnYIcYo#KSv<+K8$b^|^?&OUwlV5ZXI{5c40lwu?cw` z01mG~WPna(8g|#6BOmjo@H#RsSj%0<*NbBbZ*G*xsFhHL=(()w;Uf7w<1%~-7qB%Q zev&}P0^7Dx8?D)cm!126E(kUI7{`|cp1%u+*ku%cyN!BXci0rC6@w|H2zpJjIY;O_ z+$yxt{Dgpp<>5X8q^40{JkXKPiYm_qjblPe?~U=((e9P|;Pq>|lNskMRm zsZYG69N&N=q&aer51ql0tr)5Y+$Avpq%tdVZ>P1J!Fx5lij21f`F8!Q9pTrLXj3r* zA0RgP#`kS4$Nc{D3jctPt9)Gn18610dYqN!67&lCx9C!Jaqv3i zY&82Eg_DD14Go$Nc=UiAH-E^GCp0#<>s$zu`EV=@l0M1hg|mTA0M+2rGP5>j+C^e? z)HV3Ly&KMww-L=untMO^8Hol21cbPJG~V&*mre8K&cKntj5D#&S4UUtP9+?#G`jpP z8Pqdt1Baqh;w-Sai#A|*({EsG2;&Gc%=}yY_uPJyAlNvPet1$U7MS~F<$*gY zdaYhgMqJnwH}$ixuaa{xJ83V4TS@eEUm%;<$@p2^`P))S`L6!0v;;H+(I#sGRmLXwmG@pL$rB z5F;t3Sc~1qIcE=+`Bj`y@^gmmWt-8p?@Kvb^J%6*%Yv1BRgQslMog99$qHMKhgueW z!}idEj!z#1BDnZHy5 z>d?uPtnx}UY!1tVBjyi3 zZEuxKbwwKPiZ0cHg-l6Nbtm2RP*t7heYZUA-_6b!whXKMJ;UkVoC)d>1{+dS%yq^~ zW=;NamGu4F9h#xo4iRn8RmmrJqA=3$^IR)2M2YYsC9t7ZTx%)xy-i$uzJY{gq1F|+ z$R^9^>p>?&(WJ$5&?i%Q7XA#l?uBTwK@b=v^vQqvO~`Y?5)}vr$DUXsBFaiYhM)I@ z5UB)Ya0B^Q2P#XFYw1LMMkSVp9xXSv)uw^Zj)nheU+~ST<|GAygjt*K&gGrrW+7me z&CHi=;63a0;x6MQX6C}K@_0y(gUCjdXXQUEEz|eEgb*+k#Hhmn{Htd`1II=FBjyLE ztUA=Gs$;S_Ys3SGV-Uy2JLr6i^CESKtXs(c0p)!fNBrsJrAOE$DJItcW7c^?fjF;=1EC%)=xPd-U4B1{j15~ord~wR=hymhPDDpTE@oi?Rl#&067FM zamQmEIlDw9$8&t>4ZX|^E>lrnp)I+ZtDAt3rS0IY!Q#v6^Ds#=oO~to0@%X{J5ZlDA+ZVFWl=*goGrc%qKVO^LI`KXvJ|)r~I93e2RxZRGBg{ z1IKV{oO{nMcbY>Ua~cM3}GQC0qN(mPLSI&}f<0iRPfS!!wCmeMuMjOl*CI zP0MDVeNN}gw-j>(HM9pG@1!lGfIS_7$M|f5Kc$9ZBC+Mc>NVf_mW{!1%UvdOXp7sr zRCpMw%ZJbZ&is@D0zS?LmdAn�PHLKfaBj$oW(c;_D$s*5hUKjgC4dagReIh6(_s zk%!?axf_f4b;H!tAX5BoLfanPa7A^ebUL0BZYpXfm?HL`n_7pjgsrA3+gC%n!MlO} z4(Gqe4I@l`ok&I3_1OmZ_*{LeFxJ1dh{YLoQuc9u*;)$_&lg)~G^$ee(=GiG=ug-~ zo2XhG{KUL=N?`7a_jOO5dnk{uO;X|^Cea=6r}tCG*ICuGa*S}YGCS9fno-Ym&Vow_L09+ z61O!j{u{O)INSZ*fbsD!#5m^jkp9g@j#~epx`dGq!)bUT?=rl$lb6rEkoZvP|Mq;0 zv^KIJ2UY+?GoBUes2BZ3!sG`pV@vFv|K0)OxbFGoLq^H0x7Z*L@48i2)T`siu*=@l zC!5-*g@6!F<6ezSUJDCPWqobP3^S^DBh|*k()F}9VNO$SsR*V3SBhgaHh%n@g*LjX zh6|aa8WIjv8DVTGn)cF_t1vIO3K>&qF0KlJ#Db-uqg##i){}Q*KtHCJ zKH8hQ5uwRz{hF_&brFW;)@ZIp&N|x)OM?{19M^;lRf7@^oyF?X%*&{;A#6$#4N>|` z0_Y1fO35k@qblie0N<7|vb9#Eww~gmZ_s9~vgXSZ*x_@P^XI1*!#Dsn1L1kLbG^t1 zy{_up!}@yl0QNeIHZofszQ@T?T~!0db)v2k1IqzXja_^x^sJP;8S)^s0hIY5gIk^j z<)4-8SU^UA`E|5XXFJP!lY!V9@!z@5BvTeG)ha+L?hl*2_%F)Dy}F}Xsd=*<1RFm1 z84-;R3yCZ2z4PLCf!{|W^F~7NjSaTBmK&U(H3*XZ-^8rX@1o3&jQwt{d!L~nKBbAU z6g)2+{I*-6oxJVm?Q6Wx(0tZh=QVK|&jwz{)gP;zAR^_a+GS1gs z%R4q1KAp>#`|6XCGH2qC&K^SBfA`?%o^fyfeQR>el)~f%Bj-u*Z)5f2{+0{N_Qz81 z`?uc;dTfyQHo|w}Zz;NXd0akM@BYP`4<26baBF1oKHu2!yT-U?>(?r1NcOWVeDV%@ zkrmN03OI~o|2w=cAntZFsbkuaApTLZdG)dy{Mr#dZ%H|+AXtvPYl$r-uTkhRE~ueW z9t&DY;{*&&11%D%$}_QnOrhW!XsU85hd^w20A!mM|6fx89_IY71EJBD!d2Cvf##xY zVoFfhL(=-y=A=>_c#1npUt2fGT(EyvjYRJJcJr}WvSq@PFM3y3ZSuUn$1&=^;IrDH zw4b0Wn#!G`f9Lb(SYA&L778RVS_+QL{XQ6PVTAcv(7Ml}*CZd0IpJk_rC@2xM`iQ; zDYXC7ees&_RcHM`xzgUSGg*I-$0JG7h9VD~W6q_c038mWM60PyWz|N9kRiv@ zAirf zA!WBHq%-h?B#-U3m3?GsVCjMHsK*C{J80l4*j4N?UhpkBMwqBZ93*p$Oy(!lPmaPlXOh+ zM}x&Vxab_Dqo)s^$0jFd%UZSx9_;ehQcDl#R@x*b9Rc4C*Hf~EuQM~7913EqNX=GC zI%;*fMZEe&g5p-#R(A#6>F*J}DOAtab_cabq2RdU8X3-Sq865yX3ht$$zNGjoOvDC zS54p9Z<8F{G}!A952ngX@Zg?F3t=pwa3iVUlbmYm{F@PtV@Cb*km8xDay2onWwX+i z=}?_2?>7})Qz_w8c7r+3vg#_h9d@_G-Q~pP?@cNTn7_V#Y6-sj{Wh@YI`xIxrG(7n zjdkD&8gp1~r~l)jWbtB4j1<^;ro_f)?HcU)4(D^al>Su#AS!g=-7j8?&a~$H9BAM& z;CF61;PJPi`>|=k3b2>vk#Hkasn*aRNHriL8z@Os0`+Ag;AmUP> zs8h&Y6AoM#~U`DjLks0l$7(dGkjT9ojlx z+qXq%leNF_qdNx|bU5Q~wGn>37k??(I;pJK8UZG3=Qk$L+MtUde;bmQHd}y%%711E zx7Nd(W9azw(6hv%MT_*-vMYnum_>B2X(9!c%hC9BB8mvj$?Mg z3Pv>3wK8EIt&2$*tsk6UR@gk)y}jCBe5JctNCxMAXHca;i-)1_u|EzH{HB5)@$H24 z=&40Tvgrs{U3O%5;vVH`U5lgJ?v>C9-swOFnb$!yL37#KZ|`~RkUxats#i=I0mZ5=k*av zVuLg#CM3H{<11{5+HPOSM9MaYs)L9)Macb6f)Iz`kC6%l@zWttwsYX2();A6QPk5R zlEhZ>kaj}K%(dv>>QHRG6 zR}iLx4z(Phd6p`js%3={lFxt%Ug=}#LBiL?G5AM{UKx`Cjk8R`egb*P`q1_E3_02cPu|h zC^HhOp#g=escIlF8Ch0)T&hw`A4WHB12l{Ll5Nt#CFZrA_O_s8}3+95W>N{9wm$&u0mROBizqSiyWa6 zK?fvSLQD>FWjeDcB8!-2j~}ysk`_&I@w#t?es^ok@MCEU4A>UAI~y;544d98`8U## zFDDP%3EunrT%FcDm#s{Q<>X5lSYi(vI%nN1xT5j&GGkNabz(6?srd@i;X~Op;*lpZ z*=nePOXOLvr9B^?CjLJE3L)TY{M3`u&E|idm%(wY@B9OxFHr$qm@ePo{mCk=oxoL0 zXuZGP&o6P2#_4kwjb&sRw-$mhp-sn{;dX#=`w@=Xfi3&`duc;^e$1F>LCz7EQgF>o^EU%+O%+qx;yq zYNbSB65#bkYh?jcG{`LXQXGWGnU3<4C!1!=Notd3sQM+!WoD8Z6AY>0d%a#aY+|pC z*YydoeV^?{R9GL1@8cjF;U9If&ioV(FbYL7AKFP1>-U*aw?#sI0wAy}5 zd^LKH5p}i=xnuXIcojwopHd4xl8D0LPC$GQ|8J@q{lDcx1C}|!ZJWpv6D`erH#0X; z2D14D!2PsjPz1>%B15LKkckt-EhGUFs)9IyBp?GRP;BU=0;rxEO9Nj=MjHjc|} z)gW#>h0R1xi{0ddAfsUC5qXRolFsygCqjSZxInj0=4P9ST}H`7SxWtvDSDnk=^|U+ z=_slzzB%Y8r~As|$bCljmLmEL{!UOue(*^PVHnQ_1Aj?tothh|wlKG&bWI9q z4XuMwm6b!*P$f#Gqygz|MMKlagvIgr(8EShE>Zj8xYGXIYj&}3huEsaIhjk*$Rc4( z?DQ>R8WqHv+m4?Jf=$CrlTk;KUu_3NL$xQ*^I5I_4Wy-k7Gv>0Eq46yYU{f=-D$Tq zsrT^)A1)F~Th)6-v%H5hO;b~Spw z*YtmE-58`a_Q4;Qga;y)!7{F|jo4gAUkub{yfjMT*WA|dc?c-4`s~jH-T`5r)+8T) zuas`jtV_!)(eBot+;Zv7Z33%T)n&&f%`m}!eImefNP7~iAPHkX4TYE#YEG+R0ZS{V zFR4FdH+Xc?68XhyUO?B{Twi^MeBJlchLbdQskj0?!PVMv|3itSo4em}M8xBOQ$fnu z-nzqwpBp5O_{c0S=YH=Yo9)cCDd&taVl{Z~J_bO!9Ikmx%8NvzH5w*3~T@Z?++(HH2OOzG7n;0KFI~g zg8^c)plnoV`FO_4-ao){mhX#}q!l`cgxc+RWRAsGB?fU6AHNqK2b@PFgC9<_a)Mdi z*7#DP1LR0^tU@^m{(#Bn%c#;|b3>)$d9e+F$;OCOXjZ`Z=x;BEyD zW&<%^ft%XELvWjclQ=ROiKS+4!g#qjW(KQF3(nXgX@AglkJ9>#zgayBT9y#$-a5PK z$Gt0u-j$9nu`R(k{4#W{TonK_3tuLQI3f`W}vv*<4pTy^3W-#|=Q5P!iBOHnLQ0KsHJyP$rX< zR)zWW46uyhZ#(OV@z#s%V0z>G{>AVV1l}GfBm+7Q%sz~S2mB!f3|aobva!-)Be6$z zYZevn_Bq>}z${-k-%5}5-w`tSVvS?_a@VsX?&iK_`esd3l;HSQ zZ(5&DZt2Wi{)O4^SF}A%lQXZb{zL_ry(G#((C;`Yi+!Pzgi01t4I@~xR0^9sg_+Ea z%1Y8N?BmkTVV{$^>4&TVZp9zf% zd<~rs?$;L%^rp{DnJ~rTxxs%_3j6m15hLiom%PP*>V}<rQ_*n)`;0 z1OVz!)Ki5;dxh~m#MG&o)Qr#k3b|$PJRFC;qS+9vGkF#@U|p)MhBtlMt2Euoy(SHM zOnDBtERuF5*Qgpisaf~$kr3&h|{i7{1oxwpKoEf*%r?n=H6bmBwhM@To?ewvag zw#KZUnoMG^_unCF@ZXu}zMxx*V*+t4Cl|Gp z@-P`gp8scER01C59yZwwcIgV;Y3UGqO9`hI@K~mRvXg!XYZGB zJ8KsDVx%VtK%y0cs&UKP>NTwc<{}eETa{{W&M(8ezE0bzfb9A>?}t7N+r_GbR_@yu*)5n z=f1P=t#6IMc_au+AuZcp6QzB~+fhH86hS_|Loxy139}7xJ><^k0}-0XPGiuim(neK zHQk9dyIrqJK3N{!$Nk5e?e=u<+uO>u`?ct?=Rd2m)8mR7c{}VD!F3~Lq1p&_i`GV! zDVpG6ej`NgEM34stB*W0C4Qz+Cy!^q#4ZO$)lzyw)0xL`;_4I5kf8@gm$7hEZjcqghYQmTwt%J3@~xb83*G7{RE* z5!dIOGS(O0lZ8X}_p^yP+vB#$+vHn9^zXVyz>HI}pwOf1j);H}p0&R2 zikEwfH6+5%c~s-Q3>7p1IHoN1ERbB7r7Pi2A)X$8`zHzrNfPwGvt_ruZjKBrU*Nx- zkATitYJaqWXwA?wYh>r)b;$H8pr^4Ml_q}1C>RUM6`5=oTz3VdUp95SH}(fNYHi6o zt!7SFJJiWhxYL)w8pMutkgE~G7{FU`*-=T$$9gpDYMNQcLY31ee^~%i+Wl>4j@A+J zNQXGU@gUs$GR^vLdF8(6ER=9Zj*V(Xn^F-yodq*>LPp2u$2Hq?97V2t?g>Q@rc#OD zJnFN$gD_t!9a?Uco|k7%SorxyThj{ob1W(_{zTcLUWO7MUPAql0iTsJAU_Tkc^uZ2 zMWPH&JOR-P9&X`5cy|S3oD~=2wc@tXwk~O7zfTkrP>Ge+o}3yCwLl3BgpQ&fWpYy% z2|7+1@Q7n!DP+10NGsGN>snkTUWT@UWSg0wSM}i}dDtgg8pZ4c*!&~fU z50tm;N|oJm+()Z-dFex=N0J#9dVYKJ_K7$%m)rQsMTpV3@Z-g|H%~aL9=%%$F8q6K zyLlW5HBEjZ-UH)LSg1Ed4cz*0IOPTWRL|jIbB5y|*&s%Rat%LSrSs<8P;6N)Jaw6x zpb}PEhiXcdpK#L-V>2_q2IxD*m8$|8ecC=8K18ajcV0G1RwuF~dygokxHz1N%G$6S z5(;6Ve$>Q9O8+)ixt!dUwoU%{{TdQ@_&lJJ<1-eyHcE2?a@G}U`gajWP$Kv~eenHb z$k?wdvWY(EFaNgfj)4>nE zMlv5c-)g#_KNFU8e%tY9cNR45{n~rYjmePsec2A^Rhr6Bp`iUE!hP?SVeMyu#f|#) z$#A0gcF)Zc^TyYWHgu60qtkB%H;Z>EA$?n?sJ|Y$5sP};`C{omkJA`zB-R8lbPmR@^X$SxWjs*dG8=bM=Nm}j_ zk)eX-s;P`rUnq$wWf2=>Q#ecAKa+Xz%r;w)0S!=MVdWJil_e_Zn&W231iz znYVqr+IIAjlSyg@!2_=UyGxZr!Rc6k#V+U6$%nsLx+ghyaSHs_9XPkRnGsnlaTxTQ zP?Mm0Hl{&oVw1~9Erl9NAuV&%dwmxA6XP$z0^CnjQ`I&uu>GyBH3R;LTpIm)?Z-I3 zpbvDf(o;_xNc`Ve91Fdc3QEJyKXq$pU<#IVZJnK;hft|)QR@;jXq(H6e&Z$M-2oK?5s zz>8w{qnMmL#nX4+U$&iM{ek;$Imzcz`kw!<1+W@=6n16kokz@9lrtKezSLwQqnLa!Y^O;G^HbQZ#g0 z$xlWVPFW7Q^+SxEkZu^lm#2y(6bU!5#l#A&Z$`!x1nLU`)<)FlsbjsU<(_8Q22 z9ukRL!vrIc!w@*UDH+Mcv=>AT;nJ6a{-JQf>No`{lRlra(zSX&T4MUxTnF0v-}K2B zZGR2y^LSn8yE~4@gu>5q=PAdHf+ob^F zvv8v@@_VxhKS2VYHZHs$TrLiYh4jyrX(lVa{ivat^#{rDG1b;+Aepu4-b4!}B#ae~ zJ=?tOs)47()%-H8YpVlMBc6JSTj`4dhPPL~Exg!JKpLriRAO8SCE146w~>NvP2 zFg$Li0^Wq8mEvNJdb0EMNjpG^sK|;=p@}O8_kEkx8L_9mqkZ+)=d<_{^7Y?l2rXTY@8Ld+>alX(etCgm7#9>b+~=}!4m9D6 zyij5Zhj}b)WN0P3G-YXz+UaK|moK)56eqTvpJtK=<2b?kL$K-jepUo4AiA3d}2P%^} z+PgX=)Kw?VtTMGn;=HPyEL>cFdjFcFuBJ*O?%e5r9+{aC zhU$=Hrk<7JuO68b|0}%Q6dORbWaq_T&Xm6T#l;bO6o)Tzl3b6p&LNP5)22_=rP)?7 zvWbZO-SOc@Nx@5auGLK$d@Fx_!2NVepe`h|S*$8YDvC^*TYqAh(V=3MN~6NasX=^X zrXvWiG_H>TBn3hf=crV3%TC6t;#e+6*Z&xt`&LY7i=Z?m@S}arW$w*$f0)FNR8m-G z)a*9?R*&V+YaDgS`?J|S;U8GNTrPF)t*zvOoE8rF((J|G@N5%`byks*xM8uFNNEyC zSbdLwkit!+;IN@%mA$mpwu$HHIFv?ItD&H$&dU70x#>E8m=VXRe#~xGn9hU2{Cr?= z%Qz%yqh1gIF${rA{t(&@jwC`#`CXXNz#H8Bl40m&p?EnwRvuWh} zwHLj(Pk_f+Vf$yz$y`(z;RPe?siN_Yo>TwBmhHu$Ly=y$_YGU|*YluFu<$ZVEi(=V z+SSYD_m6^@n`U?14Ih&R_SbK@L9jz3>p2@m+tunYaD8+%x&w94H zKh#`~iGb-$Uu4q0=v%>a#SezYmjJk!fMCDXPUKCVO`dTMlATh1Yiz^<-3_EnAw9$1 zYJpzF>o;=8hHKFq(Hm<{M*P$W~@O#CZNjmWNgQrdQ(V1pI zHNmvz?K6T4YV|(N1bP2QbNfY&6j+^DzLjJ9wP)bV$J+%BhHuPXFqPm#%}eD$0<4+o#3*v?-uUxRyyw@NExvWwql zGJSmy-T&C9`J@-ZO5x;V!tzK?W09608D}(PeI9SU$KZ1@5ltkJYO_F8I$bCGPp4kNynB$ zp49OG;=a+?NO|2+D;VqG^Km&BaudIKuaqG~+w&!FzAH9Im+Risb??(3((Vxd!wQeW z5I9@{gjjw;l?AMh(u>r%erWrnV$tX_(As~$Ub9tr;>dlG(iR<7#V4*Sa(@^Q^0E83 zwhejY*T=Z=s|R65L&jML^eg{N?9pA&sUq#}nb&0O3WWjoTX?vY*?F2|II zL&mtAWg#|F1T<1A05Jh9w8bB~M;&R_07hbcmL+Mz=lmKoe>L*?arF1Js6epwd67#% zQ4&?pW7H0(1ICrjBFu-lPMEv`IEuE*cYw!29`N*dEYTvH>HGf`eFOu)M-{L6nvdpuikc$&GjOjQ;~em!OrtEVrPAA`ATEA8I7~ffT}=^T1<(#<>{Do3i|F%_ud;DQ+BEX8 z+;MS&s!`J{v9Sb6=AdRQK!2-cda(yG~5L5yHuuF!_ggjUbW*{fwGD*aMHYwCq zjJGkjo)3QQ+#NUNP0jBK_Bn+d0%QJ-4W}jIbIb)oB}kcD&J-FOt^S&b8rn^0{O6~z zw(H|~)WA~)&5sGKlyXs69F*nQkscBf7h8c&*9#)S2j+^IHy$)u!=r2@BD67l1;Kkt|z(~?+mq6M)1!h+$SVSt1S|~>_UGqvg6udS-LLC|l zv!MYH(FV;jj=4(63GXQNw-ont-W5;ODQl5HTJgo^>uJf^--?!BH+?utDZxb3WxH|| zQAOw01k7kd-jc0QLV0{vajlM4O(Fg!M{jFBrm`$zZ-2f%UQ&tIel-y)!Eb7Fr(s9f zU3VDy^v*+JLgQIcNss=v5|S{}?jvnTJxm6%3xnjXegm+eDFdahF_W3nFyk2DoekAi zzStw%L7WG85`b$;V4Q}`HKa9wByZAKB5FXE4j45|5zs_3G(cDY+;RPMcA#+HUt z!X`<#^Y@4d>_T+w>AQb^|0hCQ!LuZJ%jom0F}osFbm5Zpb~Wps=Gv}?zE%m9!GOL- zOq;BdpO%uEqupj%{{vT}R!-jN$J` zZj?weOQCVRc&f8Z!O&Ey7X9pL_I#7FU>E;G$8R_8+ncIRf4AlRSVZ5y2;Mf0J9-9` zH%oBHqY`1qOABz|j_6o%42AM8 z#|kKP3AXc{P0paI4AF-peqdq?9Eji4bH0b}#-slgw&dH_BbE zk6cz^7zzU$__4988(HQ(1(`}aRnf5i)3zXk!JOz=0IV>`^~VaWV2U&&j*@8L#4?Hv ztHZCLKThxMQfZN{8R;JG`R-kJt+V*WuQU67&VKiP;%{-`uTIyt_LVmNkt$SR2n$lz z&|#o+lHY;}S^5qbXgRrYlxAElDuo)mg!p+M$S;Z~-14+&t@{UybrV`OdSBb^%*Ul& ziih{xOYO*yZBvo5kRBiS1_L+pEv1Vq*A8(9TLF=BAwAM6&x5m!7G=Fm%o#PW1CFkH zYSF8eYYs{N;H{0QxX|&C!=}MFvs=V`eWF{dmZVau!;dsR9>xA;7iWUnNiQ^f0CsD* z2Q+^*!-TD{z&Hf>v?)~}=Hc0PTE3dEpQG7|NEEF_R@`!+pDQHP!AGgL*qxLrm( zzTkgxuP52E|58}$g=0htJ>=DHlPY1=$z$%DgwJ|&E$mAC7#P>cSDF`97FsIw3aCEs zPhcH1Z3(*cLVs3=UBCJ#kJwUKzGY4&p12mr;&8AILhc^D5;PqSV&d$+F%*xqS6McD zH!T)&Ec<%U@3Cw?uu|g_hsNkPRAvFO#C}RXj>#X9AM;tiEZ4bqzlKOEKB_$DeM4JP zeLFKcN1xPq^$6#K879U?$cJIcOIb%#eU)y&!bki|cxM;Wn3!D*x`{T$W^UzZ#Ta&k zMk}DIS6>#GJ$>uEpx*G~+-hueJ#G{@KZuDEy%t+D==t@E74RpaP4xY1UtFvMeL;0H z+Ptyy`vz+w5*c22vic~~S{mY{G{`)_XINTelwHHhY#;7JKn&c=VI7|wN~7-REjVQe#Fbt5^PWcvR$03s+$`)9o#Nw>JLr&bWEV~ zSRcNVJEG8A%CMmDO4T5i;@MT&>Q z0$)^{(Ajx-2){}*5UYburUO)TB8wt((`o5~$SYH8nYEOTEs0o?@1EdoR1H_%tSu04=MNrIN=|Dg6Jx&=ZlsrjEA8Lnx$ZqOwzTMxmHpdjcEF% z9+A!~*TAjd)sCu#kRJ&Re96$;;_>&>lN*;2))SW@T7l6TGy$Xi4h^f>T*_+Khk8g$ zzE0K0g@<0VqxHvIN3F-*vYW?fD_{9xWB8BMmthuGWZK|OB6({90=T-mEbvtpG9P;< z&qbodkhDL1N3$=ip{8Kq-MoX`Z*?2LyG})F3Oy`zU=}8&DYQ1fmT3^s2xFU!!2(4H zf9ODyQpg#S!Kc>-ZU6luDfs3Fi0`?}@?Xv84YrSDYt$wY^jQ|asNDG36%y#_Ul{Df zKrt)zeVeNEyGU)+5%NUo=24~Fv@#%)VKUyU)~%-==c6K@6hoPO0QAI3S@*2fO#Jfe z{U6V74=$oT+_~&jPY;rDa(zv~k5?tVtx{s&GFA~0t8k`r-z+WbJSHicWYA!C{MM#+TU9DY=h|a^O z#SX-$uc#jfkiEwy-?*aFI+SJjSI$19QA=53KE6*9*I)7ey8ta|30r`-3Ql)c!AtX7 zMDZK_^E6N#g;V=3z3Fu;_nTpmcm`hPzAy zZN8xj5WolML?a+k2OudLrwBDH1eIVj3)mt2uU=F3>+>aaYy=JXr>H)-+f6ni8Qy?_ zf&#AjkTCNePO=i9Khj3@p0#E|Y3J|2MNi?uQK&Xv{nF^u_^RF0!TS9ke+%793vcWa zgN$!8Ncbq>D2O=x^+i&d)3rt?x?|k}^Zf#9dWSy2&-ull^Fqz4JOkjFhG#y{6Umo< zcCOBUA!n;yzV)9x;e!XcKOQe0qm`+Y80<0&_Kfo>e@br&2>5r?qWLp2{^UY=&s7$3gC{ojwX}oD6e5zg&$Z z(RU3ee&Arp!A&0K>t{|ez3G}CV+t3(J8CEZ^c5UdTD7jx*)=_6TK%Gl8;kHG6e(Wl z25DLP{nMAY@gvNly>LmD0*ASZRu&k&tE-a$cKGO0BOLi=8oS#jUrbh_3>F=erW}LS7>`Nd|* z>M>4A1GI^mLg)jpLh}OJ+dUfVzszyn63&VFGLi6OPo^=3kwpf_4@ixW*`Y|IgvImY zzC>ZJIJ?lrS|@9X(IT*Y_SRL0F8LFR&BkZnMaR`*_uYe0qJLc*w_CUFJsxH6boWAc zAh{Pe{{~;=pZc!Djp%>%d@flteiha(82CNEH zx(9JEomUk9XQ(Xte-W3!Ge-8la6G1dlG>?tE)(tB)MASqv;9EAlHtIq{70Q^_dwpXewoDJ^m0 zx0_0f%ZoNpj_fS9wv6oB8Q)<1P83tf+mu?&nA2s+-s%~=ejTjLBuhqFM@v8OhnFGd zkd`Hp>dP(RAuIB3V&U%IK~#}Oo1i3ANc^rr{7#;7Vku&)W%6sLJ=M@+5;v{lo#PqJ z2XIXWda&~cs+I2JcNu|O`olvz=i$RUHDI2X|8V1f4c?W`T*hrKwi+`vcBK5}gBa^w zvRM!QEkO26vrFDNH2cZREjSBdOBB6}#gCRI4#S6%M=y8StlsaB&aYz4PO65qK{o1j ztm*^>Dryz*Yd?OClDuKG+?scl|V|_*G!${}Acxrhk$MV&i30z>oruFn-3$HptLeh#}0*Y0{P1 zg}nTg&e4%E<^0gUi-$yH94yG#Mi-e2y}7aM@Vim+d~!Qp`#liAWTRHaZp3eJNGOv( zWLw-D&=q30yVy+f`tzfQDCL6A4!}U%X?PdKEZ@`-Z0EKJ2Rp4(wnWP z(N(_{dnWIKpIxD$@czB36Qh%ATm@VWZ{$cCj+u+Y|IlUx|Edpy=Y-leuyc~=qD!)q#cJPFcULfD>MAj?6dUN9$ za&4D;p0zg8Ij>VKMpxD}*8-m6cw@k-mnhu`+B%&oy|#YRwEWt>Hj+L{9V(){$W$LH zx)d}KIl~~icz=OlV3I&98(NaHV^Ja5#04BJ#Qt-Me0clqJ&Lvl@e?(W&Iv@MZE=#* zm8iMLhhbrA>)`%Gc}7AC$ds*c2(Ulxzy2Bv{6@fmSTvL+)}cdP_(Km?k70*5SA4#$ zyIyOc=8JCx4rlDG^R?Ymj^x8cufd_jy-LuZU+s0Z2)9tK4Fu8lPuD-kskrqQB4{F4 z z<@Q+X+&$E+ad@Y3uE2&dO5FyLgtJmieygG%$&N^NVym%W@X?)lCM!*chCbss|FbDp z>8wa$ur1HXr^iMKcdPffTd?Cn(dVcqsM83n)*Q2WYTr%GkQ@%ezEs=8dk6@5+B-hf zuwULhG4jz8m3faLjg5k$4V9HbFCu6Av)-EJ6-pmr8t^x6NqibMGU@CzC%}!3O+Me! z%ArtEy^k6*@PrA-q3G#>jKrc(vGSmJ0g|u?I}UA*mXde-hTJLYEwYk_)JLjjkE~0` zqEgks3*OPfTg&EFGd#OR61H^4$anbUTk;w7_hjPH*5>SGBqYw?=1jjdZ0x@HZN>+E z{dlp_^1Z6W_``$ z55$l`wyUY0w%w~%{>u281eMfS6`Yg`MQeiZW}4DEK8prUGSRetLsDRF9=Q)Ps2~ly zpA|Pte0&+QvNn>Gq+ByoslgAqQ?M$;lM+>Mkxjk$#rD9K*<7tc;AZNzh@OX#04;-OIuvQ5h2? zg$oMf#)#36gvv&Y(WF*2$)_>^ISq@31edf!W5mhfZZ?84?mT0DhHbyX&9@e9JN4^o zW-r|kg^zuAJm;1{nqKI|>iEVM$Lz39u|9pIX~OO`}k8P=8Q=(elU?n1dg zM_+^q|CiE+sht6hG}=h4;g_(r#!woCmvz+5)+7pYxO4+rJQr@O;bku(`s@2(Tkg~) zu25%q|1-ntUreQ>=<2?mfm;MNE#4d0r-O%oj}{iEy?PFeg`E`BsE=NUe#%5>OjWNv zGJ;8yR*U@P4pX%&-wSO0cCz+( z!ambea@NIMP3{~H+*sJGnasS)3kz_L0_;X_vxn!&(n~&A#iu*6QKEx^E&qQH5N-|p z1!gO!&u45vhkw~N8DpqP(4FHJUkvFR<$L30E#yi%y7j$s7Nowtn6c~q>HP9&Ev6Ov zi9U_22^@hTD-$izq_>HhAKvnnxHi2hMl8p1K%u>_o3G=+^FB>d|KE}3iT(P=bww`L z+dzU`4(c@)o5!U#@qZBf;?=pdrEpH1>Ap;|k;gBDxBjcMp<-M7ia*z#V_Ms!sirQ{-^r5qYHBL^|)lAfE%8tO7 z>PXwAD2n5KO0hw_;H>d~`!2aZDoo+lj%Ub@CSjYGo zLrNL05o?1Hn9o`mm)=W{A!S*9UGsr&4Mros4UScE`^`7)1v^4E@1Kl1p5Rjz!8d&m zzueEr8!)2F0*wOS^l%q0=D&Y|Zy^$4!OVR0R)E`uUZNztAleV{9t*4ue3TS*Hp8k$ z$b|X0aps2n3uT$Jl2%W2Grwz_3f8&w`MVsk|FCmBJoVndG)sp{JCrR2-F-JvO3G9* zG+Wx&%>0JbE>f_*yrIgN+bz~()LZxHw9?#g{5AL`!)kiDt005hHNVf;dMev~jI{*^ zrG{3o=)?mY|5CaoGu=3xF?+z;rkvTC3C*Qw`E$|+_A65-j>5r)m@=8zb<9KuON=>( zF-$b(6CuZh{9&ymPO;m!`r^-Y@=oBbD#bs3Sh9)maAU}z|0F}>B`W$-7Rs;@f{1bm z4u@I#-o1cd%x!6`9K%aKdQC-#nG8n{RhoZ_L7|fY6tNL#be{m|(bkDT5grfwJ}eTm z?vD1gMj*`L8OoFx6f4gyJ)@*&aLrY?*r~`f*b3Xg6ICQP9X{xx7GE$qs#LeUJAT8*BQl?meh%v z>Gku{QC(`&CrGHeZoN%4syUIJL$0dF2) za^w9$@dAM^{%^^aLJeTjPc(0-@dz>}fsYLHp!xDt>qZ*fSI%>GQV zt~P?;kIQgXCE7VntJm-h{9mnGq}P-5a640<=ixQduHig3j3@Ho^WxyrqOExTLUPrS zZC&B-d75w@vhx4HpqRUiZK9jm5-R{WeEbpL8+U!Dg{xLd9OgPQh}K$3j@5_Oasv^@ z-M0bmfq$wLdJuqG_ z{@GMwG;71zH3XljYl>pnz>w=LvC%2-gy9tXn=&j^VMHv&l-*>4F zW7hro)k{7Cc=-sBIsrg%5d(ofjR|OIkFJk=wq#|~aOM+WZW=*fQGMliKJf3biy-an zVyfMC`0!{gbdUQiIe@ zb(!2(m%i>L^<9VTrDBs$Y4o@1354sjw0Syd?Z~5~#PVi$Z{gUO~>4}%*(@oTT zy{MA+$>L~l{@W>1|8`dj28u*Em~V*t^<$h`=#>h{W z(T{Dj+D6<>?}F+DQHVvZo+)0t3)b{;KOPkNKH45V{)A17-|aknoVK{$x3)s7R@uZxZclW`JaM5qB}99X9GKPdFrR z(eU6fg#JeP3qtuTX-R`Mi_e7RJm{Mj{Vv8b2H#~V6FkB8l{xcmN94rG90Il)68adt zu_wG|eWi$gc1s-Dl}kXh5}Lei3{nw}6|wC^xa)UZb^fXbbco(i~2cI865 zhzR1`$L3*^*#`PjuDfC4LtvmWbNsNlD^c3wto5olwYa`h$k~-6^IB-q^DyN)DoNaQ z@%kzR5qfa9UFv}t3_S|Hf-evoVQU#uO}TAQB-tgT*=Sqq=zWmYRp*LoJ%lOKL=iDZ z&`86m;6j`3Dpi#Pxz?XN}9wrZup(zaPLZH^V&(=t$e}6jgZQo>wu2cqx)HTQf&{; zxu2?;Cv2HE*AItx^hb8nv&+u~+SO~q+wm8dBRL^%``e#Ko^dy(L1W#q`qvD8tK^m` za1&^yly2TnQ3YKVmaetOPT3-23die${5pzm!!c(UOXIkPVfoPs`Dl?iL*4^x3&1-j z2kdN%h*YVdtL*1v%S|8j+*FKXvA_u^C+;-lwsQ5M2>VXI?OU}och=VlR@HFS=i4%b zAVCNnJ;t9ymR8a*O<0QoGkL{7Fx)>SQo^>q&xP|rSJJd_*#Ae=u94Gp(6YpXUJ{&o z)~}s!;%)g)uOA9oQdRHmD}C|>3I41fMrx5Q{K7K}cN48NFbn!C`6J|??fI{#UqeYc5x=kPh2xbzku#;a9ZL z+rqrL^bVe3V5)S!O2Al`r#X+75XScQnUrfL;i?!vwUK@VAU1W(6%aVKJwNzV#VYxv zGiN{1~ZnX8f~C33E71leiYmf}&CGJ)&0P9C;mv zw^iLI`80*N3=(O#T=utqq%UNB6HL9c94@$Cv~=l45S6a1Bg+u+2VV6KkDG`$-yK5t zDX01tJFf^r`*s+c4wZli<=>lrY!M4v_!JE8%JdJPSHT?uLjTz%6%iG #R?4y(B| zXN%h@Uc#MXCzI343m@-j*tft}i4=D*gQ<}7N5jqIQ%}d~fa;HWWJaIto&-u|aG)OItcr;NmaE1gfZVGEzuuoFr|jkgc4s;TLOO zT&l30yfT9HH4FAp+fezpHLVv;rn_v-AQwjE)P@2lzKJTuXv^$p4A$oD2XvlK3iW7E z`zF( z!o~&(Q`6Cjfw2Z~)l`&OBJpGCc9If&pZ*B~*1@WwPXFfBqDCcV*_y^5@3p6uFtLqD zX$YlM|FR9qfI%>2ok_N7FAzNOjYruw{2$eiy1%<0#@|XCLI`6oYyR5$RoP)eNN4Vh zlHOWRY&E*uesF~mHr2R8!U=?Vg~j}5w^8eZ94et&oU|_{8W-Z|UhFuM=bl^{^_i-e z2^74UB0OJ8u#>cVbDuN{NqY3-RN~$O9e6UM8Oj-lQIv$qXSVz7k|a^TzNzTxeOflU zmlQG-3**~OFrxb!9{!%bDqw+bO4Vm7_;9?h7g;2XJbNO>HQj&tZsiVJ>{9Rs7BvEa z*g;IQzS)VL;6{%X;dy7p_r8QNH8lmCr% z?UJWx8w~IAT1nwQ1giZZExRutd2@cS3&DRiVd(`ZzD~A60fjrxm+LD?-}|lhK9p!t zls}U1(di(s29&BSa3RRt7POBJf?!I4g@CpGF**Txny5H> z7zjc?@LqWcM=ggh28+nZS(x8CT07hQr){MG_mywXLf}`G);9j`hnne@{|WXwS z4A@XOU#Sz@zjAmeTK8vKLrOP4QgB{{w;7nWt=8Hk*B4|Zj0PC#HPw>TY!~4=W4%Ge z=;``)Ya(m4FyemHQ?#&^Upx$-TxI+y4Q3mFfmUBLMN1W>e|6u-c~=lQT$e-c1%N&mIj zRF3m(IjCUSvUyHi^xrJv*NUL;`l@huSH)-|8Bc*KlR<$(%wpoZ!-x5;P#@Np2;^O8 zE7aAtlzqoDXqpqR@XD$ zaNwxY&xmsN$Zxgxs^&!{6Qxv@rANzyvkkxiuAoFmckwb?aX0TqKy8>VBA^5*(SOhh zPO(97TslTi2ndGr{S9jLSWGI#qwx2aVO=R*4xYT9czOS*|EN%`O;Ta*8)xaj-wfMpS zo}vE1uqF~8R^wvCYh{}Ud_TMg-ZYIlFcz%FWy`d{glP6WwJ!v!< zxYSka35EuUo8_LIa9ov!rk)~JuQXF-r9y-xvki)_!gHh*MXpD$f=*co{7eQ6_A zF`ywVXrGCDZeW9z$(;4|7^hk~sxyA4KWI-iu;m1A-4U{mJAs)o84guQsW+=o6Q|bW zfJ_@t=yK9wTq~qjR&m`KNR-qJU-k7|4~A0aR@zX$l6+9o4|aYq@BS9b)cgSprVK^L zhAD%qmfKRY&${h%K1X91nZ(=9)dziKx}O*eI_+r13!-S@?(1t8`=+P9GO|CcXyBug zMfgcN`i55IBN31w0Y(R^;x!&OH661s7AS^@>3rLqk&%ngKxw&CRDrrUN7ySlxg#Y< z0SojoCNdk_JxY%LmwqX?ljw-zMYrO)*aEfFf$lJL<{@9w(d_oqv|Gcdn6uCNHF@Zj zWcEq&n*o0iq6`j@HYtbBA2^ z4|{EO`MEAn2gmn)dTm?!;vx^<&87tF)}A(>xM6C+!ujWmv&m^>Fj*}3pD_siyBI4aazBe;>Q~k(OG)SFH`9^6_gL7No za-vz`Yc;k@Ojg8XTV492#@S!{S-v@0%z4_W_pZjUuNrP-2AM8K7&UnmHfvOI#e;%o zZI7a|IV!%cKmT&c5uy7pEYuX%7I1R(Buz&04;3{=$2=atGPHE{XA-0gs^X#SrMf2Gs-KV9^JQN9>oJ@AaPvvx*#9 z8QbzgegEB8GkrW8>rjNtp7E%Fe@InLr(-kzrw*(%QinMA`et3{uwCBjiK z3v^qF5OL9EWG7QzTqC7aBBebPoxPfvb$`CI#+NI}6VzsQaVUBF&<{Z_L3PX)SzLMr z1E)E?sUL+76UI;Ow|0zlex2p;S|3u&B;(JEZ3{=5!$I+X5+MXs4Aig$1F4cSIO9Np zp~{SwQsy58E2l<``Q_g`j;3CR_0D2Gm6dKPX2@_$U%l2t(>r{=bz$ zKMWrwrn4WmhBf7m$|p%0z_Hoh63o}@55rp~~1r11O87E$%1sh78X8IZBO+40Af((xF8 z{bbD(`cTY`2j>8{WE65rL)!3%6wU z^6TEcG`-A;M~0(nJ4tod;ILA~IUox}&GLfrvI3T|ztEifMMPkGsZH@oEiB2keY}0^F#n~ns0rTB1sIF!3vCgpa)oy>=?F3rSUTjCRsBGg614So zKITi3buj(#KABl44^3GtEZEp61ge}bX`C&OMZ~080n3>YHoye5jetpc6l`dgu{~R{9!)b`3@Y!~ zVN$lE9oux0&YHV~yzU(n>?JO1pA;>=4yAZ=ueL%j(e2TUj$T68L{~4v<3g!zFhk_! zMp{5h^~3*f&JXyZuANW*Sr|wkO%bca{jEU73O8ToZ@L8JA67TOBip^ri>g9g(cky< zef9JciFe@wedp<2VO`C(NVOL!X6)CoGqK9ZWa%L)8hqX~{4_M&C`?`}Iy=QGIET!3 zUE|{KWF{W|gv^}ZY%84y?q)<93kJc5v3NlM2{7kqLsd?0En^~F4f#AHx83x{(W`~` z2d@f6Rh>q3QGey+I+S;obB0>{Mz3)1)McjAmqp+WqVJk$IMS}aLyZy7wfm&8>~>{? zVf;IA6#{@6XvHB(+?}GlU83`20CF6{!NfA=yKOEgH`xExm#hX?bJr0zFPaonHWc`8 zAj}8b5uUS3?Cwebo$opCpk}Zv>#UIMC?`_bRpv>4n_B4|LmbNW4C`)qG9@&{h&^_L&J*%|Cn6(Cxa~ z4k#~6A%d(;SFbFe$1_WF3dZaqN%x1Qn|1=girjH_B`?86(o1qdEEeS@Qby` z>G( z+BL?9Iwg(um%(wjtPa~1jE+j9=uCsLqg;20YZ(^(2Uk!^CRrKAHe$a^hcdP*?nh6W z)&-^S&`;NvizZq4v+CIVIB-Gv)WRDQOu!wq!D%gd-#*tQ8M2qp_SQ40s0JoN>kylu zXTS}^S%!(J#FsSIG*W#zytrR8&8kLSr{k*P5K^Pg6aGh-Id&&MZnx2US=!g(>?_iA`?*{e}0m zo8I>uHvFk%j{Dq{GttVs7icHItPH4hWI9h}Sgy>w(=X$~nIw5Suejg+BG|gwT{$`a zrf16+e54jvbwneH0>NC(kIr6#X(|GBO+$y#NDuTa60|^|xacMv6g{?v!o>^VJO}`G zP&PE${S!1_7@8Zt`bTy9SQXvV$`^&Nw5@ift#KaRA&t(mxi6&cw`JnW?-2fzjU0B{ zI9JHK@Y;m(C?mCE{n5W8{ZE&y??t{vWq2dEvO>-zg}=26cAV?h3)hT&TeXj!={EAz zy*T@dmHHhJGs8LPV9vHIZvmbu9Zxfv)k+&WE}MZADb02PUu!KR5iUbhMb?BbwlA*h z^F;qHAw%*Z3%g84M9HaurQ+g|*eSPZsAG^DPvxBX&r_l17W4LigNVA~V;{NvOPzPn z9}x$>kBcv&5ZxtP`KJFubWYYK_v>9t)L#|`;3kPFgg0x~$+2g$Pw!0(pGv3L7AK2z z&c98CXmOkUXq>4i&_(l>(~I)nDx}^(^89&e@{Tj4&2O7N3R5fR4aAvo`+|e}8#(zO z8Xf-b>V(D(N}M-F3X(So2epUhjff{^iTdu-lt|W{=m8;fP5qN{-N$>&mB* zzwRDenH;3s1raP;sT7`St5yd#A4vCD5*OAg;~9M@p+Ap^w@x?RZ7PN`FENc?H6yEd zqtk|m48yR4y!;={dat@d-L$T!aDI502tGEmB5t*jH%#g{5AMEx!R7odF0iH==I6ZA zGSo8eLV0iHNqOj+N)A8QXnI*f+`FN(`8)qXMjRz=Mte1Ry#XjvEF=`6ddo6_Ck=#bB93zK;|CGyW}>B3@Fa zVU=r1DMV_+L@A-lS}xW8aHaQ`(kwB~q3!f{iPs0+Lb4j;6gXoQY8>R>!jsGCh#=ev zYVxq%k@VnGr<-}b{(Otlz%fHris% zMmmTZ%W#FuJbsfZtv^>=MdPA?KdSPoLB0&5zd^;wRsgr&%5fR|fnD;UuEfav+Br`3 z(Ql;y%Ga@zCu3qXL1)5L$iAGORXmA2)NSmI)$Hlr2)b4p73?!Zbf=ZuU|Vi|4%j*z z*ug`#h&|D|W50B0vQL{T8?7|hJw~q2@eo+h94jh_bJmLA--@)q89Wfm5i^pV>&vvD=C^?#c3BG@k8j%2WPnzsd~!_pjM z6Us_UWeaA^xu`g`{%$VcUhlFRae!w(nfr_=kB!=!ExI8kPgu=r%ewY&yRo*`OZ82} z0#Ax99tjgaErtXImSi8^wjp^@+sf}ZK;!>XS@qWB>1-_&sYZI9f64j=FX{2`pYbGBJluhGQJcIp zyc}nnZk|~-JeT)nJv0ocWKvN5dr=4h-g0 z0{q$8#J0QGaUaQ>j|PFRIvqK;Q5RL_fMNSNONRn8Gi$o1W_g*k z&S(wGgx0yj?nJ}YHVa2@TJNb7AshSRz)~NXoZjBnGwEk3e?Wk{gVb?Rn@et)&N+?r z=3q!)pu+;w#`;ql=f%-`)MZEBz%$;R;X>fPGL4HM;cNeFFtwLY_c!br1zHO5ah-b~ zHV7!OH)(7w1OyXUu!vHK-r`4NnS1)uE4k}My^lvrMxlvQ=F09uq4DH;mdV)W5>KZ| zoWWHsoQwjcLs6;IYATae0Hl0jyXTB%1}DzGxo*L|kNth_;vz6Lle^MBCnp4DUr$z9 zvnw{o`{IOFm2&3h?l)TMB#iWC*0g*olq-?RWqhySocMIMa7 zhxI1<>E^0^u04t`juc~{uOQoSzzBm)wi#Uub(OtrzJ)!@cslX^+=f$I?u97s!VfLA zS~Fu8*I*+vK*7+NrsL%Im+AJenm#1hcPmPt+HPQY*}>FcZtW!3?CBNjXuUVk*0w1) zCD|e#JCOI1*l?$bcC)~qe5!bn0S^P~kBM%*V|D0}L?GUCA{gxi&n9dQ1wRGaLHPoj z)6u_*y$vEl;eIPJj4`@6&6kvHYg2N#zVPE-W9(4IPb8$+|p>MkS!xi z&VIOay6N56;94&h+}qVQGZ~TlUNpd`?MWsrw&}5ORJT56W0q8PG}G%Gs^1liQO66!tzI4y~1j-47SGpR&6UlV82bL*9ub*meXd^ zwwvGY5TRl|(MVdGQ~IrektFp}gmrL1L&rf}^u@u-oIC|p3d;;{t{sp0`!>UI~(mF%x&>G~yXu}G^|$&;>6{Tq@QrYXZz z-X9AdN*_)Ot6#+ht{}E4qUI-qBE;AS3ao`&-h9KN1q2kEwAUqyVD6E0O{_1>&*@?t zNi66T%0Lm%wz=k_G(GVN!dc|UWES~efZ(=u|8<0U+Q9XGH6PlX?6qIf7(mJMk~r6v zl#)r7YbtwXr{#FhqFSr(lnHR+oYu=V3XI#mC`a1*oM@e|d=aLC_`_@*$L3?jw1o}g z-N_^9riB9HsTW#fCcPy#a@orUTPKHf?6xfT9&W*xglW;AXV~|Ni;2GfE&3KQ&E31! zeRa7e*r%(uaSX|{5wH_goi$4=SPDXFHF=VBc6M*f$IWxRQjRmG_+q%q1IM~nX(rAu z#g<)SP}#N7;nu36^jv65P|;-iOZDYn7@6(A(}v29-C~&1#y$ ztcIL9D#~zQe*4BJbWN1};za+-*EdtdWQk3#{8xwZ#?vmMru)ucNp7^sAb3Bkx>~aN z_xdSjdl&ISg{g2-NWJTbEQ`e^a05KtMGwfbqoo&uc0sEHG<70=;(hrFBV>2VXL1UE z!D>|7kInMjslISJQ;v51dhnG`TeE#@SEo*09xsJL<3d@8la6BlA1u;Y5f#%te^HxJk)0N4G zXo+cwrt+8#5SO8FWRk}SPF1Zt%jWIh73T5J#z5pA1B zn!{{*Di?%0;5bz)aBt$tobO3dXIiY_yt)WyZ0#YstIzE%_``?9daO_qS<6>IZK z&#t||k3Ca1qtk8itFJ91(S$E)^1Q%2N$^TlkLCGMpS)L(KIwxQ=V~o$&i6O@+-+ID z#^cK!8P_=H>}PaxiPrXZ4cyB;SL>{Sk~cptrmp1{JX=r+W7pMgKeUCkcHU{gO@Ee& zt>;fM&KavelXqku23g{-5^+DH#Xd~8Y?@CUks+gCuMCg>M5h#?O~b!6&^$YWM*0Oqdcl#pg zvH)p){jjie+7Dl;zYAJ^AuP!-K*uH{_p5Ibu54}_wratY{Wc<=2H0xQqC=7@byR@a z3}|%?01DacF<|@%i;jklPp%!vWk&)&aWL(LO=UJZTvDq>Hb=*9AH&$`@TsNc62cy$ zW{VlK6Wn`E(24Xi(senIz0BcLE2u=$xX-vC0QDB?otNl~i<<hUwN1klQFdMR4DF_!Hz6Z&Lkvc6JSF+SAT0L*Z6w~pd^esz&UKd+Az=WAuFY=mf-JsN&{vQ6_Q5LsMFZ+$U*!1}xMTgZujMwM$#K1a?iPb)#) zGgb{tF7AHm0slE>q>=c!0c+FA zNiL7uy)KEwpC6>R1a{9HqJ){~^8OJ4Ghf?GO;msr2tam>ybfT~w<=x=3=?Fqz{FO3 zytZ{!s7%0WaP4(i*Eu#YNbZh{_Vn@v|FvEp(k~Y=@OEiQ+jCawcL@mr^YtO?LtXri zSQ#$+hm$0(pifOp!u%Wg7fq42J}_*)2HodCJCn2zo}-D$XXbA4G0C2s+}flTqtnyJ=-u|HO=(#Oi&H&kbi(Nyt+N^nbRPJ&z3&W!)FHwu^$ICu*J%$TYiO`hiC2!KOi84sVrLjjryRPiA;wqx92Jx_?g9=-)5 zWR9_nk=y~+gX;lbZW;S&QaYmxX(8kpwtRK(#)jy_e|1ePI~4n>T$DBIjxxzXLZ2!j zD{brc=6j9@?Q%W%hcx2Hc^T#$=Rzh=}t*F?3pg@ct1#-fErwiC&GI%+0s4z(%OBox+F zO_2jvp%9Z*WJAJNb77dqh)SZG;SdW1EtxHqgO0O;Pi( zmx=hOFVML7NpT71`G!l%V0m`JyrabYECgqCOmsr?+G#n^!DcqJKXCMc_vok{ym>Js z@`o<5E{>@zMMM7sMM1j0?xanirgLsJ48l8K{Kx$_f3H(Cch;VG^56YCsl8g?JrXP$ zUTDt3BWtO`vMh^)av2*(5{RgfCU{L$L+oHYm%-}hlkeMK?EUdezh4&*xSXX$eDu_{ zr!Rh@o1G);%>3j3_c&7Mub=X5iSAasRkHxIUtY ztXgC%`<>0smB&t9JcYfNrZ4|td;j&EZITMkH-QyvmT|VD^?q4W(eE!puYctOqbEK{ z8&7&I&EE0!_AM;uSs@+(CL-n_4^e&dPZb0Ry^8_z6J`(*IGY&}i3otC(cPGth}>OO zQ;g;wLMY2JgrKT1MpXqMM1Vhp6LiAelO|2-?jjOG5Mk#g+AJpZMna;@D3~g2Nz~su zE$b^ml27m9;5vaq-P9S}E|->?z_Gj5 z$xaQnzw{fu*M6s>!<(J0$A95(`pRF3_vY%&!sn4)WF!_UYRWtqg~pPT!Gsc1O3>P| zG*0un)uMaq@?#TBzVYfGF0*^wopSV1cJ`UeKfh95rPP~k-?{V7cX~ygb8Kd9r`jBC zTneL82n;)3-ussBzoz@w`?Ao*L5!~X2G*ad&O95op3;1!p3ZD?r1N7-O`az1G@I9I z=yr!B*?hhzs!}aEB3PLntn4PO>fwHv+$+gFA1r!jmTQ;#k6s#X_HFz7```NK+3}rR zn_0u7wR2u$esHgp*?7E@@*t-#S5JOq^q#-KE0^3l^Sit4&Mr+SnMN)|a{&_zvj~gO z@~y9O(N%}P3-0(477>D&831NBvy`I4_yiHzpK)iRJj+6QlcbVvL)GaVksWVaa@%bSE?evB;}V>kLR4d_gX8BR-DTB1rg!`Tgxz5k=~`JScD;9c+4KU zrcIR{rQ>&SdLynL$o}>2@=sJ(J{OvEK8W|3WT3-0PrvuueEYlWJFjC{2X57yWp4TL zA3OK?KR>?uR5-Vf)q1^H*k+xEp_mF$j3NL^X7^CHDU7UY7_6>BB0=1on25>LRSOKx zE+l}ayipi4eA!D1-X5&;^77-oe)tj{zKO6Sk9|3h&aJvZwGOC20+17ggM`S;DHjL1 zLyH+a#<=~|$4G)Lez5t&|8im{R;p#V9zXL7qpKe~x_#GAS50X~woPrb;$E5;COu=gr%Pll}c4`<2mi|8BaI zx{?P@nJmz(meGg@rUD`pMik9Ng+&e87hPpb1y~zxU%BGj^y-b59t^J!d_N*czw^Q~ z|MunC3s{fJYI*OyZ|iWUlA(=b_{4q8^)!rIiZ;G5^Zqd1{Qm0J_ptn6QkUS+wTIC~ zzVHcL{v`IUI*&^7()aTIv03W+rTWk`(a1JkADTvu+?gOkkwD^!`uk;dw{%Nt#yYuN z_ODl0K0e#uZ>wSRqu)LH)^F^UxpW(q$#`c^`*m3#$4Zy0k@u%F~)E)^T5JPh|RsV>&xyB8TQY>0`!TWJ3vmCdru6M8RQn@u8 z{_$}7y5!Rs*{D`bs?mk8{|t>ELz(t>Pv@%>@P>I&(kW}=#NI_tV^ov8JG=PIV`Xt; z`7i!{bNAKN@nITY*!z|LsCn#5@4RtKQ-661Ps?gF0(0ga5D^nGf#3{xXSZP(H0Q`t z$KYl|?t31Rn|Fd7gGV9ekSMI{wj0lUSlm9j`A)5QyBWnx&)E|{#qD|I9=XGvw@?1~ zcl-Cg+pca(Sp=aZ;}e_4y=%Ll{>kvMFIVGBo32|gj;UYPR2T!ak4$DIhzN&VG$&IE zakl5NHd9p#K}13+#mtxq4u|6r0udWfjFg$m=}J=I@r6}d99&r9{vYYxA3}D*V_zPc z-Q{K|IYg>ss6+xW0R&=VHiw$Sp%1we(eBl!DKw@x*1!L2Q@sz5XW>ft)Xz<>fAaYD zeLG#Zr5a(&>voAEZLI6)ZV&k*cqD|7QgU}9(nmrF%nU$P-91)S5Xm_M2qBmmJ)){a zBocx|cbJ)~ni&y^2mn=ecOqhDcULWC=$X(owLfGg9NeL*Zk~qTHCGi6{d#icLUsD~ z{5St|J$=Ov&hfRM-22LZ*nL<|S3O#Bf%s%x%~~0>teupqN{LEl)=+^3sgz}3dLud; z^7#D0^zp6tj=%TLgFia$-(wuEna?da`Eb<;jn!F?2mtwZhWVi-=(38k9|Df zyTde4;FL7ivvBSC_R~K_Th~yZTb*<_-}`|3;h+t5No?7eiZBNWA+SUc(foV=g2!W* z@DQ^ABE=jAAB9@eid0|lH&eo>*>kCCwP1T zh4cOSYCebdM4j2Ps+=6D!_W!J7_rIYcyQ&Qn#T2aeslS+{=rt6cc?}`_3yP`_;-p; z-+ANB>pL-TP9U+a>kVcs1cDPDVrF6xP)hNVnJ5qw+%0dqMLVhkwWr6cw8_;d#MYG8 z?bO?;+_`)E=>FNogR2LRKS%8zWQ@|`{u{#&ztO$>T|2tv-FmXMe>TXS70J2l*T3{L z?em`#uF_ezJY99&CPuCz=R7cZUB_YQ%$!MLtU`zeGN;jG=1gY(5a0m0I}ywrfC#%o zwYWR6Y8i}5NvSDlyyfLYC(OZz6vh$g)-a8vgq`IM+oQS!qsu&{$arcyx zh%g0JO(lmA>d9WX@}zCvUH$%lRdqM&x;gg!>iM6WUH{bC{WB~FUYFL#GTB|ZnV_zO z*+B$%`+qs$=FUXSOhoQ*H)1xkl8d{G@IwHIh?$9qnTZ+hLLXFH^tYRhVd+k?UZ&jPBc;(qEHx@s9{mx5k+}@-` zjhzeQFMR%~zcj%U*7?zEf3i8fHL8Yj6>=(l$`J4K@@zgo*uCCNwwvAU(ZST~T<*Sp z^!fN}1ZM3yBd*+wX)V^8zgF|1f`k`#Pq8c0_khDUvWTcIj zvXORSfbiCp%Ujp3(asi$^ZM@Uoo_CG_&YoOtvU=?FQ5#G2%=Wab;jpDzWwQ+p)1cK zZg;njj_y6kDYZ?-Hc%NVb`V1%i#R|Ws;Z*(tG|a)V=T-}#BegVhXDQv1tJ3A?f@JH zI1vFbGkpX=UDy5y00&IfREe30RJD{Mgb;$e_5H?5sX~ZVh!U9D-O2K>S@*q%YT8Wp z!)O$@D<1d5t#99d?>4k&8{&(y1pIARQyYtrfA3L{WW^mSK zmxY+w+zmzqB4TFO;-&%!F}a}>luhc_-8w5mGoJ8BdhcZ`>|EYMz_4BiZFzJ+KE`T| zqZ{4#|KQGB->TF7y$Lr}(^sHY}G%x65i7)J!$h4aJzU6@csL zUg;ntiu`(87VPRUR|Log8MCayB=Oqupm;MEWqj{P*(xSL-Mzvfq5} z7iZT#v$(h5Wha}A#8l7L9Jq;1B|;8@n-^6prMLxRCor*y5Rtj5S`bk)&AGS*W)=|^ zV!}fX5Ha9P>@WgDKwNSrW??C%fQcPOAajMo+~EuYGDw+(JdlgKn;9%SjLFT4n&q6U zsu^D#(>MP6lh^<6db-Ke>pNfi+kL#&&6R4&IkApLVG?3Vc`1^)3cWFTWdkUeK*ep- z=hbxk+~Km5t*r}BUpgLcym9}fh22={gY{}S*M92S_7|SJ_|r&jzI%A`!Mj{m;|j2> zx?w3ryRO?^QsMS8FKjs=8+V&^uwj3@ZmQBPH=A&Ur4zon_1n)*p8MJ9GhYR!{fGBghxeEBV+uSPH_8?Q z#Y*5L2t-`W2pp5YFq2pKVbgaHEJ?q)6$VyN9+Rn1(4KmeSG{1G!#RluvNc6T$= zQq;`d@el`k$Q5v53M_CP`oXQl5JXr&AcG?mmc+fcCq{9r-MKP}axdNeqtlz;j#v^R zWV;$Y(e8eXx1aE8dp+OWy?J|mda@Pc?s!r;St@NExvmgsu)N8`-~~*esv2$YKK|rz z^9N^N`>*-tw`%Y1@VU#s{HxO!{{ndY<~P57VRxsFvE-uMa$sV1xLPqd5!Er8Da;sP z2h32i^y@%`wk^5bIa{pQXIC!oT)9-WBSPl9kvt%)-9NPVezbh~x8{fM$L-PR;NV{G zd2;E=&;R21+85DYHjO@iFr0qi`Cf$uE8J@ijY&}A>{6JOgM`{RD3L3f0U#lW^+L+b zB0@xXgoykRW+tLi3fzU+HG{2`p-~Ij7CCyIwy)#%@BRI0I%#K5r0o~e^vc zFbRnAkcde{N-4}NEKVSY6Wl)HW)zGCFme@`K+R#~DqQ@El<{ww|AfUf;{me zVb3TYv2>BN7zG}CBlJ3)n!ZsURYdnkyzTb1;PvsC(lNHtNno zL?Xf*goT)LRw5FP0Q?br#EC(V;1PGnBSd6oIcHU6W)aEi0E9e<1Yst)sg|soVGfuO z0nnnMNbS>vs%z`!Tx_NrKl|RvdoPV;-ZrC*-5f5p`_IwzF<;x_^laI!hpxB2uZ+gA z8P{z<$SF%D9FRHp)+g(XEXpW(d->TH{qTeNZ~qU=KmOVt&(qe0;qlMy|H|Ky=6qUg zj&9%H9gP^+WR)0L*xb~LnmeqH(cQ=#re0KwqLi3=RvQQ#P-@!t;QZFbE7aERrAFcY zw9N07H@`Rk&P&JdzP4R+J)4y6bM5tKW}p3v?LFyv4B4|~ULBume;Vy9*omM6Hyn3E z-Kv(Xg=2(BQgdRGXcUUNDjXsL2X|wG3SA?9zpc zwch^v@;kp}!z#}npM2q$##diBeE-l+j;BJDwKM6ft;uXwkud=vxT~qDs+ll@NSIlK zKt)R_8bfdb)W9Un#0yPVX_;CK(YqwrHwRelm*Ynk5yH8%3J^%d0 zuS&U;4*lfa4|RPy4#RZhWL@qC(?XRsb&D){(e;CR+tAiHPpCcDRy#3tN1I#kmV39F z`I+Rjkh_&oAV~#-)y@7>@$t`A*Ipo-fW~SV=BJ+4?PSE`ZR?li@JD?2yZG>Xn+NY& z-^DONnDy3D98*=P4K}P{tF|en-J8cN(~tku-g7^L+@8L7Gp1$8i-5i_-P((f##t&- z9!Vt<;2_}`Bh7#K+ZoY05Rph=78Yh=A~th35)o#0_fm?(nCT&R5aItrj{s0rcW34h zLN{bHV^|2nfT_9_(^7IO!(gUCI0&g4mC(c;o=mEPF*VC_`dU7IEtX^9Kw;+7Cwcp0 zi05^Y*GH$T<%y$&5ShdkFC!1Qu4fxtf~8V+?SEs^+Y@SW!}|0S2FG zS%F3uE}ehkYF)P|op0vp!L9VpE2po2dv){mI-kYSbUnLr@azkF&%L0#mve`Hoz0ns zA(Y&bad1~lWl)yFW0y&YArEUSeOpUpXvyYE5f#hQ2&@pfuz&!ExtSUZ6Op@% z2pmNV90c*C5OeQGNSx9dQcXpg+ebh8-CgvXa;|#%FY(3a&mJr`%QbQi#3C%@Oa@nB z7j}XLf?G*Lr&>y=H}&?l$7j^NQNH=Lk`{UPSpAuwudjUW_FK2pgTvj1+CT~Qn#b*E zEMA0&nF%m=H&ZjXJ0Q#~LPTa(N)ZtNOax{ja==v8%*{XqfQUdOL)DHk|MI_GzW-16 zcg}Uw7cc(!U+*^6&@DqAXsFei6xc$lW5+QXjjRZ=aT%Z+qK<`zA=a~tC!28a)b;9I zweiEZ@Bhg=hkvrcVHzH^QMSW{k6-%A<>{ANyE5Ee&+pu@{@ysI;DxfVv*tkr4$YQ~ zj3hV*=V(My$#i?{`xBDE&kno!X?t?FtdF!m%4OLhuR`6`dryDy7n}3X8Fotw0S&9@ z>PR2F(!Kxk*{vTocHHJO>sL&TVrNbJ*nM(#>En}&SGeZ>-p%7%uj>6Dz%(ZO%q^#?~o=w)RW4r3DocivVB}kw6b#`3( zM*N7omr_6;g807yz}<-`#z>C4X%Zmgvq6Ccg{~P z&b-_o?!4L`zsuU0(PVlhTzVFht8OFfZCH0F#}8^v4Z$2P6(km7jx3P?H65UZig_tI zl$-}{Y*FN?ANyGwi)zlA3%Ls@a&(q86OG5Six;##*xYi-O2rtAIEq{1Ro?WbeV{y~GonJ|v1-j? z8n|xT_WH&2#{YHmo4+<<_SxsJeEF|+w3An7RY^3|xzrmWi#f{130Z65w&uXvYg#b+ zSjA1p_3X;gBJ5wiKE61!YJJ?_dh75-2KtxL_`llA52>uaAuy9aYb0`-3S z-r}XNE#LT)ocf)spV)rk&*JJAhB7%hJY65&8gFioZ9@c%&kfDKlT?94#NqBl%yjhq zf2!1y)GntIWS#)VYR5W#-GAHK5-lL?hnUy8N?$sCD=?wQ?PhbC^(yRZh3Y#+7y*2&B z(|`T%^6n?n+D<X$?r^nSim5Y83^9a2fo(D#ZBLq(^M`MB zZ+tiX@K5Oet(J-F@oMj~U3+%#sZVu#7t*R9Hbdny;%LL5I*i6u@?MFQP&@>g1erpG ztO&BXf{9p+pr#L*WtcKhF#@x|+@YZ^B=C;_Ztj4K2#DOBMF5mi93D_3QPIxI*~oj& zL#e9v!svsye!I2%GxLpH+xz0*E_6A0lZ)k?O^YzvO4{I>ht#k7v*VIBOd1*FYMKV( z1&5tc*=y$gw||Rtokkby=YOub^5TOVM>c=Za$iv~i5sh997Q4~CL#d#r`(v>%m6TR z2!WXam}x0RRm}|a5dcKQj{xNEswL;*rjtqQW?k1gAR=xiA=FK)T1qa&6eNIIwPfVM z3QR_ED{@^niIJ=5r7Vkf%&6)~$&`zXxA*1zKDxK=fBnBWy7}Jp@>d@J>R(ma$)`u$ ztvS_0s@4n(M!a?aJQ_E%wr)JF*YgLOm!XR0?O;J!Y&tCq8C(nN|>csm+>F$)}y}VpnS3!eFNZO}7xF(bm+{I;5PheD>JjR|Z z2O95fO}3|W?kd{=PtYD`XTwn9Xu{K7lwKEy-O+pH@D089h9BK%*C(S;rD}HMZQi~z zdHfUY`KOxQ$7FimOVCtONjX?GiLGqx-S4h{_y54^c5Irm`&j+CUy2|5i9S~kZoC_h z-rUk9=Tc;=k9!tkRSO5fLnOpZ%Wwaa&Y7z^)-}h9BoGHMtCL7z31;R7z)g+Zm>vHH z5jhA%ZpJL;Ztxfa5tpJ?6sAOpk=@kYK^1dr%BpU8u(F!8RPT*3N@;QHhrp)B!WDF`$@cOBuzvFcn7WMzKqAv}vzg zy8blQ_xo3VbM=jXP;YKkZFM@nHvY^nPJiNWsBO)c>BHL(E|xcf1Oj4|z-+nKoKh-P z)$|30YLlib6zh6tyBf_{TF3Ft%{$*a`N1FI>^LM%9kvdxPM&!|u05BlX_t_U)QsT4 ztcKSC!sf^Yg@RZJsX#R{Hv!R2p_zm@1SeMaREnw!vz0`yktmQ83~-KZQqz*a6h*)& zR!GPRYNl|7n>(>YYNA!So3owOI#54^wu+a>AH4Fl5H1rcE(z}*1NmP=N3GZ4VcLPRVNG2G3}-AXB% z`bkrjoYdSM?oLb+Dv|)8sFqSfh_R|cNUqrxMv)EB9PhOfm9leD*S?^_4(x!Anzv+;5xj0M1AVOZU z4M{+4Glp?Cm!@rJTQZx}lTlq&HmX=V_<%B?bU1r}(_`DL((*VR-_B>ZX*jNI6;KT0 z61I7EAwT|Hb?K9%gR9o;NvJXO<-whPeq3A=!AIliR@;Ulz49;1tG^TSay3x5`{{$9 z`fJs-AKR>!`TpzO{r9H;ta08l5w3+okXS*YI;j7~KkfoN1dfqnjS!4jK^!WH6%m`d zusl?9ftM(R{~rUpyQ;E?nyZ;S;_79{LKdhu>r4kHCLU$0QwnCx&{37Q&Npb1&)?2R zuc!4=t}7!T5$q{0D^-S@}ncMoQ7wNI*;`RmEy^Lntl|2<^0|q<0x4HS= z(DmF*e6$lM+mnNRU%z|yyT5KXUu_L1!>qpc<^4bNSNOtXWtcyB_XoUL(kfS8$GW0A zI)~7-9Gk(MHsAOs8>liU#85X}*GiPltGba;0pw00gcu^s%`#j8$43}|fdS}4W)6DD z-2pI(XJRP(#(iVj8OW)DjEh$cX&Y`vCX;OQTg%%&4CTz!Ic|l~`D*_f)%(k%Zgti% zhbq=FFncx~9EIDFho}ZOVh$n#FaUQ~EviL?L*!C&S)NXY`Pn+Mzv4@E;6(buom~_g`*&m{6+9I#`Kyt<>gv_TjzL$#lCC z3rMqzyMj&k>dR+ueSdZLgKstR)Z0tpo`oWNKQHr35Q*V+N74yE?5i6IU@1RAGh5s}QQX z;vjC0q9vDNMnulhIH(UI*-9+A+S=W%uI|3|-LK8l;;|<_8=H^czdxn0=dqdh$(Wla z)Pcwblnv`0bg5(Ai=K*V55DY-kjlYu}CI8&#ZT+IOvU@<_|iKuPc@n{r z59O4qy3HlWScwRO>ZS=nsBNgKI7R|}#2+${f(zULkP|>~z~H7}p{fQGm_P(AV1XOF zz&A)ISj~O4N}Dx7V-Rw(#Hzxvk>Ic%n(z^V8QejFhs*#56C{8L?(hJ0wH`cB%pldA zpb}{ct6}1ni}wi0VqIVQ495EqhG%#N6gprr$JvP=-CvxZXvswGxmYQ*{6QHyhL7qP zIHV!1yA(%TU8ccn9_>u_E=?~z!56Q^y{Bn%9unZao!wg9e67Ftw)bb_^XDf|J!>0U zoov)ASK9cfx$yMkAurYw>iD_UUzg@=QOEX zW-)N68>!mDLT4}iMqdU53b6`x!&T)X>W~;5409q05@HMtRx7F*fa4(sU|>9wa|TNY zp_HPkA=Hr?Hg{WVSy)+TD+;McTg8Jg&(3d)FVF72ws`O!m({uH%#Ex4E4+6F-mdPi z4)311htYU8Zb!^u7{g3U7`Gm)T+Gdh1Rr5{CnEcZicknrH09Ols9&nf8BaGdx%A}6 z$0NtlYY%?=ziV#3JhD?Z-fTTH{>tC*XMf&h>&D@nHb+xmhyILmPxW}i?Mbero{E<3 zrtIz!&EGrw=D$4q!S@elJK5>h@$%f$pW6H4Ps!dz6rP_h506i(I&O_?FPlg@-q|mu zEzS-&!-KsGZF6FV3V2MA1N$eGLndlYsrnv!cFQxOIcu@JGj559nc0=O^*TI~&F*Hlq!PfdvF1 z4Nyj6>$k??+T$0Xo6Y=qy*P&Dz@DL_OBbqkQim3*umTcr1dG9no& z5E7`UFAZq4tiP1H2zph9lQ;=e1 zGi;XKYN;i)RT#BRC1S-*5vq#Fb$K*w)@BM4QxlP3VROZ11*{z0A$3aFJQPccs1b6fRts={b%Qk}={oJi-gY8r=u!?QfiY?_Xej=)$YG zbK$Aaw@*AjEb{tnGd}lBKfbN;#e)yqoD!pb^ZE^d&@Ic)9Bn*DJ(`QZJxz9Y8W9?wMEtqV`! z+(lSi-aS5jun2Knlt!aTQ`ImRKnM;DRuVbDA`(I+5(xr8go#l~E+v_1%0ubabs5@b zbh=3!s>k~mE?mAqzV!G0_2T#cXa3-ulW|pSyx#rz_D}y!JoV|0pIJV*ql-ffb8_=I z>ZMucP)v6#du*R&_0Hzye|GZ9%X`}wx}i?>-oaOXo<8-(a#oHX%zG`wK5hehD*ci@ zkJ?x@v!RR)6_||R00;`uVEFc@w+QhwTxxQFUuQWS5JQIY@(ZhJP^s{@z z;$&G2*tsy&<6M+sO+eemCSY9q_KXE?xo94Qond`iw_6S11OfzJxt1XZ*1z?Gd~#pcXOz3NIxGFUsRG!{ON=bcDCX`AFmbG6&e?%t#eu4>+~F<; z`Ur#E&9db#_Zxz@ZBvIpD6kB7JY=vmfS5usRU+cHg~L-$MTtm4Ai#k}qYRYDa)#>SJNqrSqTwQY%8nqRfl~RaEL^uQyCeYjTnbBlY zRZVf0*iLr#+nw`x@)IbaLQqCQ8uF$qcki7}rrV*3q1JPkTiAp3E5CE{_P4e|KaSyS zk>bwP>2qJj`HvA@@afZly5HN}{?_SB|7h#p>ysg^7Km40z-Rwr`^BFv#t&}2y}0q_ zu7ujzic6@ts+E}DeCcbGz>}t`n!1?gQa}`|x^9|O)YX`T9&%z9hi6mAM;w2OLBtZ> zotcSQ&E1SB2#rbMW#zsmB=f9p#c8~?)tuW#NcZ3T;|I6joV1v>+wJ&?(YYr)mF{%D z*z|oaB+aCq5Lh09u#-5GP$tVL1`>`Uk(uFS=FBX@=4w{l%~7;yTCF34OgE`;JDKet zjCQ8LDSr5ShyVP4+~Y+*UySx1%X`fZVZQ7*G?0oV z7?A<=5QE@i%AN%#u2iy>k~j=ps~OyK&ZXp0Q;(;!qSj7k(vHxKP&Hsizjj+v*?7)K zJUQe29s-0~+BYBnKGPggn61UBM0p zVDJJXR&HG&KnG}M9s1=-!$zg2 z(nqpL9@!;^M4=$C1i-Bn%LRl$#6;#QA?QO^h$&?qPj-``%Q>s7GBlHI>WC^vk}3v@ zA+Zj~NmJgeH$g&O)e@tr!$9QZzS*oyb!U4!#%j>wMqD>_J8CD>(R3S4ji-JY?bt&F2b>@^Kv?%k z$-7PI`l0I3`d{v0lR z3R~w84XY3D{o(&Pdi&+++1;}47wy66wI6@%r+>MA{Mmj!KY9CgS+8PIHWmM0&!E!y_n_G6#(4y(iax#UpA z&CnMuTeIz<&+ODzBX-u}!V+3hv0T&)06*kL?f@JFcV(s+h1he--2m-YBN_xcq-3$3 zU3x6eTJ%TdyZ`F$%fH2EH+E}mmW$1LeeqZSVYv3JZm{b4cr|SPAFALj*1Pn+5Bm4_ z`#sOI*7_gz-tYOH8PCyUj~&N$;>N^I+{AI(qzx5GDXDr9L^Z;l9{1^gSZh7c@4$Yy;}AZdY4_BP^#Z5e z5$YRXJ^h2<**&_`=cHwQfQUt%f+9X5yI^iA zt)-L(24&Uk>T0Uh+HBe)l-yk#LWPJq;3mS-m9sVvN6Shr=!oU|X7gws-&^Fi?z(k% zHAx=*WVW2k?ZjojIdRvNQxMIqf~a2(>koaHQli@8(eZfy!FF@5W_gkO^+JUA`_U|N z$-ELglnr| zMnpMr5&=Bt9N}gL!0Ozm6o|?kycAv(wiMfGe>zT6ZQR=IddzlSTIHtD*5$$?01?3r zQ>)A65<~n_XP4YBxNyJfIH%eop)c#3`+SJ9ETteYO;c0L zrLg2OEDo>TOgC?b6f-ywh;;tQk59()?Q9@P0dbGaoGHi@I!P#5o95;+n7hsADIvN% zabDiIb#(hG&&S)>zO;S)UP=5=IpEnudd!&-F{LQ1=I0czxwy{{jb%xzj{0E$)@ucf8oks{5R$HN6_8c zj6RL0H*V%Qe|3KK_s@RsU+%Ws)y=2l;K`#O`CRwnC#RWD?%i#>O=_d<&KKdUl1Sa1 z%#u>y&>4D29lBl4A-Q)>hUAo-MAhAtA`*e&iGtw*XQs$mmMa=oU=`djQf4nIhZJk3waWh;yKSAlbI5e2(qpY<=|i?RNP272WXsk z!z!Kc&zA=W&S^Wgu3vdIIX@nBCR1(NbT)GVBuNr6ZH#c&)>=xbUmaA*`CzHVLayX; zyUrV-lMZ76k*~Dsqz@`}{qU?X@6Yafn^Vb-*zWfcu~@IVT)M6k5uN98KWc43sG@n@ zm#%Bt+#{vL1Z&N;C4!K{T6kOZISng};lT=;jh*`_%e_%KxGu{pJ{+ax;lZt^%$xyZ=Ig%+(h@wz&QD^yS~*eepLBXv0go zn^)WQ``-VVztung<9foI@4hl`@0CP--!Zeh(Pnz{;Wxe>`~7OQOo`2O7&-!tBgGfN^O5V^Zq1PH_;!jhT?0WifpN2>^s2vSB)rSI~hm%<2* zX|EIJJ&jYXI)PMj5Qm3#Ifp|iCF(+9iX@qeJ1anVOu_+>N4Oa?0YMZjnziezL3<{@!;U{o$`|zVTZ}yVsYg)m=Z|dZ~Q!ujZ#e)*oE=w%H%Q zn&0@n-OK-KU>z~o^_LbO|I4e7{$v|&z5C$!!eJaF#q@|&sJS!5V zMVBDH6AF?XoDEW)tD}^mH6;?j-EFa44eNnS{rxs<}SmA<${RLHs=I7yn2NK7fjX7g;|K2`^;{cIcJeXL~+5)R0))JU_EgLCQJ8cf+uqLEg!sq4uQwG}h5Sw(G;g$TSF%Ck>k zo$UC#=Wo4S?|(hd54xCVb1bgzM_FEf=J1JUw_kaAdHOD}zkBvz*WKt|_{nEK_ji$> z-M{+nKv~v_XrSy&=5&D6Z_PBnh~5z2ay^PL^-Fv6b|UPpJof`=2p!sOQZr} zfV?k7RT(*_j$GR8W)`f$2D-om0SK3fDCZpEbDdOYRmHr$TABy#uoz9$BD9iMcPtOD z96kATS@&`0TaUi{FQ#vQ(KipTz4zKFAJ~l-<%th0Z$A~gNA38#>Cv}KJ?Z^)@0ll|N+7tf69EW#1Ogz? z1pwwA0cIkKAW4GMx3Rexx?1NTSxE--MAkC*6bG&r*dX`rgHL;Jr;;f39U)B~&EsKHIN9FKFq>d#?*YmK(`Vid$ zA)o|{dDd|^Rdb4vS!JGK76@h{AzTP&B7}Qu44COWPMo@24o2c}kSjNzTMyTLyf@wd za@SkF_CCn7+pUf5?HC_+y9)0x97?w+UB@{Ca0_=QCIA5j=t4vQM3llCW9Rc(n5Ye) zqyFY~8^rVWe79HC_nqYt522`dj4qp@Ijrn&?epzd7=n63L}KOo2hV;Bt(5x zCn=N%g;a|GmD1_7cbyAGCm^fZcEZ!#>ev>NR)xA;Ew@=RU>Zm#pyj^cFl-Z!^* zUcuehN^FLKnA5!TuH5LJ`4Im2%hTyyAMc-79*tT|b(s^n zd!v}XtdrdT&f8}7=q?03vdR zvZo{+XUuM6gF|xRoHcw_3s9E|2ie>%P|4M*M`MnZh&cf7yWZU?SfnFxtJazZDM>Ih z5fg-nB4B2!+V{N(o2$9HskH4d-F3>FbbU`NMG~8{Zf)Fz2M?>owQE;yUyIG%?RUR& z{OZ@A{MY~MM7=Ms+Hj!E(Cv*I>-o_e(xylYT|V)iAFV$2)3<)?uVL}ze6rs^xFc;_ zFquw@K<;T+MYoKuhX^qxAxeFi zhGp_h&M;WB2uXcf9p>v#;L7c^JX|b~PAht$yK#gZEf1`iHOanX`H7i!iBh_R6;<+3}PWd zAb=1_VP@L0BnqF#IWdM=x06+|YhyVgeq_Z{_+W5TD(f3p4oC> zP9R~XW3&AM8k3RTg zc{9KM8~@ksW!*n|EG+^v)X$%jB?`#y9?t?)JyWJExBx-Xn^> zE6nVUl>2E?DT~$mDyKduZ+H7Pp7cB?fryxSYZb(~6cPatAR=a#3n6H%AS7c}rWTc`AY8~fGYf$OpZN|a*bgD3YY?@ zv(Iy#_hUk2VVkG@*~V*K_KU6?Ts0IqXKmKnuJ5U~gmR@^Jt$WewCo^5J$9SC?H;!M zd#Dd{bBfM}wRIh(%qcN57;YZnB+Q_2YpvB<%`KeQN4JK)^fw2@ImTm{VsRDSwWwu# zUN@V4ohOc|uy!$bUQ13E-c$n-EFNmjC9!}B5F%HftGNs=ok)?AbLmnkTrv^48Qg`z z;bAQTl*z(DaC6nBP2DVj?QX|JDR;zh^9u|Tj~p(XC^1Ng;D{i~DTTS2mQ3Oz@0bssz5W9)O~dv(_kaJjdw;}a+=fFu|LK?hqU`s2|9+jO zoKpm;DyNdV-hvbyoSTz6DCHz+Ip2-&01*p_JqY2sWHVK5VTy1DoM;THDO?&j;?eyI-pBe0_Vm0l)9sQy5!MyTeNY(gz7_R#;Q5_Tq0%q?l z;<~GkP=+9&p;&YS4tAZqY{Y-UdkSCJ^qxg(>{0aT7n(b4W#;=Emz^oS6{1}9SJfc} zOfv6>_$qS`@wV+j2kJ@={vqG6(hmUcA$0Y7vY|L|7GREWUH zIpm+1R^a?Z^M~kyf!$hi?mU18&2L;B7R1*9VdvT`BY2YAlF<>X9Kii{|n$o_^uPa zkQ$je{cc{J6q*PHI?(Do^JN2P))TZ@?>}?#n#qR9KF%r0`TNR=dEf z=*_Gg1iHrXe&sqiyIc{PV)Xy%uX*sbx-`NyWwZx8tg<~9BV9RgzONyf-w+~Fna=_X zT8^u}TDCn+3Wy_*7Uop6K%8m6LD8C067|OS#{~Z7JM_NtX zoe#q!?1gmV;qBMv=ajE2CKsur0WC2+Ob)8+sdD$N%{uta*BNEbwVe9djimre{H+gG zWjJj@O`}NelrZLPS86|l$$i#*mnN7`cvNJS?l>uq8ZbvmzVYR zzbA)6YZQ9tSKV>$)%Kr0F84Pxs(-^$dEb*KE$*xF7m4k<)yK40LmdzBA{-tF@ia00o7-P9S}k?O zFT`vxFY1d&7etBmYNc(=6WtMPG|*;yRrP@9nIjv!j<+7HTM@`At>ZM7V4l5f_HEgd zO!>VTy0vu)OlaX;bFUu1R2I?n@)ki zqsNEff%`R-;|zLoqs*|tH**BFaAs%!H{0uHc`pt0JX>l54-bP{_6|r|F9ybYxyEak zwFj9m{;H8M%LFfbXFf8H;*7C+oijGg8jeQZPO$5j(I?>`fg`yvI$3Q`}N6yxnx9@mZkJpB5nd6}h3ChkLp&e8+Dr&ZzALR-nMoHKs= ziC4W1N4paK2?{|gD81lQnT|F!t>#=QG2B^N|EkbsZ>v#t;O5-5{NEF<+mG%Xtxj}S zS#@9A-JKw37Bp==8M&4`Khp2mm`h-4sS^)E_QkcJBf%u?$GPhc#}fsx+!0 z(X^oG=v}SIAdR4EcUF_90o`A%fSY+^Xllvb$IkNvt-8i1p{VAldQPWUcqus-LekizLML=5rz&`k5 zT2Ce<@aTrce18S7KDXe9O{G`r-}NEU{>7>Y=- zkbZLN_F_k=<&4i?soitB^h)CR?{st*&vZgyZH2AfQEIwTi~XPUs^>6oa&%9otW8N} zl;J>QDnek4?iZ96LcR;9M8D09GMM#Nv76W)Hsp)5_*C`8#0bHS4{hWovXMiJ+lo5Y zhGEqTkVt9>r6{qArHyw{YP$)%WW<5tG>T#H-Rj{FZBtBrRrNUTs^HP_>4%fKnyaRqETKVB5N9CXj!!gKs;#>Lkpp zoFDh=WEQxz_h$MIo-@d}uSzwa`aC%?SKgo6BFGMiCK5Ex_CAVx^+Z?9lnQow7TlW}Bx9jHld?n|hpn*4vx0p&0(9s@tYfAE@du?7`S!+m?T1BND zdF^diq#Qk1&_8KhD~!^14z$qEQAz(vv2SHC*tqpr%_wzzs~P9};g#l0OVIM%L|dip z-<>tLx~ua}q3EON=MqwyN+kT3KPxqZ>G;oqB*7={9!_0Hb^!>9LFYWV;h*8W`bclQ zmG?|utvyDEo$Rnk}8W*^pG_W#O?0s;9(8Y9*!_HV47eECd8u3fQSgIwy1iIZIE_R6B0!bsTv zJ8X6hdKYj!B2fI(mV)kGN2KyRH4_1b1*p{f zjFGq~85<}S4105F?+e{;mg#KK(N{N`&d5y9YBLC4nj!2#$F`lG`9WGu*|`2!&h3oi z>8U7ka`KwK^1klAEC)DNj1f-eTl0D<5|YE4d~>?3vVE>>?bRJ|Z*NCiO5bM@h&vs9 z;{TpQQP;wuUZk_7oE<#s>gX_N92BS&)?q`ySPHO7A0ZI!r0lW@Cy7P*Bym`bTTkCo zmCd4FHOfprvY)i>Z+Kc{-2i%{$D$ zMX$zZao%nr`cm1|S33No^@%eoJ_`qoQ~f79E0h<1vb%QIjfTsjUuiOSqDJ@H%EubU z^B;xwe^gmDF?$#hlc9{IaVIM%(}|-3kx#h#5uhj)WURA>V-fN?tOeWj|4}{qc@S8r zEC{yz4;y8I#=;=2R2prdX&y~W-$&|3sgnTZv*zob$SB?WkkSyQBJMmaU$hx;$wi`_dxj8e6M^ZZ4WS9kI*ICbmqc_Z&G72V#0ICgZ1hg}bO2}Q%@ zA$;gLVi+Hl>`ep}6Dq=x>N;nZW!8s*y+57qIVGP2cvWGRD)~yRcv8?S!4q_0z4u1E^r#(dE+2>XqEl-^s5*V-zwCm)#+*C%;SI zF*f(vy8bk}T5mP@_o%y97vyJjD2YUq$hp*A_Z>ieCtYASm0788N&CthDST~M>97zPRxlM2k z79DxX=$i<&3>E!6|c(EWdI6nb)m5mbQQSTii#7Rt)C0=eR@zJE`?7e8dGZH6; z^974sFMHC1j}${{4@Bt(Lo6?1@?Rf?;Qj14R*#sc)2%Y&``&gaZ=iNdzeZu*?f$H1W>M#({|^8d4OiyyN1>cg(~vI&*kZoKG3yjKv=q7r@Q&~zjct#v1bjk3SkKF3Ev@~U$c7d@-* z(czXIe4bvn|0jmdmT_d7#kRcJH-cRRVQk5cxIs0m1PSG1k&kIpht0nPpWcqZkN^jz zB@`U*fJ8)CkLB{Q^BNKx~9FW)&jsPY`#d{YPJSu zgSh*>CEIDyDxI!Z4idrsr5C3|t?;$X{<>N9DQ`9gF! zg>-pS02;um_2qbWvf1bk+cTzL0F>b2Nl=CW_I31eO9KRs-?;<37PkFP4K@$9C9Fd$ zvb}bsyc{S-a_6pNAkbj`?a$#j>uc_ zlV{fc%^|z2(K5Swzdf1leP{ibHG{Lyx6B>|Y*f^`Sh>3$lrb}P9kibvHF=j6RX7eZ zn_i8LnhpChI}d$UaNy#ubvO8XSR28hmu`Z26e8xr^eQ{0FEvG=#s~s0Q=T1sLbQ~l z*wF`$d5Cb(ISJmGIUSfG0v3{SO6XBo;WmU-EQqVs9{#Gfa zMjft3!(m>$5I>drs7ba?gj9*Ec%vy*+b^T692UlQeV(}HX+!yoq$nCe^0Vi12sk@c zs5x1wUtjyzC8_<0EC=oGWU)*JVz{x}5!M_rPcAD4g0UQhYf`Ce0IaOBY^W@epkl66 zu}AY{>*a~pk+o-H`|9t0&GMxRfVg&4;>=@Ln!72a>Nj=$ zi-f9m?a$Y%|3%2~e5$#$Io+SVyIkB{9UeH}Rgt3*{UhQb2@E*ZZa~9=SrC5(ZAwPi zq15DvXS|3=al{ucgxEKHA1#d6YVyZ4jemY4O~!De2Ie6)A_^HJ5C=ttLA_Y`GRy=} zzN-MLG&MsUG1d3A-+5Fe-GR9*;UqOFZKLpTgns96+e!4SkTT@4>G@iU?_`UXUeha9 z4hx%50|?B4y_n`Tkj;$+GVY>iUYmFvVZq_ftDCQz4UJq7poD%!Cj9d-@)ZzKzC+mJzAjmy3MO?P$vRFf7-L>cH8*Xd?d?53@Ynv z#Te;Pm{KPOOSVKo2;%q8*aT7FMH;FU3Tii4s9<0UT^^KU zx{Nq@CgNw#mfps)F*5WJJwG$*NcEquWXs~{`sYZ2u9c7O;_nNR+(Qi zSAq%4C;tdexP*+dTyNumU+VIIi0;3)%Vtf@Ku2QxobqgSZo_QABx}%Y95(ZlmCkiJ zq##OAP1REep~?lTk<2t|pivt=61Ub7)=^2;rijc|ip*-nL03~1p;a!iYL&t$HLm3x zqW>QtsI=r|Z)Y}bSie{#KcCT~{SCU*zD(zNWoCz=#c48?;rt2Fp+KLx4Lt_GDS@|n zc>8%Qnw$6B;*q!*XB?ZR+39VGlWX-T3BQuFju3%gN<6P*D;G(M`5nlMSRz5&)Fq?M zp&E=Rl)13vHm&*+p|YPaK-7YU6XQv-KzK4JJ|iT|tHa5nJrPeK;gL+wEfHiTaAK3t z=*;iM==g2&5T3W?lJEG2bh>7a^SDnBgvC!L4zpXO^QVo>LM;AiU;R3{e_uGGNDbq` zj-ZM|0=2qaCOvoMKqD$()0qyA7|(74uWwY@a;cx2>=Da@O6pc z9>eMO|FbWs#uD&EH%P)rBM_YDgB@%j*8~eTWnT`)az#Y%cc#~por^?SVys|?c;oPD z@Lc1wiT%@2jh6lFlbLk?vza=n+S9Q?Sn zxs@^vKKti^X|pfxPc}L~uWys)tUNnNDt1X6HIO;SZ?#{0PI zD5IlCL(?ssEdSySp%Zr_&y%u@_X|qpYXJhBVE?;Oji7K#vLe1LFxv?1Yr3(oJF6r z=W;aRI$o&vRZ{A-%&e&9z(wf`b4*G}-j9@qJ@da288KLevCLaq?Ij-{uWaJ;exT*L z>TvD>*F(fE53ktIT)7Re_RTm4uO@M8{w2ZG~Pa^o4LGI7aoqkm@HJ zl!$5GhHm7UaG$I)7wi+x(G!Ac{9>3LRa>$*^(Te}0Vl~Zmy?4Cz}&^m;XlD42okC+ z3oL|#lc=P*w{))U%{W{9AgXmW)yloHMl$j8IDfHCRGgXdVsjQXHItuX{}i!?V+tif zW6K6MZ^NPgXtD5E%X{ioE0c`8Su zd%yn**S&t!8gPoc+Bw#2$zZ%|U)%KC1UJySFT)<0$F$8fT`!@PrmT`8HWWo`+J~ul zTI`~A-#hQV7KYuz4~&orEwkIx&W*;mfK4G5i}6dqIAwjD<`8N3WGBa zaYmXKQ?nXp5&ea+{dd(q1@~{p@D_+kERf53uyY*3y&WgAL^+UbUh`^xC{*NZXl zJZm5%@91pAFko9eaqF(6hFx+UY3lE%a)omRstJ*R-1SuA^fwJ4L|Nvo4u8X9Y$4eK zyd3j7PFV#~oSc$G^K|uT*FV8U@xhsZ%7fhhysB5pWNlIMF7*(rX z>~BeJLqh|#l-RQG;T~URm%zNj&xSviM^8Wc1hf;Sk?X`*EJ&e_O!(0e&egCep2jE9Gpx6-)DF69G5_5H7x_|1sX zy}&E0s~_y?OwGH(XH)b+XFc6pMi*@wd^JVXF;43u%lJrR>xV~qP2%mIj|gGEZ!1}; z39)iQLlIKp<~n-g$wgM1lY9t|0UaF!Rd~CFjdG_pX{g2RJ z)M4Cg`I?h;!q4Au!&PTf{+?Ck_Lp;yHag&{_?`93l?o5G{%u}LE?=4cIlm09z4%cb zH1sM9$4rQyxa&!il2C5(I6t+FM}Flav`Jk~ku#jEhpRLPQyY9~=}joY9f}6Ho~u3C zKK{GTfBEbE$@m&mia)AA&rW+P}Mc^(HQODN_Wsk2vYm$?k-E&E;P#nlJQ+k-2n#h(P#xS6Ph z-gl*lT~88UO{G>*0Tynmpjb&|^8viw_)S}{mtb#9rKLtD1I5I$;k2b*8aoW~Rv+R^b+k?b`Z025i{7r&;lKLRoiJ zZX$^VP%6c=i9fh>bc*HBbMZxYlpjJ=B(IafzPpug<1nXiidPhw**RUeET4NeP8e^w zm}a+}KAL`UYpdH!!tw0<2YnuM&!xZQ%kZy@~5gD+d<*XPo{*_(aRJJ!3&aG;$ zx}r7p2mwukaB?DOi7l=H$q%14nPLVSUDi`S1K2igpr2a#rv#T>TJjApw&Y}G2P#-H zKvmwaDryEdFhI-~bIhAI`Is)}@E#O<`|5btN|{cp?@8*NT!vVA9c^?CT&y#9%C#J| zRSIt>DOrEDxQ*#^C_-Mlz5fv!CjilQ_qy(lV*lOU-DkHdQdi#JI}vj5cWaw*I;h!2 zBx`szE$_7HO)cSXWXAAf`LjhDHrKTEat)7mO_ntRM2;s3LKO;q3WY_@KZAnHC=Be3 zTJ1rF8hsti7dLu&(iz~&@BGOBAAObi7jKWB{i|9mdgzqo<(q0@n?h6qDlDWdITl#T zITrjo`$>ByhT8rv_llGz2kS2)^V6b}qL=H(1GtLBtCgh_*UnGOg9V>eEN{T&-~j4* zRZkgUzD5fq1D2s6wjwD~a}JJ=xxPSyd@Y2!1+HtltFp82ssIux82sH^@Ju>OIck6b zNa`TEaj&6wu4F*9v}H@pND4Cz@vQ#yW+80(&6|TbdS~y(sf#(n(N#gqVUOMR>G3)D zw(&)21mRNEblNoF>t6OybH$Nb{lR$km&3l0tHED07WFMnPk8kDp|?uDTfBL3CAsHM;(6MRJsKdv<{5iMH^fpf(vY%w$r@jtJZzM22FM(7*e{zHt$!q8}ofs=$R^ zwmLhYOpFafl2IXysh=Qk5yO4qMR4=SN52m%#|9;N(gH-pVu*XJXM2 z$RJ_GG|2T0lt7`T` zODacfO$Bvy29mBJNJEi8aC1r<0xlR|FmG~Q-g7%C(gVpwqUR_>H z21qim9B_!_pR6C_wQHJ#rQ6>-aF?iuN3wn5R&Jxph0sHC!$<&WAPF*c(I6I3DYUr( zo}zCOy7#2BcJ|_U*>&~e$Vl4z-{@6G#lbWeL;UAqE;d8r26G!ltacJ4k2ndONUs4> z5nt)s5P5Wf zp6$@11pZ2s%br@JlNFb^uZoqrjW)aCA4_^R#|a^qDEbkGgRY}jhc4xh${%KHnFzBQ z43n^C#K%T^y|i@-jaJUO0sB=~iOU|hdZ@xR4j-T@qJm+d6rp6YyVUbFCn^o1-U=Sl zG6tqq6qJb~b<8GB`^o`l90Aqm3TKzSo0R7MUmJr6Ypa`?vz;p`g0|!1(^voEUh6uo zNhxg%SjB4*eobrIX;(evt=G@CRMbuUX(K}vZgnpS@|H*il|oDDbzecKSKR1f7)-9$ z<}t=t89+v5F85##!FTp2*a?Yu7A+P z^yLYpD|>`W=Iz;2nEP-|Cw=Re!;Vp0`<7Q=>X+(3>Ovb(j5B!K;;|kUehdHWaoQVrH&R4yUb3vuCJ$LXHr9dhlfhXib@9{_I!9TMD0p zhK*;E*UW{d%!Pjho1FBXEM9?W9jO?P*{6%XfBH&y*~b36uj%QC-BIPquf{FgRxRnh z&D`l=s}y!&aoe9ro}^T^oQKKyvZqKjr0};;E6~%5kjJ3y0C=WKEL6p(b6PwJOz4Uw zx{q53#mM0>=Y-kqYjeL$&RT e>H0daqbnj3`0M)E#ErKA_)$^RKv&6|hyNb|qva<6 literal 0 HcmV?d00001 diff --git a/docs/assets/js/search-data.json b/docs/assets/js/search-data.json new file mode 100644 index 000000000..8e1b98639 --- /dev/null +++ b/docs/assets/js/search-data.json @@ -0,0 +1,12 @@ +--- +--- +{ + {% assign comma = false %} + {% for page in site.html_pages %}{% if page.search_exclude != true %}{% if comma == true%},{% endif %}"{{ forloop.index0 }}": { + "title": "{{ page.title | replace: '&', '&' }}", + "content": "{{ page.content | markdownify | replace: ' + +Plugin Name +Description + +{% for plugin in site.plugins %} + +{{ plugin.title | markdownify | remove: '

    s9 zGeQ7VE|Q6eAS8%5qI1CEg+GM~;$FkVi)Y$kvgSG95<4n`La=tNIntn@^F9sX# z$HvA6plme~DoNK1n=U}13|fc)O@Fs~a&!c6o^{^O_VyB8N3Lyvi54hP0PVK18NO%_ zCG*?^#t^`WV0!=3QwZlKw8yAwP8GI(&9x7Qsd_{_?<-n0&^cOi0Wxaaa!6hP`>b_? zhNdP^-~fUqLq}QCl}g1;01Q4Y#k;9)l2Ks}6+Grg99ZM@ zl0e{Nytw~A9aSWlGHp66DD;(AhfFQGv$@;udL5Ncvf~ksy5MU~r678i!B!F7*lREat?Xc`nM+b(7s&zp$$xGW}4@~^HLO3#l!E?;2b?1!`&r31+ zbA_Fy5^3`pAFJ2Xm4eOvy!}I;>dU5{$VKTY@q7hJX?!>tPP3}MUtZ*`jp(z(Gktx zV7+DGkomT?{Ff;es%`1qVQxirjyOIX-J4*bp+i6;5gqh~sZ49aj*O7oX*->=Z1Ky#kyYUfJ z;8|9MSuO34*E++stFiIXVox`x7EhD9zvWQ;D(|JdGeJwDh%!EPhkz(Elm*@HIvk4_ zp%DzPS3>F#4^vhO#))#G4KfS}XG0~7i&98tzEdACzQ)jc*7vV^opvCOGvY;sz1F)$csr)HJ-lt?&D)F;Wn~70EA*>EF09_+6YRWc}AK9NBB& z9aBQqB$W3Ncr^e*#rs-kp4E!+Zc-JXwEq=_aaGtdZKLDT^i_nZ@^(cq5SUE{I)0x2QCR zylXjJKV7{+ZWL9qTRFTYGo$YOwGN|!`hj}Nh{K#>`z?A<^fE4nnUkW~b%or{y?H*< z^+wU^cVy$6VYkfB`kvm1nbw5Ynu?jk7{aEs^->t09~J#7HIg{2#$`9 zaFBz6*=ur?HpDVd)_NJhjD>O>ggng{ z7GO&h4N?LJKfa;ERy(5kR~R8f6R-O=e90(G*AOaqV@c*5GUGN;WyS^_e8#U}Ma}}* zP;s-OvfM{%Q5yBCQQ#L@exGwG204J08mzKs(uc^0gd8{((uVpdmQI;#?YkdLljSI?w0Di%pqt_)-3iw;?=3Pz zw$72r59eE=G|2tZ)6kO0`2`v)+l`RrZPh79`@Af5h4S#c+4) zsJdU_^T*A1J*!wIU@j%+0=DZc>T z>OFqtPEH9EpfV;Q^Lr`ZAWU4v#&V+m4obrkXRdwvVJ8NoLK#Z<3Yvo>vk_{<%gI^r z`bBI&W@m?(BCeDdA$_-xAXS6-4cFq~ zQvm(}jN|&wPJO7_cMWz^mw(iKr!hVYKx0v+U%UH9W(G0fkQr9=Bz zqs5#u449WZJps*YBv(8hAJd3mvq2}gFuG^TlFKkNcqIxp(zR^TvX>9L*W+{PuQ!Yk zBp65-yso#Ug^~qKoV-pY4W9f_CLOgSEItiOo`&9!@|-2Di@0}V^A_W0a9=TAz68RK8o9#N_?GO#=TRm z`ja|g)6+EO04isHUtZ+g_YUMeI0I_9p$|ZuIkg!H1X> z$SHp+-Wy_`elrF9q4B_;AQ4&c^d|kXWJ!Y@6yAKW(wC>3Z@`#$*ZMsNA+~fl9YuuL zMC+wPP8pmpq0Ain`#5eg<9j#zkcP{0K~zwl_9+Wjf@8cV^;9(^@;uP zv9?Agl?`K+k`QXfPlp&1sBa#LA*)n{KH*Rm6crZ($}5-JghtXyxM&HmDa*Qn%zX`J zV&1r>xuXLp8z>jAXnz6L9|#1(X)!i3HkMz7sO~PAMrq~eR%s-UET-$A zDptxPs96NA;f!x)!GWT9cUu;kMsZ?+Eo=o9DYg$Bhr*f*o70upn<7K7X^=}XrqHD@ z;IhfTW}wN$a5_p;4G^{%5g=kluq9ISnq&^BJZCx$H-1Jef^SpqbxSt8;B_>B|5z(~ zNLm2+0QeKX*2vH69~+em(sB<;`cK`K$RmmD51Ga<^}@*&ork%rCC*l|GGx>iN=_?p z%IO~ZD2D1eO3ejf6h>DnVbaJ&H9I26+OArb%Zb<&sqKW;Cnxh)$wnHb@JYVkp}#BV z3e6rWWOj562^Hi%C!ob(7xXwdo}5U=DaR=&jK9ROU)jjno4 zIu-YwNnr(4F?$C8DoozI)o~h%~U@C!M1wZV+`}a zikXB`Izgs16-7V(CkiWu=wOC~n+ThOP{yc&~x7k+)qb?tJ-yy+5Xol$Eo26q$e)gLz0^gy(Jhj6z znuEc{1j~}IQrvn>jhj*K!g?YIuSPA!i_wOG)VxqY&N1fu*7dV@$WR#dCbJ)#j~&yL zzWS%M`rzopqJ2sa{&87Q)aq2$ys~Ir(d%T5qXYv?lRG;E1=pxg58zPlgwDhqqKvlR z4z8U8CBM%LnbLeMenDwANzH0T^{i%iHC1U($241F)8ygsL)~5ePT>h5Oc)6ttvDCE&*_5@-GPJWbJ_K5t5jt zxcl87wqO!bRXXno0Gy^Kp>c`UXCMHeYWyC5whj&sJa)6(fSqg-PFFsDE-ttuSQiO^ zGbxuNz)wj@sXz~isJdl49-?Uds@+yVZIjAOKqism@qw!8=;_hq1MY!Pa$ka)J6_9g zBE-@C`_siWRJka7Z(zMrv$6mNb?VH2iyKu6#M$o;E`-3ClZ`AF0mYfb8C8bt6#qkZ zSirll=nYHEbn&oscnZ@|(mu2S>aB2T2e!sh^>S<+(0oSjK&iTz?}6o(<@6?aRt2$Z z>rpL6@-_Lml99+g6E|FT2hA~?EtR{T*@s@>F!y(KA5@}K#WxC~Ykf1f(Ct76I_V&e z6zDup)GxN#%(I`)jb@Tcs>>7Bjo37OGo~TDCQ!`Ggym#@C39@u@K)5HVRg;gZ(~1I zub4}z3JbIOWKzn-$7@-8wtxF%=53A5s|XN>|yUn*8>iVEQ!^^{AQ3|MLO}2_a<>kCL!R#r$H8(i|hZSC~;EhLx63!mNOgHFW!mP=NTTlK28Ofk1 zowur8do6hIb2lSE7Fu-mwY1hU3lwd&@f_ve52xqkoVvCR>QLqbt_{Z)@3S>AZgjx; zalF`suBbX(3+zy7RSO(9dcQWi?dSnS3m`A8cKU?XI+E;8ePs1H`+=~#v!h%q(?U`w z;Q$A8S5P%^Fz!(!u-)S9J79FTZs6zU4qoMtDd2}N4>P6=?`AroInM&F=L!u%lP6z; zdE#$Uz)r2wGD=ZoD`*(vSLXkr>8qon?z(>g=^R2j1Zj|#k}m1)?v`!|rMtU31f)cy zySt>jOS`I+e;=;Eo#VXouQIogk9}>}=>p%AYx$kWsL_rH{ruF#1^Pdi zA2mM=3dv^OeYF)W{>DP5&UyLg|KAZBWLKCyN^+^f2Ixc2&%W(TCjc(f! zlXnkdftXeFH?A!B9g!&M5xH8BY5gjMR$LMjhg|;|3JsZF4!NSl?fltxc)AHlcy>sxPrbj$)sR-jMHrQ1A2@uQSYzV`CrCdR_to&_d~E+Cih zbf09KJ-W_C2bXy!k8|;Yt-jlW86dASFB51KZXTZl5HP@h!3s~h0IU2IG3Ou{OC zdueKJMrmRUoNxCNl!eLOBS(sG_MH^R%cJ`-ec;lp2QgzYq}!R9QEguX?wS)9Uc|E$ zWjlNOZo9Xz!VOEV#3ewW@#rH44e%AG#^XnU8I{D-bIiyVAJd9W?)7ycQ8?j#u7N(_ zq_G5UshXm9Wq;Hr3QP-s)Esrs*F)iDbsg4^nig_(XF9r&yp5&RX2cB-GVWx;Ifi+N zrHCmwjE#*`Qe~sw%2oMT&4Cz17MxAy;kynOD6tvMz6@J!dsHq1 zC!##9Z_=^fR+4qrcVw?QgG2%+7kfM^)oF}8qG$4-6OJkAwgca}NJr#0Ze%qcE0Ymd zDOgSTH6!rIRSaP>B3MOyh>9o<+fCsp7|wj>k5p^Z7oDltdUtPCchOV*d}ZmivX`-p zKrLnFNfW>Nqv-NQwkb)Ue=rhz`unALdy1s;;4f^2&hW8u*43(i`PA>kL+cy%F~!vj zfU}p+^}DAe;<(0Ng^$IO;{OURkti4leOQpn)=o{%TDQ0nbEeSlCJ^&}`}g{@0qIu1 zBbaq3(+U@-zAUZI&kHsAHtI@ryc{1_Y;glB@z29yIZ(WVmUQyNua=hO0~erCjVAfT z$;CAXX4`DO1JBi>6n!r+i-6(-=%v_oV1E3U&+L01q40Ha8eAFRLo?<8Dy+G6alt0g zvvhI;Y!?2Rg^7Uh%yhVxYtmu=8NKzs{j_q*kjW8`D8Pm1{YJ~#%D5(QY^C$-cV{woPkTDIp#5l6U zaF9Br{}{JBLVq&Kn@>%}{&pC*J$WTh$GydNF(93G!6Rl&Ql{$XI*`9DlN^{u{e)v` zK*LUPq!xSMy9uS_uLND(e2T_~L#E^WLx z|AVssGxb&h3l)9(JrzMs4JqXifqM^r!U4zRGN)f_3wpx8!ZbLZ3i0~%6P`={(Tx64 z_$FmW*OCLu;6%9r=@V)CZX54}zS+*fY}h1x*#)99S?TiCL$2S+%cM`T$lqm)uGndB zx4PVp-C|8>eioPX-@+W+qfL@UC!-Xxo>@Lrr^8|jI(v`Q{;%vfeuMFkF-|W%R1oPC zkRAkP%iL`61&JUc`d)iwg+kh6ngn%|Bn8Fm1QBt=AEPARnAr^10-;sl{v%M}{rp{9 z>kp+AnC<@x&VioCMo{!tCjZx)yYnsZQHH;&ouui=eD5}%A8&!=xUsPjTrePkC18DG z$LSuF4}c9X*iw`OFBiow66zf=XHZdC{yOve2lVi^wv0dzAty&(J?NMj6%_?CJhHM# zID9{R_yDN&{aWyAI`|nACMP=i`mVa_(WdW5!wmOBX+|c&cm~v}TI=iGg@Cl6w5hZFxX%h$lvRugu)x z=Rg(?8*X$ccU`_M9j+@K=9Upa*ATlVZoS7Z`PbYf#w_-2#n9UdMYCb|QN;t_SxH82R-aWOY9p0vz;-Unwxe6#h-(tqa%B;HJ_1R4E6 z)b8qikLW+l-2OE7=`=GtTfk+1Vt1FC(-1%{@iI&cD=U?=)*^_ByBMT=+=Nkp-4xa_ z`dO(;4^C(4O!xP2csh>70y31pI^&lBdASl+7YWs`;sRg`ZbT@pqUSIDP7)L(Tx0rD zc2unOzw?-Ya&Ks0{e!}<_V7{M;@#r9Tk$~93=_rS0b6kiUu|-}i=FduxFiMdd;#tB zpQSLV%^x_HI&Ph{iY`n5irwQw6@!GbpaPaj4^WiDwcUzM(RkAw+vJ!DkuvCZ)|c}( zL!qp-98T6+j+1fD5$q9lp_CHr>RKGS)IU-`^F(S_a%|>VnslNn{-i?dx%d!4!z(SN zoRTTVm`YuTckOsfaIMPErO(FN<*gAps9ZqFKBSZmRm2UMY6{HdCX$pudM5YkaoCA%=*xaPo0O{T4XMQN0IxBLDmblPS#aK6EhyMqcviwGd`KqAO;P$R~r>A1ST&`16w`UOteh5`y;-5fW z{vX_}q*VABIheVUb!1_-kOu1aZ~N|CD*ni4tDFVxlvokg-5?{stT=$cffi4P~^yf7@O+V91f!KWprxbvy3bHfx zlSctkl5LDj-kz>4F8V7+ z>{2@PfD*-_WaI$VbgVbGvarx;X2nem+Nkaj3EQdF9|{awV~Ujbd*+gC#{4YqKUJu1t_|qbB3qh+dHz(DbJXPG0 z#~Yhm>BUTE3hFRyq_MOwjtuE!OiERIUa1x{IrhCpe$?W$TZulcC6vV_0|Rr9S*elc zweiV$I6GQ>6z{I)11S+56ywXT)JG?p-5mvaR5N9$J3Rsu5pfK$)5Vps+0+)PFcUKW z;I87N+^TG`F1$Cr>G5XrneU_TUFbWsZHr~&W|N3_?4!H5lyxe$9_3<77-ibRSv8I9 zN!|U-wxjJwww6>EmR+AtDo`kC8K5jv?P<;WVjS z?~fCq^JN#4VksOCSi-Sk@eihx*{p+vq>}-}0sC02}y_kXx9)yllyl`&!oL9GYtw zg&zjXkI^nd1ep=8=!#aE#?+D)OQpu>?f{u=hAiB^Puv4kxRzS#KmsfZ#q$IRZUDuC zxrr5cOL1{=g%Chv(@{9NEx^x@mV`H{1ZHobBwjl4=K_#j`KXST79gPnzTViD&tCA^ zfBj12`3SKDHje+4^N(0cz;A2=;F;7yI0fq><%Q+tE1!1ta$zWVR#&}-xg+7@K*aDZ zDE5C2++w;ok;nj1qOTZ1vn zA*PtvTq{xsQ8tP{8WUSMY#}_9G5+i%6mV-nB4t4Qk0NfT)kX&IyN&>Tbo~ZXdJa<= z(Nx3Hd_g@=Gjt?gS&|MvL8+lBU9>mt?RU`?Op#C)!yW=0LOO~qi>aA00vgiOLc>Vb zJotKRsm;SCGBk^%L0vk`aW3UHJpw9%o|iw{Lzzb2#EWbel&OK_>L{E=w8kH?jNtHe z4Y8-aaRkOfdxObU5^{`TDEwIhb*Q~ewkFh{^2FN&Myv5XmACe60{Msi*xwv|$u9(T*a9=z0lCw4+V8>CDTjk zUYLpn2$TrNyCKJ=;}9w-Gh~!N#xbLACE4O(W?_9+t0v^hqG+(=ibZYMN=DQ>c;fn| zuJ7Opn%~k&S$C5qhZjtJ?Tk$h4y_#^|4I9MvC4AUUd&@F14&MAE~<`hG>J8PQKT3l zS=^8MTrpTIJc@!jc9W>r9QTQ3LdY9Tr^AU>b9#*cxe2U zeo$YxxPc%Qiy5^7c+~HUL2(0o0KfzF_4NhZj`1t<_uF`1pDqP2)5gEe3lHe(>Gj&G zjb8%QdtaYKrFz|$ufD!7K#R!E&h7y7tyYu*%y6{lz$M*%|4sQ3q|7<2L;ZOK176i! zz$xyfI8ZVIq7gM`+P`s2rTJghiTDx!X-vv5yA8FZ+F^iT;>NJLY3;t1>{`p^&gyKB^Q zQ;+u%*Il9c$S^5FAFvZOS@EL^S)^peTr^`1w>YOGf2aIblE6xjRciJT^U(UyLKK`w zN$vut`gJd%0JDxmJoK`;njL;xEN_~)y39fX8iuX*Q6fZujj@hfl>T55TWX7sO7Gc3 ze|8>WWa@{h7rU9Yz^AU?lv{D^1nwlV*a-E0ST;qhLfYYyUgmh1YykI zS&h9ARQY&BMqOq4zfxjsFeUM9wZmj`(F6Es9x@^@|*7!m$8p9+8oNiclcF7@?5 zM`C=Ff!6Q`2xOV6p`g$KS!CvanN_5)(A2pI9FBvc@?)`PVhq6&6$zI)w})X4g@Uu#&KhZmDv>ufvxmRV#B)4DMrv zDf$pdhoKXVg=!`1(c(xK8JFpn|NT)9@)sE_muG$h<;J@{e$d9vxwcNe8l8@AF%BN` zPCCnrE&HrFl~?@ud3b2olp$_tsd!urtpqD3;b0(v2@Ur-S=gImeH}g=6~-T>Yv9Z@ z5%U?5iIy+-K-eP(VRR}&&(u{-UCoZme$^*}$Z_m(i^y>^GxU#^&ZEaZ+F~vJrTOyw zMITpN`zc#is*en0139IjBTUJh5SJ?0=+Dn?y?)m+2=OfgMuwM^bUatD_lm3DuZoAK z_Z#~0memRVtg%026`5!wq>TGRNu#Mf*>4t92u+m#qEf7)C1a6$2lgZG;8X`7Q@|Fe zmJ(BjvzP@?M{2?<;Jtj%tBi=`t@`+(R3Sy>)zsQa0(ShcIvx&#o)Xt5SXV$PO?ae( zw=l0zKz7&vv4!q@r$ofd7yr8HH#a#fEfMSI<{5H%=r@|A96S3`JZ*RUTlsq_>BbJ#3AiO8sHYoec$-E#+&_#>XnOVBa zp0#pA#Ttl!WP-AKwV`Y3KD?>Om|U)Dy7^Ggcn1~4cP@>Wx{tXONXH(kJkq9Q%6!T{ zFe6KeRi=u}BMm}-wye5YAR~cB{P>C$$VyNmp+FKjvVci#w!}$a48i=iPKo5{+(*KxTF5n_CZWMK9c;^yFu1O> z57&|RZJ#|&mh_VwYF0k5Uv?_94AWqR0co(ybHV4B>`(6K(#xi7NH2es%Z~s36G5D` z@(<&_WdC=6~!;g|YmsS`tavC;nR9^c8 zq9R8k*2^(vEoQn)iBedUIOIXjbQ%!JA^~EBimj-y1_6dRW(v~Cm{LY}u)_kas6H@2 zOD7RfV+NvZIHd5P8^>?|!ugYsKM|^!<76s=NRbK&R5B(Ewql#+V4VKND8`tcdOW;T z`ecx+k}D9{8<>nto@(fS$SNUHrj&wN35`G7G!~G-aemnWm*mKuTEPY%9*MM}^$NF@ z`L#7#KmF~F?%B7A{GNiHREgn9S{609gu_&I`iL@KX^oEW$*70jDrkE5R>IJF^x~us zpL<$jq9Gzlu<72!RNtqdmTL*A$EonsY=)5IF0=3=CD7IoX z*pz1Z4`*}LlwjvokCuvln0Li!br2-PxChc&y;=3sUS%{3E@{cLW;=(;5a1g&Wdo4K z!uFWfhj8X9ASAq-@vzDh`j!{##Fh%8Q4puw(5x9Rn516SK zW6Wu?i@(wE_>KkAWZ|V%I#eK0?}Uvc<7GGc`rvERfVc#X0V928c!y0>)a9d5HhMls z&Nw(JAh!;nbti7nD|XE%zk!VerWLv&3!K4VB0GHa5MVdblLOJpk03PJ2p^0);2sB! z1yq~lZ+p%R#7l(Ta=-xtSLf2vbq6FM?n9FFvoD$A#rirFNhLT{;W{3_g(@hfagM1? zG4K~e86&O(O5x2uk;X72A)|}bYbVK751je4z5V{QKMf-urAz;WBUC-rF6rHoe{~Cc z*BkS`=;F83tb->7Hz5oEK}Nq{=Q#S01lDdA#%XD4#pk54!s#?w>V%q#Kr5}{B*T&1 znRkibDYkXFmv{UhPefmySI>6WbP?%ku~iYJ;ofBR;j_whbI1*|F%H+tR*;;{oDEB> z(W~$tzZt=Nr>ek8Frvtxr(=k`AvQZHWfhnRe~6hP`#tbN?hj2Sr7X$L!+QnDA+q0Y z5Hs8h)40CqHvDI-K#{8q_a9oZjq*5zk&@(PH?BJo0ymgqJD6`(v4ea<45tl=nGh#G zaXw!=V6-Ig^q#2_P?i_TE6Q7zBipOYyl!{@`{sOQJw|Jih$(_T=%M@;-FXT=RK2I; zW5CnSTzI@g=-Vg(ETsA&RZq96P)$M3WcrzMMf!@Fs*qwRj?{66P*rS8kDkhJtn&S% zynYpOL=>IKVu$h$)UZavwj|f(leqI&MntWuQPa+hfDKi<&y%5KF6DKrK_qk}m=Cv^3Sy@7vqkxCq!2 zx(R%NpxL=MH$~G22QI+h$od>|&z~jVp#1@nmRyjZo4X^nNtGTtU3C1g>EHQQKRF*< z7G0nvXU4t)VN8Fq6>dZ?(2PT=Ed5?O`Mt$G@y%Gjy|wj(8^l{M1(pD56j@9^@VW73 zfmr&Zs&-N&bxR}h{n_W+HG}fmSefvZ<7+QNsqcB0_k6)G|La3Qpj&lDvKes29JqwX z&H>>|d%OLTTc!G&KRwut(pn&r0a;r(DE}jJ{;FHE9#hIB-c|K0F(mnA$&YlL<(XJ#V$B^-4tijJghS7kEpv*SExg<*#2z7 zJ~nNJkp$HFr8Cl$?^FWHqEw-y@MZsrHu!*oj8y9T@E*i>=&?Mh98?KIq7^-}_dU{R zgULVU8}t^pIZRwWmd8c^=njTUO6`O-SUq=bZ-j_>*bz$J>4Qmkt(%B7+@s zj-299#wJYWS?^l+FBeZ2!;|m9jJmLrJn>CRp_(nKUrZiB>C+%E%j@g5N%r2o?olp= zKlog;mFe);;j49NDcx_Zuzf9r%OSoZH?FQg<#u~_bXpCXJ7MJz`jaazA;IFq_uteX z-iA!>d_tr${4SB9^l?M@i9JfUU{CgP&sXWHy`y+85D6rNI`@;f^X;<6Xc0&CI?Zm~ z+2{rs;R6Txp<;xf%D`BKV~|+Nf}%;8 ziYU@0$(u8N>%||r$ZABJG7M(h&btW%&Wur@U{c1#QlsSG5Ji&(PIS2ZkEn09Hvypl zlM2qWaV6ju%a*7*_2H4fSm>49gOM+E?yQE zCHhq+M4-gAuYFcd`T|V9OFK>k&&shB5RqI4poUlvLkJM2PXg-nXWuo)Op!d6G}#;Q zn7j#U71~v;*Irp$qw&osH`B_J|7?!eF%ZM8wlD`1KkJxj%NfBA$CYZ!p=e$`m3hQ9 z$&d|iW-gbclp`3h>yPy_^{e-O2!{$Z??g@n#TbrwdRU;DmUHtB2qZEqIntne)s>< zJ>*dnX8M%S1h0Tfo4^(TB`;^OUymLOQHCVaA0(;f1!CmM&Z2tjxj=kkQu7*#JrQQl zvZ=Kdi@wp@J(1}CiCbpCgqdj5k+b%+vW>L)_0~#$to+|EysmQ2gekaQc~=j)nWsTt zMiY|D_bIa1A-mea>pzO%DX$#-U-7i^NU4fld88sqnQohAx@AqDrAZx4-+-&_5HIpf zU0oeF#JI-$O$}XgeSQ6)sZ)`SC<&%&o^L5n!pbOU$LQqWU3R<*BP|}dfJ}MjmXAO-uYSlUjZ+EyFUpmO*qwWao*F)N zGlo3OatM-tAj}J9p5!85hNV@evf_ROb7EsXnGnuMkfZ9GKxx%?Lf5aqPG+EzDWpON zY0%b%pHe>+3(~<`h7aIBLLL)&JyWpt{ z11Z^!l8HPXiC$JnXPU#JPK!4S9uDOS{w|1P8Z;S$riwxzNn=3f#Zabl84hLkpeb9z zppeM7U#}v0)jS8N6;X7VKg^T1)8AYEkW(e;bO zSSxmjJN^$!S9}l)G^%E-M+eVmVFr$}j@(*0Yi?qgTv3Az>7ova_g_&;;1_B%OS%N% zcHz+!APer>8uroxQk8B!ELqM5HBxk2@p#+5=X7RF&bld$5GvoJ7PvS`L`xLfP+fMhh3^1heu~ z8zv$ml23Y?GB_Ga6^VyPW|4=V$uSA(gDiaS(9N2l;vm$Bx9>UL%u~QHH^N}LXruc% z=+*5%v!u{q-+I@72?^((Aqg(g_DYSG3yAehqC^R7Ojl)L3&!<&6*6ToHcQXjBKzeL zhtG}u-fH$<+_kt$hAY4s7m-GCq;J1od9hKwRj!lgx}Em5j6@MDr}ZP5b$K)0_zy+R zuX0$BS^Nni%VdBg%`l(l`4v^Y&+(A<;?=wRd4`Ad4C8Sk9N515paLo&#KxN@K z`#Dyx+8+M}z<~!J2p$3g-gpPYSb!WK)2e*0cNwGE0zQOZ6Hbkp@+BDP=n(a!@jd6p zOe6e+!9w+NvpOwRogF70mOm_~?`5GpVHDda{voF+hDO7{!?{W$4(>Re<#ayH99 zB7gu67Y;&b*aA7^+~hkEt_63(+~{vAls$FxkHMCLUp^~-wCIaiz#XW|OEg|YLqN1h z^kkD|LbMn$V{#>)bA59-v$MRzw8yBZg*Dq{wxoi;Mcj|6t0?hdx;Az2!!YNUX-?aB z@)V_z%;wM_<4CVDZ|upJU@H-G`j*D#n5EQ|R4FxuItV4@smkftk4H-60m_WhrV5U# zPiQllGp|tvq@9eV?N+Ogj$=G2JO)Es0T;C7{=eMbUJW21&sydyH~AJ8zPe+E|3(Xm zSH>(JC=@<)_-jkL2+8}Vw5FqgK>`WsYu9g4{nl1*LZQ{9$+t&TxM>KP{a%L0Jl^t7 zq1BR}Lto=7LSd;Y#U#WKZS>!BfBM;zp3OV|WH12fN>pAt|AT?=L6CWDn(4PY3QRXD#hkl zszIL=5D)-txhHPJI~R-p{nM_|9ND|vI=|cOjR5Cr!M4jW$m)~7Ox*&btt=u_Q6dZ; zz{^BGqZrTERsdvyl;2A=Jq_{+lv04Tt?M7UHHU^0qQVP}&#R6c1wl%k{sX72#4`mZ ztSRE4lt6Eimj&emJY3}R*R-FPI8jZunRDfh?qN=>@q;&p)qJR^gX4V(N;bLUo`~Nr zdd!hgGW^AfLDARb+yUm$1whUPPH}`rWBF_=Lbn54U<&1ZD8r2f-IQialN9_**H&`^HMh6-I1YebbKG?sWV!TNbSHSpCDfO z=4phuv4%GGY@pz))^c#1C+KrN{Id7+$$e*`{oL=VLqV^>j(@q~Xn=@+@5`yrAX=C` zydmqu)Th;lof7Y}7lW@N(fTX&;^QVthE_i8o1$roM`$04un{gBSv%r5saY2zp8%~65g2VeR5|bs61=^!a zxoiedUN$(E8ksn`$|F~3-7IJcZ1$w|{<>0|x1*)#gqU2es`2Kb@0M-2DE+bjxz3du zK~b!WWu@_FEa+cj7r~prbIA(Rx;G+fs?E9Tq81Yr^|0XQ!6Wkoy#udrDn8(i?nM0= zh%V(q_(rklYnCPSCnYD<#w7ULEe8_}HkKlj;2)=@zkL{H(sN-+{fc_^`G=I1Hp(R$ zlZ)POmcGX{edDQ{KJoc9u{0e9slTl6o*skT!5s68#pV^d3;^|GJ*LRLZ$ioL2W@@Ize6WAJF(&N~KCW z|I*UQzqqH-hey2}9(XBIu=nQ&+C)a#v}p_7^Oht!o|*_1*fOiwLY^c;JELWZjNK0% zW*Dk&=jU_}WY?MwlKh@B*7Q3#@srJ-Y&wh2i0CSE-=|8w`XMtO|J^OU@h?aTp>Et# zW(QeO|L*l_-7cm5AtKIP{HHW_+UpH)oX>OGZ;^A>x%_Vt2c;cSKr+RcXN@M{0|s_` zyb1c=Z>FRePuObVQlznPfKh+J7I%NbG1IHnccUw4($eK{hHki4q5yNx+sdj;yAp(Q zo7XkAv}6wN02}Dbi*KcRKo;U@TYEdk?L!zgfU{sJZb6dw*}{9$b41t=05hXX7z8#z zQ7r10-(QBWsKlUMcu8PIzS!9Tf1q?xEf5$1rQ$A@4j`K{WT`Ljy@4WeVL_^78YC~m z=q~+60dBZTMDjt?T2*>-3F$5s$T%1aLbZwopdCaBz;B+7+_ds@JL5ld>U0g`(e_|M ztX0=p;JR81sbKVpm^#Bl9Jewj|1Zi!UXOn%2;oARG^M#e4i;hp3uz6u16g1KkdxAG z^t1Ra3)0YZdF#G>Vy#CrPY*sw&s02QCnsfbB}s7>h86ZN8AJ^rfc2DFe*5z%J=g|6 zx-%3{o0)bNzMcceuq^ST*LAdTSrp;P&tN&_h0xMZW#TOS*GpEKv2>(q&yU@=XBuWx z*qCgogC#8Qp&!E4^avtQ@;X!q1LLicihRW}XG0Z)ugXf-16f5JSO;R@=z}7iGU_MW zdkAXcK5xhR62NUD3U{%@L9n#4asueT)_EI5Gyh$mByVoRLYo?hlqWPkOVod3&nILW znHtOK)>!r+y-&(tHj-Z- z)_gCDe>Fd1*n8i!X}_*C2%aL{n6+T0Ek8ChKb$PM^Zk5oWd70^<8^J%f4S=3@?3D6c{Fc+-&fLp zHp|@R{84z|?6UnSXVq^L!Tx3O_2Dj{^{G$?u}fd249P?*gsLXLXQ+ z%5E=P@U_+5ZyNb)>>ouqMhXw*AvSB_Or>jptULQ(w zR)~wDSMR49o*Fc~zskLB9%J%8j$-ybLHKuoXZMnwj*a6+rg%&Oe#SPpt;U_WI|MboW>41mQ@_MqN%h?6+B<;|0kN1W3rxjxsFgV1EIJ z;(P#vBt{arVY%}SeN)1&_PK+8;?VxqugU@aiM;2&B3gGxTR@w*B>i5Cb|o@-M>dec zZ1u+g#V82A9Ge2^A)QSC7*faDf8nX%=+XW4e>vo9W;d*n|IZ#fG!+%;T4ZmrHBJ-XaH(s^a6IKSZgf( z7FH4+LHjz}-N<01XBxIY}S0=5eVx$KB*gR5d0hAt1Gd3g4Er6A%LQqQ zgRcpxCePFtRb`+FXYs?%kQ$-F^?;{qX62N-at6*1$a~)c9~Yv07S?=(qMBw172%GG zW@tQWP2q-j`2e|k9Fs|+a}^?9Gj9FK^l&V3e?Q8^H^|>w5tn@aJ2{n1SKpp5ESrsP zt1jq+jW7IF4>jYjUG}fHuV;VvG9OoN?N;s?+OIx%(gz#71k62m_FA-WJh!_hxV~() zKQ?haZ@8Y`2kAWez3w(VU)E?m59(wmHs3Yazx2M^czc#z*X`oT8@%2$v>!|Qhfb#b zB@w*+J-4jNmG0jDSa1LJNO0vM`P2?SFm`a4=G5uKHRrh#dtV8wJrnzfYd>AT`=yu7!Kg`ozlR5|*T4NgzYaTV$USaayd0W* z&c1tM=qn~v>9rpBJrxXlz3TzVAtkT72q~$}uj4UyHSRta3U-x^C4yHd%y;*50xy2; zr)h6R5D8WuC(nrl9u5Qh7;4-kiKU=}FoxH|Mu5t1;S8y2M632Uq~!UrOdI`cGC zIEE=ecne|SOPliKnPo%#lc~E|-tobGOHe8Xk~-j59yWMk+ntLICk$4i#Q`zJrffiP z0&Jre76|L8=S3%OORjn&6IJam4^E9OH8qoV4Xn7IcVBHeMN{}i?tnm?IzdVx2LV}( zmyXk%n;4+}J3D4$_rNnEgpUCahLV8Kf)A7LV$5txt7!p5d3g(MgZNnu_V z`(3x@FX_8eQ&XLtol{d-rDpq7pc8G?51|_1kQ34;wm|#>@@hG7_sQaF96o)A_gBTE zR~W7pqNKq>`u7&glSNf}=jp)Y?4asGRY+5S^ZKt)iKqFqX5GO|w*1L| zZ6kP=mkHeUI`t^Hi*QJeM2evhqoLb4lHU)6!A0Lgr8~7NsrKb!jl(ObA(jMwLhAJ= zR`r4Ba`IbC+IOTS_Sb0|S=I1V2FO1Rxg8rx&k=SG2TJK?t_X)b0^v8aoxeZrs>Qkz zht=KG=+?<#NhP(n23tfC9u^fm;gUl#Tw$z10HgL=5$FAEU}4QF;g25){3`)8#L*%u z8+-e~l8Q;@xLphl%1|H7a1fN=6kld4Xv@5b`do^M%Ps*==*6FA9~l10U7vv9msCv$ zN3vfO|D3S@mx*}dLxRibpLjGI{PzdS7CV2sb&L7y_1@vK!oYjlVu+==(Huw_VPydDtXlv9+95oti7WUZ1uWnPNGuO#5AZ61;d&5a7^X zdb&%S#cSF9-6TGEetI`q@_L{0vJ-EA_1B<12|tLYZJq8jRw6`%o#xa#-2K#d6D7Ou zDxBF?zP&k)JWx|c;dP^gbR2*CE+MD(qEkWO`d&d>ig3H{lO2Qa!;9Wy+19xC@p2g1 zYm&Wzj7t1V^6Bd&k?(`3fwiDTefHyTuGi}Z{^gFYQvUP%@h$`Vhqe^KQxfKf8PNm_ zb*#YHnNjAavZWz-^6gsBpXaTwTjM$kK1#6eYcvzT-$OMY5`rwi zx`h$*x-{8c5F(Il))@{Up6cLpk4R`P2g-b~+=ia`3cyau_rC3bD`R0`PLj45%hb}* zvEj@xbRg+(blC9U;@%t20V^;N5D*|A@Pog5{{;z@la}C<-u?W-L0BpyZaoW9!KBrZ z$iKD!_oA*{r$*~~F9!#ZCl3}k1Ap-Oic=%%mv4-AAQ!4p_veaT!5#8vq70fCLDWaU z-*L$~gDf8kJmwgijSxk2$^Srtw~$5PXufAGzhz&lInf%*#+0^Tx8QW{pSEgW18chiUJT9O z_%8-RrdebIltj#LT+El)zarZnHle%gQT%~qDh=_x&2$nDV&OYR`#?)8(ANU%MKv0x zJmj6jjn+l6^Fi6GgVNw&i!0Frv$97hi2}>VSJrsSFA&mo{Wb3wD&5$1D!E=Zq(V;p zeUO%lbP=YsI^q3aKMW(~kGoRhG_}p_@c7tRFaeHymZ7xRN`^mTj>}ZFdM=75W0{eZ zy48*e*Ua5Azm56lm#Ore6EXi2q z@*$<=#8qJgTck8?6ix7lcgcC7h2TZZ>Q&?!sZdh~oJV0-i7%fS zh>aFnncMK(W2|m;9oV_{-?lxP3BKqP%eYfmH$*SnNHTCUiiY3*^L!=py>89<({9E- z^vHj69Oh0qvMGIzjL|afRXY3fG`{kpSxVefp<+TqF4}ed}x%pLM#7nFDz9fZvNjAhKip*yWnzUslO~`%a=$>iWfPw>I(uj zE`5^7H=NaUXQlvofZyjSg5aX9b9_Z)1S1=p2#9i-s-m+O$QE8u4-ySLRy+0p8;4}V ziB_e14!k?to~RXmQL(?-9QSF}6%C}SYo+fQ{ZrGyGiJ2({dWmjZ3m@ z6!xGhTN*{+7%_NMXr`^ImX2;7p7qz#Mghw+LM)A_d!L9nUq;;D=aADJjfavO?ION@ zLD7~XL)eK##U`Hx=PtFu9u55gk7DadrvyVgOuJRy+eXvYEnZP9jgVz0`&6ed{vtMC z{v=S|9JNf?B6T?H*pgHyMMCmWr7Rb;vFkeC7>vquSzQ4DI9 z@`POqjyhB`*S+*~JG`!=0i=^~hlF!@c$a)Hq^{B%Ff$E-SVQeDI#sqvI?JGpvd@T4A0|zHB$PE~Y#98Lg&kBB zSr&F)*MEo_5KF6vxSx{w?X4Jm?W$_K)Uant^L~8K?6q?P0%lUUycHw4cWfVm}j0Mx6`&HXU59>Jk(17t{af0zg4f6c#8}- zcHjOq+>S_&4ycNCkSCfUUxJAkvauh>;pRIDdS zYJ5cPuC0)z?#6$E`6*4dZ_BYp6QoT73DHKagGwI4TO)m;U!^l5$v?=d4`-DG(l}A)F&|>9X4G)*mL^`!s<9I%4Nb<2cF_3Sjc1!BJ zR^}TcILU8VMVEsH9|JnndrLT8+6wH*HH;CM)HVuc?`g*ch8B<{&cx^h6y-!%RewsS zJn-URWr)8ml8<{WGBW-k7y%JRqG216=~X!V>DWc5!DreQnx>pTyJ}!vp}@3LP%@;X zC|W2|B5|uRsVOE&5vM@jf{z@*z0GK|-00P7v(cm~C#W_@%v-$?|4ZhY4%WRdWDlN! z*WfMyETkArdATU}JxGdae$6_4x@wb=yh+~kJ=!ktJJT@WuMTqPe=K=D9nT?|yfA6s znh$D!>911}7JIcJd%R2b>9seX7ml|-Bo}4JTfG_#^n)ggucG@-Tz+muH|z4^tG;T8t(AXd{b^kG)248 z4X8=}lT89gSD+PLljMMhIEuGShqvTHAWiP9wNWw1g3qNA(!}BgaAOJ*dG#HL8yuke zezJ}YvzIbx3ZsGP|n#kAb!_*xcA-N+<<)*xPh2bfHW@_7j#>84dAYa z)&$9O8=<_uPk+8FtzCRr12AHkwDQt#uwS9S;L^&^kBri;WEzmept}k&hcebGRN)66 zMhGe~kCQ1MDY*1?nGo_UTJ^b5O<3@^op?kBhK8gCa)6``l#mXb^bjxzoqM3l;|x9l zQKu<8=NnWTft+#kIw0ELtpxi2%OD{pN>TC;D6Q%MsB~l1C4$NY%Zak&mwvCDxD`R8 zEZ@vO+Vc^_Y?Q&k*(j7qk|z~Eq}6i2zcJ9YE1v<}+R)rk*ShuE0Me?P+voT!>zlId+UJO_9=kUT_nEgQ z9r#EUim{indD($)8@2#OF%X%@>YX&CEoqhLj9o5KY6ek?-;@;Kk8yYG>jJeo1_5tte=wO>NaVJvsQQq`(Tr2Md|5`J3&$xB_b#8IWSbe8`m zfR^<4!RfE!I~&UN%QMDG7M7x#john=o>It6MuU4w?(LvW1a|=JwR>C+uX=tSHJ#1z>}_a!`e6UMU1|Rm{a~X1K*a33_G#@V z|MpZ~v&n14B>Q?QBgc?Q@baTz!@W-X!=}P+#C_7|6*o%PU1^@4`ctn-_O`p|l-4uR zYh|O8xEO7j?B?YhU7xY4mNDO3vX@Pa)}lS_``HY;*A0y)1d)O6tsvyQ!O!i-8re6~ zf`0u8Hswi&Q4Rc7A3Wv$-d`2G4(B|Remx<|aomcz760Me-O#q4vi87XHXi*v-|TzT znexj6DP^`aus9E#(g7eie)kDU>(-&U01ihJ&9zu46O1Y-26tT_8kR3Q-e9=!W&r@c zp&^7Dc7{t(ofb~U-i|LVWU8s8hsh5Fn)LV7G zUc}%C3?IS;6l=NKmH7ui_4@y4I?Jf6x;9$V-3`(uARQ9YCEXw*-5}E4@lXN+(%sz( zNO!k%cT0D3*881v{Nor3&(N_qYuz#DHFJNW)K}a7`BF6pW`d&qpix<{nLThOG6CM0 z@K5*NnOJH}358RPXH8pt#dh%hXwPMMXiyabKVV1w`_$ls3LwRssw|IbrN7>P9;At9 zvfDt6L^+e1j+k-de+%K8F0koK{+3*Cl^SA29MYL=MT9`u6V$+EVZAg3+W*B#4^wvY z)DdoCllYE}9wF*sWjD!bJTndHkMLYRSu}Wu8G1vj8iy*AR#eSbEkvGd=l&{8xDs1P z664fc!7XE3j zz^K78@~g%M)+QM|Ha6=$&f=)Vg5~HQ!C7q6-0{zO?)Q{hKGG;=GO=N(OywCWib0ni zw+s`Q=vO9x3~G*p{b2XMtUb(H2w$e4hS}o}y9)veKm$o z%0WxJXFHvU6fGMeZ+3ln6Xbk0akJc)x5(#g|FFHT7`#5rb*IyAaY2W4Y^%!kZ=Hi_ z&e)g|m?bv|F^eG?_D4hM=cVECuIsXfLMh#I00JIX7KC3|fS==8xj>DORTpX)#Axcy z0aq@V`7$TS6=O<8P2Jqon|%fn(7%?VcGWq_#a-A6) zqp7CG;b@*?z!b#w0i9`SMGP0zzHZf=;*>KfqV3z{0!newlV{LsKre`C!z5!Mz)o?4 zq6MI~MZQa;`Y)q+0 zbYahf=EInUE+%3jH0P{m_WnlVHy>D@4*GGpM(4_A0+d~cdC9FA4N81@hLGwK&mr%= zG&rJoFU&8J6CQ!|we&S8~GY!0PGiv4>6uEPdg+ILTW192a__J@X0ym#!ib}l{k zwPq0V&fS3l0Z81JmB5Z}n?e{JXd*aM6pE(Keq)Aq13?~xH+b&a*>VLxtx~~#lu-~j zxczj0sZDi8VZN|pdpoEMmN^lG(PSU$o0~yUQO8T}2dHI>_i0j4xTQJS(w2Xg{xd6C zHdcONO#&wozy<#zp-?}fSG+~kegYP4_v_P@d3bYo#bWN{S*}ug52h!x24)mwSbfrpBY7-GZMMf~nCW4L zORnfz#tKS~c@11xh9}MRGYwd2NrpBaYPe4{(7T~R@Z06mjlEPNSs&uU$D?FPt#Y!I*y!g-Jd$jwFGl{RN1FJmotzgd z%fDlF<)bMGsdN0pl&yRwh2r=~n(Nl^lb@&ZWiNiBU}Z>zaQ^B|sA7?U*YKt9)w6{r zne~Zm`=y)T)5?t0$Ak7Vc^ML)O0!0RRz_`QL$dX^-jGgGO4PLg-SgP3k8QXk=b!`x zOK4B&ejyl1@K%5rPi#`*0yankOWa319@VHppAsrq z*5F679_u;z?Sq_|K6*8~eHH~)k6Bh+XeRV5Q655dNhj0+-VWtzphq9RAJo8;s$b9Y zu^ZI=XLuB_(~Jp!Kb|0z-8CMg_J*;*W9ZT4(yndsNNrd2zL0pR_$VB+CrqDRFv2+E z>?rx&Rg(827BzS0?RFxka5$$NGOAMjW(%^*=lg@7+|ypA+J6U0oiM#mIWNLd#n^=E zwWu82sYhfZZ&Z(URanndX7N>NYV!-l$(TZ`t(FNwRGQ!7gk|PgIxz}&O9=j>nk|r5 zx|fZ7%j`-?PI=_6TJr0_8ZQzHQp4_!{w-PsHNBQ4F@U%R)(7W%wF=(5P5Tz#DB$~IFczk>e zB+DQYbg3RtICE6A_4Q9~AG2|Q6VaXu272-My)O#Ye^`U}X;gzES>qpmTwYiCk(Yxoz zf77d>ki2F}x-4XUXh(>kzjJDfrgGAMoYbEcLYE<8g^No^1de1FBP$oIcUgq%mPvP_U!$9Wz&o-$am*N zHir@Xf{u^&$%Xa-Bn(#uB!Sb`bw5Xn=TaJ>*x)5BHpB6a-vx@3Pn8j%nEMN?eut@#$(-On4 z<%;^MMKUnggxYwbPQ(N&2cuNtYUpya8;HWtI#f?H7xnx4FBEl(3#OWRK}o6E*y?Wy+ZX5R7ivYH^84NyH{~I-|ds zJ5&@7q4mMMk`k!({;PvU8DLt>If+GuXqScuo0D?1Oers?H>TUXkY8M_{y0A zr;K(4JXyfNkoQ*`jDY^?Ban3vntdkF>Lq%YG>jDYvlylm30MU$)FJva);yBb{{MRA zR31Cx&ToV=O=WWNpDWaW!1&uYlhE@SM4emxx1Ob_h$@;I6aJBrsMX` zD+=Aj9*TvZKQtRcl*3wraq6~0i&JtrcvX2g5C{v0N#b)Ta`S97ufG-W3Zj6tDpxa*x29*(;@>?WqxG;GyMKID=(VIWWlFqZ z<(4_t#2YZO^p&;oY#?Jwbk*c#u4fP{=Ki(a9Q=SppwHnOVH{9Gz(5c4YQ|jG(oy)S zeSpLGf7&_J;{)SH>s36Z48F79EnOr96yEKPDmN%0pcjK;v8C|M1!-5ZOIK4rdl|2;EdK?{cXvC)ZcDo z6Z`bLnwF?*b&iT8<+8Jz+Z?wdEpi7>a6kTn{{;9f5(#hoa#i;fEOBFX?|oF4vyypI zm}QB&H-)9zw2p1cVOTx?!hc>zi;L>WadhrAyn2chK&cb2D0|n+>Lu}gKTYvWxre|z zmq->^qYJoe@qgNeSyA%6W{?b^rVfqBrNB@7Dbr&jbCvA|LCl*{*@#24Ln*G75&nrL zs3xmEI6T&kd*(@Hk#)GP++~66>QYmpB`42A#AKoZ%dq`mYGOY#GUybwp-5aHNdHYE zcg7o9kK^O-O`B27=@1v;X_Ei6>^_Ec$gq42MgbkY4B67(6!CV{b2bU=w z9Wrg)W4i&9ravXxu2!;rc@I)92w4|P!62xvE@5~FME68fh_Fu8bCf4J{1uchFfCt~Zh+m&kR56b84j~0!p3jFTP(tH40{eNXC}d{HVp{o0h%~# z9QK6f4L+lW43)he@4BLuCCc8C5d%#Chn$WrKG9Bs5hvp-mTdo4?lOCYup*5<>$GCP91oZyWHbfLodyMzyfX^`+j3O2+9 zwE}bw9Dilm7(BYog;XNG9P@re-o*|WvUQd&%ZZzz+UiNl8hL4#za6DJ7M_foavPnF ze%a__vgkQ#db7-jxP)S8zWY#WJ4`uErs|}nBx=zK^`sCt& zycg-k7vu5I{)8LdT`W1`DAtpXj{4jL$x;qmUBvHNhAvcFB%Hp6lYr`dA|FyQYIec&jGuN?Yh>*Qj^UqaFnv@mMf#h1qv(-go!cl#56$V#g=lp*+L^ zC!E|zFad(EQMxsK>3f0F|8L2-84#+!(TYd#uG@+Wl4vhN&}RrfW7;Sy3k!G$z_nC1qrtJi zx(bN2edcJP68>GF-T|9t@IHd*F(R~Tb>OBWY70W^ds=Z>QJ@ECQmpW3EvEUjiDTgT z0}!rLfOQ}>C1oHT(O`n-ffp#Y`7fRfYR$hCY^8zY8DFJ)qk8QWw%S;fxj!PrN|FyX zI4ws*f&o%YrYeV@FNa(DH4nuBCk&t1EJSR3UmI&EY+Zw$i4PwtKRvvoT8WqkjRM`1!2mH^$nbUSa z(7`v6WhfvQ3 zh33YQ*-cfTPc*9lTcEI0&Xz_ z9F1W8<@mE-(sg1r6w9ZtmN8?MU%n9`edNE_d|;}pVY_~>%Vr8l9ulglhxsL;mBr<} z*{S3jnTSkTT#!VS5+*o2M8%j95?himI`O*5Qa*eW$o8dv$x%6z4W%j_L)sGCp#eU} z;>RjkjZP6h&r9nvJR3syneC9?4ci^ZIf{?dZqsb<$M}&`miJf!p62}MRlico6qE4w z*-A;^L#c)lr)kJ>=c(CW<(pE^w}b`KrD{`(L*t1d1e>muybA6JVc;-{yRX2et~Q=? z@D@m7hfJ;ChodUNZ{!R+1Sk>?8{gly`4)?+tY8Q7<4e%bYBL8qfN%q%QCK!LIWr!- zGuA#25G4nM{QvWCzp-sF0z%AF%$&FJh2R|mDVS2(M9!jOV6_?2on!VHyjnmHYG;Ru z4F`mqG7n%;sf}-p!cb8EjW#>l*6R`i--JaA--yc7eP8LfY;&N5HDokc34eOhufZ3W6eK#E7me$zh0iU-Qsb zQp>KHfWO!>AJoExNj^GryGCc+@WU`Q*~*KwaONvV@W`KxB4~8gOgt7tN6sUOB&_~H zn#@v(NMV#}+?;Q;=WP^pL0S~NWnU`a)iRpnIqR=j)3Q+I|H??B!q;`1{!I{^kCAl6 zA1*PRoBQiK*6Euv`>4>aq3xc>jGWFbjpfqXa0pH~w*1t%B9*q`6gV7So>?c)xYI`2 z*Rn>;|GN^S*0XB(@H26E}Vd%=CFv6o86f zvNE}AsU9350Jg)Lw6weoi1T2B7N#(?F=>CSmuEuH&vBmw!iK4_}J|Cf^YkpCAWP%PIwQP z4C;pmdZ~5wv28RnF@Zh9OM?jd$q?FWVE1B%g`fFtLz({m+@VEk zq+;g(;_eQ1#Xo(2G~N&Lslsc;$Xw_8g>J{Iby8C1`3eft`RcS$i^p^MDpH9Csi_`P zVc18DR<6dc1W5&=vZ9T_VV{+GC6-XaGgcpRNtcM3g|wXY?+-C#{BbQ+`Ttq~B3J&pXf%bdm%-%3Pfy*x8Ayx9F*zj0KVEW5qZo+m1=t1TcXb zF%u0LxMN7Dd!<9g&y>zSW2T?s>Y%7&9+5dIGKWGZ`2!GM(hdfsqqiq1f0X)|akP{q znk(Z;JP7)J>f%Xh5NwALZXqz}-RLJ1liRF=wbvBJW+|V0BYDtb4>hw-5QUr;`UEpM zhpKfMoEFc7-LmcIZ)J0(hUZU?6U~FU7-9ycGf{%{;Mo09;rYCJFdV{m?`~LHY4!h3 zgysQ%{dJ~wu53|pq;l0Wsm?Xfmx9m}&wTc1>E9af)94`nPapXBViNuO=7GHjiK_k^ z1@PGevMUyB$NqN}wJ<(9+;HV5P({|&@l4Z*S%>fDgC_@I!Ole+_6>jj^b>v2(FsJu z8}m$F1A~sdzw;o&)EbOnExBQ^5DictaHn3?N+6=|oYSdYfzW4Tclz`edaY=RvGgN{ z#Yax42_T#UjGldUsr)3f&z1kg`_}o!KwVlIQilAo0nlYtDZHZCx`aTFg&Pi+{I*yF zRJUL|@xTaIj+2J4B`&3Kh(1}YtQ%q*_ks%Hb-N7dR(q0x)b6UR5$|lEhF?Rv`X3CZ zyS>_O;)?o9gjPccMtP zZnIj8$G>whK3&!w%ih_Zj`PDAq7&HBNs7kYr+q(jC$*NMtT`A+N#&lu`QC+|%r+5c zLyIc+OSU)zZ8@6;3SzEZY3=7ymtsc)?wP_d-N_h9wRRE{?N<3Y$01aWYY-N>9$b); zj{EtxBlqm;Os)uv9esy=KvtDIbscM)P=I-{Dw5AMSwtktKzSaW-zc}3I~4~1*K?V{ zbuQ+U!GJq)CEti<(Zh(bJ^SY?ah61IDtNz#p>dqwICt|VYe2D9tz9x{80Tjri1@{f zvLFr4c(szqeiNd5y*c<3W;_%iLIj@FfjWO4l%^3dG5w!y8ZmAPIA?ACi`AM(C?_2n z0}lQ5Ak5v%dvF8f02H*R5S3)BzQO0uof8x__sP?Fr_Nu$mg!W0?lnxE;|o}ggY~_I z#oGiqx;R-I%#gdF&TMUFokaNPX&@6WxLRK~baA=P^g0on1BL}9S{#PDkJ_C;cO27! zVu@M;tHMkL=M2PuSZPUi&G@3%>~MyyC1#TRJQ2G3`zbp~7{ zGVrq+;VoA+C2ZGm^BPE<#ae^;#_H0HMhf;+$rF0(3 zDW#pD`GdE>d=dswvG=uuz2EEq@46sB6|2Ce{?1;nRG=2)t0o5)X5KPb z$<(uWTIU<~NN|ax=3v0}BwJkxoPV+$)TfMKY&C4=UB2ho2&NR^05H^@;;sTj5Zgb^ zO-(2R+N?={^fEA}K>xe0&gJRu97rLy@0|tEpAbLI0s=H(b~tQG)@VbXkq9b5cL5g6 z;Pq;41$Pd5Hy;q~{ZB-JMNWwV75}Y5tJ(eB7!W%WiA~~ANwR+{q`3O#>GUgPVKc1%Hlk`aOrsyB{Ed`q#E$pZBz>K>K7SoB+B&8TFM(1G?pL=Gwy;z@KN09@vZt;U@2(1Nvo-OG))EcX8Z_W2i;E6YCw46S~YSQWs z^=ePF79`DuqDT#T#}?@92vl8$j}RvRZ1A4Fvq+Q2SHxzS(l{tpbGK?Y^v5~=qksF5!+urIOBzWfqpD zj|0Q3sRMuJ9yGEi3ht6ZtK4w%Dc1oBY%=)I7C9;%t1N7668}<^ium{D^xVkQ9{a8M0XN-_g%)NM2+aM+f??ZMDbAEGT@VEk0+EWtU-<6 zSG2x{%-o+U` z|6(1-o9Uja;a+>Xh(Q1qT81_a(`AW9w^zS<9~#oi3f`bc^uML)-Q7}ONK7{gV_xlV z{o0<^V(+y+if@gPL+@tnS?*~I>ZGvc!eY$nEtT>b>$#P9i3!OLTM@cZ2GhnOIME~M zTFPGOdK5Xp=RW|*|cvAt;A)8 zj`s5Y4sefx0c=%8MZjT@EAEsN+Jh?e%&{vrUodg&za|hlTa8u*V9@)q;xX#)(^v>1 zLX2v4D!`)pzYXEvXkTu}Jb#A(jBtulKd>A0&RhXKgdBi%6bQPAh0tl8t=jX+-)6X+m_U^e0+TVwS@ho9nO5D;_av?9^53@;-X44 z^7zli8%z{{fX8ty#(t9?@(okmgY1^}Y*sCpYzk-D3Q8Y7A;_WKst+?ujdR7!iFUSI z@GO{0;G8GZF`qOYn&h_ zl6+0%*NrGAUP{FP#T2YSbvXu$$YunKbY$nZ!7JqUb{yj2hJp6ch6L#-)KH%^Cx_=) zvMc0O$VJ(HC3XV{5d;u9w5d zHBs16^eOpX=zb+(_iDXgD<2w=6Ef~3AB|ifKCOWxWHB*D)RXHhS z>?CM~Zbuli?`-{;J<;5W?SA6Ix}%s)xt^)N2m|Gd{e43bkdaYs9@sewLG0Rp+Lh;< zC9q8+L^Q3@?Y-E*^t+>D^BAlv?{ryl+8bN(xm^KD6P*fu)kRhr6)Y$sy6z9rGse=& zNZ?e03chO~j_wCAs$x`>0kGJio?=IvABlZzuC0Y*VN8vAcz!uNv}R2Tvc$Pi0T{n& z)&#kj+^(HCr6Mp10cTDd;6u_T1KT6FB3Im?;fNkn!hfM#BAeLJ^Yilqrkn${q2ze= z`QE|+M*i0a#XwL;+UOXV@xgo!^gElX#UhGRN6rEh>(mq|9Pl9b;J~>_h2iM*6kM!e z^afBxr79gomVpix(rZYaB_fs6i-X<$5T=t$4>vcqdf7I?E~{Yq84oChf@9gyt?9+7 z1Y9c1>gIsG0YBWMAGbI-5wu|jlu{-Rk@WoNzXvt1W1yJN+)Hgi!+>=BoJa=nw%)p?_CZ^rp5sXopmgB+FmuRE3y8;4zh6;tY;)0ohb z5LL~=CsU<@xIT92bt|L~W3A5Din&RFH#J!N595ZyRZ#ZN0elE|eJ73#O*5ed0cHQY zl6qZMK#1ou@FPTfjF=F7G^x?O=6fNTGbHK**9kD9{sZ_j5SR3>tMJZQS{)mWx1kO! z_iX<}M2k2xQw{vqU;=j*;Bjv8pA01jf&SV3iDfu&aD{sm_-RB3iGteO7Hq)SH0LWh z0iBIBb*z6PAbkQTjDFQ0z^!dlX|UOUN}?5gL*N&Y5!ZXD9)cD-u<{_P-Z#6_D@$CTgYD6afnd`a^Z-OSLL0a;uycoQ;eoT2- z5PTq^`1Yj-@hN=aY|;X}02>Y-LWnl|W^+1BpG3w4wt@7adNK<8wO5$8dnpV{>2m6o zHKXY$)|&l}lqbr9ZaxBu$EcD%j(@0rcfyt=HrBq7a==`swdFiTj#on{4zVda;)zO? zC8e$l?oj$|4nT0?q=k$eIsE=4wpAmZ-4`RPZB3b|pDC-UXUQxWWjqx_^TAbJlR++? z`-`TsSP4#6X%LRLr+sjgFgF|{lE7K`v|(XYS5?f0vM|&DEDq;PNg)Y+a#D`6&-M3c z#pk52s`nS0$QxETgr#&fRvlx9=_gOfzRWTOOzcs{YWQ^h@3W=lRC?)BZ198o4dm~r zFPGSfa2*YC2>I;q54CgW95#Z?!8H^DFEN;qkkFf>&AcXR^WE&*H}shO@4hH0iZbNA zKJfUdYD^%)6R;GG-T-$Nr~-gg(cFnP%^2Mtb#UKnyisAmkX`f@mvkTe{Hm4Yt1;$t zQt8)%nCs(XKz?~VZKrUyqK+j(Ljbo^?PebNbunN!Vj?_&Gpe&p63GJy@9rifFnQ8O z`++(SwA!SkGIs!ltdu1T_A+3XgRKj%3MRNfhSKm4Oxi(WZO<_POw62Tc3U)62 z?{xy4Z(y2kn5_o~M=PK&jPGI7Q&yM&*}@8_xUJ+40OcOgk3ci^-zRbgE3i_kN~#!r z1@js3f5X;gipIylBggEB?h1j&BxbPSr?`5}J!2I$D9;ut`JplbR;2=u@Qx+HdSk+Op7=b-#d(-{K(%FhOT}iKsbHj9D31 zB|7N3)fXqWE3hjELCC65Zcc!4ow5()01i?Lc3xr+0WF>X;JpuVJ{+<+KZhg2g) zJAA4x`KfgHj23SCrkCVUB3QZR=cvarRd^oOOi+n#g43LWF^ZKeUVfjhJT`xi;FM-O zZ$TjLCYdowK68)AJ>&vjJksiH$lecH&u}W#sq>rT|AmriZb2#m?{FF^n4#~aIu7Ld zDO|>uq>P$#Fd*Wi7~>nFPJv7kdjLQw(<+0+XfT;Axi+u##gN!g(9a#aen=aI2{HBr z8P`7tX~oMqQ$~Oq4QSEK*8uZwov2GuvZk`Ka?G5ImLo&hr|GZdIv2K24o>@GJ$RZ& zd}E*})%p?DlSq?@PkIPUQUI=)td}oGMoJ1`n!qFv%f`kA=4v5R`dd3a zVc|_qF1f-{hDOo&`|qDzEZN`)1L4awO|mRUMztC3>BI?{aZ-|pcnp5AL9Xy(GadTJ zqfut?V(-#jpU?dnj_lUoU07#}zmcWJE?`nZ**pCB_D%pMSKtDJ9ZvN^Ou|axuf0pw zx@M+QOLy@_;jgPpwT=9MrM}@05ogVp?zS$lj5DexhBH4^wHi(s>3-=C(hTg5Mtqn3({>@edZO9_kxcr;FzxSBtq%xvR8t(kiURw+4h7or*Gc)t`6$T@F zPGY?|;35Z|R0#ST5J+}=yo9*wIi4xhsB3F#3asJ;ah|owf&2)w@!`oJGu^@b5(BK10k-&*w#Xt4@5|Cb2`W-e zR>5#AHNqYpX+%QwzjEICB>RRbHjv5`n=d0GO@a}ayrS8OCVi{Yvss2 z72`cU5HbzL(Usi=#Mk+IDZxQi!8)wKG4Vdi!WUMD25;tcID55+9~%|9oISO*x1wa0Sx^>cYW^-=z2%1 ztzHfe4z8{@!1@5PZ$Scb7)giIfwKU}vdzoO178;_L+UcEYGPs{9%fvVtW=~5Kp91i zjr{AwV2mBzj~Xn_Opun9rCc-x^(^x};Xwy0mwhYfE%>AmBT>cJ;T`H&q-{hX>Lf6O z-pZ9C=)mg-x|!^JN9Cc8qz0k%i@-=FS81L;?kFpT>mYY8!j$|x86qUnp4jXQv7Jwy zX7v7-=x-sogd+}!lYGx|1cZqu(^?nSw4uZ4Ml6~%UZha@s(rxU*Nr^7idlB~Ci z@vo-Nfj_lNv?>rN2`>)>y1ui{`0PL@X-`B_NH2Ow{T*u8qEXa5Q6V>FJ|;3r?bGcI zRa;hNrIw`J_>I}2RA>cbf-Mf# zNC{9cv{1|pjKB%#E|>hwGCXAd`|;)&_7jRU?lRMR=GgNuw5*-4mH#|zw7mhk@q4c^ zElxlU*%(tXM$^j4-5sAs4v2hO`eWw@{#K>@`}B;run73Y!{Y)xX|+qoz*^kWBFMqP z0cvw1v>yV8#cCy>x5DJ#jsY(*IPF-NnMu9RI)O}L#rAaJcac^Z6&3!uHdZ4b;Q+WS zFtY$IG2p!qdI@ACE)-J+{f!JBCi?-HdRXFDoMb+OZrXhANmL$$QCf>q5m72O~M@mYFwSppd ztJ(X0APTnxkxXB~b=?7utV&BMAL1{Z z{}PIch6W#LI|u@s8G58k2{0+qaO6@;=@KW!D-X#n=iL_zT*)#j+1k>P&TMJ94Z@jr z3feyOY&g5|vNPXIMPt}FQfMI$S}&DU&DSH4yjG1|L5G|zpicy`Qpb3N7;&d5+NU&CqEcnc0y^V_ z50EtsNQ3$;FbYtJP0FVZXmP@0W3lmQ#LT}V3rnUngiuZ3(U*e5?frWMd0|_yZ*V zd=o!6H)Ob@FY1j`|n6pSOTX52HeYa@3;NW{JvXdb15FzAj}$yc3}s1j|r& z-a}`oW`_GryeUl(DU`yE5!Kx zkR}Lr6{yQfuyjqOpA0p6dm=eX&|R+HpTKmF;o$mSHR?!PB{RGDP25mv;))-e#67_F zyED9fqht^9()PyeO24h8-61yl)jMsj=|Yy51Ku`)myz%6;*%4ZJYc` zzR}TVIX`?E_xKxYH6$NM0t#(P{&p!C|)pDE>g+Z)kl-#un~m|gVJUE|eu zxi{7J6mDU9V0eG~$>61c;#B)ks=vPdjKxl5>s-QV?RlTj&9ym8_+Rg*!(LpryXntM zEiU}bI8l<{7zF2?uK%q$y{bpg0lVtKZWFKfNlRBWYva?$59Zb(nIc#DbLo#wTW|9q zwRS?U2?k3~o86}mw^_$F`O!~Bx9N}5_f>wI?|8?YQI*|if=`8AbI7%8aJCn z#_H<2u*ZcSmp{F(6f1?*>^*$79TeWn$`mLR>5NB_V>fjc<7cKDo zH12)X8%kTO`7+bL>fBl9H?Q}mr|{)Qlj8o!ONo3=78E;I5X^7B*K5l@&lQ)0eoqgW zV;|Ine(h#fwcNo|v=tcv{#0l`BUOu@9huXPLEG(c`n$6MtC*Ql@ zr(P!lnP7$N7>cc=^+&_ZBvkFa4p`ZJkb*P;j^w=oS)aG#p%o^hjoMV03k?{d4B;pY2;T? zQBgn>(83g2)#;$OLV-$Gkh*Wv|Eo4H8!IaS;e()DP!$n}KsRWyCUK>pQNb-JBauq| z6WV;3t1_@7k_JBIz03B;l~Z$bbD*0zI+y1A zD*f~v6Rm?&ZMT5t+v5WnDtzks8vDk58qo|#RtB2ocYU~2iQnEv`o8)e&t%+T{JO%n zJ8XkfSwMI3JGm`9MEy%?_XW%P^6E%GZ^+3V}T)NHKiwOW!S5f6|Xk_RoP9 zTI(Xr(?R(uZ#XG7)P%gpKHW9pX-)9iUuQITjQgL-A56R$6a1sj}<@fQ`9Pw zml>(7w#M9Ve8*3}F=TDLmI$k!|JeDiVk!is&D>ocFC_VH%CFr$AZGr=dAM`1YdK02 zdHU<}>Uh&9;&T$$u3i7=;OXV(a@uLvdic23`ZT?I%PM%v)tveCV)wMZ7){3OH=4j( zVQ+lW{L)SF?6EsC+;&N^_BzBLx_X}yQMqP;BOZCb=KK2afeBOd*Opl+HKNe#RSDTz zL&*p-Rlds}ub*s|OWzjQru!U@{8@G1{^-ZmdfREx>UPvzC9?N%zIp6DtRv)yb0YIUqkietCWF<;rp&$0T4eW_jJOu<)(F{Pp#flgnvu zF6+-8O;zJjB{>y@7Sn5C&(CFiwe|M-t|G;*eP>0aYF+8Wlt`x6Z2QyUtjP1W-p7X@ z{>R9!< zW_N_g&V5N4v-R$_xybJM=w_+SSJ?~QTDZ@2@9yqS_H9P3)l{K{z*3=NTITbS1!BNK zzo3!wVU0x{rN_(+4XssxBV|S zORS8|YKw=vySu6B_B|j~fi4XEc>jmoA#>=#hQbY(%+;yDKnMbaMPRE{oQi2(vw8n| z7Ahi2gUZ}yF-|`G3(OA3GCusfegGjY?QW;50I>=drfh`9uf!%>TU+Pu-ouG36T?8! zp-T=%RXsg$@y%dYa%BOur0>%#p<@E>vk{GJh&T;Ce*6f87s&?zh!fpU6N{t`0k|s} z+QVysZGuEIFbT1)`)&vc;}mwR!W%gqiiK4PPvKq*$*MLSjZ$8u7gQ+wxKUdB21hJg zqK-_Y)N#6T2)T-TcFWsQGc~nhGT+v;07rn<1O?`VY>%knCsYAuf{J+8udCzIwUo@P(l z+>h}rB;ZlR7C*#UYRu6<6<~*QNcj(%1S($teVcjL6ScrFGr5%cxM@=E^`eX57*2i_ zsQyENOFXQ2_2qI!y{P>zTq>h)PGl=GuAdr$HJR16L3sVPWtUEwDE!xa&sv7V;(V(} z^J|X(=z3A?cs@8V#bBJFW& zwJnOUUrAsKqA1H!b5Js#ye{!J{U$yj z^KS(H$zUg*!g-T*dBa=zI#uUqjUz7O{2a07(x>`asQx9N>-GIb2N`P6%r;uyxW|gq zdr9Q*Z=QWzAr^LN$CnpX?aoto|Jd9Iv5EEAZ2Yd9GZz{+`kT>n@w2=ES&=t!y7sD` zugCg@gpTu518>&j-NEUz>tOJ| z*-5*q*2iq#45tf?c=T^x=N}BXu|Ef;B8Dm6I@R$X*G>U%*59ZFoA+RR<+ht*5#qZ{ zdZu7tEsL#-LJKKyYG0!uAqiAQx(~LjMBMpYH3!|B`xgkVzt-vOvjrni5=7MLupDUv z`mq*{E&2Xuv0&;5luorXgsA9fTydrZlx=9xPy!{}g;RG3daHibf=#7CJNbh~$1FGj z&cJ>XB2znc0Om3OliyDaLTCfD$`VG+v1xcfmnw9l9S^_XBn(C?HAiBIWX|9_qJR9r zKu51IXm8W6I$dpjWb?b12R^mEOR%yCL^S0GF$8xtz-#?`0dDc++B3DV*O((_lrlWW zdjJFwutWR7=HZH4*XjITfY9S3BZCFhgI=vG_%7N@8dnq&wC2SxYB=#seQ$>F5~-2Y z@PmHzBNWK`b|=6$2q~k?F;yrXk{UF)nlwseGJMbmiL! zuc>lzHF2S1eWf6N)I}fD<>pKDB*aCJS?`2tWfFfqN001D$VgC=HlG@*p-*EWN+Lh} zh|YA)h9z^gpt`J_AR(0P6gTz{jx*aZx|x&AeS|sh-mMW~@oyF!7s(MM;msEd}AHUI-QfehnVwe_E%)5W+3y+!U^bi#v%i!R2!?%dsdv}2)&W8lDKJ8 z5i0yA(HsASSmj_edppzYW^i7ZZsHoxUF#M`d4eNYx$9!{ zYXu{%n{wyV$E%WlUu-vPmk%ZCO9UHHWCqP=K?W~7t?v->S{4k)|84L%Q2g82N=!I# ze2m`9dV*kXag1POc{|E?7Do9*?Qi#`+ivYi^yj*j8;!zt6pD41H$_E8lDaKBd~iL| zZufmYIywq}n+Ytf*wLrWS>Q{O*|shTGr`?N*&uo2TQvuakMWZV^su8lps?*U_z@YI z-P@+k%*xE1&4a?DdiEDEsUjmIEmLQKT_G6Ay%6!gqbFSg&|xJu|4oN0Qh<)G?s9{} z*3}ia3E)q3qOw7>KYtb@e*xA65H>{vP~thmlKYd}+uPtzTJ#e@1X1CK2A$cSYLBSR<=PzJZxi)0qzxKo->spDH0rxy=7Ds-2cT(Gn8})igZZ}(lvC)&><~?($Zbhof1;g z-6h@Kk|GV#-Eq(JyZ8U@`qH&@p>yV(Z|wcqvXiOJL51Ynq$zYQvG1eSJMcG;RVvFx zVJiX02*4Cbc4TP3ja1&!;5*6}6cn>; zK_X5eX43Z*GC0bPe~s03b3^E*GX~BFdFuP3+%D;_w7By!aVVW2H;!(CXlU-A3oAYm zC@ZbZ#~PFv#j4^}Z*~L+$VCcpU%%R7?CbRck-}%LOqC z&?(;g`XkWkB@$&Nrk)1DhMZEVKsxGEgBI3Mjj0@WRb1N0!v_XN`QC!>)S;7aFup9d z-WMxB#QeHiuOM$=?Q9khe%c#H`s=N0#cR3p!OAhtED&?=+$kQ6-7Y@W+jX_HU;L(C z|B&~3!-c?fG zcrs||?%UDj5)7lyth!vceR^nHuCN_UKg$p|4Lo_cTdTU%TJii>C3~4P+Cq+%GwHB@ zCLZmx5$)r;9T>)Y@8WY8nLO6Iy~N|SGf=wne2y9=;K-=J`Fv6@XL=ZqLHa z1i$$O+$?AO%l#yW%;Tnr ztbZ5wmz-oomKG!dPQic+*9c1^hd9HvAkfE^X##Btcn18D40Lot`!_&`=nm^#8m1kFs{=D%oUYJ|B2C$HNY1(@LIos&3HToR2}?^!y|-Tcx|87oVga|dwq$5Hg@wU9HCnhBeD(BSwBy$P z0MY3K@S??Uo#Sv2^xx(h8?U{2^9ID9KYII^nISFQgP&5j3=e7)3H@yee9fs1%our^ zg?yrzN#;7d9HQg_zk%6<0|9O*-LYl7FXB0sw$q0ur6-XQmF7K}R=>PlNs&6of& z_PA3T*g&a4c@_ z{SZd*jYn7+A>TJV;N$IH>)=@zk56s+)N7CL2bDkGVQVF^J3Z9Q{W;&NcyhK)!#C#I zetNhU7^b7_nRk5Ds%UZ>^!#MBh8np+pV4&aH|}#1_ZRDVqX<DZZ9`|ZNv+uykoT#LK16<$LldBoo5V_}RvS#8(#WZrzHI4dRB8!%Mcf!!YF zKNodxMo6RAIjGW}PtEmg?kA*uDr+opS1Jzf{wUk%s6>Ulzq%l{_Ba`yTbUyaoO?Q{ zvpoc{i=&8}ie-;By(XuP8&PRLeh7n6tDi1ZL>c=_esmF$@CMBtyiBj%%iDY)%?tr- zHwkVY9zc2P>+9qEj@frw`2ft_V6Q1>2_Op7?Q{E-arm;bzMmU?Bo+{VLbK4mwz!>d z183v2N5x!PT3R>GD?how7_jLA&69UK*n$#7O7-{kf%Xn8b%FRSdGsS1C770kRO+*W zIS+8%LbKthJqxCr4(pe=6w^{t26oP4obaHa&;($Usk7Kxeo)P+7Mbe+6aTd@AJ`@U zRSp*^fFcFP091EnB~Eznx8UH@Pq7IenN1SZM98~*)2br+3sZmtoh_O)sX*fc6musqhgXxrg>qrQd3M*GncY*5gVI^ zmF)Ks4yRcs_1Pr;wVWXeLuc#aJ+17`SBHiP|J)Tk?fN5C3>4?-pQ*muG26E5zArxE z9*}qD)^FOK&1JItTQrOAQ@kd2I0Pe>dp+&V6+&sH>SLL(^Gl6;#40Drmaeo|HvK_f z(IT~+;>RPJTjHFI@j=R6R{g20I9xFbEK_K7XSterniDnO5)3QzoD6}k)Ok!Npn zu0+u4LbM(7Y-BjiSK!<8$v^Ay?a3(oY4TE#O^oDQt5!9LhMU8KHkyCm&iczkj;F4Dj47t62_B=bx z^qT%${(8_nKZ@U->HWFgv%}f#u}`LbFY&m?AT8G0xF5?`7w^X0sH$33_J4RTir-v_ zPx!uf?vjt@KQ3$k>$$?1MyVqsc$D$?4%6crRY~|_OA+@C-=?jy$a6fsu&zvQWX4(3 z=RM+I*NIDiTfgl7yOhqjSXBNYiWluMeXs0!s2Am7Wnazixf}n3lhA|f_w9gK#oeBk z`*G`PkaSy>iIgL%wNEEsrkacX-<#@j!`kx$Ey2f@TNCeTn9@q>FAuEGPZs|np#Ez) zlk{x(9xtY~T4>SJ$^YecKOlX#6eLH*4RPb>U=UQMkb7zRiAOR}cu_H%L9$G+C%+?? zLJW62G@AV+O4M)llR$F4v`?Wz;Et00x>Qb zkBx+rRqF?38a%+^F?|H-&0rYg$zW=SySEbU*fc)!K8Qo%H9bZGUMWEfHIB!Xf)NyurVegwt{ z1)?ikB{+`4!an~Z*4f)tEb=)iiTYk7a8DSBGsLi_PFIAN%v_gENAJ()s;)RltVCPX zA-Mdseo)0JpUj;C>CXPaDV159FrcC=W_HY!xAszOOe0NJAc3h^l|2}XQ!s%#ZzjKb zIf0z2rD^6PJ*hf;VZ7$vyT``Hz-DFNdF!*bKB`2X4~gozKWhAAaP%TRt70JU_qZ{4 z9uBs_NW_9xe>l_b*bO|ey9IaB%Rr}$ix7nwHxb%q0}S+N1F5;{6o$D_w>!8-{VY@S zEx#vO>MqA6z0=5f%@qUkQV1(iWaTok!(0)u5I%B_<0nRO9*0Xqt-=sHX5zn7{G~D8 z$F@B$%RS8+3oqeqO0l@5^Dq>uHfmBjaqsw||Mo8z=Q|SRuIff}w7vwFA$pP9K?{-l zg=g+$W79dU56@3idTpL78+blgg*iY&vskx(vk?tMlb=aGTMJYk-tAY2oc7>%en0eC z06 z3yDB_lM{d(13hko<)=@dKxM95wr(n$G|-J0xaeN#8^PgQ1_Fs~|F!`qb(!X5c_80^ z6SlK6&b+T*zt(=J0Pr#vy?T;ws?0<{U&KpGcw{ zV7RQUt$pQZK{GWI5rYDOIDZC!!y_RA%#TWVFW<3qOOd*jv-9uj($O>?$FctYexMp< zO$O2hX(|o=jFoD040U++7+{j2#S8TmW(xotZ5yy**tr3ehKUIkV1{;X0Vf|`jrSKX zf(kVSFHx1IN-hBNnq4X@D|g@ftjj8&o*4zYab%aA)WBTP>RB3hTZD_swQi5$f zeajD+)3plmdPy|-EMv&Hn{MOYbd;MQTz%rXhOITH<+|Qu0XNz(c~|NAU@x;i+Vg(< z#t^&m=JUTG-KD33b8ruW6LGNfQF}|o#Q4R|qqhiAxN!)!P4&VTIa7Q)riUBgd;Up> zlmITE;%Q)6@>c!&#s5j-wV-gj$}pNSgNkjzbnGh@{v2SQ2cN4TIiSpfdkbJX9UUDZ z9tcP2>FI%Z!08Vh2VL|s@3MO%`Zs`_3TUaOPn=uI_T9@g$v}+_^1z|Sz<=#dr+r{y zVR0JLF$&825EIEjd~~hTgxpDnU$EUe5K91q!9X4*uzjWiMq(^G@*?3f6H*a_eXp`8 z4UmgYbN!c8m_bfX4rK445(vK;oI){7QgEieya)TK3q0`8VbT~NvtwVQL!Zr69nTUv zXb3ClHP<4@55nsTN*l-}HDox=SBjf;_Em{?`cPz>qmCoR&_I8qu2hW6j-3;ElfEti zQT|b2)u>gKNby6*E#)}_C640tXOguURy2p>nMn+W@j&<23tSdEwD&JDUB&~}p zhx~{Y5Lnm42~-|FhslU#LxUbToT5tRtSeCD(SkH;v}ni3n+km01@)I&(sX@g1rgup zC8*`k(5T4q5>B~DCThvzTBr$Xd905SIJdIL}EWF!p9f#fa#)e1uuDXVgIT@QT^QdrIxD|DbZ+7l%v@3{b+`Vj8k{8W&i|(dS z+Hn0^l59n!k6ASBZ5BS$uIEQJ%@jEDzBEn6-y##!P9V2;VEW1|e=^nq4Pde_I8zi0 ztW>ah;~;(3)k@p({BJ%%JMsBCF#>_$L)QKboWyO zrT`+5vtRpdw_%ade}-q;_v2uOcXdL=FSsugHiFOhh#}#mk7GQq=c^TNIYslDP!^GG*4!3jtk2r>Kjd^7hDTT0zMQdtlIw? zHrTu#xq;*W+A!D|`UZsL`XfI*-5-Oq$&jq8t(}sR0{6_c_K`p1gRU-U=j4Rnzpt;X z^bKUDlqi@MJFzO64U?c69v+5Eo#&W|T(1F-D56)N35S^^@P8Hx0!5FmhS+i!gJzkg zsy5)(0ND+}Kd6>&k$TQ#;mnx-7BY8u@H<7vFJCZ~s)2(q&Iz=S`fRLl^WqP%X|7j; z-tBKfC1!M3>|1sZajs*88G^PPIQccyx3hg-;TFu)xLt(xSXXSGb?w&UFsi2<2WrWR zNqxuQZ8TRM3YFAwR_(jkuox-AaoEWtck|Ec>L;7e2mL0qBrF=VO{QPDC&LE0Uc`lbYSF0=5!8=wmNpVB0GL_EZ{LIw| zTaDQN1pLm`unvgvRS570yXe+?6wv6ZS~IjozkhpB!HPt?!gW%{hce{)^K<7jLwdi6 zBvM)TJP&%ol3pFbP8-6T&MjKJh*9z1)U56);2SD98u_s~Rm(wCv4O=(1z1|x!;cvf zC8%jv@bwMET+b8{F?v>0gy!FE&7XzPo50goJbL3Fg+&y)V?`qbxhCV%7%@AxotC2| z=$mNam2(72{lhibljD$>;Lcb8x=K|#5wU|4qwiEBd^-sIVSbj3cckN#cgp?wT$eXM zfUwB(kcfa$%Paixy8e{#Z`&i`bCbs_finYQ$pFs$mJlF&|FqH1a)l=OPVy{N&((x2_wL4`%X2;lO|VYvF(LMFyOc zhX=u-@{=qOi=tZwcJaXXaS%Q%0oVp$blB!~FM0~~4X;$2T~~_wKP>_^h9N|1Re1Qt%z`DYm2HJM69oaHwdjoSrXM{9#Gp-*|FHEhXG@jd3RIQdA5CIE|&yxrxb{`J|}K z6tJdJi7lpZXk>jdh3(kc-?L-L@$DqxEXSr7x=CAQ#oho?GNUa&vlC`H1xe}TXp8n5#@?kkON6*JP?n@C)ej<1o_F3B0`rdX^kumS>+qZ*e4kCO- zC6APNvS1?_qGspd>qXLrjfDlc&|%a!u3+TqFS$0>X{nw>cP(MJnoWqQ~#570<7eW9CPP#RFa;pC_@6J@`YY-O@4QTd5fALl3xWLgKs zU_=%w5!Op3v#!soRWeHf?d4HAyQd_?w8at$$yTckB*h|Xh&=_GSPI3} zq$>Xh1CiE}B3jnBEP{7fYt>V7u4N-=m5qxwTjz-_ABfi@yEF)p9Byphh;wl>5V?@GXU3`Bj#rPfB;+JU!cM=es41u+vrB z$j2Vp`QK5;FGHmx$DpT%P27>b7dla#uGMF403YO6ej!fI>U<%Cr57nYiR2lGY1?3& zw6LH<58xb1o8upvYh++g)r73hAJd4akCF)GZ=VzAg+I@}+s1 zR3IoX#%Qb#v6U$fSM(CAlS4rKJyPkzSo75h$;gLnN?=V0&J{;0B`Y06D)j#MiQBF9 z>wxo2`OIL+e78`YxyZ)Fa3zNLL(`r=XdcMlkONF>6DCcU^VW+LKW@;jC#2;EJ);D` zCm|u4vcp+g>7E%#;{5g_4lg~;kDe3-ytbdy|5}dQ$VjW}tgStM>QTkcSDE(biV%Vx zki*C4=dYrk{6@TPi+~8P$}|$zeiII^Sd$@4Zwv_98*7p%aU#pqk0rCv1jdicpxek$ z0t%9!67cHTPC)yaEdvk@T`9eMV5pz+H9$eK7S^zo@%_7TMCXjp%~~+XFf=g22MF6D z^~GkVeINw!E1RS!-skUoB*{=#Qd&o&YDY75r@^L30RUrj&X1n6Lxl77_F(*yqASb1=cz;rdv5Lbu7 z(HSfb0+Ue^P9`QMeh7I`pkyTst+LE+{K_PhVR(P}bA;g_>KDVkHyI{L|MMJ| % zf>h)LyOmYYuvLhR3{zpo_p$F3auzvkh%!`a>>RGpWx^ixYd44ofgGcTjKcc94>sbu zgr-iaTI6ombPSIw`vL4}$UZnw0=GyFwF!X086$NQ5NetjAN`U8iZx2J+j!&{sTJ5o z-)$2RG0xVO(+hC5ijd^|>?vD9B~}s7@rmx~!AO>bJ80fj=QU)+RUaUM-|nypqRNX< z)&8AcOnHRix@Cn-u=C0t7fmq;LoIRdts8?rN)p39k%km)Rgsswof3g$h25i&KT6lv zM9-Nc4eSX75Q-0y;Z(u`va(I~`V3mOJyE&zS41V?WPdRL$eaw^=XM zb5DH*0~0J-h3GS-4t-%YBPKRmaP8Cr%Fe0f5-BMw2=7(ZC6%VODK5drvYqK-|C zjUg+l+NI3HsbDC68khvf1>#erd3TqWmj?!91j#GZnQl^LXh3HRv{TE=>FN?P;X-oo zARPMSq|!2#nwt80#e=Q<1sHnYsY=AKva*tYoe%?UD@mL9xk}0G`!Dkoz*INORISCB zS7^|C4t7?)f52cJM+fCBpq8AJ6qJ$w%IuC{a8Wbi#_~sO5L14m`(lXjC>f(K})_>j@n&xxOcC^jsxYTzxtpe$5U}|EpMST0tqd&c%r^&p%w#}8A)XYm<@0EI=G6eeiDPFBB zCDMQ}!h*iR@nxc%x@wt9^+9ODzT5*AO9_rzU>4qJx#_6R(tricIMQI+I(_}S;U!wS zos&I0sYr?#YkYq-dR%{jeHv`xExczGn$>Cqbt|O|QjmwEz-aA|?AepspZ_Bo(M?=2 zS0Vo$4l&j+y`{ZUlTo_37i-9>2|GKMsSybs39MT*5niQ;wuAv<95ootNsH!+l_tE1 zwLG|Juf6n?Y!eq8Fr`Y`-DybGNsy5Pd^aF!`$L6z(8B&@M-7z*!438`ifO!MY9Z7- z0=R#If{=|g4d(twxbA26u(V_(kA4FTJ0y;CR@}?7Me6?c=%z=&Tag-H{*)b=|arl^-nG=S$%Jdqj7~kQAGPANG zxU6?Tf%%RmE4(A`MfD%|R@Okk+6HQuiYO#mZ9Lz>`d%wPipSXr;ICbb+q}recawdw z|1lwMY(i-U?mcY+hJ4hQ0Et{GXVtLAqNVsF$w6}Y>V%i24&$s6SZW2V>`qw`YE2(y zo$^uZTh^4%&`b}=l{mghIk~GLB#7~0$Y0l1+)Bi-ugrPz=JXVNtNO9hj=sSvF5^N= z&ts>ypd84sP+Agybo8%kh;eVrn9bE-FMc68y@0l8B)Vwd9;`GRt1L*yM zyAY_4-amZeLg%LWxX_sOIThuQ@r;);0T2a2KUhgPdIsuspg6AoT4(@3RC3cMn+8Sd zS=xn~C3vg>pCph8z5o@~XE!&1=KuoApE{KA=o_}56jUbx^b*VveipWVV9OjAUkD9k z)?eF%iT{L~Lc{D9MIkb4>ou_lHjC+h5z*1PUU2D0Ksn9%{R*b&=|?EINcpUSPP#qIgqTix zrJfw{Kcuv`QLa5|?u%U3Xd74aElnso%*6v^IucrbbFC8^G{za}naKxYNYJtq8c*To z?}pOu(x9^^%345$en2}n@xJrVRwr;4|2nd9WUu0WmoOZ`Pwx}ae2AC@rB3Qi>6=6w zmTb4ZxJSHbPld$RF|##&-lqzr@W<^#($F;dJpa{NZ|OGSt2L%f*!dzQs3On20x+Yl=pqYi0;0@wysD5<0_3k??z^ zF-~BVBue7K|2kqAP~y<#{T9h0QS9Dz*zjkRgFw~SUsVA6r2z~m1Y%`=suh9M7+mzP z$VU9CSV6l_pSZ&80zyMWWoW8_!xa;0^+}ugJ@DF;X#y|S0~RF8H2hN;$c`W-WT_CN zA+22u#PrUS9xB10N#I8pA@;msSJ|Ckj7AR9(`566d9y-t{n-i2k*mTn?tU4K1qXl8 zdxyn`z+{B{ml|m+@EA3vxg3wxS1wzXAdV;R2s6q36N_At(aaczh7tMsX+D>4{cJ92 zPyUaB@uprD8`UwE^=nnP^$-TtzJ@lf{>-ISVh@~4!s{zCWM%fh{9^fn3<9RzVzO|- z=lOERBv?pLH)gRHP6yrjOzd^c;cs)4sSxipzA!DXxUTH8^zSMFv#G$>`P@&A~Oynmz^0L-g zA@IA6u&fSHWPv9BVkAm()<&X@VOq_g?7v7Fd}(?m(6|2BHo5;2s6dQ(%k+{){>D^m zGBx6m;`+0*GU%oKtFZpOw3x4-`E!p8jL#b}s~C5MR%sa6K-=>_qjJKOTpmI*NY}_g zATOnn83K(m1=CC>0)`0=wxAXR0R%MB|GBPsKzJ_TObHPR7Xy9F?|Yz}wqE)5vXA0l z%be5eGI_hU?%{DhK%-+&^Pj+f^%E>_+@S&;LqkJA=e*}Dq-Cide5=)pWS%0Nsktn9d~>3h>f6=#@?J5jaH0&vOlfZGy6;e!GpF%wY#dQi-qy=ym)iQRMO$$b+y@a z6hY-7?})`XG$Nsofl>j!O~T&sR&RUjO_(T>JA1OI9G>-Uq$JDziTfUNcUJv)(VN;; z6{zdU@(I^;u__FTs0S+-WzsdXYPRQeGX5VQ54?PIl^5>g1z`no0 z#%5z-QB+cLZZSwn2kY$jX+b2fH7kKhy0$g}&r<3#R?kxCGu}qSKhre?xi{JA&F0^ zap9B)YBcM)Bzez^v?f8MWQ4*sn(>bsd{n2!mQAb1I)YOR3bX!Bb(RLxUvGugSaj5` z8C9e1xG#cW@@_OgJ6}84@I^{c@&3l{fMrXac>H&5UgOi8}1{%qmLrbugGE9!Gl?C6suf+I0nbAHQg!JevG zRJ4Gb%8GDj^8DjU+UW6>HiW#G()nnV1()`Rn}0m?Kt{C?M(g`LSO-7-wbo^D6pd?k zd0HHP&dQ1H4pp5(iLrrsETuOk4@*IDnlX<;v8gwkhdaX0K*6f>n}rWT<7X07Gz$q6 zm=h>r%m2GjwwoS|wxcHC5};Tph>cMlq(Di!`p(A9jW2B!YO2dX;NJQHWE+m*9!SU> z2Zs@~gPlc06{s=Qr8<8CVD9;?CvZM3KxA(|`GLjRt|P)Tx-$4PK#Ks*1Ly`&{z4cg80>4VE0t7WT=KF3Fi^as!X&)Z{b9-Ss15^L@hgvKa!xx z=yU0=J-z!r0@mMCpOd?RG{Td{N)hW4Yd;o}A9WM3J1ug3WupJL!t?gYAF>s9U`>I( zTyP(`k$APDR(P)XlKf?AX5PnSIkRGal65C)x6~p8DQ{6JiQ&&HSUcIa%`Dg%{G~2d z{fCO*7lX5svt$RVNjm&{@DZ6TMVF|ceDQbWwo&SK=veRq zfjoWF9-LsJyx0)Z782^XWme4nAVXat*`n>@NC_>{&Nt&1C@0&F(%VKNEVKAB$c$&p zRonHWzk9w~jFY}MSo&RGH)^mvOk0h)CcTND5C!&`-kzSM&>=Jfy7ER)mWuD#G>}F2 zi@ims#QBBokE5d=h%-?F$wTEs*97PErn5;~gI0ML*2Y|A{ zGK`Q8*gepYygXVi8X3CAOR}p<4h(n536-5oEGqxG z2eWUs`F{5zR#oczG0nw9pTxwYcOQx@OzUnv3$`Z5o`Jvc7Ry-OH0pOp`G=gVR=$X$ z)%15ZIz+k4c=~qvaq9^jLtNlqQ=FdM3A}^5er-Kx({zq3hqlIfG4oxJx4pobop1-Z z|NO5zdcG|z9$^Vw$1TK9kNO?~}saC?GUiuc6k3ng4u zD$i|de}W9zlSjCiYy@-;*+NWiMMqEz7-ZZm9$y19R1gk0J(G7}n4n%eYXyo}btb~f z8VVR-P3Eb6PfwS)+5;P>E2Kh#Jq;PtY)8o?;T*Uubbwd+A4CHm`V$MIcvP(jRLfx2 z>x@t3=iCCK$kz}NjU!&D4gTq(LuLh^H5dp&AvkK)pZT4Gif^fW9au;4!=hs)^1?{O;Rzaf`>v3cii)=`Z8@q&PmYWwWWfxs9!x_b1{k=xSkk z75tjy$)0 zb+k4*O2?6$OCii+3$1fCUH(gPh%uL3Ak0Pb<#Z*RbQp{DIZG~8!4Jao#UX;hR}}9h z`FXw?-P4<{pYrxue}))=#^`IdBmL$~HP zYm|qY21%+~_yX#QTt+~zfDWQZs|sgEOXUK>{|8pfDXWGhh$Zk50_X)Gf>k3yWk3qV z>rcX&Jc_W7k|5pzXh?=dK}D@uvJ0aPOvx{@B<;Ed!Xy5Sj}hP*(k@!{0dF7>o~)+W z%dFXf>Dp0=r*L$4l$Wm@q1ijSC&(3o67t?3V1fj`LomYGU3xnC97LTU^rtKND}$lF z2I7uIB7`!5o!-Qwj%0XNdZ#Bk=hX&B`J*!p4epGd8Pm^(gt6wsAhqfx z&0l<-X6pB?IoyWwFZe~jfGg$xapg~9riRD;m1B*k=h?toe5Xb!r7zeT+-EkyE8cB? zvt#U>4J=nRq7G59x86<%5GTsBn*WmK;FZCp!%P$qO)jf8;SQLUR&`8>Fyp-ArKS;Q zYoU3~K9VCGba~g54q}sw=*eICmPVr4vA{Kh)T_so`0d-b3EXDm?r%WWkAz7e!zdZd z>-cy~ZRC&(a@UwhfRaSD7mdGLWXu`*^RCS6>k;2o2J*d^$e z5jC1|6+u;-0hLZJk9|4#>nvESt^oM|VhvnY%O4w{V*;@w?yqA3U>8C3WoyxUlaoLi zcSg}pt#N|}e9Lqx+b(0n1-AEI1Ky0Y8*i6$-iX3UeZO}kOmWDZ9Bjcx|LOd>Q1G3O zp?9vyHiaBl^Iodz3;!<;*GmC*_Q<1XGQ|im)U?HSk1BnWv8R^0qJ?t5hz=+OFD>1+ zesOcz2@k~H6CzBRzD_C$yN(s9l%4$QZicrK!D_y8Sja&T#BrK>YMH`5N4FR9*Tt6j z>R6%X|Fi&l#e`Ye1*jivl$HGsx-T~K{OTq6`Qo-2m9;RKr;hHPRv*bu;6hpP5852+-LG@JKRQsIB7?KBNvTOJh+GJ!nzsjJxfHdE z2LdU2*1Kw%r>jx&(SoW3xhwbVboFRiomRr}3J_A5Y>llf?B{Q|snwKgqjhzkp|gUu(h7fELbL5ynkIu(&WC(vjLWW30Kwp)mfh!A~X=jZ3= z;X#cFvkCxnNG>k0hVT3aMT67!?P2|7r>fw~;Hz8q+o}%Ojv+>`u(CXtQ(Rg0$barC zFJR~K{UL*`OK|Wb3K-TipfON*$!M`4s8kk(BZT5NGOU$M=X3`+s2P%L;;^DBUW*y+ zA!_&N(TXB0!uJ&-MHT0$Bj@84FbR86!v1<4e*E^?BZremh#<|RidZ2Iy=|Sm?~luFWhw5Oxq92X3GcfE{!>T~7R1RhtLw6p zQqU{KX6C~e8Lk6)9?0&82f>ms-l8eyy+?f1kYYl0F$2^@a*kOK;(?1i(ofnnIB%`= zhf)xfTh}ygs*vrI44gSDdYjDcRm#~ZqZ}WTe8zV}3+HE2|>zqZs`R(G?v#NDY)kevi=1tUV?&*H7P5EO_eUrnG zQtRk{w_B|_V8APY3ysS96_|?8^tyBg^wNH~<{^wjTa*cA5!`8tJ!F&%!sO8)x%_4! zn?v#?o}g%g8k~Mg@Twca3>hhDu{slYyF^>zkibd^J`=)~s1*w~QE!DnL>Q9r(&su- zHA%4}ghi7!TM`r!&4hPrllPC_Oo<5BXb=pM>8>s)UA&I2E>rR_nC<}|JFh+0;yj*MW2!Lhdi7B5(3?2>{^Gcc$od;i7PR$(YJOGC1!v{uxqTOwzTgxL;OCEqfZS=MaO||3l+js_W;gTy^^@Mr!r>$l78!Ep$RpxW(jQI%4nn zf{7`kyZ}-D_+{9%>NTgvD}SH)FAe8BoL0jQO4tIGv-WrR#9ax}E8f4A4ee(0`gdlyR_`K@1vl`oQEa?!-2S@n3c01c^_x;Oyhroc(hw1J3oL^# zsypQP>$@WQ-AMn1JU&Ez^A!+=!7*#QsTC3UuAZEnfY-^j2ZWsMUxH|>)(`#2TU&^QL&a~Wjp5cwwo|2GykHnj#p zp%Mg)5AXi{vlJu_tT(ZFF|ARi35J0+I^FDcW)mssFBwRsPyd18Q@!oq5C3H#gh)_{ zE&-36KI^+aAe&<)Gje9kYc3a`rN~9|<;49A5TlflaO}thOEwMm9mabAjStejKCmw1 zHR~}1*k7JyaVGy%KRA?7fohrlNO%j>)S{sk{W5ulG<#}Q@-jI;*;owYlB2eghrdWA zi_(;AG2vEV$uGtW8FBgQ_At?W@0Pv&tf~?CS|ZOOAzBUXOMO7#yHNaJKXX_01AjB# zO6_F7`)qLy$HV-_$qMx?8s3BBxZ_T`tCu>{``#&;Ivzf@!0;qNE7^5RtGa2PP@xX2 zZA^w@9kIeLQnk7C0u(L2mw6_25^78G5)WrOFB|tKz2K-bY5 zrPJ@dEa7P?DY{8rY3MHx*%nj;v5>Ugh{LXg99hrRLvhSLTm0GJ*J~L)Qoi%J*K9ZD zB75AX5O?k&Pd7EE4CzxzE^b=TjwVlYh_}o5tgg4B#kVsOjz*bm;7Cp>;Vsf^9=4yJ z=Cd{Dlqz(Tv;UNY4|R7jaQ-d%uw1fY|1}+_i%L}vf}14CbvP-eUeh!$SE`q6jC~%2 zt5ERS_p`OfJXs3f&C#i{Cz0v;7hb)RS&*z0ql&fAuU+{DO9e>1&(i4$+i)w*w%V zuRiW%P^idWJ{Wa!eoqKvQ{ z<$98e95XCMO|@;;t}2`ORfSAQ^vBMk^V8dbKVEcGtlO&yaz$9u8EjzTvyLQT6;Xt{ zwcOP4)}#$b3g#!w`iF>gLg+nS_PJ= z_5Pz`+q-CGdM|K$Jv050q6yk1%W%sgCgS9fo6y6q^>(i^&xSZrD3@5huDU45Sgq+m zRDIO364{>Mm2(}VUGY%LaFa;0)L|+8QN-~d&G*H7b{QnxhH2&dLL2%L%!eU&+bkJH z4AD4HwZYBii_KRH$)j67B2_h|v&i%b@7x#;gE97F1Sq~(sTPxwhLQ#ddn2fajgnk& zQ@+@I1m1Dk?LsZ^6=B`zCidcK9R|7T;8XQzCPn}5JP!{$Jz7# zotFM}e^b3C?|PF(=KWqf*=#7s^*Nj8dP)1rY^Ap6roDytiO`bm{|~^-nseca-Awqn&2{j^jWB5|Pa|oU)Y^q;E zF35G0PvT{0{8N5{t>wI#4iS2$s7C#gHIgJicb}fxXN^cuRRJ-~I+bT+uL&S(fw;rr zt)e1EI5r8+>_L3}RU`J*bo%(gk2QlNh-?ssbOpNo%jWX^j(%VZIij6to)R!*CL)WJ zVoe5l&S^Zh-`w5^L_~Ns#-6=Guoamt&6hEQXQdxhsQ6%g1!F2qhx8`qCuX4u-wD6v|oCV-bV zB$j>HpvkMameGA&u+Q){__d-*2OrHA+EAujO{yTVcS}ep-YDa60t12(P#f*WLP*IO zVIOl}lmi!!DNqu8GuN@%igfu+hQuLupMZWbyRAl+#x%x(Joc^r)h*hWdkYF@K57M- zjDGK&GcPYxa#t&5HzCyJNKZSVleh|M=szL6WyMpPryi6}RLKhzTMFUn=p zw;&oX5bVG3k5NIV3ft`cBnlI7Y44$~RIfcpc&-n{Ap30M=UdNBb%-|PLE^!HeO1V) z@)9Pn(>Z2HYoi%-;9rg5YAwlmcLXo>hn>~pY&C*4M0$)G8D$23sCac&)qXxgc<@Rs z?K2FOn|=m1VH9xM&BI)2!y?9Ot0snasf^8wipb)*cLR8WU3gF)2qh>q-!z|L5vM;Q z-$dmFqJNfH-*fU3)xbf{xnD!;&p8kA2gijq@n3xHCF!C6ql$UEfD-CN@>szq zv5d!O_-vT%`JqYD0H;Qs??IBd?ZKW*?eV_i{^XwZX)o5$a~PKcDr0+x{eYG1{ZwhT z@mn7Jbhbi|r?$%<@80luPrPM)OtHTT_Bei6Ps0w^0o25CNf9#d4U6{ci1i^`R-ZY^ zH)OY6lH;$b12N@%JdO6ZlG`l}5-_hk1Llqzt9;gapRYcgJqthn4qv%_YIj>(62AX4 zT4v~dW3A=6-($MsDs!Iywp>T}HqQ3BJO3uD-o@o@6CKfw$S?S2z73fdxbz|TF&P6K z$ip|!3m(V3E#-S(To1i~FtL@#QYwjdDb9SsAwDv)%2W>FJxM!(fFBJGLLeR#fw7iE z0m??l2Co1ILy(0~MjGP5&RVmHd6ws=K*ZgkTg$M~a^ln$OA+nA>2tn#`5-!qs=aU0J zFwY2ZMY)WN)TszNI|ERGiW1PlP*G89m~#oHe*e})=mFT{K%1q-MTR6FAamMO7^*HU zCL^ygzIxuykLvEC7UC^^)1EE9X1(5Sf)yu>C@xEr>!iF$T?+ zIW98`ODspGTGfE27{=oD&Pw6JQ`RYWdSC6=Q9Q4X$=Z~B<+eTDAA%2#*z{F!2+UdUhNih>xs7SR z@9X>230C|ro|UVUo1cj>4r=p?lIClxy^Kq8*jRf&p)byPD!$tjF#PlX(DhB>aR%Dj z6Q{9lCyg81wr$(CZJQILvDKhS8Z>U4CTVO>^v~Y^bFR*F=6bH?o3*~R)+-1M05u&Z zd%R3;^Y;|)MnFiHzNWVzd|Rs6uR_$I8b&)*B6)L>U8K6=jSw4n9sN0+Xgs>BS3)et zXYcuo&Vf7Gcv`f1woViZNK;uY@2l%ZlhIzWUzuv%3(onj1$GcHQ;YegqfI@ zUA1V_ch`ZaYO&sQXo}-LBTA45Iw;1s$hy5=YjM&4c3=M?a?9LdY6OHXQevfS_!?p9 zbFvkk^{SL-#ND;@<^IeAc&Bgr0;-t3n2UCt8E~#ZT9H3QNz;n_g83I$hV^J?GOJJ5Q_rcyb%nKKG$!G zKaLC$?OGMoIR{@uqk+;~$PbM>n;WCn$_I+vSLExVL1|PRe!wsMiod20*~e1B9-H-s zz2NM)!e?PXPJTY+s#0+9C%B6E`S`$4D+-B#3?D>T6xKFa^ZjMKSiXpgpy}!UUO`zI zECxwUa0>`1sDBz=N=ps)@W{xS1snLx&dxSAGKbkio5o625`EQIu(Z_%k+ZdfL#YnR zDO%E9_P}s|qhas*`Z~BwzocRG0VNpzCZ9Y^E(r?=2yk*r&S&9S<~3k83wa#RgS$NV z0A_7v^)p#mP|&b$`QOnI94u^1mXp1GJ~%utCr78(i;3J*>=R5h0OtaY-llOE>saWC z%`dS<4)heE-v)a$B)9Y%a%PW>z6KST1<{6u+2zFskld>IZXkV+D@uK7rRB%j(^ z^dyo`M6X@WhyC`h13;@7oyf=#7Rk0)?vyO=8<%yN7A*5hwZMmIRNco_=UiIO#9^;} zGuIE3qdy7Is}2L`9$ke>!7uY8Qo$2Gh0|fJd|hL#|AAd^RIh}t?PByL!fX{cdMp9L zi#;{v95%G1J|p5LOJd%vMEAbm-{z0Lf7C`A4ds)^Q7G2-Z>!k%3J+`@4^CZ^DJ2H| zBP=GazJ7*8Xm!1fbX0l6YoS=>*ilKeh!^)tjUwyyqT-`O=nN++pU{|i zh~yDs5YR+qs8x8-hs)>l|JiERylwM)1syvU?+-p)atDBvx8Ga#J0Fg0+e^1I_)G+u zaVoGV3}4TM{bz>fKHfE10-Y@n60G|VJX!jy{e#Sc_GVH0PCMlZ)R^P|Ly{Gbo@SahJul9T+=vUcUKmh{dJ4P?KGwNEi_Zq` zQ-z-oG|pmi2X>!~?)n-Er6U^oVfklXtGo3-PtuK_#~b`{GO+&qReO@j#L;bOuSyge zWUQoUI)I0{n%?yu;OWn}Z@K_#EA^}(0pr!<@jak^CJm!Jjak?`bH^%4)@&~PkshQ@ z%S!uc&l@+4xbr;WFMN0CJ$Orr*k2{^&TaG>XYFKTZ>LdQoj+pr^AaRCzo4lkOVoE#n=?&#nm^d1B|MgG+STQKyR{($wI1)nxst!DB_eS7i;LyA}KQGA5CAaAU zs{$FkC>#ViI5-3a1$lU6TJ+L-(q!WoT7HU{i!yXi9N%Hy7v$$pw>X%Zh7N>fqye}u zn9FRzVU*w=pr@~o&+Iz)I|uYv%OAesX_l(AO^k^k6Vx*|;^P~Pr}#ZS0v6gi3l+`! z4FUOiu&nqiKt*p@%Ve)*mn_S4%zJVYlT# z6qXcs!J5w!Rps-?>4DrUlv_U@f5WH5fcv92Xf5xMC|oZAIE)rkrPH&@J4R4?5uOf&UW%z_7fG^p&B;q8-$kUt!-B`0!DK z9iasQP{|MU5xTgr$0l0`d#^rizufOkXOn;)C$>Ss!X1bAb)aZ}Q1RnG<Xcs6Q%l%7kemMSH zLK+-58)d+4WNdD|yT7&F7`yb)SyI7gT4&)WhC%N0eo@)a7CI3iL{1^zV*<1zlcFK^YA6g9o+;+7pQLHoiG`Gw74q zB1?SBef3)2t#L3`5yMVINCTE1p#CPr$?$upEJ00zh?v;X*;#opL!&|B2_w!>PmiKYmPH;f`=BU8Lk=72 z-c&}+q}y68W}!9Fi=Dbz?I(cxOIv$8x)03$Jnbnshb59xr9!+in$)$kQY}`Zr$YSV z^wiAB-l8(LJ|ogq2~aZ8jH1=G0jJi4aqJ`BYqnQ-`=ItWzBv^ZA`F6Gxj<(}!gwxR zGa|8q_2c9jYBYz8Od4tdOXt?+?M{qL=NsV<;FK8x`NdNEEb zBrF^m#^Y;~5p4OVWYEq!`*nsrfJ)JH-LBYC!IKcO*mMIgm`(1rVB zcf;SPWYa42Jqvg^gN~G)0&Prp9DIS|9ggRMBmggDQlIKzH+n-&1WBpv3M0EU&Cp31 z82QT64aiWnFOY}jhl=F5yc(^2>_H1db=#l-z*@j*EI{OQ;3lJ8*J!d70oe+~bQW|N zHt_kpkUh|O<6R_>HM{vSSNsl9^Z-=6NKxFr|IuG=UBtDryuP?>=q1<(Ed*S?= zAMA6x0UqosD%pEqFJHBkd5#W>Lbx>B?Hcr!t75R0E9KTZog9@JTuzFbg5OK!Pyrzh zS6^9n{7vw=JK<#}iu@*@2aTV)uNnhiA}89dqaU~3SAVU$ceG!EhKa#8D+L^D>&vSf zMrpBVWt)rC|GX5nOFIK3knT>^8s4Axqc*6P9zSl0`Oh;Lf-gYPY4BixuLl`%c-lvIU zr2&1`++hPx+j5*thnDo||0ppG){~Ept~fDoozm^bK9IYcq((zV!!M5>@)uSB$jgS} z;Iq?A7K;qkj`xSM;IbGMF=}1e<%uWFF#)3VWKDsJ<|=Ln%eBjSdn&DZ?OF}X4DAHA z1;;~`HNbD`kk2nR8nyiRKY_*LS zDr`kw>k#4A!M2|sIsAjo0}v2$;-=W(#Ov&_@p5LVhLHmpTA^*y^lgaB%+nk5=-xxj zQ1+WNepCJUJ~w#74VK5qUd7_R&+;3;SCBxoPYqlJg7WN1@|t3^hM5K*dxV9m^fP*b zUk!s9g&$9ZefE~+=NJ4pJFNT8QRluGH+#)-vIK5(!h(cOSO%X#+8^so!S6lU!M@d< z{^xCu=7->{XgTvapS?feSO#aoqxS~=&)xMW!LydSk3PSPs_pwSRH7+)Lwn_c<1uF* zxTUwPPtf;4zo%EUVfO#w0vsUF6rRoY-y+ZP4?s6ROijaXzfR13GN1_F^%n=cQ(C(4 zcf8NaEBjn+7=MI^4qtwxcQ~AEZNdM<>0`mXqoJG&n9iqZ>V9mW^AB#fJiedazR!}E zQs*&qh-P#U|oej7+$w;U%$R~DLUdXHqzB4ud!^`YcH__Pf9eaSm=@`?*Ngt#=1Iio^7m2 zK?5x@K7MX~K0nyb3mj8o1!)037=YDz&NUhYcz9%fX;{@*na-t9Gc#cO^3LGTkI2YK za9JrRDykNVG-!cc@t{J6hea{$!6shn!x)*VY1G9=wQ4mgTN=T^!jfpe=H{LrAHkKn zv!nbRUaw7MNS5Z{=hxHTo+)z(9y-Hj53tY9&#CGbfBuB;M_2uwVIukJ8x&M@jm)+P zwyXiKND{*sdveUoe~W75O4Mo;l$5|csLzA4Vpz%DM_x4lK*@}%Imyr|oc4U4fXcr^ zOS^_d!T16}4f^nX_0EPFB>YR}L;v!7$drP^!XD+1*d7xv*XfYAoxmL%kqHOEKiGZ8X0=r^xiJOJLo6ed-#I%6nsLr~+wd%-st zo^(we*FlaGLX5X^r_!g(RV1on;B`)zC$N5(DN%6@JAi^ zZuoqz$-dWm#2f19h>U{!^uT~ntuBTbcu7}>!=RTqIy&JB|D$8i%GAM2Uf#a?W zI_qh7I2;_UtDA+6Er&|QeycA1HSitm;HXw3aiL{VxzlVa4lWz;(rpuv95Wh@@g%kQ z2~O4kyF&Vr9Qkgqu1dH1%O&I$6i|tdfPav$nPAPx)cHB1;+<@`JSnieJX}G$!W1S1 zOaKO(up0U7MG_Mev-o@<=2f}6``_!Q(JH?LEBEXM&n^oTxvXUQcmL z4rtiUhz@c1aAxf+qoL+qPaBf`#D%jxUt6m+;HiH{B+pdM%l;c3~W6qp9MZNl%14AC<hBzfd} zV5@KrbV^&+JIT>P={cYLDb)WMflp7){@CWzbCtXu`IPJ`2Ekwvj8WD)m6$InNG#pO z3L)F58U3K&A|S=Z0B>H=@4axn zxE)oht5B~|bm$9YugtJ*W=AXdf_G000LUDgT`H|hGk0mU**J$am&v`RGP)?^@lSuJ zhnKNPqpGA*Os8_yVDY0RAr(zQE;d(h;F@XCW1=*=LFVIxOc_%)wv9c*u2L(D|}ga9t0#2DWY!YZd{k7 zV6SGgkhu;(#0utxF1xbaWG>$8F&kum#I(Z9RZo}ftD(auezb%u8usV2Zeuycor3iP zv`%7>;^LAV*PqGV<*rrNKhf0sOS*CpqHhkds}6c8fHEV$-tVhC)f{YoyB&_+p_gob z%}|>NNa90i)ImMwYw$TM-2(CK#)W^wO1+Vs_``N+Hk*PTG6DT|5R)YY5r`tMiFlh; zmRVbs!)8J;v`|<xauwa?Lg~QCA#=5@G)Q2EnXsp>qx%1OiY_n-K9V`DrF|F z_OAm;2=zWhoE!c^xlhhbW8Z(D49le!p8F3!v=ghUk|g5%AcD5lu2qYUFSGgMA`PLd z{NqEBLmV{5;VjrZRDV6F)RM+6YL%2M3<{}IgGak>tMB}{?v8H~#8$54>0;13P#D$AB!NYFg+%ian(b5 zC)Gu8_!q6!XiVhvTFe6$p}t}*2U*#{nMl_b;m6Cvt0GABt3Tu86$A|@hkM)hF`D;= zDSdH9$1v!=$=8F;c1U_8bNejtm!{9v)HCk(jDrd>7PZ>xNn#cnJt{HAbw&@X84Oyy zw<|7=KH>VHlXF1_Wkw#SThC1_DEYSvM_C$`{2v{4MHKr_bOCguj(dGf}ZpaPJ7T$NUylr$-gZB ztFKq7v5c{8jCut=!=Bb(aG*x+Y#d2z0HRTnSYc^3_w`>ya?30xAczFH9Gzwwy5AQZ zaE76wD5EF}73iaM-)<(ay2JLc{kc0?bY&``WvEG{xW<7IjOK0}WLbaFze$t-*7*aq zcP?t15*DpZpgMq*N$~66P>2|omvE@PExJ)KH-JK@%hEf`YMvD*!yXR-EwhN-zg!kd zqAe@MJ#Ujuld7JFNUHe_I|{Bzhz{Zu<@(RSsLpm}U{?D6aES!JSf*OsD9ruwoG7Ew zbq7-ZKi#bFc9c$b-;<5*`^>zgODPaFObdI|S;df=S+)GS24u*oFiq#(jdB&_%`Y*| zBRB0Z`rK3~GAopetEl`c-Z?k;Q2})gnZ=IX$$|RH0=F_K0{No)waVmTPYOr#KcGmK zPxwJ+hl6hC@Qs?9{>2DFk;RxMEu8qu(o6KGRz@*4izB}ACbG&w!x7SP`5neA)H4hU zVSgf(3*`VR2yRS^8p921D++i9aUJ$Ei_+g8s1502v*l^(iD!f66kRr7{q zKdO5H;t94sSB;cdOt8Y1igCcM{G++Nu^4SX5fL3ET*`|$Vfi@!^*ZP~=3RTJch~3W zlsv(;!Togj_2c2j=kVh_5I6Yn?dEmW?U^DD-U{(Tf!)dFyRSnr>ncMRpVz%Aedp(@ zt~aQ~%8T&%csKKxjuXw{2=x?0Dkd+u2(l zMMdjr>vLb~T@hmiDTx=3(_RnozMg^zXOM~Wbp2h9R-#w8JEfKesrJb@ynGZ7`$NR& zPBi)OF1gA~*#?kcxc~4Y7=?U8P?Jx~NCMqY<)u;W&A?a*4WX2e0aY1sRbR=V!^o;- z|2!ilGf+tWCP>WT&m0D`_Di_aABKAF;uFgEqkpH>)6wolj-MVABRDk_=4Y z%Pn#dJdM*S{GoWuZ>Bo`-uA+f{WYO^5!DbRzKF=`;Qd1XH4v2X=M~&^I6IBw67#rz zymSexAZ`k?@&62Dz0{T5#TqH)l42p@HsZoN!`+*eN((s<8~ix;d}?TK!hel8|Iw5}lH}baNVhI$AI>+U zup|6e=|zuB<#CxnsgNvSqs7^nehK+*vc|DZIlWEdlH%I|H|2*!3y-Ql*Lt$WMm}B8 zCJgzXiQp`2UzCuQ9p~w<7dBgZy=C!{BgiWFx+Vqkq*A{?5?!B7`p6PdnW{)IlPxBlhdGfU?knIoBn8eda3MD7(nQ}$2_ z0aQ|EHVm(x^h{BsTCnNHtUK|#0Q#{(c)2(URZKHlN-@BXFt(jT-x;u(r^n7#B7JdA zJ1jQFa+Cx?j6$QK*JDWStUx1KY*lF_33vMu?R3_uynpX|)#?lOED^IKnAZQ6!!!hS z1){j=vIb9~$(2uy{RN`*xVfgQ*`bY{v5Nnhn{R;(HokiXCA#$SYwyG*jq|and9?_T zBj$K^!6eo&f*2<2&Aga#zimrbhrRcf&VIEu)vZ3`4Yogpu@&McH)e>@$MSjBr_WCw z7HIiBO{gv#K#vHvS-a4hUrm!5Cm%ZmAC7#3R+6rfJ#rowhf{>O1V+hC$>K z=eF>&;-|m3mBW+Ig{+7$ycfm4;0V(@a-=j>nPD4n!E7S!%pfuBU`P43RR$MJ+gBwL>+)jnm*r&9}yn*L6Ml#J%;AT3!BUZzd&MD-*lxj z2J4O`sS)67oiGct@6OIs#Rb$6&^O0K(+a0*}1P} zA93IuH4KLFx-+}U5FWmx*x*aUXPBbHI(YKMB*^y*nL@#M;FuD6w(o+cW*{kJzf#9H7Lx`?ze^0$K;)vgPz4*Q+DDZw7-E1>@Ri$8;7T!g6ich zWr?Gmye`v9G!fiHSP5sVk!BAb-XB0Ydhx|>!69^}9aRL?u*6^Yz*&K85;T~Sl$3A` zIp|m2=MngNW8}&m@!w%%7uL0Hof_%|r`YHCmomyS43hzeV+2SV(flnW<;i`-(?ImG-=TP`&liOMXQ$-4(6>asU3vQkulnK}F_GI?n3ja?dk!9vyLC z@7sKmg>lglMK+`=JQidePTY{VUZ~>Ta7^N6P4(T3#{j*03-ldDRjCNMs^6C3f1iTB zd%OzDT9FhQJ2Vi56h3C+j|m=0G7LHzW+n1%>FK0k_z`k2$=%!7$fL{0fR2X5tPu7n zhxMLOJP-M$2v@UU_`?CpF?3=h<~R{%^bu6ErU z{b3i~LvBx$iA^RAKgZ&^y_KBEM6If9aA3%^Z@Wm&Rk$Iziy>i)(?Zg()LzraFc6pYX!Fwrl` zP=i+R)W~tkU=U9Bl_|h2**N%bqjEC2MIYDhx6#q#(;7*>EU87F zRKqAfHVx&ArkP?$Fua&@UB}HI#diYogpla3^4@w2Mpx+=j(!=({&fGeMHLzmmx6Bx zzrZE}rqcsDyf0%urUE`ooBGf5vja|RI98;gVN8ETVw;k}w&2#eFfv4rEHe(;K643O zL)2;-A_Va>Ab8$3)4$hH$%1phjxx;EAw*;q@AWm>MFx8|lDbV*WyQ6o$)__^Lb}ze zgKgFVF!FIk>^r6o2_W+0%^tdlbpiln$@Gv`qp(XQ|z(JSIVezGuPmB-iT zV7T~h8fq)(z<`qfYKUYbNz`n&KXpRQ@-}y;1Uiw@$3{6$kB(U#JlMb_L=iYc#BKV+ zi^QkSRT-?dg|07$5%_Dfd_9hI{wd?^{YzfIYEGR1B`Fr7=6xj*jHay4H4R>|kqOdh zH9#fT$_wOds4z}?fkWDbUy0`RFArGBp=gnIpj&hpH-+ZNS?x({$)_niZLiBT-KsZ} zBbU)``;C1iiJ*OiPxju0%Z0^tiOSa*Cl}CO{7Yl5+?n3IyT(hh92^G2uK9HIta+h# zokJ6wBKiZSCzNgD1`Qgzxtt;tr!WEyC~Y-xyYVR`!24Vl>@y%JEAvr(qVhDQ#}I;A!}84Rv-b#is9b+IkCl9@VU4I3zV-~w0Ysa(H9Q*Tu+x89(L{RqK9BEYP&t)c zt^AWs1KtZ8-b+RaP{O9*wC0hpYISCPh4F1{^WsJejYj6FKz-;j#yacW@oj)453CRr$pyrCMG5@6+&EG{Gd1ZKz|B!`NNMEw;y*> z79tESeXY+yu`+=&V+knXUf>7wq%${+r8^QjmW>0vM}$DG@PuGZly96oMjim-Alrrz z?dJ78_v|j6&3 z#;~xl`slk26edi6SvUTC@6 z)&)LZXB>+ojVrgzB2BcdHIin4g z1((wdJ(ooerphnIB7c}Xua_+3|19VIbQck+bht=YgI2!#1))x}3X`r6BeDg*3%TTz z5Yk)&2%i?DRcazOxCF9n8(yw21&itH6ME5l7k!J2fux29lsXV(h*oYREY!LrxQ#>q zBXp4s_fI`r3+RW{AerT&x3P4q`p;?&W7Y#|6+18ZdhD5-;qaKjNXoUXFQJsYlfafDQWeB9}? zc!c9g=4oo8LiEjoo??%$%h4d7^I08F1%snDo=@9Sa6-X^=5E>1RWaLpd3Bna4#~a! zx4?m!6ge7JTCZWr2{9{th$9XIPsXonKZ8cZ>ev9Pzu8knU$WAMspd3iF}&EOv;&|w zyJLv{LbT7Nup#s461-7%IYTq-$&kvULn5eR{IzQaV{@nmYq@H2p$pif_q7O-_bClY zEHNGPu($_?JaNc`*T8K{Cpz`OiyZs7hNm!SozD>6Ju}mT-hQ#j8CG$jA==LV6n0O8 zsyfp2JabOb*9gT$wb~=h;WXCvYYiG%vm9No{95`*in%XAU$bLNu?UatH!z{osPN;B znN(mxZn}p(zlCpoHHv=ocrDGmp#IG!6O0Rhp_@0Hw$UE=nKh*KTRvyUpi@EB6zhi^ zxv9ZjF{oF^rxq2i+Z3P6a`2Xw-A}hRblfUx>HEN;FE{`#cpTpv2?=S*u6+U<@q;Mj zA6t@TFpAEdYapTo5edn5hvUXY=S~plq>2=s%M+Pel3q2d`^GOphfw`|4_TL&Ymr+R zl0G$i)m&A@#z1^bdK}^xLPYaGy3|tLQ$k-)X-8=F1Z1;WosGdRR`)64gDR&5z93;j zA?7|3w z=TO^A1akGN@g~)#0S^j0f{b?ps{ys!=Vq`&U;zk4%Fi-5NmnaTW}sm`)_k#qnv^WM zUV^Sh@^tK1Z?)#gcuW=ww|pEppn;SvHo6lseMtTm8Y_J7?iyCvb3CLe)Q0K-1*(AZ zZ*L22xk3+=Cvh$Bv&4_w4VJ8u)7At@$c;!>GdyM6OaB5$Pmtdh>=`@7g2az`H9dCr zyrrT#*);eX+BYtx5HDbSZ1r+2nBAmTr)9sa*N|oD`>$5&0dKrQH&;cYsd*J>@H?|T z$j&CfuB2i8Z>puC`xEMUzN0P`*g_H@tJ~BeGc}k+6f9UOE&S@sD*iO(9G;)q=qW+KoSWvV9HgME z!u56LSFQV>}tg#7!?APvy}jv@AFRx4rgmx^|i2oz_zX%~-C~ z5Oi&u#}(@#75kptVdv{m8~ipT;=<#FtaN#rZ=j%ck;#mv5+>rkF^R~}9`e%A7mhgO zQ6@!`Pw3vyy0&CRn7_m;uR};!*Ki?bV`77tSOI>Ko;!*1KC_Hcy}ODn402rGe-Hcv z;w_XGSY)x-)d@2#XUZxQQ@xfAKd#OZNt~#Kh7Ww&)*rO7R&9 zg;|faxYyB=`>lYSb4Y#d26Jh#H&jC+xS-uyTp)d>zx4Ba(>thp&~?vb?_;>Epb(Ic zV>QOTTS0C{aiNjfTVW80bERZu=Q~-zm8F8BHEb0>g&(>E;eR%aHa=R zrVGB=TiFiSd)Te+S`^hW&artfVvwhX$p=Cp!A_&1sQg|PaE+uJoHVSCp7D`NTo>Z%V6$MoAI}puVNI<7cR|FtkzrV4<#?UC6X!8+Y=UxJ*1t-0&MXBSOw`mYC$Xs| zv9iR+bnX<8>o3I8BCgUS z%DC2`jb-XY}?lAQ0`t?x8&v&@b3`%L0yP+iAGoVaUm1#Xeui`X&e& zxvm{PZf7n@?>c$T11^3O4Tt2qEGQvt)@VN)7Sp4ie+%8HPK{zA@VNbJ^`X-)K!@B* z$Qu^V;cj5+(^X?BL797Xkepu%alSvQc@22DYpb+ZQErnJP+Qbv{CiOFmd+Dnb>M`P zzak0<3We;tCC~dY&Y(bN_Ax}*rdQSUbi<>MolxZX9W%$LCFD>usqnkwKCi?LhY@uY?TE`dAC!>6MF%Xj6dm+o9R0f z1h(&w_D3sL0^b83J3a?g3tsOX11Bki64yUS1NN=$i@a{eAI(*EuJI_gDE(?i_V!i# zaGkL@{Cp>_Uglwjt}0N5NYV2IplLhsm+wUH*t{9Jnz3NKCztG(>XYGpTitJ>YxtWx zbQ}2Yr6gciUt(K7pY`gZ!6JZ81#)CNdf=4X;I^B{xiT#7zlFG?eKjnoj@Nd-_D`uln-j#HNje-$Ln+l8 zE3kb}BK>|zt0sd+6D9%=kmT|ujyzaaV|8^)@ntA$M|Ybp+$AtVx-mv0Br5*=&9r^C zE?AG&mxRfz^Zeyg54`8g@7)6*Nd1Q)(V!)GN7X`TxFfkEywfdKNd9H-0Kr&zM@8k* z0&smd18AGqj7C45uLp&Jc+9<~X`M|WZ#vzgmni|{gal^Fan`BoNLW2!P}z~~r1yJZ zV8WzOfm4MXfy#|;agrYhmWUjP0*wGikSw?d*GJlTde{>n^);53N8SUzuYJ5bd{Rnl zUjP2>wS-WR9`6aGLyOY^ep)-dj6ab!p3JFV8g?GmJD&BXP29T>wcajD*T^{Swsb}* zVRITq{WIfA`&XD8Rw;#B`{gXyic&6~=HYuLEi3|?{ujyH0WnqEE#J=H2VauOC2*J% z6J_f`9~h>ksi9RpA1T4!ClC8EW{fsyMKHi6+PMed<}(agV9^vuQoNXh9EU=nw&!n( z(ZAMpEE9inrH}Nl@;E)5`9i+;CN3|cpUBXK94R_bfdd}4F?jWsk0pg# zJolv+C7opeckIg>S=hZ@ z8}Bb6Sd6m+jtTElw04B<8~Z4Z2D?>tDcXwuzKUG`kaEw(HqADYPHUH$0ij+@F4O{@ znL4KahW2`=RUG-`))gU?XgC?;JFJkIp?d) z0VX1pJM5Xv%xW?$EHV86@A-6@Sc;*3(BTLspTq#)-4HVOrib*-w^;(YOfivAK99et z{Y|uq=GJX=4ZK(Q8_^h=`kUUbsLuU0_Pb@6d z*A)NEb;`qoVE6V^OcKa`ycFV+GXpfBv_1Ex$H_{BTUsyxq;RT8cZO`6JQ86PMWmUg^mqk_a zpK4s)#q?H$5Fx@U;lIAlFIaO}XTY>a-F^E>2vDKn&_B8}sH54PFcO3;!QnuQtV6j* z+)bsTqpSQ7Ux!Ccgk+XTJuCP?L|2ivQMK$bAwGqP>H6Sn?{V*47LlaFEIW2Rpj3%##?JH_sxr@J?m&P=C=lbJBeakE#m zm`niA(4O&gfWJ(QSA5dBD!@PYsqG zY~9+0Z@m-J$}@`wukH{ zsJ+;C@#L`P6I8Bk9Q=4U?)LT|n&5x?Tp*|C~3(6u+8 zt>}~TxY%$;t39pHR26##C?f!La(g}>d%cyIm&hDR`A!NhXxqrQ$TPyGLVJS(Ha3s{ zD6cQsV}B)Em`(MBnp8f@c3*}K$(;0e?sq?0aw}>>b>ewQnEBDr+;TL2wYBIrE?I@z zDPsBAu+uNde^_>5-tbokkS9HpL&E7iMJ)C^1m=aZ5&|3pq!I`0?HM+v4|vAjB~(RA z+s>&$&8r5Y!Lk&|Vu{^D_wlnGe3twz7f#gviB{TY!$rO9)vDeHh`?wFf52?rft z9how`vuus%hMP29)+u?k5XNQ4@D#6{$~7q`B7Cwy;n68A4kme#k8F1SV)iQB zwMtP4LHhocqUHFCe#43$0D+O4L-Ep;I1+H!ypn+yJd73D5PJ5#m7~r2;?a|xDgN;r zK_CP{4_3|uBII2<(u(UZU#+z#8jK4LIW@OUTKaDn_S;JxiF(BYtP`0>nRNchM@b$_ zd~*WR@HtkxSw{?2!j4+Dmj+m2hSX)=rS3DK1EJxD0nr+It^H^JfKoV&W916iO|T`r zYU*^Pi8dGX43&|qa)-Qn4UsN_%|fip*BP_QE1Gbyekyd$C7B#s6*KSnfC`k&haWIq z&j^30Cvg-@4w)q9V#=5D%`9)h?mAsOAHQzc0U~En@}K9J+J*CVBp?4cojn z9(nKo>J+|yWclH2^xnDZa9Mvo=$tKh!dBdW;~pF|v$e5vADUhCn&pu% zXzK9H-aFvNQG3QB`&76Kw2P``>^ig4*Dh}svg@Zf z@JO`&?(S{y>FoVz__3*YF+t!wC9U^RgfsCR)h#BX;ah~LnY-2M+`YM4NVi2su2FPU z!b-dua7iC{A?x^WfY7=7Fm$`BU(`xw<&z?}@Mh0Ln6dsw51;FVveQ6!z+QTiJs~&^ zJN9bFYhpBAS<8DzXnF8~o|4)#Lb3RBT0cNbfMFX80tTndh*8Y*p(3})v{-r!tFSHd zhm$Zfn}bMbnY5wlXdu-2Wpw>FDd4~exl+IqB{R98g|YBw8WX2@8S>lT%3WXmQ3WWl z=KTlcA}pXVJGI5ti&EJGYcm{JjeVh_44bb`6Vi5VxU*>!!*UMCp)O_5{Wy;v$XAMw zF-ht0+?wTujw}S`?TiD%D49Bt+^f(K*&fEz2L=m?l}birO}hU*nj_%&n^HAJepvQ4 zsUUVTg)%=E7$WjSG6`cqDsBQB@!gE&d?qm{EZF*iY%9L@lG_hjC;tvKn3Wo4^9EEM zaJs<8FmNrks8NbA&s92%#IZ8!wIOnf3bt}nX`>$R>-2*&Or=FC;qZ!kF}DOEcLi|= zneVi7w~W)@{wlhEjRsn1GySkQ1@Llg^m{2APnhLiMTqy;!L1PG;p-~jUbd1yPC8LOPM5E`-Q1%AI)T^v+`BN&{Ra^!Uz#sq zSoki4g&eo*Eq}PP2)D~a0!aREK{)<{u+9Hgl24F6Ulmv1?Yx~U5@Ybq_T7$E83h*x zU*Z4v4k;%y|z4p}u>ctvgP5hFs>s{?sgjYC}oxfGinlbAG=u zM7=69+?v+|3sJtmR(z9Mubfit@bnIy`WBhOblzh*5wYg;h=0Z>S#*^0b=2V#d8fyy z>CInxQ%Fb6x5ICD@8xk{nb;Nvrr`&zlg;PwC6v7VYI~))z7p?s`9{zirAqk5EU7~9 zaEfhUhOfuk5<#M9Hh^zI3hV3E1?F0=BX772`9b41G=kLnpoYFGlf5K@$AblCGto`M zrNAjtH#BNS$W{^GGPFJ2;W%s*2WS&ZGrnhaayj_2pQL+`X^=t?A_%$HjDb;d;?nZ) zj)ECDFbwcg96e%Amp4zt^kK%>w*CsfG8npzGrr+jtjiX*W}}5+X+H{IcJfG|!FgM) zjqJzETn)V?1oMG$mq-@0NyErX$CM&6skRCgukDl z!Hc`IpZ-xEM<)}d8yMuBJbuY5l$LAx-ZEKcv5q3?3?(L$K}L-cv@9*XY9dQM&ydir zi4KEE6(fz72n!l{O^agToR~3H7S%>1Ui^OmyFf(0B5|7VR3sXbYRZ-CgB|&+p{5PA zkYGe3yz-UZu3Vml#!aLw(aR=tN)T_001B1RH!;d7QHtkxI#8GAL{XYw6*``pG6|ee zhTSiu6jF>%_Kff8FRzyPzBo9zym#IFVn@|c@issdRU|ES$;HNMkLDvfNtU(Vx$D;( zp1TNM`|VL72tlW5E`$)dl)~hgxtYEWwGHk?L~4t`rdiP85{pBElktf4rl-8=Z$EHR zH)M-@e{|hd?|$dVN8f+>n#z6u@u|;z?Z#bmnGkAeNnTh{kS|OwBm?Vu!#BvMfBbLX z?Rv($F5RR}RQclcYRBn4^yfsmf26~nze(p{M`HfaQqsS+oBk{5S~Hj~PAz5)KB#Q% zX`>gCrBvjV9P`DgO6Tc)bTWvxp|y{(UFPwd>HmUbCIH#F>HPE7w+qZx4(`15wwoVl zKkvjYmd>MACwJVlV`6SKM**sqwU6Yes>@m0-kJnrNKniB9$IPLaPFE8$?B%l;j=G1 zy*~w2UD)@tTW-0d?flb+YpXTc(w^!UNZZOXTd65*l~C#*A4(_oBpcWFmwp-c@zKxp z&7{z^OM>5;&1zZVCl|0-OzW!w0d8Q!%ESwio{KE;BcDwosgwdiknG7msRr4$7DzSi=+oq?AWQ<7;1c7&6gb-Vjmh`Z1+!fxFArw*8C(3}2E+LBLcq zD8zs>s!um4IwBO%CSZaIdqOGo&lTpvfMYL-MzgWbgDf>@(BeXws64gjagrtpeKwE| zodZY;C`aYVB=kpBh@f1JtCc1J?}T?+jv&_2E-lO)-~I(OCNkcwI zNoQ&k`o$*fX@{OYL+N8C`u|ZXo(Q65tB1b3uR6Ed*LPxhaK!HF$&rOU>t7LX+U zH{V+;Q-!5ZwToXM3L8?(ge~qgvG+Fd=y+3e-K3r4=RWi7@|(VQ-{P}Y|Luccntbki zKK0%cI+N-HpMLdK2LT}I8tKY^{P0|MPP_LW$(l?5{5O|A`QEqx{a?K6#V2CS{KQDlFq@7{Dz5z9NH6rd|_fH>)hU%ifW5gS#ER&3zbF$SkgJz zx;nF%)0eI-99&kT$2873LJ#|~%jdcIYSP-fW~BVk{+X4Hon?|cA!23n?z;}OpL))P z1Fcfj4&3zpornmfwltev$yAT@7%thh@wBnIyKcFyw0+yUj>J7r>0Vdr92x7r_x1ye z`EYwVRn_IH!bAXIb-AL_ffNuiKlI?;`_tipZ1+8T*PJ!p_DkWiJ4)Wv-l)ut+iLT{ zE!i=ex%q-l0T2~Fp&d!;u{*K}VO`U@iS9v#iUObs*;se0K)@uSBy1kjMc4dv!5B3+H-j*wHDriJ5<0yCDOiuLZNYXX&0-c6wKXpB{%>IbKN zNYXPIk%V8IthL`=*xjxVn_}``^Te^NhM5ja!({;oAXF-3km@5Xm*z|Mtga0KlzF1r z^d*6U%DoJgTNhK|=i^F+~d6yBuNA%xiVzv5DJ}MR3QPZBU3Qj zx-V$AbgW>VM-oACUW$o_Xy|?YWZO=|xpqw(eIZM^l$ikj=v(+Rg7)LwBXi`9bfSh%L zY7wc!sg~2tjSNOPZ8m_NZz0d)GV3Y{)^o3^Q#2=)qVpl=*p$WswuZv?fq8c}8Ar+4 zRVaNrsg%aD!IDfo3f>e*VGH@v-XC9o!(7*Sqis-KthNlT8|_FSpS$%xzH^{<8UV=t z?U$W)-KRcv{i$!fuUauJ!#TRMpuB?%0!V*nY~I+JiUUcIWQiGuO4tCond3w{WTZoLxwYQmB;hna)^? zDRd&ZpN8XvO%SzXszL|76%%L^jMR1C(u(7vTs(*?!lOZ?l~oD5w1=>!yqHz+RPqT`NNKm`Ocv17?s#Xf!epM&=cfxA{BM~Bb##@ zgP0|Jtw=R^1sf!ZDlFWR!uj$9fRsWjA6UMr=5-z5LoP|R9(;|Yg#=+F(lk4_at-sg zHe5EmlzjWV8`*=Q-h|W$5m6wR6ei}E5ke-3*L7TPwdPjK(#^qz^R)52C!0ZL_;Y1v zLBQxiFU#1GsXk<4H#bX>T1cvjLNBb~!|r%Czt=mqW2rp$P*2}fI{++{ySmF=hbjvl z?HxNeO;3(2XwKE~_PX0x>s*ZlTf@-Y{ilk$o!E3iIFcW{pbuW?g)C#AKL{F)K(*2f zd55h#No+I-2uco)(Y&4W*a`{m3w%_1)1Q6lw=Vw>$@)%s$}6vW>E?1dzw+hhyz9fS z`n{f^?w<8qPaC34DLL@eKfQYHp^{Z?Q9(B`wx8Ywp*PDT5vuXyX_AHL@GulQ15Pwxp^&+MDhm*cVM zh57|mmli7;)zXe1e|rZV`i{ZlPu)-%b z)1%p}7O9LT4+}>E*vb>mMbvWs z2*nb<*$4}F7n)G?I9JI4I5t>UxnUtJ-VI@Ku$+ji7MPU*8Uzu9s$#C(@M|n13Yqs9 zNrps&FDUuiguSNu)%RKmS`uj#!%H_wM(K{4TS_3>c*Pi|8=4R#NMI*G5KR!8!1R+{ zp|eAic#wo63K)*G?6Dn~I@XR`)WM=kVP}_iUs~A)@nc3Ms8HFoexYpRDL`&u1HlkN zpG=BP<~$K}c%A3Wgn9h2-~5BEHw;- zv`5c*`}_okLdT>m%yjklX(0c|RSp?olGrYcV2jTysGt3OB-pgH;U%B_&zHnMPlqph z{YNiy|NXn>^LL%{{5OB>`TUP=ed8Ck(YM)dsrtuTuDtrQR{{Xw{P*7W&9>pr z1mw`AAN}g3{9Ojlec8LueOX9`uD|SUpSsNcE~+6~001BWNklpbZ`ZrhWNa~H5Vfm`~I zKkeM(`BQY@^rsByzurE!?Se4?0BAk=DHoqyi0WJVH=cgpM*h>J_oVZlV*Y^a+HlTO zHvH180gi$G!e=TNgCzz^@!8PhN@)?MhW)B*wnug zAYAtFC4q*gQaDIz_;YiNq?BozhBpL%;vSCnrPaBJcy&=27!q`CSTCh?XOY#jqatid z;4(y75F@wfF38-0UZs^7oM>P3PE!X=eJ(?bybqi3ze1 zyl)VS20UT&xMQm7W*OGW2gQc))F}BPT#IZ*>3Yv2?u5IH>26pYb$(Q&X+1a_gK|p) zCP_m1-WH+q7s)eeAKtF$55gvbm^Vd_mbA5k;r~ps_3Z+0w z00k(7LYucHQ1}B=C*IcTX6Hn4#RXtf1)T8K08?}j0R#XGmx-`Kc(WUlT=ws28{OHJ)Vx95^xCDV@uj8C zntN+>J~_pOt;Sr1e$`pw#?`=Xt;ZUe+;B$dGzufI@v7In#X>L~aTOo}*+SJRQjGH1 z#G@)Dlw!BCfS0v5qh_*>lpHAxrIwZ!9SWmAX4%R zNw{@3K7g#-c!UtkSkbq^v!2hOSICEuJoJjKJp#8JKL_kwly`w1c1goY9t%u`N&gSm z@H%kHogNKZ!6>N_K>-NGh(JY!HAs?R6ap2Z02HJ>)hj4rIwo{DY7{o5L$Hj$O!3M{ zn+}A`!D592TDYgkzEp7XaybL5Q4>}^nJe2=K^>dQzB&4??t=5&U1`Gl=<7%+JPQoO zg}QnyAS`bRkvq_PO&c{3)Or>zEo=@eV)2FJ6rk=#;+SC6$!I@vMIW3!=---fi7kt+V z1BnnM1hGHKA7_CQ0K#lk5wX05B~@Umk_5-5mO8a}WTg}!n*2%`BeTLfpOBESUJc@M z0F(*DhT??t20?@1`bo{FlCt=ih$8N)I43N8KC-qVaPqywz*B_*mJ$ZFxszYF<=TYZ z0-Yz3krH&gXkYUstP`0#MHI7t+sg}FLn~#E zl3N5w^lD;yJiU$c2ZG=4DS+e?0*z*su5b5#p6k5MMF?yp?j#%TUma)#)@KhQ?y@%@ zFi8@NQNoLhe=#?Z5ru6Lfn1ms(6X!8E?+q`jdZesJch3@ec5;65)bm#TJ6E5lUFx% zAMo3iO$KQoHGPYWm_at{5oN#VJw;x~Hs8ilC2S2bkWd zxgJHw9=&9<0s)B*BiEs|lH$*VP&%qn)0@J$?*)^VQlh;xa1V1;s3;1r zU{esmsXvQ!tXv^dWr$!s8JsgFiHv2SNxx=7Kr{%lH!xA~;KgtuT;3<{`nTJcmKJB) z_FQs;E&^Kau1$?EPOn+wO$xSGE5Mr6K%=QsHq%E6j6jI7sW&qzf~1^1W#tU++AQcR z@zweM4(FCZ-7>6=_=o}&=znz%KN6P6kac&;3VLz9P>HVeCN_O+wi|E!$>Z^|#I?-N z&vRK-b8Bu5@Z8+oT)A96;s#qYsbUz!gc&az*4^Bhn)6S`_HX_AQVxmE7V~itRsrhsSv`3^#l|{4C6vx7DJ0G zU_HXoJ@Hw+5!R!z3(P1M1c34k#uo%tMgYiNi8k)Ch+CKTkMTl^SWAt* z#fAf38D%Vl-Cbs(;(a^_-Ti{+H~RySV5#br2(aN0{d?C$d3Zd|c6wuOV;U5ou{U80`)dGC3*`#L>ku~8g^c!P{eC7})=Hip z{{Ug|#jQ1%&or%N*uEy3Y<-*hB;0TS1)vlK*wnNo*~c=dMr%M8i)Nz=klFf#osE*? z-aj<9KOiBpUqFmSOn(v)fyf6V-kxC>v*zOk06_na_WoV%Ez1c247Cpq zwhaKl@X*NQ)2ho|ONb~izCl4iSMzmO&IbC{uBWTw z_rOPI=<+n25mGzbg4L->LQUV~_P>cuAN}@)FMR%SdgU}tTU%QZ@xXxt zd-v{b?&{`t*b`=GXsE5NZDC>Ii2kDPy~`aowksM77A)}#{$c~hv>2g=t{@BNihdUx`n14zYDYiznO0Bl z5iSxWTL$od;Uu0ZH*dsR)q8d}*aPl$G`FPe1GNrs>Ykl^I?KT>ScDj*Oz^1!5lE&J z+~!T#wjyDI)ZIRoy8G4owE=Y`kwCVPK>-p$39yc7H$^aL7J2G9pdH9ND$+#1vJ@W+ zR6(-tO)mKj7;A606kRebaMwhTrm0{xZ}mx2!lJqu%2``{Xv!~JX@GCxhe5x;n14Jz zcHk$WW$5EvHnw>2BF|*ea;She^?5!3NHRHiUq{dGwxs6%ZaHZ=@8Sz~c2Bgd?_7o4 zpi;E!1c)l?g2d81&zTp>R+VaCYFnD>@ur1Co1h#dzF}HyDy38+7f^&v9b1fmkSmmW znB|qe7T(Zo?*p>NJCw#f2%>0+?|N~Y*z{Q6vMg(BYdh|^;{s}`xiz-}h^bViQaMs! zO1vq7Q^ytfZ9|3R1i$g|VRtaE3>uRK>OheA0fSm8kdKIU2lZ|8$8ZD9#QK9v}lPGp=)@0pxT zSt!dn1n+rLVAQB5FOC(Z>?GD$OerORs>}_o6vQDF5z@f0s*Db1Jk;irJ9b_L^=IyH z>i`4+3iYq<9ryym#6<~D9vtXtgOWz!hV@{Z%Yggd$!cU-E8V)95H!_3BwKU~%z@>{ zR)qR#8!VfczMCYG+@fy;gMO{3f3IM(V_Ufuu$+>UvXL|}dr{%_uxV(~51^+>XDt3;-lVXIUo6%Vn9g^>S|?3KpFy3Dzc~WA7Pr z%18P(>(Q2K=?|p91Z3*$c;-C^yUU_yuosDMpQeC-5+&Mq2c=l1IG?K`#MD4quG30$IOY@-v-fbS|V0l|ZymgYjGz~!T(*CXKrQ^_9C!iR*?!YxzB zW%AMO@90$oYtaIWx7@J{&3w{!axs+Y5|{ja7yM&*Qvp&YR9z}H8cqB;x_NOy^|Trx zhkTMZxx>Gn_)n>M%R*4#j` zMp4ZUN=flEP%j-53Wmi6DM99b?F>)aVpOc(&S4ef`>YYKLDBIDv|y$RH{XsDJ_r9VUT51~Sh{rBX?y z#(VGC>;18(wTD{?IBOm92}z~u-gEakXYcR+uJ8JOO`KlbDiLB+Qxf#@pu?~|uU|Dh zRq~8{&~Fq-#zYYjnp_^6IL~U}oSwC~F6M0XN~e55$#mn_s#Sqdh)j#GoL-`+Rw~vG zhJPaF6=XjVKP@MZNNfx=jRPqBG;!axQo$h`10x)_;mX-|(d7u<#*exnMKb@fMbLEP zlZQ+RTzEL>#$JhpgoHvMA!!y+ZxzTk`2s~-3*M}qN>xm*)~tQGDEtOH1q!5F%Q4zr zA%j$C5iB>uBpI1rSt3lQN-0w+^EniqC&IXQcfrsZHJSJ)^SiT0lH@{8jSrUn3KtQ2 zu*I;8X2+OW;?Ym}4XmCtu+^Y5%K$;3$g*5yS*GrDgGY>guT~)F{zdep4*YguEU$v5 zxdE10mN`kQGWO!Y)ca%(8#`#KZg}v(KUhZx`~Gcv8#}i&H}{tK3yyUZ2bYWv_Ee3i z6l0~Y-H!;NydBi1h-LbyjN=3XAt9(>Ts8Y7SoXN(D^6n`SAD^DcXghQy6tr4K8B2h z^Q8mhilKM(b_2~a(ir&V@YKpZOzbfb@e!K9rW41+F>!djDe=r@&cclgOjB(ZjLtNS zqlI+dlx2V^?uIwICj)lmov*!6(WI4z<4bc?!bJ+j*&a%@(FKhajXF~AMLl^S|a zg=}ZUyYhXRxapSy(AYH7hH1H~-81>JEB%|?da@x}Q0JKi0AFU31&$rzhKE7j*sDLw zvP@*WSnun5^;@=YYwXz4)Og6lMI%#d{Yxt&-8BF}649GrFhwX=F$+l*q!R>$WYthw zf=M6*=|o(Vo?Zs()T4qDiN9Nmg!>^aTBit>pi9Xs07wAJvP|93NF@A>H{N3aE-;Im z&v}Y=CrwG!Kqj#1#4&OF)gR1v4uaMP@MKv&f<#Qj-j67 zKE|eD5kFe$z=7qY=FDsFHbgQ&Xs%MXa0V{Y3b-OdN?EJcNP4wn)(=rL*i^Tr`*lXX zKB*r(idii03yGV_xO1UEubCzkh6eOAUl57)uGAUmfR1y;>imKkZ>lB zw6Ms#^5g5SY#eH}T2U(sSp-`<@Z0>2Zovx&;F8&m*E|XbizS^4r+3V=uW)33bzoto z(kTHzkO)dQM@{0hA4(uffdY8fJlVaPzGu~Ki76t!jtvtYD@;@dhC7DdY8cSL-J_DlX+* zspsx#ah~S$BvEMoQ11nUU`BUa3W1W8+&;1)YjO@t)!6@DzX#n6~0K zdma5hbs^C*!C`n?!WMUYkGy&%dubaOi$aDwD+(K6O}4Gt^v2jU%-R5zLgpbVAF|X;`nO@r)jV3AT3+*acHVeb@fb;hzxZvXsNm|k6i@bgvM5hf)FDB z2)5|~Q$neJ{P90D9Br*paGBde+0Rq&U0fKaa$qS6S;!#wkDb3N!GkjMvM|e*U)dU^ zdDFPZ9Af2}-U4{WJM1r+t?8!_GYJ8FY?%i@x;HL%FtB}8wr&^{zJ1;l5XiccC3}ry z?k!lM^*Sdd3FM#|B48RU$@Vpc5C9oMrcOxnrr_kU#GASNFj6nM$9zUx(`Ua3DQ*yR zZ8$oz$h#j|Dw^Z|DX@exry^OeRoH-IA2;={k~LwQAF=dm5}PttD}g}+zPY19&NXCA zxu$`&@^-YtuGyuTCyrCg4j}>F(Qu*MC zqXSE;R*DPO>ed8~9UC$XZAXO=s)ye3r#?0nN@T)xB~j!r@42gsP(7=)6gG9ES0`?Y zV@)SY0Z{54CHk3 zH#1@;;t(fm8~YoMOe2_Rn~0cM0Go6J-pyO)6(EZI3mr*ZpWZ`%$@I}4`!->gcxHd; zcV4>{m}N1sMMZMpVpI2u9u~Co1>nXJ5VoNL7oI`_;Oy``X27!h0*vp&HDOw)|H3YWe?$MLT z|4J?|)bwv@=8^=tUN~p7Z@6C~Kg-wBrJ6J)dr^&0j|hm+W=Mg_kpc!qb$5_%E2#Z^U3R) zTXwltrv)AJhO^Ou$s?W5nQ>%t&DwcEV91>C%#D5L>ga6<%zjgP;vlYzaXa92$a0(% zP_GnFuX&$i(;x*PiA~)Eg=DKdC}n|&5(Bk?4OtMWQcWBi=0-`G9tgqb@(FA@aZDT& z%xNlL&UUV{Nt073wz7$SH93gR<8>TcRCHB8&qtljvyz;8iM!9U>N!Fx4kcj@1+HNo zG3aAvOMBh=csNjYk_FE*lqYVpSN4rAr6*0)Zise8Q8XT+AOa!k7Rp&36B!#t>k5?# zk!5+7j}J_d_d6@gctgeURvu0V`W&tw<%1s7V5iO6h5!IZ?r;Ai;^X1 z0hC_>IW99u5M^Fiz>Mp`eiBoh*P>b0c!Jyrz&AY;S*Cu>7%eHy3flXMopR8ur78)T zc3E{=YxJH!3(pX_nAZ@%7&E3EOW77X_W&tlW+jNxz7}4wIM4Gu%T;5R5SjWwt-Bi9 zH#ary_h8THv|?~kt$og%_EZfe$Smc1T`so{B%uBaS#+yZ)y7!LCU{U-azUr?7;oMV z3kW`_jP3cr7wyErlq>inIf0wA3RwUGO4bp`(;To4G8Lg&by)mC6mkNaP8<`*!~u|C z`vBPLVUZRE7!6!sd?MH>F3)+ihV{<`v+{*8n0l(UtsenDiW(6k*5T_yTGtXzdd&{9 zK8X`#!J3q8dPSGlXq|@uqGcJ9+=gWGE-A^?WLYx@V@wm`OUsZ+K|+Gm^?$oCWOSTzsLFR%rxVp9)9-h5nzD4%%wxF zqcx6Eo=jS4teK6m8)7e5$$GUSW@cxWXC+0QDhX`Iw&sq_O$~kn{_yPD(Bfijx>Rne z1`v|3^0OC9vte_uf0PR8Jfe$6w^JYSpS^Ax|0p zAzPZYbw&(?Z{zTben(EqE(!w>0D-9Kb0e>-O&Gk& z++>L-7cp_Eg7CZ>FDmFuFMh)En9i)c-p-KG$M&`oh=Fan{Xhtzl>+a*H^uFgeOTCW zuT7v7Zz?k5m!H`UjGqvMe8sDtEAX`@8Cqu&Z0q>=+nY+e zPAC_vJTH|>rBW%+^Qqg~yEe4(tWf|MTu>ccT&+$f-mM=`L|*lrMSVqa_5mtIYeMHg zXu>8S`LmkKc>u$kB2aQy9FMTo6>uY6Z3`HM*d^UgVt5MP^hM@cm;^y^sbj#M2kmxR zqST!ORt1bfdChh~p`S7}9&dWtWtUB?;uFWj@fUVnef8Dx7eftuM9)RhpP2kMNMXZd z`@dJq3?!r;Fs(yiFvK=~JZ3=FF!%YyObsdLKhHs{Zi*H9D_NrR1DL!)HM&R>N9y_K z2liF$XO*>*tqs~R@whAB2rL%y001BWNklni(3Fd#5~JUV^iVX z&(hJ!$?3wTY=jrl^xN4|FGS~0Y^MbTAc2G)+_*JI1`!o}xU|SL&-1(i$~{j`?%L88 zoaexj%Hib|YG6n{g-R12lN{-v+Fkfq6FmDltLR9`>&ept7$aHYZUVvlsUCl*V{1BI zEHI=)P?Olye{2aztA5Ev#Sx!Pi76{2=s8NW+lavOfcaDAO-g>1Wum4(aZDV4y+^$~ z(!jK(P6krQE+m0zpk)PSChwVMdoEE_59rkCWJ3&E0!(B4&;`NuD2nvLSW{ZMP36wad~Os0aLJA zY2vv~>YdGdMV}G81TU-6%LKAWBy^p1)|CvCefgn5SnTNOi377ty+W4dihk7Lr4F6j zEu%|HH<7M(0ONKSXVI@Zlst(u>+=)@AQ2n@R!~F~&o&+CTST)5p%}z79{;{>xe+SFM8`dacsr+3ATI*b@CheUB|BoVS;z3z#a;K zkAY;dPl`G%3{2IFx=uTF4zMaCQ)w~Tt0wM5i(dDMxfLCNMTrDK-OODuS3% z@I#(lkBT-+0zSd2?94?Mjyr!0xt<7(^;269J~=+5(IsZ-kbo=^TOM5 z3L)}5&$6t2v}M+l-CG~qykqYU^$I6VJE7Jh4=*1ZT3AD!>J*BKQ{{52nO@6yq~UvVH> zh2$;lF)rW)i7M%;>MXMkvI~JN76Cz`g(g7^5QRb7XoH{tFmOuOs!=(= z5gH08zicBDwOumyW9t(@kRXLbNzC+;HOV^hB>@7MHZh%HX|r71`i$C9k^~8B8^{}; zlmQjEb|8|f8Arzav`3&6rm(L%c#K?7c z?lyR%d5WJ-mzx8aL4i@GcMB8uDARYDbPHp-DXfv2m&PNQ-jt&V43fYVeeifC$n)%|0O-IP&?{xd6UD zgyT)!UY;aLB(%B$=B8(EOrhOpvn;FCYPkwg@VCnxn>xd0oWQ0N$Hehxdq^oOl}e>j zNk%X7QdhZLE|<&Wr0keE8?Dgks97fn5XY`Fu_^+Z$*Fm6hhwydCEub4jD z7ZXkay@4E)a18FV8r~V0x6Sfpqo4&5AUh9pjtsqK!r_( z5H+O(&hk9dN5B*$x0(~!bmEve{>+X_rPA8ka-g)Se{}aa-`3gK(^_3QI5^bU*f`Ew zj(jczIC_@3Z$=n53@2Of;~XPXt##J)5M=WK5eX}9WA)--Qcn|6z$m>$U=*WEEgeZF zZO{82^c)&JR1tZwYbMpMz{a6dm290r(Gz2N-dGG=XlM#VvXF6iR1mM?d0g{IN_%+_ z+*_0TFHzSsSv9D;b3n%sF*qK}G+8$oQgkcXQ^2TQ34CAL@v~SH%Vz3GwmSJ7ZW^0P zhD{l8=U)a=yeYWhlg10o0xm?yg@bPjYDrA)(vXToQa~@!R*yy~EiA7Mq4*?dKi4@& zVAD(O?=~}ub@&S%K$;05L?+cng$N5G1Srt2`+~{T$kgwucF!YoL3=z2wOtM18W68~ z*t-Rirt$WewYzKf&aS+c@r!$S?&#p+YH3PmmzZL3HKEgT+OhH~-N9|<>L^|)FN;0$ zfKVT5d zW+WFTA0m489hpyFeib5;lv)YGwj*3mACB*zHa4YVbhuh-Y0Um|*seliCh&LuvSUM| zS#xua0J1VPg3T=@{IeJgk%qUunzAY0qa1kuZ1w$%XpRWBc#GO3!%M)Kyf~ zoD=G>2nfk*5se#7d@++pN>B!D+fyvo91Pu5zmNy|h10YxS=Xy;*-*OCm?9PC?*ES=3Cd;dl#6^Eyh0m1W0IgZQ z{$2g6A@+()W-=>G4tt*G>a6oTHx+&3bJ64=fn$UpfMfBG2>87+`@nHDP3xUng~x0-rhzy8XnX&OZlQd|;wxPhq0DbUhJDDxl!~Pk&z6bZq@s zKXTP0Z5O=%edl(MuKo6>zr1GZEC1n5XHEH?09Dz4|26;i?H!9>|L#jxw*8^t5e;v+ z@!!7Lx9ZK8J$Giq?+iOuwte>#pS`Pc_B%g#(X2zaf979r-M{=TAH96>$RFVYK82&Y z=a<)f;g@Z%e)r!jYxy&P(SMRP{oaA?&{G_oa=#FHj-_0b?Z4J!rAAdLYn^?k??1e) zTTVX~a04kU#B2zW`_cu!2f^zez;R!3tXS;2$Cn~i!44rZaekHsG!lU`YzIi$O>^>w z^D`KEHpM3vPn`kl7Pb;I8~vE!J4y(5c9QcO6+sy)VYm4}9<8Bp4vQtAn7$q#n&>M~W$@`EfQICewi!gmo{d`{IDhbRF(Y)Sa2sRImgktyC77IzM zgiN|yh=}sM1ONijTIXh2mS?#TS&aONB;OZ>7DBcu3)5c9Qp(bhn6{<8d-o*%(zRUf zTX3lFxM5`-WhDhHoz?`*fysrfgH8QSi=StvO-#L8E|zZ^x-i`1NeRimLu=f|>~Wd! zhtlrC?g8;71->o@;>Jyn0j*QN4;~zE>I0`C=WoQD6_DMYEH(_4dfq;Cfz~TIhx}<^ z)5`WATy@QVS699Lo##!@0Dx*EqX2CH05p1FPrn?N`-UX^jKku= z=9MpwiufN+uSQ+xE|QziG>hh z)7apKTU*1p)`Pr27@zY~1E$Vr-m~Wf0)@T!x~O^-V(vDeY&|My9AN59mg=@5B}?t& zGq2$WW*pzs7@M+B;n$RPmDbr02@vFZGOVMR^c~10i_nGoE||K06Y~r*7D@yb3Pk>n%vqY+7CNmrML-Kob$Ejg{1gC4+)Z6dDP@*t z0DuDXJSU<|=aJ=Emh;?pJ6s%_s;?;NAzCA=ObFvM#UI$-yLXPPADAtAy1QmO2CK2U zXa1qSnS(l>G&V{@2*ly&Vll=u0fit_);*>Hp-TzsG>rBQiuj&+6InRwls@cHl|_tA z<7#_7cp87dUn59pW1Lcm87u^Y62nsnlFNK&j9@$^NhlIeZag#mX<$=1v}gOFp-!2Y z2E~-K-*V;b{-#+oOTVKx%X?n%_wPCWNc)_re=xnk=%zb;#aq`_ zv2Dhj4(i{%D<>ZYo4G^ zpUx9g1DVSVv;DgdzUz{Y1Hfm#c_jeYKTkbwrp%?R9V;}oZ4byhHdsSwa#w9veMWtO zi$$;RPL)I$esvo{g+PQ)!3&)Z@d>lkG2P!0Ftzn5J~Oi9OvbPB2*1FKg`0pHz~(wn z?b#aW6T)bwvpW`S8WP=pnHH^3&b0OufL-Q_6gEx1Wk6bk-)78LW6x;J>i`M{+yml} zuBm%N;dfdDCGs@44XIc%59(QkAUPbtc`oU7k zLe^~<;3J;)BrMcL z+Rc({q<0o&W((=Nc?2-j+85YLT0N&yZmcF)60&`)$jxV31SEtYvv&ysQ;e3n{&w1* zT{&JSf8J2^1_)++;E(uI#HK^{zW36bFZ}u^SGCk%H4i=foojyZ$d3L|f`;iUPM=?0 z|M2?W(Wag=Uh#%ko!(tr`^67_ac$=duDtSv9UH#zfiJC_eBS%6e2x-~-1hPJ-UivS zH~;gc9M`S=`X|1;q5FdOzxV8++poLn-VM7BS3q>1^N#miIG1+cd-L@_eQ5h(>R9-! zS6*_#ijJ)4|IIC5yZP7Kj>xQe);Vu_$IIrGqZ3^H#ZTR^bM7S{{ri(f?)k>oZeP3m za0Q@c*2$;NIQ-ZnoBOM+^Uito8(y}e9S;BI8~^d`hkM5W8oHN1?{8jv?t*57TK{7| zx#8Adt=&Hg(9k|}`3v9h+Gli$q0M*PaMLf=>>kXzmp|{~*POes#qIhkyB=IO0i=%l$aW>Se%;@D; z=|B@20KX6%&}P<%{^{+B&>=QnO7*RPTzILQ25nVZgHu2e1yUuOzIwY+qSK#ZQC}dwry*swv8#L?bJrvmv`^F z=SNmnl3zL5Is1J316G~bU|M9?YlS?lQ~Oyr%1Awh1yXWuHOrJfDMGv&gm2&vgWcbn z1=JLioba!o7d|F%k{n(3u-!CSawuGT54C^eQ;;semr6X8B|K@+xUJhumxqvMMLlM4 z^>pW)%rv5eNzuClLeAk$NzeZ&{-J>|+>4K9(pZD@V(sa7BHFgx5!w%5!RM)}>4*16 z$e2O`WfbbuX3A2A%VY9Xj}Bki*NP?elius|_}CcB8h?Ww*Nwhm4Yr3}@~DQ+D0cD& zBizd2ZD;2sn)Ho)$7_ZTA_p+fb2MB2*)MuBA)_HdAL`eI6$S&pEWsb)5K(q`p5`Bi z-Z0Jc2@Wmwpkj1mhRho0T2YyZ5gjEar)`lw`5YA3p|`E>0IM#G-uopAYo3m3to9CM z*_sTdxl<4be+^WX?a^u?%-C!KP;XN7Y_TI^Hr`?hljz`=O|~gF$PN#A3w0lPGD)S8 z`*J#56WeEXd3_#D?s7bD_Y`pgJ8_Z7dqCz;OW8xW7Wa1N&8bQ}kJDv@)`Rk8WCk*~a5p8v>h<&L;+MtBJNtpT_0br8Bo_E&rQ-7ij9P>~dn>{~MOoQ8+%ZLSZ6 zx~~!hI4UncH#D^N`k#cinwRFZS9v_V*2;H&sS^3z;A`!?jpyHeU?S-G5P#ifHU#GS zFCN@H5&k0a$xx&d+hy^r2CTbJW%fI7iETj_710BP({eT~=mkxVQ_c?NNBJ7whfY}T zTL@#7c#qTAwA?bs0%J=s7Ip?T+rMtAZLfFPm;3x)i3K_pP0L}(YD2S1 zUmf9~it&UVKl7D}ddi^igq3B^eMnSs*l$x$k{8CI4&jmxMi{JiV3N^Ry4( z3p{a@vDZO;X=j=3CTHW|YkAHn*(a7zQmh#5SEI!;{!TU=xE^(>;mfxACMMzZHqF%2 zOe5v8v=kdcaz+5lPegjO3Fz-(nveC5x-^WPRaxCVb~qLHxOWdJgJ&Y-n!ntTty4mk zB&VQ7lAp3CVY9yLR;Nbv5czPfO}I{R{duT0HL%j0^ZZ4YXw9}DaRQBY-sVEenoOhh zF`dQE6JKs|W_Qt1(j_dk#0WC}zgNxAY^Gm(Rf3L9!=H=?tr>+GhM5@#5W$gQhM^Ah zOkrjwUO@r$4$^-d# zn01NAELz%+>4%#l$;VG}6V`o=dte@F&Dp(yu*zZNYYk9~hA;_f`6z=+L#&?FApL1r z5*MbK*uERF5bC$Lp{kVOWIR%u=5w`>xsHP&^AgjA+Wv_(+xJNc6*@Cg8JC)n8{BvQ zm52Lqrhr5I?_cMs#69kNx%YcsBX{;jZxuCbmph9_db(ehyh;IQwnp3nFhL8Uj{~-= z_e}mv*7mUM59{$LC?aD#j$XeIDiZlWMgses?}0fHiZ*pJL8|ZD=yO2gsR~Y_rI_{h zyWuG#XrY(Wxm~v2qhT%sPGHeoz)=JtpC4>8dVKGA7KKK#A3r_3rhBzx8KC|KuBmhdIGZjiZU$?8Y2NKMyjP&L-NXAvYqMK;`Zj-GQ_V-l zgQ0NpvQzg*c6nNxwqoke$}rc_LHQ%GB6iYJjItwv)^VoV>$w8@;J?{0-bRS|5Qq-K zMt^3W{}fTAiAH1s3$4ixb)L=y=>|9tzB6hb9yo36`qMUN`gyX^P{=B6CM0t?>(-lA znqMtrQ$UHP)w$cPyZzmLHhlRbHM2+5cLN0gG~WH|+xd5AVR zcr-;?0to_OMo4G)_H;P6HSpPAuyY55;rw{X@uUyjtM=b}-<)~A!fA%uvhq6b9XYDt zwpt19HvxDZohJ$w53sseX(u3{sF6dk_Z~l8)W4q{!m!iQVyCE*LyRQviU7LK-V*(9 zd>+$PzZxOO#UmzAc%2Dqc3a2kRIx6Ix9+M?^nZPwef3|+UB3=E=61NaBx{)=8SCeH zu$mI)n#SLw!s{l7?4FlCs@h#a{Q1aPO=b-u2|aQ|1_?%<1D zM?r77SF!b&rv|{i#Qu2(pe#J`>2+0gy=qCA3eRVr2*)L`!uLMD-sIefNxyQ4E~2ul zoJY9T+kMk7_XH2n3Ruq}exG7Sa`U4bHTc>E=IV~Po2)oaa8<$#O6q&(pnW!nS*WJeIt=yXxGdQinDOQVQ?4PSZvy{9b}MQ?(llqA4UUE z$As7vwLliAbHmwljs6xB_}E&Wp(qExR-$i${avY6hda8xTqp0iO}0iD!j%5rM}Zkvf1RC@~)os9b{?8Wr0m3VN$uKM2+IjRgSt4Y00 zD!P}|;L=&Rjn3o5mII$;pS2IAOCU8z2D{1XSw9nqk-odkPG-X4*k=^${14AYzq5;UVdzew%+S})L{|oFbZvXsKvqre-ZoHJ}(CHbe@Ai37z}0e1rM1_s zfh0o%fkQ-~A#u&?*hGw0Sh+k6layYaiGhJ^x4XCttE_iZEH{_46$A)6o>;oC;Ab5f zf&uw99Kw{>`aFiywT#sdT=oCqC5O;)m0}xQk2}?WYc88)rY&Hvfm9~EB8IlQvdSh= zC|FggNtqtC8ClnsxX#_Z9Wa6be0@pvLjg?FL1Bv%cD0&iw@ud4Y2Tpk=w-dn*s>~X z3??Q6wmS(o4^roPdB+HD+ETtPB3GI8aN*UjNtUkiupkp7=|0Tx(}=1N_54^(aOz_@ z)(+$K7mAL^XQr5kMGQOcd7)rzmfw&OU5+JDmi}Rn72Rluoaj}?s{cA1FN?tli^BCk zE`US+@3zOc*3pGf7j0Zeev+8&qWu^t|9&ujr0m7s$E-FvHnT~u{Wl(K%>ui>T+QJ= z82z&AYuch_qQ7@ux`+cB8UC0k!VV+Du#~t;zTYUM)*ol6QyQ%pgIb#^UcdZf9XUBR zfZ0zg8ynR@ji~9xD+v|#8jV=lmFsh&Q0c6y2=uJ3Zu>+PO*MiXPL#B6uJ-oJ+tt4| zt_vMroq@BJ{D5D;H-nM@!I0HBY>yc9~#0*C7N?$zbbQobz0Rupw2pT;tt+Q zT`n=XGv%ZUwB8Oie2&fAb&Uv@PuzF!C+`e=o@)S?CJE=>wlX<9Il&%wym#v4>b*qz zG}_Gnuw`=D>EEw=4!AlEJ(O=6n?KR*wL2X}+kV}*|GBy<|6@{>@|FKtRUM4C+v5G} z?Wx}+Gzz=#;Bk()_cH;>mS}sevV~oIEJovgAaE(;-Qi{S%6q45l7w;Kh@t+Mpksjm zLnMT6$HQ8NqJY?RjM@<6he??5=)2P;3&u5 zM+4KegM+~9fmYcrneCMwIJeVRhof%52m)_57_wdGt=>TXlgsn!(4b-Ker@U&QNQPX zV*P;m(6lBV-WB(kJwm}KYBVC){`hSC1-|UN)OjM}(UOvo|2b1Y_v!3~<0fl`SR5ip zzWeJjLLqmr`x=hf{fURX@lu5+hPH5-X55S}`!U0p7b$>VrwJ9XT!2lmr$#plUpcto zQ^fB}2+*@=Gq;XvtZE=~ZEnE1I~P8SnyZWq!;!1N;(_Jwt}}JLkqpp_|BOw8BpK46 zUyK#cZ72F5bvqfO4on%qOVBbHEyO|?9gXoEWCmty!0N_<17tVT|J{kGpFzfP#do5M zt!b07S}$dBZv4Sn!_q+4e1(m6@gvN|=9^l@G_^(!mkCv#w*S-4q&L75 z6OfF!c{*Pu!|#Pmb8CB$%4&x<9xdjGh!GW%i5(}L^rM2*o+tabOmzYthHWX@h&J%6{~t{V#xHU*V>971|Vvjacsjs3N0x~ z#K+$?U@vmQvk>Qw;V&ndFpWblGr=5n)Sn&B08@6J#ntgp-eXgWU*UDA_(n}LaqY913Y|2!5JDlzTuZ#zG6__`SP9h?^7hk_tFu+u;Z7d3G@BK)ySf{8{nT~l9bF-7QbjQ-Q*YzIRH}t-a76`QZFF}t} z&E(O=7PH2*0WSht2uZHFuXGwZjdvaY6m0Z995?V^;tTowUFf-nM2*k8KarnA6`wk| z-+NPH0xt}H{{sG6vuEVWl;AwBo!aH~IrI#?{reOTRKC)8>*acgcU8=%BHDYoDS?^w zHRQA&Dy~Yj+w3brDJ-&G_<3sd@$YAzl;PtvM8|f=)0$^Jl$}+9fTJvKll=&tk@p?P zUZB@lw|l(nX?)DGo|)R5&ua^pe&F+LX!El3!Ia_4I9EV_(?CoD?Ns>-gk1bs--mtX z5!c7xeuW&aAgi;pdd)K$uIiw_+{eY4wO^}q#J)H6ga946wc&iMWCGlA-`V$`sbi$Q z0n5u(D&HdKbGT*_>Ng@^E1~@mwG&PSZfOB~6*)ou^pdH37XRbwE;2e&b3o%qEs>6T z4ZCJ~Ng4_#Fxs5{2->@)$$t*iEHv6iiS&-rxIL6PMT@Smur~e^$szGG<%1uv~?#I;T#g)F_L~ zC$si~A-C zjOLMbBtgq6-1*VC>N8du*H{Gjtz=19Qd7!mMb6HA^<}$RUAqW?2446ezfueRdkJ}+ zPfA322Y9rpgJGGC@3}Oc@71OY0U)C&EY^fv@iV<835_7N#WdR*ei>>0S*DXux?k## zl(^k%q4c#IQOj@ba9`U_1i<;Jdts!DdshD~s8GHOnGGyj!WB@-)l1EKg>Qbz=*Pm& zwZTm5Xp02~kY~Y5D&H@2f#frSn2^4snJtT&AUP#lhisCh^&Mj8lpqzCEZW}L<=Gq) zQaJ%{IV}Z@&^q$WZ(r4R(3DHQ~MzCK+)@A_WjTISwv(f|B^-co_`S&QdmozNclbiMJe|0vWc zqu-miIQz>Dwjl7Z$yzOE)T3_8Cu(!<^F6TluN7=oM8V73*XyFAY|ZXdVuSAb3pV^% zg1^~l`}RlE+@65X@G-H^VNA4HWkmoe#tYGcFJqumXR8sGREDk#9uOR!)}089CQfW! zwou4shXX*vz-ZO!V)ib3)&o`bn;tXu9&SZLWCW@udO7A=($y-j{U;Bl?SD>6To!VQ zspsKjD<*NOri^9wRB3K3dudQ;PAEYF%3x7YUdoLL&~~0{Bd@$B1S~%ej!pxySo*1Zec0Qs*#2IJr}AgN>$)iq##X3{eaM(% z&6-tESeD9i3TvD;BG$587ttW=>ZAARx}194lB{EFqK!9)6JqU;`6rx_jN*wNC<(K1 zyf%$n;tsRqHTqEqa(#Yl@Hf_wRmo*twEX5zaI?SLvQo(?@u<6bu(PszY0^-TyC(9C z;Jfx$0oeRkG*iv=*xu!XR`t?q5UL9MY7Vz|Z{?4fjD2nsHz^JE!0Pi%gnz}QW`)cA z5MKg^{Yv?tw`|Y+hXOTwmbCDq+?HAbntOUq_gaZxlX6@}FS7;uEaqaa*4loKzY;x& zHg=LYayc&Ix~Pae|GwC?sj+?;SE&Y4-V4zoF1LhL*dVO|Ps)3R7s_WYez7{uH)!&y z&oHvw`RAqO2MW^NzW062ZiqtT+BMx)_P|9`B#VBn*sLUUy02EQ*fg!{@RIwnQaHsma%^7#_+ox9?`4ibitxmTNl+UQEuod@n<#>{A z4;mo!d7F4Y@K2)`$IIpM97ggb(_+^9^F9El(4J%DunV}R&H)~K}TL9yp}fHAG@Hb&&XPh7Ib-qNsTI`H#evGHm>e~YNmtL z#d=8C6+Kd_Z)sY2j&@EDY#>?+K;#H}{{g*uRy&BY<7+gF2bsVi$uuT>&y(v3#c*K3D0OXTI$)k(vZKZ+68RA%MJJ=0M% zMG13)iF$K;u7}zG=zXQ0x1!HI0m4(?mQOmxgGdJN9~96lNC2f4O6gX~Ji|Wlx*6H% z^=JByk@UzR1UYup?w1?ZVYG{P*Ju)3@ayY1Sh_Ow2sx zFMtQ%B&UrWNsK(~G&koAHAK*a9$v*)xrV>F!@C{8>Yt5uua&N&mP8TWqNs$1K1noe zIK6z;`fqDERt;!#zOulg+mB~w{MS#Mu&O~S>2rlpi#Bn4ku{OtFjZz%G+D4E@gf<3 zG+_i)?W&qth*l>=m89{=96~`8q|vigHOV^}V)ntNzu9t?KcVmL?6WwWtol$qNR24{TE%j4BDK$(eXd!GA>;Y=%%q~50l>E0ZY zGLKu#8H)-h0rFn^Ay{zEG8IK*G|d~)WD_1i0!VVMOltjp^KQ>Gm0o?g)LHd#6l>kr zs>CnbUOigg-zV>d-J6A(PXS$K=<@y zZ$=CY!N{_3ozg_0xE6U$UknK;D}~R#|1bf5IRVE&%UsDm#meIPwhi?6%{?qFm(w^+ zZ7XZ_ch`k5Ua-_q$3(>irMs=fWMidIzDUaYj9KVNiaSV|S1$Qc=d@O_dpDwG^kDqZ zDc_hg+V0xtriIDeT{E^SVZz;>b0AKgWDez($wwwsSzrCN?i>d`JI-_xHf&~^GqUpY z=s4j#6@@B`WL6Z~;Av4UUpVh0$~oT(po~q46X_$Z6K|%hfA_pk5@xHg)Ibs?yItH`sHaH(c)ho#7sB${P3Nq+?P;CE_HU_ro%MjAvxQE!GM|M)9BCd#*} z6TSgD597HAW`_N6q)8MU3#I|fEWY}#6{x(u#Ttk6Bh4vDN{6WGNErFNGgwltlQxD| zbfiS%#|7g9o1;$FJGUc-r+Art`uUgx)G4YoJvaaHCf^<9FverIPVBrhp4G)yYNUd| zJ*0yF*llxw2r>N-!HY^TzMg^>>kq<_F`=g_Bz(^4e1Ufe;uqof2alcbf>RyCNqO_t z5Yteeu%fVxh_Jh4?KKE7VkvG$sh2b0WT=pgSdegGs%>VP%eC-= z-xEd1WW~)hV|hiV+bNrIn*J+E3Y?MJe*d|wv9}8F=l$U&9;IQ={|$AV|nF5cq9p( z4`>F)N>+>cUYzm^Mh;oO35QNq;f9aY^jrRToPy;a?q_x#uyx*4k0@qUg-XHu&F6;x(% zFWQO~CqdG4>6?U<^?^XZ7 zI(p7`>Eo^bHJinItXK(lC0@J7F(SDFYdX3T8&)OJ0#tGr_dviSS@k*thr8q;rK41DgH|~gbE+#!5g?gz zd<)je_}1TAGlI!0 z=b|I`)nRv1EsVIGvQ4y;KA0lP0`8a;me(yQ3I0y|0J{U>??iv+mmdbr|5VGa3kNJU z#6^)UakD^_Q~V)PB^_vZHo%R|!Tvdc3_PB@4!9YD(W=*%5ucfvF*P-9)3sl#H_*x8 z;N+Yw5E^J|VqwY*8|sfCT#9aik8jrG@qPb`<xBJY`;gh8h7hIvI+yyU* zfBqW^JsFi3g=xNI>y!Fwv6@iDHXL*Nrj-{;K0P$(?ic*i?tjGq@&rj3L`9C&d9;H( zjS%}?Um`K%i0D!}Omh4qwClw$WHm!AUn|j#Ar!PL7Xt-?;K^4>o?D49Go)#hmEL=E zg`QrFGP|&zoT50n;LeQdvWgWEIqup{wuEOL02@sh_?E?20IC%Wo-GGU9Xlfr}Yvl3ex_jh`5E(IXT zTBv4fgDdeMTSo!27t`@@@H-n6t-4HXhNYA?FHao!_JS!L`G`pjI|g|CBs}qby$9u5cr5D)s(`^f-q%54ihSW z?ei*I3z&S3T%-qcK1*2MhgU?9Ey&^N@z0#^6DwBTG3Hl-*6=LWx+oRj4{krK#b?xm zapkyY%TX~%)K^ZFD1s#9ywG*$-^byubrsrpi<-^fl?>SM~895DFEM^>AHi0s) z|5aPE%qFW7IupM;qtenPf7i^WU~UrzT)2zk-{$ScmYAZa$|Vfq^OTI*3kH5`3L65~C{c zyAyccX7jw-mLm3d1MM5gx+;&|da>L6LbmK18mJ)^i$pFGrd20Lb530(aciZ9e-zZo z7a2#P+v}ttg#n~#NIZ|Oo^5UIQwYN?>6SksKgUltC4?LB8L{f7Q7=41p#GyRQM{=v zRC=q2hCFaalS-Xm4lYBj+4XJ{h`y&TRm6R__8U+&2a0PmhdqYQH%?N{H5m>D8B-NA zx5Rl0LV2=!A=`q{nFP~ZPg)WYPBKg$=z{0JjaJja&PHU$>0qMDBu|K96*uRZ%*tH?P!H(HFB3ty8zJGH%?crTn4cdLE;;Ezp%AbHk&WcCh zC~+ClO^TmGR`bqgKEBHTg1w43+(@)-Af*eXn}qitWabiyJf}q{^Ao| zCn4A)s@)JbAU}G?8Hp9kfFiIDp#;aXJX1X-p~-u|C`3ANyM6hU;FVU$Z`pZV0A;X-UoE!)QLO?)Vtk&tZ+imO_d}hpjyq~%c?PjXhC{c@BI6;3) z7Ol3Kw`t2Je7-?168?QBEoknq_TDZD2vU1UqQBJHcC#6~`6%wQWJQBTbr$XRi6WtI zy^+Im%y8q%S_;V;QlR8B?iL@srk6P!T>5)CuY-GA|mT+m--aKy$O4*a^|&TSN$ z$VO4uJYE`d5$tzq41((BBLAE7yq{qaYRY>mGu^k!EoO+iMwZ~|U5rX^gA`#8AtY`=>I7(kZH_8EGTu_M^j$_APn{Y*%*vtL!~SY zxXOu-#!`f>HYWnLJx5!Feu(0^R3Q0mGy!rYM5#WlEKd5FUgf&FaFh(k!$lCRbkS-| zK@Mbe*kcmXMdz50#k)+eprGi=&tMC50R& zbe9?S^x^r3roR-&Con*xk)H z-`MVQm6DS3yxd%wpJ%pRt+i?MSu^l#Yik2l9;IA{G)+%W516r?ojlgjHtWVsr=>V7 zWn5Z#?Fu_5$Ir4}Hl@SU6Y^t_4S=pkdWbWA4t>YK4{2jtd|i!VX(X2e@DZD9=AVj( zURO>S68v6{VaRCN2rvr)Qg{xj*o$LK)zY|Q5n0*&FknL{cHpZ&M%bh&?@qj@46AAK zKr!8Bd@d9q=9qLfNG4~;%OW3j-Jx5nUB2#y=lfMdR{#+=6~ua4|Uq~)zu7$G6i5s&)94G>}dY#`Q*@0k#nx{ z1!l_+kJOSRSjNh?nm90rG|xy8LHBuTS#b*umd2F_6Jd1?n7uPNv=(_((r=@p!Y0~e z?I+>i%k`J4%lG&D&Z{~;yK13{XIB1xZCIZ{`M9T8F@OJ*JHa@ zPq+J!p%i%Ks+uho?fX^&D3zZewGl3r17hXeDOL2Y^F496J6PMCKh6*TZ9TYIga<5V z+q)%=LmFF&Vgzv>yy87||8$g|mV<|MKAM|xGZ+>7K_xxAqS?JQ!RC0!cNiLixUp?k zfQsZ(R2=Ek+l{o;-tF%MRw!KEFIFnvueUs?9)h6?vj&kmkaU~ZE)Vvmyn3C~<=rJQmQty0c(}@?x-1 z=33T{U13QZZLVnK5g~>d>Qf$s8%>0e_d~r7E;laFL2PBXi6kpY7|LEO&+ETb3L^~6BH`MIYww~>=LzD+00-aSqfw6A7_^b1pBE+ z*2$!3XOJQ_eA-1N6ZA82ESZEJ7OrwwlHEbNm51I;p*@WCb54W+x{a1-SQ^Zr^B#R3 z=W+%F>nFUy?1PZT6jhqWB=9ovG$;%!OXP1+svuS1N>VQs>dc`f-srpyGB|7II+6+I zD>$3_bIVY!zmTX_VEvKjrm*-LyOK0I4h4;n7%Bt6P7mZ=TJk zr4ZhVw_6w{atM$g>Oe;N>t;==L`{Hlu#0*X;oaWvEuIYHe#%$mj1WDl!4}6Lebjwd%BDVq*UO z{!Kv=B>xkS5@a-Q6P`YtD8j^LmFe4D!UeX>3>7)YrK-DKHFYreC!nz2KVaB%I=QpI3;k9# zXkqR}EvMg>Ila_k!nBVomGvPTU0Ss;4O|7Q&@^?qlY~T8bWsw1FoqCI)HZ*OWt8(R z14dHM&F&iHmGN^$;FN5NZTZcL9yB)*Qz=YSHIn;rpdvy0PU&N0S?aB#i3=yHLwV2r zSY9V2Qz#PtQD<~8UefX5v}Alg{S=WrHt@P(OU%zK2~f^nZh2`v?R$WtQer3xZuInf zGYV*gvFQJRxc2eL^g)$c^M4gH^6KrqbHDZnRuO_5yUhgle$nA?6+EI4dyV}2CR}&j zRN#M2H4yOQ*%++sDW9^!$Z6qqtb^!fgG%tJ1o#i5JokO~>k%A8y9BP;=OiuzgxTF^ z`2PIE?mN;MYio`f`#WnC_zW5jcV0Sy9nZc}4eYly@U~o_6tFS96TggNJ8Z1`PY4J6ZZ(_(}XFEIwWxwGpgf3iJF7KKOvU18DSA0_mLcd95cy zSj|>UqZOkU)dpp0U+cMb=8kOxsl8Qeknl`p%lKSX`j8 zsx$s5Zhe{YdDu^ry_UB7E5$zjWBrk3Xk0=huA~F6qciBW8_`Xf`K_oyM7)|2C4{y7 z$WS@oq|}|}lqOkFOEy{vcUe0T_xK32@H#DrnoU-mf;0|^uTh%jffIK$SiM9Q3;rB$ zLH-u3jV`-fw?)1(=zVJM1apoKdNC0(RJw3jlW?L$O zz}ni{`)-1&h2GZ6%F5RE0<^BK`oBKksg&|TvhJjNnUh;CG@`TDa2NeJYw@RtB;8y0@tHuy}IM2M2Fsg)&{-OJ2XHTDBExB>Fm} zT#_mWq?dSscPlK<{JL4`kwcsBrUqmcTm$|PaO=+ ztBRE}u8l68s_J+(GQT!qibkFuJL0sRNq`DMK^Vjhhs^@Q8t#vi$j*BauZy)^HL;EIR!e zF%s0Kt3aX&Mj`vlS1zTH5F@UK_0=%!*2*Uu!t8qZwpiy&RHm``dZ<81C3u6$`zaUt z)%ZG?B_spawPJpVu!nfyaI+3#=Idp%Yz7vPZt%R_1_Ll&W4hjPeUh_iy2S~2=(Y`D zxhI^<%YUbKc+?VltQ(U8ndpbc^JDI(vCk2=psNpLkKRpvwiL7$? zYW}*}HOSElyx#MidLFp%Qsej_*m>BganKiloKZVYdUSby1lU4>qE9~}a2emWY$0iNd65_4!= zX>6su35ilB{!~#~U3PfisDq)Oz)06l25XDN1y6mzEhN|yNL-DKnI*yU-MdeGogvU?ijn8 z$Mqu${1gis`$%A1{VkSjJfci8)lfX(lC^dto$ba0T@CCFujwLUU1DuRIl`_ue?+(VB$y|z+^~B9`TUD&B zv`uMAP~S+=H)5gNlc{5%+hmDPElY6(BW{-=&5N_r@<5|mIvWWUwG}99!pvTh>M#zM zO&{=}^qb2LsBSbs!@X)D@f#+BwAY)I>J()){uGdt5CC zQMx0q{IAPE!|O+-dYh^N8zP?ur&b8q0T<0HNeyb-{jRV!2AY5W}80l3cTE|3~aH)Yir zK0hJ&G(KY&d}dx>>b#HlpD(_e2QAbM`0X>x3!2=no8o`IU)7!VS(re4QEvr0&DbOC z0gJ2RPWuRO+1@kAm{+MmF*?v}+MTVMrmF2F@cf z5r5j&KJT%KcVBa6Lg#*NCIA2CnRg8rb+8hkP-ujw=@9;K~y%VbQ ze0OT_k?o4z4qN#s^puM409@GwmH?10*)j)ikQ)3)OLv62-tY%DTLT-Ri~WbJ>9(E) z@BTi4{ndB5q6~ZwIn+h9fhiWj*A1Ln;o|SS-&YPV>^e=uHgLJs5jf{ey6AuS^aOJ& z_!_A93$VQQ=hFARfar-NEoi+7cl4jSFJ}<46?EA7nBV+7mA}k3R{UCDZxx=V!%d@G zVR^(1mwmL?BAhCW^OnFGYh3x`93x_0aQ5u&n7Z;K0>Lj$ggC9OmzZT4p{5cX4P43P zo1scRQ@ms!o@gJWb+%b7`XC)7doJ74n+$GzwzhULW+dOT^5!^ovRcyJ_IEKsnSIWO zX$*EkIuOU5ok+hvFp|5|<^m{EuDl0}$}IKmtJ46;&1aK383* z`Oc%bMz51v7IXOmj=Q~}GTznwKeD{v$p1OIU4_Xy$9id9d;Y6rlW`e?QS<3 zG6zsQ2r6F?uvDYfFbm4yu8>-&u`KX^0#!apEco@@Q1D8iZ9+i?Kd)0t0xNCJl>;rS z*1m_@0KVjz+ zQNx6)q9PqMOo1DW%-Od4Q=*Q#G&NWEE@h;l3>S~=N+xNTouHeX))_C93ar=R%;XkJ4BD?p_yn5VS45COs-`j`gH+eLY={DMS_l@=U4ER58egmYH3tbc=VCnTBrKAV<@x6}%#Kl4d zlomL9D$t&ucLHYCj_&h;(`pG9^yESO5Bps8-R=hVcf*(n@2mWuhfGF7hoO%8oHs2s z_5J<>e+@m}WY;@=F6$L~A}L#u?KT<%QNJ^3FSou=%+y>*jN*>XVCJ;f4P18fDS3Ux z_IQ3Vvsn4(a6Ka(FJUp*pBr>M7U2)DxZd^@)Xi3S4@JxI;gwI@g$!|U?Ys;+EVvGz zv5gq7?xcXVPaAGSj&8L{_Ow@M?eFXAL*4|Or#Tn4|`Sc`9Gskn9yX80l)S2_q1P#E9 zjEvfJ1-x$dK>$)Z;<66(Pb_<1seZ6=aXNq1mCjQTU=MXPl>WwbsZd}!PV&U z5bIGd@GSvMZjlf|UNkS}D%f6rEk%l$z^idiwS`r*TH1tSYBSPTF?&|C^lDwI;Z!vH z-}gZqTou5?)JLoYh1Z$i4uLW4{e!9{y{h1i-NC|XHlk{1aui*g!m>1g(re#HmHtXV zQS8Ggi0o;Go1)g>7?c)$yGcCg_yif-o?w>3|NUb*EQt@ zOn$fcd(5v|1t05m? zzyO1_r$%q(OPi>L?J$7Cr=uAyA;EPo(52~lab!k&!*A|f(2D=IEz`h{z`pb9(8%}W z57k?NZ}nGby{LdwCHOpV+X!aCd%)+!GfkGanBVVTDB z^CP;afI!#dM@>N4UG3?>=fkxJlF4OkbF>pL1bd!(INa?T6%|J4wbsk z`|Ro?7$B(PZ#D-w=SaMx;AfN*bP7|yU$%j6(iZ&cULWtnpM z)AOgiBGT8G9+0e4p!b@K>DrFlg>m1Z;RRB7C>!TjBY&0_w8tqSBD!YWvT{=5z10-&5KbwVH6(1uCRn-T8J}U z9PR&`3c5tsscM*=w{Ky*$|spQNj&N|j&pHCj5=5N_?p=FAdMxISR;emRS(N)?&FvK9VOq5v z6TTQKuU~0%c;H>MrL3GBh!oleLiLP3?=r7@?-OP$^t#>7{``uhiRu1)yFeip++J8f zBP86}+bhV=7v$$BASO1_)Lh-!v1k4H_Ws_|(h?aF@evS6f@%zsymzjj-m@T@vi_{q zyeO84?KQj}3WWiE2L0PNS~|Lh{P(0fydTbVr-GrmMsj= z(I12w^DW%u4~!^Ksm!9r(6NFckH9C)r1%nA!%KO5i)Cx=*LO08%u!6HGN*)f>EPhrGdrau1gU6I`!&93m z4-<^0IaMZYGK;%}Kt%%zZ|hT-ERRRGh+wrErU`yX)I8Vc`@Ve$sccZvK(x&WX1R>yX(`5w9bh*1%6~I`7!cOULdfsBLu}|Nc*XWl5@h7uq&F1 zAqK9C{d+~m3k;F`WuoAY#3R?x?{|*RrwDvpQQKO|+Z zMKH#hYXdw^-2EQ-_)pA{|LtF%j=6I!%QOq1ya9NS{4k5H$`uc(^oVCUnfdL)CF(Dx z%`f%GL8@@FB#{YtvS16;sV31ns45Mk?ne3W@y9&)-`HPx;Tn(PipBf_G);f|l&aZ+ zqAo^BdM?oO?R>f*If*c80*s_+;Gb=;wlCx}4imMf?nw6Q6 zF^-ie{*SM(3ah${-aH~*(p}OG(hVZraA@i7?ndeE?rsD`q+7a6Kt#HvK^kU%Gtd8G zE@sXZ7Y97xZ?Co9TDx0NJZYZ{v04&tdxqHwCsZ{6PQp4aUV;(a^D&~_@zQl#T2?lh z&FlDde@!wZ42VdfnEyZ_6pF1l7ccsJ3uy1NU#?R$G&IdEE#>9qZ_v>0{JQ4n=PRM* zy3A=87cNc9dU|@lR#%C!vHR4 z2CkI>ju252^y~?X{3%{`_JU8)8T+#DoOsEGss?A}jSw-xRwFED4f^CAns#1yW!OL<2aoRhSRe)hazP9|Iop@?;tBf4(7X38q z_mH4*=Mky>*}#v{{T2|!ICy?1LD#syL#8r%kF^@9Y<8!Z50A1m%e$j1Cl_o-mIj7@JEmJjj+3&xkM9o$ z)4LCsn_Dd=TP)?}JQW`Nex7g*?Xk8UX8p^0sk^vA3#)y{6Eu?n$LnuvfjVe9jAPls z$#ht~v5QvUsgeGt_6RNB`N{HySH+L#au+r=t`fVP6;;XQIc z7qj&rotMaUSy&`!5Q^+E4jrzia7WZw{tpqx9}3U-UXl?4U9cgKH_DBNm zOspP7d&=6dBk>XxjU?jVn$&CJACBCrN4=VNL(>qXKoGSt+2@v{QtbUKNis%6AElv& z6{!!Se^T?uw@Qmk;{v-2UWjHuxMxI!t-!r2k!)y6d0Tn=6AtZR*QZAW>sb#mxMg>S z3|*;Ly;%!yhZ#i@#i{AYNjdEGo;)Zm#hfcCHpxrSjc{(H7t}RMwU8BHxmB}z8l&9f zVEKlN7}TyU&2yA1WUC0u(-a z_}2bRF%T7n10KChOehuSfK`BjnK=h=`ReNG*476A*rCCH@bPI|I=X&%ViSHCrxNv{ z6v9wAjgEKVRW%-r{HI{r;ax+Q3HK>e*6gEHo8~)j<`kViu{sv2qc5rMP;O?89b1ap zFxfSB3tSe{Q0Z=x#ZXF#*^6{K8ZX$-1!hZVj?pENDSs-X9BSHEN8L#mr}nm1Zwc5{ z2+q5-#f;_b^2XeuNO>mXM^BiUY0`13h$H7plsu^`kUqj)*soJiPwOyqf-nmLO|$gT z_wWOT+Vbz!!ulB-Dl;f)QZOTZ&tE#q$-Ub+RUlih?PJkib$e1))0<7Tn{<|L4Ib0+ z`spUSTFw+@P98?3*%R~Zl?Z$h#b~+@*29TA(}VhXkmL|L9H49r(6=fO2w$#fv>%Bc z{cgJ3-#o?R)oeD6XuaJa*H3nU4N}>95Pf=TSnNmpyxV!h%EbgoW2 z)%(8bUw@$Ag}R9@2{%WD-(KF@>0{TA5C|kjR^G9LL-&zu_ey?oqRQ*Z>nV+GMQ(BL zEQ!gX=Ki=`^e{@vLolJfedrBFZtiA86WjRj#)j*&@_aYTRz+iS#;zT~*2RwImijAu zdeM)*HSwnv`GK39<%aw3Ir-GewF_JPw`}V*+KXK3TfH^+1RY7FWY1}*_|_32h}XPm zuLjIpS(2yE$h#XNLfQMnW-m6oFK-1P^zt57X9jb8fh%==A+rczv<*4*LwS7=NzNzVJuE_xb7ud{x)n z*jueP^Rbb&^V>Y7>B7#9u;13KpQn1ki=Jiu`nCcieZmG2@BHsy1CEwi;WA_tjXU*S z%xFe6CLbp%%!W)SvUmpn9t$rmbIJ{xO>{r!aUalrcr0q~@*TXw8MBg}Ti*R$@TH__ zum1TYx!dn<$56O|73Eci{qAM1kXfz|u-FS+R}tftEsG0V9%cK6eRksu5!ZKLkhay$ z2(pANOp zy+&L_6SPgscDrM$ph(;C5GzU*&(MEQtIC2Ftornu8S1%fQ+LLwTollUzI4~r&(wdw z#Kq-rbl+_C{v;j;d)mZjK|veir>!@9YQUiv!<)4%4=r$30^jwFjdEVg_*S2XsEobj03g5J#CiD|DZIThnKheYF3_kOyuS9l8}%P9GY^a+&+S(r6qiP z{PdKR`Gp1Jn1_dl4}}R67EG+HC#R>UfB%{h{Md0hhno?jaJoG+PBZrxSx?n6SYB9Y z2C8##aBy54dRAF-Qqs!GikHIUYO-TYXvgQ?Lf798KjIMfLIvwkyis)QRPSmIZk?4B zd}i#^@_1LYuJLld8ocfE3N@+tE-R|qSu&hnGJwrw-gA*ABXw5-g=Zjq@2jX-a3Fyx zz)4x8#zt{1Uh##JE0PLYc_kqZtAY!4pfRa%Ln2m;nqannytUxSgoV<7evitGZ8x*6 z%gMxbY@JnTEkJ@E-oK$jPyGaDO6#mLYs``h{eZL$w06G4!?DCPHRK7AgUN#Dk8=UN zQ8ZWbY@J_yu5At;qN1X_FL$3w>P4z(>YFeZ@Rk~y|HqhOSqtyi5-_$K~sAlzdIEkmhuGLra9n3(c}<& z5Ph(UWRi8L`AX;XcH52BR@MJ;!=W0n4<97JTYty(y}wZV*n5I+Rz531^Au&A5wuQ@ z2>YoQ@`3Ylm}w%gEr(~uat)(WVK~s&Yq^1~?q|2r`rp)iHkv)o%&Q;781%TD#C5l} zJ6DIqBHb?0S&`ics#|EMyrS6wgugL`W&Y#x<+%)#9-;S4?%4=$vsi^u*8q~G4vK45fitg|4cc=0L|NYg8AKG#g*xK64 zRkCC!u(PtFXJO&a25X^M(8Hgwu1L#U~#+26OypIZ9;+dy3%2OArzq2Uf( zITaNZ*GO6dc5&Y8Z4r~)HmlQ$aZPW=+nAQpUsg>W4gOTZ2E9J_&0}~z-|USJ(0hmp zkqvrV@jR35-EFw~T-#23s@2I&WzRKniN}|gnpds+#~ObmBc^lqxEkZzkPxX9 zvSad3K{Z}I-XheLaXXb+g#`pzdQ!?`69vg?n(1#iY;1-JeOPGnkFPeYNg78te~@p3-=31$^>;23kkg$y zBSWt5dPauWt#>^c;#v^=imucDe!4JfS{{zitayum7PZ&+b%Mysroy!Mk3xRa#XS?} zMBtF;4Ht>+9*OG`t6~;x*~{649gij7sFI(DoskhlwZpl@CSxGuwWqj=(j#;Jl;}*7 zv~_eXQ3S5YnM4b*f9_&)T}BwmjE05S;~&-~bc~>ao~@ui?_CI>LiUDCYN{A744{(o zWGYxRg=ku5?b^b*{Tyz{S*e0r?^e+dTiYSKF@-)xz0Vs*#D!Or4-lgXgHh|M7O*0q z4Js)ZFTnEgs^YBB#4L=c$G%g`BuL7ucS0|b^c)Ds%t)}R`t(T6Y;diXM#%4t{boVB zr%zE_#p})%jSBh8ID!hnwnZ$d%LuhlvS2Uz~lGTV+Th^HhOw5FwdU?RR&BK)^lYuT*ChMSFyyr zaj~)Inq|w&%b>s#k(1{GW3Q{LtF3MIjFn!qjfT2<%7|H2eLeUAe84LTUc{9dfQNbaPh~kqFXqVNBTHKNyWS?41}r>S!#k-DJU7fCe)%#u>;EJq*KPh0-r{F{Il^VSW&(qO4Bls-l#(K%yCyLKsMT zUyh=&e-P zckh-br{AK7Yn4Cm*6&nzt<)RQdbj^62PyiC1fp(#-)y24u#UL6d+gBPgoBZG`L&eP zA2iLMi*RsQm?l#r0dtLfSEfBEELpIsv+JdVWelOxc`etIQbb=oW5topf)_o%!9f&@ z+J8pMETX5rT9sz9MOV;ey=S^M8r9ew@Ah{+(gHuNqj{%G2!6Uy*Csd}u_|N*ZPsnf zyqa#JFm(s&qs|{IK&&jm5Ql1rF|{#}Qf0;uMnLhhfiKIjd zMuA)nI!58wSF-(YY_uo_-+SGcPYn$XiQZfNoh{XPoJwc;tTLRIdH1J2@Coo2n+J2m z3bgR1RaJ~9(}m;KbN4`#OG-&mS5cV;$uD*F?Q0*MwAz{)y#^CWkP%i;P|(uSl9KuX z;ypeuPdDl5>7auH`U4#eO)*zs;pqC`^)>i{n~8~uf#Cq?5A^i(R`&M#-<>wVNPE(D zRQDPIePD1fH8qtKDD_3rtc|+0L-FKOlaoqvaz0lx(uRKLgVJQ)C2eg)5M~csSWEa4 zJ)J_7gS8{|;#YvO_T)@TtxkTeDBe__YuHJc)0EaJ*F2<@_45W<_r z@%<$ z(Vc?qoSYVx88b;-GO0>Rl(h*J4L*6qtU% zJ*erdB#<*o#LMO6OP}%P-^PueYQ*o9_TrSOCm5V;9c9QOX@82aPW|ANvM=Wo!kmvV z`zgikyF`+d{C)OKbdlMmp2;3rz-%u5{vL)*i*`2WusEZJcAj1Wi1w`UP4AMAhUx z51~xP{0}3ofpMci)f**T(J8Nq2NxNd791aw}m{E^9M@UkvMl%x3 zQ9Q)Bh9^0Y=PSN^J1ynPqLX?|uKkXAEPE0u%-u3f!?!^_kCN zA1Wm&)bqc@$PIeYMRDDwS?Io-#a6dg#v&~KH~$71Wuva$Nm}}RC%rzO-*q>Us@~AQ zxx?0=zObC`Hvi==-=e9tV!vx;MK{itD>LhkyJTqV;P_ZkMuvcpFfullJ5!;!xEMXW zxVqZb&29eJBcIQil8Gt0>_FJ}-~8g@WEOX{xla3997a`LT^B$GAdJA){sV*?n3 zz$EPE=l2LaraVOd(M`MAj=!5Ml>uW5E?t+Dlr%RlU32*FbLH^6=J^~}Zf*obka;2!ft+01jrGrqriRCv88<)TRoOnqf6W2!{d|OCe}Pm zn_nZpCXh0LzE6AuA)y!;Y5Br+sBAJfV(*eYQ07x>Q|VNt`q!k#sdv6VLffOLuadbu z;Wk0LHcCa^KNvz#wXa%P?#Po3JW6bO+(fY(7`TnPpYc#$up3_DQV$X2;7CSfm8vc2 zXz&r=MsZM-XxYQSjVb$@(QXPQxR&&(>oqz{_+_K>MZJ#GL&Dg7M7(NCXw0R0k3gXT zRl8OTcDSyhY>W>^?@DPq!Y5Lr;58bID=_n@I)XAp7a}^U^{vXN^5WVG8vSA8d~ME7 z6boP6YgIyj)p_bqZuRpJzF%SvV@(I3=5N3mNPV>LVbZL<9qmP-Exf`|5tmwlww)LI?|uxQrSwG zJ|{^$l;{iphUz<7c0*(?6M&(-G?TfXn?8rLD>Qk(8KBy!k$1f(n zN3|`q@Rd={1pNcrt}v#>k;c*k?4IJ)vUt+XCN8ZaQK@M`+JP3Sb|uuVgf37c!4Q7x zhhqkoWp_(6ZuV58hF-B?+R%9Nh8K@f4_GKM=1*4~agy0vUh8>cj!DgTgkO`}4!5Od zLnM()Xe=2hiS^?bAdSjJdP57ZYYtcPR4Pm7heBsfKPRNYOZ=fXXU~YCEuO(a|2(k^ z8$=`jcS(<`8fk1a%OK!Rq?~hPZ|va;DkE1lHWGQbFSFXVFznnrK0coR^0>#OS@W~m zc1aRne}H`)&|UwX{I<5XPoF-4lmfUmqE5fv1B{?^Ws0utYvs!M=ywjjk4sWxyK z_BGDB%9#r51XbO@0Hi!MbqVz5 zaT8F^7xBN^pOI&6-3FuR>Q`&1v-3F$TSr1_s)m|cQdU-*aeo+ix&U_n{+%y<%$$qp z4XMCahc$uvCEEsVponyy&l!bER(;*=-Iemm(YLf3KB1XV|zxKV30&Q_&9k_YJ>= z|CJn9+m~)~CfxnSX!N}+SA3nIqiK4IS`tDx|4 zAth8sa1uu1?ssX*4QfvC^Jcq|J`*x@d$L0W(cgc{2nLKAd0pQ)cAmksI8$Mxig@0h zF-1lWzJ9$w{r2$I*$n6=V_5fr7h)BTuVmpaO9@rhK^Pm1&y1TnuG-a0Ow5^?h@d02LY8o2Q zkN|pKSX^Y)X*8S2;;!%fr|awc&}cpe7KaJ9uaV*6nzyXJ9ErYcwWbHwB2)H}^G#k%S*r-JBr=$RYVQkiu0(H z7*QbA%8r;dCO1vejuZ@JaKCE}GS}&2OsmgC{x-qf?~B}&VcM`+*O$ay^LsMd))%7S zgU*ztPMJ)aI7t~L`vH%}gu)b^9YLF2Y{2DWm3rOHCHogGFGb8yX~c9Sicb;(N>aQdhx6$? z24@9i_33d`j`EQz7-seOV-oi@tAh#~AGNT}N}HG|W*W7{lQrQ}8q<|A3pD5xDWfi5xJEH84xP7IwhnKHTcE6*ToJv^?s#SgiiC!ShK)_tvRzzcWG}(e{CrAUnr`jl{{B7~C!e1K z%I9?S^f~}Xa&>ieadFYu*a#eRG}P2rH#h02srJi_<||*Vf%y$^>3f&2#Qgm`2Td~H znf?GCxTSi-Zu?apvTj!GFMpQ7LkVy!kYv!{``H4{qsQ2~h3M!kL7E!SEx>zcYiB3q zw*Mc#_VoO(iD6-3l__K1CJp)7R8FEKOPWJ74S%U517xhw3Y9&*-u>8@Y2o-Op zoX-g^jTA29xEdd^vXhcCVHHYS&_l%wRjmB{a*PSOB=C^Ke+&)X$%r6jOC9c83(m`} z6hWeCgI*Y4VODzgA>$uKMkO-7;GLh7Y(nTm-l^n#`H*8!V>LjeR8o~hp%NkX7up(7 zRb_{WBm0ixXd^UJ)1I258&%Vt1PMVJ%UQ;dvezd3N>mJa)ty6xBr>@>xCj+KdB$r> z_{D*X2*eD$`_XvE^Ez{X73wriZ}cN^DT+SWl`q=`TuzYBx#`;5*G}Mpsp4a+i@B$# zCt%QwjW;qmEdc`lsH^+eqkY-#-<{vb76*H4>yfcBTL*`4%XT21%m2S$IFcH`FOtbg zM}S&ZQu1AoHO)L%seI`OExf<9v=pS`Xp>_iq*D(iGJMsB(bFcREkC1I z!%^ao+uAmRgN0?+xU?VshgjG~`RZNk??IoPKx#PXzPIv0{Sftb4cyng{xXU*c_i+l zj)?S)EH``P4d*1hlzsv}O)mGes2tS(FQ^k+D$b_bVH+C^Yz_EpkXs>U=GMDtWa>NE z=s>eje6`GjXtO|OxAhVEAW^X#A8N6xV6{3e6`a#_#w@3|*S|O;|LbYT#NR^ujl=sz ztZc{#PxJm5H!R{H=iq${Uo!&WfxbmNV+*9)M@D55n>~#YKbPn80IR~*7Toyt-LluPiys~ zq0q|q(=aOOsJiawd%y@C9%`ktrLT`2af8WYdv9+Yc#Rx8uhWLGdAa7n%yWG6fGG|} zCjo(bkSpWKW)T!@Z)litXelo(m6Vn?jRDdZsDNANUckHo`X?ZHmySy5tG;}h-a01{ z@?z)Y#5U~!QW?v~Z%!mb_m_C#oCDBzGc*{)}2X916xRp$Bk=f=$g8vN%$le@Y6=ai%*7znxll`61& zoNo=y&Cas_=w@VrDsTD(!Id6oZQL;G?|!c~`INq!@Qq9T zmiZM9sT8dw5@? z4X5-o}$_HGX^}0<@5fa6%qi0YqQptUHGb0%h?Nc!BPUQR zp~~#gQ2VMU&mpCyZH&r(Vot=;q4V+Q?R-yuxuf=5Jv3iWhcY#rE$hM$ij)lx6KurJ zCnCby3teUpjfjLXKf3LM>$~Sb@wciVmkRtH^g0t?{?#UiR0fty;~8u-iTg2s5iD|o zT4{d7NViWom6aWD*cCgDTa7~gu8Dp@{` zvAqnfIufU`n0guX(&fjLlN=g8!`JHb5 z*B6~PB?1DTk6YG%|NOb{#0TEN$-}b@1G1_~gPXfMD16;rU0vYt zR91p|3S6^QwY4m4Y;2sIO_i0_08k9Yk@{XB#0y#7|Iq?G>2G{i8?ZpNiKv>laY=ziAe zr&7m{l>9o_oUwsQrk>vA*Jf`d`}7!!Ev%eKr^mEPI&lO?rQ8AAGA6woiCif4!60Rv z5oY|gC>4*nk7w7}V_ag=sgUc<*B9?A5GZ|FSXZa6>vnv)+JE`r7u8Ak+yAa}C4)HM z&nXW3X^spH@~6W++i-Q7e{Y>!JC9F?^(E})3gL$UMJQ>UsJN;W6$c>$|Et)IKGZV) zxJc5h)l+Lv*AeXNC(KQ*FCR#?YONKI;+8RQ(`8W1DPTM{j7zsC$PQw+@j4{_YWZv> z$8YmFfS&AVPJ{{{Fj;K9a(W5(_-w>Zuc1s6TlM9QPa>@D1B}M+$~;sFer0D&MKe~6 zJR2HYp(f3xSZ=k#tByN^5}WrtcWRTody)Jaqkp*s%Xagvt14DHU#YQ|gHS9(RF;Up)iTE&X&Upv%ZcY{HmBuem;YM#y~a!ujj2I>OT8oG z53S~wbkV1)IlvcyXY(gu21b(U!0a`e%H-jV{K~=;r#$Vz5{n4f$e&LzyhoR*txQ} zs2M*5R)-}gCqD&rPguALhRu1TMtHyrtQ&p#%27TSTq}lA z)za4)?;V+nI5&10PX)m?EPn!;KbnEs@82s^^D)q4B@GyC-hSFn3G*h+KpgoWFFFF~S^H$W=gUVLB@>7?Oknzq<;CI?V zL`cuS6QA?DWB-{kvger2p6a`^Ck@Z zm0%)FRt<;ol;iv;L!w7!?m~i(9O?y;Hkkv)gR_Uv!4xbRwd~tYhIc>CAf=F@@9ore<_(U^h?B)xq`65bMu1!a?)4YRpRkZuR&LR) z1yhQdUJDq&7$At2EaybZ7ulOpmc7X zo0*vbX!G;cU@+l~g5D-{7I!=v` z|7x~PUp;1JV7NQ$e*?NVLD<2;0U;3)5OEk;StmzE{!@B*9S!X5S^C+LkdT1cjWs=b zJs2F-v#3l^bq${$GsDRPO<)-E8dZbLii*C|&cJ=@>#VGRK^|6xQy8%bjq+yjY`#vb z6wq{*vm>f>rhE*|n{xQur>bZU)V0-hufP`yZLC=i=H9N8lP|qzo*~OuKlk|{sARW|2b&+umodm3 zS=W~kAkS|_QH<^d$#7f`lW=v~MXhfS_y3IJM#5+O>gp|p!t+sCiiJI&Y=k>_lR*rg z|Aa#*{B!xZQ#oBoTmxdN3$Pe5<427j`UHbY@}FU$(c4TC$YHPEzP0BNUsq90fQUi- zKIBW6&caqkoa2~3JSr1}A;H6J_5Sg)(i4_u9I~2Ki}HJ~A(bMfA2J2ihNFmY1DGmitJqZ@MCr^oZny6e*p0VMWctj^hj+O`^-BEIYiAPp(WWt)?%p(9fU0 zLxIVCAE|gZBtJeI7A6XKv{vgmW@VAc?%TenyS+IKaa8EadLZpPRi}AJE182+Wgzb+ zWn>J0XzA_k-QL~?9TilmiVFHP^UI5i(Xp{usp6%hTy9%D@nH+#I{P*{Di=S5jS9cD zxe3Z=!2MkQ$?wipD=whU0deNMHZXZ)`{n`s*ug!X>#M7n*jQok+_$#2DwTsm+f-ak zMf=~&V(UjN;B@`I<4CFk2PLS_!ovPuUcg5Q)Is3virWI)Y%=%qd?$~tFXGBU2~Rf+ z;2(0n+@0`!zS{$K1z`D|fRdskOgX+s1h{Hpe*U{&T}MYpTbn>@W}P04HO{#NEIfRK zf;qhKXT$(!`c$6lARHMZ^^^*vGz0k9qc58-gW9q;JrX&D6^QVSD2)*bpq1ooi;w-7s$zTt>yRf zP4VcrzjLARMGe31)5vOm?mh|OkdZ8FX0{@)IxlLBbm{m<-=S;QwIAnY%7K^vHu4|{ zKQexm9yxY4{v@A}t;L~b-{caa z5*L;0`@iU$Lm<=7GsYeNYIBKPH&h${(#&T7jKkhcaV~v+uQS#`_Ef)u;_jH z^L>Hn?_Y)6!)k9J#a35Grw^&(fNgeQ71-R|Ty<3yYuBww%PJ``al8AGX8M>rSiLYi ztJc0I0w#9ym)jvui*b5JMiYWvV5rOlJqg$VKnw8Fwq_@AXgeqyBJ=&v!*O_c$jHoG zQ(4&xf@g}fP|`WQ^13OK?^NZ9B_O9ZuIx}>o#M|=-?)^hiGdpFGs_s_t{_s>ERvL zEf2#H6AniA~>{T=ye9zGz5LOcB^OG;Ge8Eig>ve}6HvWa7qs%Ip- zSfo9!qxL;5;sx0gy)Z%jhL!qG#E{(F`)Wk?fk~2EcIF>*VkymMC6xz?kBRxHcGrE!Y0Era{cJc+ak~OTU-$INSKi%;u~0O?ZBD zh*L%Rw{K(pw7Yn_dnKiOp;2V$JdXaZ^2Eg5S9O8e_){K!&nvzU*-wDKW^j`pL~u;I zVaLov6uaU5_j+K*f{)%zaWn!Rk;MCELh<3~p`W%I^VJ`*{`|lfYYl{K0}htot6v|E zZ>psD#AvhEazAo((ytvJSKQuCHH*{)pw!t8RR=y^j2AG_@QPAR;yU7^Q{blSCy;Xf z*1Al8gO1)fFhf92jKEGum-T&DcqqK@!-DT*Dd6SjlNEU6yrde+5~dyTpdv z6W#YGpPdkQ8snLo5V!mSLf8o(zi6OC$=7aoKwM1}H~h`J=!%dw2>KGZMlnvesoK4PI#x zp8fra`CFk(GeS2C_7X!W|NGI8gOJAB=-FjRvIFaA6}P5PQ22n^htz25A4@NKHqby! z1~oOJPi?eSN3@e8oIA8&17}R^3nGFCfUBJBxbbb(P zaB^}2>puZ#0uByfSOvuRf7iZp)h`hv!dhhk3eC~p9vD3$qM{CukHJ3;UORk~4lV00 zV=T1EBU|S}0J0UTRFswuf^p&aUse`T@<>Wfj^FlhB7jd|$N(x`Nks+Vf`4r|p`xJy zArNR<9`5d~YbQY114RX3r6Ka?Jal$kd!tacAgql@1p*M(G1m?jEq2v9WS9N2k|&OC zqLOb?teP27Se0F6Q`fkYgl4{XzGI!%-x091xPXZ-s!zeIRH7in34k*s<~V2ly*VDuFs z*fcHj5@}4BW~Ow;T3)kH5nXy7j4jkzGLsrUowC0|lN;b|M;nLfNE+?+TC9(cK$S8( zOdS4o5o*M3$LxisPz~~tRKAXGAYH#<~gMmOwYCDee_?2LLt{@Qh*zDg`mpai7-%k(yh>=@J zDu`f?uChrC&;RduG#$@E!sk2{f{jp*==U+jX?-Mt<%5${HMaU?z#T7 zWn4#0hr5a*@|Zb?r(WSEJsd+?cu3HdhNqupnB~}%;mVxnH#WaWLAhW>eaUpZFp*z@ ze|jPt+E`_}?5yt#3zj?WD?f&-_E#xgGq$k63fz(sE35H#m zG^;rH$>%|oPUC#woHLaqh(W;hz7!vyPS;!c-T#&Iru~2Ayip<@;|HAQ7Zo+$3ueK- zCpGk`WGs-hOH5Lwsi<)IsLl(E#FC-}lW>ct_90&;I?VzTJw;L;S3s+~0I$R3kD*Kr zmNTPANE<~c%@ys(x&(TCGowT#Spg|IT^6CVYHCa?AI5J%c-~CJyJA%Zl(;kRSy$*g z&~XRpB`309kIO!D7Jbg(xs|RetI}9C`AZNX#r^0}^>2aOHpn<*)lpg0Wgs&z&!HJT zF4j9o>CV){{m#_X6-0*sO8fBP^-Dj90fGIV2r$9G6aKkZ1*}v`O6rpj1#}0b$BGN= z@xA{q0|ER{;^LpicKQfF#}&R9rs{q=cFgxZX)TtH2R0~RtPy?Oc=PVvyU(9L!+$QU zsrd`O3(U~63JTk&b3meMS+#Fk21_7UmzF@jPYntMdt1Op(GJjV0SgF$pYwNN@OFj6M zfctZ>vDu8hZ*Ob+PXo0Qw2wnZag!GO|Sj(rtg{H;CFaSbN)Tl?H)^ zzLhd$s8N_fn@eKDJ;l7mDgryNs?#=VwRmG?OlFL0BYvsAQrwjJMI14JO+y}xWJq6m z7-eRYWXBmE^e0pvqU}u$MiCGi{6=4TwoBHeVO z-(OK&3809sCb8=OT5+GHOI&lWsB|s{*oYBdb5!;h{e3NKOljC&ep-L~+*Ym>wVtcj zf((I-=B;q4x{}lT=Ac3LDbS>(?QkI27VLs(;t{hnLEPuBkBn~YT5XjX} z6$nJBeD~}WwR%9b;5{sRCUcr;{SK~98 zDEKtTFMjLNz7X?3Tcy$IcaVJ1feojr!ua(y-8DhhQ+|<`nVw$b+^0P?+^H{0otsrj zlZwrP>wYKE1FgJkzWq5~RN@`!u;FwYYrMJt|Csn*IajiG67`(u?0TYK3cbVumWFJ2 z2g-7S%U^0~Xry|TWYefmOjlJHGt1#8(^?^&&~64ap41e*DhJY$cR|Bh)M_*n(UNC( z$SQj%UtUR=Q6G>PptZ>N22R63;jrM$DdM`O(*MO&Ov6eVLnH|4Ut^Ngebc5Jj!V)+ z$Gpva$-$94{?+O`k#)Y8M=T?U4CyINkL!GJ(D}Gpvo#bScpiFrf7I#WO8_}MOcJ@L z7cvcNs;{r_?iLjkT;03$?gR#+d2r}vW>i~N!6Jpzn+M=c0~4@Pu0U!=1|JVkT2hjl zfdN=Ekpo!jRfqQ4rlz^Q%holA7-t=wWuOg%_XFjOumWISsbXi)hC$o|v|$kNprs8f zssLgjU=o4#=%#te;A6Xoy_?$=pf3r-bUJ<9KYm;VY&KB7{}Y(OI&R=R0-!aj2*l2f zIWhqO17Nr1c*e%%9pE>?IRRZ9taNa3b%m;_+3~DSPfz#sh^eY34sBIdR&MYCjyzYo z6HEv~H6S%5fjBrYFrLi|eqTp`r*~X{Rx~s)&~bmk_VP4C9t9r}mElv1HV7+g%6Jl6 zfeQ&>c z-u!=>i-(zBPNN*CV~qt=+nXuIH#t9Jr;ihiCK4(-YZo4*JVMxasf5jDk~^d{%~?#B zF>sATLglKgE~K!AcYeJO31MbnZrE)u9tkyuKJ)>*UWZs$rA>;uTN9+Oc2%TyfBQmn zy^GS_Y6$$XC`FbM{6|O}y?1`M@R&WH{maz!{fZkjqT{-1o{0ww874`$3t@d~Y38$o z5Bg)3@VY!0EoMeDom;?l^04_eo#9VzzIkGHnq^Ee^@FzTbm~k9gx(L#UU7(<}y>Lv%XF;g$UUj68cmNTi< zpbh#WIu3ux>sWQttl0hUB=ntq_Vbm-ODHK?`aqcnAd!nWa+%X9xk2 zVZ<+`oM5-%T!_=#<j2o$cZ!!yk<-lnDp&YVN9xfujjZI#tvOs8$Dg68N%F zUW>BylK5X37_yPyhswo-;`V*4k%lacc3e4GZy#cgY`j+adO)WgE74cxBY^_f9Hd~h z&@d6@_H_2o=u#D^#jDk*y#uCI);uAW4AyR~~0Va>3!Pkog;dvE3-*a#B^t>iROk)e3~7A8Xtd6i?}GXYMovjPTsWJ^4(z=Bf@MaLOC z+w8)avrW;rQG}G2$nCYVzVJl6J4P5R!jwU0=Ap)%o*=E1OxZW8N+qLFTxv@E4o;(^ z?=*>Uk5K1*7-9av!dF7nA`7r*yVaczr6o2pdU~*^NHE`|$HXS~{mG1gJc^zkNaw+$ z;q=^!eKh^hbDBF$g0y^Dr|o#)<@_*$mcO|DOXsUqSyNk)`D)k%eqov!oLflOvc^OVZl@7fojwkmcHR?HiCr2`K^TmKLN#lfi9K{_P`>5vXVKtd6aPDQ%m8~6J?{@MOOaC@KEb{Fx za4#&E`8bcQ&-k_l^oL*hbhSjHH%{&)q?c++kA&uD@=Nv;@EK_m!W7eYa0r*4o*r7S z6h(iRM;-0# z4!uN@q21fAZ1*2x{{#;chfzxdNTme@7BHFxs$^(zFqb)!5?7e9w&`=4))7bvhq@}w%-+uQ3Hc^8bXZ*Oe$4-M7oe}J(^!*1I}{qDSi zTDYvhlTxhJr=7Q-=02sj!%8dm?KIWo6^zTxrmqttaJJ14ss3>*Qo>n1*}#`>D7o5> zxKrvEO7Zl&SO?ncTP*3jq!MA15;g9EZ_V!|nchQ{TvcO{Io?PlQ~iZ8%E;&b43@9^ zyXrIDB1locWFfiY)D(Sy6OLZ^v>{MdbM@P@z}PtT2*x65flYcWQ>@O*&6UAxl&TWJ z7e_}5X#7+a;vbtS-!TY@KA5L)KIbhk@LS$5O@^)L7BVl!j;6(&qV^{2!_uFPAX}(7 zPq?kLeWb~$Vz#`PUn@s~tiyaVi{X@R~bECYMT_+wX8szrO6*d%IR^ z;$~s#QcmOj{aiu#rlm5+Mde}OfFQ#I7I{O%r&BHNCkxi6Zhf&+@Rg}?1X(k_gcCtr z2n!yyKs$z;W8H{A-7nGz40P++=ogjg2iNt>Oeec&@5`(8?s1?9-HchYG(B#<(KW2O zFQa&qnsx_aKK#w%MP)yDpk7*-lNy9DV8*XqES%mZN8#l+YM^ekGi9{kq5(=^Ns5I+ zVM5@k>+%d~!@Ecp!Ru1DX8bsj#TKC=?47wXD>9lML-oPZ53zU%V!HPNZ@a>ODVq(O zqCV7kw*IcVW*=W)v$WawJX<#j9nXl_Y*qS%*{1NB;);a43+f#i+AlQsgV{61mZk;n zzQ;SsjTj-F>i^cy!$-@LtLg5t+F2-TCm%7X@f4p(_>L&I5fD!>a-hpO^Anpl zW&ygiw$>FEX$%YuunqlZ*&h3kP+mVcGvJv1^~(fEe8}Dcf>eZZbg3r_0-CkUb=3?F zUmkqn2iVZf!^7dnM;0cgK8H_KqCRf$b6QryO;Z3rd{EJ_)E`U77++FcyaDV4%=i95 zS}`%Zzkj<60TK3)kI&r>KrXkB`S~lYC-Y?`B?BWPl%%BngM(!E@4Gh|z-74T^lf_j zfN=6(DyRFT7Cc(ut^v^no>KT3PC}U%C%fwpV2ZN3x(X_e?b-gSo}L~&gdpv}BoL}n z0NgQh?lLL2fQXA8Gr2QUOGSgC(yu0g-b0HrlIKET$dkZJBr?%JZ^g;>?fhG@V?w|5(uL95ai-Hq6RTPl}m7b|C&nGXB=?dIO7^Eb2M)P<6&T9@YQ>TH~jK;yvn7PkGA;I$6Uk0w0`-vILe0jA+!bx9<$o zptYz4CJfZ*VLM zt}Bgv99}rCol{-)Eu9Wr^N9yWQvm+|h?mLWx@)&mKI>M|!cRcthOIW(jLhRHC zukj`l?CyjUIbzEjC0n2MIln^I3KL~qrk3YY)EstFzY(qp$2ue+40#o-`hC^&X@xq4 zfy?vtEzv04;a0zOm(AKtN9x{yM$3yaJ*MgFqy6uF@~dt1Is8jBix(%C1@^Y<9~_O6 z=Q21b9%>!NnRu~RTe#mc@~LxVIGv)1?7yS^en?*X-I1G%vD8EKAZu2u$T$xDTx}(J z$!_tRGtTAZKCv5-(kj&ryt*2itiD+DZHWSb(b& zD_u4@*z*H#anRF&mjHdwqq()D1d|4AiqLt$zey~e%ztS>V2(x$?sWJBsP)^Jn3(A3 zav*GKYQ}BrpnSXVYg=1egH1A^;C%oCVP1?FFdY#2Q>V*DD3vMb$_V5TU^-0asQz;We3G_cm2+hsHEG#9txwI5_ z7M!|n1B3>navumy2LR0(fHz2whJ*=#G-T&jdhN0L#rc;8lnBHk57h0ff(=D z^p!)WE|che{04q}#AGaKoy#&NBDMkBT-}4y^Fa3w-I1@%R;@xq%&o!<^2! zdm_|4da509HO?hl`La|`QPl_1iZ2O~&6fM6w0K0M)wIXHdgC()N!|0JNicaKhd+~` zlANPEO!H^6D0^981VVRyANNG1ewJ(`e;5Cd41?lU;Fwy&YLbb^qx^yb0g3_uaUf!$ zriKSTbYR5bWe@zMSv5?#;nac!V2|v$Kp|OMN9Uh^#Kh!1#3F)|2+9@c=z*$u{+u45 zHM8pO-roI3>KHk&aSno09ebniiJuLq0Da^|xn8bU3uTuf*oxpt!K`cAIH0w-7=z|t zOS776EG;ExfH&dqiVh@+oLm53G_g56G_<|DYegDbxjzNkos|`&+pVsw0I&q& zxy4Y@(aDLgNLG3IP2ap{U!Pj$i*_r^bPt{J3T+Fma$9%3`qlZW&Jas3XRiC`k`7pB zaT2nhZ#TYHh*RK@YoI@Kkt?R5H_@=O*8Bo8SgZ!I zBpup}9lrj(z|cR4j$X8k#^1-dg)ytIu3odU#W!e?lXCo;lyCp6JH@LttxX<_ zAXAV?>eir$dj53F>A;L8kt?oHALo`510S;qot<=D~*!=?+?b9w53J&2wUg^Br_VVT_626GaBos^PnH_(EKQvP}BbwZ;jgw zZ!O3afro-)*+1DA&U$4&#-N9!icieq7+rj*Poz2CO7eg6E?v9C}pdjYA@xnie;L%_^WtbO45Ij=>6N_mg0 zk3!_XdarPDXX&TBR@E;g4f{GFeu< zLC8K-eDy6-8JUP*Zn#|QOU3)YUU4YcggG_3tjDISJQ7-ZQfkzN-973UlGut`wS_Gk z60$Pp)JkhOLtL-WX*Wltg)XsbbT4rZhBE|DTTh}B6TPYYO#W>Mvq8n+;NZ@V9poHvks=3mfXNo#+yD?k4k^IIZ|@859~?v^-<90>yVxZ% z8n72-4CH#zq^**iT&j40zqj|ek0v2AL+!yuX{qLndYr;iHLUM6+4d)b| zx<513bPNm@&=rK;xeps*fD^e7L8eV^HelTXeY@3Y_xxyk{YyGJ0tQ-;`wz7nls#~F zO&j^zgWIQXSx!M=XlRIzreMVYxD-J8V6^p&EopDh83B*l(@$Kyyu94ppr}dad_6rq zJu+?}N;r2soBAvp;<1rI_f<(S>N?!UkWCX?*4`tbyHdpz74K+M`_XQhv6=TxtILdoyr1dzW-NC2 zW9l&B0UmPv9J&a#Hy-!v5^+@tZ3^FcG2`mF;%m7+=6#kJV1{-(l|Wr-LLyX*4o${( z>ConMp?%PVG^)p}TK7845m#%exYu4xzbro2S$_19@v5@`-+uflvYcb7iA7bKe?(}h zR1{eweNk_r?MK!sBwZ>uX+g_!2A-#`+O5+Qdf~j0-*TmIg{v9AV!;jNvBh_yB^Dbq zF1U&l_8s7Oimu+&^+c`hhJIQugj!2~kxOAgEiFyE!oV9|$?zhFwXQ2J-U0XrDv1hhLXeulpQtWAL+ z3vg;Ic(3129$Gy(gVX^~hN7jHS5}?_-3}bv=)v}MB}k-p|0SsWJ@bQp7QiH!k-$8b zemvsvVNXvFz|NMImQbHJ&&>nw$;E|tCybqV2t-$~H-gau0E=L5c;;$ne}m)-N0NNE zN#~iOs=$NIdCEa$*RM)$dBPoe-;4?a>zXLF+^(xU{JyGnM2)>i$V&Yz-7s2IW4OiC zw;ejReXd}=D*BvmK#`&-SiWnqD&L)vKmYiRraY5isu6SScKG{ZQbC*FVOo8ROLEe7 zk+~|ks{Z90cc&NC39yn1P-`$d39r(|H2cOJFb(@rTq%(x zNDpM?vLy*uN`)0RL-OQ9*viSv!fmFvnWvN`Y_jNkQkHal%pVpyasOh8(3PhvqxQVl zlr8&*WH<`&&t7ZgTR_!hV1BR;)S}_9xq_#EFZ|Jy_W z-WdD}LUTKwROJkTvB^oIJ7I8#zUutd6GZ~!?oc?P=L`QP>3@Fe85v!V$xwkZ5BEJ7 zA=p@0U`CDT(9$tHy1v+j!;(qSXFpQ~=FraVqY+qP4i<9$1-}Dm`Y_M7oCGfY#d{mt z+OFF!{(#K~Mp}cTqqt#RaAu%%hNBLCu&0b!X=y&-KmGahCnWvBh#N+564bxkgdlI- zD+|o7(C)!A0M#i7F7qwk{_WZ8XP`l{w_1KsbdmD?TX1oEvz*cWOkpnEoUB!@UcL#} zmlqey(5uv(IA=B>&!A)+T{?LL>24<;GOAn&xoODJpnNHYi1c%b#_(u)LClm=uL}a|LxEeb@|#sh$7wbj?y=pG^_9MmC+yJH*sc__c6JMlx6t+l_QjjDujcK{Oitl zi>fydAGN;p=hr%Hxux=$vp{1uDZfx8G0%!O{#%L8mP$xm6u6^0KmTV#Fa`40@1%A2q-f)39>(IWr+7XJdy*vJD-d zoG{VTzwRY3+_%up7U7a1eoLoJT#TRJJR zX)*x~U%N&91-Y?UtCHiy?1H)PYNAfztD;p|L#V9V6kQjJ zoa?8PXTT{$E1%|WT`6;`Mylk`Y^+f8p|22oQWI^Y=+|rQah*w4B#Gilg+H5d<;h08 z7>1w0s%9rIKU%kahlxG|Jt z6rKBcHpN# zgJSpS8Cau@jj4LQ;Fq;EhPhp}u2&Y5x3Y4PE08{3UJW3Bfn)@|F=mLQ$mlaR;^sLA zo>YOi*s$LS6Ejv8;2`L>q5FSI8#~EAPvQO{XUXuc#yjxD7~fs&X0HUVTEPE z+YJ-M?MDUn`Ne^Dk=7DhtW38(>bP&Q(h@3&V#}h}D~|<72XR0+@Du8LBwH_;?^RQ; z(gumKqW*ZVSo>|PQnIH0-37$yU^36~J~Rl#Nk-V+IGC}E&7g21q{GD!G3 zw_O@-ha$|=|9k{@+kfWA4_ls85z3g^-)r92AXGBOZ-UY$e!Um-FSIKoBLj@oaJ9jA z&Ckz=>_eE!(K9lV;e}WoffBGR9bFAcbq!9Ykn%HTz2Z&D zR^0Tks=Gb9=*Holt^0R3 z-s{@Pm2Cv9Z)h`(GsJjPx+0^@t?E>5w=k8)_M@tp3!`LX5_N}5gG55||qnzfLZrzh5u{d*TJ+WR$< z`7K@28TwrzEmor2rFDK)e^zpdyfy}(^tEgT6S$H!Ua zM!L|{xw@lL5q@d>;qgGQ8*Sjdy34M%jN)c2IvEN}`I^!glkeWwop{L|1(fHi-B+r^ z?=~h2H2L0nQ{@%wU_CH&d@4mPiSaPJvt}j6?Y-LEiDp*$gy3=a-Dlu9oq}K%*!&t3 z-J;MQ^@Uhj>5YvY1*G4)_+AWWQIcb}@u#Li1dr?rBZ8iZ3H;DtK!qw967m1}?+Obo zK@kB|5J(7kV}M@@U|sO&S=Qn!JDZr8K*>!EAfm8-HjKz{}cW2037B0{@s{@<(>0uu>5sa0K3h%N|}uL_|ao z#0>o7WU1ErX!h>*_Q9DSedGN4K~HZl$Fut3O}E0LB3Fuak7hXX_>$nBCB*?_L3j64 zU?IKs%p}`fD6Du=|1Dd5UsdH~X7-9#7O4Zy<^0Q&IheXdL}0#M{=E1%K=h==tw?I9 zAvxt`2{%W8&LSlj&9a-f1}aU-`zf#RCD-!9ws83znvlMXx5v_l`8tIo zWzCu0*)A@F+*-=)X>4X&`ItaTfW$j41bIlDj z11rjtzDoLO{cSb*QAu{on-b-7$KQ^Jw2qNTV`TL2^CWTucU1Dla~G0?wtw5qyZtNp zJ!hex&fk^m&%p|py+uDYkzPvNz4gb-+lB)XS2FpgDHE^BHL(d<7D*8KRb8vW$Jr>x z6}%Uw1+Ri*=dpQX)wXasem(v=lryHTsz1!6B)VeqctRn+CQse1f9s=KS%ZEZN0J|N zbQKzj%BoigOOpOM8}IpZ-B8opA7k6xeiUS`tQvm&UO${Mz+wES%`X*Q_vSM;XSv>8 z&Z9XL2~SUTg(!Xw4i18d6h%fD?;rViXHh{mWkv=x{l7sDgLyw_av(?yJdccunr(Y2 z9P8NI(*tBE)Sww@gz_HUnx2UKgBnWC@^4LpK?);F#uK@$sl;<;ZNyrD-%Mqa;uoh^Pb zYyIU_lV@Irc%k7b=3iQU9lY_E`V1!YId@B^Gm;S$YeY8t`gDr+-j?x@__KI{$VzaG2-8xAy({r}LWJrr~uW?=_y=+%A8o9sW@rJ;~x;a1dXW z3qc7%dfVkbu8|+UjwV9l)_Y;G>y9p5eg^sm$(*u!`-`sq)ho84M~{9O`G21Swe(Rs z_=dU`LHKHQS&jT+N%uwu>h(pZhP=GsWr47+$FD@g!oomQii(PYq$+VJ?4}o;%3;0% zZy}E42aJsW(r2LUhY$xi2%qMCwqaVrVcg~ide`kccPNG2m>)ho=y-r0UEOOzo@}o) zFLbs=FKG>Y7^Ju5=XWpf!4xIZD+D%*KoESR0Y~%PHG~?0egy>roIjz=5ujy&9s|J& zPKZ{SHu#$0R&Rz=3l3LsnZoN%MOhgHh}kCh7oclcSTOX?Sk|H0z#5T>;HK_Q_Irq3Vu!!Y%p8&=^=u1Xv{jZJ}q6BAN2ymvST z(a#l2>dvQ|jK^L+Ru>@db3WWs8%lTi)}HrXLvL_Eql1vklJu99Arben>S0P8qs$S5 zc9#ZAcY<=7#sJY%VY49o6oM1@9^n1*|Sh4 zQH{&gi8xE#fxTPqGv@4HVvBM&GrV<4KS8h<6fpKV4eO_ch?^G!c3GFd?Q4l^^R z9sbMhy~5|mQty{7Lb}&j<+;k@p1+f4rm<(ByESEE0ucy77Prxe9$l^Rw~spi)M+2o z)_j_Om7i~rCMtZj9CHB<93i0!ahH5@#E&1;3=AO_zl<5qeIX zu6JTNAXok$gXkm>o+UttWk1*C-V;eg(dR9apCca-dRizu>DnAQ&Uk{InEcNyx`kF zmMq7!R&Af3nz17LpH&iZRiu`YsomEpv}&ig-m`8SzRqj>@E|EE;cI-plS>9YS7M{$ zS&lk6VOjK+o58t_tkQIkw^aLEECe@Buy?2S8(#KO;^Wd#_AT;gZrSkUWiBTAIF~rV zOfmPtO=_()kwS&ll?m!$lwO30Np95Rr+B553e~wGu^hR@UrQaLT1)?iAaPUo1k(^S z7S;a9d9^F{()XIMlz#Ka1Yh;&GbO46{9)3R_R+S+j(!ZPbQAvf?RyxpL1!&1e0vn5 zRXB={+4s|Z-q^3QyeQ$$M9Ptm;_9bUv%l$MPLMX&&{CqZ(I0bHOB)$aC7ZjBBsaY8 z#1vChx~UvJGQku?fA?P6xkeRdpytPldg2mRV%D@sUiyOQt?mjYRWGy+i(=+6S6(V@ zp`)zBdYRxBpSz(=J!BfLB)RVjO4lVs*tdq&^|s5pkq^nF3m5UtN*bJlJ3Au3ZDt6D zWsY1MHnRrY_%aeKB09FU6us}>O*&W?c5%^$!UzDPqT2Uh7h5L>+}zTV5dnj#8M}Ij z&-@1jwYS4q4K!$8GO(inZ8S4O+UJaTmy$9wIjNI0z()CEh!FU1E(q$ z&d<*S+Xrm0=s1%nvWWs4J3;Do6q$=35#CjLOW%}=?w^*Gv9-w z4e(s{XmWOT0BF19jxBrq?PqTWp4);l3ku!fpsj<$_0?`bJFF57H3gqE7^cN8|8@aW zn=Rx%xO)O86Ed9eZf@WwOHixo>ZT+l{DUvxqW@H1kK6&VCOVp$-=M`98#Arb|IcO( zae`2tLfuGl$G3GJUa-)=NPe*-Cj8RRnV_Hcm5|8j_p(CelPa-K^3#WWDyfIJf~2jP z8}2((ggxHcTHH))!|`~`|Ne37ACv;7_Cjk_!&Rb5tBglP>T3{g{2Mayk;KNDaBslrRr+bXxn7QafeE~n(bNk z!qv(u$<6POp$hVV(_p@VY*DgAD$$#*+UArO?asS#-2vx;lTM?H;$i^;$Hy{%nCnYb z+5h~H1yHgo@?T54?$Bk*cYadA8p=)jZmgpp(;8olu+uavMxYh@Tt+y~i~mX=&T|6( zd;QvNYYeSo-jbh%Vm*KJbyz0kyWNuJgqj$t2a7FYsy{`K~%d5J?|Yk^BV6hGG8QCM=aCtPmD7kMAaFNhL>)d!^RCly z<+BadpzTw2@eC!k>Z!XBAlfbrbsOHzwWJ<+4S)I4!_F?iSsA+X`*e>m*z_@6n1H*% z3>L0n3LG?1N);oc`M-aimzX1^)}ZOb zM*&|S+Aq_ak#yG8d%qCHDcIm)8+SULLo*xfJJhS z=?quo=uJivzyH;GEiCsy^fr8abynus=HXBi(bRs)*Y0~cN!}WrIdWldkNB*IH7Zr3LSD5en0t%B5lo_$*jbg>7;zrG1*uoX4d<23MpR{bG;( z)%YQ*RiX?>_0Z`Ti$v|QubyKd9x_GGvRtBTF==SY8qL?@r$LXg9wPCD>mdEMUcuwT zj_9s27)~6;8DFn?ZRv3Cr|z4)Qq`@Yc)U(vQOMcevbr*`ettm}@6qVzZGB|>(OhQd z3;)7pZMLCqE188Q89ExlGktA#Ju@glm{i$-cY}QlR#uYz&lQUW%(;I|h+s#R<( zzGO0`s1G3xJP92&J1|Z;0f`5;>A^JtUJ6JDPO;og@*XnO#ViuY`9U*xC*7b3={QW%Ye_Z>t_8u}40t4lesRPdvly9JbYQZ;AR?$>iQ&A(( zI%8Jtw<+HKZR&fy%PO>mgP zN;%a@t*TV}y>EQfjAm+IU>>XPEk+dlt2<$GX9WiWx}+K~NOHnhv~C;o2(1bzOBN+~ z6Qg~7JdXT8E?nV?NGy>#nrN6g@G}pwYC^MQetSsReY{}&QMyp1tmNTSug$>;N#n6O zx~P2+y9=ZOtsb;w={$lRc%=uj=+>hmF z>ecRPLRZl$dbhk#MrrF89v=RkQ$gvdtrW*XjGqj6Z?*)j(`}L1o*&{{ze3lV(bNdn z$uOqkgGtesuVW_>0xv(-E*u;m-{})8bd6B4y7HM+VN@jlj4TRx1&izAH((lwxKFW zrI(f4d=r7`zp3y{F9|}qL8bCqe#3ROf9eJE=rza&l0XC;s_DVCA}zg@`mnMnKcA40 zkPWJ4GqcajdnsSmKzM_pW^m`%Z{G+bo`N9>R#8F;1a#>2UIcqf{zrzuX|%e$-|lTN#J=e zgKo1~jz}ebtC*Be0{_On6&5>1u8k40_Y~E2Co9GgN>@zn?cNu?)BcU!$8rI>XR|U7 zka%|e_H#n2gQj8@<~=rY`}!CYE82dK@Ogjz+dFD3(DkM5MkZask4pUF5d8}EleiBy z0%3f!giD1c+jMPA)oQ!38sNKFbMQlks&!=S^fJb%Tt)XJSY|qP#D2D>ve2HoBe?GG z@$O6a*b>9WgVaZ8pRbBOwbmbeOGLb=b5hG*Q=QJzxprwOSRg@S6!Y}=_H+CaGQ#ad zT+w(j|Kh;zvSTbcpnZGa3F94~`=6tepY?2ChL0%x&9`HR44=f4nyve-=6Lgb{<%Ly zq7uVkeDxvBaggt=;rzkcTZjxpQn2kg^0e2_GF5B+Ys{Zapc{%}ufye7oy!V;YB#L`895#u?|8 zuf3FC?v~k}6Od_qf4JEsEEV6OP#9Q>B&$1Vk-LZ!5%mr&@e%Rht408cDm(Q@i1-$cY=TlK~%c~ zOxa-XfCuwm?qeUs9=~{BVj~3!RsuhN{76eq?&BJ6dwEgu%x4a$#XAt14b|$)^hcez z0lET$aK*NG5dHNR+3y#mXD`6m?A?#UERaMpA z-VPB}5V{LPg0r(Tdd_d#NA-1eFkS3y`Y;*q6#!8U zXpI2aB?sC(?6!tgHRj@Hsg`^+bC+=lnRXoI<`6md!=@&=_gF-%IZSWF+-#Rf6TFjj zc?t;B?rRC*{b3J@x@E6f>SH7?)MTV3X zZ_V52J#UvOfu9PZVDO2NN(g7MGQ-!B8a5)6vcaE(=9AtUZ`dWiYs3QQUd3(RqQiVRWa-0c^y6wgz2wFtVDn45rLkX~`pG|2t;{fZ4`y2j!(4M`xWVQTYWU-f7Yxh zX=j5@ZgMV~U$&^-U)hG#GJ~PFB}rbzy87RN~Nez5%rV*YN!GBLcrfuk`qsE7AcE?Ig+wZ z?bdPub{c7au#srzlPK?))mSoCAx!n|JrrDN@o@>uSa$^QRS@?vhIZ8T^(E8sWUrJYuVB4Q^u z;Y&$obb*b6ywKz`qW+itDLSd^zlwJXhdcYfRbbdZ_o{647ZTSQ8`e!bAPqI0SzI(G zA;Epu-ndoTpZMSjAKyKI6I4Ve59W4-EQf#5;$L(Im%ujnI|u+Dqu;)jZ_5G{1-MAi zd#4RtZ_|)O$htW>{e`v@nn>8M0N1yYii)QI1z2A)MhsagZuO ze|nS-ee~0~0*oxQK;W|ACqpV}Oy83qRmZyv#_H-zM?MipHqc0q9sqzykC9(gL?!65 z0;6Xrclc8kjW0&Js;e)KhM zBPg3p;~;CqQGABFZSrE3R^yYn+$wGl7Y0O|?+xKcsA;)`ku-X=5+MX-18Q?^F#-Tu=e+IOo1mr7in z3hm^L@%8xlX%1cc%j3Mz(m%h-bM=f*%?4JdA1usZDo(L`vME2$!9@fP7`*IjWgv#% zJWxBK6!u-d`ed0JNF~&^+(hMt5TT zzCwjo>VHzH^?7nYubFWO2N8e2?*%j=55?JgYM%GLwg1q^@fJh?>K0muWBX5nH-DE( z>}S=j_Qv1JFd{m#?5vOwRX6+10rLy%x;}mO$c}5<4T`1B+S{d^;WOWwZ<57lIKN#g zR2pWnE>H>(fWrIpV5%v!K11PuI>$bT<0GXb>T>eaQ2(e@J|(e z|LiEBW!BKU@Mi1CCUl0rnHn|F#_s%HH48H1D{h!&cVbFm@(JL>??}x}Xj7hOOd}Fe zUzD>hS?_#E%xBR`Ccr+IjcmyHOk}{IseWBR`%`lkkN}OGS%Lg{wjV-~lyXNJid@=! z7}!@eO?K$A+N@YZtonkiUSkj0=={}EKd9%kB;m^FEsm4XA{Uca*U^bhs>cx4=t%rX z;lNs@``Y`MWfv*bB0r|pb=@ecXMe^#@}Zz72e4zoom{*Lkg%tn9QFHm=FZj@_?^o> zIn4cl_4fa*&H+0ChhdYZy1EM>iY+Z7*`qT3Bk;Vz=y6~`4#IgdGh4wp0Jk=PB2-kP z&KZ-oV3z>`1@M1i=cU&Zn|^;g(LdSGdaMo-#T95mIFOc>luJ4eTGyM-UnJYxA3CWK z0-->!c&r$`bO$OM((eHP0~5o~iSHVJ<6l8515G*X9(6E*Xt}qr;Z+RyUJ%plA3+j= ziK!`#%^9t81Q3;Al7p53xR>R<8M{XWc<)a_DT+v#4)B)MT1cvUiw zBc&E%P5h*Z0bfq}jg724;pFqiZt6GmnhuS~lw}j4gf4QMn|E^)?xA#%=}iFze_J{@ zT>0^3xa4#kSD|SZYcqD7YIR{HIaY`4o8ZBDmaOG`ED>!qGnOp9^0@aX#V$V%@k)8W zzT?+1GG<#;P$JJa3;WoY%|l8Y6lbBsjvx(P^ftjuiYsB>-|>|J_0E zxYNqZtaw>iY_Bpyg$%mT8;i3)uWtz$9vICQEa|J8dZp%2*Cqj%kuvNc0f^FJfkH?}25rMjMEMj5avrJuh- zn8-65@NxdRtj1l~K|3fB@R;Y!?jAWK*t%#DSzTUa&;31G zS*$SjM5a||kISg8Vy`CyL@t+3u9vTO_HT{gEzu!*RS0PZ(ZUGg?y^1=G3j8fP8g)e zEvqh^uMv><3om@t%Z0>|FDo zUBzWh3D>Fu9}^PhQL#sf2zz1GoyEoR5}+o^ii&^zhy!(mV1>ALRL|!cwm#<|32IT% z_Syqk2ZxH;-;7uap{BsG3keI;#ma&v08?GitwFS|XxjR>yeKgt0WQzz7+|-KqewWR z`2Lp=1T*S5Zw+`3&0|FCUrckPfALs;!w-}4p&JMRQCC%Ux;)*32NV`zfRDU=0U!o= zmISmX%qBk12@SPq^+DBWXaUt4^KSqqhb)33A_ z6^q_&koUFe2JG#E$E-bAQb)ghfyM+(CXlv9-%$b=J0oN7bDrC{xYJWpfaU<@co)AO zTq6KnfFpKm3oEP(CZbO%5eV%vzJRHp-w*GHtO_;!?3K2;UMc%9ktiEPj%U{1U5dOK z%NZzzgCm)b8%o1rLSLYZd26!C>ih0p8WYl69W`v5Z_J~mgG*Ol;f=a>n1%$S57o%e z^kMMbdz&1jp(*2;;}_FS`~;<|24}#Jixfw?#OEOGCz$nNLlwL zSxO1av^mb6$vu~DuwOsMW;pp$T`f%qN`?Y2}m!vJ2g>Favt><$7)q!iNBcPvj|bh@WIM%dk)Q7QAc-l?YA8vjP&b9tPvIQDrW%W&b}QN zL2q`rl7-jc9%~d{dC`fwJC15CK7v}xPE;#d{r7E}Oe6D9r09E{a&m%mWsdDSPLZ$!F^Eg#zYkq<8#$=}h2bqJL0^ikPZE zExK#u#|^6z-KHzNJ_*+WlZ4QJc0b@u!4H`7i>rURyN}?Bfr%z?;E;_Ou>EYI2^Mep z`1-ySqZ&PcSbn%%AzoKlI6Y;B)3{9p52Inu0r?r&DkLR8L+(RXQqt7VpCX_jg5Vg| zwbv(p%?kzB6C^;mxa=QI8@EH6 zFGP-|r=|V){#_89S-fPRbb|i_HaJ1fS=S=0`?`R!8Bo!%Lll|>prVu0(-qX;zoil% zso8O#HuPNljH=_q7(|gf^g5i4OAE7ycPHWV7`I9I4~Za5h6ry(+Lq#Sxq(M1`rWEc zD$*8$`4_6Px=+|hFkU|}dpBmS+BCN;`?`x1C5GWXW-#7RmD`a7LoHIIkVZ3Y$@n}e zJ!vwgaYW+1A?jPC@$+Cz7LgW#ZE!YjNC6rBXK-MRzr+Qo>(yPaTox{Fj-P-mB>_>C8cP#M6*ds&?8%A=GtNK09wB_Dndu_TWwNkI{pUdF6rbqgch zn@C#ZGmaT)=<^rUx5AN-dss9hDH3vJQ_os-aCsT~x{&n-|Sol!r==7X{ z`>WsH(So>mmuA*WT+Gsv>$zv=e(+uAW>!4dal(S~UfBFdrp3_yyl?Yr zhok@ZtQS;dr_tFc)fkB0=5+Gm-s=b!ap&=+=3TO@9;(sZtAnP4u2AM@@RwMu2qPYt;Gf;#EQtKI5*xFw^FlWB_+WbubT zYsSC?DX>5BB>Q}_uT`t=$oa$WL#3(d{a6k`tGY(kyKOXs7cp*qLQoxRr00Y>9b zOK(t;>&0&t@>Qt5WAXp2lNBo3b9HPy{oo$0k@%iE@dpmE zS}U`~LA!?&jy#CdE1IkbpQhf?ma~1;VTqRyaQAB03P}UWZQBWMJrW+`exoFQ&`Wbi z5}zX_cK7^;IXRG_c8rL3yRHi3vNW$QU>JmMR&AeOvomD=O7bF zWMn=6Z8JnsUP6!6+Gf_6apzLgIsRjz(s@bb-|*wcZ(?V$LP~H?Up6Dr z8i_$dlUS|(qQg9kj+&HhfF&7&i{Y8Gv!nbVLrk9y7n|3<+{9p_&A%5$+q~sL+LxmL zB2V$YF?PQ1TOR1|r)F0La^ZO3(x@02MX@XuHU#OKAuZo9bSd`mo& z3Njca@L4}2pqXC)s3`O{Iq)B#B*3&@RZp)G27JI!KDV?4039Nwpkd(}2L2VsCcwAD zG6)zr#!v_@?RhC@iKJ#{XUD|>(DFul8E6*CjTZ}N4rbECz4EWpnug>!DJ8K?SOx92 zbS5UTnP{F72hB`}F?f~sKfIfh^$SCK?p;b>%b$3T)_2yHx}h}h<1@Ioa`5s~5frQJ zfx1X4gD>OFtngzJ9gBQ$?u8;HJq|YwLGU0&lj%wadB*-sVSvpUw0=*w(x&zAV`KIb zY!8@IPUw}mFoZG6B>pLm9OQlT0-w$s-{i-I+^AqS4!tg0^N{goI}MdqU7(BvwxV1; zVU9AAT(PFsaNK>|TN43`=Vqa#oDWlEa3niS5U-8}v!>lw@>EOC&o^zAi`g(#pZ~hP zs$z*`zgQw!zus$gH9R^>D&LXot^0p8odr~u>(;ejx}`%zx+SF>>23r8X_bA-!T02SOwLVtlRBL#Ah;h=gAm;JD%@)DY-+01CsY7x8 zUBvds@MC?c4_?Z+mq#xgKWr60liU$&I<~w&Nr0?7eSuq8IhP>b%CWOtd~O#ppndrsfkKCvaFFg`=ku3rmyy{#1l*zg&37;YrxY<$;g>?&4tg+P7{jEGI z&J1vSl4wZS%%WXh#qW)dpfE@DGt80fR$rp@`zlkHR+7FSq*25%9*K$h@SZzA1G|QJ zpR+@^pvW+I>^@%m?JKomebIIgmXpQeiNGXk92GPJSP|WzT3q)2^zow~j3U5z1^AGg z=&6grAz7-c;w(!SjdqA9rEj_lhG&Tm>dw;wp|NFFc&#(zGO8*kxmG+Kp z7ORx62wApGWr^oq@}^tFvNl)bmUTC~w<%rngl_wfT=d;$d%bO4T-=xZQ+hrXx1Y!s zq85p03_fCFNOb%Dk+~Oi;EL~F)t#ZqOIB^smChNb;#hc@Dj-gy&vPI7L@TtKJOFtx{EYOZjUYE?(Q$=C7JxA>Gvm_d|W*iBhAy0&VUF09L2wZmlbD3)XeZ_cWOo26jI^@EN6f{+WgIW{iJ{h&0X z@O}#_V~?%NW?ut?ns2ZdqU6G8_5%8OrS`5hE@ zVn0Js3fk(Ckpr`*GW1y^?r?F#}5!l*zzS1HwH4Cg9zGN&`_;TcBP6RV{SOsDy*rLfp{( zLVJ98h|~eocVOp(U#r2QJKXFNSl?zKxCoHs6>~f<3|Xmh%fR9Rjbg9m zd#LmwF$0uqQ18P-3zadv$AAo>q@=`bgGt_5YAvjGBd9-|@3g|ZX6C!y{OObANTieC zw;d0s_RFKo;{{mH-M(`t`o?Sbv{3|pIaubmwMlSu<6F&6O$mcV0W4TRRK!Hh^FNxt ztr%=-txX+4u3h@YXzo5}$kTSNb~HaKpRl_v5Gi0Hnm-FlG+f+yU(A;; z`A_V*;>WEAv@KYO92JSH>Qkx5V~u}&_2aEn48H6Ot5Icj5yqVQm(n;GpPc=S7Mc(6 z;PciAa&1p3&CEh6QzTlvmqfxUm-go9-4C6t5i)S4YJuf4LN8&AXEXB;tIPArT773FUn~y5rnV~dve9o= zkC9F3;)pOv+2S6Snw_M?1le6D^>SVk<*f%Ew=N)cfEEZZKYls~-%ZcpAs(Avk;}a| zmx>)_F;;`&_P4|vYuEf1el{Hhp8X~~&@-cYa$o3mejLZ;_w0V_uTANb9|Jwi%@Mpo z^<*LD-(__yUEfr9t?viY+gAPFsEk(EFXl;7mBo$@sQk#qf~8!eL_!c-hDU2UslyUC zE2h~hWlvSPvf4UQrngu_EZ;AUmunb#$3~A`Vxqm6T1X@4?Le7kU206{YVn9MLE}Jet=_E#NZ`;z@e~v1+U& zADjzc%)DhPF2<{@On(0S@4PP)YS;2Z}N4%`=DHe6eKDkG6(asp=M z90^}wCP6AP&=_vAnXT`qrl-R@1U=;yFw0bdY_qvZ_cH%*L zxO3oFf?LIzN^zwMJ})E}dOdn{yZ;4pg12s@C|ZzuwxGJ2n)u1Dm*5(M@f1{}@XKL_ z$v_GGv=LltP{zWF2OfT6Vyk*X%>1*%h))YYcC@vOzIx|J1*ZE?mjB%$oVoR6!Ci$S zve`!V&Jh_Cra@IZ3i>aRIE>dj(UYvkD;VnUUJxYBDL;9k{$%y`1|!Ss(GjMB1hv)38TlYr&;n5XC9c z!=l~ENoy2R?qNpg@nB1{1PQb57NWe*@kue7))6v^;g4^Z%r&y8gPK;LOfdFeb$$HNYuK?p19XIuaFZFu@LZ(!mtIByWm-dYa=uT{tHx8RszWeFqlGfK9lOQZ}2jw=CKB%zjX|8c}~$$*NJqF3r*;6SgI1!+z*Ayz2JaPgL65L3??ul2@h) zGtJ=9K_E7!T&dp1lFs5f)zAxJ%6QhNCKdK)6jq@Wa!KpFI-hvkPV`I2bR~YX8sRo{ znA{79cwi(FQpJ3$sWpG=tBNeWI+vV2#m3y7pUb+|`6`WwQn9GA)DfbiDh2&LO#Qd- zRelIcj9xQHub(va3=Kp)u}sn}=RRFib#L?r{31~wJyOfG3LzxZo997E-L@W&_q}LQ1oI-7nolO7KJiVPJ@A@UV z>mdPgO~nSK^h+Q80-VzXngBOUD>c7eD0$%v%%<=>0Z4UplM(062uJ(Vfh+*R0q&@A zI!EJ~l@-HhVP4+h<-PB@V&rsVb8`bOIlY#Z)zzSDqi-07(&0AWQ;>oOy1DT)Fj!5z zesp+v2#3w8YiwNHn@5eG9b2qoVC)7@1C*eU1Pw9tbspPLaq2-5wULo1G`XOM?d$FJ z-}PN!5GgXPO>g=vbu?u)BymhNv=0Rcsy=W4lJgkzZuI1GD>Xo=afA>!4=^^Am6kq! z=N!EJ4nA`J5c#bLV3q@;OHf=K7lHcGr)?hS=QlaBW~W~bZlbxe)R?Qs?f5A<$)X`0 zUHA=XZ@j!R{N_VKLO@XtG_!s2{7kbb8)f;F1O?K)+Qau_XL2^as$=rjZPrSpTCeCi z9vJGpMmEPz7#1r@ER0KbaO!iVB6*VNrr0`& z0$L*f7*F@7qWhk5?LqCCYUC~XS34BsgvmtH%AA!S=U3R&t8|WAQ&8pU%s2>h3s_%{ z_7y7(=y(&kr5tbl)&6;guxD=qmwl7^rquFzrhkJD=D#ZaltyM$&e$U zJ{wlN93{!(0Em79K4wuD3=vQ(-t09l>M4L-86Y6Zh`HuLP78dmt%sb3db41A%xB zK!z99;V`@@X5j;+#H6qM?e&|+US6y0|g|1Dp#sL@AuF?q>i_F!SBQBv8@;}hrfublI99qsI=c3 zZ!LNkhq+Rn=8ZPzV3-hYMLPFpG?GUB^0j&_QKNRz8J33C=;m{ua}y^wodptA!y0R1 zlH0UOp3Dpx(TSN-9O~k)ZV8PIH(@R3H~eCIbY{_pM2M(6;;EBaWp=Mz-XLKsDp#|+ z|5UCjg3w5p@c0Z43@|ll zhg*bn-WX0c``~Z!E)|u7jSb`jXJ%x)f)t|U+_s9s#kWO8!+DDE z#Gkt>@rv#)((F znqlgIx4KH3-f{9f1(bxkQ(*iymBuT@q*!>1UZ}<9XZJRQGWXi?Tge zjqtb#V^ydjsELr}n^Q^s3P4C-07B0HUfLDon`vs@avy(fSN%ch&AX7!qt0I;&s8v) zR*1UV`nhvdZ_xqP-ozDCSs07)eIb=hMOj8r=jW-mc3DEE-sVp zmmZ~kD3p{tP}ZEDLW==NWmvVpsj7n42XIu*?@gd8g`9RSE=NntA~-$S*&&D;&OUIC zf%EkSmIqnd`OsAdqhK^NHbS5WI7z^20&m6Bp}f2QiF82w59@t!2*ag-Pc2SyD}uKR z9pNzZHnyk&*ef9RU$|HkS~#CSz8O3`%l9Wk*?`svemB5erKPQTv=Yj|><*a6L!&f* zM9edg9?bgu>@X~CtQrm7x_LFLq_r8#|ZVa$i*_kr8MJM2HgN1b^&2uZk3* zz)%=2T3XD+>igpbir#TdK`f!XCv3fppUKi5;)9Y@F+A)^^Q^MJ&|nM zplBUbakS83!Tu#36*FYoSS$T?41>3STN9TE{OPbY1Ciwr4@CIZG2*X#Kt}W*Hxd#Z z;23=J>=_v8yxUCuw&2Fh(O3t{HW&;chy~Ji`>ib>k&TL81_bKr5_^1vq-h{R)K*vH zM05+yI?DpI>rLv~>MA^G@OT2c=Me|lf8&Agu6Gf;qMl|gU}@IGg@1Hk+t2p}?;?t*~| z#8S}ahlj&N3viycSsF0;f_wVS8*~H|?{EpU&Oy|h6ff`I3&L`|$1%#n(SC{G7urmREb{O}?QXjqqkl!ejQ1p2f)WIe1a)2-kBB9a zpqQj8c4Tl@drL-g=;_S7VVzwy>*+`@Vok=%UK`D-!xeFop=HHcx+M~~E}S&>+*&C@ zHaf=rjB#Yu>wB1h%~CW8vH(x)4@U(=;%T4K+%&mziS(bbdqH}k!zVOyF3Ch6V`|6| zzxFifP)9d2-0ZV$DG#i#NJct!U%FPF<*-&-D&+?jnVwWHvPBgHFfpw2cICj)%;z_couz}y!~;Bb)*hXVB&CFK9Q(FYdXZV;M_N2OF6LQ+OXF*3h0bm>RJ+^VbVUpB4pfB6wM6BRa<3?I%rE=BilSivklRce*dpC(ek#eEx}7Y z(p0Ws+D|wGKd$#^u8j#ofn@@ToZ{l&8yplA(4YPk;O9425)~0)!;}Fj0N92=9P{wu z1ejJ~#s?2zeYXw#AdCt_3A#I>=}k{b$&vK`x$Pk&B(&htcNggLnK?P&DVl8$3kR-T?0lK#I%EA5d~sk_8UXtCjeghBo`KsjXGY?l z;88ERSq^|%_Llo_aBz-y7Xa6ilbsFx`>dQC6Foh^g@er}Juwl9?sZjFS6&v}^^Pr? z>goWZKu9YpMvQJcfc+;bs*B425p;3km;O!v@#Af0;XfX}uS!sL1)Rgsg7U zYfe3MBqS_?N~&Dc;B}EStM@$jC`uJ7X*`BczbYX!J^8tZ93gK+#jUG5u8K_9mZ;hG zfftWN4*Sb1b(x3puk^g@rK2#5VsSP5kqDH&X(G{g7Fc4xsSKz>8m&6ed!NkE>q_ul zPtNXllRZWA#C4VYsFFOYgg8^qXiQ7yht2PTjh8Q%N54#~hW18uC68L@sbD`zN3GV{ zV;&byV)YPC=(5&gGf*KdQ;PEv9i@C!%KgHSl!FyRoajZB!El`8PvRC^bj4D7N0#1!7!%rmXbuNzd7~(DA=GKIaXoh%k9RmZ;kmXMbehP1!+-M1a z)AHQOsqalG$2SumpyJ7JaRA@KiZxFhz1DG+g(>xLbc!=hDjpm;o-@n#e~lb zwI)1X@Y#9bye5U07l>2mX>U_GHF^K0fAKLNz&7S zMb!dNVdFI9)IlAPl#uZE$ML6H;UrTqAS(&Ir0*MDj8;M-s5)b%jc!Db(TUA2mv-w` zUW&aiQLcs~_qP6=o<3D-N24^!3@rib1Jh)zB3qIW0v-P6ME#J!9c4k0W$`x;;FE8% zs>s~$Gj`RbEeoeD*NI7f+k5@RR3F<1JBG!X&emC_K=-{F_bUm1!Xm|jDE7R8v)>hK z7GL$$q$NL&;8eKj=wWj`xMHtvU-^cdVDlayOFhf4aQu%>>dVR%H(Y^ZlBf*a0v}F7 z8WPdapMjbDX0aJ<Rf!%1%nm&6Bv{m3CtwKJ@WYeDz5Ao6U)22T)Wdz6Li>DAN@0e~9JOaF-;1hWTV9rUo8^jit&l;HY?`x)v# zNJcmHT11QPO*(C^6+nI2pU!QJ9Q@|wWdHqp3bd8gRY(^Jw*c~h$c@(7@%eLTe}e~} zcK7`NiSpcBZcYx+3P1-1*OV%M4)vJ|=5QFbvgak!IP^p^S$=zTcA3af?+3 zL-yKenT)X=3rns4tU|&47XQv(RtA%MZ!WHZY?h$_LRlBL@&V`jB9$o;gwiO#`~i(x zOeA4Fn-y<1Thzl5Wm2E!DSiU$Yqq#mL*BN?bz!!i$F#k|qL{JvHORH4yqG;RNU?R; z6jS1r)(SoklVTQEB8+Oj8YGmlXUgrR^#4l_5XK#hYhzm+%{bCP8i+#jO zG`6n#*p0cq+AWP_kc&5msGEGV2ph9ztGQRve*3uB0(Yx7kZeI!CrTDQrI=Dn7Y$dt2-JX7K2f^Rl!r67lxP@k538)G`2T47x=d(m zSCurwrzan4@AvfyUU*_=-uy&mr)#?v@HmoFJF?q9o zpV{V0{|#V9AVR%<^Tre=IEfXucZi3hM=w;E>;Ag|H}n` z5(U;(`;!UL<^*~l-Lxmz@eK6hXbKHPOYa#9lODPc?te5<8|O_*Jrj*Aw>5HODz-Ix z(AM)$XZ&^ou@Gvc)7NMo0%Rp!{(=Izd!_0zk%hMr2=(Eo$!P7B))q{(d5T2YVd<8# zt0Qbf4JY!9FIl=omBnd^vh3OW?gxz~M=P-~cXu!fi1*$@(%^k8?Mj_vqZ)x2JMrrW zT=D~VAsTZHv?G3|tul%d8C#{GP$71DbmDOw^*KGQd1{-x)Fk7{gC=UfHA`uRcbnG))ND9v=F!R>xGZl zf#X9b_+jdOYIj%JgosWOh*S$OqZ$yQ1TyL2_}z8(q7K;O|122OC1dYIyZ&vd>UHAB zlcirpjZajmqt>%aJ*(HT>!~(z2uj=u$f6+X^`t~%Z*-BB^NG?o=W|%#nS5o8l(K(8GqYHal3i=)%hklTdx4;4(;_jCIF+s zbR5Qo#YIKVLD2QEhW>DD(ItVsUM~-j8Ez=nt#ih29V)A;q9P+Zx6Waroj>%f*@!I) z9`_z9UChF12k@bTaN~yeIO}`^>j4)kOvrCo4LduIIhds6))ySj!54f%;Yr# zr$+H?0>n4J%l#wITd^~<%jI58y7^!8V6urs;zh65$ZhHU?&Qa#$Cr4Mt?0`*LE)6% zcqsRh)M-)KwWTVhyE<1Je9|ALy6ZJCUNU>u?`cqk7v6SpS~9?D?ccAzkkOaBy8y1Ve;N~!DdR1ntrVZOVX-p;-mV9yVe-Kg- zOmH(|_nh}$2T?WXtU==(2*>VIYir2fxcD0(^=D@%V7qw|YSrVHG#9k+TbGpqQfL)M zpafm8N`fa8#tX1_ZNe_n7TO^gQNdgk-XzKVA;%WL zn!3J+q}uWM`N0MUz)(UJ^!V}JL9y-KT^ed?c%4CC1tl=NJx~Qxe1zIrnih_82xx({ zzh#fs^RqMIxM+Cx2Tv&~p@d%8_P`0LdwN;3;QL3>dfzng{5E=lEg|)f&FnFBP3iQl zlFVU&Xx_Z_M`<{!#;hbsX5T7qd4}xGh3+yW_uu>_02Y#86P0nG9Kpj=J1G`q7sNa! zF}adlZE&2NVC46DCD!UuQR>j0%^hz6ioSV7R}*WRpBk2bp@)S7D|(hfTBvLm=^Dc0 zNYOelXBI1It3a4LuA=03LN#@s9p7X3KiV(j)kFp5;uy6|6VNQ< zKG-)|2uA_>-cv=Rm%6@f~WgMn4waJ@b%eH{>7xhCmo7N;oW!Sdw~)u9f7uW zVIkY+SAMqlmE>nCw0{4Nmx2Ussq?1%Wa+tI!TC4;c70@le{Lo|!^+RQwSJ0;Pa);^ zcN2IUD+cAvS5*~>4f3N%n%#=N#+Nqe#sO$|LJ59wgdW)VRxG*&&h-y2dMr4%*6vt8 z>)yN?J|YO^FPOHayq8GUdZu5?zGckCye0dgR9h>0TnQ`n6@hYi30a=XN#exN3mt`K$X47}w)^LzqPg@LETSQ-$h1AcAI4IBE*`D^uvda^ivm}WpZ`YH0kPd6 zS~0+O`ChiL3#k}zggdyA-o3khd=BFMScY_XZ$MU72gDJmePP}csudV0)#rkSh898# zyj27O_N9*>=R%0bap3hagf9HFYkmXE9Xh&2h(4OHx59WUd^sE+(Byae4<2)Xq5_|{ z#;pBQT^#{kN@nJJSiJ(fOgMl%31ixaHAaUw z6DZ@iugl9L)=#BrI~p8#DB#_K5!LmQAd@dKBLfzj@HUr> zc9ha==w^?nk&J56qg%Zzk_{uNH@;lI-10q>aent~EaKm_Wegeh?%jW{svU|9VVw#%IUzuF2(2w6@%XzxJHK{fB~1;yj4FAN zuTS&wW4*aHt^f*G`ybuUNWp|QO8Cd{zBB{4sy*O0FN}6XMYtcEqXxI4$JkrTQT8jR z{Bg4n2%{KOvZ-=)ELu_W!3x>ZZb)gt3gU8$qQdFl-3q?1)%siAX`^_55yj^$ng0P@ z<)nt~{ekgTLCO9z({`VR64oemg3WCMx=@POCG}GeL!isrP<}fwsUgA+)>O{IIjO1R!^6SPQ$Jm9JHbf9lD-r4@6Zsw#FwPF zd$$d~bvN+(95U%3$P}FQ99&#iE6JKLLj{4lGw_5#iS9~;f#`4pIx+-o*p}-E7?y#&k`Q#@8`&TKcb~y1b&kl#A zt}j5Q3lkLJ)Y)c9zF3R#lYthu*>;q-hV{Y4T10mZv&sUAvt|%3V792wLE0z- z*32a#C1`RT5417SNLe(7_hrbA7H!y2$El27iz0_02tDOOXhA zCqL5gB)K5;j{g3J{X19GjNS!F zZ&SuZl>=qBlI5)Ns&C0VtvLzfqIeA$l9|YkL_K&KnlsALscn6dr*-~&^h=>$XaeR% zeLGe5*`VKbo|KdSWxDFN!FgxZI!!e)?eD>SKc~dez}3I!G*oS~yQRr0j#Dn{KgEAs z9F214uCLEu_ek{4cee*T-F05vj(?7hKooAS_R%2G+IHhp8;e|hP39K(T;uzv{;-~t zTXN4;_d@;p-<0}VG|eAz!x`Qsa_O-@Gc^9r_3w4t_Wi`rrWUy+z5I`-C8h2@S!FP7 zcOH5c=(n$TUYCxdr{?&?`@8w`$1NB=1E%NAwYA?GaTr)kPrLIzNAd(|+wKd^wk?aM zhtU9&QLOKd@8_48!t4I~zNFY)v!~zE+y64wo(?j!tYnGD=C_>>Z zRA(2khjE-DXAzL!zHB0fpG5Ysgh%?X<_Q9UK(&)<|5)j)-E{n~(2fRyaMsNuKz^z@ zklh}*zNCbSP}S+j^PFuKOdrnQ*4o{~U%39`*J4mt#@Tu;)^Z<#;BntN?bE>0Q`?Dp zemrYrhj|O_xcAufvgGYE`d2|r&2ARAX8h{C8Esy0{&Zb93R8~Zsq{T&WmRjYIx|16 z{}4cf%>2x*v#NF>@MZLaPxpRC%dl`7=A2FE#l0}Nz*!f2YFKXe!5p8CxGY%Yd-&gW zb3OL?X@^(nPrrnsU2Q!xB4bicR3k{7;5{*>6qdgg`>LaWph8YNDvm@YK{Z*2wY)9* z3#l~r=v&&cKNA~Ln_3Ch!nDzatK?GzK^Wd=L*JRrMRyA^9x&Eb`K|g*_dwo_5{&OIP zdUC0Y+^DyYh6d$8c7`M2tEfn0<{L##&klSy`g|{3&T^9!ouu z2L}gmkU{Hi&aG2E>J1}XfKK1sg0STD5T=5q0;HB4dx?YmzN=Cj&KcN6!WYafZuFRv zXB!aUesHoJ4<{Xvv{UprdJK|u##~b9CVT6KxH?r*@mKU2{0`nHo;k2E65P_p1cjt4 z$G32ixa8=B70Fd(((YHyp6{&?`Wo*obJc#8`miRLOrTAZs+T2w(=7jbMNStQS#p2- zfuuRstZqUGF85z?48$)q5Y{itt_s6kDo%guzW5Lhz2ItU5!;)vB`;RIMD+5)ueRzV zVTC*iWNipkRJM{}O$051H75v{G!$$6F9DkYfpT6cCM_yb2trFMP1JI{_ySSQdQw7& z5msGXw50b;T;5zB6Ypgi{j74LL^l1j;_WV-RcyFmQ;^ky`BSj$y4mqIRl6g@L_?bY zZ88M*v>Tz_d+R(Of)=fs{5|BnE1UaIeq}*27N~(=Cqq_IMLl-n(JR zt&+dXUkEvwQAFS~v3u^oPg^UUi5U`-nl_q|T#Emi#m6GWCosJ=ygeIzQfL+U)BEkv z?)R)*a-jhX67jp7-KLU~Ewppu-mB5X3wc4j3%H=ffvj+3)EMJvwZygH$Ca&$FZ#+-mU!{9~S^^g0S$0voQGKZYp$t zS(sPUJhTUQE%cutdxfR+&^}CY;Kd}7hZ!8454$rhPEah|5psl51@g;0M025d0iBHz z)b+Iihd?T?0&VK}cvx-*)vZ2|j@}PHL zht;Xe?_fGIKX01;4eBNBM~`e$9A{;z$UYFbDRZj3~iP z58Bc=iF(ssO%qL1o~^Lp1sl4z+`}?WO2^_=)G~NtbO%kDLLgDAWM|e)wcIJc@oI49 z#dicIae16jJ?-I|(`+lp(~Fb+_W1?BH$r-XlG zIKEr{-TM%Mz&w(lZGEvbao+MIJDA61i(zgM#a4D41yS<+Y{%1}FV_Dmy8Jj!&9g*V z)#-ZTU;Sjj#R${4kQtg;OUZ-p+_z#pa51!fzK8gJYD8d}RCo^YwMz>A6zP1^vAR_9 z#MAG^^ZR(xbpUWs(74z{F%$Ma3~cv&M1=A#c)#3-Ahl)tj%T{DkCgXOSk*TH+3d$# zW_opR1HWTPn{a|`EDJ6*Kq2|0#^}!S08)aP-HKA#727fMvr>XpK zq<|bjt2S}R)Fqj38mr@1Mtpv7ni-N{SkRL5Z4MHx!b`27Cy&VJP+4#75vUo9=wqkJ zWs)@JGuARQMs!Ix1h7xA_fJrd9qkEZsa-0C_lTm0s>JIdy|t^Xa7@oaB`MWnkH}Qw zc|^F0gDm(ComK{cPkV9eiK_pI1|c%GHe!g^2$?ceI!v+f!;jZjm^$U!3Go=eKvt^T z#AwDl=Xw27Sds(*BCSSvUj*zYZVV8HZ*CzvsxF}20J#9{OODTlp8tfoyv_YgknlkQ zMBg%WLZD(Y#1w$b8eUt6H_&Ux$ELwf4Wvx4cY^k2VE+PWoghSl>_TX3gq-Ga5yAl% za2%Wf>i<#Nz|fEsU`Bytt*D40vk{Cz4SqWaaI~UeCcvD9a)w0Sh3a^#y4G>JVHJEw zno3Gw41_~@b8GACmoL(okW72S0<5gugr6%6RS=AtyLq6TfKmry^Mpq>V}<6YKKc7X z0R%EBus=C3hAix^3p>KW1jpWEZ~y}U;`1K(2144gHO4GaJn@Qp`} zhXSOuH$c`u^?j0JJ{NyCt3n#yQ}p}SdFFEvr#P`^vQ%O<>c>bWP8jGK6QF$3<6>CPN5RC*=S5p8$WkFP^h{MBQH{c-X#^^N zbfEe7YUnNClw9c)u*R(;A;in8vMrU=>r_P^FlP{j>YS2%v6tx;$RwIZMJV?urLMg~ zmex9@MG8Xws~UV;CxF=q@cb zGU@b|&Gs3jP5(}99gYuQZt>@xBC0TW`!Uot)kgk)I_M!CpMBZEPjmFMu5$PLam$r) z?m^3kn%~eFq+HMB*Urz9e=OET1a-ExpADPt<(GZrK%UrGTJ4<(&!YWqdS56QJt)4z zB4daB_KrA71}37Tr(ATyzOAf@VGv!K^$WeIpd>b;Biw6cSNPy)24hRHH*$eW`zX}U z0>QD@Ur&aK_*Jg(5rMhAD|xxndU9Td6=+>Zcy#ZxEC$U%JtD)ZA)QNAr2hD1uo$s6 zYr09P`*u*5U zkjQxAgzq3sGGx(rxtuxh5#}8HAH(lChLiN5wcoZm)&HyR&CG%6w_h4(Cb7qUT9YsF z?_aT0Yv4m~@u5((!Gu!ryLxCu%ftzr9zj1=kd-`~t;>cF(!PDZ&?wj_=%-8SBBic4 z*s(yJxl3aEm4&$GOOOLL5)v|l7^y5X8NG-N<`;Bh6>(eZ=FFspq9f!nSIyGWV2Ujp zOEp|8!EE)X`)$Vo#K1FB!HN&~-ui!904yx3zDr1?giZUDpn!ygKkOC_dr4vJ z2AGa^=sRG3enYnhd55EBtzmtaW6N@t1w=r@rvoy*LcIf{E+*f$28xO{N4$#9AF{E#Ug_ywn(g7#(C6wV+};VX zN>I>_ntW+#%&vU(#oRc?o$2)x6P}lrXe2-QIc3T5tc+!Yn3eLBj)I6v9K|Em(enE8 zaTfXkuAaTbUG&2gwIJ%3@@%o*15(u0NWFqvgwBQPM*0>E2)23@O~QZynE`j1^nT&U~h6#r-nK%IPnpe;V-6#M6O^MPG zaDib*+lTF5oM<3AoB|t&5d_#6A|yl`1bs#JePxX2>U^QMRqm%|XB5#R>Bnpz!03bMn*=U3k3;1TtHB(gZ~Dk89KVU-gyv02VdE+!-NYI z){9U?gH0FQ_lKaigmPGD-m4fc=koG$cx!8FIHB3+`PP{iMuHVCW2k;Y~{`2qg!^CeH@4 zQuFd8;ckbI2WAXdenM$L8wxXdA{v^7nHggposhX&IGtb()CfK}_y(u~8mGmq0U}?!RZyi1gNc$j?@xHJy1ulBaoIgGfk#KUC*fiqtURzkx7s=q1#kS|DT!hl$ z66ysjnU%U@`YYmSPW`2dymZPdmS4-BinA!`xIN-}{zZZoEiQyM+QW^^NoTF@BFlUS z5o?vQGfnO(W3G!^oLU}P#A@18CeC%7Bqr@`r9c^MEX>+orn&SW)K_&QIK_I8*K$HEOKH*iiLtkgbTFl#)YK9z zVO@o$^eM`%JmwP|e}*bY8IU*}qB7!6$x|ip`$a#48S<~KB3s6f*N_b~42@3v1$-Rmbg>Po8hzn6bk_+)UHS9Mcj z!C2?I_4?!AE5+DTvmsT@#*of8_#hCnY~lMKAiQ{jBCVeMg0{31>gIc=GXC{lYY_X#$U)Z*PawqGew^{&WUfA$#W55=N zoS8;~$9ZKAU$nupGHB?-pI{7EhAT%u5BiF&t(|?W>0ygN3PeYSt*FONENP!79?3k< z%mXwIegx~EXNjaThzk@0qb#e>7leZz{YkIqXgmUsXr!FJN1`D0ZDH)bx{BiB;P*O? zaX+3HJ(_ryPFbzU$-EcL|A`f$e&qQ9Noh!(XF&QJcl%xfhD99y6B0(h-x0=0h(^_Y zB*clkV}10ptT^V&YP-UfiI2lS(`|Yv5W23pvCmxJrxw%j3w-nRPVSS-DoW(gCRcr+ z$LOGv#%(2-70XJ%&hyHLq%L++!L)HP7- zpt5XkZiZG85RzSrH2xsC`fGe}csS>`KQL9!CLln%F0&^NAUwd+*1uTSNbVA4$Hx}HZbBXlb2mWgB znK4PJc}im)XsyI!L&6FObM^GuShC)S&+2}BIy&|HpB=Z4=`XK5@)C18qKqU3Tc2qD zQnT8|+6cM5j56DTG)cRz(t|le_c^`SPV7@8G9L+g-E}`=bY61a@jco$~DO_(5hW8ZpOmw?*RZ`s|njNtJZb#wKm>=r;M4 zj5u=W39vG*^y}E%(&jy8E)1kTO^uFO59E=S5T*Gq&vZVfp|1Jun2lI_7h>6?nRC6r zF5A((m-cV0=QUm<*UpEN&cbo2DX(vFr3|fu2XFb~82d21*q_he^>qJuwV1h6#@r#- z`((B3Cu@O1WK+O8rq-V7j_;S_c??CaW}$e5C_C@7hX-b_Pm3(c9a>Ah*VogzsCJQp z-m@}Sg6H{~{^8A<1; z-`hJuDc)$qe7AJW@K#gy8fEHilx+rA(>i6SWxhWQVDWgi1UOvnZ@NjFLCfogI%!_!ooN>Kv!o3 zX?Jkx!d@7poZlKijRe+7VgIuOC^o@a9m*pnHuJRc`NF45sBfbqBTu1rr6eX!1|=P= z-M~aiswfNi0{9)TqPai4f~?Ud+vLgLU}p^6D2%uPUpNcL5cmLQ9xh36OKcpUd*^}g z4TKf(pk!yOga#Upktr1LsRI}D@ZbQ_JWfETi3oxw7bY`xWf`~_U3f%B+i$C@G zkkx#A-o01{Lo{y#DD~lF3ZVr}pD5L>*MZn!GN77M3L=1L+V|1voal)T*>a5RkK~n) zUsLhd22oY~*0%E>L>dX_l)3Buqi(D!Lk|&RuJl7KRf+L-CLyO+R1qzKa%t07Eb`X0 zC=YGvXDVu2MUg(d3DZpkGT|21sd{zT0df8CCQAW6m^mXoU!ZFearS znG{;Y_sa*bk}S7KDwx~RK0hfbFvVA+(_8tC$u3x?rH-e+x{=syQ$bVOZ|?hV-{!k2 z|C8sas6pIya${&ki6IU2-AJ@r?tIAO(%2+BHJ$f0vrnz{?$WZ5u+>F7pO0KmfIXqr zq8t5m7yj}gnQJ&b^FDY_uh2KWcT~@h%(57TYux@HP3Ij>_5c6>V;>|VJF+(sLXs63 z*?X_-k+Nq-c6PSxd62y~iR`yMG7=J%8AA9y`h2h7`Qv@PuY{}Xyv}nx?)UrcuC&lf zU{y1{+MVZr5MJWZ_;L03Wx&FhbKf`d1P$#6!=7@tG-&_IKfOTOq+g8EEgM=0H;*^> zydD=n+I}$>%XU35*-Z7~d{ZcHV7->9vQ^-n%rNdaU3|JRQutocK1L#s^{zKHs<^XD!ROY{|!`u%!58Eo`>Y36=)MhzD2xJ?VzI^!tFodaXm?1;$N(H1S zA)3q1{z8NXoO)2x0^ctf;;`yvrcKX{K^=mF>;I7v;sXAzLyNeW#6MR1 zb0~j@CmFt%RCaS~3!Lz9W(5%&`*jcaP?w-a555HU`}e@`m?h)V0g=l`><*+U0q=2# z5CALme=e^eCIZ@gXJg|@F&LJhI9gpDq$;idg+O4u^F?ILzTvJxeJR{;e|gyauWRyO zaWlA7_s{%bN+SZB?qY)jK0dzZ?vnS>s4!q<5t$f376NPPlJ{2DuV24jzkdA(3EZ6u z9S1<;4y@NKIL@0xFcn_;;H1iRyn7E-=9(H`k*nSyc;EA$S_|v;7gSgUO7RC;SeWFw z-0RY`w-1VIElfCBqE?7p)L-C z152~cwDnI|w1L)wlwy5+T7O^If+oj6fdBFoek=K9)A*HK8o?0_FE%rAcWChbpWbl^ z{o|eteBtM!HM9ZtEn-8F^GQq=*_g7?yh3N*Bt3(hj*&Dgha}&q8pgugz?H z&Q*JR1+`>rJW3>QRM%pGo%ZT%6pFtd3^_=&z#Rmg1LKe|1c^(}aqoe!dC=UCwiNQX zpjeINrHSiqLG!OZhOdELzxnuNDv3rrs>{&* zWE!T^a1N>=wu5m36f(y{S;>(f^u~{GK}k5w7@r#&e*Qox;Rlg7h<3uEFe?kDn{b%} zP~b0*3rGP#o*k~Lz4miItjQ}YFN3TCFm%XPiQS2t`|-%_yBfr|L})+; z0)+=YAhx!)z+j^!uz}7_cri0$zLv@yC8wa+dLaUz>shBo&h$k_|BDp%bg5CxGA5r- z_JpN2akg`gL&tMh&huZjq_ElRm>4P_N6P9=3PcjU9~L4d(qJqrq7Qmnq$HS;h(apn zJg!}cZyTzOz!`o?PxQ$6U@e`+PNIU=B$>ir=Yxo(6j8_vk-jkf>@6(E zmN+8Zx79TgCpK6+rKv69- z4xGvCEth`ppHk>gl3efJ#dafgzRr;oM zp;eo(u-znQ;jgLKmO(?Y^&fhdekS)9pDs%;^2&m4Qx~lb2CIc=5g0J3C;gGLzhp34 zSMQfX<^@{jmis*|ITD_4!E=_>AZA%`=b{y2>?5{lat+-NbVAqWD8Hc`QihIDV(oXV zQ6q|4EwXjYi;(aKuYkTj1VEBj_rRPCiyVmS<_B|hm6D@B2md5ExQ@Wx9?CJ~ z;WN@7a~oh0VCs*+(t~Fg668?k4YgsdUI!L%D+1Z=t4qsGI`L>C7-{SPY$q;`5c~Cf zGe5L~5eEEu3{F#7+0aqz+u$)3&4Q!Zd;-*o{I_+~(9{IBJD8N%fvY=D4cWGNBnHhr zXbAZA;8@*un-m1^DfqN>+}^Lc8IHZvu)9i*>@G98yC9%Vay$3D3}x`^>rW>dD~{WB z!^5Ph?&d6r+&aW^gXQ`OuTO8K4q_-U<=%+7-k z(-r;Ft~hm4995USd6F zFIL*U0oA0cpkPjE4ZjO4J^-z}dv^@H%cI|*6A#>lW|x`%97(WY0Z6oEg4yAP7(P66|Bc_RZn&eM_^yd0XCtM!R*USu7$~X_Q$C|4hkT zz!*>C#^d1}^bb10C!C)S@(8yAC6rU(jG5<(6F=s=| z2e(@?@Z+xHV&YOoxMb}5q)e3pYmxm)l}41-<=wD4FD&KOanxV|kt8OEB<|!r1_Uwb zLWxX73Jtn+$}}Dn0<-#q036r;oU^#SGhdyAN0*(UX$B7 zQr`Djzb`ucU#7}hD0D?adC9L3oiqD`pqS@}1?sMpHI#j2s6`0J!T~W6LXD56I_WVZ zwHIEH7Jad|m5Q`XDxoqCN1;yIbT!KxXRk_4*+del*r*2&u*q5L6tY-k%Bul~t{h0?%vp`sx(Ifv|qTW)BNto}CX^D*w%CjEsPna^lkg7dkkG z0=7r5!9Mw;#o70QIQZqS*EOKjEbZMpF(DyxBqo?O;Rizb(4I>RNGi4&u>5(nbrcs{ zgKHCrCJ@Z>|CVm^uenhU`p~!_=LLe#_)%zRDExeQkR5~^F%k4qk_mVM)HsME)9 z{M;oqK3I9OVI^CrQTIoxa^LQs*XmwVO`Aj#O_YZsq`Pm4`sY60K>v!hP-}`_oH(LB zq;g;HE)fNh;vKokL6-Nwi@xEk+{Q{WVC6G-#kt6e#EoN#Kw#z4d#f_Ae@x>vBj@#q zz-JVYOco(LZqh2%61T}{NXTo!JPU5esfmQax zTI*aU1!5)|@{T_wPGlljpD0qzZReWi)DE)HFW`L_MTySOdTYTk*_?xgOnFn3GlXbP z`JUq@)*a1TUiWz$Tfg-}vKja4_pmz7U*hVRRJbkvzWe-(bDJ74<9^; zjFAOPEkKiKkZZ62dVL@e1{YrQ@-CS7pw%KOAD+w3qpUp|F)yNj@zcenrFLl3ft3de zWgmhUuesT4Fp&l3d%#+R!GBQ^3%JZ-=~+K0EG}+ceqOggLr3RaqX$3dU&A>F2k>tK zQ{L4T;PB$!ROAF)c{@5nH3-ZBp*%B-P-2khE|d29lpw)GJ+^Sh=S;~`$t_J(i@=R~ zm-E}W)SKeAv5&b*6SpUxe3jn3^L9EIo54Y2iad3I`G-+ylxY!jl`#Fe-Ip|cmu2=k zF)Lp`^t4)Y8bNAn{gjW7{F#xCX=IyciFPF<(`dP4zI3QfxpsPo5KEKTudnkCO_{_| zy=XH;9~r28^S(&Sgz+Z~J1xWqPOrapCfIBijbx4@N@~eu9?8OHvM(#ipm})KZ6#NR zoK(VU=B%_~l+BssyC&AK#RxWQ&OndPt?Dk1K9ZDu6tNV*wD;tLJZEqRBNBOu)uILx zsHt`BMPipYJXZprO`rWE7Kl6=iq_i0v~Q?gt16GqM+76wh)M*NziM!`(8W~UK}c@) z%PXx=7pLjn4DAys4S7StPZX+F{621|O(29`;~Ak8^Hcnd&O8nEo=cw$2x8|^Wmr%m z5Fhw-$_Z|vH^hF=FK?4RNep+qQ-D?z#ah<5ama(-z4ii9Y{e}tR1^;l4GaKn_3+_C zs<6nIm}NjM$jV~LssoeoV-#8VP1>R1;kwU2cyoqZIrJ8N5Ss=?NROMGh9-&#zR?gy zSh~8pPoLr=a#5(r^=3#RI4w0FIGA26{=*Z3wHt&NFp|P_jPT}7C{W6<1x=+GSOW1wwhGaBNVn zMkQ67N9Gu5+gyS7pX5f6eH{u@Do{}NF+Gw9Ayt;SLqv#Ggx=nG6L0g5P+|~%l0&(m z@*9105nja@Kl%T1_G)Y^3W5!UQs+9^ddw8+R_ux!MiIe2^i7(~?}_M5N@Y}rjAdeDCl1hJ@X!>8x+ zBr&>iVv3xOToDn2+UHT9&@qJubWeXqkl;iV@+BuVsr^R746J_F-*~}aN%R=qHcV)( zUY!~tITbxh9x5?u1W)!sm#Q0bLzqpwm%PyEqzo6Ymr;xVKLzHM#A#l}KN z5!6AzW2O#U31z|-^6L6x)$si+5QAqDJPyZjQ7d$(587F6c z5TXP^wlC-#RADU;j)bmxI2{3f5cB~Nnrz4c>FUlwsNKowm+GrS`1UhqF!aHx$fSxw zS`X4P2b;#8%QL`(TU;FCQ-Z8KTuG+3$zDGOd=EWBK}Jf8n~Uq8V*oh)<9tfKzHKx1 zPS2nBr>Jrd&(6)Qx(xHcZeGO7zC4c)XprUQjFG< zgdNNKRDts2$RhtIG9PdfoXdhs_y=WLUt2LNRz~e#;<+_GPm^GLra8E8+F1KlB<0xy zc-n-beb3GRK6_W%CMPz)C2riBkrSd!JW#_)-t2gcWvRfV_LV9jVlU8AQ&O6R9T^c! zG~kYKEL5!&O#ZEx@pXDuZf zCvlLS;5ZfU6C_M4)B*XZ)byPz)=OoZMu5jb z0ogb1nwg`lzJEWZ=$-eIBM=8-i8UMpcEM=!J^M>F-h?)46;!#)<7<=z{8KICR5} z64=z|Fnap8R4OV4_k01}9Q0{;rlFGo>|DKs5`XzPI3leU;30-YR!&a9_y6*~f47aw z2WBf+*1o%mazue^{eJ}a!|osq=(&aG85~}e-?@!j-C#LvZ+~Z{|JMXqm%>6@P#X_N zI5@9?Vs_&L?5hy6?0{G$8~}W`8?vY~4U*Bs7|lyb=#oM-!gMt}eRCM{cFBvb*g{GvF$QK;TAfc`NUeo|!A``G25`AAi4;+^t%wM>8|q z!g6p+BPlX}BGVBAdy`RE9nm+KuZCtPX?PDSYJ~1nLLvX0Mv!MMPx75KMM?u5Dk<7K zF>cs0yu?;nMHlxX6)-K22$ivn9~ogpCiA!&GV#pBd$@&cSRfRPD3UMjnQ770>Qb!o z%5qg6B@nnKJU3>m#I!Eng6HW%uD@6}#v=(wyklQl(<4etauUg}m9UyLbo_+rt(sG! zKg#UO4-BM!6}GLtU{kFVQOJ-|kr0x!=xO5UtpXR363VcAyA~6MVE`UL-qXU?NVtfn z&ze8o(!otRTclD7w;h4_;$^}ur=TzSr*uElEczi})N1rv+u8uO3jQZ>L7_C^$LQBu z4({*2;G;CEw@sL_hjD=eEKD#f23Q~DBY;Y<0Pq+f7v8#c1V?deYirm5|4pGOpwQfH zdlGhGZgOBwN5hoNW#bdjG=MDtiFG_YJP5>U>*@;MzaP4Kn&r7dMN6v;bGT4xnt^*a z1pXHc6z1dm4@wbl-{wL}TU!^;{eVDw(~6ISlG2UN=P>gtC}3h>V1Su8v>OO2L!zUw zs0d<-AjX25>+(qA8uA#O@bng_{$*~f)>^(P_`6-sUX;JJ|MnHHOUFdYiFTDXZ=lLa zp+%ih=DsO!bBY~3wGJ{}yC;p3#_i3s=cALXEAf3XI7E^fl%*q#1mPdx8VWgv5?)fk zoaen@Cnax+*J88MPg&Ok3|9874&54UPAEjlLuP29Z=R#wGYzD;amV3ns&`(`OfRHV2tB(<%=6`V z57f34!!kA^qqwR_mFE8R;*Z-uh_N&>^4{)GCYoIcV$_o~m7gj4h}+)n%pJbU+TI?A zz9;olM42R20VV`t|!Yj=I#pgLC7^WT%w2u#*v`L@JxA$eCroQIk(W zdVUJTEC%R@cu>xlJrWqKM1_6(+p`VPRIqmIkZ--H*IJ`4ZqNnguws8`!UfSN&Xp)Y9GE4afG=U!VU8G7wCKp~3+G zOgCYss?2(;(gcpq8{fVG*e6@en_pb~s$tILO>FEHBvfFQ+I0})3`o^3Q0qk8zQ<2( z1LEptBQ5QnJFlQb0{pH}N()*d;JBo1!8Q+km=E97V2>;jo)CQGFv|@yx)&ntCVQ|8 z(jhUSQ(_hT1As9FIs$CL2VyyynLm!s;A!vc3mM;f3L_MG`S}J1U3k2KmIYVCxOd`J zIsC~K2s{3z^S&L9kc`f*mlA7b-q9Ps3Y;E(!g_@Hd!&8)=p|E|u0|5c zSIJ0m%lgR%;gMb<^PE6SN6yu7FZ?MIA%aj5BN3|y$!y}-MSyy?FiNCWFBN&CSYxO{ zge5svz{s0#l%1lVnctLZ8JVZ0z~KF!dA3TPBej*6ND|4eSm)L6?>-?T89#D%uk?vz z0|MOwQ7b9gKd(SiE`lGkp!<_P2Z_BF@0Ip2~j>i8u&!_6=@H%tFEoaqMt3nZqvc*MPlwcS$f^tS?2FMy_~#okKfz8s66r5? z6uDt}fHy{#bfP*nA4LbGDi{_xE!GdNAEYT2zs4byM*izQGli&DDzE7isRNHd)KR3w|Jb3Vo;b3DoK41Q~yTP?G;C#CT-eVYv!95?eh#oUOVAw;d z+SK8HB_s8ggCvf~K->y&hj0&D2y>N8JrEK~$-WAhzt}~zmHGTwUD--Wf7o$K9;T2U zB1j@Hjie`vB2_@3VUeAY;zxb;O*!?--y1B6u)vTlWXGET~-$N-Z5fZ3Hu=7K&($yMa06P~KNaIsK_S!ENbDETfzTT!M3!zsn zeD~&yEY-n=>jg_7wU#fl8ozmz4=tQL<3v zf8=lPio8Ig^_bmr$v*gf;I$NsV=T8pi#bgSHO7NlEwqT=@HVIbge+Ft& zRT>zX!Ow3oR)$n(&!lEhD-|kAboOTQZ^X{O&5z|vvM45%)?kwUv!o@hs>ZnBa3WPeaigsVft4l^ct~uuAeVN-=%pORr?uQ^7de`ErlKi`F24+?gH-rWRtc-WobH1-%~9x%NC?gRW6 zCaM2Qbzl>OyzwotH0`bU11<Ai6CkHNhK&%qhxx@muq45R z846)~uocE9CiapjLXmJrPL3%kWN$vg5e~=^pf|xf>GXN`$B#Ov&$SgW&CT-u_79+M zz4RGobMEf^VA2ajD_B}Vlk?nb4WBBC@Al}|lk}FSR_h4! zi#S02cVZT`aiaZEGEc=S!|({Gwzx9(`%WhTIs!M^LU_XuGZ z^d!`keQl{^I=<|Is`;F^;GMXKjZOo!1C6vnvQ7!iJIKMv8+1CZYb`43ebZbIl(9GR zbJw0O7*~mM;g(~t1jc9RzqRE#7AkhQtuP#3yq1E2}aoV*NLpu1iYT zx|;At?D&qOhV52;G5+>jI%8;&$Y|csDL1D#d|fo_r7VX zxp(&QsR(|D;j7c5t%9u;zstm*b_|CXKDTM8MZww4lz=S%>?1rIb_nQC)`8+mZ32>3 zk@Vj8&G=F3bdt@S4AyHKv9V?6H%ZqX5g+ru|NXpQ(1rD}0)B#K^X#qnlI>|#=}GpGV8{x_F|jiNEuzNC|Ue= zImWHQ*8kH}#EMg#vR{XuNQTmoJmpYlxK}5T;~Qo#)G|DRHfMP2;jm9n^nzv!lqI+c zZh!wS0>abd#~9MKFzbhiEhpq>z4pyOM}k8i;Qngi;$tg#-iyx*!(g$4zFTn22NxVH zS-|b9u72?k!U9$Ha3P?Kd6Jo#3H}9e0O+k{PvrdbxP#9eCVtRMJ-fPUs;~b5P=x&a z8rs@3tE;d%Lru?Il_~tWH{2~?d@D&`4b^er&H)cCgx+igTY*Z%Rn;anE~bkT%JrdX zl?vS6pqepI`#oI6+{(sO-+nBU(e1YL2v<9K_n9OTpK-98&ZKR2gGV{#2FIokAv4C{ zpSOJ<{mSs-@8tmc>FiJWx>7g= z(!OQ?#U-MX>1iwf!9+w$Hq36wlfDd5O!$ms=`D@sV(G_<3T!2K#7apvkpFw}bysxy z4tC)ada_TPHxKDG%WjrVYU+N{Rc6&5zj2IJ+r$LvR#x-t)ZRmiMVzS zYw=wR!4{-jZwX;pJn;_0p*hLfYYoq+`0bheJ}&&wPrvRHorDsDUCERw?d)cNZ z3$rHvGoGE^h7g{Fy9d;W03rf>rKwq2{=K+tz}FRngJjO1J~kMp!R2NS*5Q}y{V>7< zt2WG_onWHk=jR72AD~QkzkfF)zubD~ItKF=Aff#QvhLfrAKqz#OI)^h13n}zFeru& z1^^7fNcmrJ8o;W_-z2A`2tjUb{Qz><@PX*KJoy)Gx^YTMN(!eJLIMIZQqqVM)XK^V z{;Xdb$s=kh4(GBie|A@eYz=4S6`4|7#hR%2(&axLLF!I8TEc-cX06&vWxDD?9EPl@ zWy`uk-W~<0k;gj-{y&MmCAJN;9J>OB3P%Muw zw`2b4au-iKe4|&`z5B62V^DX%B$<8;q{xFh%N1z4NPK$-dU*m9>J3*pW|*ue-)1lKRj6oV@A&wQV^J7YyZ_Kpw1d13%#T5&faMRE0ML@t zxgW|4`F$goK^AaCLh2R{13+n8> zRYA3{nOUGl2BZ!I1xaI`fVAfVoaxxOIQSJ5WMt64Wb$&EO==_KNAZrvJ9d8xt@w;) z&a&6YLelVrlH8mS!Q|+h%p`^Rh1FVm$?C6rqyrIbr0CQGh*ngnUP=V-yc37P9)Wog z{m+H>Ec+#Vp)VXiM}FQBX8F6JQiPr+deeNh$>}|ZqLV#?%m`8C}qo(t<6xs!npOKUj+-)Ny(nM6i)?;(rw>O&#g<^5!b zoYtRnp4?BLHb%U&{rqRTfY;HER+dV;#BaasX)0+bQD2*o#MuuUAzHdRMvmBKoI$nq z;W)9gC(l&5jno3ZEfVHvrp7)wm2kbjWoY2jPlMbTH4^3WvK&}BnK0{7pfK`0-nKHA zVOtauJHF6`yK3P=LrGN&s9y`a6Hb2*x|}gf+jknrbE>aVa#!_7@~4zRpGNNMT6g{J zF8==WhjW|x^PT-RiOX-!nNfGo&v|Uf^nMbZI6GmK8i)(uj-eHu#~{*o`M{%_LxfH8 zCNUT5<+CkQvGiTPKQ?jC_p%X4is^taA9QmbF`0E*+x6>BImAhv^=CH{m*-w#=o-0u zIA!3TD2}!73UImfdD_))9cd|3H5k%((U@t@S=dU_oHj-bl<7->ME@=kMVh4oN;F%y(G5hUs*X@GH%hL zKSf({j&{_BwS4{=5Bzfui`QPz^A)iP6Cn#jJ}7u;rW8kXuO^ZH?Nc3mq!#_aaMrrH<0bG`8A>oH=D?Uf=FmXn62+EJ{2_LTtm_8QiZT4ne}>cOXCtJ z-|tC|sw{@=ySeOl_HPdybGIfXWjL(7l8h_N_)3SAsPgd76~zAZRnE?Rz)JX=7n}!T z4Sa~ehmf6}4gUkeP0q`HDj1RyJvD9x=gys1f7ZOj#{L|G3WUT2ov*UvWD(ppE1LdUG?Ii)-d6DABQr5Kdty_x;$VpenRWahY*O;I|HZPh zXmcIXn7FKH@lFYFaIF28aw$-gJQ|-)lE6I_5Ou%jsMJ)3%+&vAx<*as720J1Up(s_ z?MTgCK5kQbCv~!f@*U282Z0duJfo*Om67pSA(M95|8iK7D5R z)ncp zu>Lu^KgvA;ejfKen|dq(Tl0HJf0MyL%ivMTUH7TRlq{#3^V;=? zaq8@Pd~B(@AJ>g>+7K=dTvPWLWs~*)<8R)a>r#AhF*21h!l{%{qWF`BuP{tt$c94h z>n~rzUzh89Cgs;VE&UFkx@W^dye`NxeAv|JIle-%ci}$>-9XtvC!%u_J^_!35Wycy zsyg;V4r00jo_l&K&IA`>joBJJFMH^wA6lo%8CR%dg_ElqpS%7mJoZFRb7)7gpYYDY zkq6EYN<6Rd^2O(Gs}c`=cqMl#gj-lV0)XPF@{ z_WiTyu2*=cG9TOyC0%(-$$BJw++*JsQ?G72U8j=yk1`{kI>;z=;@NN&%X~owNzN1`0gP@`lI8#9#ewUKhzzD+O5%Nal^d zz|R3c`2eJgMklaWg1Lx=6b}NrJS34f2nk^{4Qj%jM?P*4nS*>FT&;hq@eIRQ*>mY7 zIPgB^H0^2>()xTR36-J!5&33W)Om;h!KZP<)N;aG@x?n8c0*rEm+H7Y6bwA%=iRC* zdPraLXiL3rno)S0!ntU35^C<6cVZ;auhnR;7 zK${)BP>~lGYRUULJ+0rHDOP$}gLcI8w1}+{Pvo~FNFEeg_%kXVi`A!*DAoik7X@&Z zd@VxPE>a@c^rn!Ty! zGN>$^l`wU&bNW0W?>6G+*r;=phL-zTs){gcUAOnzWi zkj482%-j?lINcr1AH$^8_FMGdmn9W9w}t@hhbYFwnOd6C36ph zRZWBrGi{pajIO79j#VjmI(EW_RmTwiTL`|Rq49CduS&lwt|xwt*9&_N&_DGh*uFk8 zjCsl4xqoYpXMD%^$AE;N_jSs%TSwO09i|>zK^-HQwlBt5DBejr;vg79-G{}S3poV> z18a;Q;PZB#w|_+-WG+)S4^p7@qAN86& zF~^pa+bb0yK&)07`uLnrdr!g4I;f`y^-S|w8egV*BK6@})iRlE0OO2UV9GD%PrNb4 z2Wr`ieB%Sc93Nc-sFlSrW&Sb^XgJ~@#t4gGG1rz%Gb9lOV_n#(PdMZck&vzkMtNBh zdgV82os#!t);^0T4xwZSsZf7c^Ery97lA0jKqT3u6k8P)Z5EB2)_ncd)CD*T{AM~} zvQ(Q%`TF|uQ96QPH$J|%vm*-CBUC+uetV$bft6fWL!*~51Nv&<(K9{G&l&fixf8 z-!C{YF9>+$sp~KoXz)|$3(9#qk5^$Ys6>$Xalsd@TbVu#+Z%OYrnIF`9Rv{QZeUm)H?|2yl(-~u7L8>} z)f3ytMX)EJdNq>Ftr_WMonBAhc}nN^p`2CYE+%Qx$JZ6RT*p2`L8u+Ca`weYM$Y5} zO?zriMIzF0uQ8OmlWqrd{B4|%pI08x6yna%&B6rI;Oyv?iB zcOo_ACn}{E77d+6)58D17oe+f`u89zwQ}+7OQzwSi-{Bp`|*pufpMO!-l8767Ggw1 z+yFy-_FFu&0mpM)8gryMrX;Om$-OUK2xm_7oRu(Kv1K*dDy`hSF|qchY)bY2vRN%Z z1cvNzr-h*9Ggtkd=Bj7k5}$c#s&`pl_vqq{-QB|GCpD>jx_7K~cCI|yRI4df?-Ai4 zTc%jBWQZ9R-ILd}ps+jcIlUsC+Au3W`Zee<$rM zZ1GsQ9)r>i@ysh2rh&Hi9$bc@6ehM{v_4sMfI$&nX=;7FptQW$9lG1M0iomr?tkz&2=MWBR}`0(mxJ32jHm#nvrgmH^qW%^HRY#GxgAcU zD2OzgMV>Lru-3}!eLdPa`mCIajA~^H4@qO{9oI=$@N0#WG)x;cobDg{QL>QEd^zkG$u~zT-YVf@$y2$dK%O{| z^=FpOub^zkR*=_~p$+qv8iVGCV!Pp8uQMx(LX~1+<Sl@)4oKd$(cz)qLHE4 z!jDV{4BBv?^}49dk@W1GoB#Q?JB3VJ5;S_KAS^c>zH3+7^_e9lriURkwv0WF?PR5Z zOskRhI{Y8z-NTY+1ga7Z9ZdY!lRr|ege8u@wBAKXrkqgI48|gESmyZ5 zB;%*k-csSpsyL!88Sni4bk)RrKg;IT(a3IUw%_T-I9WJ%VB{KZ;@>MiU7vta;>3fi zdx1$6S`O5RPSd98q|;nsWo2Bp%xrJrhwR(qimu_JK6VXS|5@|~A!L`r4KFu~RQwe< zHpO-7^O0N_??k5tcgneUj`~>_7Dw3pc{H&Y{9E0gF(f2Z=Z{8`GRSJ@(i5|^sUE6* z**QUCcO#Jcfs$4qsv~+l(4s;USmlwP22{T9UxbG#u6s|9 zPzSw$cjBP33djKe5--3Jq>h0CEl5NHGMzWzY#0XnKfp%>vwXOiz`_q|01yuW(hgA? z4+w7!ag_X1lqxI#xwNa=4;3M+31%c{q3rhp1WD2)d>~--3bF&Zdtvb92(bk?S^;Zt zcY7Nxus|+u#cg;_vV5vc|4YWxG%mvF^PFzmtO;v5&Ks?xizwW%JX>KM9CfwWvTwmDt6`Ayd3}C_EY5CcjA%mPhYOyNgHO z2AyS+gcF5Fy;D%O-Vq7W#pRRk^`%>KG{&6Qu0?KRYgFR*>%CoLKWgi&Fq?c4wH&V2 zR%n4!wt(@q759!_I98%t5J#NPBz2ukm)PW+(=YjK^jf9tMsd#=$(LmmEN2Q3f79JV zh-T>Dy^=$Pk~x#=Csv9d=}aqbRr+8jA~d`Ho8~~*EQtPMT*{2t`!DZiQt;@Tob0&Df5^XW-GM=*;=hFkrUwm6BR170EB4a|#reP$hLxh<&*O!+9*7OarUtNG)mRSyS2 zYDn800B_1>Bn>}OSE&}W2JW@sW6iQ_h2uQ*GEbJD`4AZNc*}FM zB#S?J?W`5Tm_(8*$=)wXN~d2;RuW?KsfKGK));y4nHX0ls#zi8X|g7>TAkyGuD2#n zWOR>3ZlsrHVeUAl6?eeIQ%18g4lL^22-bWhZs(LwJ!keZ`^Ig3CT3#Y{BS$SOvWL^i z{R5i>pMdb}tNN+IO!r-a91)%X{?40L@7zXh=D1NKl#gEh>CRhcLf#6`k8S~L2ltJ* zMj@d_w^KR)G0w44)G$W1ikNH7^PBdYm`P4gIir5p^!JvqiAa~A*o)u)1%04h?>uGP zc6#6!;S>|@`|Lo3%5I_V*YfiFphT=xlUFV(e0xb;ci&~*rWBd1zV^D7Oj0@~Dg5`* z2s?2W#Z#;Q(l=s$R^Iu~p>PSICi3WIpCq$euKg(*v9^;q-H^ocpvtylJc|hj zq1L0n%TffcgXs@lpFO%Eo8kW>C4R(h`j;JOe0gTjU=te5fMRzyJiwTDLESk+p}tG& zprh`WaP_{5B>cX=Z8&8dgez<0tEf9kZHZ&1kJe9Q<4o|)5wEPefj5)WSlG_mQ>YHke5DZL*SKZfs}>9=yGju9j-}IvE$U!tDhJFzfqe6nC-#>u1Vl=&hd@LXd~J?Do=kVNNSDNjU%(Hdh2 zUv)j+NZsQaM>)$8&aY#)KE06EFiLi>QvHG|8FFHny`OtGsC2^hlg|-KbftMUp~yR{ z;rQqe=A*gc$9E@X{x;W!Z}^|IN{gedm)?yLi~KF#do6Q=T@mkzU2h|g?xkdMVghfa zPLFMVBhO|T+YycAzX}TQC-7c%ntup`^!C;Lx@92euQ=bTUaq;Sp`dOxpf(7r(_Q&J zGi)EtSu)kIJN7weuhifoCR1nQlIt0N+q$aftJ65+`?`Mzwo*2gUQeC=5Ndj*A}4p@ zCD;hUDf7z3kGU#UWn40f)SnA&gb2_fpn2T7{U>TwLPQ%`j+Ope{peH~^PnM~{Lxcv za;zCm871??{pqrEY9Ae)o!-lP-A+TYqgs-b_GzRqCBM2SY0b2@E98)bU-OG*(|#qg zS^n#;$`i2j&UnkHW;04svL_eqC11)5bZMl!qjSt2t^ZC&NsjUH*Ct>p-FG$}S$Xbu zlQu^->xPrdxyI#Iqg99RTxS~vA+LIb^`G6QPVd7(HYiDSTy9Oy%Y}gtILO}Kw}`E3+PY z^500x%)BU|yZjEf09t6s+{?c&u3!7)=_|(na3d5~rhk1q2-exB3<%zyG>iY#`ULX~ ziY>&U^NTU<=a)a5sYyQakH_*l z_+M~2YdN9BPi?kvf~DR>YQ}%}cHtdrBy=>s&TAs?YW(wC;$3ANMlCWg#{?$EwZ(BV z6(~yWh{cuI1kMSmsMRhmp&~JV1>t$DJw?UjAJy8W7l99DVipgNQ#|X$lK9kFPNJ!I ztHodWiSJWLMoQ^qZfJ!~eyS4A@ebYngIs`ycH*7n>sy*Pg6VG$BW-zoU0h8UsrL} z*ZX?>`X2IEfY(@zKxuW$(A{0z)pZz1+KKI~Tml_sWiA$s+3l?l7F-N?2ib%!gD}9m(ASNgk)fLKdobgjrE8=pr2tiqmHtXg(5EmqieygW z*xky~UZ>WNi;{elNP{3r`tMJ2-rRg|Mz?F=={DYG7|t5@P-4TnFM%j}%(Z_9wQ|>j zj~(wp&{Bf`>FzS@(M%yU4_rVPE`;VS7}SG1nk~z161=SN0w7m|=blLl2ldTxNQS}1 z61IMrXx7806j%x&AJzaF5*!>1O#t%Di9j?;Pp5kGaqPj?J0`hUzg^dyOo;$-#EqDT zEAguGv(Xg{TJZ|u_O)Vb*Tgd#BNW-3Y*H02q@kaZC^bjN71^w;rj12C9r5NBY3HAv{wW&AOq|s>BKKd0hzhwAml=M0fqY5h zVK>i&$UstxSh0FJr%>ftC`J*#@Q-Z4znO&Boiv4Wc>f`$wMN!8Jj9-H| zS(x^kRW>;$d&ELfM5VYfT9?0zuj#%?E9diBaG_DMrc+Y+Lq*!xxHzQX2JI~uxoo+O6z{o$M%yFQQi3C;Fj&_4Z}}p z?R2Aj%Tkr8=;w=0t5-AQulQl(0+Szj25Aa1GBbhGwCc4U12o1bjQ@(8g{Wi3((bMQ zm-iSP?O?ly0yjumL&#qqQbpjGQB)j)r$>OFAKWys9fpU8>mOagV!qq@qjKFC!_ecW z08MJCLd9@fpJ9e>vC`&!8mkwzYWcA;y84y+@%aME2B_(`&q*)qtBhku*hxGec$K4L z=WFZe1SUWC>sdS6Fv7}xQ7-=?LPjk_RK|RZ#yj9Zv}<^k!(6pYLA>BMB`=RTr7P2> z@48r5QW=rJ;fm!L&BxB{2lKb?Pa+wpaRv ze5SrMgRDz1ga~f})8V=O?|tu7Z3BVQ)_An{DbGq5WXC&880gfU_%L;Ib}}$uwE4`% zC?c#X<~kF~k91!$AF~nF&$4g6W^;a`tJP)rRVRVMasKC!Io+@kGjvH z!Nvdm(d{kP?5)aMvXj9M?DZ~M+n(C*LeFN!$eO<%x+*PSr?I})#m#v`iY@YY*{=0$7tJRQc;4)d>6OiEzH~yGie(0nfIh~B4mBR zPL!I`>{5L%s~Lm~?p|-So`{6p6LS3Rj&C#~n-iMz%#mT_yqr?kUN#nM(!)?%U6d`r zddqeWL8ZbahD01NN@h{kFMPHgn~{G&)*SX>O_H7{ZUFAdDi1c3fVn+C-wYKdZ~`JA zBy4JEFm@fi4<^)q_G8c$;Lfa~q5`ZV@SwoX-eosc92pr2Vg*c78|v$kXp-$-HCQXEAywada=*#dzHFM-lV^6-KoSm3rH-V-H?8gR5Yto#U(F@@0KfS z_)Wtt?31$T&6*2oZ&tTWt`znpt^#A@DBu5rTjah`Vd5ppGrTUn<0~{v#k)SiF_k=z zCuo&Y%=q2JYX4)TPKzGv>V~XqnU9Ehh-HZ|%k)f{$jusBl9E0&MPfA%)1z6|?lf~v z>ze)pY+DxJu(`BALBC?M@^y^@??d{hZek-snKdaeCoCHVgI81em8r? zZEO9dz?lzcR48O2`zR6-py-0QR*sIJKW$Jkqiwb@49 zy1}iuyGyX*?(P=co#Im5-QA@?k>F6gxV5;uyF-EE6kYlLwb#D(wT^a@!{j7+-g~2+VgIsuJL#)2I%2(tmXJdE=EgoZj(tzo9sXt8oV! z$26*Ej#CJyKk2|5ML=<8;W=5AKdI)TDv4myTR#d*GZooU&(VGA9nzYuwcjkJ2+hc%>&T`(aKLV1}dJ#_-9M96=gh>S-9(S zirP}ockbf+mKa99(=et#Lf++Wou-8}JU8~94=>P^u*;i&PXRI85aS9&GYruML&(Pv z7RV~(toT1(EeII-Kb1yZ+g>cBtBZDS2a6M6JXwYQinaA`n(Peu8>nY#^tWO)(f)r?IZxvY$s>sckTQ7?*_s@(%Dpi zap*shMPbQwrUyLI?b#T%&+3nF2`hf9&c^rVCTpEF*6qL)KTjVRE(zMcsX`|lo@@O zLETD*@gAB8M^zsy-aalW?~4?Vx0F_vnL@Uch$B4u#a;wU@_mF|V7KglUlr$0=~y&A z@I9XN`ozM-iaDwbkZn491(w3^r!$VSDr(v*Cf-j&30q1TFyH&?lcp(HB+SE|wBEC& zaKbhI4DrRV`5x_uZI&_&x{6htB$ugk{!TQc5rf*O^T#jwLLTKO!A=fh+R=qWpn|X` zNaodSo6!>TVXwI){{5M-H(Y^KIUVqELJ|Tj0A1wiyW=`U(RkEoHO@S4_vH&DY6yY> zHjCngsK)-A!$I($79?mm^8$!;8@b}}dQ>bNGd!F{baQXg=`T_FI z^M9RMto($vK1stircN>uF(%>nxzyEGM)2p8j?XQ_1v?qF5m0b;2bh6EVu^RBm6)c{ zPLb#1nE*D0Wvb%F(+J_cB07QEEo%9B}_qZ}C&Ib)?k1Pp4`n{h8l( zvTxJ=)_YdD&6 z3MKpu3j)p&k>;BAvtYyR_d20}!?5$7$e7zn3V3XS?vGcnh62f6@C6=b zJ3ks2$JKNKL0th@PX$!>9as=(=3>Alk63hLR~suSNM>$qSPFF5l@kKH1j#(8vw*WB zDfOd<@J)%J6@XMo#9gW54AQjvlRU2{^iFLb_+Aj7Q#Rq%}tk84hx-kOlYW&`z4R=?PR&>#_C= zkk45fv3?%Sw;m(gp?)?dscTykfS4ha-cDa~EU(q7j(-+y%$T*wDQ{w-Kd7WS0Zq1o zpNXQ>P@us?bRhkWh%()47Bk9=jenz5(;Re7j>*L&=$JlQupiIsv0F=BU&*9(pc+}` zc1^$%vctrmJ3w$Poz;e1^GyshX-6874cZ~5o<}VEp34nK?l*VQ$Z$`35!>`%=mK%+ zG2p~rBV`p=!0$U^weIX1#@aTwDz%lMGf@R4A5i zR`6m5+6ALU>VPz~}>tB|;aFL2THi`G-2JK^&?plwso=LKI}!j;8ago@UTg+79b5$3BRLp{HbPez6eOW}5rHqLpfU5<$D3?h zIikjAyJP_hEOeAJK@xB*dqzj8^YnFFSzFX^=JZ2NvzZ6ovnL(j{5Wzz_IxH)t{ z&fvY)t$yUsc`A^*@{UI*frQcjjSqu+ z?NQv5mm--tOO3$HVhA8@ST-QapF1APJuHvIEU z1<~r3s=IXPg1vImc)o@YWDXMjZBUYwM%iq&UH+6;>`MJpX(QRxoElM3tc8RlA55GHaJ7P~M(tq_H2AFNYSD z6sH*^4u(W-`<9&S_Rnzf7ifnycKe@k@%&dzKdgwEMuyDUB~k}h%;O<3^pLP+0(!k4 z@@cIz|3?d859-uclqh~WLQ0n$dP3OB7EyyOip0kz4qaHX?K6`p2GZce{^PBLF&9up~t5my1hY$bW^IXu&anN>p||3Q_Zv1Psq?H9Un2n_&|J z%=MaYyL5%{{lCrySTqIz`)Sg{@QWH9A@K*yRa{sx@$vDNR#uR`i?`4gWFD}--U(q! z4Gauai@0^S*+r-U5 zRpTW-h+XSVs)()(t|aS}Jmo4m%D}6xETrFZT+65BNeZfgY8~nrjZZNHi0Z$?XJT!! zwcaGP-r5wV$0Df@ybA3Z(VWy2+R?FXdO|dC)zxPxYh<<|4cPlgg%#;EN_@Ynz4cx} zar_52Cgal+ll;gynbsL`1_B#gLhIZ~l0OPH-6wFGT6UUn#@1dZaF*SV71I=1Dk{}H zUSXyvV?=xDBB}&QX28}#0Mhh)ytG1W2n7X8*g_lRj*2&p-_qyqp5&>iOCY-O(S}O( zwq0@NcUqm9*$`8*34e!w^udLs&2uKD6hXbTjs0HN#zzW!6?G0p0}sRCIT<<^8gBAVF+HS?B~z_76uR-kcAK*-&5gs z*QTWeP8=y3%iU@g3djAwrFrzL$65b@DO7wnwY+cc$yFrf#jHg#SgbG#c&!@~UX$yw zL|8T`X3MxJfZ+QHelf8&?vVAzNHz&PbSK2W$_a$n05y#QF`o`F7k0}&WGVJ@zjdFl z&S4?JQsXu!ddnGxgGI3+)r|quy>frW$+zy69f-Z#1sp*9hbzDE%0Y-d(G!D7$8jVs z-ki&jTa90e2i=Z(udo(MzW>>ZlEUIMoGe3*b4oUaUuVTCHJFgq-gziM7F?TpwE3e> zuYX^SaarTiE{iAxw$ES#2cI5|D#fHK%%NBnYG@Vm{|WTlwwT}ANlA;HQtzWUx`2~w z7E)92^6HK>2ah%YpMWCWqX{E4KrZ&+S;o)}cw{yI_lnuEv5QBe*12px-S%X_auigB zP+qyS3_;U*$O1qNI0RYm#nvHdVgk*v#MK*G>Td#|RP{)=8=--}`u_~2FIeb@lAuBv zr>dLux~bYSN&dnc>Uc>JSywfSFBsb>!L0s<0SQr@o|=LfejxrI*(5SYXJ=Jq<+t6W zATt#JR>*f6;VyuPCWeyCikjp>#akN@$#?x>=qKQv=8~$iSQfx&iE6RcUf2r<_%pE+ zoepzXG~7s5X?Bh#nE|G(-&Ac^xncHYLh{(kAoZo(9P^Oly8zGOXPN?IQZ;XoZToaR z&{Z8+v`~~Qo}&H!JytS}DAG(*xt=vv?TTR(WIur4^pZdbOZ{CeAhW1y2D5Y#A8gwE z4TeF$p*>lgtLQF=yt%Js!JE^u;T(+#mcn+YQ`}QS0a%u9?gdq3%5i_c0MlEUs7x8N zOO#vFy}f=>8j#ZVWWFPDWfBm_Df0)>pw={&A=S>vH8rItQ~N7a#k;u?d~kx$Sx}&I z;hp2_Av(FBrtjNN=NeU?!ifi!$7jF5t|FI<^5v=N=MP+mLH&Z4UDa*0g13k~?X0t` z%}f7_OY(PD%hLpt=NTj*2;@9}P5t@pCd7z)Ip{h}%M5mYUGxr#s?_g{P>Rbl*j={F_<<$QG2b&hS$ebqlv&(z?c)Fl<`~Lh%tB~*>zQ{ zn2R?gw^c5>M5|s`24_!uI@eumC5}VuTQ)*{cotr{C<|+j1-Dm-j3GN^lwvUwxtW9X zv&8BP2-Lx)X?NWJ#Ees$Hs9JG^t3Pck%k@_uE+|FW#jGJ`|ntJowf4`6484M(-(mL zI`udlAD1naPWR`CzIMm2js3f+_j2_Kwh#7?GG~eJMF0*e7|H$1LUWr^ zDX)b-Vr+s(*{VoU5JM)L3L1y{EbF6)&|MA0po~OGV3Fc5@$MdRiS$Jd7+*vbejgQ< zRtvDA{gp=qUfS2X5+(CH3#dyqSpN4=-e@p-Q)kq|%cacns!=oO64hXi^)!8~Tq!)q zE0N!ODsqv?d-<_gEzJ3&*UE9yFNqBNs}tg*`zu$<%p}zF2nhzZwx5QD3pTa3-5e!v z^S&P#z}UlhXc6qaH55!YdQQmGIc(x*T=U)zdN+4IDNXV}>=;}npy)WZF?m@ms+sS- zOF-9xh5EC#8RUBe_IhYZ;KP_;%x^y!XgQvizxp@-==5Qc<%Z~E6LeTzJxlz!aqBi; zj|$-9?)BY@MPU_q3wIC6$lvn1eCyvw7=rWy=~^ORM_2I+{WJnyV!v>R%q&?9*F2cz z-CcP<;j5A}wjG@>Ppd!yIOb;gccs>!>2|__b$DtF!i!{=-WS)X0Z0AN|A< zh&6l?+S9u+J#|h1238;-IPt*=Fv2o1k%tM*B$A=xLhfDV^W9!sws==Q|DcP%^izJr zKzX$F>~p?!W{Fr-;QKPh{S6$Z~mD4xw>bTI?;*dLpTp>od6J!kWl!YWfu@GmDUT;Vy-GUn?Yr& zb!JpalSk3@h|yT3PyoVYO*|JkdQQ~t#@Pvfc|WSjA592yD-mnA*5nq;;tr^y%Nt|h z6q}1M7C^I)LzNz@Zsw)51EN1$q)q@(N zqJ6cY7I-h^t)QCc4;vKjsX#5<-2ENP%C>N#vW%a#cAMO1Wr-(ZaZQV0&*wf=@5*S_ z7S}ix>_0f>n!V1eU(D59XRF58R@XK;#VKn`8IvAbS}y`Fcqb)OewYX|g#su%UoU>H zK>-qb+lvAQr4PqOiP!Ht5w;j!UiAjokZ9lX$Y0;7{Yn5ue+FLryj2Y>>?g36|Gzdq zDVgWaD98F6rm3=!4* zO`lO(lV5&Y$M1A;l}5fe6I|jK$o+LyF%#eN)8E!dsF%b3>{CTX@4-g<=Xbkl;`5{* zZ8aQx33wmRrFFL81}c9NlWC(!fEL#@6K)-yFExAZr+KP3S0{@|Vkx&K^8zx#rD{&`*Y9X+8!woHNgO<@Z?&RGtlIr3_{rGM9{BDKEVqUVX^2*$ zLi%fzW3Ol!&j!XReOWgd&P#N98f#HCdN>!%1k)0i(5>-^+@GKr=*z0hECR{9&gN*P zDPgbcCRN{`bCidNYvf|7Sy2e>{QsrUZ-4m{6M=FzZTPbL^=xkTu`_b5+EbNVB%b)iAwfwaRVj* zz_p(`?QiYmU9-#k5peZjA($&O#k@diF`Bcy)kYQ7-2JpEXneZbS^YAX%Q5UXK)KX# zeZ4L8;j~Tw%V9s=c?}{T5q@4U5?wW~ecB81XMh6)bG_f#^TObK`&j%uz5d)p{%Y%T zS>6-yR)h1wbaVHXdUj%mEy@9e#QWkH+) zqlp41PPP7uP4jF^{u&8If&qgXEjRs8BTfWq;v!k4ow5Xad=$T?v3$V8B)(PG-sdN@ zw%ARXQ$>lO2(>nINw``#B31x=*QyxO?JkJvLCJNj-)s=$hb%sObn_0<2 z?CXPLb#>L>so8CPwosKG(#=(lP9RGLlGRxa>8hz--ds35TZyYoRhSa6t_X(Hc<*l} zs`BVL#|4{$+Wizr_xN@y!2VI4nF^X?6`-L!Hw_#dQ3DAueR^;J-Gh!48;OM4whXsE6iV6QIdKSEb8nr*c zE>ZP97(QZ7aS$@KGwR7vSK6y8!XV+)OG%5V%T-^mJM_Y1MaPn%R@a$a9U&hf(=%I{ zt`Um}_lF3fxR>+)pYQH$3EY1gc;4e@VhgqfbNjr>KJ>U>!JL}BOmI{`x`3v2zqhq! za*?lnOchd=6t_Z?+HKz7mC#Rg`&gZY&|e0=ZqDB2wl~QT6PX0<@WOpuuMRo{t$LtX zmqx{*NKEbY=SOu8&oS9#M14`Wz5mv+puDaR$^SSTPrMS6DKhQU!i@zteCx!|(RltA&kP1I76|gf1Kfa#iZFo}%Z*8oiZpSn-45(&tZSBrTQE~G5 zm|8j;eAcnivlavX)r7i?{-Ij&X+C{oV42Qc`u1)S!Hx#WmjvM8;s%@_7q;Ked&LDk zFHMVr^t7M=To@%&H0i`~iBe;!CRd5ji*d%flEk{9ywl^JUf@CKI4o-3NK5d2uz`UW zjA#Qv-^MjErUC|Cv?*-(B$HDU>x)LQNqqN|hJsPnyfLC43C>rCGmTb~RDFW|o$QQO z-efmKXZtg50MlT)(eR?RsRVYm}a zzhYXa`toM-dl7I*dc31;&}&sh%hL^3EWr24ODS)Z*JP=eX| zwQ_*$>x#EVVuq&i;m^A4(^*+d#E4RchxE98nk*-seG9Fm>v*)LKByHo&+czFO|>z?V>QW_O6%Zw5x=!H8Dl(*xe0%0F1V0XrNs87~f=)Hqx)K zm`dJ9!3O=y>s3z@qc)oiJHQHKhB6w!7c6gNq{h#mOzoHh_^*M(B>j0*V1!AgoWI0D zG{QAgxM^CTE(O3qMB}A%*xJXs#eBmrX9wblcq`s5x4}>4yS&>Fm`0~Fk4g4odoAhr zgVa1H0qXL{#jDMC30}ZTe%`hdxZ>>Q^LDdP)8qei_4Ci9-HL=W%rAW{yi*RZr?tI; z8f`b!g~r@BD?bAp+p8;iTfO%tFG`ZTZ!E|Ke|Y=9bbma?l(9s~;vYgXo+kyas+jB{ z);W7hQ951c1VBT4l4<@#En^-CpPGr<;)a4=T4b$8u5|8Z#$i(!1IX2zyB>!4hzWnC7X~()svk$Wm z;NuiUg+Sc`u0$SABKuRniuj(!{DJ$=OP3D-u<;$Iq8K_TpueA;n|NL&?r~1#Wmp^E zwd!1Tp6AD0wr(+qJ#6^=Yxp(oqxyufEPw_jH<{;p<1?;0fl3*i-9T>mF9bcvT?HAi zGVodGA1?n($%jpUU(?5J7_R`j`_L4lobu=>(y!Us0(FGOvY7cGHXi9ptbdQN=(cchmIRm3zK}V09?rPQ!BI0gMVzINlLnBOVk;c}i!lhptf0H6=J1s3kTdv7PhB!lwFp{0-+znc2Jh<&W+e(;G={Nyt_ zy!w_>fEnC8m&)}?+uFyBU`@6|)-nqR*~%&sus6%sLe-8LyoHn(|A;C8fH@C(HaX`f zA|omPH!3Qouo(OAbe-pNt3IEMAmm%xF+ThP0sye!AlV1Ud0r!#K&o;UYF{TnI}J@C znGhuM2SBv_vf-T6r$*8z@-!8al7?sX*8&wU-}8QOz4ztrIcv~(AO{F2krXb0)nJ>6 zxhxA)7RC;ffYEJzSo&Pa9q`b*klPO4^g~M$8;v0U*g>i^Rvr^GI0u9`jvccIAE$n; z4uf%i{`NPfIRd}XYv8lV+S`P1r%4Up+nTB|2d!%OXdU8C^9Ev{81s=Dpbu~F*xC1G zcP(zOqcnzYPqQ#WxRTo==UK z+K)Aut`&%VSM^&sn#$49)FWjAr);<@WZck4Y4zX*_lQ88j&v|(qt(Yj{o`1>(m@Vq zkBz_eSQ}$jy*{2*y0p2GN)+hdaCTZ04_sEi#aEuwOv3|hb_pr=Dk>JO)$v6&q;T*wqr93hc!W2fY zHC7*LyZ^!sWv~r#rfS{@wXHjMRjX!pOmPcnumfjGEpylAe*M#&ES8()ZbQe164Rv7 zR0j)u-&Rx#xHJ+YI+LmDD1R2@0_rMoRDUmDqf$y?%hZs5NHtk-$n#g+60;4J1@hbG zo~&L2ug}M)nhFWo2|UMUK>#~=;!mwjx6KG93F3!=;?sqsg9xUaBck=(s+Ln$!Rm+N*gmyig0hH!JFd%4lK7>5k{Lob$`4-Hr#Hf-Tn@di=aHZTMnv553T!LZ$KB z>bi>K*3E!3`TEULnlo#DyZ+?>vOd7lpG!vkF+TS-wnESQVPpqZ%t?E!dH7V+w`o6J z7rT{{9W$=+%KyE$4m!AS;{g$%^t+fRpJFMTv^>oeWQ8&JNfxKX@z)pWeKfrWGP8rm zB$9AOU=ng%EH1BK?O{%UI9He~W<0AwsSzZOgcUls9sS{9%e-dCJV(U#dII!q4JY~! zl0NmCB*u@>69*ioND52XO1qwD4AWB32#93wBNX-D9fI;ZD_K@SIOG_s%d)-v;?ET! zIjiur^C+|MD~~E+RB?yBlHZSB0Un|I++;s*l~%iDNVhDZF$kxIHmU$N_(qovJMVb_ zH0(;imay)MrsIeQMVoL}`QrtPd!e0~M-duS+RjyvM;JTrz!_^ALU9F4dW;?S@w|y{RkbsT0vPq&B<3P$3jFTH=OzJJo7*^0lTH z^rZVq29*|Bb6k571LEc?WHyqu+jYM{bxe5^??EdvGH$i5*P1hrBwi4MQJ`DVb3>R9 zcl*rB@&dm&3W%0Jt>y3B;tyV-<%gm9tGc#^_njj=ZJis>ZsvJkpK75V)ohH~I_$Q;vJhW&dU%=nuwGuxCRM)OM_q39Gk=GcW)gkv zXYR+>`R1`&jQZ$g@BN@U`E_|pZY?UwU)9^i^!9U5J0|WS96|{on0*f8i=I5Pd$Z8L z+d}7QrP}U;UrmDu-k)`7w!T)xNtD(wTM*^F|Kdg9$7srrxxu~_xxXI=m>zBD158b( zvq5%(*l52^k-OE7p4W|zs9B7+oI%E>?AkcDT?Ckq(G9eHRef4bRAyq8>LOjUz z74tC|>Ty4La=7(G!^b`rg(XOSYM|+*Y(kZy7}2SOpZH60NL|4fJAq?D?KBeAs6?k8 z75wSi@kHVm7N8jKgDF%egtJ95u_VRJy{ot^>DkUybGb@z9{SltA6vriYvHS2j`8H) zm!YWx3)|XNpuFMNGVhjNe#`2n#RLUl#3qsvBYv@KTYA9wwpLrxP1w;}A>L zw6xWRCww#PWniH0J2;0T@>+xq!cgG9w5uZh67ed}~P*x)?=MRV*Kl)r3)#^)Ae`le43P zQe{=*^TLy>jIt3K*JGjg(VkF3Zp)3$^l0Gqb)f<;PzT zXC>i1O60K|v=)*&PMyfhoKGIv#$>};PT{-88hN47<7I!HMG2rk zzL<~`WdKm~Gxx5Q%IMOy+EXOH%V~neFC`p)Lr1RCLBVSc(oY_ zOYu$A@BXkl7G{Q-7LDG}eX#M8o`*zmX2vL6ur7J>YB%=x+RsbE$iMO^ie;pw?}Wst z@q_a250!)TEY$zbVec_XdFn4%BEpj!BABF zCbN+pQ=BcU&1eFOd+o5@<4D3tz(_(3X;SeU(`Nkv&1y4Wsze-Y*SZ9&?Plmz7~cCeliyH4g0chCM)LxcH=hZJ2oINC^m_O zB=dQ1U`{H9V@Nxn9r3jHmO6`=*{Xah7G zec;*C4GI!GZENL02hjea0OB4wOz>-Z!|)|esxH&2g%8&XGUp{kA+*=O z$dnCS`VvEqc@||M{79)$&v#FtQX$GP#xZ78<&8qYBFvOh+x>8q?&~anFL*?H-f5}j zjC3~Gjp#2~ACEBka~FvgtC9Kutg?OHs3$}4@&pdWvX}10*XbUMoanPpqz!tV61)=n zc)cCmh9IBnA>i{~>#+?8u;8T*u=al&x|Af<%I!Dve~NCaw>%K@){f*I0m?mpCSLlS z^aizXw!PkNxB1I>Kl{H@|12sh!mMt24~=GU#kOm>&x8q1kwi3$jD9gDQEeKBU=N^7 zA*v>bb$h6eEMUh8BZ0chOzbyz41a;n{QZ>9pFmqP6ay&5g|UWI<;t+hXVL0f0~+v3?C3tJ&1Js9(e}o!$C0f|_p+dizd2e=gTwTvTmo^4 z)4Th^&bQz7-4g^$Z(14ow|)CJN(RwCns4gRz5EZFSWNEL=*2@v_aDxjg|j~HmUErE zD~>hfYRFz*CsZ9LS8meYdUb`mXplN32X8{3@3d%ano@6N?9_^;I+dZ7?lV7^deY_a z$k>?(s?Vh`K%K#u)MM`dcBGJk>G6YMU`2Dlqe*AeJbiD3?ERHvsAhHc8O99EiCP;-jde*2tCv*IZAe9Wm-ORm-+*>;wY6$PcC&i`yr|gdV9F4hWT;dO37OQ5 z({J66zCl4Xr$)a-9%brfgi+eQZG7{)T>YhYt~dSCHI02(A#K*W^}wyXq1{w;*~}Q$ z!&X1Jney=1A=${$L}aL^;OwOb7f;& zE*&bORv9dH+qhESJ?hFeo5j58J1nZ1dnA;l>GVYoqoPI1(uw{tJwtwr*P|`pkAQ^r zpf;=J+0Drs{?4GKO3uuzd0Thx!?*!FGh}bFT2xLOF$%Bsm>6}Zq2YposmMi6Ax=wwByvNqOcaQ)eMPw{2*r|?*9!y;xENS<8Ei}6|6iiM^yAJOk zy=#8rn|@$4>p9DcaUzzu#*w(j9oR&{Lk!@&)zfUK4 zNp+H1`*CY{@P#ruU<-Q4?^C0wCM&va8leIwOI~hhdW?PLUw*Z}4wqP3U z(fO83*oJ@)Fqsz62u8`Ue3vNNm^`Kexw+r=olUpLcmwxt5~ojuPjRo_=Wh{?lrEs> zkqYMDwSK(pAUwqBfjWe4f57CSp`xmWfWzkTy$13bAQ^1L2`ZF5Yay$((1zxWZ4i!x z=qx6VF_P9T$hDYb`g4}lMre8S$^xGbb@BI4a8yWKw!2+Q1{RW?V1avsZ1cs=maRwA zl0Y_?V3{RAuyw6^;VMBOCGJVdwmPl)@#d)r&?mnu*(h1bNl*zS9dx|7w`(~Wi9%(#?>}0 z`YhEpdhi7XJqN-{8zs%mDEC=&Z}wplK*SZzALXE;yX9ibK23#F!}dQ72!0etU_vO~ z0|S~Z9gDM7OA6?1(G>0@*qaFf!XXYs#dECEB}$xJTG~{f&RUgNRPSQf?PReXD#Ck@hHGV0{U7mRg9q-opt%(Z{kZE!K7drlw`4N*Kp9`w6Z$dr`v@ah=z?QSKwO({kX zy2~t8bc$;Kir3zV;6f;{G;~=~>-IRE<>qIVG*VgKO7w))IhI{|t4EQLBSttdYc8Z_ zdMo)|OhC<>kA*yscOf}2FidpQU8dq_b9CYBJtuwI8%Yj>ngy8nkNlTasT@*&CV+{( zY)_UlSmmihFa!~oB)^ck>OOFwNSj>02^wtWr7o#0QV`k`O1?Vrg}F2xc;4 zO8}CAt!E2sA{cCMVallcouW{uW2ITJW8aJ5 z$eNH*zkf=Zs#Qa3*{c5t%{G`R8FqA2xMi{>c>u1Cf-%}u=T2yPyz!utk_tOCSqM_A za=n#Vhj2%xidK_P0>01ovTs-?){HbAzA@1W!Dw74=oUk zKdloxN(%Z@kuLDq3}32-oTq;TRBt-(3fGi0-osOOAf>IcwiLYXIoNY|(2>SqJM72| zh$1r6qO%sR1~x9JYRx>Bhm;P5YMwK&)L6GrB zS7PfemTQm_VlLXX#Aw2Q)2Z+rLI*MPPZI0=jF~HhZT8N8WYVGq(U_3T6f5Zb64wm5 z+2H)`%o+8)X$$B9#?8)z;>oZAj>d{x(gc|H!s!+QIig% zqv0UJLUXx(pP?2OOl@R;K5i0t=h%ALoF(17UYGB;wrno&UHWSfiu$^MVpXau0ftC0 zd}Vmgl%&h31m641L2(3Qjm`5OnO2Nysl;2rTZX?)vM^hkz?1W+dgp+W_Fs83mSK@P ztuopNzB$w(6za$=AztY?!3o=O`lJ6!r(YDmP=On!5Iv|^gJ&A(ku-RYV5j)#8)D0S z^8~#P>G?RrO{iR8`t9TXc9Da^bDGp|pk0M~>wRmrtC!EY9nruukz9ZphS*lon$%Ke zMQ1H|M_UV&yHaW?Fy;ytHlm#M*bn8bwwSU94QvUYv$S*pt@P87lufxKzPC7wMr%|y z>dxz!ODY&u$ADbuvbB>i@SJobwVDh}B=6*{q2xtlvyDh}6_wmD-*qw?Rj$iLTe0iL z^zV4*ak)<+MP8N8-^)JYzf1JSFN!@&j&++#f-o=FDMo)BbOxY_@+tMtN7utnKLQ4j z%6%i{%NKkiNF`Yj49MB;>vw8o@uw!@gY!Sd^fwjmU#NBQnKHfTXJQv=bn^^u=W^RG zLALX^ia|!bfp1NPZ+|YA|9kGA*)J}XJr@9cjH&e_hkuw09_Bkiv)yzR&ol~3D^`kN zuG{TpfF>n|$L<7H470^RPVb;<$b|&?&c@H~^=mV8idl-)P9PJnyqoTV%I&lLKCVK2 zG7-PK1|2d&{aHGbRQWn~SpUwN?%WJ>{G0<1ae_>V_K!t7XiP*)Jv^T+r{e7cy# zRomMakQrpAnEsNGXC8WVIYW#VaX!>sn>Tib%(=@N{Wsy-LG9a2Yr~(?j+{v(a-kDo z!dJOhBn>amfve_$N#1v*Yjgqoke`pCO%hG449wz7tsOZvI`YhYcr~%3K=FaUrk6Sx zBRQcOB3J0QKkW(%IxRU2HGcB)8E{R1V{70UB-4Q8E}GoOlAR=8o+NG;vv)Z;{h_>{ zB-LYU=$z!;$4ww2oO_(pL`YOrIkHr{ z_KuPAI&3yw&yKF{tYH^yO}LZx3U~5#G%n_5+!7VL5dund05;!~=!%IiumO@Eq>cJa zy_v|&`m%3*i%lPgUr|_l4;nbRVLepOz{;%J=Ot!`ijOMJId&))K{ zY*#gZhuz^_Tk+OdzJOY4#7Phc$>vY@Eym~?WxH#(F-ANq=W^33WI{K}E+9+wk2C)h zx+v^0QCZ5bZl&J5?o++#^m9FFa{Do%_i3ux5i}Jv?Stp9|BE32&aS2Ah$j(He;*&^ zmn1W&E4wlck?h z+^3Y5zhXF(X2k>)SXs~T6S?djbzYglN!va(QfDW3rOwDemT9LTZbB4Jr;i+wEz?MO zcxmZC-RpqrOT1B~#^(EQ>3iIN#xYeW5W_%|4Nwejz_KnVdwDe(A=vfn9&XmApIL4Qp zxf)~q=g)9ar4rHolil|TfA>xPtnfAl1$nBiN+ht1BozoO73fQ}y`cw~JMglhca=`ssCBZrk@f@f>zBUPz(S!B!S5_k@+5J8 z^0W~5KWQUXT#5!HG=-dEU`r&YQ^0ByrgWhE<{6E*hLh0Z(h3#)+UxeuekjGP++%=*rkKs7%F=gw-G~xKp`FiW3v*B$GE&l?Y=i@d zm7jj9dH7QPWl(+~MK#{nmFdk1^Osqyd&N6meT)BVOOpm$=JySUv6i0&feHkb-pGIy zJn|sq>QQ+a%IF62EM)`Cua#p$A}*S|fI4Fp^zw-x zth`(hZ|(nER|0a!e(t};LR3b?7Pal-j#4^Y?U8>&r$ic#u*n%|)UTy$swpeb{juyQ z&6oPmjrmV9`x+WCIt|pcvWBw=PEPQT%jmz#8v@u)fO%NE=nsr`6Cv0w&j$y3^K+mu zG?bHD7=ADNR6&_Yj1u?n1>XKLcHt;523^fI|2CpNzDs8kJ@ew=qYLt((Qn8!plkQZ z!kNJ`NQ={JCaF-Fxy8mlNG=gAQ!@L7YXH$N$oRHBNi1O~xA@b~GdaOea-4*oMjQb; z&B2KH6yT=(_}yM;+7{+<4uii}!gJYOEzYK$_;>Zzr>h1pUJI&D5BVJJ&FTWXW8tkK zv6D^kF`=g84#*iD0-QeEw>Dpp!|;bLd(GO1_8I@o3Dv~FBc}6znton~=Jkt^koULy+NdEF1K3FxF3CDLxHH@b(Os5$OciZVi_QB--;rdtvckGDe*Z6v6#TACm z>2uH2=G!4h3(9ZZe&?^tNAqJvX=}d}4;=)csG!5(%!sg+%o>0$E48Tu!YE@DeKUj+ zb~H(e{DXW&DFl4ARN~cbu&s4smK6tvc@-saKNWBxu*mLC(yv7l@4Utr0!2{0{*{ao z8i>iv(X#*$N1LpX3kzNCBJ}^_>z$$_`@(nKiruko+jhrJ$F|cQTOHfBZ5th172CG8 z^E>}>&KY}O?7CT_u2x;FHEPcJJ@4~AtqPSu1-tD{&aQ%ty3$WNZukx3bb(IEtU7d2 z2gxW47m4S+UV1YmK(Lc%I+1|N&@zxO$6#9BsSL%mZE|0B5X=K7f|q&~;`u&R4~qTS z!$>-)YjccIBSEsUYm3;eA9x0e>*<`8OFxjbkNm~H!Ut({@wO}5lew(r_nnbnxPMp% z$2`5oKq)XkI)prD?|a!x48lcmy6qYKv&biu8NZe7eZdMOWV=4#B8b7I?jQD?79xvc zwte4u(&NcDGamJKOzL%VhVY@5`I;h$)yL!@*NiR2mq-&KlR;Uj`9c_dyrz15Sh{g@ z7v1>7XEYD?a8Y5NGp!~mI*f$U3SscEd1dUW2W5kkP`vJ#qrNYN>#MBOs?^nIO05Kd zDo%%;)G2I|YyL?b=pWg9Akwmov&~c6!R@S~fA_~e8Ye>+K5GF-H})^>Uvj^61O7JP z?{LiW5&JsxEpUBnaV;cE&Bot$1eD%BpoNy5(sf#tf#hD!rtajN95KR~vFpy658bPs z;Z?CDIxMplXRP6ha3?mfF>(%bKjF*YCP7s&IAQ75MyaTq{8UX>j@<1!%4K|0U92(S z?bc`IIQcd3%2pe~$Sj8SL9@H|&(s2;Ys;$63)DdU0E^LLLV+j&>nzvP$(i$h`&m2FY^KzpPvLRr>{fQz)gVEzb0Shc2C#6fc%42j1rquLYF5Y4j?0`-K zc-xEeK1)A;ov`3mo`!^s8dPC}-!4d~*K}h=4)-q5N3GF+TdU~oyPkv^O@y1J^dm|k z%IEx&mKnkHjVi`qlqtu9={-+o{8evDl9F=E$_<_Dg_AgSjC>5Zwfa>vyvSCG(?Ker z*5r{`8(*7@RNSvi^t<0z>F*fc{;jDKFuDK^x(U5^uIzH0Z`K%m#`g6I@#vm5Jzn&E z9IwV&e9oID*Sg=6JX3TYhZ!{&#J-oF*8;-Im%R00he=Q+ThwAz!4K)b?e2nXFcW1o zW%+*tHwO@>6CHW_5s94Sp8DjIM;KY^o&PTLP(_{B{uoAoVZaT&GaDWG)~XXi~4*E$^Pqn^)vhzEG@)k(@k)A(;@t6E|jK z-#Dj`f)EH`L?FOpLf5lyb=;m!A=HiKyQzYQMGB0Ud3 z0?42;g5dC)2_?k*iM}mxtMF?b)ra@R>>GuQBaNSun_q`2@sG_?wPt)aYTgJ)>iw%5 z=!`Sr1IFp7?xY2bgT(d@MDwcPQ}jT$UJ|X9h%Rm0`hKpzGV<(w69N$E4$3$&DeS$8 ze&xo8U<#k*n2E|}B&4!nGy9K3$1AsM)S89RtMqlJxD}a+<*N%=90(M@U)haSXo7$I zPVD|L%$bWJ zLi~8P7w{P%b<}$_zw(@lJP+#)6BYbgV)XGIpO6uBS_!v8sj!JEv#esC(Z<`j`#7@` zJmR0uP7`)@lISd$bogiU1qAkWy#WlS*3$sBN3-4lCR^b4eG$UQ?H^~Ye^tY2O3H-} zPPjUZ#FEph-zAaC@N#lo`pV?E&ey8A2VAF#Nzf2LiTbx1y%yIeV_we^eYf4a3tlXN zI&UY_4lG3+-bU;Y0ngp4iN3#$5qkCJRHbF7kBs4^W=_Z%H{(c7YSFLLgF^PON+>7H z{VK+Uigi>JJJjP|Q1_x40Y%xMqUj5u6Pfsxe`7wQ7`TK@RxxSjJFw<4z9~Y4j+4Pn z>$Tar_>!Qq6URz}PEq=Rhx56#gM>MY(q7dTDWrbM3f-%WpJn~5BzwXJ6A#H@Od19W zfCXs-LRh!cgWg;GOppMMnnsMD^0uU8NU*~4byWx}EX3;=N<^SApkz`c<6YKsJhU0;s@cXZD7h+W|DJ%vIW+&+j5=on&WeD7b6V2;_9Y&J1Fi!0w71jhfNMW$ z0Ce7_BdF9cgI0iZ-%krJzTPdAt}?u}4#zJh`nQAQF)-H+2VY!_&U;O`j9Ns%_Kd>k ziFJg)b#gk$~h4vk9Q0NieXW&*aE zrz@e?bWskd-+0d>2%t8`Jc~;oSV%WSPZfejCaQPi=q>-F%52I5k_Ntf-6xXKRE{^{ zCy&Tc_6DC$Mq?8-XVc@Q&$;9o72uqw-E;H4O+vjnM1ihUsyBVB>)fLXANuhqzoCi< zgs3gqtN2L-7E^sm9ly$F8}>tBz33ErhK=VyxL{FGWEfn5wsd}~S&^f9)CXZ5s_luQ zHoz09w*XbY6F;DvWc>#nD+7G+nxosQ25mBfQzKPn?1Gkz)q)n98sTV`_xZe=(pJ^j zljcv!hDf{|37H3~T)$m%0_ zV0EO$bUX!6SoT{12#FgIu`4|PK9mbHT`j$A(kI|T?ZD1^Gbr|_1vrAH%52aJEw8H= zCFT%tRM`zx|LqwBUX!GFQH1uQ!~KR)$*4n=gop0Iyp754!z zb2gvtx7r<#nB=wY?^ASc!yC*vk#4&LJ9a9zTKD4ODr-s_pBnh;Pk7b0eyt1_{TiPw&TcLs72Q^-kiC10+(RJu4 z-sgzw4+I}CTfXA1Q?NF9mm4r z$s@J+vowL_=|P}9^GFC0+!EE$;DWD~7IXYeu?l0>ieVNDBIRbG%J24!kmDX>dw88o z?kT_;olDP<-jlF5XeJ3Db2aC*6zP4N#)=I=V>$?zPPQEsOMrcYXKzP}}ilJ0$u zsZW^5*q1X=oW!7&jjVW8uW$!Z#P?RRsH84J%fDY->`kM`{Jh+gOh883kniSV0kxAY zI1vySaokL3>;AQI4}xGR=Wc8kZ7&UGgHszkF_)OJS#q*je&rZqKpZ$G!A>#L`(Z>X zYbp1d8y*(vs8*p1F(S!=M6pfBDa;ypOc@#!XB3YdgG0gG)&yrIrXX;d7dOf2^|{I$ z(tsU-F_wk6<@12~`}M2c?PiDYeSXoE4>kdVAxHbt%Rr1Z`OW7UQUCQ){xqk>U@z?8E&&2yRVOE)*{n)62F3(IRYl9Mj&+iSOHz^pL0(YKp!x6o}!~Q1k zrH|Xj<>S~(Oy!z5(_LAKJZsUd*VSK7kYajmE`tMGZ<*xqi?z=^YeB6~E!TkkosQ3g z@C=To49Db5rp}MPwd!}HyN@f+N0k)zD~+d_VE&7wJHn0HhCqK6waLn*w^wrp?It$f z_w5f}yRVir1-(z;{5>3__ZYQG`ux#T|H$Dp)zt1$9k=VCjYf;{8tH&j|97e@g8X9DFK8XiM z7EI-@RuCg=zkf*jU+s*jVgAvvHU;gDs=5l-2b0vz0!&A3EJ!`!U)?d=u5zlYcpkFJ zggmF5Lw}cWe`+Y%*8^|C^)LlTMhv`2mf3(AE^0xqFnegrtE{}Ujnk@~r=Dy-QAnN( zWlDL7Hl>bEAEnJESWqMB6M@+tw%EdysKW)1b;NSy5cpd@VhI>viFm0Vg=N0df!q}$ z779>B^hDFY`zX1<491QfjrJ+In*twP4bY)Bdao{vg}NvF%P?ecP!SCI3TJ+*P)Tal zEPbCocWo*nBJfoq`&+@I<||Hem}(9w9j;z)47;m!25j0IFQy+0Nte5Z?DmpR*+JHu z`66;KaL6h9`Kx=OWWZjypEK!;nebG6kTF%!bU4P^`j@fa!uc?5%QZz)Ez&{Y^Xx7r zSBT7cR2s0|1ENi2Dl0)h<>G7AB(3E4_+8#Ja=dJK>K~drLJa59TY9b*WyYhvZo?Qi z?(PWr?srFHHa@6&*He1Vbf>dDwv&5aBkV80{C4YdKHMmG^3}VZbgiKfy}nq#o{DV+ zUkCjg&}TBgI+uF9Uy6IaMt-fCXFavI@LM0R#`s>Ed$!$#Y!8Ze�FDI@f>Juoq`&~HYXATR|3N;dZf7Y7z<4lxv*T*hYr0@yr3M_v)X9^OHq9c9>#N?JmR5VWkN|nwW{wI^r_$XD4@aBUGtHp$*N_`mrB0H}& zKX05*u~0_JE?3m30Ui}jwTr<(gb&OQa2~X0s=DB~2x*7V{vcoN6=vMAHsQ7$$a}NC zVCN}ym)EhHh4^BZ3p4Y7W=z4$3r=U&wSCj&W!S|=d$3sp{taYsk8%eQF_ zEB`S`8Z}V37X>xV;?CDu3JHtRHXIuWr)D_+vtY&M+r?`3-}zNKY=)U;6!cg=RXB>0 zB=vYZT?EO$;$x3$>i7t7Q*T!^3pc}R(fiuCyUiGtM9@|C(mNNXijdk%VStb5FS;y~ z<-|at=r9%F>#vXJU#bVF2XY|7DkTfTeVQwF2VX?#Tk&MnlzNiH(munNHGDN;+dmLp z`q53w`HS4nJ5R1Ju6m9Op3((3JZIqm0D}h!ds(z62}A;FkYa}HSwJEyrhJemf%p5& z$Vi@&-)bW_SSC4j$Ri@i{dC3}BM~m2p&BXy{wn8wdtoiJdo4(8%t7LV+!+|x49)&= z-vD{tL=;gj5zmTKQ6KOYTY|4MyYTOHI zCyd8(R&+0pvA$gICsE^%y@lrR(*Hv)*(=77e@cVXpxXmxmliA%9Nj@x; zq^D7!&4CY5aGacsc*^zbr*9d%!KIM^$#gT!-!jk=PhKz{YLL zenD8wTqY6+&|w|(r!J78|E{&*WBi4vswquPPvk_4XWhV2ce@HZa*vy4D?#KuPobcU zLgWt^_#JOV>#cq-tsCi1!8>ZAJ<@gv5~?q6o^{&v+@Kr#rrlUpJZGj(bXxAc5uHwB z6iSCmVq6=^*Sr!aVQFs^3&L75fo7w^;iy-Stdge_9I40^Zx%3(hSJh}+#BuEd-JIt zDoS$>arjlYt`@6&go(s*spNaI5Mt6f3!SE7N%>=r3^4;BU?fg?J%$#@Ct4Xk8>t|3 z%UgGzcNZo%rLIO?XbuH3l$jckC0NtCjN8e|j@xCptB`}maiM>Aa^)rQcj4x~xJw0! z)$M-!(YvYv@?bLr5oCc<;pA-k4M4Efa3JIp-q1J-X$B9#b2E90)nR$Lo*LEyB$&G$ zquVS8W)*otz9Hv6eeX5jB3GONfLT`SaxSfDz|Y{J^3|^lxM^PV@7AN2m7c91OnU(h zN3DB9heG<0Os~(Sfl}}}92k6GPtzS|j)ETRM1%g=V1Sq_&tro+qp6XCj%dLBG#1jb z>+UN0bQ|)19(B$symEO}wmBf+Y(Htft?#F1)W~(s1H9uHv!GLW5K_ySP zk{DoRiX5QG?9>XuWb2@?wAaYnue49rpr+KUb;10Q<@)(T4!CZM(M14MJ!%Nkr!|FV z@))ZutzYsap|ws-fPK0Ka4)ph0GYxCg`xdPM3Dw9vahgo-G0koG1xc9A@J1aJ3C1c zpQYC`^Ci5Y_u`ZHxs+aO@fMYvvp}c%0#f^rDTO zV}|Tg7pE$a%Gz&iyuV#YDneSr7{!8+Kr|*k5gf%ov0c;3m`c8cw}uvmOjT2r2)TaB zO@U|os8K7@jLz?)BbM!>#+O05D)-s&lo#tnZT130X+f60N6miW^r2F1+NxZS7!U^_ z1Bp+JPvowAS$f5=xT9}D{Ih~CB1x9Wppt;ceDZ*sSLCiqi>zX2b&h#cyoYh-{UR+w z2AD9U6^N1rH(6WhT;^r5BmwvLRXOjK{u~|=Edu$x^CO}T>y+bbKGmRYWxqY5O0S0f zK5i>`d`PI7X}c&3NaKj}ROaliZ!o-+M3CiPi~a@q3r6NpmG&q>pYBrov9jdRzWc01 z-Rm{Z-C=2p8O!a}UB;tiO5o|=SF7DwmG9e0Nb(Q7^%CEg^9JBl&p|Q%lJ8-SFUQGD z^so>e&r{hv>++l>^M(FnWYQ!(F7WHE2`Xjkgg$r`PVYrx{B$Kh4Yb+jc@?v}HP?Ro zUR@vUrnHIMI;Z0qct${y+VW`G@NBqL!k7k`@x#uuQoO;VEB`efQ^)I7_v?2I%5eB7 zZBED>E&PCl0Cd3V0O!{jn&Rb~jWKWwRnP^R0+2WZ<}n zwn)?v>7df4%w+qhB5a2SB-dy`0#0w{RF2S1D*`zpzYk5?FvVS0vMqsv^kQg0V;^vS z$2VCfN9i?q(w0Wx$J=ypaEOaS`ctO(QJMZ~Hcbq}ct~<1{SwUfzFYB)J{OdzXnMF` zf&+k!Zj-mhi9m~hjs zABqr^n8_2O4>L@Vk8ExxRSgZGp;|g^@)(kS&OB)*65&q7pc@SnRVK_keAFhl_K&9< zpU`5s1+qyvu^=kt@kVLBEMaq&jp&-jGlqftBXA{6>1dB1z9k4A@!mtDsO?R&6lKBsf8*2BQyrhI0vzBZ-!L-~(7 zZ)^vaHm~*1TI@EVG`AwjBcLEm8nPck?6KQkhX`#pZ#2ALslOk$QC2gPYqz7NoW|EV zL63u|CEu${d~HI%)$M%oda}&M)1(@{58AIk(^GO89vJilG7Haxh2)e9At67q?lW0S zJQr*@j0elUftNmDjxDZc6H9L&t=@Y+`C0W=wVuIPn(uY<#V_$z)#!>CNo%dL!_ zn+QH2x9wTe+Wh_8^X*8``eGdiFyVeUIKAcmfylY_XHCuTwXiM1{0a7$`=+Qyui@%- z&6U6Q&sL>n0gE%5(XEQ!XTS58$9S?R_hHOt(+(AzdX7NL8POvCs8k_G{CFMu(S&A~ zS=`8}BsQQ@hgTulUA{^uTFKVrU7^Czz^lKanD~MLg&W1+^dnYi&@R0s*MJcF5R^aWe7UV;0|!I!a|!kCv4^)dao;6 zby1d}fvbaD$&g&}RM|6q7ONDQa0dk6KqbXB@X!ZsJkCpSvJO~!^K5sj=S>3;+hybW@9Su>o0YKN{C<`cY8G+ z0+eMzXhoFpcbr)by?4%D#PBMAR? zeRSFbYDlGu5&=b36(sp|MLd(zM0pA|(v(HNWlXV|beo%5Yz?Su&UH0ElPZ4;wKEXr zE(iH3HA)4{{G%nO7TRqQ_!Gbj_}x1R&elH1<9sDe=3av{P4c zo1wXaTKRTiw2h1W9BzmygYNw4Tz=)cUC3@9?iUyk*u`I-ZM#9@PVbZ?EafeaO0t&}u^S?G>@wyX)i5TF|}CTcqwtV#&vPZ!?7RGKBg_ z*KO56NDO#bz`1U_7#~+~ zLULj=xeUrYtW1_%2XJyjNECpykiVwrBN7`KdPB)Hra0wh*Q~`d^cx_RLa_`fKuRS| zCF?AD3>I&B6KlOtJIm}|K4*pVL-Or-0b4~vUzwNBIZ|~pt?F`u#808)le5bU#eudP z5r>(bUdx!&{^1~Bz#POv(Z5QSr#f_UL&tBV<6x9q)g60f#|YBr5o0iBPZgclS6h=t zb)*@-g&t*G95&`B92P_zo{XtU z8Z3~jInw?IC^Bd&JcuXpGCL^I#(x%N?w)96WzA&MJVxQQ_CHDRXMb6eQ9!Cpu;jqK->;VdMhR%)giD+t+cyX!Hs?zr*-{TpD9X^P1 z1Xa0Pml7O2&tEN`IyFy%jC;AKuyug~Momzp4(E0bJvhox=sZwgyeBPB9Wwy=|06cg zip@`)(e{XL?eiSOd)fZA&3!b<^}{ID;{Q(#{Oh=g-g@}n<6-=$)N`HJ{jPx)1re*G zCi>q~1LaG&(palXj8yM>o@>SXIuamt0`UlTRzGZ>+&=pb3(Y&XHQ$Q)1%B@);uW$o zx8!q#R*4ej~>uWXDzZ5QLY!vNvfV>I^MvE752C7EG~>cX#ZN}PKW(!9xKVu z=0hxNg+9J3M#JO*5z4L5)KUlvA0#Sd=>5s_%JQwx_rEAw^jeUe2q;=^!$+)HS{ug5 za9~+%5=+u6>!E{t%S7AVN&Z61HY~Y`tN|Z9`uPMWMMg#cfcaqi_rmv@jyBLm00Lm# z67+d`Ie(cwZ->qYG0lO7JvpYj`&iKw<{Wk%KiDKgEn}wDU=s#CSl9eV#lKUi)$)dr0au7a!b2v4(-P0oen$ zjP|D1eS@0f>h<$Vs>bapCtHxo{PZRcG5n)K@2L;*9J8U=si}A)uD@7RbU?-6Wcz+F z>-ZPi_m`-jB}iKy1;}&7$Q)6Qv6{Fr0HM8`)$Jj(D^kOX`C0Ur*#m9>d@q{zKZVx~ z&HAdbJKT5 z7NZT=$os#Gp&B2JqF&JmTd)}A24$t?f}nsU1@I-wE;qU1C^JJ`JjdCV1J6tOG5Y&1 zhn}VSnz}L)Ic{SdNBU8U*IZ=!@QWWv#4L`)#vNe$b8Zo^5j5v$j(H z1=~@Oye;ci|A63DVRr;LS;`>Tx`A)MbRq;El zTqH1-B`8Sxie`hd_;$El2gdl(X}y5rQUEinwE9o6KunaSBku4#?il3Z#HC*HrDT9S zvB&@O$%ao|bMh(7=JY7Wjn@$r5CWI=BrHR;u{~C$WW6nOu+U_#Zv$t_@``z)I4S zYt;v1scw7{bz&-*ozHdDn|(B-hS;MZWeyD#R&=0niV-V}#1)DBjz=@6 zi4*dOq)X{_2`-_gLd7EcGhz`PsamH;k}M)gn?UC@pgGE_5QUFXszwDt{@09FA`}It zR`=rYG0qN(Qf@IL6xI^oq{7t{eVZD42cxBn^?lzPcJwKjGPhg-_BXv8orzSbobHl3 z(o!N{Z{eHv>1AcGt5B}VZYUG7!BQO6#Wg9$O-P$&SRw6_;mS>RRcA=s>~O22G3NiU zhybC66*1Lrr6HEFS4r$GLgW2nQE#bC zunaMHv9NEO3mp`gtXy7#QkKmQxEuqhwX1T)g$gGQ&K=}$5ULN1Cm@hLV)j3DjHYn1NZWcnl4Z? znl5#Ib(R!b$WhdSf`2^FwndpNk4}bKD!HC6mnxU4mQGB`#9fKDkP432R4x6`cJ0vA zBS*@Aw*FcxFFb!lcesUkDvo#*O_AtUl7$7`%Pv`FtYV@}0sxT23JU-IV0)s7-|9@z*|^A9J)QJP7Gi_cJpNsLVzNl` zZSRDrz>9QYXGt%w=-9_rDWMa7me5`CDINq9XX`~mSz#;nIG$-^wMo2ZCzE)U5*6vYxQ89_rIkyqUlQGqxRFxD_@;C#X`Iu~l zp_4$KPE@=8oFB^7Gp!lwxqem`M)Uu%#kMxEB-^8nQi-Q8;wEr(;dq2!o0|xNJ-9Hz z#dthVfh847*qU0=3@IUg~S-=|*|vFa3fO)rhdY#}^LipUAZ&;gH3O zlbUM8s-*^`s3b~eH0P4SqBi*v;E(cDj;#Z|FA<^fTlZxy`!F_^LDo&Y=!Jnuqe8K0 z<}gTuzJQ2t0k@@+<+m>cLhNXIoa1}}JL&dr>)<~awjB&WG|tkpa&YidcS#idctf9X zeRHix`>YOAPOsK?zZa{~EQ`Z_T1Emy2nNMng`d0^p_NLh0<7xT=NgkL1N;O$AzL3N z4zZDMupEs46I6lWc<95HEG~Q|a4Q2btYiSUx$EFTn^9&juXMGv`_Id*!Uo?{MvdpQ z9Ok9FR7j4;mgQBu`PlSU#{-x-0e8gglz?6YS#zJEhDo1CMr86r`-TT7oO!fC4A2RP zWM7Vmlbzb$$mVh$-x7nxyU^|qrIB23`?F#Z2N&16X{hndQnNNx)qD+2h^v|0kPnyC zmgv^hsm8JbY~SNN!HsAW9|G{ba06SR@Gy8Vho7lfDvi{+nK&0~iiv?i#E`GBX+4p?q>+?my1;=Hh-e+ zXq%OzOYCK<%knf~$+ddTw&4%6u9(Q{{I(L@CH}YqKU0rz!9n;dkl(4kcxq9c()+Ik zjH4=Fe9yh?G()(>C(y#%6Afr@p1C`r8wvyuQYqYIl>M{j!(742u~BO{fU0?M+4J>z z8Nc-%48mo$YDyn-2VcvC&F#1HGnmUhY=nBt2;tW*U4b*tdFnqxn8d1hVn^254Tq9t zCL-ce9-JZ`PdXD!J@km-Cf)BM_KTxs6PwSszNdud<)lhiOE6JS`fcT@&Q-cIy}bV5x;}xX;ri zoc&w>%c8f#mzoWJJ8Dyzei1YZOaU#?`bo>e^K+g39>x-tddc;>?wJT6B_^zjWhE$l z`UHqjnZcC&GDoU%TtgDcb(CV)Mk~Ta2l9kx35qq`-E(qCO)XF}cO`(L4gJt4Pqe4w z|Lfaeh<3`cBq)S>`#Pk$m%GCnH)IUl8{^u7F-|NxRGJ^jj~9k)z_jqrP+h9w4-A96Htypr5_Xnw8v`iQv5Hil^0xUO2*Cv z5u5vF_vf^^n;P+HQG!pQ>3ghoUC);zDiTWZh^1BF0}NRi z7c>!6{T9XWgO=t^6{ZO)TWPBWeza$(S-w`ls^h)~rzG2S_H$021M z3JvTGdqUREfRd?vB_atubD#`v2`k{Z%Q0{Ys0f!qRWRXVlp=zlDXrNRC0F>oALY0g zRp9T>fj3Zh4Q*H5>`P5{KJm0d7N!Us8S4j!wXUyNsMgifZhtYl(Me0nR|~H+(7QDC z7iS3P8;6^n!i4~gM6PzVod&|aYcGC{|HKB;buw}kk7Ccgj!X|V4Y%;cZq@%2Ih{4b zc;3M%TaC=wwzeY;_r+h9>s;*_UK8z#5fPu$y7~n)`RPS#LYK@A+5*jVf`Xfni~nBE zQ$j@MZyz9U_SBwe1x$RT`N=`caWmkw@vGDIEXmsY1C(g(f7o<)QEA=R{m})Ob!xHy zMte9QxJUd@L1<*5&}4bNpv8PMobEFA*Nr>m7X>AU4k*xQ*k-Vp*VNb-IuOSpT*M+X zqKJkMa3YA=qj)L_e z@U-XiI~ak;iA`9EVExIcZD-u2g)x5F%`Rj^$L6}Z4hkFxR~D2JxJir+X%9wB}U-(z}k zhPa4WguS5%g3MN~$Q};wA5t>69sl zp@gVC26K-E*>h@2ac9OLtwdPi?8Th^b?08u(>$kX@75xxSkw#7N6tXv0_sFSCZl6H z^@(sw9LydS!3HjiM5qbfK&Apim6*R=aM4%ju30Gs4moJSuGsHJFEdffQq_5VTNhw_H2LUFxvfoD%Xgll&^1}bRF4U`>Mug-|) z>vI!0FB5g&vkL@3xR1M&sep$Oao~uU+{-l_M;?f+_F(gP)6&iiZJ32`K(oa>D|sP^w7AUh7eb+ z3lp_y`+1BM&27vylNZk(eir1t=BfU`Mn2ifXwklK`7b1?WvY}Yu7}pfc5*SXlDzyF zQsyww3Hn&+J1At1x3P!u=k;k+~o}|#CmWvvVp{(t8B(9l1ODIJVI1#a= zJF;Y9?(tPaC(of@C2A%7J=sswG2XL}D9sR?DlT$#ns(Mbdl#&Cpd*f&iLSM*3k^9j zXucR40JbFll@yt1?3x1%Ktde&{kDSh%H0UOEH}EHzvcA23x-Vjyyd)ahVg%iZbyI9 z7@zjtE(VidcZWw)_Q5?3AJ=jzUmr1N)4op~dQA2rA=(73cjdI*+%A2d47?Q?*sJ)% zI|8y}-V!doowwWfyg{XlwR)%w3ze}K0S?p=Wl&SAp3ggJ4)P%>>7N(fufj?M^jhK- zzZ!$@;(+Hy&xJ-d!j@x`p!_QsPj~x{-dvXT4-g;;?OkGv6Y>$;p!*fM#V+9R&c?I* z=U-gp@1T>oJK>s>ff~d1L}a#58cm;u`xnNZ|JKuo*OYa9!yAAoB5p+Ke`d-V1vCu! z@@PRwOdwOCfq_@;H@b)4xnUw;4p|W$9ImN;soU&aukxKjUmUHrk4`8rrY??+m3;j| z77#@URtb$e|Mp_KUY5&7Yu|m7AzUYIL?#{x$Q%a$jR5_(P}cdhnn4q8I91aL{}n*h z7#dJWh5|l^6>F&MX#-L*5?crfTi!QfpyD#6Iga)_se~1I5Q(+JRpHO6#wtb_pC}RZ z+o-5{DUFb^^&!PaZ*$+tMR;|uRjrKJpM8KhB3_k6W=PzMq#*?71)&>z`XTQo(@Vc= zWhwl*oOeEPq@KzT_@P5OqtCxgWcj)MerV2DcXEufmE=8R_BjfLqod__!DOjJS!4uV z_z*q(lT+esL=*bt> zpS;jiGDQu^Eartrr?Qo1P?H8C<$os*t=K;!M4%kx8k3ZHMi|DG9ShoC7|oX(=?XDj z^pj0@H2Rsm^-#|Ib`^0Ic@2__&8SSN1F6Pkr8Sc=G7e4SQcUyoHb4~}N!(HKeQgQ$ zw{_K-R*aC=ktj|_mM1E5^@z}LvaO!&tXubYG<0F5J5)?obtF`{c zI+kNr+H#f8%qC%lDKQE>&0?8uPrFcLa=s)*vai5brb%b|mrC$U)^htmUc^Q|V5V;p zEt_rEj8QxDKGmYK2EiV#%5K+@m9zQb?W>FMb-H`IOyytp^X+|&&p^)SjUKakpI98rBfaOPJL}c^+JX|b$nqjl+Q{R)$D>b0?-I@>pcyj}W-I>ab8Hv`|+3^_3 zmEfh~5DeOTi%-u}ij>-%R&Nv2Jj8y7Rw#ks(+;^Gqf?A_;uHms$PTA8sWqbwwIU)@ zGQxOJax}Ej69@WBKFy~ir;`}}Ke}!bb zG$aggSl>tVw&)-E7Fbnp<6V`q<`Zi9yD{pi!qUaJR#B34-Xujb&mF{c!SrG&cPiny zI;N%=pKoEnD8QPtXqwqN---)je72)y{zT||G)P!pYqssxW9UwlVDQEk_KkBvu=iYP zFa@l-<7NF>ICm_xMudF}$&U|($zcCfRL#SW_A6svJ2&uOpf;sZZuhuSkqX;gE?@8> z4~$h#YM8Z>Er?OyPD672C;{JtX41QVZ;fS>`k+|9WXi-gk`m3GCCMc#vsuel?d$!- zh?e_1rOPfy&JNRq#)04c@ln%rlV9WGA?M2;)^?Qqb!Fe}>b9sYcoS^t`gta})&A#c zhePNKrX+{^>H5`q?Z*LF#I)xmu70;wJ=N34F=5a3WK_tipSPnz&$V-nfU6#Agy>n1 z_Xg*e=iVl>-{JlXt^V`SQZ_3oEu#JVBfI|BXmJ-QzvFc4byJPU5R5#-jL&|xT*3c9 zEc>`t-$-~vP6z9^fc(qk#Z|!lU?`jY>UFC|Pnq|5ujl0-Ld?Wl7h=y-XLd-p?*>AP z?J|Gjq|QsHy8i9E>Bq_hYqr4A+Sak=r5A4B@xmdKyukb`R?JLWiW~Q&+a<89ogsC<+&o zDna-CQ+{7ku5mgy&!!5zS8AtD(UR) zb#xXfk-UJZ3s~;P$;Ul|fHAS%`s4N?*x+s-{@D{?LdW}dJFcU;b2lR++;Uuvp0{?V zJL797y^YXk-V!V!g#p`--;-cHB}ZW9cuHvFPbLCQn3XLcmEZGmxW;W*V)N1cO`Wi3 z7atCj9snqBD#Hu0#M9NR?I-)mK)+qK+xf$l@Q+ncv8BoGO*lwZD3+#l)I4+Mj~^Gc z?~#~6D0CvDFLhwf$XE@O(mohbKcjfmOszD&r(cYGPCJDTbDysQ;MswH-#6BHy4eCF zIXWS)l5B+q$60>dT+r49lb@&*iGBZnD;6yvqB)k8%Ep#sO|QC>xfyDK``^&I9k_IS zAsgHU$A)}yVF-au zmoq(=Y-l~9Q5L&YrVstGvegQtbf1AaDm5w0@=O6VvE{<4H%_NI7&*{~U?7m`B+v3{ z#3E7cUc0OYRlZ<&nVC)Hn~|zSsg9}^eL06UPEVF?vSJTO=lT7?e9=;ggk66 zb3o5WP&$uA-c1MjtH+wEt!GDopV8IymnUTyDx=TcnHs0-#(f&CPx}sLOqbD#NRpaL z^f@8qafX29x@h00se(528o}oE_RgJIjc04%i2}Fn>WsI#?U>VXCp zrnep{)QR(EDLIu*HRn2X05RA76P2tbXw6@o4;JgOBc$B1zP7!1;AmixXi6`$PQXI_ z&ab{yv0hg5Kd_2xzK~~QKO;!p#APGiH7L2RDAWqnD%iit*#^yuMLh5pMFkk~ zC=*3z&K0Pj^g=30BT;|i9<^)QPdlD2mT0XD5>*e$0l;+jPl54*w_w0N(E4+CV5#(K0Wqrf zQh9EZY_BJ(Pi0CE8u6<2t$UJ{(5CPHPCkb`_>vD6;Mx7K^!29wswolT5D*-WM;+GA zRmvOPLkve{ZA(2qdDimvkmDWnwMe;jcktwWD;J@zKx=KQ30N2gDTZg|K?$2KSB6BD zwqc2RDd45oeINIU+-7oCkEc=UWTFj~j{lohEu zE1a(!UWYB$qh2uSu37EvGhyFMgAyhDY z?ecQhBX!3j|8eT4@Ot~@XukkzuGlzyJK%=cpF@>GXTFzduc); z>q|$yZ}Z42G9Z`3EkO5=_>}=-@6JHMLF+hE=x9l`Za8oA$I+5&lfj|8`BZh-aLGLg zpTI$;jGkjVOC-w2-7C`maUQZ?_Gp(TCY1B=4QF_!36N$?t%AR}`)*3G2OJ>qR969# zyGTG=O5UIrr*ecClrp)yRLDcN8HD4m{QwiF*rz(;LpPLYdC96(${WkPiNdl2vvKzC zDi!3oR<#j+c*Wa7+5k%iIaQoIy`IhQC~0gao3jmSvI?n*(XTF@M2#c4_^17a6dZ@f zk#`@?HMQ;>;e(;OQ=vL+!{cgMgzA4gohLT|?En_#Z^#bj}{Tdk6L(DzzsO%oiQ)IblU zR(Waa`hMxSi;)G~ub`vZ#t!%tUG55WoV)7UdC#-%{^||xAUI>bq-o+d&tgAoz7lxV zUs|vA-a%vLS#Nl(A5UH-P3<&rL3q4c@hRmptrp;3>%MuJ-XsA4(j)X=+ZXXNtNHBR zZP$tm$R`A!CepA&sVjhVFEO~yU-#|Su8i55_J})UGF$EN$Jdu31W>6xP99wmfBzR# zZ^0HTwuDHh6mS;70u^{zl@1x`({;b#Ewu_LLOp!G!{g8BlYEnscM3X0 zX3yEG>j%=%qln#R&4`(C=coDy&$~gz`}LI4|ip|`j2hytZ3R|@5yo?ODg^=HcUjs{H|wX-cO%azJqem zuFJB|I1}p3Fi59ml2!LuH33U3OnhpT(^L{NT90x`1HBS#6aX55m6VB#9jS3 zbg|ub`)`UM#)n#T_Q9<6H-6>A@LpUjczs>w-!;P^t*hvd$ooFvUc~^5%Fx~Gm*Qbz zli=PaXrm@u!|6MG3?-6q9lgDV&g`a{(stVN!c>)Xx>GIv?+^L{FXyyq)$ThQmpqWwC_&I#(ZsuOjaNbyNdw)CHc6%BGfhj2oth`2d;cQZm-mEXA1*)rJN0V> zLR6od(5NE6|3ewp))#7v z^S`KyCa)0?Kdd!eFqAgzD_r3bHJjRDo<%1)t~$8kQZ|IyLXxo&rj43F?VpOVPaCfVmwBwySum&=FF*PBD* zh2?* zfke-(bY@K_ys>HrRtZ^x*dxs3 zW^WdZ&v>(cvQ>L4Bo*<78X$;kMQ&cTC;PjUyKKZCDwLky(9;#}s*fGXnsyXQ1BC*R zrcv(qVKknK)R%10sT3Jz1emDO(`#Ttt^@wAmx_d<#%Zy-st3`oSGvW$sNKOaI3_Yb z8GY?B=fwEO!nR;DZI@>?0VF4f#d9W2m3s4y&SY7$tf1-;gfk#a+a|YE^>F+9tuk-O zU=mC&%PnBQ;YR%gZ+x%ifzCInNknlZ5QEJvKLnj-1Mdf;>{m`D7)}rfK#B+TMh7CBFYHs!Em=7CMfnRY9``%Zb2_{ff z0ze}|WUXKxH`R!yonSP_hkq)S{F9W}v5@S0j54%E2!I~|IIf${%Y1Syf)%nNp^!)w zbfuDfUd3B+Oq|)iNbIHO)o)->e*erh@}udtENG&v61*!0C(GQnY4lB$X}ZLA_Ciw= ztG7Bx(9h#=G^uXg2cw40zO3i&88j}+`ifA-?oQ&CkMSL z)Wh2_)S}cUreNYYi6pnDZD1ZI`cnYuQq9G7IDr7icAowP0tIBEumqP!;U7{xN^adRfs#{gSe66C5iEAak^_@b zO_xY2FPuhUQ-#=WW~lHGV4jn}U&^Yk`5iV_cmxj;IdiFC+C6AA(QY@uq? zjvryd{1b2%G=$2(kHX(*ZxOlpGH~dP*vUg@K}Y+QaaA%CB%4CBLmw)P+d;icf+fgN zBMR;(x^Sof2k*)$WU*@pn*S)p?6AMB^*%pVoIq3#HIEbl&%t_6sU9RJ(iT&qg4gA^ ztGb|EKeN<^gYAmViNL7QIrdpaH|F0Jh4{Bu+W44^{Z` ziTvckZ20Ap2uOK^hrNYHIi;LYOP}*d{*MdLm+(&#KG@+QK8-jCe*i}IcV|dwWhR4> zr1#N!m~NIgcu}Q!25CvUm$35UBc^|*xEEL1vSK>tMz=L(q&^FN*nqLCV`6uyeE4E` zs76k@W2647d%Q>_x6KwIXdEfC=M-_>GczZ_^W(ZWM2zh z1egf0@PuhP@u|R4eiiP+2pwbliXNt1=$F`CWt-$FsR37+pR|Ww3B{qT>O%N6U@uE0 z@21v!CzUu)ZvH?Y$ttQ1L{_M7G=_$t@c!LgN!BFDY-rup^YJ-(eo7e%WI;wBTP1&o zAI7hudbig14a{lu(_QD~KculuG0214>}&URuInkZgu|H8WcfrrQ}`5TV0=GFkk8#W z1~Odm9kHWzP(@b$VH4|HRmZ4pQ&1d5@WYXr^8tAKyvEo#g1?><__r*ByFmzBLorL$v)Eu7LL*%SQ^N?a zu-x@KwnNQ$9MvZ}y}{_% z(iN%r9liL1F30IDPrSJ{&Tb6yC|J!gY|I*)D6%-ckr$Zk@4d7ik(FJoZuPG#YQV_v z7+JW3Ii3G#hh~0?#NNb$KVgsMEy7oLibX{{V(x-ouxkA+>jeYMp$XsP<;S% z0S*;#p-rq>Yu+9+=RN%v^j}$Bg?SK!2mpsgXFe-h0^L>*Qh1)G@xVSE29#(!9AWE+ zf2E!fprmE-*j5TGb4{sHRxnF1!0%UW8uBx~MMGrNgajUuUlS)sS`dF*XxOW(oV-z+ zs2BoGbj=iNJfzu^0?!Mh6t@Vx)-rvn;@Xr5nS*K`TwUeV*VI$A$1<0%w-8iupOw^( z98F}$coH-oc&MJ;-*suV@3CJlzH`bTBZKkWnR%LMZt;6zJ=9J*f;^vmTB@`xBUHDL z67Me(J|dZNQPej%gUIJ3+d(3dlCuwT0g2GL++tQu&~H2}vJWOSFSP~l<<;|-%fBjD z78A}DHPoZq+5x$)#T=^eA&XPHWj87Ft#R@&k2sQP27(z|o(DG25lkXU-&IMKe(su5 z*PVd1s`7u!Kfwfa33hx6C*tgnG5%DX()UEyI>S}L`7vO1f{`PW<(6oCa;JoR!jKHcGskSsL>o#_M zO}d|UB_x;T+Ve1T#7qd@)ho*<)Et}6yZLhu*hyOEsee|PUK}F_BK=lZ(SkRkwRj;FwLZrAuEzFdeekwX9BS@^s$N4&tNpQ3W4e^m zeHzOqh-rmh%ff*kQjlmLTF1vkdjuy(Rgthss#~eo7gAV!{j{$8SFz|5DV_zT9pHL~ z*iNAIxIsPa6;A8Vw3f9hKRp>YzsfOnRT;+535SKsz^q0$dn&I>LMkKE(dMN9#P3Pv-CxfZ;UE9;CgZ$lxL$3pT6r%&Zj;FHa->{I)SKe#Gi*pc ziB#&_7pVK>`;$qvO_^cG(&i`qrTn8Kuh|s`ieq-~JW^X9%QM_fB3Ey7rRL7xVv2wq zIn7f(I$$3zq?V}@0%@RA1Wf*xrb`2l^w&N(<*Z67B!)_k?K}!AmNKmZTf8SNjFe#y z8+NdUR|>Qu>qE?nj_4f`yII&Mzq1#n_ANOmq0gSopiP6;`AIUH9Sz@Z3ATVTfn+YW zQEuc;d^pe>RoUrSkq2^n=HP$_gQjAU#r0c;w^z*(KvZ?qO1R^?2 zB6g*=0IP0I%zuSFBkC(f*-~T9Trr{A$bdFbQ6fS#E&dX1EU?I&)b#3P^xwJ}+~QN@ zJl1?@%dn>I6eQgiOuj2RVrIfh8}j9 z<7}J#;P9I z5T0>{&Sj1)vO5k)illI)PB{Idqf;=@px||q6V*^g5(UU?NB0w-c&Af1{Z3r@f?uSe z#m9@Pq?S~sNC7mEXVNyhF@q?iEa>gKiLXFNzGqgq53z8IZzRMR$YgaFN859mK**8ZCCjcbIaHlo;DC zo-GH)6gBM{dQ%;0y4MKErI(m)q>TgAF@i+N6B|liK308~3-vpz0rpc5=TC0sK%~TE z>A8bjhC-6iQVcT%x{D(F!Dxx?EJ09DysOf_#NIIYKBt7NRUB zcQmG|qZHL#sbU6{xaUYXh&9*qtKHFvo?R_F>)Gn7U3Tb|;PmNTp8queRp*oIx?LRi z5wUqGPCQml{yy;^(XFPoNauUTCoG~t`mmkv2Yi7hnzXUhH?sy)1=G-(>IPr~?zmg; zYvuU9$u(3+Z|*btAcuiXAENn=j;Ho8@YogxY-TG_k&=lVw;gtkB0L+(``-1CndZ$X zQtjqScpVhe2~p%xiQv5nrC?oOnCb=lwK3rgIF;r3f~ZlSqk|+r-dIe|aY4D!-10|= z2z3iNP|uiub|g{jP-nlfmJ&aE(b7w`khxPmK`t& zV?C~1G{nxM-Vl5Lm&*%y*mLm5NY^NR!78Z6n2;6??_pxUdCTN&?D@u+TOoJlp7;-6 z1VI_%fVGBcpL4-J0omi*&3Y3RqA#4(pqWO}0=m9NUSvVR$ZpUZRxox?g1%v%mno=5 zl_Dcag0Qncgp0Y%p2*yhk%nSHOX$7p^40$$83dvDu>Et&>Q`9aV~ZLM$@1lntP61e zJFvpdrJKq$$S=>M=~v4V_b>aZvI{l~c(nPB<(m-Q`K?p$GpDOP=^EGC`gtwBig%=~ zV5B@+>FoAc(Q2Ej(wZ`_l}0clalVD_jMF)fUi?`HTBgfA!J@|SO9;Q$v0`9wPq7v_ zjhi|so+r`2gnp;7s0DN;M}_c9{H*`2GV`jxm0z157Q{m}ZTy%M--r+kNx@k&57RUN zzM!|#?40x?}a1c*r_q@DL6bk+mFE5Xg76%jVZITDX zoDQ?gyUgPwA-gzezXndKg+_Xron&1 zW^hghi7b9tqhI>Nb zP#*nEQAH)Q zn-Yk*lFVqTmjcY=F#24%E2NMWu1E=nWQftshm1}-1C&L|0>Q*AnzS(X+nQAf?&}bx z=+E}fEAiCuNO+|WHR~G>^d4jWv@v8B(P7&WwX~UjxgmOgGRR0-yrpkrQJA? zcnY|x;G5iz^i1ak`PZ~GF;`1|AuG+rZ%9i`k;V(#ii}BCG`4IWK zOu#cJ34Sb0YKUV|VqvvOeb-S|>;p>s-VT)^%t#j8*_Z!Ts97t|&l}GS_Qs4;UDUx; zGY{zq_lNKFIMM!_pwk4{{JH%0vci7i{_9ew`uJ+?l<)qz*Xm4H`=Szhk{>xmRZTk% zViBim0DX2vI_yW>5JMTlV**EtW@`O}APp0>7UL_GtN(pQ{0COyADB5`(1~VC%JFS? zf7#vJ{%(ahHIDo_x*vLD5An&LcCN7d+EA4mg&fIDB)pT(CJP;j{5-99?=bOtnz?}( zGr`QFH>e+*a$j5arP>$dsc2d*Sie0na?RNOYTh4fx{wGhuuDy^--w7WVy-aUb&sikAS_kXkGTYLTuG{ zEK^SBgMab9Camf~doZnGdYH|-=I#^cHz)44Q^~3VV^U9zI*xKgCF0QMBeJjWJI_$7 z2YyDf_2o!{@n)^KQuNV8HT%tb6b;3{Tbc}2hEV2DMhW1>{N`J)yt#aTX>>y2I#+rc zB!beQ|EslCrfx3Ntgi`qR?p`3^bZxGn!-fnIUjqNL=~&8xtU$*l zD!8540x?CEKaP;vGl|Ld?Xm&Y9LB7847w-j@w;2(hFFoaD{?lA4pJ=2j#?MvJWrtY zc9oQfdRx=@mY^~4IZB~M{kyw^bOTB+%WQVaqLWHddaF*sK}y-x2AalksI;Qc3!>jN zGbOuT=y7p-!boLFj_I1qLydW*WLT*s-vp^fu>eA&-r14>e}$i{-D_&BN=tab5Xtt6 zK}Dwi0YqgdV@a=O#NL8=`E*m~Z1L##!PYN89DzjXl}>Pa(ZMWpFsfdu-sw%bXI#=R{M9suaR;k zE%F=4jsY=dEzT?zke!d_1z3YD`m+frkL%12f-39GoenpltktwjD}IDPEyax;KG2>f z`y-t-R;q90QUr{$bvkCcN5*(UHja*DTlBl~$hx3B<&l^Tznw$ z|0dcy5}O%~tu;7Q`{H}7z8(Ct_6a$dpC&=aiP}WM^u$nSJ^|65@Z_8{-v*lYzpwMu zt}fMeGi{`r%-x+_3Z^7$eEWK@20ZVqlcm+ZtoXs4-({&JtwAUQ8Zn2IbQp!0A;oHS z4eK{~yZ!@*P9XzQmW**rUwV!BX-h_ZhSO{+E!)Mw*E4s~xyRRs8w?^vq5y#2k<*RR zt7HXgCb-qVgPt-E5)=}HJZdiJvcO3Pur%Az#;|KZ#Z-NPXF6VQ&aauc!?q8(Mfhp0 zAj5d=Vx;Z2%|YCkCG2KiTE|C9Ljhb|z)pwc9H!mql=1&$FTuhi|O1raTvlFmB^MEsg0FuJbbp z5U{9RH)l>V7z#>JCu~j|pR>ClqgyY#uzd-Ol#em1 zW6vPc)815fC~*A5SAW7kb)&eiMy|qtMca7vml~e4h1)KbAtE}A`bYh%V1>4ZgY84a zxZyG!EanhXXkRHhjSq*Vz~Rz9nA}BbtUG99cNoL&v1@fl6&Ji4 za`KIO?@iihikr=50~gV4`LT6g{LxS+=uDGEzbWn$CRsIvo1v*9mCDru(+th&Xx2zX z>$A;BDbYyXor@JUE09DrV$q!sWjW-cCgT1w4|ggi`?H{7CI2 z(beJjs~OlFy=!triky3xD($6L&RHjxc>ISOthJc^PPn4{%w(!DM3^(YI)~o^%Utpe zjX|$c{6g~w@qMUa19!@2==clCK%k)Idds*+yL}voUz-8Tx(7jfei&C|p{K^>tGiC|{mFd! zmz>MxGkP3Gp0MgE01tsHZ(nAuwSrEfn1y^wr)F=?=)zUcwdoQJ%|n!0Rw8a5u(UD_ z{iG#Sc5N4(whnaW2LW2^$)R?HW*55fX2fAp58sNhN6e3nY@;ij{8Or(q$C+Fo2FNx zS;-V8_bppl*4Nfg)O>>vhoxUvYuOAT8D||^cD~s?H6oUJk9iPad#eqUW(?-At0|(U zi!F!XSmQ(29nA@ozu^LEMsi@H%g5|kMOt9>}t{Q7oN4LsLvi4*?MN&NmLg>8%z!$r-O zKvx1@5&7t4#S4?;I<;#-TA@X;%ZQSa1NrxY37mPC$U3A9t=05w42G}632;YN?PNf- zY?2-+`@6n=!MS@=goucU-;d94?fvQgWPg8u{%l`MNdXud<6*HTr}4+RL{dj9xGWEc zCAkF6ttmrH(Hgtu^`9%6)@tAs43uIA)nsmQrRLeRgvP&}6frI~#<4tU<}E+S3qoL9 zJU*FDjc99?=@Tggo+kIiaqy>*8KqQ9T-$=4ZuEk@yS3>lZDCq=6w~&>g(BBl5dOb# ziTPv$x2pOXb^}3T1as0Czx0B{~=mS3xHKP%}Cf_a6BeQ%RiFaUljD~MUm~c zwxE`aj8p=KC`By2;$RxPGa39+3AT0Vm0o{j{@tipTzwq}mm&j)r@m3|cp2Ceh~1%5iQ`5M%O?K}dpBuN=O0u7hqehz z#ATl>u(-IvhiGu7P=w5$vHIHSdf2UfiT+dWH&uqTUBVpnX{5ST5hUnGYzHOl3ewIV z^HWgdRbLeV-eTJxtJ>6h8CVQIr^Ecd;NTiC{OC;`^!r%7zgN_uSmHcuh50_!_ekS$Ms_50~&4g7p8{-lq_nneX zQ-F3J`*Mnp=G>PdIcrci(}C#>z3a~!yIsHD`M>eH^Vu7*UK#DBxkl7vHyR+Cf}#Z`d8uT7%jzSC|Lr<$LL6i*Z}K#lqKhwC(-B3IQ88b6q{K z{T~AVYbNOtsk2JQ^}*Y1@uLPu zPU>L86l9H2eC*PMnHH@i^{P~L{ol5oP5pn>33FiQe=QeTHASk9dOWBd6)G!?6oXF- z7akjenzH=WLK1R=Z4~A;~*3fSHw46 zt;q-9S-Iffr=l7Y@t5?xqPx>`YM7VqF@!OI6K~lsouW4Q5*`FEn26IFy~*+4M^o88 zTXDWuS5z3^Tchr>Dp1L^-oUEr9txK+7RAL$3CW$aT3RzMp3!kuLJ1-GqE>a>-q>!% zb>81e$uFSYO}*)+WSys7kX}(csl(X2-0x?C3K>~}$i)vEWa5j-G8K$u!eaTG_x9xN#0Agb~#VU?X*QMcwIb)1XQ#y8}{%9%IHF^skD!x^z)ohtJF^>4Pr=<& zaKFl>Z(64rMp9{adAx|*SkZ4*(zDtPMFmOS*;hO+Z4v~`Y!mvsfV|>bR}^@T3HxOMb;zMg|p-+A-)&D$}#&!W=hK0xiqg@ML2$S z%yD5GGWYPX(9_d&bL~uUeb3QT)Sa=CT@fktnbhC@mR~G4x2AiPRFta}82w!CzI6X| zU@o^np*1!~UL;g;Xv`?FmPdOHWrXB-ne|<(ZKwmP-MjyT;5qF|D%nRjaO!xPJQ$MM z-?~N(+)!(KsOO%;&AF`Sg`7cn4C)y=mskX6b7oQTBRx*+upF&cM z!2T5l{c^RFamh}P@lBAOVu=E?SYT1#RVz1kD=_)BH&BDE$w9Fx&1JQt;be4Rz@xpX z*x!!JohjHO@)7*6=RYZ?K*aCm{^kZa09v*?1N;v{-Cdq-{WiFI)594-JFSndQfP4^ z_7Xd%+^8iL)i5=y6+->OrZh}oh#VAj8jFiVI!=kDrXYUGjA3p?l z%eKTnsXduZs@xyl?T3BU(%yucbx^_$oO7op3*6bSjl!l}ZWhz}vYPYhU)jx{H}pq{ zPI+XQfBl0I`*uY8|0Sw_T?C9A=1c5bDy}CkjAW`O{<;6pxA<^*U+W|HlOYKT|`eEdkU!;nQJnq0?@;+%b#Vv0I1o zMtEKBydrXO&{dEdBJ{=!NZLDGS`mT(&FIT|@o$T#%0^Y4OOxm-p;)>5@X+nS~maJovE+nAb~0C zMpUG8BE-CWY0_BC)c8Y3t}=t?s##F9m9bbu`%l~%OkSh%xxU>(?^B1wEo5DjF&@T} z0die!GibTk{ro=v%kJ)IN`!RRjeST>vwT&X@zdK&q_V2Y=Y{#w=QmRIS`t*#_E>e9 zD-iCMzAU_#JL(qO5X?q^+Ig|Y<9fAaI{rq8L}9XsP1*d4n}Qy?3LU8(Q5~5XslXXj zI+c?h>_Y*jM!{wpb@R?kJLt*e83-X&pD`*-UE1z+$ay|BOOtPo)C3Z9>Uv7I`px}f zEwj%+j)RNUV@z?zSvqVi@t}#7v)QcXudkHF_1oI5oDd3ye#D;lOT_K>mz=Lr_#wI` zhCiU(ZtJ|zw0bb{rGw3ZG>*W&+7dCl1%e$8o;~m`tbFc8dU-!1u^u z%ww#~j%TKP24~yc>I5&lh`3rs&&wU6B^fz%Xn^}llegQf9^RD`%Srj#Waxo-{aSU&*y?X<8GYzZppl7Kp7jZEk6u`D6N2L!xywGU$KRp4q&dovoB`rPt^jhMwCA zRJc<$FGqT@Zo72psP{sG6v}BfpJ9e{_M8ZMrPYV~)6B5iXLY4jD74bdw;nlADpuW$ zmyF@EeQga78o)h0nIAcOSTiWhE(11l52^nIa?X5v>Ou0%@KOp0J3Yhp1VVvXM(chw z@(4xBwL6jEgy-Sjm*$>z^9e{k;m7f&=~-3_)L^6>>3wzj^6I;wDCa#hlOsox=iF@2 zQggG?CXEYPTQLsG*AZ}8mny5fjpTm3YY|$B_Y3=SA+?^Z5W*W*QG66l*?xi_7J!9C zRo)ZoNYua1GSQ@(ZNzdYnGhurhv&MvTPo$1f&G)o3JpMsX{Y(G>sanGFteY11zEhSxwh zYjDXQw3f@%DAg;X%iU#_3gx2z*C9)W^@B-$!6<|CB9&uVh9guHMd~?6AuDYzNoJlu z>(=SDTsEN@3Z}|4lzy_<6}QBGvR!Sdal3ht4Ir#?!$|^3V^+RyA)$i{@b=*j!}8Eocauyz1}Udjyi*MRrYf|Z{aZ$>MwuQa47 z>B5WY_|~XLE}rUmpI0i_c=bH2`BDLQ9b?So*)Ts2lQL`0x$d~Z8$~fFZ-OJ8>7E*U zH|`pMlvAI|<*w6vLawyzcRE^K&e(^-aK99hD@8R9N4}E55|82u;YAyfMPY`vv|DvPSvC%e| z$-^vCs9*zr9N{4_^%{gyG4u4!aoHnm#AJY;PYU7qR53_(@V=i*Sf#e*c$&w4-F0oK zO#)j<^xbHQt{B%?sDltYt$)N?_gHkA0Yyp5%jfpL#ol?fd2(QNjok2|7sao!9EcJ^ zGc8HkIVFCT+l9hIM>7DYXFZR-*Jch3aJ&39S>V7ft47UD}Qv3Fzj+ey_fQgvM&nu_aZT z!Eky=LaKyHoX*XpEXp=Xs;A;G-0Ja~?i*^X7T4-*0%49Tf2qKVJv+t```e#bvpf6o zSN?w|y`Ufl_#0|pr|dTP7F6&k@+z!_WC)zOa>$q5pV6bs?eQNDkhnH_WEM1-mYjr?7R;}p!j;k5;vPYG?AkIIdsR-h59}LcN z&6_QgGhrx};F#|jd<1>b?(2xdbv$H6W2s9Px=kmOw&iM;Jg}M!)M>B?m`CcerA-p{ zf7kfyi_iU zJaCr4ckN#w3SKe~Wd5Tbg+>L}>>yLKc96XPhhMe6A##ty`r&P1UrE`hd}t{4vbqYX zUunlxiEgrV&HKx?f+QO&fIBRO2RV3{vs5nHOM6RDq_E5Y*h(XbP2 z#=+3{n(!U9USzZPwq}zN^bT~{5^4}oc=Zwqi}xX5o_GNGIHhPs%NS()7uF%xj4sr^ zrALX*YI@=FEz!%zY*w?Zs!m~a0?@2npSwVeRJirEiXT}GqmoI=Kz90;&yYTK|1TvQ z%|5)OU5LV4TNEdJ-qJ7S^SuV^krb1Eb96Pot^tJp7SxjJ*+BgoO(dP0L_YxOXdOhcbjC>C*Jg>o=F}(iiU=zk*7EfD3sR z7}>!liUSiOHvMf&x$b$r(Cy3^>+twQBg&KRbmPxhpp^;lzmCDPs>>Eq&!El~B<*T`+ z2|YVIBH5+>z7o?0`sdgInoJ?LItGNzl)GC`%$5+9M?K$72z)aw6lA}HqdmJn_IVtO zh=uj#b2$?xhW4oa6H4naYAWk3X*I_>!miCIVCl%$AvB~Xz<5tm^M~@4#MYA)m9!_{ zLt?j2(LiX2CA5MlA$QuYZ}M-b!G(yqcXmjLa}WN<-&tKh-wjUKamSBP)Q)EIt%tvq zs)qu;C(Uj6x3SFVpDmqF7Hm?b+q8I))#dOGw9>oR;7O>Hc4@9f5-4RnC&DY~`|H4W z-MU^&cDAFs-c6;JKZE$V(YHQLs_9tqdNf)f)4FkSQ4Qf8Cb=d`gah^uKzuUwFGzb@m;Y9gFM1rsiZ z#|H)mQs`9jg}jS)>bd=TMAw~Ir#M0o(x}_*%tf8un7PG0C0=sfCOUBn4}wFg zW74i-Yw0J6Uv&R?j8DXIunm|&xOh7MI3Oj6nlcg{yZvUhU=rkDY?u|wP^G5%r+QqQ z(3R&>m}Tr#VBPsEtiBi0(EA81c;ES`-? z1J(-ee~EO?o-H|=7YJ}>P$N5~afeX)j_4NZg7n?CCQO0GwD!jgACiEdtL?r3mE(%i?uppJ3E+!!^T@uv zjM7qD;8vOD;{CPqe}+Fo`@IXPsA>?-baH)l^MGpipi#S+d-I4Ng>L^D)C3 z3C~Gh^{t|}A2HuMVs8#cQ{YtAx2s~Y&Arw-!KHGq(6s26!*5!Y^F^derNXt3La@bu zS5ytcNzH$+66TU8JpXDI;mhi};9w(m79b50?z_$pT?(r7PuU8fm`C+{Ug7#72(5lW zKT+o9;4je8<;%3!Mq|^v0Oxd+TOq)E!YH}zdmr4r8WQQk&avq}sbly?^f;?kL^Bo5 zJaZsL9wIMTYO|P6u9LG-5i1-iW2|2@ z3)%B`kE)weeGEGS|qEAjkhQxV*w6EaE&(-Ue6N!tVsD zEiFqQ>w|ThbL)LvLrVq7pxnVO|Lo@X(0I@=cY@#@Vu2E67oN?(c*g%ezlYm*SfAi? z2)$TR(*b$K#w|U|^x;PW$OVyqPewWfaxk*|SDiSie(rj)3C;%Z{^>I^d<2c$Bevr;;dJEE69)tZ@vE z01exLp7(eO=dvbAoT0)r{1$Q}88E@5i=g-MhC$G~8u<-mIKmRGK`_w-`x~Egno&E+yCIp+WSNL&vRxP)S zmC`f8c=V@T>3=4>_8R4U``?(x62;;1Wr`T6e??F}RwrZP?hclAqakBBn>dyp^?WsY z0)0Dehz3=hFcccJrCzwS3mLFvIM`uX*1S@)`4R<+8#?IZ<&|A5ANy6e?PWQS^v%@u z@>j`MW?$uEwUT!@aoDr&Cy@>;pcs{BBu9tSBaxp=E&ZbtfAhI}bmIKFVRmn1lC^MY zpdTi!+;UsjBo>S7DZ3U|WTt6eQuVO&61G^Vl;v&Ie6*GUZIaD(;m%DGqV((bH|Ka@ z^G{qmSd4~m|JZA39fh1j`jfss?V!0B)F;6d zy-xmQbJlYV_uTv?l{GQ*d8Q3%e!1}<9S+0(7db5(hJ3k>M0j>}GOm)q#5X#&;@*!W ztv?7+LDBZH)sd6&UQ)bsMXR`jSoaDfhpLPTe#>ytWVwG4Io{tmL^_$5L&_{e;!$32 zE-%s~HmhV}j@ge#XqpiUv(y=lejqeA6nR36*(s>!bgF$hS~2rjM^bTbA73YYjbPL<45)%S4kOH?ieslF`{BKyrc3X2?jz_MYO(d z^N2>p=nhTvF~;-`N3f%U$@SdmA?U-(6Kzz-T%p`GjyZ)EqWNi~#pUFdR-<{_9=~$S z?v`e@M;*TK1QuN`D&Qr}Xa2Q!qYmgl94$JMYV;rx|BP9ON!}_;BsNhvB$Xswv?!*4 zfYn;6vGDaFP~GF?rqNrsQXRfCO0E=;sz%Jj)V$;_8`; zCdTu0m>zvF|Z3cbs7n?I04@z6}c*-d~6}HQ^&cGuPJZ+mopkxZmY&x{i?sTm!u^iXTcWf>qLom zs`PXsyy~i#>T#&H*@@nR$)u~{Ek201CT|LANONho|D-<9Q#cuTneBI6Y0+}SXSRkV zwQ#uT{54)L@T~M5cfI6uf2@;h6GcENmq=gwuwtH~Xos#}LYfK| zN#iQxiB4jV`(D_#l0dH45;ub|BB^T@Ob%zh%j!iCG;&elW2S9}vO$xYGD{6R z7zUe-pxB=g?mJniO3H`-D@`tpQ-gy>Q@%((jWNeY|3`<-y1nw66*R|ya(Cdjd8e2#y{W(%9%*^$Q#y})8T^Bp6@o~^A*Yngz;Z@cO(>wm50A#g2snuxL+wI%{ZOWd90LX@AX)2p9En+Vr zO`>B4foF9MDLAP4;TPP%*9vt0qE-$)TWBebfmv%OT75mt@YL~5 z4WlQm!dz~p*b)YXhJtpT)BrhUpOo$oLfyHAbV71V3UC_?5B&U0OrDa@Iam?h8b*(& zjokFqB2TC?Q}3x{Z<18;`&J7xp_vB6FlKxDq?f>ncNS@=V)uf%yRN#|X@{?+_bA_@ z%c7!YD5#a?nEt_5RD8*@Tk2Dg;l%M^`L&HURx~}WGncpv0j<-<%vBI*+6B>x?u2@F z?#`aL*!}x|6PZNzF?dSYA4&M=RWYL3Lh}ZjO%_{G@O9i&<#%#5VNqG* zEjZjRtYJimjOtI_ew*K6qAxwqt%<*YzOcpp^mJ#VIcS2wi;khdWU38H_hp$j<1k4& zBu3dV*|usd>_)czkdV|0m5W};pLH#ST}lfKvL%qA*BIm3^0T=>UZc$fja@27&-rer zMrHBd2naGO;MOqU>TL{VW50 z&J50<5M+p!hiQLvu*vCGFB$OTcq*P{<~MT$LbRhEE2gR_Yzjji#qM%=s!|`Qt3OBx zUa4WkzB9u#PQ+|@lrwIc?%DK-RH2yV|BnX*ji<-u`CMGi%-Mxq#oxr-6U*%-NtMZZid`aJ??;e3$XxKq2c z7D4fWt@`VNf2qEUA_{_m`tX93$dO}Ggi`1%;&!8;swdY>lXhhqM{nr=$J0BoXVx{* zx?#sw$F@7RZQHhObc~K|+qTUowrx8n`+N63>nGH;=9;xejk?Dgeaq4j**E6&Z`H#I zXMgpkD~tRh(haA^tzawmnj{IdX4#iouf0r?qQXfy6>o(Ms!*J~4uL=O&SUUfz|u~z z2mTfjkadDxo+MWuVi><8_j-&PeT32wb{=@c+CJWyQCy}ZDhG`EJSrc%OAVIl<^SnG z)OR;bCvlL<{9o4;eR!#F@0CP$pe#l#dul^_g<9z_`_$R%Y!%xeXge8QRpUl}NNUUN zOrOn&g7fC+rh$?gV0nPSlvxRZ8;xpZ`8tet2ff&@D`QV3L;scBnIInXyPq-N^eYTG zXL@~Tm3m1yv_dA_GTY7{T=l->&q{G}hsy%xEv4v=IX3_j;Fvn^V0wB!hzC0|F~4TZ z^NHQuVs7GSWHsJ3;oSO$jaLyg?o3LSpH!hxf0KUSOFpTP{Eu&fm`h686&(17nd-QCUR_8+z?DL;w^ShiEm3;n&0PX1*Ph=|f1| z@_(Lc>=+{Ad`|cV<#M!6Y2eveU5b`?5-=7piI&9GOW{gU!|hH(TAipQ(k58GM+AjKTWW3l7;4Nd|kTlemGM( z(oZCC0S&u(+733%I=`KOu3?1!`L4u~)}&@Ya;jNLYj$7I_N2X__Y`E9+jvU26$Ywp}*wy0|`b)L!c}3>SSNd{T4$F1>ES8_*1Ynl9a?zA!qhXHQR>C-d zZ}Tzz-ybhCgGyU0V-cWOWE~QMbRe8RecEEXhQdGZI^3_r0> zYd+npN|B4XYN`?yHt(q-pyb_m(`?0p1+NGshJ`FvrFc|>>mjLBv89{tP}cqMX&$z_ z=FN&C?qi$qm)0Xo4(X@zcDK9Ldhm(#Fi?-9or7OA+2qI!YkfzJQm^->?2ooUNw$|i3y+vi$ z(>+itW?oH%jjyu1X0=PabofrzK^(o__j&y3&+=>VYywOD#RU+T#shLT{=07?#~R?; z4ynFv<2ux;9SaqkM$!v_I#C)iHYVor!LyIa#X@5nH}fb(aj2e+MsWbVwdh*d6eH(WvZjzZs*M2+1P+Xm1O z4-xmCwzbsVr^OpmF=oex#gW^@0RcLEUugI2~{4*eei_JraluDfe9!pF2Ee0G1 z5ipLUnl7;nHS`{#pw5;j->?2!YeSgsb4dlp9Lpn1LF(E4&()-_I~kV7Tx@0tkkwHo z!bJNJH0P5ToT5YtiSu1&`z`Wz-t7iae%{1Vdj*%&y!~u-znHT!dX~w+hns(#ch8`Y z+n+3x#W8nSz6x9}QV@?f*1mt%0pQQl*^Avr<7a8I9+M<@J}@*qovn&XWW-U>MR^=D z{=_9_k#S_Yd)oV>8+P@)UDB6ikYu7Z~)F(Zb zb7*LsT=D1IGo|jd2F4Jv&zAB#;@$OahyVl3<+T*TmXS0>3F zTl6J^^Kl99bDkaa-tJxbOKNvEqyl9w+rf&$i>BR1l-wlK2H~}XR_0Am9lr`c+|p*r zu1AjWSo4E<{#k3l#1rZaf{Ie-2$9FPu;|9SV8vmpW>mtZwNR0#o^X z?*4sS`90VE6Lb$Mt|h>S=4@s@X`Wgbw3>4tJIZ$msDCJ?+;tZgjv{I++{72vOpU!`P=p7 zMp3MEl-2z&bwkP)N{W)EUSW9o&2CuCID{uv$#qNX*7)A5Pii9<{fpX~k;aI!pKvcc znaBdGLv0FJ4n+&9>IcoA#D#oDiDCuNXbt#tn?^3Rc2Yvn=r6rM))rF04 zbGH@YPdGhK5m@>As`Igum~fg6a5`Xr&X&+-QO4M3kky^-DwlYsyn3J-|Mb5X$)2w8 zwd?c$=K`FpW);k(FW6XB5p{$y-;@oSzh~8>qGQ1euho}@pLcmZzPWelmRy{!?OI4B zTh2Dd$de-wW^u14dWujhC)>ipY+ZDwTgRP+nbZ(5d$LSnDK};)wL|oXSIrvQ|!0u81L{NA7B2~og*~buW61inOTcO ziaI{~Tj&Nn?mnIQ@%nIqowOdyoVfe+h27qsbV><34Xvo1ZFw9wx8CCUC z78foCH(Qs^ggOI3h$N1xLs_v-@bAWh=5v=z67SVnQP1)@Z@bhYjpepg(%NL1bw9o` z0MbUd1ea@71%&8WOF{)yV5*bP%uVGLwIDEk6`vi6!l%o;6PNGm5`XQ+83dgd&d5}e8A+b^#vo_<$0Y~%=J0gH%n zzUjpumi&c!|2gTf(t{~?XFiw1@^bj-aIE0ZMg)Dcs;s(5qrU1C0wQ2^A0Bl1RSCNv z6wsD$4sHT7hHQBy*bTRX$2GZt@_ZB-rM%3-V3I%`pu-aX{5E|~C7W-qo2A$QdMUtY zgJ#?w36j}^L0h7VHj*;Yr!=A$C>HojUg0Fn;kDz-(`$7qv8K94j|OQ z84fTvQ15e5UG`k^>@*x7`uG0Tic+#8xlA(d6KqZ9u9%xdnDLcoyd++I;QY4S4iK^F zb;b`Uh)2>+ZRADi=IOI|`;A7V8i$TJ<8mTxV%qFHkwl1Vlntyf|F#fSD;eL5BV0tc zIER^%fybWC?#W7G-r01N@wV`s>E?je6-Ml1oph@p{_%wHAoq)ZWjY{nBZ6gC9oeRU z$F59v70H^Fnn{d-hq@whDMcU>Pav>EwPANYT$Ow8mTIe)7^Xz+k1q7iwwc;}Bf>9s zvME~qS~X>zL=*}8*_!aPuzzzGeEjfWuW(x(;2FhXX5gEZblvzDB=IW0EOk~QGd!D2WTl4zu(X{-e^maI3fN`aO7ayNh^O6~`v zOW2IEY)0T+ii+2YvpWCheaG5N37md9Dd02ALd|ZzCP;83Srg|Jku9PaVO9EO{dTMe%O=VgXM5gHJ@o{i;F2#?HDmSY;cdp!_LZ1|)I0(9?o^TI30tsUdn|L$%^;tq5UjtGt^c6%Ov z28czys2-9owI#c_1@G3P`fJ!1?#%I5H-eAt*UMwHr`L;$4mu}|#Okh)y*E+DSk!54 z3=XkehdRL;rR9elLgr=)1*B?~B!=ZQnlUIkHAUF+^;J796O^e2xsAdqc3BeX@Lc@o zJ^+oQ0C=p5Ke62Bi7b>#*6bODB92YjgxC?(5s$fy=CEjQR1lp0Fz5-wIiur}VY*vAZ*|}s zu9R(4)`7N7aPphA2?fz7dpsaE*(UJ*){n{TRh>vORkM>8PBf=p-))1TV84H1h!cXn zl&2ihhyI@u;}FAYqVJ~vT)92+?FwEB4O2$$^e2TiA(?CvLaTH-3Hf5V37XIH_I<%Y zNJej;UMu!=D?Zb5w7svXHX?*mrYw3frWqBVN~GgjbF7&evZDF4@bK*xe5^Fcaksx{ zW_ch&TiUL-H(#;iE_+mqrybnx-%=`IX3zgp^xTNlRvw6;orampfUU-44=09JW{0h!AA3}(B= zgLLK9USu4vhjyVw=?JVCB^a$D>rd(-|4vZ-2t?@H;O=5iUy*DUmx+-A#i!fpftVF$ z6@s`Vr$>}v7)%`y)g$4|IMxc;)x-{)c{;anW@{ZOFt**8wdIjgvQT~a7bc^i9PMFX z%>Y4Jl!F4LViL)lZl;AE%+dw->CHq&+y`iYL8bDYuz+9K>co`aRiA2zsLnOq249IU z@sX;gw6uk~5Carhn4gtdX8F!x47)$t9v?g}QFM`Fqf?t+Vdn&g|2^xn;>FSgt4&!K)}0TXJ9@<@)Bla1$!x^Z597Is;wdMLf) z6<;*rQGfEBYr>1&KsmQ3OV z{%+|S_0lE19o2S8;XL#7mRTucYbdfUT)&58?|GENWM}y--uDVN_2KZz&C+?___d%h z5;~Kg+PO1(%Y5xz-anwq2t($S;djR+nU8 zS>I%Hn8)m=hFx>=cEw3RzL`|CGNQ-}ere-Xa8j_ zE-~tfl=K#@6pDloRk^dQf*i%E;uRQcynE<{&8CrYATYQICdjaE41g}KICy4;K^!Q9|9 zT#lOycous?dRs6JqT4A4@19d=pCJ0&Yv(F_5Rs5h_fw~~$0kP9qsCk7;5*DzXip&N2HsBOzJfG~GQ=H2x zrK>8ofxY+hm3$V|l`yf2;Snut1r7`%h2y!)s82gh(gs&O8V8gOZh}1d%UVajh0i-I_hW7_edbHzp>%| zGja7f_$?nJedH{!*sD@$R8pznm=)ClUd*xA(5u{8a^haT@g*%fZtvuf8%&oZF(@WD z53FQe)6J-!<9eBcX(lfG$F&J1gR`8gi)F;)ijrIA-eRtRospk`ahT&RxexQ*dLEpi zi6Q|3%PuAZ7wsNWD` zl+nssZ_Q$i;7m>)YeH7jd1PxoEQ1}`CO$TtFc05 z*;{GEF6wlPrCWG`@KD_Ttk?O?)6v4oJWoI?M#2*hxw=oqazB{NsgO_EEJGW^WC}B0 zq(XIgly6~raC(@E(ZK4Tad)4Ygw>H=oPlY3JcI&)J{&Bq6>$BmLkq=URVguC4w$i{ zX#d$+m3xF*3yNYG4zB0k)T2ABb^~p2k>hm3g4I|p=%CA>hJt)8RiM+|MM=ldcun}M zV_KK;qf?H2XJ3^Ui(Z(FXG~$~JRch7&k&Fk7m?8Q)_b5>QT_4{4{laDA=4BvpbDJU z^@hJD5UQ;Z)i4#YcyC}E!n^KB*A_B;qESi3moJcN2;^^C3VVwpr?194*^IR_1y3|W z|A{UQTu+~MXd4Oy@JvW+D@u%2v4vd@<>T8mKQ=dapNkde9$r_0q;_H!XUpK%`Lfmi z4Ae9vm8L739NXF7ZcVgqm8%@G;-=42kMj>-O{z6xS7%7(cHsUCX3{_f#yarPT20rh zOoA?vGT`A`OGTSRitU5I(l5l&LEvPaOJ>`vvX+%A(_W9TpL<`D3b|<3csa#3a zX*AT~aaVPhGnl9ZtSYmsQT<{VS_U$GtpcYMG7@cQq`l3R1}(`Y$9`9V{uYzz34+yof7A~tb&8>b>>+^44 z(4+mui3sUn+{+m*paGFl!-p_xZldi1<0Z|5rEt;TSx}HEguB znYhzL2j8YGPN$M9TBvm?!C?D%Ux0spw(HfX8VjN}5(|SB(-leiTUCL~1xArN6wj}- zD`4Qm^aTSN`ZmC96vfHoML8snWr%@;P)fr`9Vf`+|0>aw^=mJ_mm*aP6%UfhvVSFk;Kz1Q74T_mKyi#4=|K4w38ee@h4I9A>=z7!0<;3QsFgQb-7%t zNFtRB7I{&gIBAvLbviR$o`XmQ>zEOCxlr zDL;R-Bl~9;5<>?JYGWa?~0^MA8Eh5u&V#a zz8cw!3MLA1!}!#0Ov1@S51@DkSXq^O#Qx6?lo|B2sSjY)i-yDz=W)(DZy3n_TR3r7 zQ;^A5{tBA0Mp}OCR8gvCDlc_951{gza+HKzV_VnLC}M&c+DRyfm+=%O{7YYz6XB^h zvdUHYx-v0jye(2t^6Ss<)zu(@wDuzFtC$<*rE1R9jRJ@m`SK;ghhIX9Kv!5iDuI0b zmN&s55Fw~(`B^oWAhWb0j{!%Ysq#^@KDRdMIsA zAj8mM4y-YOu$)$+@s$_`|o`3Da{=XUyXRxBfc>|T9CKD+Z zxk~kN{%MCB5fv8nn)tohwCqgvU^Y5yj9bF>{XhiX{=*&&S9fdzb!>Lhh=LdVC2ZB8 zvs^c<%jlpd=WmhhWy7A@Tqq1rj%m3>N^IGY);#8n0(lBDQ=;yVAOwx=3Q%8BytcgGyhiBP;{+ z$j^E?KLz0)_BnW0{Mn1r$lyX!9@;?d+;g%C7twArcw-=FZFsBaY>sfu#VQz4=Fto~ zNsMs~%JME+VfB%!L!W&gj58aqHdPIgmj{G(m`26do&KE|UlB#I2yi##eT2`GjdJ<7 z?d31yB?RhCMbWg~lcDa?i@I?yEsV<{)P?gNh=NkbP{{UkaXQzmO>y-5WXHMfOk%iB zQ!==OXe$Me83)OA5od7q{dbzLT6OW)E7^Gjr7Wryh)9x3Z^G0A$KWJ`H^5Zh2aDey z*9M>AGTL7uq; zG1Q4%BBn_bv!-3ZsJ86ZB^eFR=)3QA>@U`G7}}_li)BPSAs)E6Si^+Jb!LGYr`N!W z_0ImPb(CYLkgWaW#!)JCJM9&WWeJE*nCuD@?lsHDu|Mh`g&%t6rcIke1$~ycH=%rL ziF6PyN~F~_af{<6KqbF1dFuObW|z)pBOFdw_*b}Hij|O(4!613 ztLw^A19~A4q(}g1LDKkx<9(cwgRqU|)C#5)&}_P=I%a~OP=U!1$)4p`a^vSZekb6G zGPLd0ln`!NA`2iXgzUMw2_AAQQCWQlXXCAM=wrXpE}XQ$zmQ~8W-lxAediHLd#Zli zUSy9lKSjo>D>IW8Y5}dX36}@kjCfa|OQ3Ij(vZ9-x)^gTSb|Z#g*$6%X;rm^CRNp3 zkT(bB8{>Bm5X5#_Z3CFM)EmiDnt|+sD3R$9?g5W>~ik;fPYEQd*b;4?uelez)Z>%xu^`b~H8Yl()u4 zKMs#g`~4yn+F+J`OyFkBR}Y?2PDcxWZNnx3dt>!9?&@pV$ zzBv^wIJp;-j8l(W^jzMGVosaOyjPerWe<_KEIhx47U< z(Q(Kngj8k4*#$tvXD%lPd%GgsmuJ_fjAB1c@yBQCqCw_u?rGFX|Lb z)kfI6t2~S)-t)&@)28=MZ6YckoA9;V=grGlHiz@X{na2a7) zcwk7iS22TXB5;Q_^@ZTVc=@V+5vQ%9=?@ZG zhUw~#E?Lr{QY@+>BHFtIYl3|W;ry#~LM!7+c6r{MP7Jv756>tWV040;`S~vAc9Y^b zEWYGbWb(|z)7<1yCzx>HZtyA4!=xm^-Z2N*Xtjz46-f*QzH88y1NPC@OzZVxQTe(< z=4#GSO2yH*@+M2MdPcE-+|?E)sEF&Es;BZ}XX5pNCGf2q!OfJcMU$wk76B}-9VMBxZZq$sdnt;jF z(et~lOIA*EO*t?o+i54ih+!5$vr5JnJ%bkn#YHZ_+0kHLu8X!dO)a2GR;ko5!7owq zc5F0T{v;U<%6h44behE( z;X0W-33|lxH(Pk3Qh7OTHrlztC-7ZE9KRJ#)sfRx^B_Lhu(z}S;=zC69 zQZG;%@ZzH`5LVK_e#u{ZNGCV6U~P$MHFHnE4(*aHd~_K!&R1J=r@e9GJ~J}ZUtE zXaY;E`HM7ljogT|C@9v;o@GswZIi(q){{{~b#c-9QA6+~EEPe?X#zSp=gIj_;sS~A ze0Cbmf+;`EZHn(i@Eh@COpv9qrC$W4<$MiRTA=-;S))ty$C#cG}-RA ziokdO1-CJ%tjtEp??-|T90_gk;_5@?ItwRVPWkOn5r;k$x_Kc4^JUP0X3%2VAIDWS z8@y$rqB3erzj|_uk`SXs{y`!!vP*d3z9L@u4Hab2)clH|5QJ%4zke~$faYh1O7mXyS>f4) zQpalidU#%fBWye81{EnGR{z?-V1b#TC3Uz*ZsWRH>?;!exUjG8_EON+I!O+Q=KXgg&F#`tKhq-4Qv7 zNm8k1gTffP%QPla7syWNCW^CuKUf}=zy);aFVzn`tDr!UQl)+wVM|hVb)-`;9Z4uD z5*4uo@Vqg(`2eY{5AdAC$pl%T7Z!~wa1W@0T%L(ZUbk<#u0 zBZCNN=q=dw07X__5@SFK940(gm@0|9x__v7J2Gdu=5^6Un+kd37WF`UtNOTgQb>u& z-`96vFj=F#Er*D)WCsc?mc&ViGo%nv<@R#b3_3_D#bL65AX%l0K^$XyGIuR3?vl_bS&+2Mj z&~9);%~^SheFQV4_WDi#+QDc2)nJ~L?<-9A_G}xk+=<**nmYSi!_t8e{jQj{U_pJ} zK_ftOSkg-;P?U_@w4&^_V~!SUORJoata^NjRaMNr+Q47hDwZyrD>NknxC}QsDfM7s z^tcw14Xs8b`O+|40MoptjWxbAa}hU=s{1UI9WwAJ_1JkbP_vJq;#=gDMNH7{vM`_? zt_b(2T93SO{wu?h+&|}B_Ps2lZyBZqqn!r4AC0CpkTGX z+YZ^$G?3vpr7KqTOsh2~f6Ez_tiYJjFcvSl=#f z##9!Lu*aZKnD@6!ekfdwFyA~ql++B+axhMM#cmEGcNN{!N{q#n5f8y{ zO9E9=PmQbdyrKkQQ7qzo72YfkUlUQejFYGdigp}Cm&a>OH5D}3(cIN61FdcoxH>KW z6Zu%bvKWw39%&~PA9kl*Bb|_l{%nEdaY)1u=n8!`TIN#3L%Xhdm0nZFJFDDfdtIWjrLGdTzu5gx{nS~TYvW{oQE2UzzdHN%@-?{=+pS3o;tDIBmz zdsdC4vy3TeNjEPRV*ggx{s`v}pDzb@L_00~5lR!z{a+C+E}Jhre>Y4^);I$tj!`9h zJj2K?+*VTKQB@sr>G`b762$ClhbM20iIQNM*gI1c@v+At<5j8sKQ2Jn1waM|du$Gg z8*P*|;#sPN!yejY(FewEB-NWRZrSW!dj{{!y~LO!toH@?S_1j7DLtyVG6rF`@7^0@iSX6E%%_9XT*dlR?)@6Wb)tsGczJI3dAztc;=*~ z`H8S6M$&9m`U|;KpgOd_;pDh?gIvFa}q9tMzCEkT^&wACoQ%UxkN zUP1}WzhJ4fqMClnaCHVDpm!{UTHE*FHVq=I0C+ExSA&0I)?`DZ+v?S==>M)Nd|{mv z&!wWS!LKmNSp3a8hs{TE9ih8Le{5pc5kP9(359w*wcy%nBV<0)je6uyU9-Whx(=j9 z^uLk113WTuyPbfHN4j1)OPW&3Z(LtsWshEkrktuyA=BBg#G|X4gF!|-0uy4&CMRp1 z!#-HEK%FH_Z^WV(&iDZWz_0~@J|Aehqq=S%7pY8a9c4G|(!wB?xQIR$N)mUL(QF8Aism%jGSYV4dfEzztv>M9bh%!a?(#$v@qpUBKNxZf?uWc~ZK zTv;njcC1m-*_kxBnvAQ>J&-$+U9?E%VZi)Ov?qhzcS9tKP?R`v=(rVkAM;@trRkP= z0XZf8$IGm?E6>81u3z|Xnx>t}01xw}-ynTD(=KME^eShTp=NmR(^k4>q(3#<>jSE( zA})x1M!*U3`P&{Oxb%&!e>QyYKM*CzEH#no$rLro0y@zF{S_^#-RvC};mlyGv#H?n zI;pf|p{?~Jdk!{A0hqB!Vlo{+d+lZ&c-1Hdl?Wa@V?`&3Ew(!YU@D}D+Wq*<)d-Gv zAF;PLApEdZQv1cWQx_;2G*G^9{Dgl=F`;pzvBOXuIN>2|fhMU!*vJ-4MGEA3zk#Rn zWGp5%+?Uz5`YI#LH7q3jPxrdi(puuKos&UUpb+;xv{>+IT|7cM+otfwWh4f!hBbBc4TqXZ#6^xz^TQvRn6k z7CkTQ;3U1rnAFy>&(`rFz2EE4hTk;TPigf~w@?$GWT9}I>-mTH)v)sMhKiY5?Wd)< z+Yf?E&|+BD+*I=gTj^VDa;0ZEXH0p_vV@w*;I@EfD_I|higTcQYI!1=>%oErISuV$ zHzg^xR+YI(KTAV!`_=7g0}+(V3UC2OojVVP%getf+Mrd+mFs?G)n{W><6=6PCH-5D zV9JIk1PR83w$8Ck)WR)XP=xJ=t0nGNIw$96EtU$Pg(({2^zP-KOWZ|3cHpEkW=#Qc z>{oFMcyfk^iqgMof5DGEGCWul{2fRx`j9yBh)Jr(7~P1v(aKK=DRZ8j`t0tN);z1# zh%kAXgCV$B;YI>lFO!@%wb?hTOzf^qiKRC(;{jS+{+*dzBmu#uToG(LpI%HCAkF4{ zWjJF_`L|HjvI@#_VM7AEt_yMH1}8|_x^K`3VBdBY37qi*D(b$pvGW3CY&|I8KPuqg z0OQ~62?@S;e;>$w9X$J9KR25lrtqq{ZN*^_*m0&*4kRLz7+3nlHTN1pb)zPJ_@_F{ zb8f7!{Yx^?b593JxA>SG)``_AR;t);&t}5BBV`>;irQG&gFPFp0WH21p;kfHMUN9J zIbGU44OuC|95Ad+GE{o3SY9kw<|p; zC;weW#}A^WM;aSSkuY(jSfw#QoZfA#nu~mA^$3a0h)EbW0;t+fJrE_i%9_KBp#kg0 z6P+{gRDLkR_#Vy=fH7UKx&1QC)~#-Uh-9<=G_KZNpLn;q{kci+wL0N@N}P8e(+T7O z(8(Pv)t04y8BDWvUos!OKU0J_`xWa9FNM)MDusAV*Unf};{a2x_A^y-(K}w%Y zjVQ&N9VwP7ZE||qR(__aZKWc^$BN12L}rteMMR>Urd=w!-izhEWE>QdQ@b2-@K>X7 zZt}SEiM&qZ((1p(-=x6XFC!}z#{^|!`K#cPK^K5ZN(}FG;Aa6t+WeAQeaRhwFaLhk z4rNsVB@;*nz)wbN;4>LT^441MANz=(BiIY9t}Y;-O#c-A#wQ9F@P0*x)AJaSs=G;B z--UyxlE6l~C1)^$t}y`FzkzPG^Z?8enS1y>Pi&WN!4OCP2#dGjdt-4Kdf4+zf(j3o zzFpSZlFsD)N3Qk{x&_hIe)jPj;o7>5Q0olTUD!vfaUbH^ex1e;hB)>R({*2Qt_jyN zZJ7!cgbSSMu6^wP2$1w2Fcht;CAH*W#>9@4NAXUp&b7JqZ^DqLsj3~IDMNsf!`dLV z0F+y1I*fP~j^ms41Y%GJpP6g=;5}4>*B>{NTfM7VkLZE|WFy2re1)eqm{@gZw~#X9 zpuFS95}INy+{?he89U^s3fGZ&Tjmg843}c6ck4QFudl{&tu5d!l@j03y%t*2++Dyo ze*Frtc+(c?#eF`oknvliwhwH!Lz(fHf$A3*DqyI>*;pGa3ZJ65zE}kMc9004H(p9Z zfz+wi;92mA_Yw()Wx&a+w9)=tdp z)pWH)XhA4+62)-8^D7+)FbT(hQa#MP+x3WRN%0nirNrnFT~>)|G1>oEsj!pCxhWK&R9}d*3yiC4}APo8(i}Hj|Ce&gu+=m za?egL#flLr0S(cD7wYqbkft}qpC1+Tq2pu)QxX=^WwAZFE9c%}YUhIS71skWmj>oi z0*-=9Z!jy#Xcs!4I3Q%(p}ku<=M*3cg3kv+oFPvjDz+LGF<$u zp4ll5GzfDbJ;QYuI9QyVfP@+x>tSR&3JgEm%YV*p&4*;lUpV!Mwo|4D*Tj?5RD>#d z!_Y+gNblgY-`ndy^DXQJ_UHqGt+34Qk4*6?;5;rHEd_eUX((2yieq1S*llU z4V~i=tK;AtcqSJ>C5W8PIWWaeBt}kRLXnY9=t^IVhv@o@`jnZMMzE$I7&M6sXht*T zrwVy~Qy9f_HB>_k>UB_gBEULtT}b&(6JR6FMOi@!na@*LZqCB@@~R z^GmSl^u{!;Cc<_|iny;NQdZhEe2y7xW?TGINwqTwGMl;(CUUlu7HyL{-Pr&a)j<3A ziR0X?bEegVL?o5>8iSQJI$Df=Jb=>g7?l zAAsQuyF}(gQxp{q3GM`>0%v&D(@Az@g*1pX2#NUO+byzKAsfU<&MwyY9e zlgV9Fl*wnGk+o`9Zwq{|bZ`(RGexamQ_<#jqSjc;AbsFqRh^uN9H(6h%^8+=>0$dv zhmNcQ=>x0N6>$P&8f3dmw@X$`CjzKkhTzuuVa{2vzU#FDghR?+P&gwfb(GVNXO!2MZTpp82>uW%-O9tbAqB2w0719f8DnXibluM0i- z6*;8>A1aZ8>_{enfDK9nO(|EQ;FE{@55F^(Y%G-Ro#)Cg_zLZXz zlG}7HX+yjYX6oT9sC|d&v~aW#x`f%kLvZVABh7k&#TxKClkP+Szl#E14Ys*waDXcEYq*F{M-p^E(`CrJ|)f~IZC;viFZH}}4 zJALVbI$}>?wDddErgo>A3jQe3PtNLx(|@7J>a^g@{@Ucb)#AOS-g@=wd9C>vsqtM6 zfAx*K8vR1idmgL#oL_F@>pb|>`=r#n$?-Y8_P#2j_cyy93hEb8ULuaSXDJ zK$@3*Bcj(jZ;kIaU=7 zW4YS+(i{$iXOy>F?L)7iDqE&gS4{I-X~`X{QXiqk5MlDT*Vk<(Vip?d_8P;RK?}*o zi;UbQ5;`Sq*!&N~t$m~M2e0&}|HOE#w(-DBQ?ps#tS{cqwYT~ut|bfnx5Fn8EQGO7 zj_J?RQc;q-V`<$|!4U)|NAFFZLL_t=RFP3iN?eq1vmOeo3ecvaRDd;8yP zT~5s6u%L<_+dZ+O>ir8Bv9-(;QSy>nL3E*?z@VY!TM*od5+X_mb;1EhEyL=i!v@yg z52&{Twyk9CkDb(C*&G5E|XjFqNsx1cyEKQJSh^FOGnB z;uwR*I(C;iZ@RV?h6K4JH%78YBRxkf^@H0ybhNOwt%j+EL5Fc*87DmKL*SlA%3kx; zs0+47rd}+1yN|eq3s_N9J3z{%EtFh=`n|T$1J?&`tI}AOx~w#O+@FW7+KQ* zaxpYa=GMn*v#DjZ4pg0nWV$&J@$waFSn4mN-AR;?4A#Wxd$iLs^bC#Gch7$dyH za~;9=Q_pi`67+}?K}E=@A)eP!S^bN_k-;-fbU(%4tu4r`w^o1 z&WZO)W#+RS!RNB%d#va2djVr9?Msn;`e&6Kf!^y|?Ymme3+*!q|E;VC1Zxa9k6>vZN3=q!sFCa%Q%H zJMFRDwAy?=MfK~tdT#;-aKbE63Y=Unfu2H;);P-`nXX}JN9Jhq%>(XuOShx zZ`TX;&2*D?+lo!Qes5brsXwD;|9U@cWD*v?;KK&zLxqz})&h+I4wB(&rI|FLHu>Rn zOHp(Ea550yUM++wUXwXoVw6LHhlCH(U#7|jLgl~yM$7mqoKU~6_Ix&N-@c@8->)ry zoa4K_p6lJSeLIlmzZLgps1HPn>^kx%oYkckiBm&E(iDe;;=r$NEg?c;1)z z4j_DVU4JM0d42z!b+Ki$*1(VIZ6uGkBm57T?HgixkHs3l!vwePE4j}My&Jy|r|&tp zkIm(ttM%@a&+fzfuP(dK)1#G#C;XRtzwefhwClIIp8KYp8zaAu?Ux6>+ohS8kn2w` zzw;i?N4L*9`uFJ^q;k8j82Zx>FR`z+6rU5l@4cC?JA98f-JUCe?)_5F z17GLYF*fsO4BxjA{zqBQsoJcZ-#LcwQA*D~;A>;s<1^NGM$NY$`|Ab&rAF_08eCq(kFir;)g286i7zl9Q1i!b?ue7XA86%Hrg@Y^`#C#&PjGSGKyQdbA zR;Qa%gE)x?kS1L?S*=mAMB~{_WiH=w)=u7RN~20cZAgb-;@&AdUtyz>pT~{2abr9O z9&H{)39$Gm$;88R7xutZVr!JLlLL(VTj0y#A*NEXZt72_$h^~u+g@?sPy9|uw#0(; zJpXIh*fm(hb6TGk4ei1U)bu?UV18jk+JZrnZOCr~H^%|5Jtm~0Z=aJr47w{@QZF6K5?CC? zJpzsBe)kN&u0F{I+b^$%=@}t6NwJwlm*=9#46v5dDA93;_OBV-%Sactv#e7~>~qBL z-s&sjBV_w?rssG<_mRsFz;~;ocdzE>iSe3t{Tb5psGIW^`rUM_J1)n2qxbsZcOHZv zEPPXPbCk`|UD)joNv?xA?7Zf4^dE-KWgZEw$v9Ya%V9aqK2ZHjTgNMYZMRr4QaZJ zeEPbz3gwOhT5C$hC;ZbR9wy?J)dkSU34)zYi1eiyL3iOrSrO!(=gi# zMKvOT7+}jN4;Pm6_qv{X7n2e&rJ%CDPv?&y`kvZ0@>RVkVAAPI-=neRa=(KYuF_c2 zEf`0cwcZM6fkxG5m2NDHAf%)0xnzT#e^pYkLtF9eO8VMc|SG_h}LN@Q!%%v7R zC{EYF%<$}@-bvj5yIcw~3ZdRd@$+cq=H_46gV8GKiKu=5+j)lleYX5Dby?8!F`%nU z{h2QJ6@7h+sdwM=^czn)J2;Pu^b{jHd+dA_gZyLWm0nEq_zCqwV^ z?f2G2$4o+aT|CEGtVhB5dF&!)iRO7Hp!ZSbcl-Puk>j(;<}+sYb*%S_+w;wW|6R=1 zc}lx|AL@H=mEFkl|26i`!I?c#*XWaEf{AV0&cwEDYhv?>Ik7ddZ5tEY=7i70wr+m! z_r3T2dslUx>N=|KUHjDOy;s*>PuJCVB!agOBeWtL6FZlOdNvem1}}+^Pv)0y2|A$% zH}ex8(a3B<_Q=7i9QS@j&>>yYq45e-9$G>Fyf6808-9)y&m$EJNdyK`+&fX%(^zQX<9U(i{t2)3}Nw4#RQBJW%xCdER z@f%>TtQ)_gXKG2#8*H0V`DE7_)-E-%6gcJ&cP`7QVW$uuJ7T4uD&AR(PG|sOdkIYMm;h= ztl*B;gnC{%5}oEGDw4WD>XHB~0aFYNOjub5AdW1|Lpo0qXcQ2SNRxSXG5P+nx|Pn$ z=J5lLs0(WQ^`9ci8Y|o5^d?9Elm$X2O(^(8vofGFkoDNkDQJ*C`zM90N`LzM1a`d* zr+9C>$rtpkXb`M+p-Ks!x@9S;H zekix6SW*TL02vk*zmDWXqt%`w=$_l7(at9vEWkfL(R?7N?{>5{+2Lc$7H`G{pcD^e zN@JqCitDtQUBFm)^b_+G2J~tDh155?&p{ixIA`{_uK&43CYyZL;CR`D-RNWV4Sv z5uqIDy8KI(@9rP#pt~G7$8nzMcLfnR9YTd}74VVMeyEd^iVbFs9`%#zrqqICmm|cf zXh4UB+_KVnt+Mj)8PnF zux*(MYQjjYc3XcR+z@l7jSZTRfP>RQ-thd6zn6@uH{C#VmdeE4Z}mrBF6E@0M^WgG zSN+HonKJ)o&!M#(nWQRlo)We9JJ_sNnJp(6J7UG*M)4{+oeEt1L32QaW#DOrv;8MD zO+aiyl@Uaebw&}CF#wr)4|xqqm2pSq;RKt`-5fyd%j;CVnOI~d{1<%~QUPE6QE*xw z6*?dgZFH(scYNSLZiJXhs3EiOQ0d5Ii*|vO1|r-sCsA@uoHceZLk5IHE7O=@*08%* z&h8I&-MfgcUR3i2K6fQztRUx#Dv{G5yTyr1stAUH$F$P@JzSKhyb=vlx7B25K%zZx zs0dWMK=d^~lw(-Z6qt@v_=LA9RytMIPVF$RXcVYvb-+=@IQ0BZS}JdlUa>~a{@$Qv z;sX7Ie(g9IX8h*3VS0TuIU7?be&B&0q{;9fwnPWoZRWRq(cS7NhnX-}{gy`%zxTu0 zTBF5I4+jKkt=)ExW!X}J4ZTp=_SRpap@#3~&Qq{~+xF_C9+9#YDlbH5)2Hzc1M2U$=KF|Gk z8j%yRR-gwhy5uZ6P!f%%uV|cGROS{97&1XH<6NpfCby1}u3};>fHOt4cW7TgMh%~+ zh9jJJF?Wn;j_^9i7Zs zi5@hl)v1`6RizZIiIFMM&?jfkNnZ?Y6rl?-+bv@*Q8AuV2E%vuO(-8QZ>!0FIHAmD zFFhh3V=Z36qku@)4yktJT9M5)%8p*k)+k)~Eh+J~=AHYblJ-YP31u#wnHdhR2IbHM zei%175sTQ7;+V&<4v3n1dU|OQH{#@f_W}@$zx<5pO!V4UO>x+JuEM%?&&mG%VY(!L z9>LqwY0&amC4oW$wGs#ZdRNO zC)aPeaA1D+FY3~1H?kM>ZJhcjWVXVi>(E^{5lZPuXx}Yg9H0+<%U|f(p01^D`EX%w zacv8)Cp$`>g7(KhK5J)HgTELZG+a2$045{&FMs2zJ1i21pprXYan#8XXwq1@j@qfJ z0s#s8l!{$+bLH`zHyEo=sjm0{$(~k6X={z8y$fD48SE(9pI4@}pz9<@D zW2I#%8ZR;o?Je0;LUAiX(ee36wV%z)BJ7N$tU>1Z132?;;v{3`fL;>>I6+37Tvk~K1ym3ax`KbJb5U^VHF zuR+tAsJTHVHzAuv@M?r|CLtlC*?lUM;DF=df~9CoRZxygF_1cu)|yr~B^yexuLxjZU+5XjoVyiZR)Z zXTATc1``6-5`*!mMTg0C{0k(|5=yiPHeLjsa@jZGM+A|A1`uM-U4_;U`kT}PtDA-U zjdr=E*DB{LHIgO^Qe8_G* zIgUz`MEqtKf9D1sLZCP9=P)*$*jRQX zJW3VT;t4k8ZRz(pRpdJBqyV7-?_9Y#*Wx6Yy{;5=<@v%yQZR7Lx=QV0Xo3mfj&<<* z{^;?j^4b=(0%z6cpVICr@ru~2oLMRmlHa-m*V`jU+nwgvSqAf05oi;kM~N!7{4scW z@;C@)Wqw0799RCX4(9e4FQ+dzv~!I^o^q1=5Cwy~m?TPTW^*-kjvSFY;5 z-MorhzmJiT%hsW3XBxs*Oy@xZ?CtMsGc2kiQ}}Dxu#Z|O>Z20{5~?0Ts|A6 zKW;9P(c~ddmYNYN1I!$(K>|Lp$3GHN z9J)Nl##RZ95N2Qp@;wN5Yq;7+rsSS+Z^x)@CewZ{1aaO?w}uqJ+ys)}o=EerQl!eR zV53<*-n{wb9fHVi3ei2FrMeY13rdpfrJuYb+8a)uLoqUeR+yvy;ZZk9%Dv_PkkdOe zq^n`k2EIjF3uXYZRMw>`De)>py{ut~@KAn`Dw>QgiX|Q79bg*H9VOr*Ko>wkHx=p- z4*2BJhUYmFvto-qGbC=lWXUNwQqaSRz0%1uviRLoyb$h6eYLD>l(|; z3r{d}4%xVfJi`xGA6$f>Q&+J_alNYxE8Qyz$SQu$TJ#dSz`Up`AU^F)KJOeFJ6=Yw z-$PQ7#P`T%RvwYp_#Cy?D8jV~J)z7@j^wO(;T~J%bJG9>jQbhBlcs-=v(nLUqp*9C zjbTF%=kb^Gg@HAR97O6@V$vtBSl!Qz%YpGDcPHr#?=B~`>HC5w`kA2?dtxptIy$;%@3D8P>C(SZgva#2W~7M#S( zm$5fl9tsLU$?Z<c@-V^E&ODb8+^){or#Es_@#2x=-~xs z+Rt6CB?XmbmI9Zwhom^P_q$iGIg?J}=>T03J@UWbIk1z7e!luR7-%@^~ zuG8n|%S@{RWZ;ae%fq{^d1$5kwM>zUxBL@t$cu(MIlSs=m-IrnDm6~vX7}%F0uPX- z;ndR`zS7pkEVy&ia6+UpHNGgQ#}%7JN%RPAoK(o1tR@5%UecH^E6{iai?F9?sLkguWWPr=ao0>- z$uyNDNB;PR%c-9DQ{>^6F%{OjJS7LcOoppaLuF!FU*wZaD#+B7z?Rp_%?Mo;r#gjUY zNrc3Vnl1;h@HdcAig_hDm63=ANnF#b2-0s+#@J^>Bmjb*0t!9SO6sX+%Zl&y;=!75 z5j%LK)TC6G2u?ss*7Mw&p1!+Egenp08~JvA|DL)&H@gc7SwU>At9@Bd`}7O;GhC=aG3 zJXtR9DEHEsb&!h&BLO2zRH5sILwV-O+pR8k3N0UJ*XFy-*HE;{Eg8-1Zz$tO&E^dE z)&S_tC2kmEb{46wA&?r8Dn_2&6K^ce+B}Ti*`{yGe<{dG2ccK@EH0vlSE#biiqQ%v zvT!zQ(I+G%KqC>_Znimv!eZQc@$>0Aa^bhyZ}E6u8GW63dwW|AuR{SkZzi7@ir#UH zID?Bh{YDL*R!fYuT4shF6ZTPx)W1d-S4c*jzwuE$`BE_`ULq|yIHgz%GTN?zrVDGb z%<4!3141rVD6O zfT+=1=du`wOW&f@cuW%0#O)m-z#x_&;70WzG4j>UafFod6?nEy>5b&pmXyBJ7BH(h z+w4~Cs2shHr@2%_9-9}0u1d@JN>ay3n!8K<+$U~;PJrUSpZ^D8c^EKGw$ehIr0*WD z9?WY;fIR0Eos3kVjb%HZc?m%1nGH zmhp%Ypns9Tw2^?k{o{UrE4VBhKDkqdy9h4NjVx-$i-!S*V zOkhJtIYAb;@ zN>w1EhDkFwLBxlg?zWiKL9W$Az2vQ86k(Rn=~zQ7@-&)bE!c-GxU1`QDKt38!)q~J z`o5fc9zWnlfBcV|IXH<3PjS<#Qc2i6RRG@yqebx@-LD7@gFNG$UyI%t#oQ6U0g7D7 z5g2~haD-Lw+Lim z)O>uKwm)8<%xh*EUCOD)O?UEo`sCm8e}UAF)kR6 zyhKq&DdqGA(bTeODpUPJB{A0Di(yfu9<*@Y4- z*9Ucqlmlut_W4}hm3s|ZvV!R$erNDi6gMk@^4m6f6r&UAWwYAJmnMo!NY|M8?f+UY zM-0^%T_8eR8}gCYD;I1Ij~NZ(P?-Ngm0RR?-P^&K=M+I_7>Afk23vE{ zc=c+}un_2{SmMI&@X}G+qvyB5ELxr*v{l-gp^FZ0f^5LxTjPNpy-==sZ()bt%;j2uT*_AHgn>~@qzyklE^;it(3a5?d$e#N zhUs%6=foIvmN+4(#!$%rA%A5Ae5H3(1*Jnn{s%A!Jd|IOrDf=h(lNU#X{1AFBf*;@ zZj^~32q2lu6Pt08{)}XJd{wxsW)<4*u@F^3YK*CLAzs0y;MGDc^yUKzrD6#sV4a-s z0i?lSX*=~{4&=2#)Fv-ppn)tOvg!~XhE92ZwNiCNh3V#E`9H>>wBr)zUy+dX)E#r4 zYd$Lcvx(;PQ1Q*v{or%MYSNbnq0=U;6`lyi1|_VTtn@J8wU+O)Suh;sY87%|L#fD% zRC0Hgk_L{dfGcw6C_{wxSA-LyvP>N7r_kj4rZdPos6vW!@n+bYqVOPa1z$CXciBy`>2|6u@2&O+B4vy>^s3tn7 zVlH#?-e|2k1jyh%?&I=KbVWyxnkz9yjQJ{!CvoMx@_Y29Mz{39UH`OXYfnLC4#Dc; zvhWuYF)UfW5PEKckz?0ss*KguvF{8fGK`;QqQvr8c;{q~M%sDE8e@#*sHfn?S@a)k z5X#6j*;)ydIc*u~%I)QCMIEF`i`8Udi-@5*-cW}}fqydy+sbulXjFQOT8Uh2T&-1o z-3FNN0p%W88HI`$6U^b~aGTosiLJf1+>!wSNz$cF23+Jg7;)S0n&VDh%wZ~{x@Ntw zxMY$h3~*}-*~9X}tcnF&XY*;OJ6dLO-VDuzO>_m!o|Z$q*WV?yL}~1)=Yg@zl4PBe zXnysB>MDv-DtAP0=uBSW5Y%Q?bkN5Qn`H#n^@DMH&b_jQG+7m>w{!CjS z7<39>a3WSBJ%dTMmoG^CM_OX9txQraZB-%VPHL9M#Pa=5uoXA*SRUaEl@$vfLzu|y z^jM+5Uir062r@Aunf6x-!J}!sn?Eaxim0qWMXj5JQArKS6={ReiAem~un1W-)+LOs zJc4@FZhN0{2)tQ2^&sTrMpS(prfBwXn_il=oY+GaBfY3!7!ATv#^8`9S=g8crmv9Z z_n{cis+oK&Iy7ysjh*#8%t=Kp)Y zCv4xz-Issx?v}8nx^8e;}K>sNpsmi2s8DG+~jwW)>p9y~8NbWad~K z&3*~|7Z_I)_d$vVz6Xqc_W$PF^+}0#+k>mW@67z}x{&)-fAKq=$xra1HOFwu{z$Pk zaaxeg{OSY*V!BYycq7ef_P?8bns##0g(~>mN}%p)uzjMxSim5wz$UuMzN`G2>Ls`- zpWj2pdvEsDRmKknT)&5p029|qNXY)V!lyT&0EM__XA2`GlzPRTB~eOBiu!>~P*70h zS@@s-hCc9#3tQv&c)sMN+7cc9LvRlb6_oS-(s>sv>vx7>-nX3TsbnO+fabrteo3Ii zVIlr@Xp4@zb$reeYyhv$$9zr`wud=*-X3o+`GJwq`?2lM!w-tG{q8id{Z10­Hw z1M0;e272VA^%%A}F4S*m?3Dd{m+0MSZ>W7^x6@2R!f7U3cwcdLs4>{&5V4ToY}+&0CwZLM!Fd$v|=;cq_O6lmC;emLb>4XCMvF zk2^cw7^2si$=%z=Y$hWRAJ9U1VbEf^6&QjKQ!(#%^>5d1d{&x$n!C|*@X7G+;j@i| z1{>J4z?Jb1Fm0=sgEPD5B8lfG!270VD9R(N{YJ5+aJV$ng7ezt!(f!V_x_ebHtMKO5s)nOd{s&%Iy_A92BBd=dbEY6nB zUjN3s$}Njaj1vgjW+Jxt>W+`m1b55Bf+5pRLVW5- zuwr?}IaC*Kn|TpRmH*Vm=P?PLFoX%E?eF!eibcQVt^*i2_-g~RNx*8knVg(>wvS)@UFuf%1yykf7xiOytY zX6AEBOv^Swu*SRC$I$KX0`MqYtB^2pp!L&+-~s^Y6Rptz3@`O@-GG8~2RnpNDX-^ciVZPL*Suo)k41ELi9V2)F zY$tk%W<5s_KGkT8J3YAU*Mr9VFj5i9j6C^PNDc?B^d8?~L@!JaOWKcP$7^FR@CY!B zy4&owv&P_LYjalFN4@-(22;K>jMSzRAf)|}PiFy&wlhJgYp@B}c6T}57hf^!!(NNJ zq&%ihS>uEN08UV#H8Nkv6b;`@53a_iTi*H3#!oFSa~JzZn$wQt)|_ZOL4S#eAs54# zMTlHK$7w1X*iN4|Pd$v!pyW)PKRi>S;v&O;fNc9y1F5!FR_#p>Nmi;qH1+0tgE-F? z{Y-BULa8d^41TodQ&@q{q?1z9^jRuuAe|K$vhNFZyB{}{a6YVd*fO*+9?Fq5V)j_=2GU$n);K8@>nY4nMm%UH{_c z4wv3IySrM9v>|EijPmlE8eML8dp};RQMBy;-f>|D1n}QmZnpi|GBq{rM9iuCux-gB z)+i6_#lP1nU1jwBVDsOx%PiyH+Pq)-HSma^L%o*0^Z22<+q{C8a>F9|<9Mf1&g3mY zZ4D0}C*sjnotK>fRLS;h$$o{4{ne`i;mhDguHg1WZw#H*BUl5j+xq2QQM`(d3{b-w z*PKvlm#k$h{+=rsbcb$xSlIXY-~e>3+MT@Vn2MC|2(jVzJFUKBO)k>FHtK2MWnW?( z)Z+<09^QuOzvL;93-hXjU3Sk+#r;izv9DL}$MpC_D4?(O6F7;x#T9v==W{gXFpPA8 z`SpO^Ra-L^+gIsmNG!}dA})*fh8YP&qRrNsS*r~PbR$3?H&%;p^S$C>ANIr$;>ALT zd#K7EigC{412K zYYiHDX09%kY@P%G7=SCuJ!GL=kLZ3;JqR21SJLX?b5)YtdT_Z|iizs=zf z|8V-MaKn;q4NVL0D@HM;X(Tiwx<%L(D)Ov~k}pS;?AUa8TZ$!*=~nJO(_v)`WNcOKO0 z@hKlqA;9Al=x^uUzo((0IX*r{BIFyLnQ2|K4I<`JSN}iD8EVUyHLSwIDfMmbdaL)% z9A&Ru*xG3A7T`!ML)43wU;5`z1oWyrb}ag!f^Pjo=2~rXB9qI@sKUY#5~D-;=kfYf zCa1%8o2@5>=D&&5tMjL43)-G;pN&|eR0P`V(<<>WHb|A54L0xHdS|kgx2JtgB8}dr z(_fkY*6fMCwBK^myTS^;R6=P6F57Rw@Bsmgbtd9Fcd|6@INh`hZ9V>bIb_lr+o=yL zGm^KJ&1KZOkky*|{u9+}<$iT(Guo08A`OLVF;Zv%z;DvRfwNZBMzwDlim$+VJbte( z0o$`ZeNC4X^yHZy=UqRk`-UFzai-DBFGYDxyRCNLg{Fsg-Jkw$bJpP}EcRL$F3pdc z_UmuwSOXR5fRHMeu*ORE+P|WxMcs`*&u>p#55fop>CcItCaQ3}_33wV+)sWkCBSJ^ zJzGD>(wwFdj3Wa=-cDcrH@%+&^SVuRlRmntqbdl00swu)CBr1&d>-zL@P&&lFLfSt zpa0aVYi61LImB>yyqNR;+quxg?LK30a4hQ}5$lb0i5cYhd6SD1NKxzmtT3~>I$hh_ zY4nIdx6G&JeUhT)yH+u+2RP7e(YboBY`v}b5RDnTlnlDhwZUYvYG&C&@>GImTl<~d9!0Ky9 z-*AJP&D-CzSk(?J9*I|A79AJpY{js&m#>Q>#aG~r+@F*WDj#6D5Ui)4zmLddX0bI> z|9eu{PvFnA|GRJGSW^7w{Ytn-_1W=pEUyPK6H=AN=uB7_UshV0|B;+j<4?=24#~eI z3J+r_06^G)@JGukDGg1;f2-|Z{=U5UYK3k|AQ2y~=~lf{1BQ20#Vsc*`C-`X&c!Pb zpzkzK!`S4F>G2c^Snc;aflZtp*ezKu`&x5=;yjb?8%) z*-d9O9XUK!X_?t-8#V}MLLGv~NP!F)S`_&|_S#*WW21@m_*`p!qQ=Gav`6{6K{{eH zoI1%roJvNI9PVPJR=wxj$z~xrkJpQm!TPY3nJBNehrE9P^vfA#{dMkjk~KcCbAh(c zo595|i2f|tf%$iEZoW+R>s~(weopYc4zyYj7)>xFyQm7decoh)`9d!zsrQq(99|H~ z=kVCf6_gL)ZS0r&Has{79+khUSrSg=uC|@t_<9SEUthKuKyO<&o014_SSxZnl2|{b z3BDme3ZIS*wEzGJ>C$4tYB6+ll>WZOLib%*Qs^WRu>;Eg6)fdlgQ#%_3_Tk9>) z|F*zigDbChK5`&J+e5MY)XG7f1O#{z_s8>x_bfZd9bFp~GO1~Sa6|`~W(54Z8y35% zcBfR$lk3cG$I>%ri(0_Gvy@7WNusTsoo>smouZ7`Mul@O3#$hijJO8U7K8P+8=WK+ zf(dNu+oxTs=Oh656&v1V$**_kvzzPN-rR2VJGMhan<$*VD{K` zs0)^shbO}?sjfLOFmSgQI?KZiG`_TtXPU5#1*J*UpsY| zW(@(9DnRqa)o;;Cza2&ZFhbOmje%pNaXP__MH;tQV1PWigE}Pp>=(zK=d2%J>fIZH zofbYV3`V1yttZ~X7$Ikkx~cx%kG9USeI%0h20}EMLO9i;t)!WnWLCtvnK`9!5%7)% z>e>EcWdfWGD_~%NEbcxGWC<^b5v&_=7LMJIboE?DIm?H&NzDmdFo3o-QZAS0@m_my z?+ja-f4*B|o&N=7=9o5#8G(NH+QZ3R2?_o|5|KIWMw_@c01$r0Kkn|XwE0KZL2ZGV zOz4liq_4a8bsE}Bbu*-f-8SE_fA029c>I_NxT)NZy_<+UfQ8>%bGv(YaEoM#7MnT@ zHfwI?ujgON!XSnjLI-|e8-?;%sRvf3NNH$#p*IS$7blVp!x;9L`GslvkD<*ksn_FF5V!Q6pWh%IN2p*ySBYQZ>V zo)}J7=7HiD8-;Ad0ww}{PVM5eT@3yMj=i57ch3HbJ)suO$cWT?V5a|k)52y^w>0jA zzkJN)?|*QKM2W^of8en50}6UWMMcRd?=e@pLD2#~_s!vYMc&251?Rs!#8aAaXTABw z%i=Vf#&p#|X`}vENj0Amy-!c-fA6wTznTa;Pr5DF_OkqC%{qJf4c8#CeNX_onW?8V z;WMG#4W27>sFw_72BeQ_DvUL#K|-F6Y$SqB;%&miiH!KNh&HcQTPl=@a_Spy6>n4X z`yOZa6}aNcnF(sFq6#S*CvZwn@#j84y=>XVE133-}b@+#?_@g`gBS@;k zCW^~+Zg+k^yX6rkaWB<4)9yO23wKYK2Tg|Y-`uBb>A_eF)arZrrxY0oN#a3ne)*Um zgIoB7K5hV?=`Hv$L*HJ>dPr|a_o>pxkE+}2GvQ{jn<#qq4xg?jI6y#rkHcAbomYza zOWFB!gv%o%zJDhO7f`ohi#-f4h1+GcTv^nJQMy1f2}k&w1xpRo{GHAK0^msQKnNtS za7jk`r!;i)!9!P?6VoKhkzA!Se?8C)FWJrN)wjH%*#Q2f05M*474c!TP=gdslx)ZA z?6;8s2yjuD#P*`@kSHUBMMKiRw&HslV#Op7YA+!;txos+@)q^)POv1ZW=n}Lx5S5h ze3OS7XQwKDJ8ooM@BbR0W-`Mjs2nz>vlcHk0m!yLpy_d0|J6nq`e}`vy_5UzIj){B zLzfSxoAePI!2_s}K8%=}Fq2A&D)cu}bL?Rd+{me1rp4yE_(mttz6m3LtI?k(QR8o11HIZ~y8Xj;9oE=G)ereYwmf4RniMCQFrVn>e)3!&-JP zMmFZZ?jU=G&# zcL`Glv`KAN3+3>g4EL+U46StTmMSVpT%YR?wLb`E{s!L0(K__JPi(v3xKD!gc6x7N zW2^M~hvJ`_{`**(?G?jSmR%aX-LgGdchFRQdrUHPW`~Y=G6I zN8j#?J_6_fvipO;{S}pl+nYuQf}Oj=*k~Ds93&y5-bRP%kxC-hj3?z+7_+YxE@Hma zSOf9Q1s;m}{A3{i;izJ1_V@fz^nY;;4kf%yYR2=svVJi(VWS7OjN~Q0#htp#1no8h zEuE6fz8;+>oiFPg>$uHIT%gP5{Stzjt6Um~#XGmJ|3T+~_C~7v?q%jN_w!?tqJJy# zg+{g?!8q{Utown;%F+j7!9Rem(Om$yAn~h(e={xyvYcE^L zzj4@N8_#m7eGPg47H4DS)30uH#)~zVz4fiLuCB?!ot0{?gR+I;>@tLh z1H;E{nn#%^n4o#nu&tks8<2o)dyi=n#-{V8`_rD-s4wWURD09-4&~osbsf%I(Ima? z{0Yw5VvtK+xdQp~O0WOv!s0XgjN??;U-C}N@A{(W)F{bv~xpQL)? z%0uPL9uh`IlnWjO36Eq^D@^%2vTn_G`nO+wbttOnGkwW_(f#FsTKh^o)K{EBgo%xb zti{;z^Y``VqtncN?vD)J4r{YGX`m5&WW|#EtT%#?PuuALZ!{3JTs1b}e~)w*SGH6Z ztymD1xh-(FU&G3DXQ?Ceic-e3V7^(l$Q`xq$&m>cadEf1in!|q&~v=)i}SW-zg#X0 z;r9C1<|msv1vIrmgvwQEHY9u(o=}=*kU8&BmZ6j}w$Xt~w%MBlLwg?S;^=t{f+V`v z(>7w<~@0 z^mokFwp-I=^_1r1T&C(k?3A&)^v9D?h(L(sR2uM)()@Upcsx-vIr?X>>!kHsPW1X| zZpo|xjBzbq_rGyE31Zs0;Mw>IU%7R>ugDW}3dSDZ(}-CiovC>Wm0(kJzus~lp`p8X z_6Isk(2+ZlM+K=iql1hD`c$-{m4Nkh>ZigoojzEjgHkx%E62`G*+M#aFoX}++ux6& zTui2%q@P1Zv^ZNwTgSoK+q!Sv1eXZfz^@qX=i?=830A4yQ&mm*-{qbeth3J%*b)^t zlbzh9-dHwjyP6-4dzlkQil?mt(2#1@Y$i7W6#_=xQi5uXO^0EopXr@<)%LfZpEBp$ zI6I|5D1b9<4>+0SiUXE$2D98PW~=?3bVPKea^Pk8KCk!*Sf5t@V;f4kY--#;fd#N% z@z&LnvF9o}NLNBx&OE+qt=E_4)B0~eSLnA}ZIf20dQ^9az=Wm~6kjL10AEQsGOt15 z`?#L$jUboJci*LTa}Q@v=3g2%A4g5bOl=sB8!^7G3zc_va;co!GgBU~IUoETD~iY* zmP?6*2@;=wk+Jfp*-jI-QPFLkGKiHZpL?OZ=R#Pn_#8mMFo;tGfo7Rbxnr`RzY2cW ze@kNUEUI-dMxA;P@YbhuAVZKvumj+}vvAt`c<%_j4@MxprkiB@nVA(qAL(oo|GH^5 zd9nO>dnVvZ8C6w*xZ3`VbJe#H3r4%e{MkxTUo_| zL5#E8ov1dD`(F~GV;1BQGjcsmf4narP2CTK37$cF?RQ`9wtkw&=ldYBygxm8mi(8_ zW#$8FnG7>V0V`s)kVSMK?NkC$7Q%w+Pp&AER?VMk3*@7Ibv_c@y#<*#mr>JC*4gRa zRB69d>-rWJ++jxD&r{e4gK;_)d?es&W%gbWn+EA($Y}Nv{yc3Wkz=(4iWJ77fN7|mZwy8;x-{78Yq(f z4Z1}|b(Db8?Cv0;{+A$F^>n4+kcW8K$m9DJgMK-d`bn>)sJ}bG7p)U1ay)PT#n>Dl zM$xJJ)L<)HXCtbY-w3kGEh_bZczpj~W++EsaIu<5wN;=KaR~qG+7mS9g2n$5MNgN1 zM5ztwN@i%k|6jW3>&nj@v O07#1~h}DP~1^qwm{4{?6 literal 0 HcmV?d00001 diff --git a/docs/assets/images/multires.png b/docs/assets/images/multires.png new file mode 100644 index 0000000000000000000000000000000000000000..2afae9f6bdcb95ca04315be8505fb4441a621f81 GIT binary patch literal 530325 zcmXtNMi@v1U1AP=!5?tdCKv)abo75eT#)QsIQS;tJ!2CCzKKI( z!WSj3ay|BeK%^nY`g%9R#*`boEAQCEOosjnUW#%}Q+4~*ThLHl+E7;3P?lra=V$u( zu&vC27b<`#jQ^X%x8?TzIIc)ne;@y*OVBV^-D+o>I*(pygB#W8w>ft*hcDl~Yx%2p zlluJhQdIv!r#DwsYA00~-LkqFqoearXFq*^SZaUZWy~rylwD#vh@5i4hj0GrOlhp= zc#vOGql9I7*h!RpnC%GuxDg(IHS?;R0qlO9^Me0`X7u0RPgd(Z$EKYCm>)AMxMAGy z^%GUI{_GM-v$JDx%v{h1Qnb#e;NN->Lr3R>i~& zNE;|d z9sn>y@?~eZiv2TIg6xSC2KF!WC*G#~q0PO+m2%YM-%-+(Xz<8ryeRZOMWt`3VzIQk zJxO82j?Y;|EX&d@^@ZtK4t0O8>t)oBlW~%_+=lUaH?>OcC`1<9;{udmoBB>R*^;tuf@P*dg&=5~Ja>2HkwDgLt6yV<+$nj7fBQw4vpu5XT z5+08?MZX!&K4a8TlH6aXJNNWJvXDmYdUy#Wug}P7;7Shf3#fpzQT;K>_Fb%yVy z4(w(?8_5EqCkb2!^uKwm((U}U{{84(@p#?f_o3m)lW)&DT|Nk8emwm%w}u`ebVZVI zN(Qb(drg`xz-GKwCr$1!nBiFz`{9({s3ohiIe=;$ij)Z$G1Nf+cQ`Ndopn0 z5yty6_j~U#blQf21u0Q=BJ4E4&GKR5F~HP!m&V&Zw{rPJGAiccR=Z@~v2t?7q$3a* zO-a{$EjsHp^fcnzN_U{;h|XTGl#pRZLj`}KVBGFB_y>?y9wVimnxEwQ=D?MI?9i6A z^?T@@%Ke=ECA-O(l$BR+nRUbQiS&5%)v<;lEY0{!-J1C1fAzN=@lGXvReA2hPGbaAYNZ2-S`+&no`rXpw1?izm^+-?T;5$na04hjfS9=YXP?+u~W z9pnNK*E0w=>NFPqCr+Pi{PPr(+to(ueBlrOEueYxbqT_>N=3!Sx(AYU_h9nhC39;| zePg`ReaJ<_NDl1Jgc|F5AhJXH4smHC(i?Aci~u8FZU-RGOFTs$5S(a9m$V-ZrEBlB z?Y);5Ow`K??uo;5ohWMi?V;VfI_(qk_s?({ib%X1D3NY>nzK7RjFlU%^JP+US39O3 z>pu#{tPaEqCIVAjhY>CmAQ`9!~e$xMze9r;>Pa5xS{gH0C z(#B8@H6r>0^F+9|49UcBW;h6xQo5|M?Nc|KtnD9hN~wk4)J7=esVK_rqnM3Gp0iNM ztJ(t-m)Zg6u?BQhmLUy7?@6xHtLMLCkZ(AW2?YWDf!F;8`;%#Vrgaa_a5a zc|by`!U2{oGj`P=k5(0$bx9K1=7j#rFvkulFBbnKj5h>&f3OXQ+)-4UkyZ7R3C|L| zNXBQeU~T?QYrm%7$1eY#-W+E(ju&{UW8nyev>yWj`uzMn%}n2Cy~PQVu!CF#;GAnb zGQ(DnkQ)rRP9ff>-ME_?c-;I#T_g2o=>;r+pjmf2Y($GZuoY)T%SN`tbpgHK<-rUW zqUJI^yjWTH6Au812Rc1VYv-9u8XW3K=y={Lv$u0Nflml6RIB2dZ4{``{?<=DzTon% zhW}(2Kzx|+$GkSW3qE^03`ju5L*VYY!NwVXqlFOqFbp6~01)vjF|q%4C-++>8ur&$ z-TU(bPbIl2YC$aEA-*RL6fkVhslDtkLON8A1WFhMLLpZ(URQX#rUs|sl40DC0J;*5 zs6_a(<|)E^e}21;J;KIMZcKEb1hy+Ebb_8!Y9NF66aheC$(Ql=_P1~U49_Zg1l!r! zVFXoy=hip_Z3@cOssLuHX=tq0w<8=z5Y`7=eaeSu>Z}xIZ=kWu%9Q|xj}MVAW8V7O z`I3P6xqH_|m2RDIdvd3{vvUY3Dsl3qm+J>uV8(6D=yGy3{pxwXj)I%fDxc2Ibcd<0 zK%5Bk4Ouv6LNN(%ak8gFb>cr+xZ?VO(*mwO6qCXvSRpC7$U{@~v_RYjdl=iJ-5=aG zx4)jguf!72Z57?1-Owl9G_g5c9d$8Z*^+8Qj@{q?*Rj8#vzcyYMmOA?T3@tNbZ`)x zF?g(dwS3h$7X~FO#a~K-Il~e6SWDx((~r--SU7`tec@nR_>HG-mQXHsV-Ni4+3tG%1*Y@-Aci`ohlJfv?i zQ@>^h>&cD#g)$c(!ZgLw$OD<(q$44kIz4}OHfvZ$tEXMRPrqMnl{LOC@&I=Pac_4+ zzQ?7i>0nW-t<^APFgx(VQyI87c?BF3J1k?8R?MHDGwC|Fuu^@j4j&lQc__pgehj~; z^(x7fcGUf(`@(OJI@|MU>1oI|#(#gzd7a;nlFj-}pRqgdsNaXUT+gez55TwqgxmEj z*2}1^?ueQ;Kgks1*LdsP$kkU|j=@5`bl!cN7fl*Yli zf6KXk0k0?SFJi8FMFd_wSl6QgURNThJtY6WAK!}5Wf)SK-kZ`V7ixY?ix;xz|SgYXHV{s9a|z}xjYaNOJAZM z@YKy1xDRt^dEAE5AsN^|C03)7n>M7P|2_$>V5_sV5dX2&5g+edT#>Z)u4kWzI<+XG zS&EL$bqoRCgmJ&^oz31wzx|2GNy$_`**9G;WB26ZuLh)n(r;yO`J`D0lUhYn7t+*) z#r&IAgz6zFx5kw1tyC!#6(C{S$$WS=qTZy&=dqi+ySsl=;6|^alr2lCz$Q!X9sEpq zzWAB4(y;A4JDl8gfPfOX0v+&cw8Rz%;w;b1l>0W8yyHy9)^HkSj0Y7Wqr>N#uE4Gc zxhe9Tr48nBKSYajk!Z$vq?)V!$YEZdHUs<1{fk_ zz0395Dhw2=$6j22-_OT$K|lL7b5ZbUymZfC?YWeoda}@L_kgh8Z?V_JRYJy!4+f|* zJzrU|Rq>M8<&129y!-o^Ht6Gq%bt1WTDvt3cJ4_t{WS9lr%<;3x4a*&#Quwn)!{GV zbBx+dj9u<8{+d{LM-%+|Vccs*=jMzpC7OoqM>cRmygaTq^WAf+nloXAZ_F<6ZpIz` zv$a-pr7Gl>AL9_Fb#hxMhUFEGM+zxAPz!T!^dKJ6Y>CEjUR+3Pf@Ys!XPbsR0mV@F z&sAnpd)4B zQe&e;ACfs7|K3*v0d;7+x9+l?0!*1ESZ?QyQ)UapXGg+NVQEb_p zXSX?_UP_VcnGJL8(jvFRSd?4ayJ@(1SO6V|$tg|KC;jAa1;Q#*)w8A6qAOoJlOi~A z8@SR2HoLBqsGFqU3XXG2OG_KYTh}0QYZJCt0HrZ$V&!qGjiqsFj1yVFRRTjqxsaR* z%nJDwZdV^Nm9C7UNyha#*N-n2BC8n~h!WH$LmFb#ao?wLw_xhj@`S%i&gc%hKM_3L zt#H|}IQ|E)%lK5-9g-~@M!=QI7;8dC3JyYABUL{oVm+tya$gHVFmP9r1x-zsfIAB> zfVMSUXlza$QikclJDsJ=Z`m`w-C+6?3DxB&1dJO4w0{dL%F`n8`K~!B&yzmFPZ%Hw z9*qv3Pu(}2(C2!py-Mpi((wd~spun}jTg3csiTZ}g-n8v;Ew z1q#zQj_G8vdl=nVgO#OJS#L0e^QS_wo@FDsyBiHLYG4;YEX%4>f#4~Thga*H| zQo$M65g#gF>lJ8IC`1?fDs(EFJC9N{y}ULnAO9(IVt;D5>{?OYYO7jUP((yT$d%Fw z>uX5kLFI#2SeoF%#O#=Ue_O#Y;mM$wu;z>F(uD0@Nzho~>BkazFagS96kjG@s{o4m zD9VXc`^*Q#pJT+Kj z?k}~p*j8jJXJQ{XLtn+N{4p3OO>XanCUyuQ?nT|(nSJI6T!3LLU}~J&nu%@cwB(NI zp?+<<3k;(-vZDbo{U@sxzG9;rW6$e2#2R`e=cJpDresUR+L#?IQ3*r9B`d{$xsfc2 zP;{jJp}(<_>{@9Ny=gg87d_Hxp`3S}CEK;_5_|6+>2CN?ZOx`;_eIRxDa~uR;cLmB zStSgQGnO}0zeI9<W~RRE#qOc#Aq+o|Jgrs5h{IaQ3H!_Ff9<>^yM%x7?AEk|GT} z01*1CbN5=t&-oUipcDVg9^x1g%3=tDVW!fuv}s1?aP>R8sojvq!|ltzHd8A&>xtuj zE#n+33%G>fwrSmJQFrAo*|AXM!Ue|=OYev>v0>G}xK|hHVy*`-G>eVN@ z{nT-L+DMAJL1%8Xto))nZVf2jO<3sC+3Sv=&XLL+E9N3RZ%*RDaT#Wxm7q}8bBg~o z_PNqS;p~TjpAOJIMON0H%f{OEf|p|&F0167lDgTA(Oz^~(}wT(YvXgp)eNCO&Njo_ z9f;(@aX)6=c|@3c4)3Wi*u~IDAW$TcR5KiL0P+`NZpedxwONS#aNM8WsLSaqJE6EV z-kjGZ_x`NFzg3o*fix}C(}MKeDJc$L$6w*0aHeJcBBqzl#<#mXn*c zfJbkQx)U#YpKSl9t~TFz%lp`as*MRXGf^IxPraR7u@djmpeW@@zk2(T8$EE>=a2jD z_C5%p>w#Nm-s;4M>hC(ye?Hn=1AH|^jg*S6%gN<1kY(zRVAvXBkYC;^06ECT{Ve5L zV$_?jUerOxU7M`Cb3qjBpfZ4g7T}l67s&O;|2eDy2;$=!6@m6E7Jos_=M^-^o?Omb zK*Zb1k%#A20+}JS(K=7j;}#;Sc%J)aKi+d1QNW-Kx%6)RsEMKL!@waG23-FUU#m3_ zByQs9Rpi;{(u4vEO)VYu2V&j>0h2p|QoHrJN2rT59za@uA`%i;!w6^PJ%Dj1X)Y5U zS1WWN*C(#YQ9~I!nqD1}7*=WN&a_ZWoU{*feKX|*CMoK%hEqT1`{!!3;Degu5%2%A zy>Ps2bRj7q@FdBZmKzFzaL%9kD0Z0ZzK)bF;3@%d=OUm&yd9vcb0HKdi<{gvvC;|O z`e(jWBjcTOT<_aW%9M+y*lEI$a^%K%sA|snv#;mWi-!jWqLjt#-TiW_&;ry|yp4(b zCHDEYTHnU*JHK*Q>E35*l#PpicaJ#M+h5^7DGU}1eW{pa0DG5DDk}XVHy32$2G%I^Nhsas zS+OY111)h*&On+-$r-;Te_1juLq_=id%7TR0{Ys2Q@z9Br!m27H(zB;&2d2}{*e1g z1PS)%$1MAVqGPi3Hz~pG-MwFZIrPzz^ReqSEt{z=yY-y!+UY;OdE~jhBkjh-zMVg) z%PF`5*t&N}zsfz?6J&L~tWO=LC-N{nzh!@7Tc{;MEFMXU7Ytu~>Usgt#g zNDd+%7eY8fjAN7{1*@MW7NTfE)%PtjgySL4iLyhR3Q_`)cuV{Kl1rSnvfgWQk)ypx zBI*?JeH>rzs;@t1hE1_VBNr^*m%UH<)9V4Dsu} zdX@^jCHZF4W&-!}Hd=Pcp`fE?t*5a1c@w5(rDC&+c{tr+ntSVwoT!b24bFEhD{LR@ z5=0LUja?m)+8;LC-)ej2=y3iPXM`-76wvp0Gne*vWcTmYj9*C-zH2!I)w@H){`dx;A*U9> zT<@d`V*<`n9D>o1rX+nG;_8mnftx&TUJu_0?GAUJvT!-8Z zPeXY%rXAuHmLZ_9O8UK>8A@5jqhTnA@)MR;>YNVL7-xfoqlvnIw@uxjnB2YW+LyC2 z*$U6imB`D>lX&@Au9LZID%bJCgUPVXber4U-0Xd(_>?4Y$z8%#0pJnJT~p}`?opd9 zRNV^tfTQaYf#UFdXQD8|kg0jCm|^S9X$qYXooVVKgb9Ug=TQWupMNwS3AHWTjB2)4 z5KJuO$UtF7iP8s)fG|aU^O4J}?{E`<7lLX_nV$k@fq?}WpU+4)1xAdikSz}0ASwxC zeCl)9J&4{v<1ufZ9={KPd65B{9t=g>YTlS|bk_!saP(k?BwR5V#_Hb73qcmku^2WS ztz}7W5Au~SyT22qqPNHWwZs4Di)1_t*)c@XR}Mg-QHlA?I7K zs+oum(I60@?G(^ceLdr&N1vLV!U4}`d~|DL<>o0Hb|&?!?x`kky^J&eR;$ zR7TF4df%!8RtO@42D5A}!WZ=p(PuapeFS7#U5rOtL{p$+l^L2LLv65Cwog~G99s}< zjCyVZ+Cvluder;+B%ZlQSMw)&Hadu2%IWVa8i=6yW!L#Olz0y+ljqfqheoWdd`He0 zUzA8qDQsx4^&qRUS~W0L3){01!*z>J$~PG@o?8o}DfWTr#=vzdCw8AkwljOFMb5q( zijLaQm>l=3qdi9fDSwuWr1pMinrRQ)?youS_jM$KTC!DEc%ipJTg0I9HSS^H#F`eu zTK)jyG0xWgzzhw}ks!3%GDCb7-QLLPKUNA+&d<-!Tdz*f45Qlk){A=|ra7tPIB13w zmHg(DgZ20~)p8;@RH20B&axB4;I;$BcPI`AFo5K32ZstPHlL7WQ~16(cxj%2lk3?l zckVP9!c!k!@%A16Y9VojC@Pepe4}~<>#u6(`gfyce^;?N3MOlu#j+pKi_6z+cDjAr z;XJVl?)t8H>N>C|-?DWrv)ku`t*9%rnMG{D?=N=jJwD6t=2Jguf4+i9q2hpPR{u*g z_n~Tq2QUC}=INz0m=_7pK+(DB>}nkKdPTa(1?1VBVfEBZX@Stj@sOGi4NaPj;p_9m zy+xbf;jYAi9w!VX!!!4_aW*SK#+Xj0gL{8CT0*~-UGfV9fruW1%}hH5pe6h!KkUvX z^b>DvOrZCdi#U@lu^UT^s~YuwL`^z8~p#rjQY%XfQ$ttz)TOUcDn~I2BV`WjwCzzJhvTymRQ?2rUMi$_AIVA06}QiMPb0aYsCrmxmv(= z0d%bp;e~=rhAbPEPpdkcR{P19jz7GQ8?%!-z(qru9Hn^-Dfe~;)r=CWg*!j1wR|fF zSNu>8{iG9Fwc-2X6=5`l3j-QDYDQkLB%-`_so?@}#g(`^VLQXs3YRa2yN_s%UMAbR z-Wd@u{VZ4T|15yFa66sH^`z_f@S_j8AdpkP%P-q@I2PK1xJ9Dp{*b{c2=oXhd2j*4sK_U)}X z?wmQ)*_|prR8*uWsr~)gtl8fD8$mrn_m4k87bROZf90@;vx5gVKs> zaHE9j<)ysH?Zswab#HrZcp#m8IU3ABBV)FI#l(g!&z=^t5Rvs|qFJ}tc-V4-FRBgf zJB;T`n#0+Q5bBy_tuGHEx9@I3)R)WWms`EA@C%=khA)QLk@3BgSjj$V}B(wrXsL#?b?M($+T^%*AzCoy{8E_m$0iUX7#s z|GIQ$6)Xk`fja|6ll>XX>3f?}d%ZfFnGK851(50Pd(}*^>BOyr*@vgdU!+M!-6C)n zzz`o(E|?7V_FiiTFsMf}sDnSyg7L2wvpbv}Ne51R58s}1f2kF@=MwvNud`+6#=FCA zx5XPLrI4rbb{hVo?v|F$!~|W)lrV-7?tWW>M*kKUIE?kaH(uxHsL5ZnycMA(nkt)V zJfsZSQb>Wj-%gslcP<_!aEj~;r-9;%f#IWLS807gj+T~ZpjKE;h~4$aJaI~rylr9X zdhkoMZ3m?u2m~yyHEF>9oBaWQa4NR>+V$Vf>>a5@yFRn3EJSAayXRhN>jd>gjaBK` zY?}GEPnAX*kiv1^=9-%Ij;lwp0(;cZ%qqV+b?(T1l(j{Y@ z^KN0q7l~Z3!cqmbPDof%(#?a?9z?m`i@i0OnMD=;>)WXd8hjEmNlpuS9l*Pi;^(%$ z$yY2S1sU0Blh+m`i{jMFXVYAh=RDA3iy_3-I$yP;CQM9x?J#kmp@N6bE;TLuCdSrs zdVbSQ^dVO}YO3&Uk4)N=#F^=jc1GwKgyVUu{(Q|3v7Cv~mB7imYBpEfSfuCq_M{&# zw?n~Tm)x+9LA)ZWPYDyA!w8QVV`7JzRBe?oXm@%z;c?x=KwjxqxCSe?h5&OvAO9GZ zTWpNv=2pVM5I0ABnIS`)_cSGa*L$ygaI6G3NzGp*p~1G88u#bFY;HZ94Nxv;gC8h; zun>TN@<=*Y43nA4{--G|a+CmzHyJu>?2@WV!{>b@97G^b({21u7T<*GWx1uy7B1Qf z^OAzReJ!oP(#TvwN~&_i`<rd1Ep*Hjwf=vQw?4q2XZ1^CPBm z8x!FAgrlqb>mBKeudXY#tOQO$GZnhy(cBXhU-{zfG+8$bOcLCc@f-#7kD95NYPZR} z^N5F`)@XfO4}fsnkEF?-_Wrvvu=DrtJ(WDU;?f2~c(S<%Sz|P)Ep?FI;LuYyH(xE9 z{zfWlxh=Iud}t2co6)bczq2&XOqbN!>2%yd3Gg7`+@Ss)(HC_Frc29T-@>lLGc#v~ z-1{A^*&{jsTY4kbc7|i>(`P=0f4PRgcTWV$r4MnvndQc$;D@F48!B>4-=vhu6QAJI zP-7cZfE&0U?65wFcD&^#9giX=M++~ zr5W{&qHg@qg2XVnp*ozi!P#AN+`Cg{O$Z#kC+3WWbBY(nD$eyPTq{IzONzS9m*kt$ zY&{K)EiH+I3fIa?iADdG#x>UP-6Ns+8==uJe~tRJ_-ntMhS;e1%AZKF z%qU6xp^HA;@hX$b7l#`Q$s_IJPtIt)r@eDXGyI=t4T`EB_luO{f1?T8{t-Z4g}dhB z!?W=AsyQa2Zh(v2vE^3^@^m!};QIN2Irf@d>SbSM5DoqYf8#Wf#ITT%FD@(mbNuJ# zQ~=tENEre!J-}XQ%wi-kvv&6=v}!}TclDWKzN|6apg_q>Js&`TEv{nzZ9rJrm#OS) zA)&bph9^5aO{Ibz(*aalSK^QYenQ-}9r=Y30U1xHMdF*sXd zX6N_Mw{v3e?!b*;1=7h+RcJOzPRz@0mPf9WZo*F)%7K-h9p=%(u!pjJg^J0D4f_WY zSIXps3jT{izal#3JkGTk#glOH&Lb)WT$0k6kK)&q(mLLHkJWi9#Q_CHn*tU@11$w|-*e4!|x>s6n}CFo^&8WdNg(awfQ7%PBMu zfVv^b4QT!gmplNWJwJlsrylQ1Rbtp6(3mgqE5OQx1`E|rLt;=x<^E?d(!doW&>j~1 z&A(p!-BzJ`)T*8T`Qp!M*CB3ImQ%egxbhfvkMtne!>yxRWBLks?Mb#n&N>EGlGVX>-0_o=gf}8m(b{;b}|Ig-ZSdOWDPZi4P4?yE~mJQICxR z|NfmjAQT2WfMu^mq{t1?ZW&zult}xJ6TRP&uCsS1^czU%NdwsxJd!xt{SA}xi#drEksV7IMK4p*!tS6ES41-!}_=IuclwS5%j7v6FJW+D`D-hbn zA4K@&P5NYSO^An9D>Q~h6yU+ynj^?Nx~LI)w`MLq=5Ntr$o5nUpJIN?zg3<65gV0% zWi9{aRt8p>oTkIl_l{3Ag|q&6%_+P$oTNr>56`9~I>tQWrwDTC&nPRF(YVq<6d-0f zZzEqPvh*nzgBI9|H26|)a`d2z*kP&I-OCu5YuGoC#U!gVl$R;=w<8b6OA}qLKdMVp zdLjen=<$#>>P-e#E-`Z@Rop$XW5W6Jvql=i=B&m6Q_ zViDIzr1($TTjW9NYOWH^I_nJlDDkQd$rV-A|Jb%W;<4-#@bp2StNg5+Xm&&M84*{g(*4f= zm3Xo>CDe%*2Vj1x zOf<0&bx!brEAhyD?lbH`gke$O;Vy*~CBsz1gtFPEuz01V+*L{G zB>v(FjhXSaptqzW806DzsXk`KCE87VAAEy;<2twSM~jc#C8_s;6x65`R!DD1c~tte zNTdK?5m%dax8!Lb;(%?sq3aCsW;Mson_M@>?Vl?9{H(>1@3aR&C z63OvLvfb6(%g>d~Y=TH9sahs2wDDx?r_)&KX^|NS2jYZ!|VpSIE7f}ynEK)yIs5DWI z>q6p;z{(c(kzsp1X_(iw{AnExbYmFe3j5S}1S^gYrc10<bo!TW?}-vy)(+mR}8#Y827ZRR*^$causLLqu zh(AO8Jihh8f($RoV*ST#3K)YGXRVIjdtSWX5xYIfQ4voTjRS<+58Q`|75R@h&E|0; z`5^)cFi4n*Kf?xtguL?2Q8t#0-CdhD4-zp^0PNun#zUe$MqJE^XbTs6NKIZ67i_#Fg-;DQ*MW)u9 z3|YGuA)~ey+X%4$Cs*%43}P5KBYYFB+ETHZ&9evrS(kD ztY0tM^Rx3_DGib!+2^S&A0hp?@T<=ggC_>njPmcNE}eE=8TXA|Usns`e{OeM^ZRtb z^U>|B$&C%2{muRL`dIJUF6bNM^@&E#q&juYJ$A2%nvl@t7-L}be1jK1TxU{7?y3Io z*i(@|Ao;+Em+4QCeh5>@O3}-2*<~bj6eVQN%z)d8!rh^YGGo85ZR!O6ip3u1JRk2i_NM{_nr4sXalR+en-voz2F?; ztc{edE!|N~KGpLrj~NOt-i?`5XTM5>C)dr*g7*3l?d`?+KU)|322De1<`%Z*x2BvX zZLc5~39axoJ}nHe$Bx~wA{oMivFJ0OZQP0U)tlaOje>}O!!wl;;rqYl=4NN{88XJ% z7$UL=TjqP}bn+?5hj}E5M_-+N`QdooM`@SDoK9tD;dsG|^k`C3@R$2C#wZ$?yglKQ zbWzSRO;yr^VT*I>7S#_lSz(Pwi;cgsH<~sWHbQYYunntVL*hv0-X^WqvTm*67Fon9 zv@xt5aCOhCa=3@_e4s?HUhq;ksnJY6#j+o&BhH{76)$MU(Kl0i% zhhm&QVko60*%hJb!R$r&c?z0kcf?cx6X;|iF@xmk+2a&hCZv~O>9 zlzB-{!`2thxcOXs0Yy}nolCtzL(@c@pa^KI8Vk+B&6Bx59N>ch8R)$ZDeZ~L$(CRi zedvu@vdM?o0GVP8;EXA)e#_2Qnx|SB%6blV`&HeB>Y-i`Q(Q9Nd>D*i?p&hXu`vV! z!N$va1YbFFZHVM_TcmUKM1Q8t_~c|Pd$FE!8LYqG|Gr~!ToOXF5ixMH5Xo^-0il-q zW5o`YR+g6bBWC%U#zO)S^ASr$j+%Q;LkQylh(6vSsksZsVM8JtGaJg$?x9N)7FhoC z?9z-<*W8FH^-(p}7PXnLnf((y;Jhlpm8b;vq`1rY5xo6~1&y^De#EHWf8s*f){h?- zK@^Ycj5StGOt7^2HSxlURpo044FsN`1Ry~}qo2`@w=0n#_C#iQ6ISk2A3~f{DU(Sfzz8Tv z9OI!h2DP}hm1tyCG@Z7fPR3`K7})&Wjk%$k_c%dM(P^REDm`(RtKjFKKl9)cVPK;N zkt+axRF?y14JVw7^6`O3x)^Zs zWyGD@OI|s372fnKh>vw7Q@J9daWS%!^tj>OYf{2=fWN;#J08udQxppGNd2WZMIEy3 z40K6dkwnquK#_ej_N!W0Z6p4IamT z30wygzG$>qf0lEHpb1k!m*qG`Zic6D{xWUF~A(XeyO`lS-jknm{4(~odp2D_u9 zqwd%nRSrQCUh!Mn)Zo@l?&c}1{ece`+s8K z2>R%qrr?nEQ)xxx-9P`#Z>dVf=E{f?-XCqZi^StQZFEH+ICf!I3z4_VhG%EbVBV7L zeES%!0rd0FdMntdvpIcY7;DQlhT-u-CPuy~(U#3-drBBF>50v;VoZIcm-Heedp5Hh4aAptE=^G7i#65Nqk?17q;WWP@0foHQg>`l-DEW} znUmu_4Er;J>q5dG{VOU?a@#0U8?<$FV%OUEIL-uwzOOtt9q|$C300bDdUuYyVBp+T z6k4K|yez3p2otFT|Kl$dkFRz{`S0sqn`4O@!6F&VyI z$)fA|3Y2`aS!HzaW#$bSNkxMO=2`D-m}VPETStR^cndiFZtY$~9xGhLD92?SZ=W?= z=sSc?ZBMdLain_<{N2(5&p}wt#8>>-anZ_e5HJE4)xWTFz79?3V8}8`S<(r^1$7p& zb$?b?{CJQ@*Crr5@X4&_>EzOiG_y1`%gyGhToE#a?n;nz%kvODV=^uwA)$i5hI&_a z_u}YNTz-o-c=rJ1W**+ubC|tWSuzry6^LC`j{fuW5k*Ddikm=unDQ8Z$KxZ%p%(H4 zkjHc{uc9}72)l8sxT-`4j!GUIh5-X?2i z<-bWOu$93Pt58HVi)c~&l%bw{S}2OCVw08SW|=ix*Zv5E)bDAI@^=JW<9pk45OIfS ziB)4i9mEfrW3&P^1qd+gT#091u)S<@wI(&32LeFKbJVXz+PTCtBDVXfc&-_fVQJ`7 z682pjALDsxDM$iYlPMRIgX*Zfc>69SnSJij=`xCs#wcE5X21z%B&>__Gg9s(W32kW+rkqf5kh($x5qZ~Y83Ra(u@`x@^>nh`0I&0x+Qa%N z;wiCZ-zAB#fT(*euQN(DsNqGW@+|vUG_p4%(OJZ3B7sWPGJH|v7kW_-FbLEKJhP7< zozGQegbUSgk!vKme{%&fxCLN_5Zk1<(3swL@q+rAl7hUu3bK#`#BpjgANLm$MXBzc zw~+M5$3a**itVKyko?9%Ek^K$Y?);88cdJibi@dAaH{p5I@2e)BD2z=IVNzux}04$ z_hVuBL7m@?a;<7r({!EPh0MHZYwr^u`A@-hAq9L8b1bE9*|FjijGG{huztJ5(%GI< z)!8x3XLWVSn#e2B7~iA?C>c3m`W_N?k0cXlZ$*av?=D@qD?$i4i^F1#vrF(M7Y*wR%f2;|HCIFRWaf%6gTkDe4gv-&}W-O zrG<^{n$6F)Cmt3k-K`n@XhBc{jpn3}%5#)29?lDiukbEwuzi+O=c@??=~NiP$KStR z=Tll*dcJn}V4cahaya7(OujfnnYUG#m`kY{y$(3%ZtSs}vqJ@sjvW-`74C#`q2^h> zH@Z!)yN|G4YU*1+95=o0T_6#>dj;2{*CNE_!5oX+?tJ!AXls`}S6eFXy2#Pl>)0$C zL8MP?Pwh(WZl*WyQaRdTZ0(sa<%QFb=B;^o@AGG%VN<#FbTyVRfh1k@6n{2tM$@bV z6*3|2ovMU;QR3OOVP!Q!tjZgpPw(l$pv3ANRa2`RuyDZQiOzD3{?Y%YXB1nYk`FDK z9yAFUby!t8aQl~||DOfe*(!33nc3ZVsTFM)zRX~z7s_n^UG3*0&`0Zh3#C6t6oCcv z!wIz_6AMyD+gtW)u-3OKA8EB7O_m{+S5>p~wIUm=KT|^|_xD=H@)lG~wiBdwz$&?S zg?_>9d$=yD6WVEfZ+|bLHxhbw%vDaNE~#;FsQ+Qrvg6TU?bFk6>0zQ$AvmPihlNHP zzBj4IJ^)^m7?!iS-8DN?PC@u+rI-EsBigZh%6&&@|L)fOBHFojNVmdlU11-qZ*U1w z1{-I_QAtf}Tta6vjYo_zzvt%q3cu-F5f2rVqCE;@FFiVgkQh26%>^Rn5kP3)-gpt z`K~Ml0?hFBOY`c5pwB6uYfayfh8#I;BVz@5&W}!NQ8hK zn>>msM$#)@CO^xoQ|E$t@3r6qxt@v@8m-GrKC^UiWSETq?@U4wMHH_MQ?~41R$ z#UI8M$T)co)oWO~4Mu3aGu^=Ce6fP4uE|48ac%V|&ataph;S4ICBzZuX8v9zb$fp% zw0#fe$r{dsR=>8fX>ih*h1{6>w=9DYx_|rXT!FxMe$^)OSiYA&TdDeICC>)GJonUl znch*Hmzd>uv%NbZ7B#7Bp`Mt4!X?F)(O% zlTv!hq<`LUv$V8e`@>S!GpJk7bto@G2oFQeHmuPU(DfC8{HH*HChB0eeQ?nGvjc&J zC)KIAXoydjuN|XjNAP*BP`#ijBg^u8bMuL%nedaPtF3VDdnTt*u?o>Z((nCok z9m1EH7z5$WOEg8Fb(9r{wB;9;Io_qDew6CQ+PN8fIII=kyBsf0RwDn$7B0I&OKnHH z>OwhN-G9N)`S@eJMJ(IRDOe)4e)3zO%H z1epR}0>~s?M>$_mN6ARCqY{wpFh#$9#S?Zvg9h~CI8Tt$uYh&Av_VlYhF_dX`0Kkl zH*arZGPXmHF~MQcME;JLo0BW=<&H^`l|jy2kEK3w5_!AguUl#5gyz5XzMj&u(&x{g zGb#ehw2)L&6HApp2m2g#!ISMF+~7Aq#0%H~-(+8tfxlGh_=`>Si+9z|H=|JR5N}^^ z?<|Rxjp=^rro*W|BdyOFMzUlROKGooUhVYQQoAfQ#~zv$yRE8qiTc}G(*nJCQL*%r znJZj(?s5_e*=Bk*mh}B^h8;MD&6T*!CEI-W?|zk}RY3U9>^Ng2Y`b0lAop-DmyytJ z6t=lG(y*WBBEZ8mWyMo`(p&3uo7BS=>P^g@DV-13Xv3Zh^8^Amn-6`~m4Z$7qWfP& z!ywW+H)P+!Q4pPxoY7Cu6uhWO0sgPL`W-4h`!Un7MFU-l%5^Eg6P!v_=m#GewRd;Fn2WZdw_65Uv;-bg=x0X^XM#}CGDnxu~rgE zW^rrR!ly>AtFN!`;a$A341RXQdr)sr>mVj90V)@N`8g@yW6g?3^plnRl2*taeo4sV zyL^FZ|1rAE7>tI|_eCz06O1fuxyI|?zDMQ#0eY`fIc!+&qf>{)is9ORjWD3n!t5vIOv2a^zx8|7fN6_--e`$hVU`%`JOSS1zB%#_ELTGZp6Ym zRgXV`sk$<2qnBOl?1NqJVQ`a3G^_=5g{A#0H+QZ|YS>+b98hY6`E{KWCkQ7v8cI*K zO(6c%Un=eoVY%wW9CAuTUQ^ZlH8Okzc9eyuHQY;CFp(8pN>cAZuhUc?BaYobaf-8x z&u3SSdRVFxJ_cOl5?^YFX)L*Y>&=>jdhSX6hOPAE>Qm5%6h9$dTfTThyw^L*rOdhR z>Gt;Nc37;{0`duu!?0AEC@r-EL#2*JnZ^+ryFWlMkR5_5bLxX&x<79IL01hlHxLa4Mt7$g8!M}>vw%glb>~pMlgV zd>mbUX&M5dtdEYC&OgG@hhIG75Iz;+n{OBns^ z6ReyI)~kk^+Q%XD;~Isc5?Mz_TZ>9{hM(@OEal`}H8VX+qUGf7&kQuFg*`pk>EBL~ zHj0Rm8_%A90w?$%_0$RqR<1KIeWfR)fX>Wc)Tz-J9M({^k-IOig8h~8W=YX$afHE1YFn2|MbmCrSflw*O!`3C=zH42 zg78HLS3|ZzXOer`)_u4$6QQUy)%!vXA%~?tnt%c^jq+<$@|*z2?r|tKms#^a`@80M%NS@IK~X z|8y$WrOGPC_*eBsDeHn^!bj@;y$+F4)}xOj3(Od8p#dERU+w`B zAxB;xt;w?^UMOruydwh9Y})&qs(WVi6%Rrx_NX?3TvFt+%lBZwq)cUYnvG;IpeL%6 zAw^Ro|1?Ez2xAH(0X#&Fn zI@Sgss^&1KevfVPeFr1?-*J!ayT$o#)I}8G6DjD*r+KqNk4pxS}Pk-Svbbmr4cZhD(F_ z{NiHh=AdJ7KSs|!(V&70;v0G(_57}#o3yS_N1i)E2XnqNy-KRPuZ?sg_D+UFR*Z3$ z+?fl|2nBTK;@`dkpz1hj=I9p;FuMh{2?~Dv$W9|eLy8~FhO8*{?libds26ICa1K_V z!{4gBXg{_32W7EP|5~15eeIxrVCiZQV*z-u#i!j(__V(cWEx0Mc~{YX$Z?@uebe%7 zVgKd#RlJg)R5dj}Vw=9TYGC}kF)+yY@$&SmB%nn<-I%Ki$Wfr{P1lpyPel&r7iU%v zFfEu4YoF(*5-QGE4x9%4J5~s2IxzI%%eAE*IXV2gD|7Ry;M6dOm@*h%6gdYj0$Jx> zd*p#1vC;4L@zbaJ*t}orO|o=aU?CT}(pjDQFUazXaWaT#;~Pq}vT4~q<~aQF$~Rf? zT%N~pQkVC-KhF*oU2IyJ*bPkkxsfkJr`9H{6$9^FgVbQ9%>EoHXsUYyHgh{&VaB<0v(M1nSGsr(AS6%5^b1<~H zD1MS%`+iz#+Rpg$^4#j>=aZo2wzat`$J8lE?X0Ljm7N^F7XC025l3R@P5xhLdX#O@ zPxqrX%+l(?XkD1dA4cjo6eUeC^1$$K};N_ysu-bztTAZdQH(tN7TB8@E4kOduC z5#ii4zbM(_VgFxDwWX`<26wM?B6ak#uE#`eS`Z^rS$TuhTP&WM!bMUejB*@*zUh-=c()qU98%yyuZ`NWm>SsV~2|Y zCYBq!Yz$4QM@Zo~LlDwE+#!VtChov?3@g*e>jydjMn`9ubzGKA%aDl|u!By#axCjC z`WpP&kEULrUR80$o92G*d9~{+=5$cS%J;jiMAP92o+Zr|)!P-?O-=VNmIR1Q2ZkY0@faAUuJUXg(nNG2=zbj9_J$X(C`oy!uMOWOU zCUprB4$-CoAwF4E3hpWY2TqbXRwE$P>zBnr737Ji;D1Z0eGhVNeZJX(>$|u#RR*xE zw3p6_-p8~3pCk(5mkT_7=yX9`xbd3XIW-mFkX$IP#H~&qJh3$<`uyx9` z0D26|cMPZK55=mXlLTHo`ogR&U-W38;cF)g0y6);A1kU^#u#HkA|WrMeQ4#1&bqFN zso8kgOdvPQJq+1-u7reFWf~e9YU(&=1oA{7*&#qY!7GqLK0okicNZN(LQ4YJPm%f9 zAwfJ@W~he{(dC{VT7I8vEQG8{IE9b>aa8q{{WsE0&ok}l*t9jssYrztP$|#Iw;R?dEFGnCR4zdn~qGPc+M?0>rwhM=*dC)AGr(4CKmULaF8 zjQO&gLJed=HW1{=d3o5t9*6%vsj8om9|0}Et)?{Xd}{~};B1ePj!Br7GwAE;>gs*` zsp5)D#+-cE-egbHKZ1`iJ1@kk;u4Wa8|-$tAv-cWoG|HhE%y|vK44gfOZ)!qeNanF zNVvcV5h?&xIzQi#ABx?yCmry+X6^;PI8$38JxSgc3&!2s2AnrQL*&w>Q6b@TaMEyo zV(W{KZwiMM4c=jgX7kQdDm0;>$2LzKBHD)`xhCH+`J&;F>(Kt8PD9{I;@Ilh;I@>0 zmntv%{$ha0E0fb5Aiwv`O*yk?#%y3<^tDXfwSUyQU5+}fe*Z5%{7G*QQ9L>yQ zhuPx}{>;0n=RPz3pfdWpyOcuD4PE7Ik%{}`&Y5&sjQF5zfMi?7K@arnUxqfJl4W5fJPPbRX+YEmi6Ij68;tzMm4%(F$`{U6U za07lB4re@p-1FJX`-a}rr&mvBmz;mO6$IQ@$oF%?B3ah;a$T1VeAwf*4!{9puiKta z8voKrYxj#&MNM7ty9_Jq3l!N&VPYcGnE=@se(DzD9mEEzAo??~ zSU(1d;PZ@E3jYq*7Eo9Jy*7F>l7yJoajcxs{xJQCL;DtV&|?b1gJ7qt+7Uh~>-{l= zPP&<-qQ9*;{af%1VTZ@zd==t-G~*1=xz*gkE+ zLM00Mf$9-|8S`hu@wn4$uU$c-wzGfl5eXeC0#{D zuokKSewknGEfGY|hGb+ldM}zC@5I5MWp2dV)IV$Y!$fPtqeVg1YpBKM#TU*Nb}=|w z`{SU@2n$a=2NCJ|pOdOwf*2P`u}dmtWQF!grfb3mwtNR_o9F{Hv6qbPgM-krfi{>* z-ZN-0Bw%av(xpr9OgjarYLMppb@r~cWu)ToY)K$lpld8)9)b7*jj?^7NCg^bYMOEK zb$nvQBMpaGg~;$L9+d9#y}8v|x%j#OPfxAQ&B1myo^ZBiHb_Ja)E57kU;1ku2hXCv zWx$h=5XR`!UVo9pnXRY^+QEdEkhF6$8HXJ(8Ll2xbG;~fPqqyX9Gp836Gu?{yeKa| z_rrW5HeQxwab42!XK<22Av5Ekt6Bnrc%D-2p6#Ozvx(%TrrR(YeiV5K;sIJkIgTVOSK5O#Fx-K&~6~iQR&e4NO>P znYAIziMGFP7-VX;1U?8lv!+J9ulIU-n?^G`NG7<#Dbz=QLri+|A_rS_p8ybmtOdnHKBjbgI z=B2$J)cBdC0@aJB$4YaUn7JKdnnwP)c(5N_ga-m;rKwrV57^_hL9d}Ly(D3$JM+TQL{LL%(dz8%lh5Y1`aw~l$yBKL zq+F!Mf0$FcFP(-JZzCft4*1s}e|`{vI;t&0{zIrlEhCm8yq%rp59MN8Ri7sp0etG| zysl)B$uO$=fiG{dNw+WbNjv#~k4Yl6jf|{_9F8ZE=SRa1qh6I+eJlMRX`-&wRVPJi zg%VsN+_3AP95ed2c9h-t7VH4Lx3u*)d6IIPLSD}NjjCD9%@XpW`un33wgIg5Tl+TC zYIKWcX;4N{fIR8-Uu#eH5tfYO7~f6+07t0YV}3S~qnZX+@K8wX$ux(C{~;8BxeoOF z>A|kN_eHfwp{oe4JelqaxvsgQYntlp+-~&DwzeB~8;heJS>&Nx!bkk>mMJqs!(e!? zoUNhK(oUDlIr{QtVH-wG_4S`ruc^nkBDqL1gqXJ8hYgkBGem2U41N7ZoG9}01$Y=) zj)yJjO~AEo@80-}>qjnsY*OuKd7P9A+ zVL!G#8WUxFpmNAO)EorhJCe60i%}#pC}{J6;3;X&>5$LnIk`;-jHJ+Wt8dO9D^}uB zwG|Sdr}SZu5=8Gi8a7p?SqkJT1t~);<_1#}{kU#A3MfJ1_?q1! zzdm(FfIrm&kwW|t41uI!&N3l7*5X#RG}T*bF+>jBsQMa7WvB>7HtbQ ze%7360TLg|hEPrQ@Qlgg(1ZrUbi97Y@k5rfPPDzSnQ!P>tCzbVeA8XpshKxAHgDTy zrOxO8nKLitY^WB{e0C|ng4z3KYxyAitaQh8{wEMH)7qQVIz~3{ZP=YPHgQ8nYD`YJ zT{B7v@$_txI}eG#t}gD^IVTIc*QEXDzpvwej(YzqH)8zihhf{R>;luoJC6Fpigm%K zC>zx`GQP-)|8!x45ZauIkGqTBZ)-u^2Bo43xpUk{Er@@dRDYKoCwvGnj5Rzz=zNh} zGB@*Y>QTd}oLO;EDN8td5Xig|&(%nW>s{8HL06f-^JO%bjrqVTt1C@0R|3T>_T~!| z-aYlp6&vZ0W%CP;E&L$(d#?4XIuqukPzl1AbtTX{koWfB^EUy>cRzDB%zSzLhtih`6Jz({1PKHZs9VF!55j;=f*k@U` z@{g=2tC>eiLBtph3Z|759}h*r|KUVOcNe0U{O#e_XS3cC^a=@H!U#!wK3!~AchI?l zI9MdeHV>dZKQ|1kzXCclQ^2kgn~s3?I^2B}nDin1$_#+zU@?6%jh||p*;&VR#Y;Zo zGFW&Z5Y0#2>cT5sU4IuBN1aqzxrv!#+$fTtU3x?M!acZbt-XV-rn(20h?j@b5zn)HOh)jw66O;Z-)Ewo*&@c!S2^DjFQeH|ud!74 zfFgNz2zZJb#?7M3=C@;;dwbtj`D^qvG&LQ9;+Fe*h=P3QiOG5p@HCa}hV!)P$g0e4 zL?ZrKAIxZh+Agq8wqCtDLpaF@!SSWPF|4NEM^zU)Uu=PD|5Co_sBNjFmxb+|l&GQ! za6AE=B3XNP=~b)7Y;{2+f0_2aL46lVd~DwPLRZ<^i;eHJW>>-;adhT}f*AEvK5yH^ z?7x2>QY2uphXR!YVi!qn8%uYKTswwxtXS`sz$^D!=(I*xb%jxhluqUutMxK5)l2@|Q zBDB z_&alJuC}qUF+MLHOJ@RhE_7nrC9ok~mQr)9$md{cmKyTW?O8LhnRkn2zC|I?paQ|4 za3mc1L>11x+wj)ZLETz7Co5#F%`L<=k^(A z*RBQE&`M|=KtXj1eIGP~3**KRg$ zh$5Xm>w+`0y0}xSCs;U$@b*X17?TY;DM881xQv#)0W&jUds9Pag`_IR+E5JOy7a+( z=SsR>#wtP)eF~)`eeG~>%_=7hw3@&P6Sm6ELb8bb{U+BZo|m15TMGHgw)CKxjdnkc ziir!A?=50$w&mhIN^v5lVdhL@t5aa&!jJ8Lni(~r;2gH9ncba5`9xzH;R>|%+ml&J z=;qYQbo=&(+m55w!R@!}i=(4|6Yn|^Hq^NSO-x_C8W3(?SiL(;XFeSHU&`rp%e&I^ z)cYq3ba9e(*v$XS0^Ii$#a9e!LO-twi%F34@Ph8iGJ-SvhOzxY-Kx^WBEz$Goc5SP zcY&NcwIlD{GXXaHzT8}`6yMlqA4lN0JA%sZS^BT;Aa{xg7l?}RTuOO? z0V+xdRtX#T!&@?b&B5cMI@Dk&OQf)!5VBUc5rt=(mMCYgJbn`N#3r$dW=E)|*iu2E z#j^&B@TS{BQB?U$J=s1l-sB#vFFjN2nx5GxR*7nPbDC8&7B;UgiXYd$4ppE+prGz% zS1EiVMlab-so&lFGz8MjZ#119U_a=KHD3Z{7$J~2nUf*Ye@WSz4W7BdycS#%S0m)tWW2k3+Pk6VMv8AXz^kAG+XQaBOZaWCo|K1XV4My2tw! z)S6a;+Y%;aeUp;eldCm6BMt|&bz%1XmhnHU7>nDoHNsTA&_KWKztT-jfos(Lx_}(b zrw=P-yYdP%Bn%RjK>V*e_;VH2oK*Ek^VeK)G2kgYSBQWoNo!CAV?S0$-=Tlw7Q073 zt&`(b)gpPI=bzz^h z2D9a6)>O_g!nOjmvU|>egX*n4_Q&JlzG_;(bkIbGPV}GhcyM zeN&UQNw=G_^?$EWUy)qQS}(eVtAIUydo3a1Rhcz!t7fFZusQ(n^X7e|N_dsmY1n3+ zFW!v`HF;%X5@*P6i!gtCsFg8V{H>g+-)9l(-jrmNi!*sWU2Frrt*j&h{M zTeYSHvGp_C|{8w4aUEiB}7!t4lwMx~UB|LjN$*%b*_MD1bV-o+im#w7SD zFTBGRmUku=!nJEWgr&SbTot_M_xV0ersZE-&GSiLi4%zQ7-PNyy_XDaScz$IZCb+i z>iBHFu8n8d7~H+2suRd6hRK`iQD$W{R;_aG%JX`duPJ4@PjY%bZ*4CfKEB#`Fy59F zf0>PY3Kxx-B0j|DA?3QtJzNOi=uYgSeC0pP^~eYv_$iL-CjIu}RppRm^!o`@k?VYT zTjMDhgzUS^<1zeRFWKBNBcC%82Kk;7Xki!vkERSHdl|_#43&T)Qn`w!VM6`#)t)U) z!kr8$xHy!B{LY<2!}V1{VDcAOBwEq$t`7|uxllb>84`rmjtdognKgW2GdZEFujKb5 zKc(NJJ-6HUe+uvgMfAj(h%HCv9;D>Ty*mEZw?Ip?E^C_n$uA`M(55CuCsXclufhny zp7Qq*Sf|IcqDB^**EDav`8c!{g1-NfLHk@?_FZJ1B+TQMqxeVJKzAD& z(_DUuh~ZOBLD(Ax;tcN-wZUDK$uEd{eGj8&fW%^U8ns>%A}Zh$?GHg4m{sc}ChPY# z+iL?<)^YrcS7rm4LaVYfF%t=|xYAt5Yhcsxc9ebQ@;n(yl!a78?WdRXb!2G*-6T2iyCn8)A4w^C53G&PPG?$bi)> zBd(W>VCSV`WGPiu&wW6YnA9Is;os~`8lJw%R2SfiL4B1QMp6|dQC|;iY|h=%$VMxM zj@Rg4rhp45$dS9u(Ubb6lILo3x*grc`_RyBKCyU;#;IF{Y7z6o4elhxh`eG6Y$!Bj8D8 z&$<1tMrIaSm6|q+0M+@-5uN3Rt z7ug&|v_dOu>aNaj9j?lU`7r;{M>GP8i(b=a0I^T#oSSFTOu}c=+7tB%0MBpM?pbqK z3p6=XE7ILu9%wmy_A^9thnpGE;X$0c$aK)f%}@KDiLMsr;9A?ERw_E zU-*1ar+3Z<)LF)6`Q?v^I2UqCt!)#qC8^kQ=bl^8h-q)*f&M3&rNtQvA%H@4GYP0U zi+lTH`v%e{#H?bh8k9*`O{IhLIH2k+-e~{8ppfr`!K1F%^G*v!GzEf{Cz% zKVQ_5!bYt!C3EF+T|C$J#(OQ2{=8%3-BCH*vDS!{VHCT$hrg`l1>8z`@)SYWHXI_v z6)n7_YM-*g$GYAyYG#2-UpkU$z>79cvxnr3G+6d*rS?*Bo%dnv`=RpBA5!?DVGtE- z8bPVJzf-+SEot)Cn&x-@p; z;tbB@)zDluj*Hhx$Gv25P^1e@O4(U5$UF0FT3oE=TLo z?RBQKb=c0|g2@%Xrh&6u9JYLoPgctN7P7O!_@Rx}fZRQg3L5`ffA54bAG#;EL1;Y& z1XFtsmIs$KvM-UWO!(m~p-oz^^&6jVpZoGbglj4uy4rxURh=r@8yLCFSvaM!i^>(Jw} zoGnA?^)hq$&KKNpIRhxDXx+Y*)s!<4Dru208&n~Nzl<);M~NdPD#8r<5HkMr62ty;XE~CvmgnMn9UiXTWM-no zxF-7V&mS(-0MlPR`;lf2*yzR|q&arAhqzXbDb7qxihwY<3hE(-UK|KRqF?sMU%5nv z<{=h*feB|hkh7$cx}5HrdZqJwc&l=O5l#qC#G;+x(FT@AXRa&;(^c`jUt$63KN3uL z02EUnQFa{!cU1esP#~nYyjd!7w|foEYq4>nND?lkfl(wOV=7csxO(;?;6n;HLa*CZ z_6L17C;D0PNxrRo8R;d=&Vq)sz;?8AUM=J@f`xTtdJ_DVexd)tzQ8JDj-DqjYw`e! zGnwc_F&|2K#;lqEyw9rFv+EwSuk4NE8m;R+GR8tnU-4c5*emHi0Jt;u$hC+NR z;MX+-?au{WPQ|EHU5D0S*|e6=BEiRw)tqq0UK{+OT_VEu3^Q^LZX8aw>i;sAbC)ZWI(4lq)=o6yhUdc`rX3^rt z4rLp>AyAJCPK9k3$R|r+vBW{D%yd=-6{U}$;**O!R>gAV8FUtuv(;3l+uhV7_WBrd zDxkvlcyqkDcM|da7AF#ghp?MvruujUgcTIU%N*;hEpIj`xPp35=NBzW+|-okBKg0C zX0=1Nb82wztYb!b=?~o!7yN1)I|S^VRZI+g`~v-+s$F85%k;}|BF!(pV)n1Lj0E#6 zjTPX#3$CymH-2OE1r`hghuR^l-=zPqlgRg2d-Dr)vijJb>!5l@&<1Vz|9YPrFxsQVd#OFVk7{1=LKTq{R18;djw(&2|KU z-Ij!?_N?tjU2A7YeR?1l;X@s&|JsIlfmN8%hJtYlbXfyC#)FGGxYLkYL&36v<0SG@ zaKK{Lt^N|z<90u#thaVYB;uBStGy*ajl+OJJ?QY1v3L$6i+a@132XI}B>2%)wV)I~ zf-y~iI@=Sv=f(HTKpYX?U=?=FTF-uF&A#tvBC*UWm*2kSs)*QXf!5Ov(6~BFKuT%G zim^2hPOEL;#9i>$E&HL`ju+XT0vrP>I$`giFZzQh;D};_BH!6Rkcn*#tr-xux=O3i zyh3w}XFc_w>e%S0DMprDgSPO3i?KU)>B5hs+u&a=aS*YX!j7w=U$(b#d`C$WU$y^% zE4HK_E38O&@=cwOcfq+hva|FBZ`X@d_+`ByX zh}7$({u*z5ufH3-Synohevb}n9m{(WJi4G!lf=z~wrDH=FHfS;Yt5l%EO>o(;-*%} zVbqq^eHuRuVKY8GXwS6fWb;(doWgl1A>i0Z;j5tlDL(lw`0RU0=vT>~<0;7_Jz zox;Kb7=Qc9Kou|PaHs4L49vQe=CiowpFXUZS0orIV9#~REj$WZ{hRN2$x=n0Olhfn zo%7AujNni!K6{*=y`bz_+35Yygk}h&R9Qf(k{5Mh0Wt4iXAJK*sWLBk+j>i7u$P+_0v9Br3GX9rcr^ra@(Dtuf^_`1ETG*wlf z_-s<)=l%(k-#H7q`@+%G^pz)asmWL|_DKnCsG!|YJ*Uq1f}GRpZ!}N*p-e!<-%*sB z9~hL$7EoQ1kc2xXsZeqK_ki%SfDt9!<2qHW4?o(-*w}5@4zZe2d(16bS<}=5J!?b_ zg`vGPGkc25)3Bm=lonLe`k2zJe}s>DvFh`#qO5KJO?&Ja)+Bd(Jd3eXThxlw?=u|d zFu{ovNJt{4nSRt+KXVn8{;x6j)sd}FQT$?1UUnEve|YmKo?rC4|H(=(>V2KK%YwF3 zN37;o+Opl*A zLWiB>39zvg5q$1ay(rCV#J$i*dj_=uFKquHA;U zgthvwt9jv2-0`PcASHHjZNOX{KlNLj-OS{#k9=I83{(dv8Vd;cK>WHH!#Hy${l$g@ z>7B88j4hYKTY|WLi5K>3Xu$H!dUt>S>F^J77wp{n72$ScTUEX3<3&ZuihgvcF~BM$ zOMEl4*1CH2>Q>Zp-xvThTkln#KRy-iBnV{D^O!vC8UU{c-r>=siY7PIhKGk!6Q>9l zD4FK}a-@qo1w}LR`Z#6V!I9;DMS2hN3;u;_ym{9>FzJ9)TdHQaA1Z?SwXpf_p1pCf zFb@gT4vC$et*V*tdLMc3|692E>I_4=#905TuOmVz3$##;d6VQGJN zY_Cqmla`jyZUgpcka1~zdN2>ZKVROt#!7O}IUOM)c#)#i*l{=*w#R5QZsJvfEUXWM zTPgSTo;8FHpq6F-*x3mZdsi!H%@a%l-QfU_vB0N0R4`be5cvJwvXXFD`;bL5-E&8I zNt(wd&C15OV#Hlf;D4!&2LeA|-Kny)sB^a1U`LQmEI%!mOEV00Kg}=YMr;{y8~YiG@iL7xw=6$ z@4LiD1il@cQ&h8-rY0htFR(j3mtkKmtM0rsx*ub3QB(fQ;eOLUN8P*6qk&ViV3pw= ztx%4>O)*KcC)}~yaJa%j_eeWy%xTBfBGX0hYTx^oQugOp2h>3NE}{96cNNfne>93H zp*SVabhUR+X6jal?5w*ku0=&PP!=c?kKy=(k>IU*B-&qt8=dtwg&* z`+#5V#5-tN(hwYjJK2F!&RWxye|IPLdu>so5=OZWguz!NdVJjFsGq=KtrKr6i#j(P ze3&yAwV-qPag(1cH!Cl3;Ss=kq*PYYSjP#y?30`R{f$XQMXazV5oRVpkAaC%Dgm7D zSe9h^d9nv6_yPWPXFeAF%7hchHh1)sRo}9oLM3{2cA{rA5y89Sy~Gabn$f3QBfXD{ zwcrw7dkbA>ayr&DUtz%PDvUGW8Ny3VnUyI>TH;49p&L*-Q%MvqI(x)wSCYDY%hl+T_(<3Qqd1_I$zClFE-rilukny+2#hDKK&X@c}*j}J6F zS*pvY^E1Q8z4Bi95o1;e;UoC@sel}dSqy}zWBzK5YQ0E4iEyNNDBXgIEp9{YP`7Yt zu?SaR`NX8n&8%k^(JY98=do%GEC#9&-prbSc*y?B-p@aXFq ztxY^$t_j;ZTv%9eafh$fW{*y9rVo<>(Q$f;K^YwZA5+95nCLMOn?qrOYprlb_5EzkCl&C<{BTM(;3Q}b3^ALE* z#t$pk)0}O$T?s|??Ij~ga zIUu1I)ArWqP2XQ+XLOq_oE;J#9I(_Fy5XXpsbl*^H7Vs$aBwD8UGTYSSO3Am%j9ag z3rUk;E2$X^;(OKtT0WMkc!ZsV%*z;=8|4EF>p@r9Tcm~`>C(@xTZeAd4m10) zI$m>uqmM3EQ32!>`5k?6psU>_=d_yGqmSl%CKppLn+s6ba&JJ|kZytzNNqS9B(gb^ z=0G)Pf64ad*~9zea67nNFH|3CS7I5iC;N;KE{ZNBidlFLF)1B^eb6Ky5cz5~2XXOM z5izZ9vh3Mv3I40y_F=`C_N#bS3n~yZXx~sq`tgc4uzV10Q z$)gpr_3z)~YiB(@ldKw_3@&YD`_*`i-ug2;nKarI$edYoH0l^IOPB^=45|P-vd4$f z3}V2vDt9_M79F1_S1#u&3uu(IC%3zMDnc5pc5`}U#AAKcvsDRc3A)3t-Vu}y?6RC& z<_Op%9|8>Zm8Z3~RDtYgc?uPNMWaq5u#p#xlTA&|`Y}0a;b(FacqWD^65kRu^(H+E z>?oAZynXQBne$aQmo3!I(y%~4+0fsWpl<%}%{SnTfoDO8;#|ox7zFvtY2#HXL_bIK6 zhE&_3ArCGjfn60634&mt-ZWYpcuS$awtjJQhoI2I&=Y!PLaq|SS8s2iW5s$9_=NVn zr%t_EhNdH1$r1cgu0zx~dWJ$guQ&ZXd9M5<$_ACJ>KtZk%r}%l|7s`;EN}%=Ge5vK zVPNAW5}!H29kEI%<(#GC;>UYc@s(`cdFGs`uZd?>GV=ZDE@UAjq`9_;O$!?J;Y73> zJ&;*?q7A~TGJhf?-!S=$Ad_%9PZV~nSJgGT&A4W)tD;D^ulo9ZM=p}DYvmC+2u%!M z=WKNEv^U}yieSvwo~a3dF3`E!#f@FM+9HR^2)pf@%F9$ltX0@nyv_W!mH1Q$&@}n% z)r6CxWC*SAd0W@&`}*!C1qQzCalG666PNaMr9-~2k{Q?%yworz!p$ooZygfw__1PU zPgl9>wMM@upTfL%O<^E}r5U`xV-H7Xc|o$PHaCiw{>RsK*joG@x;NXhxG7`sr>K-? zb1R8EDeH)?)kxFf3s{D`H+1FUM{k-vKq2zB{B&wl+qzm-)Tt5R5%X3=cfz58X6CvW z*tFL!FRT?L@rbN1e$Tz6nM)#dU0_E*YD2}LYIe@aE@TnSPhlXg0?vCH%w$y- zx?w@zIAOgW8fYP1BDGYMZ#rGOn{erMLnS}!or%WHRPYPv>#w_(&M zY&8WOQJpk}lNeXNKEat(Ic4Pk-P)n2%Mb|4|9ZdCZGKr^nkjDAGK1b9M=38uPzIzQmzxEr>+G(QF$I!{@`r!qzo7v)i`k0x9t~0xRfatm-5ZmP*x?8 z-7q(F>ks`~cTAFSHDd*>=$vuh9!%z|VE&bh{d3^7o+5JS)Bqf{1%Mo5kFq`Nwct71 zU$Um}Lasal^Xhyg9_|Ada|PwJiT^67GrG1ENqFVCSBeIciq9t>HCS=jeiz1zf~q|h z@Sg%rl(8_pLd$nG#sfHe;}U1@1M5TqlKXms&p``^2vW^?4Gx`onzyu9q7*Y@j>E0{{G_w8|;!kAw!C;cs&U(t&)u4YLO6NQZ zZY#(p)R+25w!0~VGX_Tt2Z{3X-s=3koB_6Ht;8p5R~L7le6^=ccXBrrhR61M!&n0~4}ovch7x5BK9FHR!o_R8{vZzIdBR zr18-CY1kA-FjAHUs$M{zlhFG(c!xb~(^0FGjuY(QhvS`!&nSTO?mKKV3qUhcT?{yt zs5#l$wkY*%L%tYztzz8LNbtQhlfIusV^ka+b1M!u)hL}x#s9PiiA#7i94J5*PIiQ< zU|CSMY;ZaC0|liyA4f0L^_N_Xc*s^^fa%sioB?7i@MI15{JJhI;Ki>b}Ok2w# zJ+;a2tYcfnc@S<1=eaD(I|y72@;^C~-T2NF7_u#YnWE(A_W3>n3V~#57SGl4vLa?V zY{QT+FqI&r$2G&j)s?w37v!o4lEAaGcl0P#cYj=u?dhR)q<{f2_Dvc=Ycu-LmAQVV zQRo&A6x3A~J(mchfm;gs@4sRQNQggj_S&a_rK!zty)6e?`+toN|7|bjhU}a09o2mu zWBhMsT_1DqpYh9AC?{%tTN|mx=EH+a0(Jy1*Q^S_*p|ir{1cjx{IS+3QdDM#ipN;v+IUM8@FFje>zr$w>T>hHoeA4}nghb&YGDWK)9XQ2 z9xjHF{pY)sbyXI`V(G>Gn@$(vf7BLLXpWVbnr5o%IWc9N$mb)hiK%qK8<%G{i;L(( z*P;Jo1Vd#Jj}u{dSkKy1t&*Z+c3;$7=gh(R+#5OTh3+a(#s)1Hc znW3?fS13d2im0d?v^`K})7+og?mny1s(QZ2Tl3tNB>$b23WgCVZ^c!p6f}xdc7CZy zr~v9->+$p-m%A?Ka`lvuQ{2s~V@Uu&YF7NL z2M20igA#F3&BKEu{N^CIUg*Xrjka(tQQ8>+55307JGJGkJh?RW=N9!8f;8`m1KUCucMP()Z?gqb2Qm~?^TwInlP$&NBDo(K8 z-#L>N#iJGES%E8X&Y)DZhde{r5(UJeHyT1!x>lJh{oZP4uwcqiFtl~BWMiQjAfB$c%)1J%$|7d#O>!tG0` zPG|j|%s0IE#+Hz(+e;gRibCydvQ6WCo`a!ViUte2jo2OP!GXia`7I8b8b^uOQBih? z!_O4dDSh5>nqcJPWSyq{%qDJ9v+C2ee~$wkFL2dwJlqZlI}9+72RDngwS;fJ>Vk<# zDHzJW^4?`GQmtGh;trUYcni9sX>={}ozO zMt)IcL%2(o$zM2QH6BdFCRH?V@m|mJa@7|?8(1y@vlC4^)05lbrD$;pNyWG>`Y=G? zz%aSCkW&(-O*vgqDR-Rw=(nEi+w>RJm{=qoea2o-rXOP)2^EbHQFR2h2$8D*^gO=~ zdL6-yW7uXg*4)B4!CVn_tk8t7J!h%m+S4lYi=O91PH|DHfs>n3cIgt0H@a^SE~=Q@ zt)4x#G8xm@6SjOXJl3$YxKZ2}8um*OkdXf$P3IoY^#8x{iH}w(Q(~x)6y+R}V-_oO ziW<%Nd_L!VEEZxYM&(pt(bg!(97Yn-Vo45bPUURPc{%fYegF9Rud6H9CGWl7ujli= z@5k*u;+Cai+^2jNR5rcEA4Pm$r$=kI@$at2?b)Xz6KLAo0JgQV6=@^TZD}7%NGqRL zN=Ya#zAo+h1Q5;R)+b5+$JR3hSC3*hHUv$E>de*WazM@D_IgtEwM#A9I2B z7tI?^^>-6N68<9Tuwy_-O#NNil*;L0-uN#b?`(W?t<;#@3F7fm22Q9iVBjmwdX!W7 zh6x1e&FC6CKIB9G9=aIML#1X>r?24Gm8HyDi`IdKaGw5y_a-P}JAM^O{gHBkI?mu8 zf4mDF?i7u)8D!~7RpebXxlO>U^jy`LfMqk}Cjb#TGy6a<95O>h5q*m~?IwRlHBM*Gm zG0wg@?z_FvYh3Tx*DDyzN&P^T=0wN^Gh)f!-zwUn*Ve^ma4f57B~r6FVs+ZX8;<-9 zYE^TiK^s%g@X{N%j5W(oKe$6&V1LDj_xw0(sUw4bA%PF!VF+4p=c2;!X!p z`{%pq5fUXc+xY-jnJlgc;c9+y&Y(0as7F*g+65<@;si8OQd$jC`Xtu_JW8bR{D06_ z;Ch0q%DGikgRgu)z=yD)x@NuxTVi8bWE-%hw&?;-`5D$iI?hjldyEqOTuKc;!qM~QZ%wyut>vcEXCBY@bL{asA%9T08ah*p?&#?~)#9^^w_nPf0V#Yeb?H))M$>$6{sl6p0KOmNUtgVd9!Dn>!H-ON=KB=XE zZw?rh((%jZ8B&CW{NbL}qX>`p`PV0`&b?IO7Uy}(*4zi^{XP}~i%j?pq$D{xux3&L zo6Sqf907js@9H@kDY)YG9jhrdQ;PCyZ9skt(V&?8dXsY2*vaH3I;V&a?&xmIsMd!9 z6jn#aFEO6CHTq93qxAc3N=u*bm^JyO*ikM(ohX*b0GgKTH;(c9*P->QV@I!fzjDEO z5fqWQs!bpW4|IbY%_Zsks)6u==BxHH7KJmk=_4H!a&JzRi8AVE_q#!RSpkC|o=4SO zpI=5+`COOAR9HSUCwy~IRzlu3(v$cjRoPRM?ut`9@RE3uP!n-3J* z0!-M7A+{PXfh7w8CtKzLmfNx7cW*B`%bw-Z<;rh+RvlypwvYnH?#{mbp|lh;F6PO% zg1baWYdCQhSAi)|1l`@AU>5*+$!Jx4JyJGJv=KCTq{^zl4Ne-Z?{u=K6K<;KfOr}P_ z+>6krP>8$0yP)IpE$UuqL)5!f`TeQ5-F8cR7_x*P7&*GNxL;z(Pa~d_2QT&hglAba zqb);VNY<;NtE;`8qMG3W`)#~qqHEjkGyY(|%&L^RlJ~!BGkFkp7B|FVg!L(l^Rxc? zlzPVVMY2ccHs|^$Blou0bhiTE0TQEbQEfbSz0tH>t|Bxv?0F|BMk_Cui^&l2wTs!7 z4FKVMVdqa$=Wu#~8^FFV^lFVgCsaDh@Nc=dKbio{79$ib#N6hTzIr8k4f3@KmiCr(ac#Hzd~xzdEaXAz#B2{M zi&r~(Y{rOR|MT2bUY}15u1JbjiG(70qjbV~p0J@8o{g--9 zX36$Y#CYO1+C=#fry#ngw8A%lBWO&c`2g?<4Gus+YXD1i;d7em3}IK*)OcCdCDg((YjgC z$Jh7tUr`T2U0Ch*?%v#79zEJD2jFP3=7N>-%zK0g6u%ijnb}O;pOwGQ`BYF40B9+i zEeoMr2E&+cOAQSM0!+=gQs?RABEKRNcZzhj5)y9m{4!|3#wj@8xoIHX(ja^ti|ai$ zM7(%LJNniDdPF%1sA&fQAcyP3Tab^s5<;n}8u@zTAMY`6kXT#kVkXI-D+U)45Nqva z=3qtUISko?Yr?K>@N0N;#{2(tk9_?JZsm&cW~VICbk=J$`T#^MzHV`p%-mwn)r(?* zk7k@7RGBuO(I4@v##D$wMoO~IEjwvv6shsFHI(15wobz{jge9e`mb{0Jh^T(rMQgG z7|zA8F1}#e?AQI+{0$L2pem3a56Uz7u-Y)3qOV@IV(neID@-u$2M(x&jHsH6>j4+% z3!~Qt7l`1E@Vt6GF~|Q1F5%d5BY;4=O`Z&@=QmE{OFz)Umo~HPSI3#ph9B8|H^{sW z{UqjsyN!q!`~K@z2grxx|7^{B#re~$IPa$wy(_=uUDFv+=$gM=SypMR`l37aY~27N znONCVm46!v%|YC8om2FycEd@(0{(Po=W4-?0W0PyBut#=6y&3skriukYEx2tV@79J zNK$Rg2X8(CHu&xZ`mj1~bjLIE6mzGy1gw-~n?m&7pUvOBtyAq0!kvLITt(-=tM#$% zFRKZgP7lSV^TQfOx?Ft7n2H>$Iig<)e^326&&3aAp2Co8c6iaa9mS3hGDoOag`9BU!IEoeb2w%Mm23ov!Xi&PUee;O6V-5RU2f2y)$9Wjq(H$(BU`IMCVpw z)GRD_DY^oFt`!+xjC#`^*(8JQ76aqdTPa$NI0N_73MoZ{eZO^C;9(}pFFqS<@ z+TUr}Fg0DsS1?g%pAq!0?zLuE`?stP^eh~E_3TzPg%ScNbd0dY*v%bLdIY za_OclK|KOHZonyWLn(* z=HlM(tZ2-E)CsAO9&YiLdy8tgc(ucQCM!$7cY&C>y>5C&r}>3%rCsTjf^=*71^KvT zYU!BfL!e!SkoNA|M-`jELcYG0n#*8#Xkos7F zRMol9?xeMx%D4bpu}GxzwABAq5}-q3Vs=vj#%g1rt9=fAT+#&dVq1H?O)UD}mYedg zPheFO7agPZXkr6I(_x>)mim-;|D@`KHfnVY0rs5qZ)*)}(Wd`=*L~pWE&zU5)=}OE$9gB?$3JMBQnbwpcCPu}g`$_DT<%w;1d+o4~wOMst!RCVp z9E;L~j&ZL}6%DfRAJ^N4+droPsNMGP}b-l(dxUc1k@w>egLUF;c( zem~3Jj<5?j6TQ~kx!ANSCo#*aJLBUI`1$Sr!028^ng^9xK(iSJ9=RLVj9>Az{SE!n zzD4%dD^b77zf+)%@3$CF0#T+2lt>R#?ul@KPI!_G!vPmLVv^ax<&5Zx);=2lUH!U( zZ*IdN>o~%CT-;q5cR*ZU;xn7AW>C~1N2)aHTVS)%a4s06SOp1JYiy~@n-Sr9pqS|B zLw3gE_2;5?y64`QU!<|~FW2Nk5s?pTz~2(Rcb1mQjy#(0t#=#k3Qxoq)&B00 z_Wp&f6XXIL4{q3Dan(HI%<~;yOdoin>l51fiPvukFxa(3Xte<6h>6$5c@3Rew$i<31aE`$f^e&Ny(ah<89fvE4?XW><_gM47?r5Rj@f z6Gi|>KG-CG7bZPixeMX@Vc|`9m}$nJR(b-fSX43sVt~2C*n3+Y9M`0dw3VH>;A(~v zS3Lh!IQfYW*A)Nlw`sr6$W!AL8|=!n)GAT3f~itVZC@7G)mPi&Z(S^TiNBZ8Zctg( z2qHVx1G;dZ%5QM*(;uHvcK$IE+C=)gd^8Ie7Fc|Vr{B5S4o3wqj)*o1N}6E?Tee3Q z&-cwGB=HtYEor_`v_pdr%9EM*?z9$NSWt$Q`}8WkEh$X89rr^mJ+~ot@9)(aZHUMF zyW6o~qFOPRmL?hdYy(wf_^i<+cZ+?KKl-FAhPi~b$u+VWsqraTVN;-eK6pa5ty;+12CY?dkY#4M-ME3 zg39FpwVjnz`2prhLa=w#_Ux<_G+x=@k5oh0`a*A-2&H#??eEd}1;Lh$&8PNS_05Is z$e5m8qMw2zLMmewTt%YZ^)X);_bwe=Y>wLBv-MRzKiS5sZ6hlPpBUTO9vhAeUp%N2 z{uI{KQnx<7M={mjoZRWg@VBSZSEi^>i_B8nr{{zIF25|-J0)ppX*oeMIMoq?E+{CB z`8T(Cg(O3}_tgXb@K`)MvONZja0m9o_WulGa_Umv_|;kS>%+JX9z5voK9jY)wzLEs z8~EGO{ebDS%d~XI2cRfmv8Zf}ExXay3(Vd>jqfoB$VjL(JGeIZv2xnC)XYG2_?lwi z;L{n<&1WMc@ITzH$eT|JcH|s=bmEf>djH*TjF^~hPo07HvDL?X4kPPp20Zk|@Tj}q z2WXeA45V`#=0X}hbC2VguZwWItg(Gg$h*Edy+GvxqdmT-FRfFU(W-R=;9$gBy(yAX z#njeNT*>{Y>d64->K9=q6edqYW)pnV=l05eG+Ft}} zkad(ue2*08>QmbUT&>CN*q!|oY&YXf7x&0fdQ4bG43$!;iCP_~%AgHKgi6s>A)!-u`}DG^XDDZ|dTLd%wOzNn_Iy>X+oT zd;g2#bgpx7wduw+KO51hA7uVB5iN|}+bmU)haE^tO44Wq9L)}>?zx8_p%pnI9cA7O z$TKk>wTer2jyNoTt?xs}`+T6(YAHc2{UJ=iIg?tPz=?x>j|_9aGx>b{Q>~8!&nK8} zNePh}q&AzRTgGAYEyqm41!wl@hjKxWTP&;`%yM4N_nibhRr5eCA+_>OvN|q4wn9tz zD2WJ4ly9ZNoHTHlJ0ka@qGlojEv@)*SUGB>y$NR{W`8d(M$#VrvNy#D}!B;9mt6#l1|>S%g(IQurxm zcsylJJ^knbypji=<0bI}hZyZ1ZM8_@j@4B>N?h2CQv&X+KiGQ%~645djaqGK99i#|!ND@2-Ajm)QA=u__I``oCZG11s) zQdeUq&wGsbC?xPySX4r&dq9-N!(<-rn9iz$ZOy%ZmM3mgEAzU0f|V|%%(Llv{)IXR zVG2p)iIB#VbODCYQPYJNJpzV=`!h+9Yh4kx*{Gnw5HT*Z@rZH>;Mi+d?Z1t0cNlUP z$U+$s_^@zif=lMPZNbsf_wIQE>QxOSxB?$%fiSs7((qijxcTpf17iOOI$o$+ZwBT7fr}Sh)iwoc~KC6 z8>QGD6%~b?GikhyMi;s_FV5&Ip5o!`RI$=XAMsPUQ5;)I2X&g_*M#zZk*2;@4rN`) zknK>-8xr%de)~2>*-%jzhbdh2;>5ymR?z1}xz#2$;2xQs^-vOOVXp=9bDJNgt-h|p z_aiABX0Mj{WrmGw+V+Zd78Oh zs%3@z*OU_o?44&jX7d2T`EP-DRETGb#6J8<=M&^1ETI)9-lQ)k45`%%O??k2If4M> zGE1*=2N)*kCmE^?l^fPjZV3Il;$vNUoy!ro_k`O;xcjvtlCxlnKHy=4&K@t4^CpBm z7wkqd0g=yIFk>+(omHJHi-01fsP_ox2v~I^1KEd8-;UcLcuM$hBqcH6a0wj!ThL#& z+fnhm<(3_AIek#RnOQza^5uj$n&)I&SfTzC-`Zl%q)w@K{Xmiwt;^%ziDy?s(dM_} zPv(17c#jnB<5()K$4M*s{~_c5;8MRA+lSPw?40Mq^iivJ?KIBt*eH87Q}4 z22En0Ua52Q^WbZk^Mh0g%6 z`hi+k*N83mxPPS?FEnG>^VuwgH=n&ITdc)6d;W(oC(Sd4;@UgQNi$EM0;;R2mzhp@ zcndu_C-vwnBWbz^Hpdw)S&Fw(rGz!nB6b_ccH0uNvMd3aue1-S%wTyfL&I@b3LwgO z<8~xytN#9eB;v(X;>bd9qn5+>$P*grhRKrEz%oMj5`w4(e!IFJBMN%2h8QCZ_p?*? z{@)8gr^jp!Sc86~kM1vG)lVH&M9SMmGv=z7#&-HmV`z+`1V-Yg7-RhzgvpH`BrPz>Ho5q{$ z%AX!gio%M4&stEG2?@0kJ0!|;dQht&4CE~u8?T@;j}~)DXx8UJJ#$EDz7b6VO&4o& zy4~R1+O1z|?~X_14;J?Vlym(%A2-G^NC3qEaO0$$F}a7uYd+w6$HGNsQ?8JW#Ny{WOY0lk{wXr%d?2D ztV5@Tk1EawYq+~t5X=*FD;NuM)8OH#J-ztvU+r5GIf6rcvSA@u2~%MK-Yg-zGBkyb zT3>%!DfoDS=rJzq+@qo|kdFkhXTxcWE0ynjt%dsLt5qPn{A%g92MOH5&OR6cu4@Jl zVZx>z#lOK2>K2jXHWv!gd0mx%XO~8U>hGBI89~K&_rAkH6G-{QVR6EpqH=1(;o`E9 zxtqRLl=MHx5kA#jsc#vqzpTYWt+H;if|n3C^E;|Gf5O2>TQ$*2Rq)fY4c9AXgEbtT za}ve03g`?O%!8lEba^wOj<&s#hU7=4d;9+}t{VgmboQO#3Z$J!tCHEDEzanZG5!&( znuow@jxiElq2k|aCS089xIsyU%)uIcxN^XER+u%bjY6sX@{2q@)xR03XzM>P@_TkM zc9l14^L*F6&anD%oZ?sLtKh290J&Noq71bN>4Fnz@>9u!UPrRNXUNfL8Kw(b`_rJh zUQ1hj@89OStJ%ot@PDyuU2)qQw4;h0g)O#{7a5hXv(T5|B^S${61BN9j_~{s_o(~t`&h%n!{DSCTcr{`^ja-0Sm$KJiUyg&&f(pM0MYKeftAInYd4=uRx5Es z%MZDQ$iCzrYY7+9@3ts4l)elb9yXS$(Y(Ub2Gy;$D;G%vEF|fbKkU5A)c3$J8mw+P zD2OwU2Ul1Lhw)(bz*GM2)f#6^Ij*6+8I{C_l%l1stP54`Z~N!+L10%qYWHtJ-3zTK zx5k07-Ib@Xgj|5gr-5$zTZv_$@TXg=843DmDQ$*u79*BN$cL$wi zu9%gj-Z^^Sb z`?_YqH)^GooCV9|3T<`SC3C7?bPJR(!P63JT{j=xfDKrkbhVp&$W*VZs{;v@KGV3k zdoic=A6Oi}9lbSv&cJy`esAT%cMo7|tDj#_ba(exFVOCooSjv}?I`eshTX7_+w2e4 zCX<9AOW+pi!%)9^RTnDN1uU#cjW$gxGk0-;l@S`+Iq}Bzs+G6S67R8pKx8kNa$5e= zegyHBlzM59{h$@Ax)Qf9LIuye5(=T?p~|ov3~LtbZ<>zxmb{VB18VAZQa`;E zU|ZV9G#5O-L=Z!mmz^`N9>9*jh+bRvkK48;@K-P?6s`E>y}f4c*Fq`)4~d068xJM* z`_yhx&N$0JqkEXUl#%t(2zTv*b6r*-Px2C9oqM$P65(g->eFSns+80e&Sb6%z5|_|Nm*SR-E`6g)52RIY#kVVBcL3Aab;(6k_)o> zmwvl5B&F$=RYbE+q0x?*%eRZvAO&H+dd!QMtxZ;UxOee+=ws2ZRp;@>klQ%P=jnToOt;D zhBh$D9_D=YsLH->m4miWInNJwR=y9ls;#l9IG;6_S9PVW^_tYx0vWtgj;};~_79vD z*4$V5+AV`ae9d_##LD^5MwB#2Fl$mP3ktw|r#bf2{Gvm(qGt}$46ahtQ2sE}75y+R z@jG$aCg_;hP|k_k%536Wzz;v$^WS|35#eClu&D0iHizYKO4#p3QmdL5;D+KPE1#KB z@ayfpS@pKp$HAy%5+wwMeRp#Yv-GUF`>h0z#+>=fD#h6N&y0HJPD`J^Ba{X;M;#!O zioR5RtI={cvRxH}9&%%>w*G_84w<0)v*z%tzu3bvw4NS2dCMbMC?cF0{%!Tt*&z>A zpsYWcK}n12jYq-HrYg1n_tZvYc9TPbN8Cn$Fm7X5Z&z`uGlID+A-Bn5kvXIclo%n| z7R`&djedmWR@^%bKOklJgZM=j;oBjDI54PnRom}jH{jUCX`QB7rhZ_|nN2DeTO6MW ztDBJW$uG>`8{FSI1Q|EoTYJ$IySp_-vP^eoZ)?3oj~}#ZbIFQcrVADd3STGY&UmWl z^?*gUOe$r2K||l}u7JwNq1yjm1=^I#Tq<@f?p5x%Dec=CWLrT*-FGOa2W#bdzwe(C zONO>W#WAZg20Zt_1t}tt*E>V!Q9=n^PYWkht&R2GsV34x!4w(VSVjLOK8 zU{9IR0#0SNS6lrbL_>KU{WIj+E0ABg6?vuEyXF_9HI+oQD5X4_pin4dJJWS}=U#n7 zz^^CsD_|d=rS_c*k!d6{EgDyuV>@2&pY3mS>KJ8~^e%z$-Tqi1Wj6r`^u@)LPSZ2x zmej^ZYt%btWw#fYPyF!pVZn~QeG47-M@Xx2Kus^gO(_(99gUk zDe}9h%(UUos!kMbowaBmyKlPxXC`MVcBM-`BV*AWqbhuKB0S60vt=w|ZK=1b%K&Xz z{M$r!gUtr-R6pgS?nqbMbEEU1=+OCZ*8aak=i%3W`lwoUzdlgZpDrgaXF)>O^<8*Y zZULrJq%<(=Y_C<(iWN3mH5S!WqgFO#$!q=nHRJRD7J60>cqu0Kw*FoS(gwqaN0*fL z&{#`-qwCL4kAcf~`<3EF1M^~bYpZSxqcJWzuEvfXwOb_hx=*O}*%3#vJE#HIh?o$S z<~+^tCCJ&2@a{_dahpjYNJpR#>d;RRr8YweIjhY4tjto@hu5ha%l%jNw^HWeBqkS) zrhBQ(H$=0y`WJdU799i~-XrEt%tVk%=0!2PDNy&3q+TE ze->KxoUrLuqp3NxyVf^GF!%)5(9+U}@MGK*FBxZU`dAHykotd((C2u$J#!#nt_1fc zy(@Wu{BRaKp=?_*UC12PX&&^dnK(BU-vTPZ`_9R(D2;wrnL%Cb7y_?QS+Mn+iC7;0 zeI1;34a9J=G9=lH{M?npqv>PBBBgHkW90sbd+o!2>)f+q?4?J2QAz7!*Ib{h ztB+i9cV|ST|3GRq`eDa@&cL^6{sC@NLqrbOZWBG~1-+Qgvi9Uu}V)z4`)P`E$ zBt>wRW|o>8pa8xiq4k{%m9>iWJ}SP}c1`;E>-SS1a$M=@F#+#%^5m5ju;!c`XZ29} z(i|Q95zTZT;j|9ZxUD|cWm+w(VLBZ|60$T;- z!1{`Y*ZM{kUU@+ia%QqSR(FYVjU#rp1DQt{A;boL^Pf#z+z?-z!D4~y@I%rM@rc8m zIM>UFcYlr_aA4H>*5eepo(v@3I|g})PjrMrhGXS_6{N$Wo1ZBn6HaVC+_7DV1Xe7UHiNUOq9eR*(fuq| z_S8GJTTDz0aAN{n$o@#nw*A3`S2JqquC&rD&^|sh7QH%G`eJV(>_xd{Ue(}C`P5U_ znn!|gPlg+W2zWAp=yjr#&a6rutdRF*s9f{&XFU+5r(fc#lQHy`&K};1T_1Wqu0gZStn&OS+^YdfG3?3}gG?J6o3+SY zO?ffBkoE+H50v_m&w*&XMloN-=6RE6#vJk6Nl_1GbYjus9PxLYW6uWbBZ3_tbhXclm5sw1zpHpfkIj-%dMp3%MTE(;f>vBF57g`OcPGa zJwjGi__#`;`)uuojoonk7;*Z7!KuzXHb`hF%m3r$^<{)=xhue7Mx}iQb%WMq(5>3k z=P3c(QJPPQeER$S~hE#R)yYCg_OH*xhz$yGBPrff#n z0kO|gA+k|bHnq9k?ZFobw?LVgbgMz8o&A^xK`g%3*HC<6q_O2uUt^;|g~pd3F6u&8 zM9j=`XfNW9h#6JwkSg|o+sox^OAijw}OofAiuI z>7!i7XaA>)0oZ+EarS@}CqzmThUg5$_2#sDi9_O{2T-%1`hlMdc-3*eaYl9!2oIzK zLSPTb@rqT;KU)&39*<<^~TID`BWm~T?5 z^+FzY)+*2UhMIx1I9AaLluhcw$pe>)?*NvtGox0P(Q8%eX*H+<`ToAZu5RW-&tmL0 zFCtlX*IWHLfZKKjAFh_J)Py2vtM?yRc}o+1phT`KD1N-NzyR=rrS;)|_D#4m_Bgdt>;M8vyGJ5A z;T;h+wBm1Iy>bI4$pjLKj9{t)&)&+6&SJ3oi>yj{J{>|poF+}3r~_QF3~RcZ0=@7QTu}^7+t6s7P!*3|D?+Q zZ;npABFJPn$be7R)?`;P>-@^py8KwwVnSo%q2iK$pXi#S742s3=d zb64rsYM~lvE8UzI6`8&d;yHuTrhfwq<0_(a4wjCdJ&aCf_twh6K>- z5joi@_c~WHl~3lM_^R+4b=_IH>MrIfmHh`yYLtfN6;2&lbL#sX(!-zXCQfqUndh^* zeuCnKw++)Mq6JC1VwZ4R(?d`4=gQfVC6hH(Q$AW3_ zz*q$-QnkQW|EXx~Mlm=GMoCY{UQl-Srl^*&-#6w=b$+dIND-PRtaJKPiWtni{hheo zvEtr6lBIvnDq(R0N5^4QW~glQ!|$!g(&A}ueZ29p{?~+@@#hUzHkOO0oZj2W5*t2H zC_8^hwDiT(yQwW(%;L6$8@y-23%7yCe}pp9`f`7=>x9vlxc$Wz03eHs+FqSfqOQuO zT&5k_sp1v2L~ka9jr!JTK*z;Wnj`l9?EJ}0{kr@XdFh9h$-=^lCSc|CvPM`Q?!ke9 zd)uJ4bbNdq{B*yIJ4-LDDSg^6a>R5UbMjI{BE)Cl(qNzqA0BYsvVSi!w^)bh$p&` zcn~?0l8oBbzAu&zVxB8IJ3m6STC)}Bmjc|w!W5pTg@vtO$*UebjddLI;SQ@C1O%C) zX#sKES!ewCj}TjFy+(Q^R4(<$ds*x&SF_Id#3C@2K%J$zI-V(Z5dH?Mn|}q(V77yl zu;3*S_1>8$$@_MO?7k$bbxi*ICzmz>+!yOxE61(I{ae&txO4?FeKQ2repyWdQZ4!;HiDEtMjV*WoL{BbLs^HkahP_ z@1@+7%00rI4#nX#NDka`wc%k|MM@Y9X<2-&E$coP&D;a?QB@*#){Iw&` z-QL_%>JDO59g^gpC6@CjU>&3%4luN3o**pHEOogDumg8pgmm9Ae76dZ+*dm6V>kwZ z5Ka<|q$wi{!exgfp>6F>7>g-d?7zznVqCM+^XI9Tjc&s9LTnl75^14Yf+x-b=@VdX zuK16_5X@X>T!NSs)k&n+4QC*p_T$SlWs|Q>@1CQxL1;kV4kfKQDDl($e~kvNb5704 zpB^hFieVvsn2)jJjGU7XU(M7blFwd(isRpx@##W~kX&LvkPA@Z?41aej1~Xkgaef)_MS3>vcXntAA3;F;VrrMq0Mr@+Cj^)F4OmqG z*mY0H_T-sk+oc!4ApyWf3uaDJ7(d1HAY3hAlb@ge8gsGU=V4kL`%2tBjph@GfG)7A zT$yrz5wk~M3|&7K2fXo(h5tQih3~H{#X?O7TY#_UdX2n`DQdeyY=TTnjm4@5?;knDGJ&9}hO3=l=>i=raM zzKpZjYY^e?L}tC2L?oD9eN;6xhbxF){$cL^VQWjRZH1(wYCfv) zSD>U=z2LLw{MP92UdOt=z5lr;>*{KKD+UY^0722mqD0&?d4v||cTq}&9!I?FZJt?e zc#ZP}TS`~-rD9TU#)YhgY0tvI*09jfuS6x77!Gh1|E-Zf@=8fIO;>FWd)z)L3BqI_ zWGDCHuyIJw@y+&sytIhI83AWqu&5sPQ2kF3+9yLp7ITPy386Fy_JSXj3u}V z%txA-O?J#0H;Kb5q7*NIRPo z)eJJ#kT3-X@cLUv>SHYOy15}=>c9W;Q4KW1S8e)KrTa3LPj`Bd(-I+pt$cde3q)3Z9>=m(;w zu<)_{}XlQ)Pkw|WrVcCHK_PG ze^o$1#F?YffJC^9yISk4{LTloY~Y@l2Z?Y$sS$%ZW3l6~`@UZl*EpfK&}i%F|B7XJ z5ClAP$Q5%_TF4cRZb+|+S@&T~t6ad|6o)9-1kvtUlcz@}{YdyDI}UjdqM78n+R>rB zJO*n7@2Cem{|st(L>%~U;)ce22D;0->ObR^P^TGB%*D7;S2Ei5I3W_>-sgWj0{ztS z%y-ks6Vs1|agX@bNg4jHhgsq$GlW{1Pjkn;uav1)EuT>ON+h0#U+xgYx}qvsjO&L0yFmA0%T1&WZ z_z?2)Tdql`tF5n=X|t#lSxf$%uL$H$e~oWdgPe5xh+SR3*V>jXVU1~7ahiegcfuW- z390JGO|Tah%BFX=w!Ab8f%RYq+!te81RHvS6mMW}QM^VVkWe(*SZX!lWf`z^eF9RSbiFyT zoJ9A@5u~3tu^BAIIwl|c$6LFoiP)H)e$A&(YM)=32dQ*1TBZppjl<#DXA;;Wz4PsW zzdx-ZyDDSox9A7su#aO)O3I{9upTXKtvCgRkxJx9sKc9kQHuqX2u`sNA2j3EHh#}_ z?T!@m7T+*Ukjf;MM+kL#Vpj5)jnvgEb%S-qqfpMgBUw}R%t+wdU^l555cpkf`&FKz zjw5)0ys2zVvun9y&OSJzW@lVF0mO+3z@wO5aAdP z)!yDowR8s^P?KBJ4bx}6kWfcd02&w>cKr9JX)Q5(f7aGGiod~ESz)x(odQML+RZZ! zaV|^BpKgjcLw2^9I-21d9uzxp$&Fd-HB~Rjd93NBmp$nR`-y-}SA)JgsG0s9W_ z?iYHLbe8y3{YUdNO8Z!9XwDN{;;)7RS-l?c&gG!@>cC&pmDOqXb3EP>ZHsm-bZuse zIY<$h?D+)V(N4HVx(0CURkaUX7k{XxHne_fP)Y*(mWc8s)R=XIH{0VSAuo@sy#DYd zHIL~{xC2YXzbA(TXy=J@o$l;j`7^tejFIV9LX`~=FH!;dg#4P{Jg7(EcL*83qG=jX z=td7$%0X;3*FCz8km9=L&8PnWhCW_Oc3YhVsP*2$pCP$^Qh?RlbWtCZP4PPdnQN$R zhgV!QLqmTv^Q^~!NB^BHBk)vf{SS32NVIFc!H@sxri&mkjTa5SbpF2=fYAZJM8;c? zEg0({=}<5+5p{68QQki0sar&@t7py(=6v|+ib2QOn3b`;e-zQCU9i7h=y^Hf>BRHL zM)~rAT@#{G_0cy)~&KD%Fre?J8OX|8Sm!18;-Y@e*}^@qjSzZ#~*;d ztTD;FbNGErojg`1CEwh9ux7xGlD^nXX5IOqrl03iubzYr*sYL@cO zTO&SIllq_+XWmi9UsUdelKSQqF%s`^lb#{5>GtvV<8-2KSLx-1mM^ag7U4BD~YgA z`W7E*kKlfoD~he{06O8QXm4`9uW|XA`E+=>tMy5F!BqO_ z=z_!dOVq!8G#%fXJTOy&t3glJq|Tn`zJV}V{9>wC{b)3sE!qq^SKTh>nwB;e^Xc70 z)noiMb-t`>f>x>eJ1J(hRgDb4y1KikP|4#q0f#t-eU2l9I!a_n7LBYACj2UUH@#|w z5VxfL6bI&N4!wr`mP*FoG5^x*5muG%Eq-c{^i@6G`DJTy60eYJI_vEK)g?>W+L&5{ zH~%W-YjmoU5_-cMEC7yQOuOt0IRM(Igvk#$P=^roz0pxn+gUMa&@^z3_h3P1hKXOP zmdxP;tZ%%B^5Iw-x z6ed@2Ggw`2#Yt^g1u{B}6W2>~oA3)d2pgiGKF%}K_h|Cdz2PaZZ1?)^XTFN4SM5tZ zJ=YG2|91f&&F&ZMcm~?Iy3fBMqM*mbZ<%`%NW@VmfL(qDqt?cZU4ihUpSwOEk2d`6 zEC3*7j{M{al~y$aC-HDI{IB~BL|L~>(tyKU*--xD+@Vim@?S0BpmL1H#{EFs2FXbg zzE%DzScs%7?}#1FEBBtEyD7}q<{owa*!!EJz+=VwUU{on=pq?pp7mV({pG#FS)o6@ z^uI%p&&obbs2gN@lEG-@O6S&f#XnF;KH&S&NwISS_;rPOmVv$d@3}0e|9-5Nu#ZG zZ`5SAu~8$Tlh<^6hMu7aQH+0Kv}Gq`wXU}J$_)k)Wg*Z79G{aE-zZVzz~chrM! z#eRW{q;q@bJ3yF~un<|Vg$6&fX{-a}0saTPo_tqYl9}t@OJTfr!DN^FTH^#T1FY)P zo$2v6yOx-^CjuM_s&pD`oDT$`i+l;jZLOM6E{xV7d!T0-}rVFQ1SXG(?tlKNIEpRrdB~ z8V6wPD@x|%e1-l8fqrr@d}@h0-0EIMr#`KS7yAfptWAZ5Y8`a0K53cb+6yg~>1L+f z)`NWl4!0+_%%x4F`>igKIqow?;E8Ic$5Vg!m9{YtI}a_cuV^Mc3y%#5inQuyd({^` zb2NIO2zMqEm}*sX*yEo-z{m+l$YFe20u<>+MHTK_@r2B)6O3em#45ce}H*+mN<(E7d|~Wcl_QtMqdbvp@HidI9ZMcaEzy!_L@jvTv@0 zueN#T55v-Z#)^{=oHJFp7^XpyZ{7$Z;eeSi3vu_D?S&(+s8%i$jZC`=Dm=^l^b2jN zl(cceVq?UU5OqpuDRc8T>1jm{m2JP%uG1$h=bqP=05t6=jbdQJH-(Bj!Z7LEy{56h zn1C|bvUz1OW~s+REx@L9Iy>_R6G z)BdbiJ>>wdw`;EJrH)4(0}6I!Ilf?cJ9*E>);3$e3m&!CU5CTOZ3FL9TM{qfI4b#L z$c^IP0m`!>Q6ZS9^7WM|(q=R;L|;$72IFFdUK%|Inw&Dy7sRm^Omr#ZNoE*B78I}| zzcWK)_Z!DXG_*&@##$&8&)T!N+`XZ|?W|o!oD^#9U%14dq&d!pJ@55;AGI$3jCEOUrdGx&Pk%evhAj`=hMwv)Ajq z&Uqd*8p%*^lqz}s23RraRO&MoeNZ|5MmysvRP&-pOvvSY)y!+ZxVUdjejV%Y=d9`; zJN4cY{4J@!o2`Aua#R|;2t%&6n6kpey=e0HjqeJ5*dZu2sPyb5Hv;7qj!lMiS>x(e zKY_wJVT?2{iCkq}ug0PA08?hsH^05T@!;La@|IMBy=PgCaN<38XEdMz%0)T8B#VUFyQNZmo+11+A z6ev(C=GWsdbc2VQL!z^C2}bVj9gPQmjiyh-uZOUz6eZ-!z~Np2IMa!V)TcY4oAW)) zHkXzvsirx76Ezi5B+&jT*FowYuKCu$jfLsJ?XgJ;8=kssSK;f=wV5#WGnG`8)S`Ok z4=|+A#7Sp1o%dxD(_7GDbBTe#t)PTMS^ec9N4?Dag>#D&RlL48opc->ot-j2eKG!Z zj6a2m?IM&4?|aXr{C$=0L66PNizYW?$Ki5U9J!*85h1W&G66LhRUR7I z?91c2mdV!8@dh6^>D2RTFmH)7nE9k4k;nMq57dVbRw~t0=d&S{S(_lhLiS5UsBW%=$U&lwOSNJAobi_~ zrOm2fVEY?3hoBhQg`g)V8fe6h=y^6YGz9FEls;#X;#(uaD|^%;DuqI!=a7ucyCqjg zecHW)cPGAirNceM9gNGxPO#~WxhI`@RaXJHh3EMlu1$ONR{V8^swkf{urW=FJN_(4G7%1%03%VyiiqQB$T)6!;B8S&{2MxI1Lr zPo?GyoD&p0Z*67O7P-%V$}rQ3aXPs$5nb|HU^C26OoYYZ{)4II4SruH;<~QJj;25l zI6DV#HTKE8`@;VAXIGKKfPcim?z(b8SpF78*~jXV^A|?M;o9tPuBgo`SYNodTed3a ze?%Vbp`MJ0x$n&yj@+jW)e{U*PA#bQBqvC*Lj|>bfuFty z7lRz7#)Hg?zq`z9iFYFa9WAw89KJ*FQDnNa!k)C{+fCVpQ)r zorEqR1Vi1VP4UJP?g{ec8HUH;x4D~C+IRkt+u2$^!1dYk{@evPA8yF2M@m?WMD%CZ z@=?@q9mRb#5K*Rj9DKQosu57Pu#cBn3+LOGgTq^^+IQTQa>z!j`+_ado26yo2gG-I zle+=8*Hzur%lL5J;1D7ewzK|%-uyh~?j;m>$8`}V)x-lEN4SySr>0C|4nclsgL=up zIoYhJ+!nW~n%CRUaO$_&ly@x3LkWPDi3ApN3H?nBSVGts`k>VK$I ziuoJ)WKNqfx--j=1svwS(LVbIa40hr^T1P8c*ljHSozXYP>K@*kWcm2dd0&EZV$&y z$XR$}Ppq5m6<;245jI3hc#OO;15_Nky|o0y;f#5T&-L9e;NbL{8iE;=k_-nez#>Q}eq-w3z_0#ua?8k)!r*bpjZ=G9 zh~WAwF4FmaWZ`eyw8B`%lir|7F@a~o^~Ac#MPtdf*49y!BHa+8$>0TO;B7wu+W`Eg zg#b%(Z!N$BL+33akU}{vXyYtg)A2PX@p8gxBkuYO?9$OtP5akF=62A?y>N{WJQ;yk zE&8jxE315bq(4H0bWE)>`x1n(R@2}D(Sn2>fv~+YVhj%-hs>~EM~acIICyq98JAV6 zu*j|4jCp+7IY(rSA94r%6N-$1J!0Yah~o#GUsYI4WV>Ch*p>ZdLTHSQz;tEQjOm&Z+LBNG@q82?)oJDw*^cXd)JW>v+Ig_>%+v`|k zj^Ejz3L=EAt~oVMN|I2hZh=PfqEDj-djNp~>Z3fnR|ldF3fMZIweIf{#$yw7k#DNn z_e#o|?wLz)2z^Dxx7o}${j`sYimJK7#Cu!>+|p3rCtME*`Swe@ks#m}D$Sw`t+()s zdGK_Onf?2B4)^)z!6FXrb{4KdT;itXwAQjK`T` zFsd*VtYn=7jr8!ba<27iMn>SxT__e}g}(E-<}1qLpY?rw{6$|D%B^QZh-hMxMa>)X zYn3RsuQml0xQN&HcgO_~PsRcN7J%Y_pR1jzGrTwM`5#R0^$Kc)0|)e9t|(yF4&S%V zo(s)S(2SM`wV{#gzkarE*9ZBGIMuf0+O8=sm)#lRm#y(T6YN6}Da(vp%@MA<^t2k3+WMt-`K22g+q8=ZX z9v+nPUX)!)==xz_{W}2EH66~ZeDJj*`yL)FA4aO?Z8qmI7*`zDUDe$)IVTrIDJ7K1 zs?mQVR@zlG&-B3jeh1{go>!bP#_U7%x{#+nN_64A66MCpjiB1`$h}p-^Xh@#><@+g zO-oIC6$hr9jl6@G$~glEYgGqpiv)7`v%E4H+$;kW%H{|ID@R}7MvA;DsixQQa%*ch z6u1#Yz$IRAW2c&K=&(*#_DMZ|U8?+dq!N9z84W5-Y@9`onfh^uOuZwg6%GbkIdEKX zCFpZ_1_iN(kU}dp`3{D1Tk;x-NAX*V*FrCK{cBI3oe6$2NW~3>;5I`7<0R&iu?LEf8 z1cj3(fcT~ICGZ;A|CzAfNX7K>HUPx2y=$-4KEe(`!pyNxD?Axc z{e_MplXQYA>zNu}Fx>=>J@-N2U^O@1I5_yRx>}?zyZ1p6j6W4jP&-%YA{_f8SWF)$ z$4&gk`1l#(C-dE(3y*2xQ5%AXf{+#W`p1Qd{{3)|#Q9#O`oViy#d=8*htqJhTz7Z*SN5&GjA@YRwWkXd0WW-U!fc)TT;#Fv){A z6ARHCYG*};A_le~7;Ur=G+#Z`FDgnf-tH+M1gYZ&!-Rr3&uN{f%VEf`X8FcWG8tbd z9L?sNya|+JA1;%(Hz${IKxnziA|J?)h+YoEzjsQh{vaBf3I$N}d~lw0sROSUdyH3& zBJ696k}+3LkxCM&u!59rn{{K}R(YjUO1kc;`R#;il@sM<{F}!N-!#uW5^OL(M_!cz z>v}mUc_`%Fl@}G6w>|JQR|j8`R+Iup1!+qTwHW8MKTJlekrXEc18XHH3TwAQGy5zol|L1CFW=xEJf9?t@Jnua7 zU!Q{=ADMoTc#jN@QX{l9SEA1A;sLiI0ea3rG<{1SOpZpzCj+T(=c9?W2U#m=KJ+q&OiWO*D zsBc7sS*A!d5DJ3`d40}#PH%ZmIslk?x`O_5hoT(!X*6tZ+q#!jBg0S+wjw^i`GUGVHPn?r-|BPjZ|~Rshl|=lCrY>{fIq{gN0>wJh0FBczY+r4lNLBbuXo*RFjn( z^Qm`zyyX$gQ7bJJZ*BC?d(J6Md3PTjwVpxT!ODX`*DHWS5tJe4#Ks<(=1N}_y`3IF z@ajf966*8A^!D~X>*~5Ge$?*g%1X3N`u5Wb6>Yt;+eC<3n1ms9(LhroQ~l z;JWX*s>;wJq4Lj3LMIeo;>__Wh7-S5``?i1zKFFNQ|T-m41$0RGFy-{aI?MP1`*^w z##i_ievZ<{MvAp;-<4=vvn%ytt_)O)mfW zql+5b#j2~Tn>_v}C~Qu3$*+20E5Yuod+;O#?vYVfBL6Zx)dRQrW(2yw;@KShiUd_!s4VP<&sLF6-(LF!uiW~Oc02> z2a}wBL|Ky^v{<6Q^}{8MDh>geHGchCDw+8rQjXhFHMJab8Q|5j*Prs7L`oHlvh3!U zbbV#m0tmg4Mz7HkzavwcfhC|575f^ve79?oXvD# z?%k`@o=fmoySuwJW$&K^8ZmiTktZt}!LP+kx*9BSN&nemP%I2ucu$OtiKpdJt4QR` z*&+ms_6x)bfTXtrbm34m578G`oIq(0vlsSjy8Ley&JHc{UV%+&!QM9{LHUJL7DMcW zw)AtV7W%$%V5XD))t}%z0gukfIXkaXe{#(H&fs?U_JbDcdl{ry-)oW5pO&Y=SM^&k zj$>e#iTn;#K9yGFjfb)nQCtXSW?@mWD#<2dPc{maf=y2sKp-U}1a(=L+9s+Y@j1?1 z@@(AD0|fx7-doD?=@R2X0x{}D{3*bno{@Zj*A*KSqQ!B&kUi@-)Tz<^;=si+R0Wf#=j zG8r~v8+|kUn)rKaSf!vLGO6&^Ge>m+W|o)rgE5x}xNl&&doHHl-v7{-+~Rw$y|S{TqF?Lllph^G zIu1G(#^0WOZ}v2$r^tNuZs{|Vrs`($vKbU-90_N3#TwbooW;l8YsqXJ*^Sy-J}CUM z?b&eQ+d>^dXYx~;rLw^CA12J_nlCkVBdPK_kZ(U8h_SRcHHGd>fp;fi|Hlnf2b^i} z0;W^!ySK7gcAO?e`dfvv9V|Zb1C+f;%rovAI4sbder(&pd+;h#6(%T&qJVs7PQ+y2 zSa6qmRfv^GkyM@LFJ<^?GNV&PMP2>Yh?iRG+3NqgxA_X9RzbPLE%B0(UAf2+5UG@!iHT#m@ac(~WT|I56{xA>oCxI+^;|viNSNQ_3 zF%Resv=OI2=E(${>|dxdt2nThd+)Ql4`}w&fWw{Ougt}~j7mrP*O-}Jzixmjh`gTj zd&~`fY2VhG$|{+vYXiXPJWb~>svjFOg+!W&ct;i^M31l|ka>539kUSkJHUc8Dlq_f zW#S*9c3N_kq4lOR!;ZUa-N{l0Rs;W`n4kc*?T^&UchWCDacGhokXs3jl3O%@Kb5B-b#P&#b$=FYKH)6D?3c8|8)>3~O!RRe!hw0*TV|xjti) z;FE35D4CIRTnt|daWP#>zb%vT#89>JnR95mNNqRLosIiWEf}i)RkCig3O-y}@QJK# zZx^heH7=*BcxO6Kd@Ij6Tby#AS@WLb!pmv0q1~;vzkBTB`ew=TR-ON>#HEVFN-zLX|BA7FnUpN7Uwj|5m`N9#x;B~0 z0*n<8P`a5Q>3#9+`Oa?HBCK4SDe`S}-~NbcAB<*>U?arylH^jEqRp(=caM-6EVO)ju&P&4y?n{2_w8b_qVf$1Xl&t^M{$k7 zu(_Jbw=?lu;WkxHVy%YaZpNOXIJp>9I|bTHR8j#uJAv8}K5)K0WcwhNb$8#obb9%4 z)+cIpX_T1r1&n>$_Tq8bea`=G#sBC$=hRhN+L~7P2N`>dLF^Fd zLqXFVr|qy-;&jyEkMZqMis$y)=oaRlTRPsDUQVJLmq$ct5c2MhD1;t#0DKx{F{rYt za))AVl+kK!;Nc}TXnq!N6SYMNYgJWI53tnzTHoc`NNLNP;@r9B@kkzG=Xa&`?e8!J zexUm;EcV%7_tDbV1h$E%!e^0*!#hjfN;v}&8erj_o%K_nu<|+Cvnqti%Ho?`bXLka zckZ0xNpEr>v8ehexa5-IH}R)CLTab(JMDv``e+7pPl&Xpa-0q6mVRsePU|h8s00xj zgB#7P8z%DPPQZ&(GLdI3R^5Frzvy!YC`Saz7UE_`IN$%x>=uO3jqwgM1ET5j}h z%^6l4+BRi5ynbekxo2xnt`4REkDKqvroE+wK>#Q-hy98C=D|{AkVbn;3#vh{*MkE~ z3!#$ zHJ6dfHoHPDzkuV#JGi*Gw2Xo+>7m=dW@PUsMFeygaD?EIalr2HAJ0dL^XrX;%g z+14vB9`plJb%AHYWVikHW}h1VMDcp0l7*BBnx{GSKb|HY`&#Sv!-L&|sO>mf*rhZ< z<%hS#i*bHA!oFY^DAmpomXd z;^J#ZtO}4BD#X|wQkb$&mJ}NzQHTn_Uq6MC)1mjd2iE|<h%r`jIMnPn;RWKbhtJh!OU*UsS9ydm(->)UJ75_X0~ z)5xT8TBZ|EyPs3ch8vy$s+&8Ts)B#r$(n&#KAoxckq z>i-Paz}7Prb?|4X=wfkXV{c+nBJ8_&V-~%h7Us(nFo7SZ_?WzM@siKmp5`6qqa>B^(1Vihxo;vij{b0fTwq% zZ=GJ%zP)vLAln|kzqt|YGabHJQ33c@oLXYN=`|8j8$cbsl(r{ys}|hp-k-jhSZ8bp z7craN$**r1b-((>*J^;l+~0jL^$1w<>ziA>t-f;FrIX=>D#wK&y-H1aQ=8%YDx6(n zmOe`9{={Do2Dj8p=TB=T-s9Is_j%x7^D-l_+{a*7J`2oST3I(xZ=tHMOs!sPtaO*T z&(n>R=zM~^@SrHb$g}Zn{c)siN~(q3_ayS9bTs7Ri4)L05E?*)qIsQ+##%1mgfQ_` zbZxG`RnJyS;ivMNBZZg{WdFqiYj~>BX$35es<&#d9fYn(u5mE>1{II2zv#~&EWNd@mPW#g4F>Nzl zv?JCU&kIf}2B~TNQ>~8+X&s*nwT8zV88w>ABNP9xP9j)98T#<;&me+T z6_5lG!2eW9hl*Ryj~QLdn{qbGq+P|ldyMk$;O@+2pH~UA@@mNOZY0#!#=_hiC;Mo& zST=-SdgWNTH=)*2iXoL{=!%yoqTHbzP9GVRLaFB@0dk;KpoBQ7X64$z)TFWotl)ITuXo1ld zZ(|bD&!KOlZ`7Hfq@xkB+&em#0jtLyzc9EEbhS!e2ehQsRTG&dU#qLB`7}=a3s`zH zeX7l6M-=}(*s}H-JL`p`HUpXCLGJWvviV}_(M*ugW*lh;63XP__`YXwa2D)1IbZM-3 zFQ2K3&2obM1&0L5HJhllRog+IMyj!7*uma7wdWt9Yza+c-SU*x0~w)CA~STA3uJM69oM>PHYZqPjU}hfa3NU0m}q{s-(!H0T==|?W)rbt zl%Iu4qEOB`)D6u8b+a_;Z*5PSAWeI8F{r%kd&NB7IKVgbIzI<@Cu*VF?z zoX_=w|B$R*2oaUZlF&>GFIde7*A5SH%#1w%LyuRcdlkO_6+{5U0%qV}haH1;)QDLu zh7k1Xc;Gj5+|pmCQvGD)I>}jli^lAlH_mO%{`;8-+%K$@w7y!IHFs4LD^K2vc;%sE z);KLm|Gm-?E36;VcaDfl*GBV~=e*K|1BZ%%2gQ`*5`kc3v{rTj2ULq;o{^FSi|(Q0TggOZL^wu#KIF0Xu{I+&_P?k!w`J{TbG2LOVeb zax+m5Ndf!7H3zJ`XrE#K)lTSzL~cV={iK(8-2Ix#MWxks=lPa#PjlZB2={!-Sd8=Q z`Q5hrs9Tk|KLG^5ZY@#!{*vd=GVXaZy@JF4e&UD<8jq_dQ z3Lc-EfQAq{1v#Bz=wxPyx;Bs;vogQa{6&(y%BXlU8+=!7nk)MXD)!UuS{|hBOZ}0G zZ37|9_i2hIR8S-GVQ>^zw3QSeX14GXx~S&ZJ&P_lz*EO0*GLrOP?BDFK};JUHhvSv z7Rq^Us=^&~-teF#ojC3cd-^Qj&|6ex0%Tf&1Zi}#@pmQ2`}_jlCceLrZ&YdmG}^l{ z$59WRVf{;5NpfBlhkjevl?zk=nSXioBHXa~Rv4wWc7(Nut8_&C;~=AjPR{{Du#1~S z+^?;j;1R;8pP6H~do}10=l{>B<;AmtT=ny*@itNWr!ltm)*wE&ztFwi4M>F@2Vl_Z zdeUHFr9;VEb!^p#`$OJ+v8(J-D(ATH4PGDhUO68tFz}cPK+OPPM09$=s%b0z7jUc^ za@N7RsoHu?tzB&GGRaSTF68_2*0C(UtU#+^LhB`i^XzEZtYlF3rY>8-gnYB#dQJMM z&J2K!lMKngF4uKPDma|1YCiy~8lTyOcegLx_Jqd6!!t26$phD4+#w>rYTk4%RT!wP zsmT5lmCt8p{Qw~p4W5E$@fj?{8;RN0-S$mDz0EC`J6@M*CjcluJ!uB>$$(iN$qiQf z_@aXwY@z=C%5cEp>7yOaPw%aEbO7p)RZpNzYnWoeK*MCp(7f!y>|uY67OI-!4K_kH z#N^^8fCS90{Z5vRBAEMFw>>R4L=uAi-MQ?H2}i~ z9O2F#TMajuzB%@tLWx{kxOBKD+a3`6>4H7eYLTf}Ukb0`JrqpmOEE_NGu-}*Z-mSj z(9l-PC?`zrYU~tgD2#o-<5O%L+wrDSqPKf}eiJAG{C}`L4#nD5CavDVwUnP`)oSB6 zpE#OvvoIlF10}M<*rF)FD$^G(HP5)K)|NAMwm4!S0UppSjlke8U}F~6cYp)w1B=Kc zi~T!__iNaRk#2jXKU^V3dc{%Oq%`Hp4Z;0CE{4aUp5nhpg0tXiW1Zerq@zHOB?g>f9ah`_kLbHIhP0mrdGTsVOMWRw@LB33$f_0sJzKULq6%Aaxfz1Hkm0^sN_u}aM=6?;t#<#c4*h;!E?X9Hw>$dn( z$w--)LF#!oxB9WK2%;64hV28ekh20v#$=v}h7x##``*}eL41VOd#ehdg zk!2-V!S~mT@A!!~seqi6w-N?6&6TeaH6L~Y>A&~u*U;*!U#$-8f|fwfX=J?b3CPY$ z7mWo0jUFng{H@#5Q`H_$Q}u2f>8t%7+>-5I98lDD8tJKIQT%mry`iH^vRI(U?M7T^ zzBXE}V8EvRz`NCqDG^|Thg-z3N|!EOGBO)gOn~y^GoF}3V^-~zg3mR&dAQ-Zk!YT~ zqR+s0u60$G@Fdu8R5(ebhc%5^G&8HwUZwF$WmwTd06=7kjz2&cM8BN0w6L6yp^jP3rA zy&}Q=my?T@)>cwkBu7HT>QHjp^^odpK!RNJz)K@e+-Nbaq#AohztxUdp8+YIYu7Z2 zWdLCD5Na0^wxeVKGN?h3L6N?`z7dKMyPJ!;vevn|>Z|)g1IeK4n;e)`K4%cQ_iX5W zyLJCAytTmKr5Yd>$oTwb7TC;f!MLJ=Zit~@HTqb-vv9L98W1Z zz}c2aR`*UYdcodb(7v_)cW8(((#RT4$P0Rt5e@rpX#mP23scyNZi$a1S%B`p!R1p) zK;K;xCJke+T7O&0wYHvfN`2JS-gG`K%<_TwN00-60uY|gqjt+LPZh~z^1k=Lmcx-x z53Bdm4i^r+g2Ore#fvn+gbR4#O7!AtqTPBd?O#Csx_a0*@5a&*U`ujKp9h(xA45Z{ zv8-Hbd7KbuC4v>67xmVdP>f4A?3>@(Vua8C(Af4l{Kf@vC2a>gXCXpPsrQpqv4#`$ zpt>PLNzj1u!LHJ{L_(6CiSIkJij7o;;c|aJ+bcXcbA?CvpXwe0T}0BvKa}llQ2qms z7v!pTLUXGT5r<6hC0v19PfuNKvsrDPH-c|h(j7yaErAs$^YZ3=Br)Ty`xJeH576() zi(I;S-di)a({_JWW*|4ez)#hyUsrwcM<3d?Z#^w`u_?f63vAt3rICfNK3IIEg^7r! zFvS}I`C^B=;K3ongRCPo8k|di{dlM=J zJ>1vNr{V5@$evrf-dnpNu^7Y(vxn5-YDN}3oQm(|lW=d?IxA_OjTYE-KG_=+TA*XFXLw(^lntjNimf0?l$~fG9{C7GUh)b zZ}L(9b23_e;Ic7hN)*6vfM<f}aOyb(UXH7qec}eKU@3P$INDxzP3a@)$Eau<|zt6^(Xfra#_5O4qwLn~*mpzx%(q??{c{DKlyLV>IhWS+EHAIN_KL%o#em zns1Yf25uzlQA-c{F4L=bYLnLmz}Zc(@K2yp6NKI)6}F5E(CDnE2BzUcR5y zyZ`~^UQo0ZnfN?D@ZS{yV7hNWyTmHWYDV0m4tJ+ZD^_z=%<|F1PC1G4bnk{=b+!NB*r78-Z}cf|KF^_>vtj-~ zChh|cq_Qs``Cwii_e2|gVrRdsER*EKP+HvD?Hal#-Y1Yb2kMQym@DB9u0Q;mUO!j5 zVW*SV)y0}c%Q7;$780V;nrChcFKSypg6WjI1KR&A^@^Y0OsR%E-zw1X=u|XB6>lt3 zC>!fU_)WNx;b;m>(>(@lWxV)44&r(|1zI#3Hoh2GKjd3J_gB-J2l=^qp5-LSUY|tZ zvbG)n9o!2wzL`~wRW66NHR`9g?-OkHesVg3S{M- zDybJ(sK$4*m_FF*N< zIMrB(bKZn~ao%c;lqDrEEG~lo#JlG;HjBoBtER!0IkvcY_k4k+jrGIB(XAjIhn`ov z39Mt;V0J}`gC!@6;sz z$D4NjbOSK>t`_OCbk2Dyfs-OfLin@Zr77!7r!TL-<;uY?)EAM#GPaX{*r#l>d`GnC z$EQF_;U~C%h|wjtPPkX_?3~{t*jM6-9*2bHFAkXW?uU^fA%n|X;jQOcKC$0qub?-B zV*5ne`_!A`Qz8-9TMi7QUX z^;8cMK?Kgd-dxMh)Fd$7+rzrltR$tmfI)*b*Z83LIfMdur9WH8plHPyq9UD#rrpa8y5!1|16kcq5E? z^BAe{66tZLXo6uGteS_!o+Gox00-zRN9o^p3DnTa%(bP>rG;mujayrwFH5NS1PGRZ zXu8KKkSHC7Q?SRo)5wumBWln=c?H!Z)ocyKp2^|n2NX*Y9$)`NVh=tJU zy4@ZHm6w|vxwRM!oBj6;T+-J$1-zCS;o+=C z|6LV?I{+A1&K=RI@Du3v=}Wjz#)djZ*0_WSvN>`e1ub5wtu8ew?`c=xvH0aUR!LO7R5Z=U2G(qm~bt%qfHbsA3`mZ zQ+)gR{X;|TQaJk0oj*^!aI)GKdutqq%;kc=Qc2Y~++%<$iI4J~-@>PT3za94P+z~b zY}oLRoDtz4mOsr5a#9@&a8BcawnV+}C=j1I0(CM9%z9T-!AEjB*#kpx1IQx9+NM}< zZRQ}BPu51RpQ_To=Gi(fhnoDXHADMZiBqlpdA?L+pS#}{Eq9!o1EWZRqkdP za7iBb^j+Io2l%zrLIwRRGKD!gXNd2;>7&jTqh8e%B_qbBnvaRmC#|oL2B~ZDAmC&jDXIjK6&R;(LlWR!QGV z1dWlGpV)~`f899cSzcm>S5BLH*sS*AdgNY-ulpeByhdbzZ%|lJSoT&p@)ENjqq1svS^!v z$;_(shVLtoW^dhqI!&t5#a`vgyPR{fbUVW~q@XWZ%$1)EJvC96vJqKtzB8k&{bFw0 zy_E@`ET;MV*o?)f_vZ_+GQ4Eju^YcCViB+t!wSU2W6Sl%i9+0LP8`DTGdMmzd5|kS z^sp&fXgz%UT|vb5_@$_=M$jL*>VThHppzjiMH}PWFXZFVW6K*A)iJeOQ{h!^=7K631LBS`?}}3NL?NaSq5HTW+I3l z+~5&%M%p5qW^{XWacmgZ>~*2&n#wapV-vT8T-WI7casG=dwd=1$0qv zP=v!*^H_Q3T%h=AxK1{latmwCuUEo=$99Gx9DxsfC-eB3I*GTuII*ZN=q&JhdXktg zuy9|V631hQ5Yhc!Dgq}ml^bE5V)~zfPefciVgGs&hT9%oG9Z{X7xiP)l$DA=sNJ0h z=_P!8d>C6k^=P3RH^c+`&C0ov!JJ$-pLOO%Y#ie#szzUg`pm` zGNUPZcKI3vcJYq**)$!Ey&qfvklFC2C0H-F&g+T*$7@e|GiQhYQ`i@lw2Hv~xab=r z4NRCKwFKk?XorQtd7IpVj6e~4Gxo>ta%2MH&B%uWuUM&eA+{6AxY<0`okqUuCIn-LiRLJ?U|ECO_4Rcg2hjIUs%dU+ zF-9Gwohe3r9`$>h@*}s$7l3b`MOIz1*q-@80m`Y({=DFP@>R^Qze|*bDeK8P#D}GV zd*sp4IT6Hrhw;BK06ux9rS()%ba4)czJs6!Sa`BIpar<%V{6LJIC+f(i1jynW2?O; zZSTZ)F=5_x<)0}+APpt%B>GoM-3H2q9H~aXT7USte@R^ojK_&Gz=|7=Y&Q^N7qX2p zDL2a2B4?Q(SZEP0-_D$f$I6eQbi|NiNrkNo3cRxh2fxz5dMFefXcbtxSSFQOUOc9% zKWvQBITItt%N>*G-(V_zV@28- zWT=#9ss`smt^f?w7$64d3hsN?TOLV^FG5^+uB*O0hkH6h2_jUM`CTng^8g*S1)x8a zZ@?A{dJdu?^s;!UQz&ou&;u3kvvKmhBU3>Z-i_KkJ#P7phRb(F$KcC1qvU>Vu-0x5 ztCV5^;{0$iYQLBv%Azc=ZvAjKZ_8M6RDK+O5qPpmbHlETwYkS*VJZS3J=`+wKgFkQ zhkXI&(Pw&)DOV9V*<6-9nRN*iGh8-cF`8P= z%Pr7|T;qW}r|knx7OINNZE^Uqd;nm$=GpjChWD9XTA5` zYR&O^!Tsh)xsJaN4rgZf(hc)Jz8x|a*O$wv$s3^Mu}Xz#{MsU{tDS18kf7z^P$)BH zMFfl89Wf4}#9Km``Z2d`adFmG0lV*FXQH<{&I$Y>8@;$BPCKW;&Wvf zwN9ySo@A{8s zSw2xC@n{PcEvy$7x(w=NbNZC@3~81Y%6V>T5IKHMaS_7?BP*QKTkIwbOLXwcyMG*P z7arMTM}=~fqN8mG&Dr|vF5{l+rU|AT>mntyFXvr3hIvAJf%8)lu*VjvWdB(_tv%EM z439>XullDTxdZcKs%|{LOxK`rhu>wx6ZiG;DMw)94wEHLmOPV-eTx-tlR4vkhZ+nZ zR_~Wa?MOorB!+Mj7boXfP6`a2`_XFj9?#?cPg7&kE??l1A?rJHB;llt%jRbsDC6S` z6hiRL6>v&zZfbfV%jfi;hm-Q;;$q+4D2Z(74!Z#wDdtW>2ES(bi!N_*cN%_9_3jp* zC1vyl$KhA*5D4_gYKWB9>x|0Z6T5N( zDHFzF%Pm`$E5f&#PCS1(7q$V|q%tO?sh7(!w`YY*E2!zb!#ey6Fw-yd2=vkF@ z?P18)ufOlIT(D0`r!y=gLm|TN;aojas>>~k4P_GlTuH$-XQLbYrFd&=zV$mR z%Rxj&hw`Wc?SE%y*IK;kg_eACL9N#L`T0EE$21krr$ug)Gz>;SNY#)$s%#S#3yX(t z?zXBt-rOn;wBkyLEvpbO22CX3QzcHaZ+pHwQ>1dapNQ@h%jx4K%_T8h+f0#|qFXaj zTP_+L{p+j|un%BIu8`l41UPr&@;O>Tlv3W^<*94eBO-uwS#61jVEWZOz{-V6e?um* z#zu}PFy_9yDo&lzMc0gbw?`hdR8E#Bm%}WjK0fsI$kUsx^K$%8QSIC&+el5tu!3YV zF>DLuPl}3)@>W+aMXhMc8f=Pojk=fIuLUX(cy7}BLRv+K%GD&2YUBOmg@z}Dpl7J%8`<)rEbKy9aC2=3Q)h+} z<}!=?jZg4cw(psfHR5MP0IizaJ>T>5(~Kj zO}fR?4c?6^X$f5&RZ;tN)~)46uT$F0H{MxFFMV&ilGAqt^2VcL;4;lCUE6X+EEU!X zJ(UP`5V+uqB|^E5QH2*H_D7QmTj%TW0;vg~O>emhxHQ(rF@Bk}Z!h+a&&@4c)}GAKG!&NTSUB@tjEMoxorExki)67T!JyM3jcoAzp`q))Gz$8Y)i*o z2>bKDegSnW>TMlrnCHJ?iN|bj%d+Lma62Z4zYPqm^VJ{zU7-QVI4x@L+4jSHr!#zo zgzHmNQ}aMlQr@4>sUqj-^XTSXyqHv2;%40za=Kg3Z0vdn{&bN-h=KSBif@wHE?4+% zA`1<8>O2%hznSHT%42M6$4%*N5eIvqF&K6s@t&}j6`5j~U$W5AaoxeQ$rNYABPZ1ii76iYdiJz;Hfbb z5)kB@|GGD1`$m2LL({p(Gu{4wd{~(hQ({V(93xpd zpDl+7MLC}na+pJM7GgzA2bK!!BxH;-rkoF%8<`uKSmu-#!yH0#`d#<$@%aARA3d1u zv+H`lU$5u$(<=~P=zjA69Md(jraNv5nfBibtyJjgx?Zc?vwY)LVq#QWoQvjZ=`V3c ze9;0BqqkQfXpUaVb+X4b*puw6;2IQll!D=m*RvXHY3qL*d!yys-b4&Kh%L<+}?*_E7a#_g$SHkV@Gn^zr$aN%+_2wn$U#6`$VX?=JqxlvLy9 zryC&h=na!9QnR=MxwHBpd_UJ^JF%jI4^>a#uh#4$&f#ee{&+C@1&ma{YwR@c0->bX7d zZ@4$R!`tawvpI8SZ)&nV9)#ap1wn`!Kvxw{0#`Zc=Nv#b?5r~cCG?(IMd_;fI_|hR z&RlEK(~fN{sLWW1GRW7DSpwJdEv{tpAX%+ewq1VP8od%Jy!5}hgV zw{L^<@13I}77pD+m!_N8Kfyii&WC zBf+)#IXUNW_al%Grk2AHo&D4Dp#tWq7d|sE>Mwiws@XOxr;R zI8^pH^_5+g-9nhEaz@J8*4+*RC{j;fUte3B4+7$0iOn0kg3P_%v}Reotf^`uQS?kx zeMHPefp$a0S4!X~Acj+)7Md<6&aL_Nm@1nzjETULwJgf%OlR2lTcPIpB7lq2*HZ^o zt*!zTA^r0W(2~ z??+O&5Z!Np_okHxepy%+&>B8@NQ#TAQi()WY7`zYVe$KqRDnbmWoNOYhZy+c_R5Ig z6|g8y`ZGUL(g!riX<)U#w;Q@Q+~2sxz&wAuxyl+R6nIpRj?;$yMKx)6WZ3c+xvWMt z@14Y{)Ym3hh?qZ&M<^U>3wxCdCS=Ti=rPUTg1d=gS)Ii*hmIofyW0&S?rp2u<79 zdeRb6DDEvI?J>M|>+D*qySuw=K)3b=P0Xje>Ocz_>`bR82>8Qjnf!ZjJp_M21g)+@ z_jyE!YY3ok2nY&ZFN00fH~$+^X^To5wIBvvj&|f;=0?gO*5YCrYJ}B%p;KVA ze!voD_BkF7use!Hchk`js#B|}`M)unE55ATuka$KcTvlWxlW=tI3}k93@HUHPYm3JyiLoNbtmJdFGKxS3)c-W~ z-4+*k=c*c~PZVPcqHD@))a~s_8cK?c3VEH2gH_7c2h9q+agBnbE-Z2Ha^;I76xuJf zE}a_}&-5w24#?$Gk*lvqyru-CZqP@^z>ZiLKk#4s{VuG?c|Vt)LDNOC#>P)#hs-UX zEB6wK1vb&lq`k4KQH9fD{;M5UpKnFQ^Kk!RH}5LpE*zGpe|s=4^Mr~OxR(mD)r?JX z5Im@+|BR)0V6G||8v#4easD{!^PN-+VX);GUt&s}kT8=DWUp85zHE+T&*ofny@9dm zqlJWouvR~*um4ypwR5rDT$#B@8fs4iU@h^J7p5-g0o;UAvF2X5Kik5=I?^ydM(*@k233&9(n9-=Ibk^-V(MGic34 z)qkM7Z~*2>HEWbIR<3Do9=$v7xz{&6c7po+oPbXrD;0b`#%XLHs}JNNjQ?fv#_kJM=KLW#a{EroSGt*a-pdsA+e?~TPjYS6nuUO zj`of{eR#&;J_VtF99A)r@r8j^f2q*?^W%i1RjKR@!zHuOfdw8A_t zjh5$FX)~qeSHKOK)@p95OOe{1Hryo+_oN6q=NczVeP*T+mH}PO2zqpg;`%uA&GtMQ zJU&Hj=aEj8^wiyny+1vBWCa)M)JD>u-KUR&r?6<&o2(R z#_D0Qro-gB=>z>V;Uhm2TAsmF5|?%vv{|hTRX_VNy7fY8X7)$S&{{7kN`t+o!FXeM z%!NIm+_Un<8GQ376yfd4B6DX3XFdFR%^#I(D3R1zZb9xfq_b3KbNJzcr>2txO*%Dv zfN~h^^u)K|vs)PF1oZv!jU#A9Zx;}QJkbFzWmvBub@{9Cgj+FM$M_o}V8%Yd5LIk4 zoEs9uLCLkI3K(PI(!!mwe^-7C1=g3&?U&|9auZy6Qr6;XJVMySMJZ*lxZK}9!9)Fc zW%xXdrY(sUHjQ-WfdCz!AGu~!i-kg;NP2bTq-OphRzhfKoeK$QE&AcFRv&=W(vcL` zGTr&N*%@|o=V1o7E}lZluxBhmh@WSPAnsIqs7M$hRdm(G+~TtqnZ}1KAF>s;7@>an zR^f>7!M#_fJ8fioZa=P}#Xp4KMex8-a>!)8K5bEEe7C~qZ`vS0ThAw79Q?uQKx^Z{ z6V<9Q54qh=KZQU^!v9&W{^jyWkU~VXr3mV_qwd5Q)Iab2iLU}BA>vmTT{a{c1B_EW z+7Aan_1#oDZ|pm_q(UJYRw@hSYF(OW-Pvi}>Ax;7`FnkR0|EnOJ==uH+b3kZ-h6Ws z&8w4rcB+uhwwE!ncXYW}DkJ@|^puY^Lt~miP_U>*!O{K;apc)No*d;h12~$niZ*#x zMFd|+>Mq_^Mlf332nBDqa(f>i6n=}x2pwQ_*<=c6_aLn^H!ZYCb9L{!wJeCm{7m~u zU(%-t)+5{fT)_-8=P}C7D@P${^wKUf(b+z7FhhaJrluyVR?$eq?2+IKyv^Wzm+PhS z+FCLrdOS8-qn-rH8pn#R3d=uz>ga2`pM(Eu_K6sxqC(r7C^4K{JAxTin1Zx07{}RP z#_Bs$Cm)@oI9F;<7xsVb=~|E!|2r|9f9MVLik*E{zg*wSHP`C_yW9DpdkZi3K;tlm z!`!I{U+zDDul)Y?>ye#_(BT4JNgQS4!6GK(ntua>l7XtIUKW^Nv>`>nrW77Lc*rTX z`1`X^6YSY{Pxy#KU$RC*6Ib&!nF&5>;xxYqEb2%(#-#{^8V(A%Vdyzs73tF3l6y}L zt6k1fvrq*Gap4RK0sTP8rBc&EoV7X8YyMC{*3Lo*g`J?$9@G?L7;4sjwZkrAFrH*M z`dd%@@YCVgTz`u;?Mn8_60P6wN&$gT>5#A1J18UeuruXc=`r7{40_}hozTn$y6c&u zg5J}7KpEnfRwX-Ey0+jdW z(QpAq@7(VnL*Uv2w60}6`3rT=<`>kvjgoab1G7OZ35dReSCq4)H4xYBYSN+wn0pgD z0EgRw7xuMKcw!kL1n4Ma2vWra!X>5fMgh{IEf1{)F;zI4OB($N6>>!c92}qeGUJ1+ z-b^qE`wM)gR(P3D^vm?BAVeM9Ii*MLW8rxPnx zUR?h+3v4y~Jrj4tCod=_JKu_o54!Vk@cNaj63I8o-dNl{o{Y7)cT1Sjy9f&}T>ZGaN6FT4;{&QxU+TM^Ys{#g<40hdFJLz;g-`RyBei`pt&kV0=J{^#UX@0b^;lr=xeW;LYBD?n*rUHsv3HY z9TMzxK&Hu2J|OpS3ar)46?Q&X2F?w8tkJD=9%fVcQ6Xc&PpJrer=)nke5qk~s!*}S zY6*Z`JRZO(^!*bEe+;9JQzJWp3#WSFE_pNs9_upwY>I_N(IS7XLLhS2o16}tr4>%b zHL5eOSmr2?6RZlgTtwIo6y53Yr(27(1o)db%8D}xAGn@zjD}}$ttn(u-f%|>A}U`1 zpDG^*)rGA6_E#dz#$%=rLE0w?JO7o^Jt~H&2p>%0+l|GJ%%}K%n^XHC+rP{W>*85Let zpd{9k*ppuG@WuFQ5$5Cs!`1a*=+d3!ZX)SL&&F`G0V%xiMPD#M2Cw~h)x8J;EwI>=p$FVer z?LX)n8gBh%SE8gF8$5H5n!F9nD`N*K`U=ZV_rtJKh^*;%r!ottb%6&eA#!C|{^bh~ zwd6L2a-?*6GM=OXzL1iW zQFV{)EbgPs5L*)pg^-kD%z2otuq&&YZW#nOdcPQ!w2~VAf~oz@2Ol`S%3S)rz0z~$ zMRP)=PX3v!$V=mKJx=cGHCMCY;_@izun#Ux2F+5qx3LF=i0nL6ZpmzKu!d(vZsttM z%cSsgp0WW+4fQPK_Iytt(loVyX?yCF5x3Ornz^N-m94uYARxIMH$$A9-=3GYJ`8P{ zWjnI`Sq#k1(5fi8L#H?15+L(k6hBQcuDRx}g=u{cq4<}ughW+a)VdOqv7IFS+5cq$ zE>qu7p5)9{;15Hz#0B2s?I_(h*toNHV)w<`abN;oS#e6`GoTlb-m^PZbkz(XA2oqJ za(kN};#EGIdlg~~gZSV#;&A=N0S&eEXWnNXD(3U288hTV4gByzDOn$o$toEP(+C~) zsrV3e>a$6ZOZbYpDAs|6(@-5Q7a{1w9drbLxXcsPwkw82`R;5BEp)8kxR+ATR zqXh&C)TbwJ_(vD`l}0yVTwq>#MJbtuy5=V&60|*~lDpsB$fG>L*bhezUbR2k84hCZ zdY!PEs(`$?)}8o*<+V5-p|7-R>(#}24maeb{+6)!cQs6!C(6v+_UrNA&6_`uvm4hd z>`AC&$zFsZv#kj}Dqe^kES{-mku3w9_YMbHdPWMsI%BQnGu}yxqDEec+)D;Pd(!StO)9%(Q{C>AOD+7SWG`6++Ev4AYU zf`hHy#O;-`%9r}__f#w9;>aTx6tgtkr({8*Xa8Qk;ois%RTFsR;un<>sb}fZt=gK@ zFsfru%?3?7-~Tz?y-_aOftOP=U@M~~gnv|wiEETdQ9T?UmZ*^*>p#pmD*F9D>!R7q z7le+-ORbsd5v{NyYMoYwX4%w+WYXWizuhRsh5%WjbBuGt=PtZ#=5K!JOQq8#gN?0T zTJ=Et{Q^t{RoQFR^l)*GRg?#h(T>2|^-fxXc@EBOg-I7zni%$V0HZDdRwMyc zd@`Z;;96*7w8o7d)k(ZqQ2Bc;>LW=L&MGB8bylf zg1!v?7RCsN!rg~2-)!QBe0Oti-edk(z%WDrkaawm52(&pW0|k^mL^kY0u`|c4o-|s zlzlbP5aLR6f*HhAW-Zgytyfben<{I-RidIy<|1DQq?K5zYKA4(1^6<|!h@@2@y1pK z8v@+uX9taI4qzV@cLjcGgYv+qv@%Sv;E8;I>yhf&e~uV;El;*K7M}c-QoFeRGxu_y z|MRpK-e2dXu(uRNSZ<MF_4<)d_f#om&Ry`N z#};O(kGj-*kaV^ZVXg6!Zs|E6$yr7)u9WU)o7e7ua7!#pS^}dPL>=)XtJ9J}6CL|6 z#EsEC(OCP!>jrL(*%>~dHjws6=6Ov;X@13GI%>3Wf*G&qt9h72oMSe|M~*oK)z^!b z2y>?+r4dg}0sLe@WI?-O22}M{M%qL zUzpGFZA$6K3F!=2ThqC3MhHk4J(e?CyvC&!#08!1e`NQwp_Uei$)jk;u7L>$5(;mH zCuF~c7^y(zsujA6L(0kYPjwZb5V<;e5_>^dHm9q)qAZ``s_2?7WOSKG=S_pl;DKQj z+g!VDghlwkrUU{^P$2KsKvsG(V3rEEVoJ2u5_d)n!sas4BPfzEd z;ryd1Mkd$lM-o@pp87g-!{KtKw!rXKgYXWucK%A$CauvH)6d=rzNqlGH%&5edGjgg zJD?m&0uCoT5;qymoB4oC{WWr}{$Zlw7=yi$Mh(OqJ)-;|C#2)z6aooupUd%_rXkAO zV97(nKNG2v4I50?&}Mb<2i?TDn7#fOwZ!c|DF1?U>%GI{9tEE9l5lEfM_{zSe^QcR zuN_tu98=4$59;Towx74O$o?FDOsNp~)5pHz4|gm0G@K`#5EoxuoKJxhiET-LrfWre zWKC{piJ!I9Dv|nAOez6kNBfyZE;JPBmMiO9UN|I#Rw!zXjDJKMP@4h(cB2b}CYE=l zqUd56se6U}H?$-`&jj=)(n1@SAHjk4Gk>R5%4SNS(s^iYwrg|m&jP2r%6`CeTqUzE zYx>7bSD8Y_{vFU68375U=qP#o2Ts%N@Oa($t+D7!9$EHs1?7mA;F@mDPsl@?v1*Wji;RS1PBs}(VimE^V-&c7ePLkEP|NhJed{(i- ztbY2c|G?5GwrS z;Z^YZUSh_r+=^}(%-ZL+R9m~+Ff6$^Z&N(T@kofib?XP$$4`y=^;*%)Yq&wRRG5sj zcxTr&?GpY7W6(;A=QQd{9O6Rn>?U8Xb2=T%(&#!{SfjE3&%dV`DFbjlIjsz7lQ8!o z#oFFY@(_kqLuz?iQB@dWwD7{f(#bxKWykUlq!N}MN&U}WJpPSW2aY3}x zoPfplj?BLJT8w^vl`Y@(=c4G60*E48@mR?^wtMzlI#?o#fpRY{Z0T~h zT;D*~bx^?=27{zl*r9uc)lZq_j*L+e6IqaVPpk@%3G!}Y`k&cndwBU~J4 z)010xNj1?bSXF|}XmOTw)3ZK`uQozJsLfV*#(95(AQB=-LT&NJV;F~58iU$(dqX5E3 zum7yg2Jv#6Ty{NTC@>xW^N2ke1lcg1caaBbVcj#A;CY zxjG!8${a>hh+9=+KHS*+h5cv+*CBeZmzLFPFnLT07c1<{Q2_T-M9`ozCO`Ka7m}YT zZ#z#&1DgjvY1}}S0v7%Z&Pm993wtADgN8LK%OjMEU`S@HWbhJAi|kUF0i?$_{~Ljx z{@d6jXhT^`Kt)jPx`n8Ar3w$CO6t>vaF0P!ZcyzKt7jx>uf92!MJRa&!A*h>ICUDC z^8S0SMKuyf4aT$=W)c(KY)Gr zD?-krG49DmoMvt9-i+a%EM#JFd5lQpj5iN|wf=+w+DOlr1y`-XUZsDRX<#IUeLqs} zSay{9&$091eER*1pJiEHDefG+jd)7672!=C@%mTL;IfsJ5p9$ve`jy%QW90+HC_gU ztE0Y$wBCgm*wH>|H3Kt;C?t9Jm8WLS#2cQTI2M6S`_%eM@ba&=5?k?M`-4KKh<0K% zwVDJgd729xd^W%u4D7Ht;u8No0n3I0HC&UEDQr7MrI>A|pusoc$h?{GT zR+D#RW3kgF)o$SJUpV=`bgqsFPww#3{k4XjC>t7xyJX^~q5cMc*)QcBO)LlvamW7S zk}7rMdcBhh3JEbv2@{bghG5DN#js?s_6VwRF~$am1suD0vaDDdiiCm@W=dVTLLqfd z#u`Tl@eo^i-79DzY*hu~&LCmzTH_iGP@Cg7I4=pFmI230k15s+4dnIYvy=ZF8Cv5Q z0De)3=Sz>PS#H5|Pv!kdsM^e--h}18<~_is2PWb6&A|Fm2hG}pkAEu&(X~q#W=8@B z)$C?>y-Z4B5`01t)c+r%0=rY=rzQR%I;#2a9N>)w zb^r2GEjW`aU+D=B8u5mkvp`1odv>!Uwt1Z0Jt3bn*4PLpm(jHyE|eOt?Gf@N4MwkK zU-SK(7}aAnRkHX15{QtF$=N~+qUomLCW>YGejhw+K_Of1b#Rf zey^Zkz(7pCw4bhUo=*(XMm&8$q%9elivh$y zh%IeUtrJmW*BM^^7J#x<{!H+s{HraG{dKq-_aWrpUSQU_VwOdZj~}d4(e`glv=Lit z-2&%06=>;`0pf8I55%KUN9Y+IJ0Je8%$<_b@>GHEy!hjbe{m+4 zxwW`nUcIQ*@0@pEOGiJpW1l*G$ht#IRC-PV`$5h^T2a;vivA3U_wnEZYFC3tA;Dsf ztK-K^bfu1UN9?7$5a5t4kB0fM+y|=*Zo-YO48vP0(oB`ykIKsOpZt1i8m7amD2MQ=9xKn0dHu{7hH48aP^(&im%<^1 z)f)oR?`pO+_kLb_$QeTlugC34UJ0ekFd|>fl442vtO9jM!X`vY?y!_`m8l)Mu8?tH zWYN>VzA|B0Ko@-z`}Nutne%G0*QB_(wOXEs73Wo*N+ZO(#b-5r!?#CA=0DNBS-Ezb zv!(aJE+gEpeDbQ(LSCIkj@2pO^1JZjaP9_AQbjqP{%v@%(Kfi2b|-Zw6*SM5V`8SM zUH$#L)8-F%0fuR1CN-^jYm8&C{i}WU1{n0Q_P~bhH`{Zkhn7H7Oj_RF1or>|@t5LP zEO}FfjV{|44V-|yh;Yd5(B(9d$9_^rcY`&@pZh!CjEXvD-XG6N+E}?M)Vb_OR;27p zd50NoY}AJ&_a6gPzxp)uEqI*2wYWK)3o8YkSkCEe(Pg>WKZUhPWLAxZ$WL1sw*Imo z#{f^dHli4M#OlJJ8X7uWHWO8UBI};5xV?Qq))P_!_?adrjq{3ul(T~@8tLrlyV}+H z5|i5zrUr(A{B0mDc9jty&B?f|EFzk=wZ*x;#fT0WXO53`ViSK?Hd{>nT3=vz!{OXy z8FhzCX6=KHl|RXf)7w)kQ=WTk?VQ_tsk6XYob_yi-CO)*<@axKY0%vqP&?gYsVa2O zJJ&b1sgyXd;o^xl%dr^xx<6*x4Zc4m0{y`u?okl}+}t{IP@g{|dc=5XCwU9b4&IU~ z3#6RuF&mlPR7`H+8Smcj^PAVGGy(wx5hW&y0a;y+LAXaB_MgNd??9pm0(|xHEPB|Z zxS%IjaaC`W7n$`tv;Hpw7E+{cwnRHbAXBuEDL$4$GgqPbyApP6+q2>n%N`q7Ue{7E zyuGt*6qp%cXn7l#hs@Bb*6zWZ>T5-zZCo6E zZV3qNuc=DWSCCm;r%U7D_u7}2HhV;$*%f8+UOwKac#|e}QYNE~So&!~cXjsVPS?wM z&b-O%N0=SS-D%J846^d`OLCxy(GjD?&EyfxqErobk1k)&K+f9|nQ^ekwx{^96a3uc z$K!z>Z|wlL;e~5M7Lc8hS+Uk%6JesrtGTjNtH^G|ajduVQK~COO%xqDc0)A-(EcvK zg!tn*18S{M3`H9%1v?K7XZ!=gpIRA}A_vVBKR=6@)ccj=fH=Y_*r<47{b4MyP}@IT z90{w|(7)DP5yUYX`?~3;FJ>*5Q;I4k&KW@?-G{7Cm~i=61^NiW2o9tF z5Ax8=&)P`#It&X>Ow4!m8c>&USnDTw#Kwfoe(zj9UHIy1No^}$^hP9xZLsbYNDui15!kU-2K z@9Geu)B%_r94(P<1Fm8~@rKw?GUMEqFB<5+aT0ol;tGAN{?jYTkUzCfQLMe)xNao4 zDR#wL;hN<);D9e9KP7Kog?>kX@@Wt8OVw{M%w5^OR#O);>Zd2cSzJ&YDstA5c$lrV zIVqU<-sAL>Y`qH-`nQ)$lGZypO*^z0J$&TWi2TbAV~Q3i%j|+Z6>Pfo##hlh1<~QB z>MESw&a4Xxa3xE_8X_DRRUqTVC3kGs2lrAO1>(7iu{LxHg@8X$kL>j1|ak|INE`a9RUz^Fx0nLL=^o12?) zHE|2OK^va&y@;dOshi<8+C8;wnM3k9%Rw89S^HD>rki(%Hxp?4l2(2JVdcZbr5#S6 z{}mq{v(gFvlm95#+Z6{Kh8pJ{D%Q=>63N*_cqc{1itU?>tGOe=lfHtXJqr_274gDR z7?JiE*t&5`)`wA^pc8GEqq6PtikBtn+AwYov5p(AP?Yb0hLneM&3xmk>{aL)(AuPJ zF!xp_dE~I+4p1PO89xR9ELAz8CH|Q`2ZO4;ZpAkKGw?^=a2Kc$-Y5qB0^e|ag=$t+ zGE^8pSw25wp%ie=?wILF@UJ^f87>PlK^<*)*G;UD zLRYb?DUtT;mrBWtQ&R=-!|6t0t%^JnF@kTjh>Z1-Owr7aqjJ?DGSb43kG0LmsgG;u zx)Y5XEk5Xi2po!}4tS`kD5~(`3>A^gHH}W}jfrOysjZMB*KnozajJ-$)O?~Gd~snB zJmFXYdHkL2v$t+0+(O))oSjvKy!vO=A&UCz`lGwH?`lSWe%he9=KDP-Q!2_{Oika} zXmN~GNASatxPArUA6d+EwA&v|1lDpo13lV*KP>`$0D(ZyEqp)N0;gWmo9AQ8WWqu+m$Io-Z zw950r!)(a>sEWwb(NPx%tEI^s5UB|?jJ6M46qhx|D{_^7v?guMUQ+B}C*%~5+|r0& zTbTi373f4XumVXNtt#=Wqo5~>xZU~RTyxUWyR@I z)M@cB+c7mr@@(*TQB_#0<8V(;2QbDL@L|K9?X9nH<`+ENJ>xk-W*wA&&8+>e6h#)u z*xLsdZcRyn@XkY_R>X#swWXrmXD$vQg61DU%vy$VaY!Hj<>42SH95{B#6JZhlzflf z%Sg*DCsXv7Bp@vDws#dumN)jylzR>se-(^Zd|ma#eRv;Qi}iDrkaJv~n#Uem+uSVU zfIBinI+VRWIs6}lk3uG2($>>4uo}1yY#x?`=sot{N^|q>sJrDqpkZ?t{^vi)*=-j6 z`dK^T)>hJ=tP7QEyR1(i zE&Spf9T|C>#T?UmfJ_b-1}wgxpB8oe`4jgD@d4r_hn~#@6^6?3>#;A+QE~Lj#&sQk z+}RA2FHYOP9n^TzXxcPq$=8!^{QFbuhH$=1swBr{td!&S!Sst34dw2q1M!COcNE+xc2in zD3M-(uhefW;yO>FLE8N$P2y!i`7k?J_0Ml|AGeCxG!ot7bS2l7RL|}xvh~x+yWE!1 zF#6LJVTxh6yOTbqtDNc6zkCOxX|wJ(*wry}wAcz}BlQM)^4rS;DD36P1LsZNy%)HF zQS`QjgCJg;^`MEd)-eHc>%`FJMUjlEQ(Rc=Bgwr#@^(?U>{h9riF!^mkVfq?L+nHL zwlD3?8*XnkA1fYdZRP5y27~IrJ8RDP5PI3>t?eatrOt?{H#ZX7A}Ky^BR_o!yxTiA zWhdRDPJ?3XCGEbdFD^l(aORa1!W#ajk2?sZIfD|67>ATv02bd0ug&u7D!Ky?-r?+v z4oCDAuePVQOTh@d@H!5n9-!an`bH=%fMON{mj#{-k*SKr}KhpTmB@3 zLDPL7{l5P63SflX%;)Fzbr+(Ev1mMy*ZqD;p|#OYTK+v%(pV@kWR`Ykc%c=+{1J4S z*gEzX`K0b3j&#?2$WO@e3)s8H^Xig}5yv~pVCTH%LBK#2od=tKTYx)=mBKsRfx8b! z5f8S*xnJo7)TF>^{#RHFIiV7Q`<=z_ii(!tA8m|p(KebkButiSUnXQ<7n?4Ba`VH- zH!xivJ~RBFULT*Vb8Z016dp#)mMO-scL8tVsw(bC+l2z($Sdw=9G_;IB030P^LzJm z3*LF^t^^$>+=HB$KVf2g9p4I%<8c`YSJ5HuO`X}*8!wN)T1akE$?v*hr8=i`7rv-7 zreyj?wVxix&Mz*)orDUZbwT*nCy3xs_prarMhWbK!SlaQJ_oom?8k19Vq5q?osHeQ z->60VVPU$h2=w*r@4!zs*}~E=DOI{#Wo}u*398V{SDlO6r_0V-lPLjnL=od>EY~93 zhL@W7c|kbDu2hPDTFb#*{^PR;^6++Bjc?-&FeO`#Bj1Bj>IPkSAX+}SDwzjasPOFH zgN`uoy#LC}h}Yn01FXI`(W)JI4GbgHtdR!-CSi?{;n@%fSveIRQX4z?)fj#?k_297 zHB67f4DO6$*^6mYg?sQH44_9-*LvX&0;svQ9=()gh4`r2n%4X`{5nUB1^5dyYATh-|gw{$wgIjKmy5+qM z$g@;j)hj75-29oZ`T$&qR{yd$idRcvpU3xh4Byd?r4Fbu^uOJK2L?$cH#*Ob@6-#% zrEMJ#ZAjc;5*nON@~1u;{}_Ai)<%C?^QUN*3JcIo{gYOv4L8%0w$t|5p?iIWg*>d& z$*Mi~?1!rD+&xZ%zV_~X-`>>V_@0dtkcRl>@IXq)0rvKWJF`iB`+*er0w1BTc&DTt z22g8QW_(eNU7aRL7gny0>9Zc9yG#>A-6jN^ZYLS!&vQ7)^x9b4CpCDCxNL367_)qM zdij}Gl}9LK3Es9AcV4Xh*%y|syF4kH0FIfsLZG-G`#Cr(bD&MjLJI40oEn=85^tn0 zz>lXa!fDzH5jF*@c}{&r5W}y=CCYtJV}|9KkeHD0XLKiCusQLgbEQcOAvz!%?>pIG zpsk%tI-IlozM@RCY3-+@r~XvIQQySrAIV;BKW2v3 z&eHBl!?M(=+LnsbP;L&GH=Z@S!wZudvItV9!i~Sl`#zxqYLkMGTUZ9)R0_{Tq3YMs zpZN)7+L<$=h(h+zsh+dAJM%wgrld1`Sa&ua9c*nkaxJW*A3OKlx&{SFQNgen5E%?8DV!t}SNuIsc^sy-qCm#sfDj7A0r?ogLmQ-tYL<=S$B95=vIVJgL02?u8R-pLr2s>f;otcRSYY& zJzq<{-@=s+Uz0!-%1M*IVRL!UVw+{^rCV+ey_3X))%pG+D$XDc6iIkEuDY%1ERYRb(+t=p|b{w zg{VEpBL*#=~+Cg_2Xkf4xRUseS>F zjInenBlux7Og3i(U;>81)a+{abo5X5>m0Y}1KE#e)BIRxHUhM9;UJ|xYBABlcP%GY`T zl-v4{O}U3}Vzk7w(oRB*>~mAjVJ~MNngVkkyP%`y%d~_Cd@9}CJ_;#Du2~RJeX&S^ z9{_(rS*(f07lb`Q=9!dLMpZR)S!xNcK)ODROmB#$e^ccr)I_@TqN_1MS&=O$Gn6c( z?OOez^ZgWcllQqXaudA?Qg#v(I*l~gOZE-3Q!X-g_m!IxnWyYg8ZkR?vseZA2{WJ_Sr zaNBBTIn1#un*>tAbeLRmxf(S8MjjTwGmknHGE<`Err8~ilk&JK1_PcwUXJ#Wtx)Y3NGb~=XEF70hy zlGOV%w`KTea%5yASSOsOVa-#}T-Q)wEuX4<;!s+6_9-6_f6|u4M>L(LR4pKmFh^7; z=-q18&AW4t@n&NGTFw^m?wCkwb$^0k9b6*qf@TPvFsDM?VuL!ECf4h&4h}lnQSbxB zWtrC)lodLOL7q(rk6qi|?5R3Mswo?C>5kHo@Ifc8u|1X&cc z`4bp!s~M@pC@Y(h8()!vd&99H3LwtU3js1jzfyq15xKjO_~?-0jK#5&R&Y7&*^w^r z5?(*M^LyhZ53Eoj1$Nr8Z0M%?F@ZeFq10D7Ri~6_n>W-d827^IVp*yK)OR*6L3h%i zN6gacV>h&p$&?1WVjoYusmLP`#>N_f!x1i>ak9wXLj->E;Va%2r(qvAVii9(U1LVd zTFjU341t*Z6F-4W2DMhMC75@&f-L^pwXA^r;w$b7CJLWp^ehLp1kPK&k653d=~261 zl7lL`024@7%6wBnGzw!a49Y)zp%?dOsec-ruuah;q;c4@BI1LFXX>kgL(2oqXd(1}7TrK7TM%%6#x_ABzecC_T0fOWu-DUTv5Dhs(e zNG$#1W`Yguxs^Nv90ncPy~K*+G;Y!@`675ZCZ9mi4ufz%`@DSptOy!#$6LK#;b;T5 zn(E7L)w-M}Y=}5Lyo~5r8=Vd^kZ1ZDNm(Bp$^#OWY{Aa z3pkXSw|sqjqV;LJat{3X{-}!}5vs`aR1Aw=(_2?aR<9 z&Mv2UXQVG_{dYbKq%Vo5#AL<5%!l)j(}W%t;$u}!N1VsqK@nhgSDP;JU*o?ztYN>e zfb3!zyZuA7`OoIH55j7Hdz$}%x|HvW&>Wdans4eYEvu|2mNf;BJ7%smGS%$aTnTG) z%6$=>9dpT~ul3Wln;QHnLxD%lytCh0Gdxs8*u8a_nZQO6AYQm`?+^~oSYW;<`wr~L z_kN{~TTCx4d2Mv8ipIWh_30u0!p}APa88&ZkS&N*xQJ6x;Nvw+u`+y9=Wy`L9D6>^3+SBjQs!{1jE z6&1y#j4jd@0kQGFtm4b>AJvaN{15t)=DoeBJHGh#?^5AI5YpQjUQ{A6oNj#-o`HM?^|kmx5-J#Pj@E=hPyV6z=2u}Bzk?G_ZN6`+LPnN` zbMC_Ye2ids6)xu)JTNQ%Z!dW!a9aEV?|G^g^gU^2+Wb;qpGtR?6K2J8chxXyy9@l% zntM9pS-CwkBb%FpC4G_xaS2=Wg|u7ida;Fr zrv0FXuf00P_2R6pr*I1soZ$R%UczDPKaYnRO~A|~Vj!nJHYTQH^ zEA#WgKx-$2545 zvLfkPmLrP^{^5}iRPj|ad;6(S=Gvf5p}Hx8J6)=p`aANAnuYEViVFUcYisJFT>fsL zf>^G5`_?VB=T<@~h5ZT#PFg;Px5elCwpS^LW}3PWV?Pv^N*Kltd_8@ndeBU1tZ$K9 z;%&fwB!B8<$^g&5ktbvkMxOL1Ji9-BW{o725Q8i&#P3>P@j(x04b_#+t*rb#eB`@Y zw%0wO$pW1+B$OFAU4S}vtpyejMQ~m)o{P?Bc zR`jUCp3K3~)Msq=-3ag|Ge3Sv+z2Kcu8jRvHiEy*D&G)5{vrv!`N#R7o)q>n8vK1# zIk#J4uh_$o&_;(7)OP{Lsn2;0U|4eT%RE&x9n#h(?xO#E@-w&|n?O?I24SAqq+A|p z$iNfp>+0&<+-4Z!-ml8F4Gb2wjRhqQ-6|X`^1Ln6+Qaj*a?5&~cYmHw|95i)ZOH?f zKQd8pZbSoj1pAm5;q%?IK?-Y&KonA^AKNXEYGD*zZ$G9A*Zb3U|U#DC>+{8`6}ly8iD0PI?YxLp2|4s zD=htuD=aawUvZz*R~J!VZ(Mkb=#0qT$R&eE*0IxnymU@zV!%ch(B(#?dNuQRQuSH$ z8hyU?WX9BMT!EO_`=5DCBLe?vZB(nDP~9`(BGd^+r0C; zzpzBpCPe7VK^H9kl~oy$CD;i~U*R?)n$H<$mLAXf~(Xv3_`Yhg&AmQVo?OLYl% zmVa_>DzKjB*_g1l5Y4<__^yKJS{r(Mb$+DX{NWpg*|)n(?U!B{?EGArvxIU@HxP+K zaq&@2PHvTRb@ndi;R%f(KTIN4Iag{lMx>`t{3O(e17DpMI-PER#0(|v6gBsA0SMn# zE~Y=Hzoawmt9_YcXf&t})EB{bO6T7Sw+Y#Qd#z+`iR+p2^(}G~%k-Q`a zHxBwuQ7DKM&RL6FC@93qS_Bqk4qkT+&Wa>&S{-W~`6-%NcDyzOlbLc^XZ$%UKhjwQ zQHXIy_-Mp3#l$+6%LcE|fHp~`s5&H1%R&xdGR}&<75iPG++C-v=raN;H&bY+?XQM& zgpAbmD|6NNO;o?!!`L4|Pb(DTb%NsI;!q&Hu3$r!x)lVC7#7pjks?QM@Ly>=bcBCo zWADC_*AwlnMq*=wPvb;WR|U8sLQn|GjIY%)!0I1Tz9tf&s1V%ITlC(`s z2>gu0W%}1hc!o{c1t`>qBn(lp&Ms`v*=XKs6l~gSKO>oN0t>>6?j{_dkx0 z7Sqj?GMC(PnUYJ1kzAHbR>=Jlx#gDY(%f&&ikL1eiOGqO%g8a!_OtOQr` zHgVzb!*IQbhKSt0Z{dz&c-Nkd@Qn{XDAW3|HO#M+NBMG z+lbMCs&*BrH@}SnAmr5p%HE6 z7xPmu^wxsP49Wb+bC{l$HBH@fS9Oe*KY&WKW>;6P|6W?!{Joi^*m9)xTFq$jOGU#e zJ_#=Xy$BCh2>poQhTFLj2jL$??6va0!0b;&nr8pAlSbAdu2zY7Km=_81v zno7Wh7eyCwdmUegSxUiwEmt)*FKe_lS?@>MP{M zA314-E`cbOm{#P<7R#xMqKDviNl@m5UmLz;%p!Lre2iW^443{KQCoQtBtt@Eawnbw z&mA{!Gb}d{V0>VodOV^+Lv4M#6}4jCJCtk$Z=?+kWk;{?P@U1rNx3jdr28%YgHWAw zP4<*e$PAhXAh^G@Notn%&KhVBg*1jBrizM=ffmh%8NVQ_t9}wcRoj9)_xN{mYSfKy zk)8#;C{^6)N1Bh%5dWcP1&N|9`KJR>D(woV4x_&WqJE5x#lw+iO zA-jSX!L)7 z78q8?4-T+WPAn`xFZY4Gw`Pa< z$ZzcitF(6tvYi}3ZtYj5k;tk4xLDQIcL-egM-M`GlhuHNDM(cBn7F4r9y!i=qCdEz zBkzwFuL10g3jEVGtCxdWw`yZnaNy_+{ zxUv>nEhwy!`V-(7!FU?J8RJFSgf3t7t ztX1_%eOq4vr#{wIN%o_tLej`FImL&bb z8jyBN*f@6L6C&W2+=q{%cf2*PO@VbTlc^B(F)X?f)=X^J`B*0TUKYJ%Z?zO*gpP=|<{nqW?V-8j=y#}F008HmALmSa`N$;S=Eg^oRP zx8jymX$Mq$lo2QOzu={m$--#U#yB<3xY;g1HLKr+KV-z2$oF8x7X7aFqkRDJaH}oU z1^MZk9tUrgC0Uu49#X1sE&yoZ)zw6g0UQ^Bb5T9dE`yRbl9)cLIhL4q znUBmqA4GpB6oR^ly?UI3G`_$t3A*j$N4`YEQX4m552TJ*4dodf=K@l9?~I37%c0~D z1(QjoBb*Acl`#C>Tcj;I!iPf#)@dzCQ0FC?gWJ22IOmO;AmSgvw#`G-k|KWmR=O}YGu$Ohx=P_1{Nd$qc>{ta$Z-_edZbBie?D&3{1KG<;#~8 z62-T)w2TO z`eqOaUi|k^nK1*hXeG<8pKu85%HrPTknKr99znR7cZtJ6+9**{g45@8`-hUV3Cq*2 z<)gpo^-@M%MW8{#0|~^|=^(%ut7Vy@mV^3)aJd0ABhE^pEB`7(L_>$Z4@PRV#B69S z>D2h~L)(S$k82DFea=c6Ew&(%RaN0Z{B5GnJ%zGUcqtb3ccL>ncTHm-++>yB_&FZb z{m{^GIJSUjOg5UvU05~Q1nu+qHn_fXMr!7nRF{FO)vQq)MJKER!p#BJ9-1O`Uy?V;+XRY3g3l2*a@*0CiasyJ10d#P>s+J)A(Q?NmRDyQY z>*+3@o=Mab^rOyu)hcv8OjRGrOf*4j`;t(y(q|*GGb9UZ;DcGNWc9A}cxb+gTxl3H z!^9~;m|;FhG#26Ls8F&o6Zoa|{oTy^v&OQ51|f@Mt296B;@zgK{C6WDG1eckD4_%6 zGkH5pt|ciC8=;YCnEm0#u}o8N@{3f(iQa54S*^dv`o%zWL5x^wW-*A67{vJXM20BfowHb)Fr-^LoL9t?pYtO! zj}Y&|uMcPny0Eo`>wH{rv>c#4NTXedGK4C>V*5_@!*L(&<9Mh9WG;tf6iMrjNQ7ad z4W%lJHpDS7nx0Q%BmxO?4YnWwI9_# z^Z*yxfZ`%EVmCWx%|`)mqu6U=@+3!!+{@~{-FRrq>qQx(MqNvNJ9B?I0CghkyHoU5 zn?QEV6TZc;C`0dQ%wCuN1G$ungFoi_Kp119*--cPo0`0%j=u9 zG*K`@=yK2MKFg+M4@juXYXSN6#z?6h#l~t>1y}H*&fdXjnAi~~^>{sagM3hb_(=R! z1+QThbVBRYlu1Yto6C;tfns-&cjiQ3dOqKuae#!(b*+rr952poor(xqh}s>0eyP;2 zq0?7Lx-(Ssxj8r}hiYaW>u{SYnX7LO;epF{T_EO287oV--(nw;K}g0bjdKKKwuc>t zh?BTn-c=t$X=|dqx^ha-!roLXBF zG??%xq#$JwFBuddlo2Pu9e~eXV#I6ebbI=R5!GtCJ%zf2v<_l;ZdAvwx*!_aCr5TocHsV=NO{qz9nFkzS!N?#u+M(Is?=B z9dAeH-EAiR1@KrMc196k9Y!m2TdRZNO_i5{-QcyeuU4j` zqvFnnzXhqG(k|v{E$w+T;jzT$KqXQCB)s!nQ;?spmSG_Cjr9F0*IA@byd+}#rR|FX665Jmuw!ESYKrVEiA zf8{#-#9PabgThDRjTymNdWfqx^gcd>V~;y3mQj=q*cHgxqN?`B^^quv%~V-a6Q|dw z#j^hcV`}Dok1&K?p#M>vQzBMfNVssrYk%dLUx5bYh3GLZBeI^E2=oD5681^^b5!+$ zWk^_b-R&}P<$-^8H{)2$Mg3tOCn~>D^JkKKei=IgF^Kj%kbMW3By!S3ATp0^>S-Vh zb&+*r3wpg?SFh2hn`|LgDs4dFE4{f0DSJPU)B5 zE?aRGZZ8j#Nz4IeFY?rbK;~6~lBAWDMOO|=uK4Wr<1p%=>je4qv38u*<--Vf`lfYZ zg*Rf#=r|5!ZWc+O5w16s@-DABa^CzLSL4m8P}QGrK`ciS4=B`RQq)dCZmIzmAI^dg z!;_cW3DrU9Kdw0C_8IC<1aNzBoHI0N-rNFU&BJ9d`DN+28zklM*tPv3Nsk>)+Pi=nXmD52ZyYOm#WL znO29>=s6C)1VfIDNQ(N=PYGk#&I_tj*Aq@e6qe1e8QcWMO zFI>+4`|knRoN(D#0OJ%#;OejP%6!UMJUrLZd;T;r_k&oR7X@*$pn!!YWCc&n@L%*G z7bjg9|9P2L!WE1tOX-X5>Kx)=MIQMwM7({(9%dv94s7BCAs_BIj&_vr z5zv$y$|MIdReJ7gjK1nM9C&b`$iHZya)41A5Q1rn+><}j+8PJQeWzi4w7>g#GsYPJ ziGT4*_GoV?E5hxodSy|?p@aOtWb`W{`uLH@T{FG=&JP$Ip6Mubr!!R9GPlHapNT*C zWT`_>7vvLM&FY=2^uZ=J{OGvizc9AZ+#94Ma;%p|bC>0Patu@w`=Kt|V7ix-bk5CT zX<^~lU5(RWEb>*SCavo!|Ncvz2~-gWE$d9{>Vf4@t?Z_~$zqkq2VhfuU%ZZTd}wOE z&HO1>cv~|9Ft8gK3z;?7`z`grjZ5FrVU&5l9o|j}qH{r9AP<(yyuUU5HJUw!&Sr(# zoq|8iFO-1Me?TH(Z+^Tq$JwRejIHJm7gwdF9RGxxAF)2$2C_`Xuc6TQ0fL5r_vkg;G&G5j;9QSyg_wBAX za-{m`oP_NjRXk+vw+s=fOT8?i_p~Iq-JV5J{-`^Szm#U)t}m5GK>Ug4{DedqDzDS9 zv{ck<6B)&^s8?^7UCUui8!PwZS0*yqP22awT5<@772aCHT9cA$$ymI%)hVM4PRJx` zf^W=sf+w=Z()!4YYOd;$7_cIZQ(|AE#n~^*3JQe zxro*Ix_3N$h7s~BE%o;=4M4e74&O(KC>f+mt#f=f>Ou@)1U*6dAwhD{K?@-wA_6C} z>t~-+B?$7yye#f38v&}>N4Z*2M&a;_5ErL8|3&{=#@fzUXjo{dGv#%Uj6oqp#Nb`w zEsC)nDIRD?%puNZra`<=XIR9;qLMIh4bn67rJPSRm&;3@DK4eg4c@C8^E*JW%TVrG-;q4!Eo)^_+fZ>A zfOT95DN?0Hn6vIg8_Y|qWWKGnGOgPb(A+6vk7)MFxxpcFc_CWH;HEo8hF6R(^652< z2CIl}LDu!dLSlN=pQgMm!T{z_hj}p0YIKYV!@T&O9kV^y%5BOgIZ`*;OzQfnIE2aE z->Z$ej))0bt|_^kH}7BDf@;_-$ljlv-CkE~*>U7IEGUrO-+ZdQvy;8In;ZYMLUX3R zCghdEFAv~)_{;8-?qAi1RF0y*03*`qd{SH+8uM70 z>92Oh;P43|KBum3uJH74|Z=(8@D^hcK==2+v^$jA$$Ypdfq4_aR}kqG2Ru;4e(ThW#v?;lBgL~&Yi<0;Y)bK zElLe+V29y86l~8}yH~6cgbUNw)=-c7dq*kjdxbl`EsPVc)PC1{5=BjSxPAMDKK6sH zX4s$iJ{dEiE6a-72JojHQ@qW~TJCph$Ijbyw^1dHxtVeDJ-nwX7o!&$JG-inPq199 zYH$NTnWHxf26BG*b??s1bc*fw@fKHvM=Yyeub2qj>@yU*60vfpc9_4RX?)If|6fx@ zT5qZp4+m!gc!Mvdg$%@nnJq4+ZD>Ib^L;{C^sAoFt5VAdaTM+_f=NK0D!URfgX<5} zd~RgqLkQOrP)|_PI4cv`)WLhNc<-SfSDxYoUTgEN8sVq1FyKAUsZLBmoG|BiAA<(c z9>A3ht~|?E{PtfuDvlcK+F$Lse>0E{Y^R?{7Ypw!F_Ee6f~=omVvUR3!>}CWlcv?C zXi`uqDThCT1r&({SE590RDI#RJ>ef!A=eU;2f)u}Z4loN-?u*bBCSH9%QldbflBmP zomuO_F>o+9wq|>iYuw#p@Fy$Lf`))MM2%n{fxPeNJd^Om#3U;iE)F%jb;;eV%JJMJ z%;jh2DarKdSA*@h4wDVFl!(dZvhne4{t+P|motsyTg%s)4a2V{H2c@Zf0mF$V6QT%?|qfqLb;F?cNUCEDt*~D}ax- zbsQw7#`BsAO7D!)?zYOEaDd-%6%|~}Pqnk-cel$H$wm}jS&BNAD` z2;h!Ff@?=pOa50Nlb!BIq)I)mtVzA_BsB-wo@xZ+aQUjPt)*@}8LE-BH?fheV%#+9 zug8xwH!7^^GakL!zT*3>>L^Rn*aCA+TarEdD9D8}AHcJFhGCneq)=?`GuowKYT;&_ z;f@t~fm0VbwyJqq!{Iybh5O9iI!VGKc)xs8Q$r;kOMN)*Hy}<>)}z}NT*|f7b5+ew zbKgqd0Potl&XATJv)3IgRzNH-{&2#$mr4cAFQlPpJEIt_e%V&UvO@5NLBpuOla=3q zGn%}C6>&k&*53tCs-i-MNifc$z-~mPXZP;Ow&%E-qU-Ip`&(y-a?-fLK-$A`qZBTX zUA^3Z8fxDhCxZ&0cr1Wlj`@d7&&n(s9-xy3kWVy*%`o^N@^U6y zn6`CCvz%t)xvJUSO9T0m%9y{SvSnm7&BSEff7e&QtKFL0x@ASiW3_m~SyP1AbeO~^ta6fHGC|IMz9uV$vC9;)Az2MnGwzO6 zIoh3qoB%|LEi8Gnt1Deie+^$O@@4!`a*&IGrU= z=4G*7cJJUULYf|)>s~>1!CVRo{;S?BYHwv-T3Pz7WSqiMd|hCKhVP9AXg{8^72KIA z1|5aWu}9oHW zq?(S%g~SEr+mr>-0M$?j{*QA0kC$|m+Y#6?7q5~hDc3M<>eo}CXg%2chzYEm;g^f5 zpaW@7oN>SW6SuC-;7UNy&&U5 zxlu?N=9<|waR~Frve$?7UUwVE+vHu)Ieomk&>9dO8WF-!&05`yuB)PNyaNv7mjz+v zj9Q$d8qNxw1T|5ts1FTwIGUmdckxcdd8?sIsWVc-|7NA&EP$1z`Pl;TSGrcz-_1Wu zq0ioOo2}?c7#WvU-1sf8^EvyEHlf@Dg2psOq%a z&#>$}JQADZ&V1vlpLqLqN85B+^zGSYwYwxv2)o{-zsk_@TyC{F8Bphx&~cGUuS}}wj8PDFMB4_akymSc zBnaXV%Gxxe)_6ciObIOtX%B6=w_N#JgDs|X(uO}cn zJ-=|!LrH|3osDg0HmY}|s~Ts1_8y>PR-dyqT+A1Lv0Ld{m$ildGLOCakl34k$75!o)Y9AP};hd{bo({ zKE_1GqL5Ubc27&_Xmy|F19iC;}E9Iq8q_Qs8_;EUze;&9^r1EVaV$B}VTlitVomv~2$w6u<+B zTlwfh4dXQA8PPd168~U#cFf|b9-;ao!ysC&CI#r;qd)~c z6~vPl5I?WD;B-fQ<_SAto?WIB6>Kt!?cQSWAn13Bi`Vg!E@#FOAEh#<@+#D zj}ZkQBNS}yNN7FcAwLlb-wUs9JB~3&OGUxhZM(SArtG%Su)Cc`W>2ZYn5y3`f$3W9 z?e(#}js2Rj01hZNMJsA=ax`Qtvqxsi3|P*8asKoTo^gi54G7S20mIb_xtEzI1<;pS z2Yg$i2a8aTDV0fph5t5LhTxo7O?PBSCTuVqGu|Smq%d+5MC_vGkvIE~*!A=gJ)@r% zH<0=EXQBUCuKZpaU)iomJuma2=-gtI#n5US`kZv0p3%+e7>hTGHs)^!+3Hort zup)7AggZtKG{ZqUey}hh>0YfT>0)~vFGAO+D&!akxDXW}q6`2`D7e8m3jZXUb^^XWVS!|F2BIqg4$wu zgdj}9D3uzhBWF>;I2BQNq@9Fah!RhSqwV;^AaDBt+Y|UoFn~qZ2lzK>&JO%LU?Ro( zwO(I3J9GbT345s9aY)Dw;YsF`yR7irS9y?rO?oV1s{(o5$1g<+RBmpbg(?=GH9q04 z0+TSVEHKT!?da$R%}dcQPeO5vJ9kOwxZ6o4RM8!W_!9NytNJ8Qfief-3Sq<+Z^SrD zyf$(+WJF6}65Zb!iS7ai&8Y)4#1dY9Tn?C|HFr-9drIMRMyfaRV zieYI2t246Mk*7Lxie^h+FnSh#Zvt8;D}Z+UdO?nq5qF$HaC-wXd3E9=_n4vskeH{R z^UFb&j^u;=rL*c6hd@Z^Czt^GY!BjG*C!#j|4zx`(ifaWNZEj6f`reOd313=TUK>4q;wx8i zQ?nz}%MG4yJYd!(PT-rezw3FL`ql~~=oTf;f3BF=2QrdMdHjG2^xRy-hf;1l@I>Ye z#VW&{9CQP~0_UZ45m!_4?O+csY%{wz$khqsCaMHJPYNhUUo@zjvqx~c9YI4O&P0oL zK_E;aV9n+th|jDsM)Qp}7)inl%c2*L6Xfz?Z|X}uD~J0g%-)~cgd7NEWeGq5IjeK1 z^tM#PG3f7PDuSC;Qf=P3_lc%2^#Tt^N?(O#?@gTaB$=7poP;g>yZMZViZF!6>}|2e zcK0@NQNh$5i1LDNu?ipGAtgSCkP6njvvM0i9uY$C5#Vk|U<9YWYcw!@VGw|3W4q3+Z+1~!*+Lt&hj2w5X?x+e0%lpx{{5_2eqWp<&4~Ix5D0@)m z1s=d!%P60rLG65c=E3fc+_B`t%pIUY0HsRX#Rd~sGz0?1b+I52;|zX+N8?)s7B!v9 zY>0gVimxLAx^qJQGqzXD_QvD3KvOgQ8F*hYnWGfz;?6q`R@441 z#q0|NI69CHNY-xPev&l3TOof~?5~>kU-+5Gdn?Y(wqBkxsmt@DegohAhA8ywh5W1| z=+LOBlj!&KHmnfml9tjZBt2@AFhufe&_O_5+r^1WB^Zkq^vKo*%|tGf_v;kOOs!w%oEAqQH=WzOZBDT%6t*_ z9Q0UWE_huCJXgLOe|RUVb1K34xc+i5Pzk85&ioX-Eb^qgD01&FP-3=3Mr7p;2RHa+ ztjr9=GkU@`vbNz}QOmT|jyjO74(79`p@H1el0Sc1U&<{hR>PMV|)z@=UIo0H_L z?-Wl>EQ>B?Q9Oh znCjY@y%GeN3;KP3;srYRaecoGPU0q}VqZNgw_FWiXM+zK{9Y4q@>gS2R;sz1g|ezu zqx#PnRm?YsF4Gze4Q1O(ok`j;>n4u1eg%_KrWG8p*XEk9zpgh_JP)sC-Zwu8qXZGg zL!25{X9rBhu0&Uiog|j;>`XHNvt(_1ja{}PfBFd*U4#AA8Kr~ZVk=3-Md~P1y6TZ# zJ3Bj0`wJVe!|ad2Hg|Icb3FwF+P5Is!K#KR_he7}*w~ojDejoHmc6yf@ptpzLp7uk z+2q%7V#ieH=;+GkW>v}A!aER`y4!Z1!3|B$oDxD1Af`){^f?0ghoy4{&m+;EE*int zW~ObMp!Z#|ipK!XMX^dNfIx0|Sy>U@7ZsJ3l_A_D6H7KMmE_#36`f+1HJ(hNP8G=V zGH*K=NLGx`NhZOgb z_xu}(O_%acbBBLY`R`Pg=Kf#o2AW6WvmDA(KBcp{^vAN={G2{;Q{jxWJcs}D<67gc zgU8SV0tE;jDdQ8=gvyK);2qE#y>2?Brq;4Kttf#Oc=>YV19(p0jh6Xrp~WWiL*Y6) zzmr~(gLuJ!-weZpV{$`zfS2`#68g)*csRf0?89U6Nv%Ei+T z1$J0rT9M#bviawGIP1!9R(Mk`hnp|)ky64nD7>UPivNq(D9+K0WbXs8n4qi<=Mw*p z%dO^tUn@+JYD1U-r`CUCE&S?KA3SuiaVH)Og$>1`P$EaQ0bZiM@WmV

    5zv zs2Bl8sY41?3XK|FC8%m0%8c#o|n=A^~qfwFPh^gzE(RB2ZKsaZ&U0z7t4 zJxU!~^wt&^5xYPQpSxlyL%Sj64Ota*Z)_7-kq~9)ZiWOna6MSpy|0=2&eE_MO8@vG z(EbR%W?7MH+)Bvm`z zkylP7JNy}XY=$|^eT+5eGu{jy@l?t8xp%@TIuYI_R=LrKF3R*DK#3SP$tD$WGC^w_ zk(o+v{@{|$UC|j9uuBw{z-&FW!1Z6z_@7TIc@+NkJba7E2-*KvGY1FvUr~Jb%Am%g z`o@6QV71n|v$GQ)AOG;+G8ExlLKT#ca2If)0BT^6lk~#@_5u(%0AX{nmXL||?;Dyw zm?}i))KskWYxBANJ9i{RHb9cmL-9@)wW?XY_&>m#Q1En91Kpo_-M?Q+2@?cF8#Ch? zd=IBqmVw`nn2zpw=%w4~jGgFt^lR-CXg zADqELrm7o6I8SmsEoJRP?it(Qc!#@rZ~eAwuPki9I48Vn-H;kOs_NDw5Iqn3L)VaI zO%mL2zC}H9K_0l_;x#|g zhejuykyG!JJ+fs}%QifzO%vKE;-N(4mb$mKcgxy+5nXosC9)|uq1Y{Z;2rO;DL*8W zl+1>H%C>b=xjh`!fI<&j42$ z$YZw2=7_%aHRRxL=)o-sJn-%r%M^^vC_H-t3pLp(uvL1ijYRqr4vR>VDhrY9Mw(E& zP0Wggs7|{S_&{6M0C8jt1)Z8yjJTm{QFlcyg1i3LR&SQ0>yndi9@;B#xfIznbLrV*Ys9O=7lU#V5hE!|A1D?-A#NbBtWK&2Od zzMW=L*a)QVVf^0puUxJQ@B3CEr$5xI`B3aZS^*X7TaYO)s>S#EFlO>w!y1FyJP>}! zTCsM#;A)*jrq1W<1xC9ByyWEp=_7y#e!opRg)$JPC+x(PBwaCLsrd5e*)qx=4A!{B z+If*7tm}IKr1`YI?%LAY+`Rmg5Owr73yE7NjduW(j8T8?69F}JCRzSDAM@~(s#fC8Q(eU5T`KXa0+BBc{1~}S zdth{v(}^hzJi4UweN*hX2uH`psHK#PXF!dRdjf(rvJ?4A!es8IiV46r76>4uY45F3 zgGAul&ymbhIPk;i%bP!R6$zn%u&$mSBmWo_iQElS7&j{ovtBrAuTnZ?7pJcDa<5;R zVUk}9ookXghvawY`&BjJ=<+F-f{Z&jx$)=ZTmN*n8e5Md5Px*(!2S4Sz#OFvwp@DU zK^Hn~NB{i7B_}@#Lo=mQNHOwpt!ZG9X`$4XHE{bTp+#<9I3ou%GP}F9UrL_y!gC16 z&e~`p1K<|WAZqkBn3PjyZF5JpyncFKY=rVuTNBoCvW4;WAN++%)xpBC)dH3*j^u8| zLFr3(Co^x%0C@_7VO?^+XvQ9;)E{&S=``))YELn}JW)~UWbJ4Z4)~LO*=9yf=)`Xp zVPA5K(0-OB$9GHmtV20!?lr^b=yX&DO}7<*6!COHFUUp^@u@wJo5VMO+!7qUW?aMO zgS9psDzU(D(iVN-eP?*y!0w*Ex1iM9jSWsi2dD&`eZm}zFyFVG_%+@yKYkXD@arUC zzp?40#S=8-M{eiwX2EFZvklGk%k}A3HgBn{%#H)jk8f^JDiK#XLUX1H6~Nh!!vl_- z|L$Md0yN&it@yBQ=fM&79+9B8q4)y!I(2rXzNdU`(9ouud4?7slMgT@Am@ zwX?I6GEwKU9UArL&!6ksxdJ|&aKs&P4fH9`(pe9Ti-E#$4F+ayDiM>ig^rdC+m6t} zX4&k8x}BRzVNG8`o)T6r-Ru4@H&1X9H!+}~K%5r|D}MGAV}pBsMXpwBnRdYGv0z1&F{ zB1)4b!-jw!Mg4SRAZ+IiQ#UUt=8Kjfy)7?(B&O3x_vPxPn;U}3vOq&qw}glMnA@S4 zZ-yBt+)sm;%Z&I;^7(Z(+=H@rJ@8rmXVj+n?=Koy+Ws+qTT1sA!I)B{HHtBkvDd+v zv9LKHoh8v{5GG-A#JrkYjnFu~pop51yAg+$|6^5b=c9vVqZVoA0Z~7{{7cc-DNat# ze|8_KR;>@<7IlOB{*M`dT6=}ewVXQW5Ao)ixdN8hHcBL(DvG;f8C9%w75Z z!3G(@J?-J2pz{AVHV#58C11K_-aHyA_d@4p<#V^c%Zy<9b@_()M41=+kkUHd#>51P z4u!P)pD|iO0w8=y?k_J{mbMJa0e@dtUk`8MY8^XIkL*w>@gzH&7Om59V?@m*a5Z+i z+9=NGz7Qve>SSZZ;7$50xzx&<8>w0t5Luwp%@f@(E`hWIR~M!0o{uk8hJxa+P`S{ zpw1?o(<;J55dE@Zu5PmynL`7B1GDvc%-Jz`I)DFGFqt46 z_D4l&=|@tSU01_S=*U}UWDxtjcv9PhYKS{)J|kYrG51@8uHfx2IFJr`YR}tZNi9{7 z5m$tkvG>k%-Aw=z`{lXVdJJJ#+)Itk3vjw@K2vIX~Jr1XO|RS=|4+pFHxP zY7dC?R#qqGmoolZ@0h#8ja@~xJ`^c<9L{Q6z5I#d>0-kEeua^zTvS1hxIn95*(XBi zn+|76(?6SRy*UieylgP|g|X8v0hgPy_?=UOCInt%*QW;>?d{+9dxQ-K6luBsUWi?2 z8{0~l?D+5No2(Dfkm7Xt>*(n_$s|MpjBqHsJ5kAM`RZXjPD?DSnYRK$ulL3>B^Ihd zhW!3`_Jk=|sotF|;q=+WPymV#Bn)Pib8v822kUT()8P%ruT0SjMsTR8H%>M37z-Iq+M#-Q&HXb=ihBS}O==PCN%3;BZUjw0D884Oa(2a;&BaUVF2+B8} z%{*y;Iz}5!-Kc?^F;ZTu_&DXQ*RE9Lii7`fjLgUf#v1h)X*!cah>ZiUFH9u?6}135 z0+SaGu1PO5jBHRm&kv1fuM{eHn@O#FPr4XdW8L@UN1Aep(XK=#d&4yMP@fNwx(jMh zeAf$7EgJ!ng~kaBmj`BSe4qZz{6X9F;v}%}r@zY6erTMU?$UDN<-^&l-CAyzQ?Po&h(INsj zJQcSjzqQArS@8GcP{)RxA5wEN_E@@aT|Cjndl=#Z9isXjNaUS11{Q64by0!<#4ews zjvdf-@|vCH;tB2iL0Q%t4|=|$?wKF&B5R12gB#QJ{*9IkV{KT{B}t*zP<=_5OQJB7 zql+-0jw0N(MkF^FwxRKi_e6{W+Q@RF$jv6zuU z^um~1g%=~5F{IgP-2cuN$tiLq_7N$+E^^`$>Dy0;xdnZ-dXf-5oJS$zgV&EPKU8bn zmT52kk7zASj70h^jiGcT`*QoZChX^}21GQ^Fk2$DJaS?9H}=0ZbX{cM7O_5xcD(tF zyd%|N-7-$I-b}=>*Z%)Qbn!p*AH5xED5IIDxPs=Cib29*OyhNuH*cx0mlTCR6p^?e z`hu~mSdO;Y0Y}USsLNubEJZ=jXJ_2N3MD@T{Je)1%f!e$H(5lHSl*3qi7HG>X*kNE z((t+aSSJuF4Wp(dr9E(3OqQrv%svK8L&e~xvjz`yv8Qg*5GGl!_4w!~4~oJg)cBnd zG})U+2qlx~(u>9Y0KB!7Os!+?a6>Z9l^R>dkz>KawPoHV|C&}cP)=kFe^-^q;Gas4 zOZ{k6a?DaCFfYC*zaca!oe%nQ_cfrvs+Yj+lrL0aigmL3KNjFajBZ$*GW`5TOc6sO z-S{voe@4juQRdY#o7|_pl>__rUM`}@e+s2BFUS>GoUv0ENPveB2z4&xz=u}q7;1Zp z5g0T`q7t$JbI#!X6!S84VI8lR8$!H5xS?eoR;dEB6is=L?MB>-_sX}%v@&WvTX?JHQu$zH?qpPL0DZW|MmboUq7qV~qeBX%xYTvg3-=2O#2T{LN!5yYJx$9!J@aog*kp_({WTRWj4U1@O#|bDPhTujF(z3 zGAVkpcwJo<8Qc+Z0ny&QAH278`Lb$s{Itvd@JA-GMqf-n`WvIK0~Ns!4!z(1KqF%G zA~zS_U*(uZynoD{W_-dwDLC5Vq6MjMPM}&N^dp6hHggH~>tym~xbK({LlC6$l zBrPDHM?uRg{+2$ENvGbM9NFoXCKQxwyZX9CQh2>5Iry1Uu~R5lx!hLk?s$qMqh{(^ z-x{=%YFIlDBut765T4W#4RocxNAe6UFpNXpH1wy1d|5T%vbHe)U?lQ>#MwmeLX0o@ zFfVWYa3}&9U1zTVJDoa0-z0{D1^%yH9N#xKa=XD~)sbUk1FOI4Y(wGQ$DvmKrVU9p zYjBDYIsI3Blkmez$GTj}vU%73aT#YaV=A(9h#!qDSZ7FfszbJ#yk0#u4gJ3Kp~0gZ zgOVNeY((zoLSb21C2GAN(4l+R%ZgNlFz zLK9k}E)^5jS77yq5;t`_Yh(ROr3&8LJp_mBUy8a*!9~kxcG)qs7`I<|BHf<2Kqf1W zx3{Zdmt_FWy#*=3F0IY*=k z$50fPH!ICoHv^Tyox$Vktrw=Um#tM#r#V2($n>9U00^09v8M}7aSvlR66_Pb}brixwe5I;_l^0QpS ziHLj_(;r2c5in8RcykfiMIkl5g)=Ea?_Kp)L&*__&OG0kuKENCp|qAOf;twVQ=)PY zz!6sg8hS32$JjtVGCMoFR*Nc|U)lJ$QAlY<=Su?AHM@AY%uoRP_V55BMnjfll6IfM zt}bTWNQn|p8#jEyBzD#Ur^KVREbZu`yP+KGlzjBBrh1CECS4)5SIi>1I90tAx0VGHN>E!p`qoxj|`Qy_4{5L~_ z0>g)%*KU^XN1PtlU4qtJPAGv+FV`Q-W7}RrUTt-CJV&lKULoO3O;0!iPi5MNZhf9- zA6yYv2aT$9D}CZ@&CQG3*Eh3K*$!;We(p-D4~&dbwATPp^rNbz+`Memk$-31x&&R; z58S{J<5;n)(=?j#kJXEsf{Mt@RK{;nZ^vgKEX#(!w*~CJ`08-TIY~$keLREWVPc}L z`0AY&XhXzvzb}`l4{tM3BES_-NzZz7VX4G+RTCiCq~)8g$8tr@%Z{z%EJOx3@>YL6 zufLcUmfnIP7@IO07HeM40#`OMNmUwymU@I&%{R-L)>)ttNV?9rtZd=hB7P*nIk*M@ zVVQ7dBYYp!B@{!!Qyh3ao`a{&VBM|X8&&DP!*{Y+42tC-@u;{e(2y*h(1d0gglyr; zQP0=54=mliG!a?FNQl~#t)~6usH2(za&9KyBjP`%e@7?TEI3kW#G)putEyPibJSD7 zsA%9jU%LGLs*{An3X>WQ-=)6jRg&!&b7hkLA)~|5P$XVwl6j9Y7cZIL1o>=hNV7Gn zd+9B@I5@ZGqh}@yPX9KPfc)ODh7WoDUnUu!VeBFfwkVncA*U$M($nz-SI_+_1g>{0 z>KLsPU=pYA9HGF}qAif585$1dr=_LmM%mb-=j>8w&Tp-v=|45DrPwe6(dwYPS^QDM z!O6h^+H^2!_Jf$RrOEb+lEFhEAg*9!#QD5G?MF$gVPR+I%9Jh@(^H8MF{+^{aJ2D~ zK$1xKzBZ6`R6@vnQMdptjil3fyG}18&BY0?<#5YHdEnlP6(SK->r$LxKJHjSr^J0R zq~SNcc0QRXp!m3T+GQHzRh4A1aFBkZ46E!gVp%jXue`e+!wDI;;V7Nn;hU;d(1 zEi*0S!kJ`HKqkV7X(l!3?XbgG%w4!8`^Vg2Ye8VINY0UKm=7;sQHz?+p{=SoP7!6! zGDaPSG)uI|K81!h;LL5RNXf;ebxeuP@`@++yR(-0fy~&fBQ}jU6W6{2?i|>5$G1K_jIaW+^K6%v*+GZwtZ6%g}tXnPJ zci(4?jb-rvy4E+PaBU%yl>su{d}VNk*ZKj67(1}N`HM-wZa3`XdF((p*OKP!=f=d2QIX1gB)!2B%RHvy+vIE{ zx`B4v*en$DatC#b1WbtlAy_#^@^!*Euz1s&wY&<{~-Fe9)U5hTFNAYdHb9b|mQI|~N={}rU zp2`gwO8NSp>4dB|KD^fNx6WH5&MYb3aV;}3bsQ5c8^+qvBWr(>$Ebn=L%lb{Ewg}X@aL&VVb*^~_Pm4Y{uzB@f3>b{H*to*^KMP>BNZ8*KW~?P zI^E^A3d|NQ7i6pLsbFtp1J_0VYo>JE^^TxJl959H8qqZ>j%G!tMfFfqpW`aH>nq|q;5VC#xLi|UVa>3V=~ zvpynJR;`T224K=<4?EJPRMIwHp;6X?fcPb~Y39+uE%tFNcn47?HM)3UcYs|Xvxj5M ziL~!%3^g$vV?foq$05vpWRLS@NOtB@e(_EhLVHFT6a9+;Z=^)>uVJ3l{2`f@)0QSD zqC{7e$GdziQ@Os7^f;xgePLbchvhc{0vXgEV>rqMW>EeXX}ocxk~)1Q?{7c({@m)n z<3FHPcqc@{l4NxJpEaD60%FtOrQ&{Mk-}YNxwpvU?31AsPQYR~%6@mv>en-ygX82p5dvA` z@jm)+uE;)WhznRnvf-n>SpEFjjs{EqDYtZc%6x9Kv=tKgaSau`gk8uAq0#+ANqIRj zm-T09m&0jVQ2~53p8AR^34AS&2dEt9d^|_GUNW$0$L1nH}m4DgDhnDu69_8 zfYvj&53yA&=6K9w7S((X;uR)v)9U&Zls0vphz9R=%51k%yM@1?ho1i?6PIOOSmP z)UunYK_8Qr%|5-?l{q$lt=IE5w-pIX=LIn*kHhSf0FCCGHct$X$2zYEPQlCZ3eN+( zwwD5xv!=bBGuNZ5)UU1^tY?s$wTJT+^IYp2ytNxEujiS$nbGFgM9-(}jq^FZt3jtn z8K&n3eUFg~cl%tBQpOh0aXsDSwJ*qbzpVYjd+MC$w!ik=tMJkN{9_xWqe-ET3erli zf9=(>QBy|*AM%*_lkra42OTr4fyL8rJ#KW zEb7&ZNpDdv-#9JoMjG@w?Y`NUx7;_%tHPjR%F{iC1RDKHs?zaHylfx+2p@=3BG6xf zgkX!w(D{(rbToQNtCQ9F+$=>pnO6gqohriJ6l@9Oy&MPbzk3lYwGZ z8e4>5eCeS-Puo@^m|LTsBDSpsCmeOQ@bfLLKiSm=c16xcd*dHrq2E$&p6%4d%0)oe z2}DZebGbBC;^G6&$kHBsM3L+Wq)MQRg;PWE%9&5gdtAv}5#NX=Zu!9MuR*=I zw4}tKj7N&<^DE)6UfNFSY&c4%%bQGHFD=-l)-;P}MiCNK7DIoTMwWyW6oL{pyz9NV zYbu$Hz0hBsm6t?36!6ixk))*D4k+p$E50;ejq?5*>s&Yw`$7i3L)}d834HS&y?87t z&a}hLPz7A{iVUAG@L45E?O-UH#V=zL4hAxWsVj3Vfx>K@{uZi~lor|H{F4#;?>0Yi*vCyy^+wJNFa4Oq!e%AME+z=e~fbMk4flU=WG>b)=Fld6qh8MopXyIW0Ot;@Q0p5<&IwcoT!$=jRa)~CI; z*8`lnK2*{R|tFCi&c3tLTi$w7H*}cz zMSHPf4{1c-{{nI$Wi;*+8CyAXiKt*XNO~FCJsMc*`%R znQm81Ui*`E&Bxw?+)o3q7uh0Xo)3vahc4Kx_1D_^Hs}9&T^EI0J&a;WwY0s)Muu2D zrWekM-$5?#AoG3t*P{x}PYE7-g3rWldqF_)YW2Eqgq73bch+*E|2)t~+?sQh?R7WF z3F)M6-Oy$FVa)mU2}AH@Fw^7S&Fkz|(Ct*(_H@+^u95^rcqU!pb-CE{Hrngqly}Wb zgSw5VZrUp^6x9J0#z3Bn;;= zZfHgHKkv}a1D?tAF)M<$)4;Z7~<&8$1Y0kgVCxLZXF{`-rDdAQmrHC9k*P)2*1MY z4+q6j^+#nNVUM4}ynw#Tk)jbxvHq#FFKJFZdLV=AGJ+r&D*4ynCYR>Wv8iig{0>l` z;g1-{43ph}O*y*Zk>_zdi&b#8__HCW2ih1eLRg{kqnonELprj?SIASxne8E-F(OdZ z1KVW~*wMHmPbiV5rvtda?NyP#TW8A9wp0^&m+4Bc?@0vVKR`&)Qh}eg4(*}sY zL?mt|ZWD8Hdq@lnieEL@o${)IAR%Y}1$qTluU*#6hKpW;xw*NEAya)FF81f)ci$c^ zj|+9Vyaaj$-%fQ=Rxh0Z*x;PWhR{!;LxoZ5L)U#2>}k0=9k>nkihFF1pFGiE>C^}a zj@tK+j*gs7#_ZrS>`_sx2-tZd=oCGc(>Dqu^BR}y0K(bhW_FAJc&^Da_;a+Q{2brG&JuUq<7hnpKGJ`T?T>G)vZ8Jw2KcZsU}joS@lZTtLQPriv>D`L?S z8mpHjyVOLQsm%uW1E}c&k1v8x&3;%y@keb>Pi6NVcdIoorEm#H`mejMcSmhMl6Lf; zC(j!0+g>mF=Jan@iv5_H_qIA@Am@jN=dFT}>Jgmgm$jC4u*lh_6ohoOJ-k1AX*wOs zkijJK+)-$KTr5x+!SOh=^L@3RYbf%Y=5=a5D)-fByOYRtQWC}d&-t-B*wnQHVtzNe z_KLVmp^ss5(rulh?>2fg-`hAdhQP_e9ra#Uf-Bz zgolSun8J9XuzT|gB7R0b3@}qF*$n=+ji<;FU_ck~aSxAYEG>@^G}iaaav!#_@GeBO)(=I#swAZ^^%DsYpxQ<1$H5Xeu^xjDb1+ z+HtDIk4?ujc6IEW6ym{-ZALb9S2?M4yTZy(NNpg>%#ff=CkB7-e_;AYxin2|2A$*r z;;c-T5r^<87pJcE^f-gDR8x{ybuzqK$fQRJ}5XeWjZ1cIs1=AF4MEL?l!$4h)z zi+s8-TaxWai!0Ryes!N1;h~02=63kldNQvBm?=0zIg|Sj!8NKpleUbB+ zZu#o1Mjvw)>TA)QM6YA4AO((1?{$;Up86vGgJzN!m7VQ;diNF`vl;!Gv&jzLH+glFe2O4Cs>6ZXT_%?*3hryCgjex~J85xnQ#oYR>%9idu`d^Dt!Q({0 zj?z|{&GF%h8XfEI3iB!>x8cqfof;u)0n(TpfxQtbQ}>b74;VYjGsmj8;@oF1F+CM= zldQMr@ZuwQTR)b>x?R-*5A?~EHA$!%recL&OC<9Ujxi`DWPqotV&EZvNrS~jdibmCY-^N_cdBiFD$E^ zIP*bg`xk95eon1twXvxfq&L4gn{B^8!s?A2|2ijMEB`q2!1O2Ie$q3CzxnJx!ONGk zPJ(>$7W)wr%11;}g^BzL!Rt*8-N)jyhxvfB=L9&&ee8_YLo5bX%1?pDhL;B7)(2R4 zr|ZA;5l(@$=nr-{BO5nlC9nrHHu7?dymc82URRI>m1?uQ9QrM6e@SB&zxE&0b| z!^R-DS1B@w0%H?Ppogdft9+nO_qadb=p*)e4q$R8O$!`4yP}9{%yOq5J*0Wd=Qv@C z?dcoDrH!BX9!8gzdDX=d%-1}LkPwJWyc;Ui0H3}dqkDwK_5!@MDtZmD-ZF^SC6db+ z#-TL);>890Uf_)504!6gE#_ywRwQ*C^|32R+%Jr~0PiiJIFd%NcUwB)a1`*1aqP9h z+4#vFE;fc=M)&Gc7+XJtMt6c{qy-5vcRawROI9JJC4d@D3?~tzSjk5kg0RbTrBW6#p&{-YgN802P(D16Am>r595oTbk`_o3yuV)?$@b2ak3IN~DD1&T z6xkcgCWb|tAH^3F+?Y!fxl1uR>B8_U5g1;irUH@#J}*s{YX5aTG+mYot!2F#xTfS! zyD2=X;KfKwKE6KU2js-P$FrdaMq0>NRxNsP*+?S5ck7c*n1=xto+Y-9sybp?JXSUT zbO<6wGHcQGWmmTQRQ$=z0%Llp8DB~HEUU$*>dVxcIaQ7@7LA?~L>=sDQ>hpdAw0Q$ z@C`XtvQ802gYoMC8Yf`#RmRWKQs@v*I&F1GkF|~s&4%jx=JLA3fEl=K)|%ui3!Tzt zWwua-7l2+>}Hgb zKjOKE_9%}Qvf1C^_OY7YP0!m;rN!|F<(-rx&{ERcXZ!y(`0rGKCNs_Thw)EVg?CE> zo9;sz{Uw>bssYj;Jf}^nLHm7FO$nFK8|Zz%w|56uU=e@dD=Ecf8e-8_1r3E^18}&zb4*&ojb8( za$Ac>k6v_gwgGxmE4L*%?#?E+vs3oZFF8hDTiG=TCy^#EN06O{T&BmV$d(P~dN{|| zB60^Jmu0i3va`psNU!HD5Y=R7ccoVDIy0>AX`9wKL~EQE-9?1ei)I(!*!6C7TIT%g zai>1npP3(kFx2cJ<=E-NAX>XOg5AGwZ9SX&XX^tD55W%5lx-2f@bmMgbxZI(?;`Yd zbo^_vlJWTn4u=i$T|U8nveIS#kLigbXJg1rvH$%}x>NX-BOPp3?b`f&{dSB@9?+{I zJ?Zy$ztbI&wUOD#bUgEkYrz~Max_ZP!;Q*+u2HI;qp=QRs2a1?%T~roev(3wYA}lN zE6!sMBN)Td#Fj?NjyCDe%?LnY*XD`Qj@A6=@2eVuZhQM7N$H(B}F2<@b{KNt}IY8+@`3Zp|hYH)Z5lqOC^B<`l(N}2^CX<42G41TmfV=&P?=;630+-0>~Mx5_Sprff=FBO z+L=C(shWD-JiYv=`Qs330tG9j&m6mQSIB3Owr1$i?;CAIK zS5~EUzu-1^KFgc_a2-_;YcD%_K#|VvjV285*DiMb6^-ysxo>|~;D#^GTOo2*bfHc- z8og67Ld9u??@>zdZ=p$Hg?p(EPOt5IorsEWArMWsvqdYl^jIqEmuBnG=gtA{GtI8D zf2fXmz9+@IR8>_r=yYNVhq7SRUc)^-yBdj(e5Z>ZoW-5LQwMKgB$U|r`QIn}N1&X{ zy$Ae$)}Cj}L_^Fbw1V;DPYBVLvFCrMtS4IGfi~a7*w}kImV#6{V4ieE(xD|SqXOkhPZ)9;1^HC`U(bYHjc^xbAott;%uM(S=yn;tje zMCNaXyl$j&^}SZyGVdXYe6|7tx9Mlsw>qvr9_NAtUk6&&oL8QRZ%+3Fzbe^Bu0d|j z{1f$C>T20l9=)gwTe+1pGc(&R2kAk5G^PiHlsB#|=N+iwDr3sE*5Q=nhb(q>RV|QV zdd;DpXZ}@2wb=?_mF$uMoG_S|547UD;@*Vf++#Hsgw`9rfdgKp*Q;)4{I=VY)eGHS zKTAJ|O@J7V)0HN4t5bQem=VX-IAOa)jcgH8hxLbX=7O?QzOnSCH*+gpQLXo_k;kar zaEJFw{XQrS&%&7gJ%!n`uvmy*8&GO*XNqnJZMt9HGZ-@2vfpwbcInfcVX_VQ?? zzSk|8*YN@?@ipQoe+;$-5>XjyEwY49q70VxU$-fVZ@)%vIXgJ8M|{)Kr%5w5F^MGN z#}@;{Foy8wDL(vg%X)L^PeP(P5neCLN=^JEWS=d58)Xp^MD_`x-M50kbl!CN7>cM7 ziUHh^qy*_P*`#`r`7dpJbq>M9**d=r$g?#Jvtt^vhS~F94o1e5i;jObeq$K?yWnX& zrqF)<*K*|BqfQ5V$FVeR7tppop}7N*WkUmZ5-D)VTOT(-wl^~?Ql)c<99q(H3;7*A zo$2zBuA+j3D+u3(b{pYLAUR;c1^ctceeHGF1QPP;LnnrKw=!KozA~m5@WkJC@wH2k zoH?)uP!vcl2J%DK7E3a~p!$oTR;^v})yL718~X^w#)!o?pRzFXa{ti@!u}XLC5=Dq zKm!dtyExeD*Sqte2u)<^dg8is+cD7uy;yyB(amugis~KMDmO4-~jg zw4LBbY51-ZU)Oh@`H7tm#$NOieGkAl;FZ430Z-{+*+jtNRF3JjoLB`(!FB4%^J;lg z$`kV}F4Gl)VdZis<9Wk`Q*cz6*7h2AzCIvew>PEt)RarG`ufMDttS4yCf$wr3TaMH zTolzT2UF2wY0LBAS>t6^&Q0&;njh^>6sP$z*K1h+#Z7_liQ7U=i|dHG++~Ef%+tEc z?r`u(;IVPdZRZy;BqHC2*{h>^?O{Vk-T~s;hSrIHyBlU56a6Vc_1iS|T5&0&?m10ek%RR5?^~0##Cr=6c3vl zg7e$pijdg4FyJCY4ninkjoa3-HhJ@|LrOZD8`GCRDcp5ewc)u+W;{=rhu?O0BQ-+x z0sL%O*SEH!{5^45T`3-bt~4GYVqNPtC7;H;7w_6&4ker3FxA|k^J8~wTLW